From b6ae0d229f16f67b7183afea0c1c279de3a15198 Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Mon, 22 Aug 2022 08:05:37 +0200 Subject: [PATCH 01/41] Add .vscode to .gitignore: (#83) Prevent accidentially committing of .vscode folder. --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index b1babc9..9fa72d9 100644 --- a/.gitignore +++ b/.gitignore @@ -1 +1,2 @@ extras/build +.vscode From f109c2fb0db77837a850dd60ab0ab7f3beb1aa31 Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Mon, 22 Aug 2022 08:15:15 +0200 Subject: [PATCH 02/41] Bugfix: No need to increment the ID when setting the max torque, this is a leftover error from earlier code. --- src/lib/motors/SmartServo.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/lib/motors/SmartServo.cpp b/src/lib/motors/SmartServo.cpp index 397e960..dcd656a 100644 --- a/src/lib/motors/SmartServo.cpp +++ b/src/lib/motors/SmartServo.cpp @@ -283,7 +283,7 @@ void SmartServoClass::setMaxTorque(uint16_t const torque) void SmartServoClass::setMaxTorque(uint8_t const id, uint16_t const torque) { mbed::ScopedLock lock(_mtx); - writeWordCmd(id+1, REG(SmartServoRegister::MAX_TORQUE_H), torque); + writeWordCmd(id, REG(SmartServoRegister::MAX_TORQUE_H), torque); } void SmartServoClass::setID(uint8_t const id) From f9969af39a79a1dd21a7aab28eb1542e9eb1f7b8 Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Mon, 22 Aug 2022 08:30:00 +0200 Subject: [PATCH 03/41] Provide API to set the max allowed torque on a per-servo basis. --- src/Braccio++.cpp | 8 ++++++++ src/Braccio++.h | 3 +++ src/lib/motors/SmartServo.h | 3 +++ 3 files changed, 14 insertions(+) diff --git a/src/Braccio++.cpp b/src/Braccio++.cpp index a0ddbfc..1091dfb 100644 --- a/src/Braccio++.cpp +++ b/src/Braccio++.cpp @@ -215,6 +215,14 @@ void BraccioClass::positions(float & a1, float & a2, float & a3, float & a4, flo a6 = _servos.getPosition(6); } +void BraccioClass::setMaxTorque(int const id, uint16_t const max_torque) +{ + if (max_torque > SmartServoClass::TORQUE_MAX) + _servos.setMaxTorque(SmartServoClass::TORQUE_MAX); + else + _servos.setMaxTorque(max_torque); +} + int BraccioClass::getKey() { if (isJoystickPressed_LEFT()) { return 1; diff --git a/src/Braccio++.h b/src/Braccio++.h index 5ba6db9..37620aa 100644 --- a/src/Braccio++.h +++ b/src/Braccio++.h @@ -80,6 +80,9 @@ class BraccioClass void positions(float * buffer); void positions(float & a1, float & a2, float & a3, float & a4, float & a5, float & a6); + void setMaxTorque(int const id, uint16_t const max_torque); + inline void setMaxTorque(uint16_t const max_torque) { setMaxTorque(SmartServoClass::BROADCAST, max_torque); } + inline void speed(speed_grade_t const speed_grade) { _servos.setTime(speed_grade); } inline void speed(int const id, speed_grade_t const speed_grade) { _servos.setTime(id, speed_grade); } diff --git a/src/lib/motors/SmartServo.h b/src/lib/motors/SmartServo.h index 46d6927..266ecd8 100644 --- a/src/lib/motors/SmartServo.h +++ b/src/lib/motors/SmartServo.h @@ -98,6 +98,9 @@ class SmartServoClass static int constexpr NUM_MOTORS = 6; static float constexpr MAX_ANGLE = 315.0f; + static uint16_t constexpr TORQUE_MIN = 0; + static uint16_t constexpr TORQUE_MAX = 1000; + static size_t idToArrayIndex(size_t const id) { return (id - 1); } private: From 6188939cd00f2639622816f7f5afcbdbc0b73473 Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Mon, 22 Aug 2022 08:32:22 +0200 Subject: [PATCH 04/41] Also make the setMaxTorque API available from the Servo abstraction. --- src/Braccio++.h | 1 + 1 file changed, 1 insertion(+) diff --git a/src/Braccio++.h b/src/Braccio++.h index 37620aa..f288270 100644 --- a/src/Braccio++.h +++ b/src/Braccio++.h @@ -187,6 +187,7 @@ class Servo inline void disengage() { _servos.disengage(_id); } inline void engage() { _servos.engage(_id); } inline bool engaged() { return _servos.isEngaged(_id); } + inline void setMaxTorque(uint16_t const max_torque) { _servos.setMaxTorque(_id, max_torque); } inline Servo & move() { return *this; } inline Servo & to (float const angle) { _servos.setPosition(_id, angle); return *this; } From 135893f164a018ba4ff780835b47ff29093f198c Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Mon, 22 Aug 2022 08:39:42 +0200 Subject: [PATCH 05/41] Move check of torque limits inside of SmartServoClass. --- src/Braccio++.cpp | 8 -------- src/Braccio++.h | 4 ++-- src/lib/motors/SmartServo.cpp | 12 +++++------- src/lib/motors/SmartServo.h | 5 ++--- 4 files changed, 9 insertions(+), 20 deletions(-) diff --git a/src/Braccio++.cpp b/src/Braccio++.cpp index 1091dfb..a0ddbfc 100644 --- a/src/Braccio++.cpp +++ b/src/Braccio++.cpp @@ -215,14 +215,6 @@ void BraccioClass::positions(float & a1, float & a2, float & a3, float & a4, flo a6 = _servos.getPosition(6); } -void BraccioClass::setMaxTorque(int const id, uint16_t const max_torque) -{ - if (max_torque > SmartServoClass::TORQUE_MAX) - _servos.setMaxTorque(SmartServoClass::TORQUE_MAX); - else - _servos.setMaxTorque(max_torque); -} - int BraccioClass::getKey() { if (isJoystickPressed_LEFT()) { return 1; diff --git a/src/Braccio++.h b/src/Braccio++.h index f288270..ad0b014 100644 --- a/src/Braccio++.h +++ b/src/Braccio++.h @@ -80,8 +80,8 @@ class BraccioClass void positions(float * buffer); void positions(float & a1, float & a2, float & a3, float & a4, float & a5, float & a6); - void setMaxTorque(int const id, uint16_t const max_torque); - inline void setMaxTorque(uint16_t const max_torque) { setMaxTorque(SmartServoClass::BROADCAST, max_torque); } + inline void setMaxTorque(uint16_t const max_torque) { _servos.setMaxTorque(max_torque); } + inline void setMaxTorque(int const id, uint16_t const max_torque) { _servos.setMaxTorque(id, max_torque); } inline void speed(speed_grade_t const speed_grade) { _servos.setTime(speed_grade); } inline void speed(int const id, speed_grade_t const speed_grade) { _servos.setTime(id, speed_grade); } diff --git a/src/lib/motors/SmartServo.cpp b/src/lib/motors/SmartServo.cpp index dcd656a..8f8e1f7 100644 --- a/src/lib/motors/SmartServo.cpp +++ b/src/lib/motors/SmartServo.cpp @@ -274,16 +274,14 @@ void SmartServoClass::setTime(uint8_t const id, uint16_t const time) writeWordCmd(id, REG(SmartServoRegister::RUN_TIME_H), time); } -void SmartServoClass::setMaxTorque(uint16_t const torque) +void SmartServoClass::setMaxTorque(uint8_t const id, uint16_t const max_torque) { mbed::ScopedLock lock(_mtx); - writeWordCmd(BROADCAST, REG(SmartServoRegister::MAX_TORQUE_H), torque); -} -void SmartServoClass::setMaxTorque(uint8_t const id, uint16_t const torque) -{ - mbed::ScopedLock lock(_mtx); - writeWordCmd(id, REG(SmartServoRegister::MAX_TORQUE_H), torque); + if (max_torque > TORQUE_MAX) + writeWordCmd(id, REG(SmartServoRegister::MAX_TORQUE_H), TORQUE_MAX); + else + writeWordCmd(id, REG(SmartServoRegister::MAX_TORQUE_H), max_torque); } void SmartServoClass::setID(uint8_t const id) diff --git a/src/lib/motors/SmartServo.h b/src/lib/motors/SmartServo.h index 266ecd8..43d38bb 100644 --- a/src/lib/motors/SmartServo.h +++ b/src/lib/motors/SmartServo.h @@ -56,9 +56,8 @@ class SmartServoClass void setTorque(uint8_t const id, bool const torque); - void setMaxTorque(uint16_t const torque); - - void setMaxTorque(uint8_t const id, uint16_t const torque); + void setMaxTorque(uint8_t const id, uint16_t const max_torque); + inline void setMaxTorque(uint16_t const max_torque) { setMaxTorque(BROADCAST, max_torque); } void setID(uint8_t const id); From 6388c9ac54f2d1c53382c8f95fae19a119b0faa7 Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Tue, 23 Aug 2022 09:43:21 +0200 Subject: [PATCH 06/41] Remove Tools/Braccio_LearnByDoing. (#85) It is an outdated version of Braccio_Record_and_Replay. --- .../Braccio_LearnByDoing.ino | 158 ------------------ 1 file changed, 158 deletions(-) delete mode 100644 examples/Tools/Braccio_LearnByDoing/Braccio_LearnByDoing.ino diff --git a/examples/Tools/Braccio_LearnByDoing/Braccio_LearnByDoing.ino b/examples/Tools/Braccio_LearnByDoing/Braccio_LearnByDoing.ino deleted file mode 100644 index 3cc189d..0000000 --- a/examples/Tools/Braccio_LearnByDoing/Braccio_LearnByDoing.ino +++ /dev/null @@ -1,158 +0,0 @@ -/* - * @brief Learn the arm an movement and replay it. - */ - -/************************************************************************************** - * INCLUDE - **************************************************************************************/ - -#include -#include "FlashIAPBlockDevice.h" -#include "FATFileSystem.h" - -/************************************************************************************** - * VARIABLES - **************************************************************************************/ - -enum states { - LEARN, - REPEAT, - IDLE -}; - -int state = IDLE; - -float values[10000]; -float* idx = values; -float* final_idx = 0; - -/************************************************************************************** - * FUNCTIONS - **************************************************************************************/ - -static void event_handler(lv_event_t * e) { - lv_event_code_t code = lv_event_get_code(e); - lv_obj_t * obj = lv_event_get_target(e); - - if (code == LV_EVENT_KEY && lv_indev_get_key(lv_indev_get_act()) == LV_KEY_HOME) { - state = IDLE; - return; - } - - if (code == LV_EVENT_CLICKED) { - uint32_t id = lv_btnmatrix_get_selected_btn(obj); - const char * txt = lv_btnmatrix_get_btn_text(obj, id); - - if (state == LEARN) { - final_idx = idx; - } - - idx = values; - - FILE* f; - switch (id) { - case 0: - state = LEARN; - Braccio.disengage(); - Serial.println("LEARN"); - break; - case 1: - state = REPEAT; - Braccio.engage(); - Serial.println("REPEAT"); - break; - case 2: - state = IDLE; - f = fopen("/fs/movements", "wb"); - fwrite(values, 1, (final_idx - values) * sizeof(float), f); - fflush(f); - fclose(f); - Serial.print("SAVED "); - Serial.print((final_idx - values) * sizeof(float)); - Serial.println(" bytes"); - break; - case 3: - state = IDLE; - f = fopen("/fs/movements", "rb"); - final_idx = values + fread(values, 1, sizeof(values), f) / sizeof(float); - fclose(f); - Serial.print("LOADED "); - Serial.print((final_idx - values) * sizeof(float)); - Serial.println(" bytes"); - break; - default: - state = IDLE; - Serial.println("IDLE"); - break; - } - } -} - -static lv_obj_t *counter; - -static const char * btnm_map[] = { "Learn", "\n", "Replay", "\n", "Save in flash", "\n", "Load from flash", "\n", "Idle", "\n", "\0" }; - -void customMenu() { - lv_obj_t * btnm1 = lv_btnmatrix_create(lv_scr_act()); - lv_btnmatrix_set_map(btnm1, btnm_map); - lv_btnmatrix_set_btn_ctrl(btnm1, 0, LV_BTNMATRIX_CTRL_CHECKABLE); - lv_btnmatrix_set_btn_ctrl(btnm1, 1, LV_BTNMATRIX_CTRL_CHECKABLE); - lv_btnmatrix_set_btn_ctrl(btnm1, 2, LV_BTNMATRIX_CTRL_CHECKABLE); - lv_btnmatrix_set_btn_ctrl(btnm1, 3, LV_BTNMATRIX_CTRL_CHECKABLE); - lv_btnmatrix_set_btn_ctrl(btnm1, 4, LV_BTNMATRIX_CTRL_CHECKABLE); - lv_obj_align(btnm1, LV_ALIGN_CENTER, 0, 0); - counter = lv_label_create(btnm1); - lv_label_set_text_fmt(counter, "%d" , 0); - lv_obj_align(counter, LV_ALIGN_CENTER, 0, 50); - lv_obj_add_event_cb(btnm1, event_handler, LV_EVENT_ALL, NULL); - Braccio.connectJoystickTo(btnm1); -} - -static FlashIAPBlockDevice bd(XIP_BASE + 0x100000, 0x100000); -static mbed::FATFileSystem fs("fs"); - -/************************************************************************************** - * SETUP/LOOP - **************************************************************************************/ - -void setup() -{ - Serial.begin(115200); - for (auto const start = millis(); !Serial && ((millis() - start) < 5000); delay(10)) { } - - // Mount file system for load/store movements - int err = fs.mount(&bd); - if (err) { - err = fs.reformat(&bd); - } - - if (!Braccio.begin(customMenu)) { - if (Serial) Serial.println("Braccio.begin() failed."); - for(;;) { } - } - Serial.println("Replicate a movement"); -} - -void loop() -{ - if (state == LEARN) { - Braccio.positions(idx); - idx += 6; - } - if (state == REPEAT) { - Braccio.moveTo(idx[0], idx[1], idx[2], idx[3], idx[4], idx[5]); - idx += 6; - if (idx >= final_idx) { - Serial.println("Repeat done"); - state = IDLE; - } - } - if (idx - values >= sizeof(values)) { - Serial.println("IDLE"); - state = IDLE; - } - delay(100); - if (state != IDLE) { - lv_label_set_text_fmt(counter, "%d" , idx - values); - } -} From 570b8f73d94eb3ca79d47a67e88e528d80dd9b82 Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Tue, 23 Aug 2022 12:29:14 +0200 Subject: [PATCH 07/41] Fix: Usage of 'delay()' causes unacceptable large delay between two consecutive RS485 write commands. (#86) This change allows for a much faster cadence of write commands. --- src/lib/motors/SmartServo.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/lib/motors/SmartServo.cpp b/src/lib/motors/SmartServo.cpp index 8f8e1f7..4e29d75 100644 --- a/src/lib/motors/SmartServo.cpp +++ b/src/lib/motors/SmartServo.cpp @@ -62,7 +62,7 @@ void SmartServoClass::sendPacket() _RS485.endTransmission(); // should now receive an echo of what we just sent while (_RS485.available() < len) { - delay(100); + delayMicroseconds(10); } // discard the echo int i = len; From 5353987e147888b5c53f6d54116156d67f44780b Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Tue, 23 Aug 2022 12:52:05 +0200 Subject: [PATCH 08/41] Provide public API to configure servo runtime. (#87) --- src/Braccio++.h | 2 ++ src/lib/motors/SmartServo.cpp | 6 ++++++ src/lib/motors/SmartServo.h | 5 +++-- 3 files changed, 11 insertions(+), 2 deletions(-) diff --git a/src/Braccio++.h b/src/Braccio++.h index ad0b014..6d3d1e6 100644 --- a/src/Braccio++.h +++ b/src/Braccio++.h @@ -196,6 +196,8 @@ class Servo inline float position() { return _servos.getPosition(_id); } inline bool connected() { return Braccio.connected(_id); } inline void info(Stream & stream) { _servos.getInfo(stream, _id); } + inline uint16_t runtime() { return _servos.getTime(_id); } + inline void setRuntime(uint16_t const time) { _servos.setTime(_id, time); } operator bool() { return connected(); } diff --git a/src/lib/motors/SmartServo.cpp b/src/lib/motors/SmartServo.cpp index 4e29d75..0e6d311 100644 --- a/src/lib/motors/SmartServo.cpp +++ b/src/lib/motors/SmartServo.cpp @@ -274,6 +274,12 @@ void SmartServoClass::setTime(uint8_t const id, uint16_t const time) writeWordCmd(id, REG(SmartServoRegister::RUN_TIME_H), time); } +uint16_t SmartServoClass::getTime(uint8_t const id) +{ + mbed::ScopedLock lock(_mtx); + return readWordCmd(id, REG(SmartServoRegister::RUN_TIME_H)); +} + void SmartServoClass::setMaxTorque(uint8_t const id, uint16_t const max_torque) { mbed::ScopedLock lock(_mtx); diff --git a/src/lib/motors/SmartServo.h b/src/lib/motors/SmartServo.h index 43d38bb..d42d487 100644 --- a/src/lib/motors/SmartServo.h +++ b/src/lib/motors/SmartServo.h @@ -74,8 +74,9 @@ class SmartServoClass void setMaxAngle(uint16_t const max_angle); void setMaxAngle(uint8_t const id, uint16_t const max_angle); - void setTime(uint16_t const time); - void setTime(uint8_t const id, uint16_t const time); + void setTime(uint16_t const time); + void setTime(uint8_t const id, uint16_t const time); + uint16_t getTime(uint8_t const id); void center(uint8_t const id, uint16_t const position); From 279a155e671f07c4155413b08575fd1706d724c4 Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Wed, 24 Aug 2022 07:47:58 +0200 Subject: [PATCH 09/41] Rewrite setPosition in a better structured way (exit early, lock only where necessary). --- src/lib/motors/SmartServo.cpp | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/src/lib/motors/SmartServo.cpp b/src/lib/motors/SmartServo.cpp index 0e6d311..6c81d96 100644 --- a/src/lib/motors/SmartServo.cpp +++ b/src/lib/motors/SmartServo.cpp @@ -203,14 +203,16 @@ void SmartServoClass::setPosition(uint8_t const id, float const angle) if (!isValidAngle(angle)) return; - mbed::ScopedLock lock(_mtx); - if (isValidId(id)) + if (!isValidId(id)) + return; + + _targetPosition[idToArrayIndex(id)] = angleToPosition(angle); + + if (_positionMode == PositionMode::IMMEDIATE) { - _targetPosition[idToArrayIndex(id)] = angleToPosition(angle); - if (_positionMode==PositionMode::IMMEDIATE) { - writeWordCmd(id, REG(SmartServoRegister::TARGET_POSITION_H), angleToPosition(angle)); - } - } + mbed::ScopedLock lock(_mtx); + writeWordCmd(id, REG(SmartServoRegister::TARGET_POSITION_H), angleToPosition(angle)); + } } float SmartServoClass::getPosition(uint8_t const id) From 7bb9bcbab26349a182615679898593ff18896588 Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Wed, 24 Aug 2022 07:53:58 +0200 Subject: [PATCH 10/41] Rewrite getPosition in a better structure (exit early, always a valid return code). --- src/lib/motors/SmartServo.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/lib/motors/SmartServo.cpp b/src/lib/motors/SmartServo.cpp index 6c81d96..9258082 100644 --- a/src/lib/motors/SmartServo.cpp +++ b/src/lib/motors/SmartServo.cpp @@ -217,10 +217,11 @@ void SmartServoClass::setPosition(uint8_t const id, float const angle) float SmartServoClass::getPosition(uint8_t const id) { + if (!isValidId(id)) + return -1.0f; + mbed::ScopedLock lock(_mtx); - float ret = -1; - if (isValidId(id)) - return positionToAngle(readWordCmd(id, REG(SmartServoRegister::POSITION_H))); + return positionToAngle(readWordCmd(id, REG(SmartServoRegister::POSITION_H))); } void SmartServoClass::center(uint8_t const id, uint16_t const position) From 6e15737315316c449785042100ee8fb16f6cb935 Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Wed, 24 Aug 2022 08:13:52 +0200 Subject: [PATCH 11/41] =?UTF-8?q?Limit=20angular=20velocity=20to=2010?= =?UTF-8?q?=C2=B0/s.?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- src/lib/motors/SmartServo.cpp | 34 ++++++++++++++++++++++++++++++++-- 1 file changed, 32 insertions(+), 2 deletions(-) diff --git a/src/lib/motors/SmartServo.cpp b/src/lib/motors/SmartServo.cpp index 9258082..3a475bd 100644 --- a/src/lib/motors/SmartServo.cpp +++ b/src/lib/motors/SmartServo.cpp @@ -206,12 +206,42 @@ void SmartServoClass::setPosition(uint8_t const id, float const angle) if (!isValidId(id)) return; - _targetPosition[idToArrayIndex(id)] = angleToPosition(angle); + float const MAX_ANGULAR_VELOCITY_deg_per_sec = 10.0f; + + float const target_position_deg = angleToPosition(angle); + float const actual_position_deg = getPosition(id); + if (actual_position_deg < 0.0f) + { + char msg[64] = {0}; + snprintf(msg, sizeof(msg), "error obtaining position for servo %d", (int)id); + Serial.println(msg); + return; + } + + float const abs_position_diff_deg = fabs(target_position_deg - actual_position_deg); + float const runtime_sec = static_cast(getTime(id)) / 1000.0f; + float const angular_velocity_deg_per_sec = abs_position_diff_deg / runtime_sec; + + /* Check whether or not the maximum allowed angular velocity is exceeded, + * if it is indeed exceeded increase the runtime accordingly. + */ + if (angular_velocity_deg_per_sec > MAX_ANGULAR_VELOCITY_deg_per_sec) + { + float const limited_runtime_sec = abs_position_diff_deg / MAX_ANGULAR_VELOCITY_deg_per_sec; + setTime(id, static_cast(limited_runtime_sec)); + + char msg[64] = {0}; + snprintf(msg, sizeof(msg), "targed = %0.2f, actual = %0.2f, diff = %0.2f, omega_vel = %0.2f", + target_position_deg, actual_position_deg, abs_position_diff_deg, angular_velocity_deg_per_sec); + Serial.println(msg); + } + + _targetPosition[idToArrayIndex(id)] = target_position_deg; if (_positionMode == PositionMode::IMMEDIATE) { mbed::ScopedLock lock(_mtx); - writeWordCmd(id, REG(SmartServoRegister::TARGET_POSITION_H), angleToPosition(angle)); + writeWordCmd(id, REG(SmartServoRegister::TARGET_POSITION_H), target_position_deg); } } From 99242d9d1be0c873e2c494c8ba462ea142fac88e Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Wed, 24 Aug 2022 08:16:57 +0200 Subject: [PATCH 12/41] Only lock actual writing to the servos. --- src/lib/motors/SmartServo.cpp | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/src/lib/motors/SmartServo.cpp b/src/lib/motors/SmartServo.cpp index 3a475bd..6cfe01c 100644 --- a/src/lib/motors/SmartServo.cpp +++ b/src/lib/motors/SmartServo.cpp @@ -294,16 +294,24 @@ void SmartServoClass::setTorque(uint8_t const id, bool const torque) void SmartServoClass::setTime(uint16_t const time) { - mbed::ScopedLock lock(_mtx); for (int i = MIN_MOTOR_ID; i <= MAX_MOTOR_ID; i++) _targetSpeed[idToArrayIndex(i)] = time; + + mbed::ScopedLock lock(_mtx); writeWordCmd(BROADCAST, REG(SmartServoRegister::RUN_TIME_H), time); } void SmartServoClass::setTime(uint8_t const id, uint16_t const time) { + if (!isValidId(id)) + return; + + if (id == BROADCAST) + return; + + _targetSpeed[idToArrayIndex(id)] = time; + mbed::ScopedLock lock(_mtx); - if ((id >= MIN_MOTOR_ID) && (id <= MAX_MOTOR_ID)) _targetSpeed[idToArrayIndex(id)] = time; writeWordCmd(id, REG(SmartServoRegister::RUN_TIME_H), time); } From 7acbf71a049960c36a7e28364637bc5731fec498 Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Wed, 24 Aug 2022 08:22:34 +0200 Subject: [PATCH 13/41] Only update position array when we are in synched mode (otherwise this variable is not needed). --- src/lib/motors/SmartServo.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/lib/motors/SmartServo.cpp b/src/lib/motors/SmartServo.cpp index 6cfe01c..d716d34 100644 --- a/src/lib/motors/SmartServo.cpp +++ b/src/lib/motors/SmartServo.cpp @@ -236,13 +236,15 @@ void SmartServoClass::setPosition(uint8_t const id, float const angle) Serial.println(msg); } - _targetPosition[idToArrayIndex(id)] = target_position_deg; - if (_positionMode == PositionMode::IMMEDIATE) { mbed::ScopedLock lock(_mtx); writeWordCmd(id, REG(SmartServoRegister::TARGET_POSITION_H), target_position_deg); } + else if (_positionMode == PositionMode::SYNC) + { + _targetPosition[idToArrayIndex(id)] = target_position_deg; + } } float SmartServoClass::getPosition(uint8_t const id) From cb87a59128f5136743cb0d98af02ce7bb1bc7cb3 Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Wed, 24 Aug 2022 09:13:00 +0200 Subject: [PATCH 14/41] Bugfix: Runtime is in milliseconds, not seconds. --- src/lib/motors/SmartServo.cpp | 15 +++++++++++++-- 1 file changed, 13 insertions(+), 2 deletions(-) diff --git a/src/lib/motors/SmartServo.cpp b/src/lib/motors/SmartServo.cpp index d716d34..41294a0 100644 --- a/src/lib/motors/SmartServo.cpp +++ b/src/lib/motors/SmartServo.cpp @@ -227,8 +227,19 @@ void SmartServoClass::setPosition(uint8_t const id, float const angle) */ if (angular_velocity_deg_per_sec > MAX_ANGULAR_VELOCITY_deg_per_sec) { - float const limited_runtime_sec = abs_position_diff_deg / MAX_ANGULAR_VELOCITY_deg_per_sec; - setTime(id, static_cast(limited_runtime_sec)); + float const limited_runtime_sec = abs_position_diff_deg / MAX_ANGULAR_VELOCITY_deg_per_sec; + float const limited_runtime_ms = limited_runtime_sec * 1000.f; + uint16_t const limited_runtime_ms_param = max(5000, static_cast(limited_runtime_ms)); + + if (_positionMode == PositionMode::IMMEDIATE) + { + mbed::ScopedLock lock(_mtx); + writeWordCmd(id, REG(SmartServoRegister::RUN_TIME_H), limited_runtime_ms_param); + } + else if (_positionMode == PositionMode::SYNC) + { + _targetSpeed[idToArrayIndex(id)] = limited_runtime_ms; + } char msg[64] = {0}; snprintf(msg, sizeof(msg), "targed = %0.2f, actual = %0.2f, diff = %0.2f, omega_vel = %0.2f", From e49c5d04e6f65974182ad4ef38c51ee5ca9aa2ec Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Wed, 24 Aug 2022 09:23:03 +0200 Subject: [PATCH 15/41] From a pre-defined max angular velocity calculate the individual runtime. --- src/lib/motors/SmartServo.cpp | 50 ++++++++--------------------------- src/lib/motors/SmartServo.h | 2 +- 2 files changed, 12 insertions(+), 40 deletions(-) diff --git a/src/lib/motors/SmartServo.cpp b/src/lib/motors/SmartServo.cpp index 41294a0..931b44d 100644 --- a/src/lib/motors/SmartServo.cpp +++ b/src/lib/motors/SmartServo.cpp @@ -198,63 +198,35 @@ void SmartServoClass::begin() _targetSpeed[idToArrayIndex(i)] = 1000; } -void SmartServoClass::setPosition(uint8_t const id, float const angle) +void SmartServoClass::setPosition(uint8_t const id, float const angle_deg) { - if (!isValidAngle(angle)) + if (!isValidAngle(angle_deg)) return; if (!isValidId(id)) return; - float const MAX_ANGULAR_VELOCITY_deg_per_sec = 10.0f; + float const ANGULAR_VELOCITY_deg_per_sec = 10.0f; - float const target_position_deg = angleToPosition(angle); + float const target_position_deg = angle_deg; float const actual_position_deg = getPosition(id); if (actual_position_deg < 0.0f) - { - char msg[64] = {0}; - snprintf(msg, sizeof(msg), "error obtaining position for servo %d", (int)id); - Serial.println(msg); return; - } - - float const abs_position_diff_deg = fabs(target_position_deg - actual_position_deg); - float const runtime_sec = static_cast(getTime(id)) / 1000.0f; - float const angular_velocity_deg_per_sec = abs_position_diff_deg / runtime_sec; - - /* Check whether or not the maximum allowed angular velocity is exceeded, - * if it is indeed exceeded increase the runtime accordingly. - */ - if (angular_velocity_deg_per_sec > MAX_ANGULAR_VELOCITY_deg_per_sec) - { - float const limited_runtime_sec = abs_position_diff_deg / MAX_ANGULAR_VELOCITY_deg_per_sec; - float const limited_runtime_ms = limited_runtime_sec * 1000.f; - uint16_t const limited_runtime_ms_param = max(5000, static_cast(limited_runtime_ms)); - - if (_positionMode == PositionMode::IMMEDIATE) - { - mbed::ScopedLock lock(_mtx); - writeWordCmd(id, REG(SmartServoRegister::RUN_TIME_H), limited_runtime_ms_param); - } - else if (_positionMode == PositionMode::SYNC) - { - _targetSpeed[idToArrayIndex(id)] = limited_runtime_ms; - } - char msg[64] = {0}; - snprintf(msg, sizeof(msg), "targed = %0.2f, actual = %0.2f, diff = %0.2f, omega_vel = %0.2f", - target_position_deg, actual_position_deg, abs_position_diff_deg, angular_velocity_deg_per_sec); - Serial.println(msg); - } + float const abs_position_diff_deg = fabs(target_position_deg - actual_position_deg); + float const limited_runtime_sec = abs_position_diff_deg / ANGULAR_VELOCITY_deg_per_sec; + uint16_t const limited_runtime_ms = static_cast(limited_runtime_sec * 1000.f); if (_positionMode == PositionMode::IMMEDIATE) { mbed::ScopedLock lock(_mtx); - writeWordCmd(id, REG(SmartServoRegister::TARGET_POSITION_H), target_position_deg); + writeWordCmd(id, REG(SmartServoRegister::RUN_TIME_H), limited_runtime_ms); + writeWordCmd(id, REG(SmartServoRegister::TARGET_POSITION_H), angleToPosition(target_position_deg)); } else if (_positionMode == PositionMode::SYNC) { - _targetPosition[idToArrayIndex(id)] = target_position_deg; + _targetSpeed[idToArrayIndex(id)] = limited_runtime_ms; + _targetPosition[idToArrayIndex(id)] = angleToPosition(target_position_deg); } } diff --git a/src/lib/motors/SmartServo.h b/src/lib/motors/SmartServo.h index d42d487..ab516f3 100644 --- a/src/lib/motors/SmartServo.h +++ b/src/lib/motors/SmartServo.h @@ -46,7 +46,7 @@ class SmartServoClass inline void setPositionMode(PositionMode const mode) { _positionMode = mode; } - void setPosition(uint8_t const id, float const angle); + void setPosition(uint8_t const id, float const angle_deg); float getPosition(uint8_t const id); From 672628a9f9b98801f6bd9ec389de4911590425de Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Wed, 24 Aug 2022 09:29:33 +0200 Subject: [PATCH 16/41] Turn compile time constant into member variable. --- src/lib/motors/SmartServo.cpp | 5 ++--- src/lib/motors/SmartServo.h | 2 ++ 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/src/lib/motors/SmartServo.cpp b/src/lib/motors/SmartServo.cpp index 931b44d..84efd23 100644 --- a/src/lib/motors/SmartServo.cpp +++ b/src/lib/motors/SmartServo.cpp @@ -31,6 +31,7 @@ SmartServoClass::SmartServoClass(RS485Class & RS485) : _RS485{RS485} , _errors{0} +, _angular_velocity_deg_per_sec{DEFAULT_ANGULAR_VELOCITY_deg_per_sec} , _onError{} , _mtx{} { @@ -206,15 +207,13 @@ void SmartServoClass::setPosition(uint8_t const id, float const angle_deg) if (!isValidId(id)) return; - float const ANGULAR_VELOCITY_deg_per_sec = 10.0f; - float const target_position_deg = angle_deg; float const actual_position_deg = getPosition(id); if (actual_position_deg < 0.0f) return; float const abs_position_diff_deg = fabs(target_position_deg - actual_position_deg); - float const limited_runtime_sec = abs_position_diff_deg / ANGULAR_VELOCITY_deg_per_sec; + float const limited_runtime_sec = abs_position_diff_deg / _angular_velocity_deg_per_sec; uint16_t const limited_runtime_ms = static_cast(limited_runtime_sec * 1000.f); if (_positionMode == PositionMode::IMMEDIATE) diff --git a/src/lib/motors/SmartServo.h b/src/lib/motors/SmartServo.h index ab516f3..7b87885 100644 --- a/src/lib/motors/SmartServo.h +++ b/src/lib/motors/SmartServo.h @@ -97,6 +97,7 @@ class SmartServoClass static int constexpr MAX_MOTOR_ID = 6; static int constexpr NUM_MOTORS = 6; static float constexpr MAX_ANGLE = 315.0f; + static float constexpr DEFAULT_ANGULAR_VELOCITY_deg_per_sec = 10.0f; static uint16_t constexpr TORQUE_MIN = 0; static uint16_t constexpr TORQUE_MAX = 1000; @@ -129,6 +130,7 @@ class SmartServoClass RS485Class& _RS485; int _errors; + float _angular_velocity_deg_per_sec; mbed::Callback _onError; rtos::Mutex _mtx; From 14c3c7a3cfb8f771f3b0e17abefded7d8b50db42 Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Wed, 24 Aug 2022 09:33:19 +0200 Subject: [PATCH 17/41] Provide getter/setters for angular velocity. --- src/Braccio++.h | 3 +++ src/lib/motors/SmartServo.h | 7 ++++--- 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/src/Braccio++.h b/src/Braccio++.h index 6d3d1e6..c895b56 100644 --- a/src/Braccio++.h +++ b/src/Braccio++.h @@ -83,6 +83,9 @@ class BraccioClass inline void setMaxTorque(uint16_t const max_torque) { _servos.setMaxTorque(max_torque); } inline void setMaxTorque(int const id, uint16_t const max_torque) { _servos.setMaxTorque(id, max_torque); } + inline void setAngularVelocity(float const angular_velocity_deg_per_sec) { _servos.setAngularVelocity(angular_velocity_deg_per_sec); } + inline float getAngularVelocity() const { return _servos.getAngularVelocity(); } + inline void speed(speed_grade_t const speed_grade) { _servos.setTime(speed_grade); } inline void speed(int const id, speed_grade_t const speed_grade) { _servos.setTime(id, speed_grade); } diff --git a/src/lib/motors/SmartServo.h b/src/lib/motors/SmartServo.h index 7b87885..4c634da 100644 --- a/src/lib/motors/SmartServo.h +++ b/src/lib/motors/SmartServo.h @@ -46,14 +46,15 @@ class SmartServoClass inline void setPositionMode(PositionMode const mode) { _positionMode = mode; } - void setPosition(uint8_t const id, float const angle_deg); - + void setPosition(uint8_t const id, float const angle_deg); float getPosition(uint8_t const id); + inline void setAngularVelocity(float const angular_velocity_deg_per_sec) { _angular_velocity_deg_per_sec = angular_velocity_deg_per_sec; } + inline float getAngularVelocity() const { return _angular_velocity_deg_per_sec; } + void synchronize(); void setTorque(bool const torque); - void setTorque(uint8_t const id, bool const torque); void setMaxTorque(uint8_t const id, uint16_t const max_torque); From bc001ef75a2ae341420050e9b1ffd57710b388cf Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Wed, 24 Aug 2022 09:34:32 +0200 Subject: [PATCH 18/41] Drop runtime/getRuntime API. --- src/Braccio++.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/Braccio++.h b/src/Braccio++.h index c895b56..c3a3f2b 100644 --- a/src/Braccio++.h +++ b/src/Braccio++.h @@ -199,8 +199,6 @@ class Servo inline float position() { return _servos.getPosition(_id); } inline bool connected() { return Braccio.connected(_id); } inline void info(Stream & stream) { _servos.getInfo(stream, _id); } - inline uint16_t runtime() { return _servos.getTime(_id); } - inline void setRuntime(uint16_t const time) { _servos.setTime(_id, time); } operator bool() { return connected(); } From 517570821a3308670ef516504932d3918c788675 Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Wed, 24 Aug 2022 09:47:53 +0200 Subject: [PATCH 19/41] Eliminate speed API alltogether. --- .../Braccio_Record_and_Replay/Braccio_Record_and_Replay.ino | 5 ++++- .../Controlling_Manually_Braccio.ino | 2 -- .../01_aligning_braccio/01_aligning_braccio.ino | 3 --- .../02_waving_with_Braccio/02_waving_with_Braccio.ino | 3 --- .../03_moving_challenge/03_moving_challenge.ino | 3 --- .../01_Controlling_Manually_Braccio.ino | 2 -- .../02_Manual_Control_Challenge.ino | 2 -- .../01_Braccio_Record_and_Replay.ino | 2 ++ src/Braccio++.cpp | 2 +- src/Braccio++.h | 3 --- 10 files changed, 7 insertions(+), 20 deletions(-) diff --git a/examples/Braccio_Record_and_Replay/Braccio_Record_and_Replay.ino b/examples/Braccio_Record_and_Replay/Braccio_Record_and_Replay.ino index 8e0439d..88e6b06 100644 --- a/examples/Braccio_Record_and_Replay/Braccio_Record_and_Replay.ino +++ b/examples/Braccio_Record_and_Replay/Braccio_Record_and_Replay.ino @@ -18,8 +18,11 @@ RecordAndReplayApp app; void setup() { - if (Braccio.begin(custom_main_menu)) { + if (Braccio.begin(custom_main_menu)) + { app.enableButtons(); + /* Allow greater angular velocity than the default one. */ + Braccio.setAngularVelocity(45.0f); } } diff --git a/examples/Controlling_Manually_Braccio/Controlling_Manually_Braccio.ino b/examples/Controlling_Manually_Braccio/Controlling_Manually_Braccio.ino index 4d2f5ea..679fd73 100644 --- a/examples/Controlling_Manually_Braccio/Controlling_Manually_Braccio.ino +++ b/examples/Controlling_Manually_Braccio/Controlling_Manually_Braccio.ino @@ -54,8 +54,6 @@ void setup() if (Braccio.begin(directionScreen)) { - /* Configure Braccio. */ - Braccio.speed(speed_grade_t(120)/*MEDIUM*/); /* Move to home position. */ Braccio.moveTo(HOME_POS[0], HOME_POS[1], HOME_POS[2], HOME_POS[3], HOME_POS[4], HOME_POS[5]); delay(500); diff --git a/examples/Platform_Tutorials/projects/p01-moving-braccio/01_aligning_braccio/01_aligning_braccio.ino b/examples/Platform_Tutorials/projects/p01-moving-braccio/01_aligning_braccio/01_aligning_braccio.ino index bd0c162..b06b096 100644 --- a/examples/Platform_Tutorials/projects/p01-moving-braccio/01_aligning_braccio/01_aligning_braccio.ino +++ b/examples/Platform_Tutorials/projects/p01-moving-braccio/01_aligning_braccio/01_aligning_braccio.ino @@ -18,9 +18,6 @@ void setup() { Braccio.begin(); delay(500); // Waits for the Braccio initialization - // You can choose the speed beforehand with - Braccio.speed(SLOW); // could be FAST or MEDIUM or SLOW - // Send motors initial angle gripper.move().to(initialGripper); delay(100); diff --git a/examples/Platform_Tutorials/projects/p01-moving-braccio/02_waving_with_Braccio/02_waving_with_Braccio.ino b/examples/Platform_Tutorials/projects/p01-moving-braccio/02_waving_with_Braccio/02_waving_with_Braccio.ino index 2bda3b1..f837495 100644 --- a/examples/Platform_Tutorials/projects/p01-moving-braccio/02_waving_with_Braccio/02_waving_with_Braccio.ino +++ b/examples/Platform_Tutorials/projects/p01-moving-braccio/02_waving_with_Braccio/02_waving_with_Braccio.ino @@ -21,9 +21,6 @@ void setup() { Braccio.begin(); delay(500); // Waits for the Braccio initialization - // You can choose the speed beforehand with - Braccio.speed(SLOW); // could be FAST or MEDIUM or SLOW - // Set motors initial angle // Should move all the motors at once Braccio.moveTo(homePos[0], homePos[1], homePos[2], homePos[3], homePos[4], homePos[5]); diff --git a/examples/Platform_Tutorials/projects/p01-moving-braccio/03_moving_challenge/03_moving_challenge.ino b/examples/Platform_Tutorials/projects/p01-moving-braccio/03_moving_challenge/03_moving_challenge.ino index 2999342..138d7d7 100644 --- a/examples/Platform_Tutorials/projects/p01-moving-braccio/03_moving_challenge/03_moving_challenge.ino +++ b/examples/Platform_Tutorials/projects/p01-moving-braccio/03_moving_challenge/03_moving_challenge.ino @@ -20,9 +20,6 @@ void setup() { Braccio.begin(); delay(500); // Waits for the Braccio initialization - // You can choose the speed beforehand with - Braccio.speed(SLOW); // could be FAST or MEDIUM or SLOW - // Set motors initial angle // Should move all the motors at once Braccio.moveTo(homePos[0], homePos[1], homePos[2], homePos[3], homePos[4], homePos[5]); diff --git a/examples/Platform_Tutorials/projects/p02-controlling-braccio-manually/01_Controlling_Manually_Braccio/01_Controlling_Manually_Braccio.ino b/examples/Platform_Tutorials/projects/p02-controlling-braccio-manually/01_Controlling_Manually_Braccio/01_Controlling_Manually_Braccio.ino index 4d2f5ea..679fd73 100644 --- a/examples/Platform_Tutorials/projects/p02-controlling-braccio-manually/01_Controlling_Manually_Braccio/01_Controlling_Manually_Braccio.ino +++ b/examples/Platform_Tutorials/projects/p02-controlling-braccio-manually/01_Controlling_Manually_Braccio/01_Controlling_Manually_Braccio.ino @@ -54,8 +54,6 @@ void setup() if (Braccio.begin(directionScreen)) { - /* Configure Braccio. */ - Braccio.speed(speed_grade_t(120)/*MEDIUM*/); /* Move to home position. */ Braccio.moveTo(HOME_POS[0], HOME_POS[1], HOME_POS[2], HOME_POS[3], HOME_POS[4], HOME_POS[5]); delay(500); diff --git a/examples/Platform_Tutorials/projects/p02-controlling-braccio-manually/02_Manual_Control_Challenge/02_Manual_Control_Challenge.ino b/examples/Platform_Tutorials/projects/p02-controlling-braccio-manually/02_Manual_Control_Challenge/02_Manual_Control_Challenge.ino index 4d2f5ea..679fd73 100644 --- a/examples/Platform_Tutorials/projects/p02-controlling-braccio-manually/02_Manual_Control_Challenge/02_Manual_Control_Challenge.ino +++ b/examples/Platform_Tutorials/projects/p02-controlling-braccio-manually/02_Manual_Control_Challenge/02_Manual_Control_Challenge.ino @@ -54,8 +54,6 @@ void setup() if (Braccio.begin(directionScreen)) { - /* Configure Braccio. */ - Braccio.speed(speed_grade_t(120)/*MEDIUM*/); /* Move to home position. */ Braccio.moveTo(HOME_POS[0], HOME_POS[1], HOME_POS[2], HOME_POS[3], HOME_POS[4], HOME_POS[5]); delay(500); diff --git a/examples/Platform_Tutorials/projects/p03-record-replay-mode/01_Braccio_Record_and_Replay/01_Braccio_Record_and_Replay.ino b/examples/Platform_Tutorials/projects/p03-record-replay-mode/01_Braccio_Record_and_Replay/01_Braccio_Record_and_Replay.ino index c5180cf..5456ea5 100644 --- a/examples/Platform_Tutorials/projects/p03-record-replay-mode/01_Braccio_Record_and_Replay/01_Braccio_Record_and_Replay.ino +++ b/examples/Platform_Tutorials/projects/p03-record-replay-mode/01_Braccio_Record_and_Replay/01_Braccio_Record_and_Replay.ino @@ -20,6 +20,8 @@ void setup() { if (Braccio.begin(custom_main_menu)) { app.enableButtons(); + /* Allow greater angular velocity than the default one. */ + Braccio.setAngularVelocity(45.0f); } } diff --git a/src/Braccio++.cpp b/src/Braccio++.cpp index a0ddbfc..d5d7d9c 100644 --- a/src/Braccio++.cpp +++ b/src/Braccio++.cpp @@ -136,7 +136,7 @@ bool BraccioClass::begin(voidFuncPtr custom_menu, bool const wait_for_all_motor_ lvgl_defaultMenu(); _servos.begin(); - _servos.setTime(SLOW); + _servos.setAngularVelocity(SmartServoClass::DEFAULT_ANGULAR_VELOCITY_deg_per_sec); _servos.setPositionMode(PositionMode::IMMEDIATE); _motors_connected_thd.start(mbed::callback(this, &BraccioClass::motorConnectedThreadFunc)); diff --git a/src/Braccio++.h b/src/Braccio++.h index c3a3f2b..9fe3145 100644 --- a/src/Braccio++.h +++ b/src/Braccio++.h @@ -86,9 +86,6 @@ class BraccioClass inline void setAngularVelocity(float const angular_velocity_deg_per_sec) { _servos.setAngularVelocity(angular_velocity_deg_per_sec); } inline float getAngularVelocity() const { return _servos.getAngularVelocity(); } - inline void speed(speed_grade_t const speed_grade) { _servos.setTime(speed_grade); } - inline void speed(int const id, speed_grade_t const speed_grade) { _servos.setTime(id, speed_grade); } - inline void disengage(int const id = SmartServoClass::BROADCAST) { _servos.disengage(id); } inline void engage (int const id = SmartServoClass::BROADCAST) { _servos.engage(id); } From 81e83b0ff1273c97632e453b5d4d119a2b2b35ac Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Wed, 24 Aug 2022 10:00:11 +0200 Subject: [PATCH 20/41] =?UTF-8?q?Increase=20default=20angular=20velocity?= =?UTF-8?q?=20to=2020.0=20=C2=B0/s.=20This=20seems=20save=20enough.?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- src/lib/motors/SmartServo.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/lib/motors/SmartServo.h b/src/lib/motors/SmartServo.h index 4c634da..d7186b6 100644 --- a/src/lib/motors/SmartServo.h +++ b/src/lib/motors/SmartServo.h @@ -98,7 +98,7 @@ class SmartServoClass static int constexpr MAX_MOTOR_ID = 6; static int constexpr NUM_MOTORS = 6; static float constexpr MAX_ANGLE = 315.0f; - static float constexpr DEFAULT_ANGULAR_VELOCITY_deg_per_sec = 10.0f; + static float constexpr DEFAULT_ANGULAR_VELOCITY_deg_per_sec = 20.0f; static uint16_t constexpr TORQUE_MIN = 0; static uint16_t constexpr TORQUE_MAX = 1000; From e5a0e6adfac9e17264cd3b4ad0c020a85f3b4240 Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Wed, 24 Aug 2022 10:04:58 +0200 Subject: [PATCH 21/41] Eliminate 'in' API. --- examples/Tools/Braccio_Basic/Braccio_Basic.ino | 4 ++-- .../Factory_Set_Initial_Servo_Position.ino | 2 +- .../Test_Motor_Angular_Control.ino | 4 ++-- src/Braccio++.h | 5 ++--- 4 files changed, 7 insertions(+), 8 deletions(-) diff --git a/examples/Tools/Braccio_Basic/Braccio_Basic.ino b/examples/Tools/Braccio_Basic/Braccio_Basic.ino index ebc00c7..547c1c0 100644 --- a/examples/Tools/Braccio_Basic/Braccio_Basic.ino +++ b/examples/Tools/Braccio_Basic/Braccio_Basic.ino @@ -85,9 +85,9 @@ void loop() { if (move_joint) { - Braccio.move(4).to((SmartServoClass::MAX_ANGLE / 2.0f) - 45.0f).in(1s); + Braccio.move(4).to((SmartServoClass::MAX_ANGLE / 2.0f) - 45.0f); delay(1000); - Braccio.move(4).to((SmartServoClass::MAX_ANGLE / 2.0f) + 45.0f).in(1s); + Braccio.move(4).to((SmartServoClass::MAX_ANGLE / 2.0f) + 45.0f); delay(1000); } } diff --git a/examples/Tools/Factory_Set_Initial_Servo_Position/Factory_Set_Initial_Servo_Position.ino b/examples/Tools/Factory_Set_Initial_Servo_Position/Factory_Set_Initial_Servo_Position.ino index f833ffd..64ff66b 100644 --- a/examples/Tools/Factory_Set_Initial_Servo_Position/Factory_Set_Initial_Servo_Position.ino +++ b/examples/Tools/Factory_Set_Initial_Servo_Position/Factory_Set_Initial_Servo_Position.ino @@ -85,7 +85,7 @@ bool set_initial_servo_position(int const id, float const target_angle) for ( float current_angle = Braccio.get(id).position(); !isTargetAngleReached(EPSILON) && !isTimeout(start);) { - Braccio.get(id).move().to(target_angle).in(200ms); + Braccio.get(id).move().to(target_angle); delay(250); char msg[64] = {0}; diff --git a/examples/Tools/Test_Motor_Angular_Control/Test_Motor_Angular_Control.ino b/examples/Tools/Test_Motor_Angular_Control/Test_Motor_Angular_Control.ino index bba4fd5..cb97616 100644 --- a/examples/Tools/Test_Motor_Angular_Control/Test_Motor_Angular_Control.ino +++ b/examples/Tools/Test_Motor_Angular_Control/Test_Motor_Angular_Control.ino @@ -31,13 +31,13 @@ void test_motor(int const id) delay(500); Serial.print("Drive to start . "); - Braccio.get(id).move().to(0.0f).in(1s); + Braccio.get(id).move().to(0.0f); Serial.println("OK."); delay(1500); for (float target_angle = 0.0f; target_angle < SmartServoClass::MAX_ANGLE; target_angle += 1.0f) { - Braccio.get(id).move().to(target_angle).in(200ms); + Braccio.get(id).move().to(target_angle); delay(250); char msg[64] = {0}; diff --git a/src/Braccio++.h b/src/Braccio++.h index 9fe3145..07651b5 100644 --- a/src/Braccio++.h +++ b/src/Braccio++.h @@ -189,9 +189,8 @@ class Servo inline bool engaged() { return _servos.isEngaged(_id); } inline void setMaxTorque(uint16_t const max_torque) { _servos.setMaxTorque(_id, max_torque); } - inline Servo & move() { return *this; } - inline Servo & to (float const angle) { _servos.setPosition(_id, angle); return *this; } - inline Servo & in (std::chrono::milliseconds const len) { _servos.setTime(_id, len.count()); return *this; } + inline Servo & move() { return *this; } + inline Servo & to (float const angle) { _servos.setPosition(_id, angle); return *this; } inline float position() { return _servos.getPosition(_id); } inline bool connected() { return Braccio.connected(_id); } From a5820a628ce9ec4e81637b762363111df200370e Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Wed, 24 Aug 2022 10:13:25 +0200 Subject: [PATCH 22/41] Fix example after removing in() API. --- examples/Tools/Braccio_Basic/Braccio_Basic.ino | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/examples/Tools/Braccio_Basic/Braccio_Basic.ino b/examples/Tools/Braccio_Basic/Braccio_Basic.ino index 547c1c0..0ea708c 100644 --- a/examples/Tools/Braccio_Basic/Braccio_Basic.ino +++ b/examples/Tools/Braccio_Basic/Braccio_Basic.ino @@ -79,6 +79,7 @@ void setup() Braccio.moveTo(home_position[0], home_position[1], home_position[2], home_position[3], home_position[4], home_position[5]); delay(1000); + Braccio.setAngularVelocity(45.0f); /* 45 deg/sec */ } void loop() @@ -86,8 +87,8 @@ void loop() if (move_joint) { Braccio.move(4).to((SmartServoClass::MAX_ANGLE / 2.0f) - 45.0f); - delay(1000); + delay(2000); Braccio.move(4).to((SmartServoClass::MAX_ANGLE / 2.0f) + 45.0f); - delay(1000); + delay(2000); } } From 5f81b5396ee5ee1dfc867c19e4f4f283b349bf83 Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Wed, 24 Aug 2022 10:13:42 +0200 Subject: [PATCH 23/41] Enable max. torque which is save now due to velocity limiting. --- src/Braccio++.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/Braccio++.cpp b/src/Braccio++.cpp index d5d7d9c..82c3776 100644 --- a/src/Braccio++.cpp +++ b/src/Braccio++.cpp @@ -136,6 +136,7 @@ bool BraccioClass::begin(voidFuncPtr custom_menu, bool const wait_for_all_motor_ lvgl_defaultMenu(); _servos.begin(); + _servos.setMaxTorque(SmartServoClass::TORQUE_MAX); _servos.setAngularVelocity(SmartServoClass::DEFAULT_ANGULAR_VELOCITY_deg_per_sec); _servos.setPositionMode(PositionMode::IMMEDIATE); From 8a5cc9472d49eb98c31a4f67a06792070839f646 Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Wed, 24 Aug 2022 10:15:28 +0200 Subject: [PATCH 24/41] Eliminate no-longer used speed_grade_t constant. --- src/Braccio++.h | 10 ---------- 1 file changed, 10 deletions(-) diff --git a/src/Braccio++.h b/src/Braccio++.h index 07651b5..565b9ab 100644 --- a/src/Braccio++.h +++ b/src/Braccio++.h @@ -38,16 +38,6 @@ #include using namespace std::chrono; -/************************************************************************************** - * TYPEDEF - **************************************************************************************/ - -enum speed_grade_t { - FAST = 10, - MEDIUM = 100, - SLOW = 1000, -}; - /************************************************************************************** * FORWARD DECLARATION **************************************************************************************/ From 0da6211b391358a25e11aa0e220d4ad488a115f1 Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Fri, 26 Aug 2022 10:13:32 +0200 Subject: [PATCH 25/41] Fix: Since we use all available pins for RS485 communication there is no reason to check if all pins have been correctly configured. --- src/lib/motors/RS485.cpp | 44 +++++++++++++--------------------------- 1 file changed, 14 insertions(+), 30 deletions(-) diff --git a/src/lib/motors/RS485.cpp b/src/lib/motors/RS485.cpp index efa610f..c5218a2 100644 --- a/src/lib/motors/RS485.cpp +++ b/src/lib/motors/RS485.cpp @@ -51,15 +51,11 @@ void RS485Class::begin(unsigned long baudrate, uint16_t config, int predelay, in _predelay = predelay; _postdelay = postdelay; - if (_dePin > -1) { - pinMode(_dePin, OUTPUT); - digitalWrite(_dePin, LOW); - } + pinMode(_dePin, OUTPUT); + digitalWrite(_dePin, LOW); - if (_rePin > -1) { - pinMode(_rePin, OUTPUT); - digitalWrite(_rePin, HIGH); - } + pinMode(_rePin, OUTPUT); + digitalWrite(_rePin, HIGH); _transmisionBegun = false; @@ -70,15 +66,11 @@ void RS485Class::end() { _serial->end(); - if (_rePin > -1) { - digitalWrite(_rePin, LOW); - pinMode(_dePin, INPUT); - } + digitalWrite(_rePin, LOW); + pinMode(_dePin, INPUT); - if (_dePin > -1) { - digitalWrite(_dePin, LOW); - pinMode(_rePin, INPUT); - } + digitalWrite(_dePin, LOW); + pinMode(_rePin, INPUT); } int RS485Class::available() @@ -118,10 +110,8 @@ RS485Class::operator bool() void RS485Class::beginTransmission() { - if (_dePin > -1) { - digitalWrite(_dePin, HIGH); - if (_predelay) delayMicroseconds(_predelay); - } + digitalWrite(_dePin, HIGH); + if (_predelay) delayMicroseconds(_predelay); _transmisionBegun = true; } @@ -130,26 +120,20 @@ void RS485Class::endTransmission() { _serial->flush(); - if (_dePin > -1) { - if (_postdelay) delayMicroseconds(_postdelay); - digitalWrite(_dePin, LOW); - } + if (_postdelay) delayMicroseconds(_postdelay); + digitalWrite(_dePin, LOW); _transmisionBegun = false; } void RS485Class::receive() { - if (_rePin > -1) { - digitalWrite(_rePin, LOW); - } + digitalWrite(_rePin, LOW); } void RS485Class::noReceive() { - if (_rePin > -1) { - digitalWrite(_rePin, HIGH); - } + digitalWrite(_rePin, HIGH); } void RS485Class::sendBreak(unsigned int duration) From 8159bced69c5ee129e03e11b95fc2aa5ddcbe173 Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Fri, 26 Aug 2022 10:14:49 +0200 Subject: [PATCH 26/41] Delete setPins-API. It's not needed. --- src/lib/motors/RS485.cpp | 7 ------- src/lib/motors/RS485.h | 2 -- 2 files changed, 9 deletions(-) diff --git a/src/lib/motors/RS485.cpp b/src/lib/motors/RS485.cpp index c5218a2..484730a 100644 --- a/src/lib/motors/RS485.cpp +++ b/src/lib/motors/RS485.cpp @@ -155,10 +155,3 @@ void RS485Class::sendBreakMicroseconds(unsigned int duration) delayMicroseconds(duration); _serial->begin(_baudrate, _config); } - -void RS485Class::setPins(int txPin, int dePin, int rePin) -{ - _txPin = txPin; - _dePin = dePin; - _rePin = rePin; -} \ No newline at end of file diff --git a/src/lib/motors/RS485.h b/src/lib/motors/RS485.h index d7476c4..38b0a05 100644 --- a/src/lib/motors/RS485.h +++ b/src/lib/motors/RS485.h @@ -66,8 +66,6 @@ class RS485Class : public Stream { void sendBreak(unsigned int duration); void sendBreakMicroseconds(unsigned int duration); - void setPins(int txPin, int dePin, int rePin); - private: HardwareSerial* _serial; int _txPin; From 8434e1d658e022209449fd21bfdb21727a7d7eed Mon Sep 17 00:00:00 2001 From: Esquirio Date: Wed, 31 Aug 2022 10:49:03 +0200 Subject: [PATCH 27/41] feat: new lessons codes --- .../01_creating_a_button/sketch.json | 7 -- .../btn_style.ino.NANO_RP2040_CONNECT.bin | Bin 345140 -> 0 bytes .../02_designing_the_button/sketch.json | 6 - .../Braccio_moving_range_angles.ino | 119 ++++++++++++++++++ .../Navigating_the_display_menu.ino | 81 ++++++++++++ .../01_creating_a_button.ino | 9 +- .../02_styling_the_button.ino} | 85 +++++++------ .../03_designing_a_menu.ino} | 101 ++++++++------- .../04_adding_an_extra_button.ino} | 101 ++++++++------- .../05_display_challenge.ino | 7 +- .../01_playing_with_the_Joystick.ino | 4 +- .../02_handling_events_in_the_menu.ino | 15 ++- .../03_navigate_challenge_I.ino | 11 +- .../04_navigate_challenge_II.ino | 9 +- .../01_playing_with_the_motors.ino | 20 +-- .../02_selecting_each_motor.ino} | 47 +++---- .../03_servo_motors_using_the_joystick.ino} | 5 +- .../04_servo_motors_challenge.ino | 5 +- .../01_designing_a_gauge_interface.ino} | 15 ++- .../02_completing_the_screen_ui.ino} | 21 +++- .../03_learnings_challenge_I.ino | 23 +++- .../04_learnings_challenge_II.ino | 23 +++- 22 files changed, 501 insertions(+), 213 deletions(-) delete mode 100644 examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/01_creating_a_button/sketch.json delete mode 100755 examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/02_designing_the_button/btn_style.ino.NANO_RP2040_CONNECT.bin delete mode 100644 examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/02_designing_the_button/sketch.json create mode 100644 examples/Platform_Tutorials/lessons/03-important-programming-concepts/Braccio_moving_range_angles/Braccio_moving_range_angles.ino create mode 100644 examples/Platform_Tutorials/lessons/03-important-programming-concepts/Navigating_the_display_menu/Navigating_the_display_menu.ino rename examples/Platform_Tutorials/lessons/{ => Basic_codes}/01-programming-the-braccio-display/01_creating_a_button/01_creating_a_button.ino (75%) rename examples/Platform_Tutorials/lessons/{01-programming-the-braccio-display/02_designing_the_button/02_designing_the_button.ino => Basic_codes/01-programming-the-braccio-display/02_styling_the_button/02_styling_the_button.ino} (84%) rename examples/Platform_Tutorials/lessons/{01-programming-the-braccio-display/03_creating_a_menu/03_creating_a_menu.ino => Basic_codes/01-programming-the-braccio-display/03_designing_a_menu/03_designing_a_menu.ino} (91%) rename examples/Platform_Tutorials/lessons/{01-programming-the-braccio-display/04_testing_it_out/04_testing_it_out.ino => Basic_codes/01-programming-the-braccio-display/04_adding_an_extra_button/04_adding_an_extra_button.ino} (87%) rename examples/Platform_Tutorials/lessons/{ => Basic_codes}/01-programming-the-braccio-display/05_display_challenge/05_display_challenge.ino (92%) rename examples/Platform_Tutorials/lessons/{ => Basic_codes}/02-navigatting-the-display-menu/01_playing_with_the_Joystick/01_playing_with_the_Joystick.ino (93%) rename examples/Platform_Tutorials/lessons/{ => Basic_codes}/02-navigatting-the-display-menu/02_handling_events_in_the_menu/02_handling_events_in_the_menu.ino (92%) rename examples/Platform_Tutorials/lessons/{ => Basic_codes}/02-navigatting-the-display-menu/03_navigate_challenge_I/03_navigate_challenge_I.ino (95%) rename examples/Platform_Tutorials/lessons/{ => Basic_codes}/02-navigatting-the-display-menu/04_navigate_challenge_II/04_navigate_challenge_II.ino (94%) rename examples/Platform_Tutorials/lessons/{ => Basic_codes}/03-playing-with-the-motors/01_playing_with_the_motors/01_playing_with_the_motors.ino (76%) rename examples/Platform_Tutorials/lessons/{03-playing-with-the-motors/02_selecting_the_motor_with_the_enter_button/02_selecting_the_motor_with_the_enter_button.ino => Basic_codes/03-playing-with-the-motors/02_selecting_each_motor/02_selecting_each_motor.ino} (71%) rename examples/Platform_Tutorials/lessons/{03-playing-with-the-motors/03_moving_the_motors_with_the_joystick/03_moving_the_motors_with_the_joystick.ino => Basic_codes/03-playing-with-the-motors/03_servo_motors_using_the_joystick/03_servo_motors_using_the_joystick.ino} (93%) rename examples/Platform_Tutorials/lessons/{ => Basic_codes}/03-playing-with-the-motors/04_servo_motors_challenge/04_servo_motors_challenge.ino (95%) rename examples/Platform_Tutorials/lessons/{04-integration-of-previous-learnings/01_playing_with_a_joint_angle_gauge/01_playing_with_a_joint_angle_gauge.ino => Basic_codes/04-integration-of-previous-learnings/01_designing_a_gauge_interface/01_designing_a_gauge_interface.ino} (94%) rename examples/Platform_Tutorials/lessons/{04-integration-of-previous-learnings/02_selecting_the_motor_in_the_LCD_menu/02_selecting_the_motor_in_the_LCD_menu.ino => Basic_codes/04-integration-of-previous-learnings/02_completing_the_screen_ui/02_completing_the_screen_ui.ino} (95%) rename examples/Platform_Tutorials/lessons/{ => Basic_codes}/04-integration-of-previous-learnings/03_learnings_challenge_I/03_learnings_challenge_I.ino (94%) rename examples/Platform_Tutorials/lessons/{ => Basic_codes}/04-integration-of-previous-learnings/04_learnings_challenge_II/04_learnings_challenge_II.ino (94%) diff --git a/examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/01_creating_a_button/sketch.json b/examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/01_creating_a_button/sketch.json deleted file mode 100644 index 45332f0..0000000 --- a/examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/01_creating_a_button/sketch.json +++ /dev/null @@ -1,7 +0,0 @@ -{ - "cpu": { - "fqbn": "arduino:mbed_nano:nanorp2040connect", - "name": "Arduino Nano RP2040 Connect", - "port": "serial:///dev/ttyACM0" - } -} \ No newline at end of file diff --git a/examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/02_designing_the_button/btn_style.ino.NANO_RP2040_CONNECT.bin b/examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/02_designing_the_button/btn_style.ino.NANO_RP2040_CONNECT.bin deleted file mode 100755 index 00d92a93265760362103ada747d8b42903bd1c1d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 345140 zcmd?Sd3Y36);N5ss<(7^l1{?XOO{?pNYVsCny@4yovKjT09jnX044;bfe{*=(I7K# z0*EH!0%_2sTM!lfp}1f)4lZa$+)!t%CNcvFI31Ssj1FTts0k$9{heFgVHthjcYe?F zJYhfn9;y6ZXjo_n@?s)UY$DvNnxO{q#i)uAu^Q@K$OZw*lFL&nR5i?}jTcl+sxqddZI#SS zv4aAIe+T@`A-Y3C z&`rf>vl-V-@##ifH(gnJIk+G@&#&E^@CD@10*JbSi$Oz$u@cM>p#HF(9rEidn##xz z-U|h(Bh&|8cCgD`cHJbot`orgk`Bz1O65ATR^%t;b(kkV{O2xHmroNv3q#p=7vznd z?d~#w*jft*v9EarW&R@#y1WgH?v|SY20A+Vfp=B!?&jTPB(LjG%(B&kUFnxsft?m) z<+xApQ#PAhcj(~92qpfzAN$LybRA%41g0X|LU*W>Cw1>)8&W?CdxL*O)h^y?ZK1u! z79K2H`9waYd_-lku~W<4i(N4#dYL$jBXew2jWBKck`X9ab4eCh-=)qlAab<4>>u0sw45!gJs%xnGbgJ z=~ar)x3lSjs@PZqIdKAMX`b3tCw7+dv-z9(+jy~a+iG3D_~{=01-_kshi|+P*JPe5 zeoC7=IkKv%Mt{&<7GIg-YGW@Qr#hNp!NMo`#7_e_gRX|GBh^tL4u+X`ALTy@lKksZ z{tv-}GBCfJDA(z1vVhq}2l8zYaN3^a#W!TH{D%LViXw17kZ?odpAtVwd^hnECttzO z=d1a|PtyK05uR5=mu%viI5=89G2;^g_e%b|3nLz=`=o}aDkh8SNNE7fRJqJTRq4w* z6=44UDMm-Xv5v1$RY2U$74T>&{jR&LlfPWH_(~ZgwQ~ZtTuMqAY`NKFmwx^}`QhuwH=cIg_JIA zr2JMX&q?_zDNi8B9#Z}=;)3l#YA@xtN_m1K)m0_sON?-o;^&v>aAza9pGc>oI6xD6 z&*>NLL0VvV4cGA1|G!seN#L_Y5Gq(agu?XNbvm9x_>l7)t6<$_b$qo1Z**7XxT}ye zAdJF2CFewNYEu2qCwX&Gms8KpXX|(mrtY%sP9}AmRPJ#ar1CCI-DUUly3}R-!@ME2 zj)y=epV2{yTLvJT`U)(cvKfbvV~VFDPL|5oVV)B2C3QVu)*YhoM|dwK-bu<%U0nuZ zB!XopuPytLlyzSzOSMooldKh~7PPu)Cbg7PtEQRaq+FbA8vTrJu~Sd*k})(*;XlGJ z$-fd-<@^u(8%cjtYFb)4{>zB{1N%rnk;Mc6;e$?HJi!L$zU%-VEAzxAASfNcPM|V2SkqD#E4ef$WpmaRblu zf95+oWU%Q#JZ$G%`K|1PJHWeLHpl@L1imn!r!G*a~o85@CkwaEaiWO)gIq#+*LxE#~AJ` z0Sk5g82#)L7_Siav;RDSPo#AGfS-)MfCs}$gwEDuhxvS$GZ&Wgr=6*=fFB89&+Ey8 zTln{!4#k+n|M$B(|ji!geO1DfT}pd4yS5+&DLpf)VSN}cRuAz z;C8WaYF_UW)9O@G``cc#<%n@QV)2->$$84TKK-$hiJ-J*b0?gTspN{BkQ*l?+KQbr zyId$vdxw3$q=7wR$N(~H*6CHLA6MNZzcb#;f?v`5VP!<6b}mrPr;E8{&7%RLZygM* zPOX+#$5VDVnID7w&63ZJ_prN74jPWl>Ln}uv>$h33}m`VpOfbT1e48ySLbxFH9}+7 zWZ4w%AU_pruJ7ge6fOhqOMjwdhWRWMZHzZPL-Z(v>j2I7z3*kX7cA%X{^l8@q%iRQpM!}n|K5oW+!o-P^J7# z_1lV06~jHkx`brrPIk$60MGP2W?}%1_{?a-)rJvn?eYKc8(g zF6Rs3vp%Jj&;tlR^%0E9D|73RRIa4L-ox@+;08 zCpwFq@Ah2}*;5~I!q}(!rXqF!VaS~SXx|k|_{2oc133%zeF;zu3J&)uuhvh_%Ma4N znR=J=(?AE)g2o%(Veb{zrX`ZNUcIscNBd%otfUYvINQVZ7E)DDU$?6oY$b|E2F9#6gcZ z{H71=BZO-yQ7H_mQjreVD+QH`>*Xylizk#w=+HI$t-dsAS33J3ui76Ea@@DmeM^u= z4g_jvzrtn+ghJMxBzQg^FlQ#hdE={yrxIR7JZJOMxe0I+zYpnUX8OL8rcx#MzWxcM zl6h=NX(1H#5jr7MxTQ}64DJC4bqM2+LiE(!*B7N-r8P>uMNV>ZkM(hQat+QS=cdBS zzW@Cs(tVQ=($9p(%sgD99Pas`iYrNPDtR7f0)Kg5ls{hKF;&N+``Ci}IG=4cDy_@; zB4^7vic18-?{)=KArZ{i1*5bu=8Un;869yd_uD?gmoodV9f4rUog;XTn62w;#1_d+ zBd#otGW|P=hagR5ek+ZmL=IA){vdLYmB9ybt$ZaVrPb^aeIY!1j&Qy|2}xp{m=ViLEN-&ippbxLTfEB)LEmZJb3JJdP7eByXGA@9Af>P_%1dJ3&XG85tN zv`v)-V__TZ`7HQ3Uj%d;wUhFBc{*pTz@TQ;c$&&774ED6-@|-eX)3_DsizhwK}b1$ zR8`IQP;ti=@hhqf&aHf-Pc34vYKBmzfD<9kLFC8W$|E#Q|!k8-&xm9v2Sz;!VlWj|^ulyyFf+Nz02ke7Q2SAwx8 zgHa5Y3PjdCBuUMkml)6#ry}id=uNYB8E@q&=ys~6J?cz>+a!D+bIz!OER&I}E$x{f zEa4ZREmmCNBP)h*gQps`pkhC518X`*TWW)Z@_qaiJOP9{m-RaNNPq3+c^352cwSUR z+nr5(8gij|{0XN9OElPL0cv7K0AFUslYC7ngDWHLsbxx#vAxE_HfK?w(#$++A4S=vGCjn7V(%0Uk5ati5U$h z%`-ezITv*uLW9&$B=SYFOc!AY4~vAu5-&?^jK^|nAQHKNgP$QnGrM5@<_Y73>ET@rKv~n?V8PZh(z^Ij7LI=($djdU`+1IUHnM!SHd&UY zt>#B)t#}4Z+FLnh$7-&Wqj$PElVPOxTm6$n`yR8L-ixc4svRjap}ua`FEMOn@9nx< z&>Ekq{GI7l)N6L&4mPlLr2$haJb>%d6Clvcj6t2FRbGL5#xT?mUWR%iLS4x>^EtBF zF{pEfaYU%2IBv$)Gi1%iB4C~}a!9oZ??P@PPq&WLuH`sxCWou2y`S$f)RjI(pf)?{ z`}x~T%lQlx<|Y|ve`nC^Utr^5!imCQ z6@OB>P_+TiLqs_#2xDGln~#>2md)H-f~ShzYgn$Qil1lGkM3dbJP!Uh17nOnzCOsn zt$cQ|7iH~szNv2^Qmgu+IsdLc2DNcg?%~1uM&Dd44-c60y?xKKr~L1lC&ImsRGc31ZAFYYV2Blz(@i0A9^P8PUj$l>9DaV3s zv=cG1fGx>60%SQm{Z=4c%cMD~8jYv$`E!l7MYu=9=S)$#>)au>{kV^ZG4J;^&U~xO z2#3kJBWDfIS-K41di)LBefOi~*T@^@=$S-jHh^X^Y~p9226-fLJHI@>Cy_FDuxjBA zmJyyqYwMPoTH%WBcn9hx{r;EOAN@D-Be;M0Df6c@zw@`TN&)h|_1EzkNQY(V2TRTc z!F(om_J`-44V@hc%#p;0_;D2(%wlNdC*!Q!ac(l}Bk0w9m>q@Vr2F%^`*|2g`HMK4 zu#AUXqu`yHBh2GzGc`@+q^4ehXBuiE=LFj9WPb?ebC(dZL;=PnV$YzU4Nz99*u&|8 z%0CxGd(sT{UZE#g#P#{TGymd$jy-nrIac2D9_v4@LYx0R_UO^MJY}P%wsKVd7r{?w zesmlVzaP3j4w7~JIUeJG5f44$k%V~YV|b(^G^w~YWd8iCu*eM%=)XbeGXweDAi|!7 zuxDZGG5#yKjt-C&NW>NBMTiNsr;ZyWXw_FiE4vEUE2~q)35e-O*zfSk0OHdr;d7?z zd<>tfbpiz>qE7H2>I7*p19gHgB%NSw;A_+g(8{qzkRN7ncPAEel&8B2#-g;g`S_n; zW2v24iQIlZdJ!t(&nFV^$CiLl)rLIp?f}PkLnC^2Qn>m27v=L4???GHA6KHb^e8l! zT41FUwm-~MmWtAc_{0ftVq4(Diud8mMen0VKxP7ARWE7;Vwc*gY-ISg5lIfKcKpP_lZJXv1E(N2>bwRdkd_|Xp1aQR>WRWC^Z*O-PKD0hvRN_w(@B?bwdDy?fu%a}i-^VZE^9;|idrLe- z2JweWPnJH0vbPoauxDmV$zCFz*akL(o2;GBE@$62Skb~*#!uCA^wD^xErnY}t0lf$ z%b$t@@+zAT4dObj8%~cgRY3^%f0avZE&bqM_#w|NFk4PG`&MC{53%ayzC_Cn} zK0OU5DA}>bF^2N9z&LL#)tBFoUXiiErO307sxmZn@=;uMd^>97Z9M8$xQ9M|c^_k= zp4iB1$NKoCeaNRITDb>H8FL25@$34o=uO%b)SJ-eBf8Sn`V-h1$AV`D16f?v=03_- z0DE!Y-F+|dYx)|;Qf)JsX>6WQ%-a1K+ze)h26m2usa0$GsLVXm)I7A?`!e#JCkx9{ zVQ%Rtl&kkU|0zk{C<_sb3Nnjt1``{7ho#Diay=&Rv#6Fk z`xYXtCx^`Ww_KL@DQGWxP~M086bDHxQAsN^D*_bpe;FPF| zjv~^~3^pB+hS_hSG$bpVfzl8?SvCbiF$}{ffU2-$^9;+p0knIF)$=t^JZ1s(nDL3X z!9*?{J!bc)Q7c9Z=hHd2Lnm4@N8!%+XZVeLL;REcHvad>zupQ|^HkQ|P9OhI)3Y;) z4++NCokBh#ycVdFJU6!9yVJ>ef4lbqV;z6s-~4E0=trwkx1w%IwDo4`>_0R#>`Oy$ znKd7MX(i~XZ*$VH+o_iPX{#>#({`XgO$UW=#Q3PQTk@!_OMkQ^N%E*crh+So`O_Sd zKh2T$I(irGL7gOB@~2Hlf7%in+`}`xr2NL@}Y>a7`=!l^sL?1JB9Pc{A%k--;}ab8EV%Bwhc&RerVi0(ZvzYDWXBEAN*4Y6;Htm|ra&G1?hSCmu>+ zX3!a2h9ehUJMyV-0~t7eQLh6%w&vo$I*Y+PUM@JtzHhpNcyN&i@%&xskC!;OZpl|O z;&gPUT)mC9Ip}309ySF>d~7v%*Q!U~MjhH^M^#Ieqqqyu#vg&Z5=+s~R>gmAgx91WnbGA^tEjWUJteW zcJu*!6kN;`A4hM1csni#ccUNWrCv+bQ#gB3?*+-%wpQ}BJ=|-~Oh8}CE6xMF0(~i8 zJ7@BR+<5e*oN(@Q*73xfQjMPbd~TGn9k~?V9ii84I=q2iFhVmRobA(8{iM2#ov*2jFQ)lp4}Yvx{ci;=?lZYCqg&G1Gh9rH)7z^fAhdCi+SMwgdVu@=z%Lh z58MlV@1y@M$w?r1wyyv^aGRWv^#JF4&cC~Fm|{LQl5<4-Z;R3Ywt`o1C`a>_ zO8&PC63wOeqCJ3XHZJ(W4ezlVgmn16Pj`*~&FdV+-JQN0{cqAKLI2z4;3zzy?Ktux z^mA*Bt!Pse^dT*s+8;2FeaGbG>-byvcbskL?Z1J)fWF>hyc>Aic}x1+B`Mr8{$J>W zYwi0FTN*sfgZR;e#uMb|8pOqoc6#n zgdklYbhB3Sz&(K;xL>B4VGrEHr3&s%{o|4cuC{bKWcE#$XtVyZ|LrF9iv5U?5n8#k z?`nDmEAhSweZ1s-Yd`lIzohSfKcnBBn}$$+etDht#k_CN;EI6%I;4pQj9(%>_)v}y z;+~o4Ime>=IP8DJGh^L=-nRrGyz!}E8YH0K?4NitB;R|?Z?+L{wm6>n_4M4YB`@6Q zzH7%pY|jyz8abPa`QX;$+Wzubb8sv&TROKQ_yDe#ucTJ;!cB*V&z130BrjYEU*N3h zgRw=>cP=W+$@y`2Xy?Q;sZ0e_L!PE0evGC%{x#fdMFp6*vW$NOX9nUkcOQ~-lo|3a z`M;OWUVg`j*=nW=lCk}fL>RN5O**BU^(?D9iM|NN$|cM?Ys?s@Jr!Sm*hp;R#Vpao zQ_h5k}7Zg#-=68e0+Sj%w#MB5CNTu4K^(1E`c{GoQyaDFg?Fk+04aCr1b z`X$Z}6SMJr=3g9HWipa`7j^c?Q<|w;oM6pk@-%?bDUVUd=V_AVxm^5glROvi!>-&p zxDU|?#>j&0PBmyOD&t2^((4R*4^UUn1nbv9BBzONqwA2RXA0r|!GRH%XG+GI?#G$N zFk_^d#^6k2a3(9Kon?|+rI{9~bU26QsyRM%lJOJeTQ9n{0_W7C7z7WBb!lICii9^N2+;~bc2ev`LW*w=AnMJ5j}GA_!>;r z@D5vhe5pXjSj3YXOx1o3gOIf6QPqcWK>u)LnyFz%C+=doQrS|A;D0&m6+tBGfz+-TatO>&MFg!U8d zPNPLZaXSCD_BN82QJmVZqYX5uI=nfLxj%r^8xUj!31&N08>R<0&|(F0M>5A+I?6Tt=C$oiK&-Jgh%?AG2-SS zGg!st_;-T1Yv8A#*b$HS1{ev^BC~zA6l`BERoK2*`WF+8Pl$2)2*3M~3vv8MvRtoDL(KIL*FAU^}o*@QD$Q8MZV77{*2LF&4r?1eNA+B8|W*{AC zD{{r(4}h(}8i#bE5?>g!ilIw#@z}s9F&L47ykeC2T?A|+tV*fA4fnC^*D~F&7s_-` z+jJd1G`l+&cD7Ft-y1;7D|@`~jLioDsib27?*_6nh377pyfnaINviPd<&tLyWLT0S z?7dv#9gt&*T6q3)$@T%3om--?Ia$U@qC|8ZN#$DPVDCqCl}x%`pe)qXr|*_$%a4cp zXAG&e2|7lVY)h$0an;oz2ew@djk`KbKD^rdo zSM}-hv2AfA>2llGBKeRQYr9lx`%+jdwJQ`eao;WZk$jo>w~P5mInxH;2o9eyLWkRP zK<8u=Vea85Ee>=jP}U$Vz}J(fxc5#nyBP7n#cWVxw8dBX)5LQFkDHx{-(SO6<1(#m zEj!54=zSe89=%*b_SjKxcE#Bfk29`nY~!fEHT7HlSB?U=-aXt8vitm}gJk^Xivx!S zIvCjRFw|4Urg|EBxR(l&>#L12j9LNfzDYgp^tA1)>Qq*)LKq1z7tUNl6;zvg+J6Xc z)W1AYEu+LWirk}e5YFuP}?ZqS%(Ru zbHU#ffJ_R#2Sbk3RfFxcXS}#Hd`Iejh)mYcBkQ&0(s=Qv@aj|_tm5_aY><54iw>ik zw%+QdtY+}KBmK`r#*3xl{n$c3&x~}l6rZmPTi{!%bPMBApTz^OUo9&DT z>;(eh-r30UdLxvTo-`5jd)sNTJ3>u~AJ^xnTMNbPOP9=zxWnIsRtLw6e+do4k$TAr zdkRuqlq03a22VOnE)utl;x<3he`9#O_(6!kNZG2{mx5GmmRBN-_w!)nM}X`Yugk%- zzeBXzXC)yg12H9J18VG9M}}L4_Zr~Is-TLq${BIWK#TdHbCP%@B1gWs%{o=w7qJ6m zWmIl+xKeMe{kkT-HiDe-<%>3qR2p&^%hQ(0#Qz$wSq$a0xHPiI##nvOH&^C3J@=^L z%3qm-DLRd%+Je(_6U(DD$X_qUmlui;;@^ql*CEQPt(woCo~x9V4Hz$~f@MkUoGdWXt=7KJt2D6AV;fVuB$`#vXV#i>w<&*LXI#2xV z0BzCXIdO$3+lMzyuYdnS^?B&-k3*zpS?KM` zcPjERH#P*BZ&lh+$w}U)ZHeC*>3<`X`~snosh5(GL%cThdaPF6qQTndLOSy#F*`CI zPxHq$k^ZNLM*6<3LC>a8?Mi+j8(PaC%MOh7c@z@k#PSFk4pIP^rhOw12GUUf#V z2N_c1*@35!&z;i~syiMcfBz8rQ?^V1o7^LB9gPw<8z>7c7KL_SZr2!=Z-eaf!fWkd z#oEcVxFeh}zTZ!@kCE8+k??TtcTz3|%Qj<a+ScX*I zG4Qk`b7)Iv`*?BpP*jpdpPm?s%B<+qwxOuJias?DMI~JHY12?taz&pu3@OAfBk!9( zwY*_#giL)i)anWR)%e26>*4={^AX-{5w~LghDslto_j;(2&7L{@i{!{7V*{a?_(=q z5g&>C-bNz@pT4oIl2C6p)_Wo|@g0`HTyk#eLNb)mAih5YQo1=JO6P~1DoUgWi!02C z>;6mSwxZdTXRZT0*IB1ljl;I|P7qH(66Hos6L7Dh; zctTZRF4AvUfl-oU@%@76JU2vgapdvhErZFkr=pqgMwU$c-Nk#L-4=12Sxnn`LDo7+ z{3eovR3Q`H7qc-6gwRLTkQ%9@bCA^bM}k4ZDW4wvDro)$%#8w=1wWXd?7?$|=V#{w zjP7^iK=&NVrYcN{j3Tm1Hx?287|cXx67j!tSpG*l=*Hml{kO?ejLY>^Q-WG}vp|=a|nL8>hM|XvS3l zx2?L>cCgG2c{jZ1$Y_*#Xote1@Y<`gA*Im{uQ-gL#0b?ClqJ6%l6kYLMmH+Fq>i#F zy+ehh+&whjZA020a+p?S+<@H9P1%MyNa~!OY?O!C{|zs~L%J>zY@CCdO0C30`1_ZT){thkqzpCng%(_soIkg^`d=LyK) zrec)RM7SRAH7cGcGYyW8=x=i>pSah!K}U^cJn|>@vGhp_Z)fG(WZS{EZ04*}GVkMT zW)IV<^iqyZMy4hCnAJtuQ~W6_%|r`_L|+aZER*{f?|Hq(ZkPwaL6xfvn}P z!NgYBb`;x=#E4DI~U9U9j!XD@mCd4wR8YiL$cZSCHZc`z*f~WjNT&{h5`N z1K$O*q=4X3;oC|w>j_s9n=iDvE(Hl>wyPjZk|0ZtL6(b<{r7MMB)F1S5x8;@s&5dg zcVkeET9pfL1gSA)!d;Fz1$@YOx#`){hU}jv4oL|}uPK@uS z^c+paPM^JIBMaSc2V85D^{zFWF#kqiA1UiO5cnH;?s+LN z0rsVR+~A#ZkN)pzM;dON^^hJ~is~U(FVHU*yBSByx)j{=8!B#H$9U(I(bHIEAGtEI<>nfC;txT3j2wF_x{kZdSf*;CC$`r76wE(F`m3unl_s=- zeUwk%Xq_)JAk_}}bv8xCXVRV|T4cBffiRix#;?(i2AE6w(degYEYNkNxEHvY72FEu z4(<-dC4*|@n>N>;J4~z1sE^oOfjg>WxjieQWq}pM{_5|5Oc@kb&8$&5m>Mose%H*q zPTjjX?bN-8(=gKa-W;G>8>eW^G;VbG0MgH@kPbkGV&!yLsK?>yE9fyZzbQ zZJ2tYHGZCvt_NhpAL)G2z}Mhp(o+M9U~F zQ%QZ+V;=(u){S`D=GFQp7vT9c_;c~^D8K!Gph-qtj4)iGN!7s5Y4ShEi>y4^mx6!8 z>&+0sYwTsb7Svvg*YlyD)ei!hdn&fa@#e)UY+nKU}bi4mri z0+o|1JeWPkKgr_1H{05MuS#lrYozX1XO=(vE8FdAbDn5Idh|*1x6)6zNEup#l*9fr z$udEbEPx}OxVJm_V7A7ejrl?x)g_HOA@VGaTKB82V6@EzY$Nv<#%BK1@&~DWu5~~v zCw(Vj-+h)qa4zNn%L#utZep4zR3aO=Zd3ckQ)`Sm8sTd+!c%*+}I3T4rhKr>1Z0IH_orQDfiSglf>FGpB zE2SmjXgWO{?L95*kje{V>BR8wrRP6{3Z*nB{En2q70Q-UOSn@?UyF@r2!9|wzYwCN zG%1Y!ErcpQd{|0%g>+IX4}U17J40qE4TV0I(nmsxQu<>^kkT!oy;6EU^t6=zJru=m zeXPDWhV?15G08k9LQzfNSZtO2F*yGiDv;`rgi59KqYx{le+Vh0^iU{4O5X}4OKC@F zgp|G(8ZD(ShkB)SdTie3V)H&7n|D`i-nQ7hJ7e>14^5Q%JrcT6N}EGvQo1EJ-^Ng? z^!&TnJnKUy>G?OIbSYgIvPdZv%9YZPWYb0ZZ;#Di8%vjj&Pnx)LUt+rd#v5OSpDqS zepG~JNcA&Agz{|?UoiVszsMI<676^LL~kHxlAKR!tlFG`Cwbjal!kAs9g8O+Ekr2y zuS5S%{gxQ@r%Tj7LgKhL#(EN&WJKyeekn(SXxk7O8Ke`1IBltEWSq`XEi7dy5dP?tMxrP#zQ?3*P`@MUJq+N1(~#OKRfDFqebEUR(I6UwK&e3>r5&!V8pE) z+n{fgSUm-{Dw#4UXcV<{BLPJBnu&-%xt{ z{kPwrcCJC0zeayvf4Jc~ga}$xUZ0-w=xmo_762or4_?u9l$JcCwx=)V+TOX!0$@b# z|1ONA(KNZnUmsr`ff%ZwKC~GoHh1(5vQUd>$+x=v7!Wuz{o3_zd`bQtai{Fs)DW zgJ9Cv&4iPG>!oauvq?S68WgSbIDAim)tqA5YGJ zztL-Idx%|y?{K;>_RU+6gkOaiC8W3+Yx4fjDvaxHTbJTJQl5-5Flms;z z-PDVG;6udzs{zJ)cbcjITFk(BC*m27i^y$DFnaD#W%9n4_1`Qu-bgv*_Dg=SsjPG+ zx9&~!c=3y`XLE(GUE|RjG47@&?yiyN{NQhZNc#y_4wjkPsG_6oZ8eblH-yWFHwR?R z*7tfRS*6^sd#M7eJF$RR*u$1K_?Psyxh@8yqndViAw5TZ4szRSF3uzKsah0h?aT3p z{sW&J-xH1V?x^b0%e}tEc$OxxexuKXXX$!By~_?Nhti`$UxAU06J$O)o}V_o&6Nw} z^ceB|dbo|7t%0iQA2O3P2dy`_FVzB1RIgHc(?QWj?hB>ar$=W$-`-$>pV)^w>RU= z_*domJ?l8JnomVer1q@l&6sLDkd^Q_^SBOI1*z}&*1!&4{c^F5&kK4h=dube9fj!i1@Wk*e(K%+Ws^dwYv%#x%;Ej7^x@-6T3MY;K z#eKh4T0Di`fMG8VdRZ@yL{3V036Y7!<|0yW*ghGJ7K$FNNych-%k~@B(M1;Yw;-*S z%ka!jL4ON_-%_~31&O^F#&^KA$WQRTsptZ}Swl{45qjEulOp~05bWRB*$a2 zt^68je;A0$wyW1e>_|tOfOrHS#Cue*uktf%ztl5po?>tB*^Gaeb#rTv=?|~j#V+YC zS@Q@>ci(Be#}E%M5)RkB)CA+_ow9+~!Jst(c6>j<#&|O;2#<ylp3M!T)|pi&{WidjVn{?w=bWSf~3LADO}EXV8C`;!cq4 zieIoQB+O~?bF^l!?9;sx=KmAkEB)Nszvwx{czF-A_K*6_i1BURAFO$TUEEEt*@<|+ zjChZ{3h%l9A>N#X_vWABtw6l-?x45`J(uuAr2o2Wus#<4C9D(w7p&)Ag*7b>MSf|& zGh+L_McVK6xZjOy{;1!={<^zv?Vt5$*6e22c3Wc@Hz3BfYaV4~-D>YW#uh^Ys9U}< zY{Q)|GpW7pdJju=qj>hfgqu#0uRF|_*2IWX0O{U}I?;ZnfY5!W!4dC1>Sb)7eAZ7;Vk z;pV$;GVEJ_JJv&cSI|7&oBndUB9}UTTi)l#Y5O?;;ffdGp@oW;4=U#`QMTx;nik7i zmG@!3cI`5JM5Xe!#hKU4*KcC!p6A!RhW=|!n|k+3)GF@4C#FZ; z)`zLSN9kL_Ww-ANcBjj8wa2xVMchl3`{3q<^Y!ywjf*OlD7GoLC*Sv35Uh$8O^dSS z<6vAHHFhJb>v?+3Lu@?mdo8AMJsPhXXAIzs{?Q*NZerJ!eA!N;NBXs1rO&!j;pow6 zJ!f1VRwht+v=r|;ws%;l4?M+Lh5#L)z72td5l~x~6o0thDW#(r;s> zC#2Fe3A%k{aVWEP1ebEEwtEqBRd=ro?>)AI=Vr8bh~9EQfBvS%f_D=2b@w(YkLHnq!QG^jgFX_ZzOWE7iw_$7{Q$*J`EanEb!#wIAyg|4rSu zO7Ah{HFY<|AlX;;NKo$W(rdkP&kkOV*s4*}sw-7^WdCNffbb2{gcr4JDH0vEM58(w~NO1)|K8GYT~E3B2n)l2+OZpi>1<9wEet5<%2d#J2K$d(k|VFr z7w%|?^R44}?vHx4?_Nf_AXScWZsQPO89XBx)NzR((q0ORJ|GtJ)RV4{|4W``Xo>2E0E=bH=wS+Xnj`m+oj#qy9FJQ~7xAh#oDG z!VCI1PrUDZd$l1Rb#iL@`SwVj1$A!a?pAzH z*XqFOXb(ltrNK{5<$tSPNj_(c-$Z}Huz!daKOL-TQ2G{fJI+S$yofH$z?2R$BC)4O z#i*9Ct>RPG-Ly_qL3uS8HS{K0t+e>lrRZ4X#43?y@4HCiMV~D2O-gaw+*3%LU+kWZ z@BnuQ%4pmHtjC*r)T?o)?z}{NWLGqT|6PwqEd*!1q7keZB=Lk->+xF-kS{uU3p0S+ zHN^bSSIfR^`e#DZw?qc3Jb+hmwP3zTh2y~B-~o)_A} z{rwkxlcu9a#+qqQKUwQ!V4So!s zYJj{^{tT-Yc5t2Jl>UdP0sKma+R5IJU#+^gFPJFRSRpX(ul_iuUVE(ERC`IQpU8rJlN}iAhCYu5Iyc=f z^EKH2aa`uTqspf@7aQyG?z7;i>L}m~zfjwtnq0*-70Ny831)w;i}+;hHDJ520<|lf z%yT^GPnYLtkCQPzL+z)MyQ!jCU+IdDq`B{8kjka-UH{`jl}%wihTQoH3Ccua9(Q4_ z8NNiH0=Y4LkX4+@b;%_O5gp$Ktx`)BTJvTwt)76fj|W-&ik!_}V{IT_%coZTYpvZS zL#^gu*@d-wy||(|sGgufj|o^*1^yMa4WBFV8Pu<6xQ+XE zZR9fC>Qi8|!nZ3NuBHORhPsB~`N)f$1cRn2U?0Zedc@&?ghO%7GQ@#K&VqE?a$3@K zi(E3_-`5_%2o3N0x`qYZH*01#18>81HO?6WFohD+b|#;tkLaD0 znX5=vagFWaLk!+WQ`UVB`d$Nm{S^HDhX@bYQD|?hY}PjK%uhD8wBz^JkRyNJtsS$N zt90$vTkpG>{i*%l_ILRS_3zGvQ{&ys*C!i}w#({oZpW`!oub`Da-7B38L{JlBfSZ1 zo%v5+SJO$@gG)-xDq&5}1&gvPsu7<4fepW6-BbM;};GXFkL_c1P2cG=wQ1NG}pQwS}d6z*bz7 zU{k;7)9afY7$a+Nox$i5j50+z`uWY(?3op-d0(>=;yey`2|b}2OqK!0B z(p+3MWOf;SDD$IUD6}Iy58ZrbZ9Ym~^dVvC2+2nk>Hld+?PEOA`3m5}0u$nNbn%Pq zZ%)D3Vo0#6Uzo3-2%k<&Zi;g?FMbPUYd##$2UiQMI;n~Z7OQ|9;;i4anG=b^^j+%6az+gr=xwyox6 zZN}z&i1S7IpAW0O4EPNNxH2PFD!qHq{-CBD48r#0RZQCme3yrmb)#Hm{BndKxt(dD z9Ov=*TfxOc^F$YHi(7@dBfN+{t9;l~Ci5XTw8zD26<++l&Z^-$s<0tA5$)P9CdRo` z1)neW<0@6_yH-T{cMSc|M{1fTzFiRKN^UAdO?4&zCSGmmm&P@}QD|=>@5Lk=d$C8j zf8L ze7DPt>I~!V4a#!9l3JP_r-QnVk8C$cFnDl$%0^bpD8aflVg?yTdlFc;L>L>!g-GQM zSdQ^#Qu+Ew1mD|;!hJXPCu@V>c$U^CBepis1`W zFIgWV>xFnrup+4c%M<>;6jXw>#`$A@H6dJtoy$y2m+_t1+b zGk(RwY>n9HHlvf&Jv}tKoD$z0g6t%LLj79lPr>K6hvYu}P1L02?cW9Mq6_2dJB^gD zl@+^?M(|q%X4_BtpV~jdn=Y`c1-p35{OnyCq+f>1vs?*mabOZ_|et{v4{-R|Wen-Vl!cRPu|w_=3ny)hrq zB&2=H?JiSxC@Z8M|y{bA`ziT*S*WE4=~GQzIfo4HLk?3A!Mt1I@>9W9clB~m0&sEZWnJ1 z2UcDwKNUK&l9I~H(WeGh^U7?b4iY_^1Ey82Wp11wK}HCw@oBgx;E4I*;St{n?TL*@ z%EyrLF}m9>z8cb@#MX6WOBxd6r>txZdACTy4dK3s`eJ^^rOeH>j1R^fu4Uk5*is{( zo$XK+%4FlcfB)Yswd3c|S(hR7^&@!BzlHixR2uYx1>YL1jh_#wH(ASWkJH8hGjzm895`gJZ?IGN zU7w3VDsD<2H$Rns23O94C37Z5`n^~-&9A{0c5JDZM!g@)zQT56(dTx$mauMUcd*GJ*#CnF>w^8BEg(z7F1vD?D?u(iV^M>^f;Z@*?SLaNFu^U2|BYiU?|J+GtH{?+mnVp1REzCv8?I^P-TYkMBZzJ)& zj2Dy8-c#c`eiMf5ZvQ=pjQE`_FQ>*{jG&73ut6ol;ZyW{MZLlx#cz;VTP?7eyho*;Zodj7CY9L zVf|NFpJ|(cJEg`lGU|0$dIU>P+c+#uu=GkhG!aY5JYicYmL^(4QfU^JzK*44OL1(5 z6t{62WsCG1u;zKJxptouu+)bXMOo+Jc~RiWuR%NK3*MYv2`JsFAE_4qEkz`z`&9gUmZPuzh0FzN** z0Y>`*{kk}{gL`Y;#kAseRR+qV0rVhwx3fln#Ja>l<>$H^;oG8BZj=6-f*0LArX@w+ zxO>`*VwC&qkUTxfPdH9%SvJIzI}@+-GiWJLC%7x!1=`6854r#3mQ6es)MfrNn4FxP zG6i*#Q)vubkF@SYTDQA%krv~mb4}jQB9wIfp))Qyjz~BMo-zw1?dSDa`@QfT$`K{{ zgOpWs3&5kSqC6?}lwEdw74HKdzCDckfm!Ds3|7~IZuK(IW!RKfjgxU}6uv~xU8RoG zq&SnDo85mv`On-(tU;w6PN1fF7kSTuylp458tT=Y5$nklefcTr|KaRy;G3%M|M7Eg zlBSO|w1wV0wB(_M(o!gGL9jYvq7_v1S*KW^eTUjMHB-%^_YEhT0Jl2TpL*J0yKCv5!~MW%PkGnXr?Rknq;#mh|_6Yi|# zi>!(}ovsPC9!H7;Si?9@p;*D5^+ux;9N639E&OMjh?YtP?exT9*{dZu^-sbadocPp z$8ZYtl5wKR)Ts*DfXX!JN;NIEs;a>t5306vV@WdlMsa#dUTs=xSZTyoV@KbNZ>#vFppdTxqaZa3v7y7%M1!kvPZ zC^MIHcf;a^sD~%7=?Ut`5_pct#Y~unnZWYeEW*Ic@FFOmxq~6tfqifKgvQ-2zF6ay z6`S0h$vYHWagy7iaHQ=>yT_5WwcX)yaOLDB!vUtWBh88Qg^mu#M~?AZxxBA@0!R}n zRY9pc(meR)D_=CfCRLkUWUgh49a~HVX0_SOHdeGdmcXwDlXzfHLYKU_OxGlP)c}i- zQi&El7&dTX;vK4Mjl5m9Ua=LmQnGT|MziNSu z#8bLM2cKNK_$=#ZSbw$wXUIbOL(rFG_sq55{(UxCIV1g)!c-1E{sJc3)#`#4Mu*~1 zA$CKqlf3^U3V;WvUBE1Ak|9z7-?h4Bv6X>Wl7EKp>Xq)hER)V$Y9YN5?TN|E=Nnh` z23st2HgT{P=iR+6&cxF$NdB5QBdtD)gU4HTC4!T(V6pX=?3SgwEev0A<>y`R`0|br z9VBPm&*n(y!>Iq(h>-=GreQVi!ur@@N%I&tE#E;a_}*x-w3EufBaQ8%{-a{eSz-Qi zc^T|z*gD`N_bP`zB+Dv&M4y}CPBqPJ`l_kgI@QIdrVb`8;PkbE*8X{l$#$gazXdCX;|~vQP~0*=6hrd{*He87d&IPJjx8y%5K@pts@QSHk_W40smW3&Or4^1g-`8 z-~($1>6lNzd$~up36gH?_kp8@;N?@@=MjwnDazNL2e;<0qwhF9tw(&d%obZg`YU62 zEoak=@HBw^GCBep(xy5}>9ktQSxdRm!Lywut);L&0~Jf-E3Z~Jjre~ODum52t=IjP zvvKxFt8VNgOAHw!yNs5YC4^*Yv3J{4c8`(Z|IY};94ax^;Qj;LH{#nJK8#>uQ^HjPPplmpiT_Q+AvVkp7*!YgqU+)raIVu6u`i63?N;4!9p8rPkx znTpN@J27MBjE7eTY9D8+fkksA`qK|Q*b92_YhPm@*{bB&SC}}12C|D7M1=%VI+;`_ zGU}y$=%u?b8)AK=>MIm)06oZ8shVoQHylgnj3WB_NkqID4=;PTQglmnYX(vz3H`b1gH4eF*+Si(j9 zZ@{XWL2o_>y6^fN86;6tk$O2uJ;rt9w!CV|bayq)gwTm{yI~Q+8FL&a=;4F9FcdOy znI-r%^9j4UP%k4mc!I-VFR!RC)i!0cq#*}yIBF*q34^-w0{o#>?H*$3KtID)4({{z=$Oy!u03N8?KWyEF;aomo(DY+DZBK)3i^lhJvg%#-8K-DCTbdE;~|s!Yqc`xg9W#|RuC9Dh z#~sAUAP1aGK%5J{B6pDBdO{}Duhz~Tq<)+U>WBx2BHLz9`xkpQ}EN>0sezNq*VX%TU-$Bg=qhnUf1ACEGqZmZ!}YIh5b z(`t-g3=bv&+D^j@r5PD6j9pFTAt%f(yQ^PI2Y(X;(b?*bli``!Oe&>G?v%z%*Da zcS!!cpwnFTqY_!;I>31icE!`+Ac9~aqFTqe{}onFp?sj?-ypri)$o7kKb5JlXN(6w zPlh#8?O5tqww9kJ^Bi|Y{eQwbK|D3GmR0rblhzswhvvOBMMFLJ&BAcEaE_< zvvfmrcHhQz8|CbhCdJ%_wI|J-U}7^=Zf-`7I|2H?52%aSA^3nGY+4aMFss0E1oZEb zwf>_VTQ(E=xGlrb`aXyrq#Qj_&iPZE{m%M0RyXqtUrc9kVgB7^Palq!CGCW~e^xfL z+y^?eaE@o)hDD{sm*+h9Ku0(EP-6?Nh3e2xOttLXGH8hv>fC?bV64K1;Wk#SX@N(f zorN1XXzKF2SVwMEqH``wg2#YyBfXGz$=%e4J1@a;MsU#Xx4k$ayMP(!rh?RDrT;!#@blio*>sx3fvJ7+B zi2t>~c9%lG!q8+L@#l_~!9C2hDy1Riz%23E!1&%5ugUr1H93={oF?Qc zT>Egf;G+IKjNhN&68k1Fo<&O+Z``#}$=VL%jI8ehot_Sjk{j9GrBT>+AHaP1&9dqn zqc<+K{t6lpNuC2(x0Qy+s>pLha-f8fy}}_{KlMq4>8DgI;2()96gunUJC2_`bvnVg z*m|HW2niak+J_?x4bhpKma(E?&jI62Y!Q3&o@jafMy|Ae?WTJM;P3KTIx!S!Fte4f z@&`{mTGq(Fl37*@$(owY!Ok^1P}WpabqjWGzW4O^r?Ok%%>fbvXSw)p)a{c)6NUI1 z<>Jxk2fl^X%7dyh>xb5N5Xs?S$D=16%`9^Y8kS+=U#S&h@FoZNUg!7ugU7!Qd`6_O z49K*tRcCyxFwK*N6D@ymk>F$}YUTm2<*EbWYJx!HCM@pf|h1py(X&D*`)QvYm>~6^4L+L)78o z+X?R)fp_Q7zue9&q(2gsI~^`V6>E>x;m+t1AFP|9<#(?S8u=wP))j^k|L+5ePMMVd zUI`AM0N373eAPi-qy8=LQHyA*`5< z611WKw~tchA?jTce7C1yPo=1~+)X8o=Uv=v(Pztj{1z{KhUr;I^0|TYt^EU6%=1+n zh&zM;U~eyfXCa*fWT1>lCQDpwnSIY{&eVjzeG za|h~G-~v!glTqx5vHWtk6Z!gu{w;U|?+rnp0`XGm-0=*!3{KWBl!%M4|6%X@Rg4dA z)|ZGs3o4k#bgoV?ovoWD4u&28pL`4U##H?{Rw8y^_jV+-20fU+e43aMPO4s6DeFk8 zhLy|(tL%r_qm;}QNxd9L9JIMv~(tWC-MBENfYmL~A%`34UfzLEe z>sD?KY8Hj`9~Jy*nJ2d9be1p8fz!zD+H zv4*kdriooaYi{Q)X7)AqM@Z9*#||$xvko3R#{$s(kO-`tCLRD4mW@+YbV{gHFMd^f@l5GRb1(f=B4$6_#Le0N-p_WegU&$1^jP5^29#J6a_na zcnd2)8Q%@b3Pw)_{Pyteyjo2daj6CsfJd3Oy#1_j2`f~(VbMD?I+JqSLeN;bo9-Gy zpZKQXY!oVgu>QyO7wbjLF-orvtcSc@jG14&HmIkyowdQF+?~?CBNqOLW1;jU!nMP;8lr+DiD7#`nW}QTvnaOdFw!1 zNto7O`7X}6qb5*-`Icsfk?^hArja}lD3;&0TxR2%7lCNdmz0Z3C2uhI)$gqzs&7L% z7vN#)!a@~1_t4!rT*JZ;aF#p(naie1SoK=W%MkFZI^-}W;M~hPGPoj0&`ZQh$Za2! zaGHGlt&ng#Lm%}YfGj-|zx$(#JEmeEBWegfwj>F9iI@$aj3nDF!Hc2wOqBx4s|2#$ z?7Sxrue>#-@tFPLTLt*4VY`Ox&=0>|-=qY-1o|u+Wp)K{>wjEM`?zF^90{w3DV?_$ z*?(=7Tb*{2QFh)g>lePvzGL=SDQD~{ z&_KvMN-F~S-4hVAnQ*@rxUV{TL!T9AYMch4*R~rxjn$Q1EwUY578TA4nhnGDM1x?T zCjKTgY@f>L?qo=xlK>nj7srp>fUn=f*Q{9Xkz>ZcKH{}0Y{RfoqS%)uNI5i;W$dX_ zFqNUcE<pe#AxR76U*f`mUr9QTW#{S@7lO+mTk@3N{;>x zeeQ?;Le&5Fh?1q?_p=D;FW`(GVR@WUs8-)OXD;E-wyJVh%QD;2ZMwDe zb?n>HDDf%C*Adl&#*_3R5;3-toY0da8b)Qg%q?3P^N~orksL8wO0!;($%m)S)h2Tn-&s>u^F?~%P?roarh$F4&A6|x*^63oDt;; z{*3onWyH@$FWBIo8t-3-j>CK6B}~Hm-^Sk$j+%hOZvjT44rdcy zJTd}bm7X~)0lZKpViiqCt(f~8w5r1zyz_PiJ8XH$&5D2Kxq&?o{uX_+8{ZsuUy(FK zm}eLGKC$+6VlUAdxcNEaL3qEp<3Y@jzGOW0M&!9PUUEZ@xHl3qfVZ<*&r;0d+!X6M zn{m16vHIn){D?PhBYDhx-~#S}Ik9`$W>w#5rR*cVO12>CUm)=pzo_F?pWwRwU4`_{ zk8~fdL=(Tcu`km)K`CdSr^_CzRVID}Tl^@E%jc}aS_Euv1P@{;`VVk8X$N2hGu=7j zpFqdzJZP6#inb=Xd+anj74FkmUwgoJ28SxzgA`uM6B_NY7qGpy9C-dn$W25`Wyl2% z0mdRnJRCXYliTR7Cvq4#Pvdh0dRL9WbzbC0H^3ZmWAq4egV$^9vSGi(_p76S@#ToMk&8YVWIXTKGqJK}+94N(77j&t`x?4C z3?2))gK6M!ieZxfj3aIf$$K_;DUYYOTGVb18pu1%yMzvF3hGYlAC*6hx)S!@9wF=` z?wdQzK>||1Wa3jJjaWkyax2`t_=A8v_XhBrxy@>G8G6_asy0VVLL1;y&c4r52z+Km zD)%J&Z_u|?>s+b*bi(`zAgbf|UO!@5dBH~QBaElgb5MGsR66z5PUMxv^WFiEsMI?- z;!qeCSJ<1`W{0vroz4I`;-I8+Vs2_y@+X;*uh!UN@A@mx06!BAfj%p^<|#M@Fk_pQ zuea3mD=aIljrvvEJAbmOz(zjyGTo|K+jN*umUYsgH+;S)tgo{tY9-TQBO`h z42{94|AT0%x1s4YY=ug};V!^;H%i|f#djCnfup71h*RneDbc2a##;esxH zo@Im4G6C=vEPb-IzPbKby>&(N3iGU~O+U9zZR8BC)|ai8HL|Ma<;RvcKY8rQOyB^0 zKQ`Y84pHDTyU>Ic96C2ND<->nlVwAu)w(7hD|s{Um>KiXBhZa%;%L7)g;-y1+3Ft9 zqSjSC@ShJ&!TLQ|>6`IHIN4m^2rjIwVUOiY_vb#Hcp^elcHWbLIsc{4x}gZLuZ1>V zf;R5ILeq(^2sAq-h+nub`KaDfJB-#1s=f|DlQW%oD$>0|C!UPhR^Tj((h?o>vG(&u zDyhQ?*)%Y&){^3=c3k!)8k_4<9Lf0a$2>@e-Ux4J`i!PlD+en=bD7Y@lnl5b%T-?Y zj(JYu%*RXwrPGoEsq`3hg(pjbIT8P>Q7)a16XX3zeLL3YRBz&4j>DYLV#h{*>1k#v z;FI*WTvn_cBz`<6o`EkORxrWyg|7!Rsm9*RI%}f-bHD?ihr1cOkbyJ}Kfvns7tAk( zI04i$E53}igA+fD$S|yOXVIXezL2mD4|Z`!47p+b7|?H5GdS)`Ora zM-6Hm{#B!d#|cvEw}J-nVtSDRy0<8nHb+W(326;DV~hjdfxEh#6X!$P1<4a?B6s_b z_TU}!{MoBtRfM&Sxd*(a9WS>m-*H?s+>+s{)o2X1I$_G$`?W5!%DAmz+XB@hRjo=Z zvG z$NE5{PP{K{TM>g{M%rm5`{*X04KVHx-!8#84H)cHsn1fKAVE<|P+BD@Q!qDg#`h*4 zqCRt+__CC0@O^bL0q2RATN<_+x3Ypoo+7)czM-DRRlpZ{@VwK|MC)J!X|=6@wp8O% z%$%i-@V0I@J=yT2X?eqPTDv^bN_US0^~;Ml*f(MP*vY?Lq?HX3?~$J4F0fauZpMyM zk%JhhVq=)K&soh1mbp1`RhU6Pd>i&dR`_k?i~2ta5r=RZzT;4*iUz`ge1h)z!^O8R zmfB^&m>)`IYLMFF{sq#&kM}=4O5drFHrsvvnl)6ShfrENu#NIg}3FV4?N2}kp?>MZpnc!)L`m@7JZBU0BHq@eLp7QqHC4Z&Ft`p~n%I)&r z)0;q-U}h$TndxVD7TM&zU7JjH;~K6|;nA(c7>7dT-UpOkXsZ?CYe8aZ9aG9_pWaGOUvHM7pJ#bGFK~uI_m2=yy^(z|I7}rjD zgv~hbrj_i6L0Z55f)kLUi|aUx7N4^@H<{Lg&EVeYC3<|eM<>1)RP45`NQNFfee*<+ zi;vKz5tUa9U3W^|7%a8x4VQgMQ&aIw5oEUnDgEc8BwPI(&VXs|gT9oh%J|zx>Fwds zFMO1%Hpq;(qQ<+)gAihXB%@WFv0+0dW;e~uUFb=g*%Jq(RBOW;1?;cRqi*X_Zubg> z;dNhZ^_w|D<-LaT{^DNii@|Way8)vSFlc6fFrX8cp+(&*b%dB`Ax;n8|{FIRUYN8XxPw! zdhYTi;=79hQ;xu7z{`hFGv?0sHEe(uEu{Mi)kMqCS_R)X(0}>1RPzZ}_iI=&Ni@xS z(%boXd%>OHlVf~-em2oS*xj%}ZRQH^@{oLLMNVuV9mCKA zzE~gaL=T(=mMPF<5!jtjudG1YXKv%g7=Ct0_z6~`gr83VKU2}`D19m~VduBePt3E* zmx=%1l`!wv$U(227{p+r5$NPl>c>**^B0n(5&P!I`%)S2k8lOY2lU9t ziJy!d#k|h6{K_+4lAl$N^if}UHeHB~IgR-DE@VpI!#nFNvTIKrlrx!E8Z}5##&Bbg zXm*UREx@4?sKxw{R~otr>k6(s_%|1e5#@29t( zqzk$W@aH%34_}EP#jHY^pPWB&evIyg-NwiYn2&-py7`KR;tdxtqJK#q=J!83TC6U1 z$z5N8kKcA!!IV4UnZH9OmX9iPaSqXwEb?Z=jxS(x(L1`jl5bDM>|utvRR!Qv$>EP| zb)~GGW)$}44u!Z6v3<(!khgOkoRjt|g=Yq0(hs_A7UnwT>$P)TTG+V#xu$3ViCYrvg<9AuHD^sQ<8s+F6$LzCqC zFntN))~s$@B>c6NE34HcbZT8%jiNKdC1{SNYX!cuR+S{Y=TixcjmH(8gtG+x$o3`` z)PdfR+^c}@;iM)`d8-*dl~d5VKK9LML)=o$JeL6I zZXe{RQVqf*v#!?0Kf+H3mti`zr>7e{pGtL^=bDK8zx1tc`|LlKYF1IX@2lszPPZ;< zJLdatyc7+-+Up}KB5e>@Hpt(U2m20gh%e7`$&ADB6R1<~SM9>75Ej87)6v9Y=yhd&JbI}UFi`F9+C z6lvGu@J)zf^nb-+Cccjo;usDy@eMp(kHc9K4);npEJ!$9^#2owXSTVn!{H*}@GJkH zI6T%r*WmD~r^yo%;%{E|Hn;MvPN8|5rS%wok8O+K{3)|fUZveEe_jS#R+`oDP&b`< zy1gpQQ3fkZ9+5Lrr5U>b&la?nd3JhBusS>q3(QXuAL$(YM#lW=Pc$^t4P@5})#fhv z$A`@GMZTj1d^tZjUVN9#Tx-#od6Uen+(i*o`7V04Dw(oB`*e1NS!pi83X`}?CQb?@ zwU^-Zt`8(jzfFM@>G!ih60nUwL%x{C!#4$S5hs#d2I~$xEqW2#&OH(JkvVHEUGVhb z^QIsVtkw%MhLlonNs1%o9`Yt4CBaSgAIpEjOYq6cJ)wijU}xAAg22wypGCXR)W91M zt?c)my$WaW+h=*F3?~+>$}?f9q`wI|c+KG1!DgYDdG>peW?)k&wE&hMazu*DY;+iY zRR7R&CORXqg?8`33FVdQgV1^yk62|o$n;ClCe*|8qiWOk^7#Er)jiuw60m0b?aI%RM*hKn)IQblEN%vH0^KJJ_-I#&ryBAPP9}juA(^q}?YA(LA;H!H*S%~O1A8~0Y$H}mMdzKXC?KbI)KZd)v z&+=)I!(0`ES`Vli;6%Qft~G z8OE3DQjIdmdJriNt>_N1DG6)>R^LSElmS28`!A+=!G9n6cf8+w@n7fCa~J6>AiH?Y zY#It(*l|%>S72j-y>XS~Q4cu2-J8H}nqAfe&I9zuBL1ym$bZ}Uj@r#;+J8D2MH<4Y z(Y>5%Iuhm~H--1MaJp%BldL`0oC@50+{>nDOkT{yDa~(M?uS;7-1(uV#(KrCi`bee zzXozs`W+w9NSIpz+@;Z)7DCiCr>&XxI$nGr+5_Cb8Q%2BM+c>hgkwE48YX<*g&t52 zF+^4-J4M-U%26GqJuH^n8t>1(2<6^(P41bD@1or0QAJm>G}|&qd1FIUra8f5pm{$t zxoI10;Ckvw%Ne|8L}#P5snpnA_m%Jv7F}-ew=@@|XFLtjQyD9+DweQpPH?tR>f%gY zKH2m=@OC4hH+bhm=nc&^y#e3XQg3__j`ha!h=6g&sK0O{dI$QSK@RdGeKRwz#|bDf z3SAP^p+qWk%GElQ|4SXx7Nmf>gCFqFcJ)lu;S(Q#onGfNTX;OJmY$mN#NmnW+Jt?0 z3=c?Zkp}PbX>OL6iW9#PyxA4`ERVM@+I&bu`e3A|uSe=--+5s*G^_-6#a|l6z7C6N zioKp>9uIR^=Xr5bI76aXO4vVIW#Zm&vG9fVEthW_H}9e5G*C4qtPkms zJva-5evQM`y)Chto1vMrtuyp z)71>YAJlHkKTbX1?P!60Wa>jjHcyuQxG%w}g@h>?^tljBYftW!BVJ>IQ?|RS1-kc3 zyI_5r>TJe&BSrG-lrunH+mhhNEDI$kIrmxqf)#L`mEUcIe~q({pQ{~)l}j8i*#~U! zRk~EOwcf5-zRI4#XCyDR$((#ymrtrY&XH$W(4M1SZ5I%UR4xvT2JI>BIzw-(~O$6;jXf7!?aANf8O`+fq7C*pq~ zpa73P;=d1jUPkd!U?Sa<6(V1BgL^r2R|(d4LcB?lJKe)En~|O$482<=b5Xo0c%}yb z?;U7EQe+^RxFj^u_-5Vfu0554X|zsb*i@JG3hQ{Y)!}k#QydM5h+FMo&ew&0;dc(M z%VvMZp@m-w(xu>_V?6~}U@#I~oV7yzu28|{fvLgy9%dwvMxHe1=zk``D!W79COeCkA*uhO9)al2xK?x ztfKpopkNBuO^nz5jn+MtJ+2Ql@L-nja4CM8p|Ra+aCjYTch-R(N4RGwNeL`j^uWi10eV^`xK9s$$0vYBT@Cqn*xwqJy{b6G+DZ2l>#mp_En!;G z4Q>|myzf>1lu92RaTpB71w6IvDd?(oujLC8pr@gar)>*%I~<0Y@uy9cV?AFm9yu0P z#lBh-WUlUJz&w+B7AMkp&Ig0GW`|*ZJkR~XN+aLf?}87RM!rBj@VL=o$lzk%-;M8W zPtf;YcpZkD<6l$;QHSlf#-Ys%>Ys2JO5^Y51dq8wMJcCxHuk%$R&7R&wP$T5^lDkM zQ|MkVG%9<$Ho}LZ$GHWRt*5e#KZtW3ba@v;kIoi{I5CL!OQXcZpGI}i^P14XnzYzAn1q(F>JEjE0Xc`-_KFF@M;uPe}AIpicJs43QWY`lE z#7C~??2cr4`zwnE*X3En-_!o6oGTG#S7(nFC5j*ZA7n*S^QZ zRH!-_Bs_k8)Bu~gNz(nZqlC`_=Ay&JbjafL6>7YsI-EVd#x0#ArY!&KP~wkTib*TK-w&*QlVNY{g7viVH>*(f?(tb{~Kb(G2@o5<`;McDJko}U;YDc%#&Ut-noH`U5>AW49hx9AEm@daoDFvRq^ zl#qIoKS&zJkSm1gmqP?7{uTPYONshyAe|@4E$4+D z93sHz475T`2&Z`U2Arxq|Kly3p6-#0ngGjBV11Cz6aCj?Kgb{jo#n1!h;4h>mj;@o z-Fs}MMk$=6veaQk6K^bn*35Y5y>Ni}2VW7(sOYeshQCJa7)Xiww?>nTKX$+CJDu>+ zNhVIlY;j{R;6*WzfSrvO>%n&-XkUe7O&LYwq<0TXyB>qATV{GYTWwAfcBmGplUyqA zc+j}?Rc$=S4N;CA%a-W{vsrMc3N)OHtiE_r7TW8}gw`D0YXZ&66K>$t8RFLeX^7G$ z$G;!{FD1mj?hbDDWnpLDgq55VN2ATkcdvf`mh^o>{QEB>|62Z#Z`|}E&#{$G1%Hx5 zyv@s!BsDu4_MZY>9tO{sC?}+r%pF|h@&PG?+whVf+he)NG5(W0BZo$>2vJgG!L2hDP+$wF*6#&26#HVcr7jr zgunI~r%yq=K7v#d$ipv{ z;9I*txJV`bEd1WZOyD5(%jeKWrgI2sVk`8D~py{~uF_}>(%$xBSWcYrJU#Rm;XO!9iA=FQ2>bsj9*y`!NRj)cyB{sf^vFxJ z;toi>KDEhh@W+t z-pQ|f$DqSRd(xxuw!uR?hW3>20OuiZixOV+M?^y==yaM*zn0eetq9chR!{-Y2b9Z$ zIV_XEFt zZsf&w=~?W{f>#Hd5&G09b9*Fe(mP0FR1P};>Py6?Zjara0XI|D&KK|l98M33@Q?#u zQ)$oIp7oiH%JSj$<7r&PSp6zi~0LQ{PK|suM z*TmoW!|<5~h$#d2##84vc&tuXyB_cP0a+J+Gye9IuotsW?Vb`Z|6_dL{XM=w zHQ==?#MBYK;C|0-@w|wWRi$4ZgLEw1y=@9By`ciMQL+1Re4W8jul*t%qnSw+Y7jJKw)PO%!;SH94@Qsej)~KPk3gPH-7&@ct(|edn~;@tbYQr){9C{@m-7I zgG8H5TCTSB9q=ySK$4 zH-rm~-tWck?+cUVi~g|}Ae9Ie{b_*YGIlgBVyxV1>(g*>eaK3E>Gtm3Y zN9Gvkn2#ZSri4S?>yyF#;l;m(lB)EuJ)ryHkbXVcjZyuVq8+ukmSNseo9@Hah`LuA zV>SOHPODzbjho{&pBk^ZcVn#P-nGLU`J(9qIHAZ*wlUe(7{|27F(!8!OBr^|H^yqw z4anVV$sQmv-s&HQ^irD7I|bKAR}IDMd+TZwT=ewHrnE2IwDzc$&JmZMQr44YYEeq z{9DcXD;J?&j~fGhW3@URRD%8}#V%M9FXgzDlHo3nKmQ&lY`!3QpfLXYPLR3!)!m>z zutT`=aYPkSbqc@<(yFqq9;6s!4IcE7OSRbwXTb6B2W(i!FKBs1w;`+V2V)v>eO z*jaXLo;LQ;DQi9`j;zsq==9Q=f^$!VztYCr*J1yIzgKv3*qg)Pw+R-N20bfsg#5`k zAM{G{d_DHAcSm1_?euEsizT{GY`gZ&FGklLmEsKn&g1ZQ`m&w;>%ck^6c#V$qhE-o zAsOdbnl_$B^69a(@#r1Ow+i!dEKM2DNBqvQwD4#Qo+LMomvK3sM(fuNeen1WKNg7# zz!?+&5+RLl&e@A|53HIBLeNc?>=(rRkt;sszvch!f6bqb{E5il2zx>5u@4c&ohX1$ zps#;@nfw1Mj6Vio8S!srKJ{Poe}Mc%zy7B(8~aigkOv7LbmO6~51n9=F%?1wA>dY2 z8PIn7sKZ5TeZNZtkDGIFF`C%)j?S}1)t6#Dv0f&A8sMep*wbGFW>8U_TZhQeWbXt| z9XLhF#J2;~(sQt%pmjdwj+8r1_Hk^9&R|nQ^PvEgZ)-r73mq%awR*dvYMXEz{EkVs zIvcS66Q=+E1DqZ-+@watFQVQfm>U8yFSq2&r}5~uy3kPUt!r~=@c%>TMH77{6Mqv> z@{F_7>W5lI*5?) zM5!H)l##?6nh&*Ft=7z7XpXwY@;1ivJ{Hg06`ussNET+|Ef$kwB7T!x z4Gsan(56N&_0}b`VTT4*e$)r`5mSpG=pA(bV5Fx-&~!`pb0Q5$w@LRmMTU{?bu=E$ z>_aT;pBmXT1J@DqXFzMzTQ?DN5GN<^_3z|iKK_pL5iTH-yOkQlgWxH{ zIvO(Em%s~8(qw3k2@dsK$3{oMv8r+^D`0P;w{u1ka{r7I057hI%5#r{-k-{{O6gpr z!VLTX+!o@`XQ14_x!(a-KjeQC<$MSpV#wc*yWdK8@8RxWoY=04nT&-Zs=WLY%zko zB)MGRW>W|kdZIn8@`IU<;nu|tQ(K3lq3wj@DC~6-ULm+UA~&*xSL6q93LPQ67n(aLElGYrj3o#2TNzV!z^muc;wYE*cXf<-Wlz2mt3;T_7aOICfd5Y?rf!I#-=L_ah z(`nQ+<(eAH;x+h5L& zKO{V&x=;Jp{{ZK&5?w*GLiELGG_{1WG+e}!ip^Ye@c%k<_l05Sj=d-iv-0CekA3ep z+CQ>P@71L_CYs)f;)xI?eHvqsoCj6#gB? zv6YoXEqFoG&1CjUwU~`{O9e?x0sDZ9_>V&NhDeeo9=pMKq?y+6FNC1ko3{b{ZvY5-i3(HMcwxmKA1ClzgsqJM6$F+z=neaTl|904vGqi;_rM2fEN7va0+J;-X zS)Xf|sTkN!x+A=YbWC8kZA$A(#R|iTi6dihWL;YLcuMdzw4IB??X{2vEv$~hJ+0%U z^-c8(t#Di?t#MNrt>YSS301F*JD?UPMzd~6!1~5vW>$xWTLHb|KJ^35up)piYS#`9 z9Nb&a;cLvko^9g}PQ^|V^52R$J4OT78S>8?p|Zju+H)b-kl@Z?Y7yRxr-Rak-5m2Y z`3Sl$#O1H^{Q)Nn%DFuJVYR|_Nmy!Gd`rLaG-iBkHmfjl37%2oyVb{8k$E7!%W~H( zq>KD~@a=CZ+mC`Td&Wz=@bQ45mgvA+p@%_rm_7Qst3+tV8HaX~{L$IM5!{oW|A`>9 z$hus2?G=gz+Pf|X747sz(kS(@yn`#KLL6n%uU+jqP`%G`ubX!+@b=i{l6LLKHTxIL z0mg5H6t2ue+Q>Ubx!g2QH)Ld-7!DnCCBmkVGxfWwjLqg~X(s$Q3(yP6GHk4KYTy~m zl08_)CU~F6`bS@!#~GCD_E%O`wEZf+-X-dj>NN0@`2sZic*H}?b;%*Mm&0~|YW0Sv z8MR7w%bfev4v9xCcNgjUfRSao9G3%dsYibq+FXToUb=UMAiHmfh^+nh;FFKF zW{uRE%&V<2qBW_Who#oMfYvDEt!XxQK(jj;ZFv)IsgJh>Win`?c~`_+^MiP6R#nbv zd$Se(U!XBUc04jjb@!n)G6;7Q;;p#@8md2me}8$|z!telZJy{^P(_$g3mCt|+@&$O z4?4f}d)tUZ{RGAjG{MMr^&zZ)t-evyy!lRWcVc^yGQLXxDyVRM-**f6Owgoof|lHHc%||qJHpS2D=*4sLt zt|DEr3wVrk`6Snb_}C5NoE@WE5q%*DZy~NECt=!Cu+R!$AbNGiDV$ia?vU&N(lSVw zIB5;1Gb4{nhKtsCqH7hn5^(j{`M7@gtOXSNLk$^MvBUu{7*RkAM+v=*8C9e?-i6by ztRVT6#(1P|VtlM&yD?bAa$H&7DOCzcxH<7joPSAQwXyATe54Tp1>?LI<19zx71)uu zGQOkP$BK8x$C;PLS&+v0A$)&0KF%v8DH~R)z}Ps?3D7vta6O7~PQy48?Ljn0Qhc0$ zJF0ZS-msOcI3bvt-?)G?WV{c?+D-jK`x9){VVy$q!hFd3&go8UNwG|Fx8a0I<7t%m z>GuU$@dS5zy#F;pk~F2cQzeVxq!TIC{Q@pX83jRRzXg`rB+vM#tclLs|KlT>4xJ}4 zGLz^`iF1e~uTJq$R8jEAMtIcXOWlWvlvilxJjTYxqrKJ-*VAdNH~N+DR}Gw=eDNwe z#=(0U18!0L2_-OUFiNW@@d|ffKG5$IBdk3FKZKy0IwStqqc~d%G8gNVbwvC-qu{}~ zNWT|5CvwnO|47QwEK$JFC!X@j{So-T$P;=%XRoeI%+uX3$DT3{*bqS+6Ru#Hgcs)m zGunDvqt>XvIX_V^^vXNAIavi0LCLHfxsz2eG5Q?a#=2P{JIDlflpSM(Y?yt@qAZb1 z=O%MAx!EwWW_fH%xtCh`D+wNVLlD*kpQIDiEviqnq;GFl%@gLK&Qbqw0uQ%cYURp@ zk%uTG(2SstVtJNJP=5HoK%pKnMc+hQvrPUv<|O@pMb}$GR71PhIWOyE;-*mv`Q|E#6_ER6FmtNPuJ}Ir>y0m!$;kB+)>HWg>{9ZFGk&kI6xyJGz^A%t;k7-KU`ZY&d`!!0}m%c~aMD%r@ z=G6ZQ(xYu$xrnm&{Rc<{yI<391@AKNX6ZdWJxXgs`FTyAYdBq}{wMcYiTWM`-CL_V zuUUUJ_rq;U*Qc#|&7*C3n&10M+Kx!;%E_yDA78!utB=OWIHHw!d3+Tonn#F37vs+{ zW3qwSgZ=>Y7vOcr&WWE#4dS5ydFmp1bs|P^^GFZ;OK3phEK+N>Ep6SUUb>CqBSidR zP@yT_)$rR9^Vkvb-!vjKq#Aqesb=-&{cNYzU{zo9wis_q z;&1b~vA4~3i2EQ_72xl|0h|72d%E;ovzbXY{=_|{w=DiP_T)&2<&~aV;ZF%Xq8Q(m zd}Nr_&_{qbZla{3@ZA^V!Se2!|B#ah_ZT_RKhR-CPVyoii!0=Z9}-TyBg!UEzJs+h zXgZd8Naju_+BE?ad;!MpR|gD|#GTR~2xzMl*dFxHs=RhyTv1;UW=ov3pGQI2X=I?jiQ{e335e>}Yj}{o1BG&5Ajj$Ks%HQ%S?);OF_|L?brZ$e*r%>DdeZ(1qJsVo8@bpNWb`{n< z;yiKUcOn?OJE;Xn;$x@BiKHWnu>=2w?w^j5Pe&SkCO#RZvD=HWGfHE3AE+|o(3s#a zOXAdoY3yi~kBuE+%x@xNV+Y;E!6J;^+wcf+?b!VZTAT@<3TfKV%PRXNA@p#OJobV)HQgPy7J^lJU9K{By9@nUM$GX+f+EnVCZc?w&yqe-rr~ zywP@A%mV^TmCg}&M68yij^vKw>Ny%2{)6&6n1minM7-Od!A5nehhQS+NO26>4HC3M z3EB_i&~mOqyD<(;S6u*T>g%Aj02(hrn-HP%mt6?SlU0qi1}#y~|Y8CwG5~kN1m`J$*QlCGO;R zC4)P&AgqGkOxXW5PUOrp|19<7Z^8=9Rrr7jb3aS~9mykpb{6acUy|lN6W2w$s}j&U z;$%G%IpP8h)v>3l8E2E2#XOxtRyupdDxFA@5-6pFuUaTZAtYS+T9rcL@D_$Z}H0I1)xkpNa{ZJMta&UoLlATL(+isc3YAtH>B7xs+GABE# zT22Vn4kOfK$;bEl$WrtwJG0dHsHK4A!RNIq?6t6u7W+s;{Nc9q7>!dcOTk}~?_S!H z;;g|q^+SSisrB7-z3?Gca6c;e^JkRVuc4@K%oU>tXA2Mb2zv{F zy*%uYndcE7SuRPvf!U1U=IUk}CBL7H4xw09bo;K-zja9fpr*jR%;?g@v zZ$0r`Rw>t9vhx~bh7?z=Wsk)@cn54Q|LBX=0}%xv6Qp{`LaZ2N=hJ#w5wf7{4Cx#n z_5T!QQ)&sI(r;yGtn5M^&XCvvCZKF;TVr1iU{RDp_zQ`SMVj~n_G|L&J`SmeVM~l1 z7<2l5oG@{Yn8rNo&@%F}pH&j|^AXw+?hYF8P6Usc%X|KCIxKUUafM|())5o*#o2R$ zcmO;e6ZkK(PI`JNM7E4!|M^ixdn)D@WNs48zCTEw)B;|n7sRqrc{`8N{w}@wJ!~k5 z#`Olt{xIsF6UvZ&4~EjE-)DoVCafy?0{JDwSHoV}H0D0(O>-*tLVFYTi9^|+Yd%j; za5|OD{bw&TrFQIv7W_NV6EA_xfczXd46dq__62+iR-kF2)s+szxb`_X6)fNn;k-*$ zQ-+Yk&bm4SE0ReX-<Hyx=s83z6C(e3E>ET6nn z5N{cg!*4Sy`pPo_^AV%%o{sdO|L|z46bbP?*JPh!Z=R1vw9qG;mgvbqZZ?$XOP7B2 zK8=sQ%9g%*epH6_Z@g~;q-bPiK>a&E*1rSa^!?G7+|}cHt}+vm(5XMicZ|n#tUsB@ z;+u$GlXWeIG?IQ#ASOaem++MHDXws#2NKXZT?o*#%cXH-2whU&DxG>wzs81seQp$7 z81&iZKysdpHC)rP-wW8{J-co6iFnVhMlPEb{x9P_+i*2cBj8Za-fE;?b+)C^e}R0= zeBG+Ri4f<@scP`X(z=#8VC7?7*QQlFvAdjb3|}m5JApf=tHYtiYMALbB-vQe8pf%> z+i@Op)v!!pLmIHbtaZ4OopLpU#e={u`^!i3@a=vVceBa0LcQ4W5hS#))ycbF7CJ05 z2Nh1H*QsULUza%qF*T5!e?9id0%O>t!f82ANWhHQW0^1n>8Jj_mgKx_@vA7>Yl^iu zTfBs)7`6pQnq8lxSBJp+{~C6N^4$sWs-tucYic!QE8KK34KU7Y;29(TJXZ8P*BM8) z_#xu0{1bb##beR2^4%lIqv56U+36)0sRlz*4Ss%I4Gvzd!7r!=fPA0Bg53A1Z*~k> zXSXSwkEt(fetfY9vLBgq8B;oST7~nxCK1HKaWD5a-~iV8w|Pgveb_Y(Y7m~ z8h+zo`fRZ%dOenAi^i)EW{fcKZ6QO1?e?sTOn+1=FXOuMQm*C}q~5#Pp}%;2Tfauh z!>Dnw)KWUD-GnxN5xE|7vc-#$v5~tRkfYo@Vb3+K{5Wzg*0}K$!Xo7R2x2F6PBO;@=-2D*Iui zAdccIbRKaA+A&cc8_SHh{ zz@V2wC1d{|q5pTl`+-*a#vA8cE*hB&Zk=@Q0sm|qJdXmx^rWFjEa1!!!Aq-=b54~w z*dL7ekFx0@z#kproHw$W>@xOOSopS2oe$n0<97+--=V9G+I2A4B66K%<)Coxv5Y{M zS3h46eW59Kxl`8uqGdMDa7Un{E}FEmeU=%Xo)+RT^X}~GE=vLAP6jV;7`0zwCxpQb z$?!`i8Z%@sU>92|*%!JXsTJ%mwW!5SL26yL_+He&lqlglAv!U2tA(2t<=DOVmlpN@i$QV5D_)L;JpsC)DHrpkPO z{5jc|E@`@Ol9V=0DBS>C3J6psv`EG}t5EeU9n!zSg< zg%(B(;#{{8#c>9`Gm{h@yKyH_Br58}Wu|-cdp{>d(0hO1*Z1G=>qW_V&hqT*=kxx& zKcn=#`YkL!pc{>S2AK`cp;pOMX6M2ka&ks~%GsRcgSVIDU@v&#$KUFKCFUm&Uk@Ex zg_GGsEg=trdyy&qGP1zRlo)K2Z*AD|0V%bmat%+UAfNv6h8>^P&^-Q~Y_ach5YPJt zBB*X+%7}*)8A9NrMxRufzjmTz&GC5AnSUF&y`~1$ z?FGooC(sd?gKBR)r^kY|7UHA*zd5GJ`gd3WkfMXZ4HNga#@>Z&$R8|q7GxGfLcT4K zpFm_RCnv2D=K6n+Nd5gtM_?rY@)yUJYc~VZ933k@{Rb2hSr1 z@Dm4##2Z1$^EioJ4<7=a=U{73Ja@vo+-~&#BrK`Wtwg znMuO%dT0jcdTe0&_-|mPOP?MXf6;ZpNzjL+Bh;>8M!Afb8mWgjQdANggNz|&HOaDU z1-D(6X+MsS&8fil6=IAH4;%y99(I?b@%s!ccBX~ivKI$CWHUZ0lIMR!pROK%3%$QV zuK5`DWXxnRwNjfyXwZVR_U+??m_hy))Z@%b!|#sk%1OX$|MP?f1J+aH3F4jif^XSB zLVJ%5RE~5;XuCThU-=$+TsBJUf%aR9`KR?D>XPsqg@1DD<4nGjSW8IZGMp90z;I+; zw8b)|iq^3N5#yri5sg(em9I zqcfn?59Hp%M*F)#X7-zrc|_({&3m0)zes&X{qA3Bo1z?aj1Iy-Iz82ui(|xNPw1xj zo3JxP)GLp`XJ9lZLA05G?gyGZ68&zJ@^Sng7|g-9n3?*rjgTi*d&aXN=Sg0s#)z;jOJOSFEYC$(4^fHs|? za6Wl_(~eHLJE_IKw)+Ek#{Aa#C!9^+1@o;uXm`FO&dRUD_Kqp}B67sF2p+cBu2}`@ zuF`^{PBZ+m7E}NAMN9gQHct(g6%2u6J0}<`Dhqz$oK|s7U(!yb<19EA8ZR>Sed(08)BgPTK_-umH>r?q zdL(QA!tb1n_lV0v*p&uYJ(BBW!FJaXkpuFHaZxr}cOkO1DBRZ>8HdlZX)V2x!j_}W zyBvA4JWjJ*FUzxSa9B9ia#^Xx)@kb1t>CKEe>dD<%S*U{I}~^?@(WCn6z85j7*{ddnkJaS;*kvcXij7Xk3GoYO z>K#Cdg=N@*pJFwC(!3|z!^~`O)b04p>1(oLol})IC&@hJSsweBT@8)}7NKQ9iE??0 z?E_-P_(>rRPq5KhBaG#X zMy#`Rg)V~!g9Bg#mV$Q^oS30)&V%@shMHV$F26k*WW*R>9DF0f6u*sp(seKjPa90$ z)5j%P(PiR_juG!^PI|_kd^SE$%)Eup6GcDF6Q_p5HL!L8CigNqjorz7*zr_4nSFG% zf8MSYR|SdB5Um)L_!)7{DIcS)%gp{LvVKQ)IUPkIBHy{xF5M~3+2J_L_9C7;vzWqc z?0dc81n-wU`V!GM|9t{+F3VFp|mGiONEpc&9d#c#KOXMPn1Z`b2oYM!HU3Q`WqVXM}Av zvcr?2_YCXHZ^AiQU(VzxJSpX}T}nt=w4MY{tTfS6=8_#w@;u_IvL|~+oZ#T-=wwqH zw}a=Ytd4lpo=ISNq!NeNR;=sjmml{K-Gg03mwt}Q_~|@9n>=}(?#kkO+7nqf|6WjPGv+2bQ@g@r0omDXK&%z zH+XZd7~AKV(31E+TbnYV2GK00CU$*<-+NZ ztEAzNVmYp0Bd_ceui$E~;AyB_Ie9K2N%*^B+j4^{ZkIM6ztqlUA^z<6E4jFQT?k*w4S1Tn~G)cP2jWohNvW#`jg%WtUI;;itDsfp`Vh#hr}{)`$Lb3w5gBw z_&u9=kLK^{y*c7Ny05!>Z<=_IVuY^VvxxU7X6EWWR=lVF(Y++`9<{Z*`kqX@NAq~~ z-Y|6TryR8YuHK7^_h>n&c8J3+o%&N@$v}j2Qmr~Y1A(a)SQYIp`Pe~GF74!?y&k>* z!tXnMq^@ z)8uR>e_DBkt6(MGq$gJy-o4p54VJQWe*8u}#r_B8E@sLGJGG0VR?8H-f7}jV!n3}C zy#^qT(0vUJ{298hX~DRz;19s5=3!188Q22UzL{i1-^1Ky!JW~8e-1Uky9Oz`0h|Wg z@pNJRDQ6qmftmE(mAi4)I?XckcGwHf-VgiaNzu8nXbmlyYJ8(84vk0@`osn))F;YDzjM&Uu~NoZTacTsdlkQCe&9EAlBt+jxN;+zq?+qsSW-YM~v zItlnrDf%s&a)u?&EnVdY!llN|?Sk=2~Xr4a1pN-cvHzZ_d9zUytBLvUkGoI-$6RYW@oJY+wJf*Yaa^Tc{|P}sMjH| zfYa3Pj19gOWNpqMypj3v{Oic(llMCQ%^_>n!nV`V#S_wBVFU6v%%+#orpeG1Q=68Nfs12` ztXuHz=m0yaI7V&4>2=jugQL(TxaN^gV_rO;^4gN8mMdI;Yr#2hC8eZW9kpaX;aB=PNk z4$InE@hXZdgLrj$nCc1R$OFx>PgYVcsL=uK82$fkSPAlAtu5jkT!qABY~VXwk|U?t z4*s(16!>jaNbeq`2agy>XusTsGvXganHFtxSj2>~;Q?r9Ksik9@be+xiw)c_%D&pc zZUB}FaeRZVDvxO;FEGM>dn#-(;(6UaJd?!p>c>?)ue%{HpxDn`vF2Y#%?DRfIgTQf zZ{)xva5?~A1K0ONXgW8>h9bAaCr9+;tGB*zyx5r$wU3s9m*GixT+(<>!?y(W-e<)O ztN~M2iL-5;20rCFox1u{%A}8o6}wkF`vx)`*4YMjzc1m%gcJ?on}0_1^={=?ANQ{V zfs&KMGZH!)wh~=wf~VLjdDMvg(P!r?z;*HId4-wy^^fXo3LK*S;RDW8o21oTG&j`N z@+laDtS#$X7*DN(@loxrA<&R1K*w9oRcApXjXk`i>{rI;?32zCA;DMWf{jR-5bzt< zn22zp$>d_7eWKxmP3s-lxcl#FvNlnD^)JKOE@qze1*I#Szt8b@vyzt-cSp`DDnC|X zR(^X#XT4P2)^aj{G)-46O5~VZ^gw4HFpD~wXBnT$)8C@ZFF4Lo_;DcTOnO>C(D0$PdfI|4RiDLEdYN9N@y~zT!*38Uw&sp&* z4O$<@FHjz~9%2RCFwtXYEA`0087YO-)(q6Fi0r~hO&_6clpI_SFKY=wjZf`VKY9k< ze9qUA0$K1y=XS`uW}QD+GYP#|Auuhy%5%^`!et1AhB$=d^-$FJ;KTU0VJk_H49&$Ma9?e-`E@;aP>>+N44ms4X6|SBi308K7x8=LyRN zQ$1y1c~-o_4*w(IC{Qmw>wv`Y(|R$I1Ru47x^qk}2((`ZA4N?`{0&?c{#LE?`0_ z0*+ES>Ya6t<{j$54vd|3H_Q99KE1%q{E*dpK8~n;w-K%HuT^h4)?!Xnk#!E){&!X+ z`-;KaUu97Hn3BIos!YSQ3_eDr~gsjf&26A0NP=5G77ZWo$ z74be~FqlhNB0mxvC;Y)AM_WSy6VAi3q;j>A&o_Hq=J4qaL*(2iSn>1kP)3eYH=2k&U*O~fGGL`inc5&z3$+757O9{+3}Q9Idr?L-edt~XGxso0 zca(WUlHW3OKjZ0ISB&rs>_0yXnw?UVEb(J2nN_Ozv*L6+JX^pkdPNOvq`QM`^qJwm zMYf^lm>~7|N%CkK{gv>$+Lc{o>YC~5g;#U`Q=42pPX%1Yr@wVoKHYACulY)NN3ZCM z43SwS>%gQ>(@Vf^{CJ4D{_Q|tq#cwo)FXY7tL>=fT<`02`h_P=#*6Jw`rfb&DYv(F8FhdO=-UhIi*ip_}Lh5DZnEO0VH!qE?a88?$N zxa-AEEd$cKBJ2VstzO)jF;a+k=!_<9W$|q42$g%Apg&FSEP|dT2m79#PpxwahR{ zr7Zo$=!L|z-QpDMfp~;UDWo-|cPqv-&;u;3Em|JbK$r*$ufh2t;%K7h9ZT0%i5QdI z+k{`K0DC#qiPEDKajCE}U&MH{j}mVx^oJRgdu{4%x5$X1Dc_kMeFy$G4>bK!ygnN% zax!znO(v(@7tf&v@im1rqGXV+hk{G*im$5@_%FEW76p7XFv71gt6*CkGv+%N1k$4~ z$DXp^*h^zRikPJVi7)JwVGX`{Nbw_wH&Dw(U zf6D>}_$AgkC$Oz<9vSE1s}g$TM_kOzvqp)}6!5|JYIfEaeRO{Yyc*hQ_3&i)mD0iZ z9GWHQmDWVCR{9mCy_oqmz#IG?wkwfy61V;ql9vzvyIGGi)-2oa(UIU)^F{iY%&L2q11Zw zGRu^C>`CVW_G7_Wuos(NZfTl}Uz77-6MW9L+|_iU>9)u$XwIq7(szvR z0Lw13u<63;o!;Bul!4uj47*@eD6?GdqcwK5MQBb8z~)lC?&%1=Z@Cnim?uAmECOgL zvvVn#RXi!We9#R4F0;WaIVtKGY`5az@eHMN^#nocPCFwG(M(_@N z>m@q=Y5C~M-sZ#!591sB2Y8?EZs^XPTF>ZCQqHpRf$`YjfFJUK^yu#KA)KOGfl;EM~QCqPjLKn9`_LK536^ zr`$c6By?oCtXq`evrXxiV8;kg48fC-lE(&mV~K)<`W=7%J*)|GzsxrmzLTk}I(jl2 z-e{BHLyAhnlRKzQkFFg^zeeZ@NZm}d#LQNDQV~-8uLSyyslXo{3tTp?!0$z@KfCy^ z*pGQ?Y4Qr@<`?Xe?z#oB1we*-TkW!L38|YOo9_-VZka!5lmsX?Pww6ceFe3f*`Q-) zSpyVrM6J{+aWa>9q606+Ds$e$_tAkpu~PvVBu(M-GOVoV$JkN+1^XU&jOhL#3~!>L zxmf4^3bfpw7AZv;aYd$6si)W!q4N5bJbm^Kyjs1A`)!8!{pkiTMxqR8@{H&SJX^_~ zO1;^@c=1K?IiBE)!=qB%orQQ(pd-oTcfvZlNK8i%(~-o}nTW6Q`Yth@XYkdJ(lK34 zXR8?F)pXW~={$hcKZr>3XNKmI%3_*w1LA)ru&*VaLfb@14jEW6h1Fs#nL7nmtixG|#0IDaF&tM{F^S@CQX#^GiS-Y_n$pothC1V?{!1a+nJzzKFN%M0cM;cp{K-qOQUG@ECioR5!TpzzihoawLfB_a5$2e(e#rark(w_fyB;;3L`S)D(xJ7vKzUIm!cp1&MAUdY@-%f?NU@5 z&Fe)LHbdldAOyJ(t^4XrSL*&(6SW}oUt16G(!zr$+#AndWpTCGOV%OAAE$G*wpNTt z_c=Il)<$m?bMurv;T+B9VuWa|D1iy1bwLbW{0yZ24KR#2NnFB26`XX5*?R-IQnDE% zmGIFLmks8RJY}CM*1T2B=aq6^X)QXcz$Gr${k3(rQmlL04*P$oTZx$aUqPq;NklpY zV>meZQhfA&^66{Xt8YJkk7NC|l=h59eY?JKGSPLI8kKHlMrk+2D1b8^S~3k`i0W{9 zRF2s+4>MWTh?1m73r1z&hh$ph9(&7Ddxc$fSRYVhZSDu(#a!nU*rCB5uO7M{>?Yt# z9#S3D?eo-*knFy>zG}Ow9h|}5!;2}Ng>t{E-08@H+@o-3;5V&9?N<1c2)wTrEN{_t0gOAvd24)7)GDt2WJzaw0c0FZ8WF$aE#q^YS7aV-E%BVk2Bc$ZAP!+~FOc05*i>uU8PAjTDgnqR zqbGgGwMQwMD~U{kvJJeFRtwPblwGWiC(&J_QtbNg!rm5Ib598=!+ipO+y;EB zJIRVG$!~$+vOXRwwLI3pi7Bn+V`ZtF^+6rD3Z&WKoi%HUm@Z~naP`K;<~Javw`%g0 zT}x|inibZsng zKEm&D$iP&C5#=_uyumAQ&0B~0Dw)p?Y<U9ogW`$Aa!^x^dZ7iP5v~F|(0gbds zG&*K+mAM{0>srM=%)jQUU|;8lAtM~&b?s809zCEP=aM&r8bN=A0k1wiHz|eo zy6n1Al<#;X=_L!w3O@Dd^LX!YP-=d|HGg9Nxsp@ijP=3@w27^{!%`kQ#2k))!?lec zah>MVqszxAT2ku)n`(7}M}liP{-?fg&Kec4&ZS6LIri7mb24v6biwe$kt=zsL0ZM| zZ;;?)fq2!z+G3SaCZJs44Pl~lU{9!qM39NvM(LN9VR}7()EWV57hWFKC<`rx?y#vY z(UZ8JmL#F0swJVFDP7TY79;O$6C^e8BM@ite=Smkz9WT)Yak&SC1okZJa26Q(|uN5 zMdE!&N{Z*63aG&qS5w4vo6C9w3-L$H@*jHNDMu;d*m%+`_SzLAF)PV!dq`gXX^pi; zUM@G+*0j~6N3V~4`j8p?9-k@XI*PNQcFIcB#AH`;M^>Y*BO6Tr@|_AdY+W(4NnT){ zpUgj5rv#gc9R2O^V!DTko_rY?NA*sX$Mfq9GG`C$bGlv;Jp+-@@vwM0fkZLYNoS?Z z!wOG&^fl4S=wP^Xs|Gke26ogM&!(*&Xleanpe(LAQ7HVXyieBZb2e48M>-9O*b(Vn z8eZm?n03_|xtrFeyIIT0YP-Q5SjI!Y7Tg{t7NwiY@svL5LrNvAWH)bB_=qP-m;|0( zrEr>+d)Q+V%4p?>L<<}Skeu~Ai~K76URFb`c!IBlDKcN_ll$*5ZrVyPud&fZgFnt0 zEBX_Icn7lMeE!6*Gd!D}37!*9tw-xm5P+-bN+k*Y1drBzVymE>6f_@2PmX2}pJ=x7 zuxWUtiq5krxiqI1Ut2ew*xIYo+Ki-j3$)%`?Ix@Ee!*~QOB>IMJIqu_6?Hhhsl>Bq zvL}A-doWyrHjudATxLDSxM@wLVH6U#$_JmW(68nXQr5gmoOh^~2ux_b_eNfHChk=k z-P+pO&jT{j3{@mb5^kIk!AePBl3wPYT+gY{&W7rgEKr18${mVRdO|JzqPGyhWZ>d3hp`Ha}ZOy?Nxu67J0?qru zpuBY+MhNxyR~`9jjZcbhkNvd9mqg&xr9IV^?lZhl#isIz%Wv=rMo3M&e;t-sPHauZ zEY#pwHj_#fO_%}9@cZhkW{-Z5T*0n$Rp=_%66X|`D)*MPpC>Ohz^gN>4`dy&gRw^K zPvF6?KE#Nz7!gbPL@XsvDbKdAa3wS^Z8jO;`_89#Eq!DuyvmvIEyru%Wn1kxcR*eQ ze7W4O@a<>gwS+lO?02t20?8hojGaG2OfD-Q?`2YWz&cUAX)E4B51RzO>z|f4ZVhEc z4>OB7Nc2^qj#uz<7%8j$3e+iN0X^fF|astRB(Ro*k~Je;b% zi{-@7VQM!XNrpb_gK@^P8TC{bGz!+DMEHJ}h77_aqVxPB!oXkA%V7yD(_Vrvq1zDt zdB}{`Sr#z}I=^647TH6|Le?=KOROKPuDla7R?%=MzmeK|DTx!mC&m^q3)sWB`t6vE ze1_llu_+8NB@e@|&R9yT6TdHxt+v!TQiNu9GBcf3yS`FoTl1kYWNmx72FJy~A(fn~ zVG@?d0@G|VE~Xlk+%4alsN@7Tn|~va=8@z{A}5-MBh>ztj6y4id8-w8yzIeP>~`4U zEXonsdWQ)sODZq9Zdu6WH~JLbwCKDst)Ophvs=X)G6%KbXPn%Xfd7r%bcFe;vko&@ z=Y(oz9_V7hK!M)jYhj!CM86vNR%`od^pK{(dZh4OGmZVkR-~n<0&X`$V2@E2vPww6 zVTs2ZF+-|-@GUzg+P{R3Tne-lVT9=YAFmk&r1gr$`h8=))1>@UF|mOlNTn(N^3W@ZEAb)?5~PuQahW+XLI;Hdy1wB?FkfPNKhtbZ`CF z>i2%elnzD+m>#8>DjCCh17O;eDVIyR9Glgqn_Oi)rCZ6_)Hc>^lP0hnO`Bo~|6hNf z;=73D$>Y*vg?y7!38ZMYg*3uLrY$8~QjpelN^vR)_Ugm)oTpT0Buf+T=MoI>1lDoT zTUb^BnH3vY9m{u7iL$a#ADZV(CG;(2$r;_P9OG}}o;NU-i@I5coGpHv#%5et$VVco z!t{_7`&>ni(N;lPjPsm_bo8q;tjE?&zwU}n3AP< zM?PO5XN`=1oo<(518bX=)0k|5eO4hjP=tBTOapJF@7~JwlHb6dzqGL@qMa`-{G|IZ z+L)r}vn|rbCyy(E-hB#MLpijRQfIHEDsc^W4=c^Rhnr(K-bhQOg?|N!lQGN6wsT%v zr=%iLIkQuDC-+~vhYT~<=xpplsu{J}PX!{8gd&v7GPyj(Mm!4ZQtZg2C>f1aU|Vd0 zZVmU4p>&PWrdinF2(JEXB(aDM=`8xCPDfGnHJ~wNR*TII)qa_CgZLFRi1;Si>ajg! zC|N^mquy~L5;G?iy&NiYKETHFTeGGevOaQWdn}wneTk^R82aRKlZ0EZ!4>f0l5Oh~ ztbeSg-gN&lur{X2RRr#}KgfM$_+6k8Htgxqlu>5RtJo256hoTPN-NXaWui}HxZY=i zEELz{BbupFXuOH{SEdH8kt=}(#XknF2UfzCvX+y=ns*HsUf*c=$H4TMEyY}W;8E~i z4&{P}f7a~$M)gglw&UP*&fiGye=sDm6x%qG-$;3$^EV!RRA#09&C2 z^3XxofjaB@r1A=Rr$!1q=LJ{WI#WUggPP!KxAE5V&4P4^iss^b;NaUHw6+|mZEK>f z=H+@(CoyRlKJA*1PbSz&W1WMgOo%tz$Tnb2nR(3o+5Ch2%lx;Z+$-5j^8UEC(Y}%+ zdS)&kDCVDVBzw=8BvWK-S8+9Vy=f&^iDzoP9?vBul9_y=v}QPQpBj9&(84yktq+8{@4g9pcLDTMkYB`dgl zQ(!xe{Z;`<-m{9!b4mAbTs^nJcu0SPLGGCX+cQWAcdd4%LVoCH-TH%UDwug>6JOVJ ztBlS1hgpS33y)Z-MCry!gjHY;{Ygh4ZFd+uE4L0DR0d$5U*RZ1)wA?q|aXGjGbdqna=K^Q3!? zUrp)-i_d-6k?vh#>*SlTX7O`-CUqLmPLg>37-)k`pzSe*hibrN*yUD1w~P1463Fol zjkWjGac5YG<$hKT?c&FyGMwL}e$C+&_<~u*NrY8g?LBAM``OsQA0c6r!LuJwFaA|r z19u0v{vPdN0cJn<<9qB`V6$(6uTS#Pe}|=l5i#G%K?lr!#ooV0wo_)#sa^(eZg+4R zazFdw>W2)+SIfmb#lLwk9Ls_BW1noV!vCRh4Y!HoxC-Ej<$_+nnX59G^nWp(3utYd zxeStI`!y%vPG_L)K}jL$eiGKq*+ep(bZ-l@gd$d23lh3%4OLXja@Vb8W-_@g(DIPn zt(LP!X9TuJxpzleuS@KX*OmgMf`?`c_PxEtvegR9GUIw^dSiJK&)UdT(g7(*?&O=` z6SFN-?&*FGJPdPI!4BElLiMU|jjB7S1kuzCZvvh#p7XP9NO@JY9?!9F8`a?H7tcwA zVqj<6GU?ZPu;9|KV*~p~wRjq@H}2zj3iOR)Lf-(_9+(#-!WYlQzm3NVp7~Muvi#xh zIWfjHh623*&FGyG)I(P?kP5_tvsX7AZ}bEigDzi!(=5=`9_n+9U{zA%TuRaW#*ntd z;3C&qLN7Kk)-{os6>HyvU(sLB7m-+@1lWPS+dq$}@m7PwyB$1UBl67i5yr3Sh!vg> zYLBRaH(^~dV1k&;o=6NFt^eNC9hpz^GeM;?a-iv~*q>EqYxSqiXN(&BK7G8?$XkC| zf1th!+$hFSI_a;^YgohG#+7q94O>mixVK@v{T4RL(%mLj26TZ*5BnJFr_~I2hO?oU zpqhiWhEgz?#>m?oq`aHD<{OBAh?CiA?nZ=B;Vron)HrnLw`9aB4i9gSY-t0fdmfG_| z_mYPV)Su~1BXmre8he$pk4LQsTY8D#9tie7%9u&fOE~ce&GnA9r>W-1?dpHJEwkro zXs4R3lY5?CRC?D2Gs)T*8_+pWjH#kT4ulpKn&;ek> zDFSzSJ@ix4U@h|~171xt-u~D40g+`qJ<1J*C$4T9GDD7326PDOk{Db`~y$Ce)T~7WWtuEoZH1a8;>SF|{tKP0Q8t*2Zm| zk+W=MtodQe2SanYJT`ghH}JJY7OX{t?A^l>+_0wr<07-keNQ*9s5 zhb(dm@o=Nl_>DYA&)vCv&o@{s?HfF;bwQxq4SUcd&rZW)TdEQn( zKCox({yL_W?&j8UOAQOTGdfubvCKtDo`C%JGvrRy`rj(pCkHljStQk`>X=FB(_i3e zH;^v-OdIVR!T$bH#7O8KkaQmmd&?DID1D(^XL(_%>afyN7#$ji4O(-mU!{@m-*4CV z6+cGPhi^&DAMtDLTxtG_uKVj~PW~~FI;@&ewuC87*?9X#aH`Jik0|r#u6H@74ScS9 ziDNt)SjDl;^^8}Jwf^}ba5zEx<&Km-3Vm{Dv(x8HfMtlx4~}q~$^w)O)?1m-XtQN97)v+^>M9}-VYq*iTi_i^( zd0{A$Ga0%%oHc>Q$DAbb(d!S!BzsOptc~j&Wec+{T3g9uy@3>4QUM8GUM`kYA%XrHN?s3m%RJ!a693v*o{Q9 za^s-0X|;c&%zw;yFMNcdhW4U{;GbGrD)qP6FZSINAyf*0J$Y2zlWQNPykFp9FPafr z;!KOSjMZTbeltw+YcK}uoOG=H3=-W{p$2HV)gfJRdi2&o=X%;_#v?k+I&Z+6eSN*; z$eGn4oK#gsL!o@Jhf1?0;7u(;uL5teSstcL80Ahc=98~ObSK>46r3IFzKNX9rfsz| zJU;OKNJG66a}-iBr$WuXb8wpnQF=9RwDZ;!~3d>Vj4xQV6H%fA|rxL6)uRvZe1ImfseRj0XS&ubb(y_A9*Jx_w zRlTY`j=LSHjb~IRxH8z*EU-?wjkTq^Y)qL=%BAupwkr7Sz9(^E|r8%piaIIYL}!%ZLngcJU3qlt+=NMQp!UEjYBD+W^d+o+uU zWg`Dz`T+v(sMDOK3@W@ph_t364h`Zyu=pY9sZbZ_j|sukNSQ(TfeS{iWMZ!VfDu;< z1cdIS9I@t&Qrz-*BrPWmm=`nAy+!MX+QO^wR5uzMxQvyGz9BD{LTkX`ZyWwjBZhcg z{(BOmyI0TX9!_R-_u-lW3S%Mu9>?E1_=Equ<_9_jnPb`|~VDcgHP^?&TcZpUUV4;B&6h ze98pvSYUp| z{N#8xSq;ocHCW0LcBj8Ib6Y z57@@5g{m!rQb=ywh%2-a34IBzMSo4TaB!1pOWT7D4loftlXheexJ$4L48#%4>b+XJ zXMffU=4I?Iq2WO2xpH1AP=>N(Pi2-2Y&TT~A)o_hNC>omgT2~!i!0+ug~<(;m_xY3 z%uL{IhALAU_+$i}6qn!~XifS~gsHa?0?*`V?Y?8-ca~)ymPXqKNlxZr_^}#?e$e{n zva}->-1XwF1$Vo~%Sav2XZqF?DC_g#QZWRSNvJjKw8ly)-lQ!IymI%Ua2c=-rQl{E zo&+!=X?z@jh+3d}R1&4=2U>e^oXgj+)vwIi z2A)N^=j(wyXda#rwbj3Z|8E5t^vg(PsR=wmR1>r}j5avy4=XXAR*qC!oSX~@1D4fy zfRv6;!QER%R$C}iKzhx6749z_sTS{F`+l(~FG!1)j;yrYj4!@QU1P{ULgP}AHU7zb zYV-XkP;_(W(46 zd`Icw+u@hv8fX9|K@F~J#%T?28>h9;kN*PeN*o{bvq;@dv725EtN;%g3GNDG$NpUY zu@13csJsn)8s)w~iQ+l`40sHRAxVpN4O8qv0n9e9ls2DVs0W!?5A@9x?_}IPG)!wW|Hze8 z;&r{ouR=<1PoxyDpTEPFXg_$r7KCVu_roqd{}>h_3oQ%P-Ke~m5#OU?zG<%GC35~y zqWe(JHU2B<0VC_O=vpytBK^K$4!SYSR)UG(0&;GK{b6^EqLQjvZe z`Yew(FcO3RINz4V6y4eN$a(Ccw-TJ@B}LftPPmq5oL*uH2!pDQ3&@=I&; zGJ3)CALZa4?*jfocYOOfdB`wPQkJdUo(OQ##6#I>%G~RV0 zpOzP~7n6AWGT^d+Y7WpE>>Z*lf3@8Y^R$NthvKz&rB>s$M=eON_Jt(mooeP%FVK?G zUWRzDXUgV^@xJtvc=LHW&JO*r@xJ?`crT0qQ4=zqr(<6~M*Dg4813f?W2xx*{iAd& zgh#KAg`QD5Us4&+7T}Sl0QJ=1$oe&V)CyEd0gxTBfuT{U-|AWeM7@=7a~TiARsb5} zTA&PS`F{LwA^m8Xt;j_>c1OMNQk9SNV7r?`e;)wn-VEr*X#d|e0yG`C?&$sZM&l`{ zkiwt-uTr=bDS&L_60yEJk%nX<4LguGSJGGyJh3EtAJWiWqBGQYm+0K3^zJpLMP)<( zbLP3yEB-aO8gtlB=c>ztSH|ISc8!6KHxi&D@$Z8x|9?l~Fm^asXDZ_ea?xcz{~nz$ zyBi-ByrnO)WXtOWI|8xc3hx<%X6=nn*_%v<`{weZ1 zyT5ZTp*f^;=pMArY^0KZ?CP9DdwdbN;I8DIjx4K~lPlxu%KXa?E<(#)OwBZ`@zb$( z6#en~AC>VJ!?gAvxKxi;IN5zo8$7qhf3*!LgDUXA_?rFE*K<+-bgbShqSdB~{mObt z%=`6ok@wW-C*T01eJB4I3$%jLn;QKKGzk>J_d{L-snPdv?@IaTOpzLWBUV5bao}^E z$o-c{yJv*<^Q=o(*1Dk~7HxA#tWOpGmlRDx{mMg$@QF<4(BIj=rzLtOANqK@XIbOt z@GCsWkZqV#n6lISM-f{4B>4TOWZLJ!Z$71KV+dBO(#$_AmdKN2UnTKL|4K65CMi^O zaZEmZ2K-CHa>X3{yvZ&m9WrE3eFdxSEHcYhEq^s>4!gh%#=>p|QP{d5Rk+!ZZGIAA zIg#5gN@9g_$Yma4=GuxmGj}es4IJO>MA#;`C7QYMf&Ur`VXqxOhx}P_t2{v_&HO6q z)uf9Pd5C|1Q9@%Fe2bNxN-`VY<1S7z+p?z|a+qza!Tm7D^gZrOwJn%3)z+uDm^9t= zCBnJjP06*rhg?t@7R^Opq{i{T<)P)8Jp4s*iOzy?k7vb#mN*)$* z+2$u48&YIqsW)=8F8+TF(AR2XsMK!?fJD4|PwJJ9={G@ibEJ z@NCQI;6IeNni|zR6&|)@a^vX0z&J%crbgR`$#p5AQfDtDawK$5cy!>4aaAk1t|TOZ z)RW36_uBR6Qm}hbSxRBAlWO}cL;`${EIhn=r`^497$<8ZGz|lNeUM!P*N!jt!4{91 z9gfsFRG1Z6r^Ma7ooP?u3j@Sm8u(+K8n~nXT+Gb*EYjw(xZ+j^8c)A#{lqn}T~?V# z=GOv&^UgVvYYcB$Lkcs33ZF_?#??9W8rErbU5RzQOXjOGPz(rhzgq|UA0qdu{l^zG zvo$~kobQWK#761gA`{>fU8sCtCp?GntzrY92d}J<@i$`ygx)I*qB=i%g6DLS7JGX4 zcGGsftTU;SOLEh=ZzL69M5*MG#ZdNCDvzuL7Fg--g`az%FJI80rhsAUTN;6UYs%@R z<(MN?eqW0W%9^FX6$&Jm@RwaK|VH{M8?S(2G5q<^aKnjBdbRNv*<8=|gZB_RwA>E6XL<6Yxj%C}8&|m_}f^Q_-gd+oKFfJ*HIc zc|TI>tjtUg$x1UR(~CoBQTnmB$TZf_>waDmRtnad+8Qt!&XEDNr<&CnAw>hhnT@eR zmhKc=to$Zi8^r5cK7ebZc-_W-i|by*dEVtk8D5Bmd3ZB-dnlpyp*;Hp#XjX^%JhMTT|^)`v;;I>#vqXkydFnOFKnf0A%55{5b z&Ha7qJu=~t*o#y`j0G+jc0@sFZt{ZC>DFNWG6rKoed&K62Wo+~A-QfE@_i##)OnfS z?ewg#M$e76>zAL(_K>N%@T6tuB9oT&M)J@8HnY0b-<}CG%HTF!nI$K|9#!qfEIeC@S@IGPehC6I z=PXkGQ-tJxA4wM~ubFd^_lY^To^)0*M>PM(*up(Zf4Vqd$^GeIVUEX3%di)-`Bzvc zXg$gI|G1vi;Nx1&bs9HdCf`6*?i(g*NxqAjDVZ{BEv+TfHMR6tmd@QN=V{MWqrNn> zzMv;iz&H7I-AW;S-)aI)hMn}Tk657Pg54KnOPKxRIm3KJTmCDcB5TRVY=KMRAFLc3 zczKMOg}oK#xNrM@`ffb7GDyI`j->A!n3(VWf_X%{TUG{?C}tw`qTWK(o*X?Fa-^w~ z!a1&d*Vw?5V`g3(mRb}-s$CaUKvPXUb;Jt)5h?!AJ7@H2uk94HXlxjV1Ax|bqqafEVO%h{naMgk# zp$+T^{YYhErkhRYx~qAZJduaWi9DG?^ectnp9mX5GzNvxgK!`6+!Z|U`V3_mW3_sEN`!?;$D9l-pT=m%QX=tqxI1m(UmL!u#8C<~QUX;;u0 zYGw9kI=Kk9;+b)_~` z;A17dzq~|pKaWfUlZ|A$9&=n$kj`*bmkMuzhsddPKD*LuZpIihhI4QEHj;ZwRO}I* ztlF*i4ORjH=mJ6-D-pF)p)0TUCq0PHW~8t9lGrN*6Y_p#Hj3xHhL~6b@~-yKcvzl6 z3%A)npNQvbOVZvLZ_9X$O2qhiz_nOF2hVJPWAJ$j&5>)}?c6TCMQ^ zS_}WLZSeov&yP}m3!;zeM=UOBi@LSbXyFgKY%S~H9iiW)Hkyn|?>hb<-_JAA$}v6k zY}p~+I@4Jt^Fu41f^jq{ltj-|K_5lrZh>_?FkLer(fIW6m?Lq2yG7}RV@3;c>-?hw zz2oyRGbIU>3s8bys1b6GQvPg>AWZC|l06dG7yvQ7?|9j`fRlB+0K^0TzpyD!10( z%mN+nZL&xD6h2A2p7Oc(5K96qFLpqNmgu)0UB4(1$l^}69elDEutUATYw)ec{rgDi zBlC$#X##TfyDd4uM@g(oXcE){{4v8%GXp6qWG6g!m3ceh|pD`A2vhQ$G>ycK3>{vZ7O|?+UoW{Fg8#)dSXit*BQt_e_RpV zv_%MXsw%lj?wQT;{Wa^Jxh1~0PIadUNq$LQDrfL0LNT0O^a`-sqKB@{q-b7gFu_O9 z#%G7oD{HK)}vUZ&OR5WeWah)3DXEus`EU9nb$~QU5nAOCTK!= za}WF3Oo|&ar~_jItHxD=$v{03uDp}hjmQQvJK6J_$o!nlcAUQ&EAPzgFg+L8LJH>v zGyL6}JGe=H`;ulh+rpOsgOHeF+u^8`XZYMn%Q)88tEgZze7#BKT&jnWU6V9|5r&Qg@f)k(CO29j;{aatnfikG;PDj14uT<@rohkz2*au4K4ka{XF1Sb3H z$@Yrl*!?8=kyD%)ll^YwiWL4Pm@HI6d#aZ}%IybRX<rwWIwmN#2$5Wk4(aw1?3)>%ji}_DH;!9T+Od zzVgaGHhOaJaoNr^V$Z3^8g79FGR?mgwmMVjoK8|a%nZ`So*$b*x?@wJB?#%yv&Se0 zNCD=kl&DvfQL4@tG-I|1$L(l;b5V8eq6AMT&bTO8An?j5vm{Rj-U;s#dF$wm%&r%f$Qp_H6|f!bUOvV7Cie2XmLGD+_sk|!R>#0q z_5hcwfxP8sOtIJgU1)oG*2eAS*)`kCu)@KW=AwY({0P z%qyGv)Y=+Wv+Fo)V(vFGC7PWwp9H>JiCNLwg14HD3fxhcRnZkM;S4$b4jg97~hKqalYAWdiJOT7Co&# zjA)8IO!TK=J#q)qf#x&?w(&Rff8ZHDoAU=s9jZF72%fL5{a5+dFoc3b>Wi55#G$;S_03k3nOa(H1e%YDXcPSyjp`7r;Akd zV-_<^l_Bj|B4)kMt2;v5jaC^t;wo~{6Z24qzfzmr zdwR9XE4`EMcNN{kwtpFzSubNGvv>XzUx3{R`wBAk`v~eF=h`}`5bFRwa!?B^hA+Fw z6gn;&_{;oTkp;jZyt#of+b$6E8?}si1;QNuZp0t8{{Q1~b*pA)qFVxn2b?8Be+!q1 zdf?8mln{8`)Di-Fc{RoZtObb#ef$ZWH-VZBy%WBiTxF=z!3)f>sgynSoFemI#u>bL z-J{6dXZS6zKb(+>ch99|UNkP^#p|B5Op_te&ydr+K578p8wu@!Y>AFHC3a2pSB3SP zqP*zdUPOEOaVoHm!aoN_Zm`J6-{cNyWtvG6eW$T! z{oVK@TTIH-k2Ub@VRFqlY&1!**D)C?TvetN(;;>tf0t=qd!la}#uM@}z8JlIWWYU| z65Tg8V+z>rfqC~F&D+4}+K3YKs6P7q zxB_;ul`RI?6uAv&aOzc3Th!>37^LsO8l{0%Nsm&fe7hW)uq^kHwcG9HUO!ubb1<;Q zrTTyYUwG`_^hqp_Y?*f~-d1H>;9ecAWyR7!TkFhVgNvRmF(Slq`MZe1d}H-ju>Cq> z@9n8|wEavA8}$Y{fBA&%m=}R`FzukWm)G2*{b>iqBtWVl_QO{(=QBCX4eND6%hld> zj>jFQds%`}&tkhc>~$Vd^s>YcDlUYVOTBqF6W+bESRP6 zewxw|NIT+gdE#c~9B{(h<=#%C26i0v4uw~|+e7dA*%m$tt6C>Ut`74TY~Wx=mlFLQ zblD{IuTL546#ZnI);}HIcMiduQUGZVhO>5b7>o!B+vk|RVlz!(igqXXrw8T$wZeF? zFX`)stQc(8yA(baHv0?58LJjMXw=R^fKQ~77$ZFXE@Vcbg8(jm6WGzF`%+&Awq*+rt- z@e)Gc_{CTW(YE3q_B9EuBLfXM2c|?H8c92mz3)6>k+I)_|H`>m;ECb*RR$YYXQ z{agklaxa4mRPOWeOItSM$`mLdEBLd#KH5Agfo%zF5OS)j&$2+=SQVbM3A=W^cydso zKi+*V9Q#HsEy|Hu~okt_2+{7gq@f{}su$LWmo+Ayul`D3&muZJBaMXJy` zC>eu{4%f66ipF&C-76VO!T+&QE&d-JO~C)q&wr}L3b2yty(Gsun6?m&?QVFXA>h}U zN#w#5NN}^Z3oW$9wVo=&g9eldt-&4!n-c1mu^>%6GnrTw8jq zX5yJPUVg{;cNkrCXJ96qu?Fg+pN!C2Js(-|rcC$$G4}R>O;z{*__;UFY15=>X>T4V zd1#@u1xs77P@EybN+~{2WGgMymZGMhTbynSf-`{5(1I%sXphF3jv7U zhH2}wE#Q#}P9&{X(ODK~dD!uGCFpz5OK9A{$LR;bg*Oo1m@$zsIbWS+vgIKW=;Hs~ z4W?_W?4z~TCabuIZJm6c@t@UP{0M%;(3kciYQSklOwT#)JezeEb}SB0At8Tn3HhR- z+~!x4siGdN<~?_0?3?#a;N7stI@kq1PR%#}iO=0(y<^^$z#H_xZl)lf+1a3Gt86Xm zG_}bh3^uH8*OuFK>WkW_?gxbAz{lbiHS#!WRrbVffZqX@?bfAhRx`6G!{uS? zJKby+A~c-2Rw)?l!Lobqq44Ysa&Ao+aZbGsJ^A>4wB06LUm4bDvGwEBk>3v$hf_&s z!*bi%^plA2I;pJVX!KNVnDL&}Y=OMi5LUCvB%a9>EVIQ6s%+1tZdUItHCnc(ina?8 z+x3<1c}Rf!;5EGR+=Cf(2lm(A%MI05+S*_%%u}J=u)6dJ5ydp#X5%%Tq$x&C-yJP> zkm(#!9R^=p+$i*))OL>FzYO;MGPTZmGC*+=Z*HH1quCC23axDkklyIMG>FMlY~C%rTgeldOgVP zNxRviB)q9tbIri~?5q(O4qLOj z*biGbF}x2F;Q;ytMUe}eS?PkR0Z`>y0h zUT3>8R)f0U!@0_Cn*U*IayM;J781$W{mcl-lfh?wxc^n4E{~44_Xg7GcSi`BX z4|)&A@IPVttdl*1;Q`z6^kU1?)<{=}P6i!G0*CR5`^eNV#v#Wo>t$wc(oNHffNUnl zjzG8hb@*Ag1m zWck2xjz+N>$O&6lI%i@0MlHuBN8XFmwqRzwL`zLh*_hU@bd4n$DCN(FD>%v>dRqH( zc#Ty8Z<2L7rsRK@v(RryKWev%&xvTfBUTjxAIZw40)Mqmj_XqR6Rfs+m(wVXt1)`q zdLJ|MweRF{&2}wtnUj9hhV}Y-KHahZmd}Sb@}c!Q+YNmB{F`gTqBc4$G;Tc_)PdH( z0`518PWnx&kSy9RpTc&EX!W~3C68;S*v}!-NCZotD)(9lS`KUEm}7BWttv1CUE})? zFa~g{WM+^ou!YfiP}CwX*DV9eW5}+ja~knXvWt9$d|#)SQ(pz4`3x~x(xOY__d^R} zl#(jFC@5G+Ic~i7p5c}u9)RZU0ERx3NhV7d_F*@mousz!2NzClh7>-l8TNSee4Hst z&iglFE*!^bdLTor6#}0zAw<#1r9mxNuf*pn?a7gvk=ll2L=mZuRW&eks_KR)n?t7f zuIy!W=1-2?J(8`_8}&uWku#%?y#IjP%kdy%7(f~kNx7SuvKtIG`F2}IE8^7#j`fkN zm2`e!id1<6A!7JCtX<0j;Xp%F25pUhy>v!4DS_rAIdTm8m&<6ki{a!*!{ESpoxy$R zk#-VzsLG&=O+xfyI{4NYNch`FDb_xED(b-8&fIo;U>Zh%sHX%jLK8_LA-f1hh`^{r zRBHPM^Ln|3VgQ*RC;rJB9^AM~cQyS>?z0V7bjvK4(=TyVmWMX{4soy05Oovt6rh1a zwSH@fGuh$+A}PFD7nC^8*S%C{s5L&C0<@Foz_H;n%pexQx3o628P z#7nV${}!>70+V^A8Gc%()fpkySOWf?5{E}capSzUX>xiEtmP1ZcynE($v7X60gM7uu*NBEiUtKn+v-@{+eWuQlU23P@dv=!T| z1go{c^XfFF=hfRNav=4&OpdGvMjYMEJ7bn)fzPE`m3$E#xQO*=He=n zY&6v}Cex!nM7FoggM9>;aP1pD+c0^oz|5SkOMEBYEd*)7vctzyb94)Jre`DdgvH|Ew4r0S3-MoVS{-i>uVqH zC+&~_xty5HwXAu{h6gw7-e7)ohjn6)-ta~lMJTA|xGA6B&%F32Yg(wXfyrX>E94-ot&k@vWJf#xg$RuB_P zCxTv8!w(t`VW*%kbmT^GH6x@qBu5SoOZaFay)ha5e+(iWO6t~>7Tf*qhw4f;jg81> zVqyd1uhBbf$&nqy#fYRzLUhr(2BvUb9b;DF{WE@D@{kGPJl22oq+kuk4yLx6u!SeM zSS{mkBj$<3bAmfs%OKk7RkOfB%tQ7R*HYIT_-+qJ&|6*@W{hZ$iF*SlIGK+1Ob#Sq z1v;!s^`sE4gEVt3iWbqf0HRKbLDGzXBb&kgEcY4w$b18pewUQ)S}o+pr`2>?X9q#P9bgV3=*iVVB2ad z*4p2@?+N>9E*X9{GA0?ZtGv!NbisxjHaf#Qn@RcU9l4 zdv&V_EerDl@wQok*TNgftE$w4ixvwqMLUZuO#Y(9!tC84;?=^_>m--BjrFFsQp9-J zQn2@D0`hGl?}99ueS1I+bonxk%qj3B<66DG%&rTZgpF9_-E2P@kZoIQ-^@wy&q*gmCnKw}*#Yf^zbgZ>EqF%IC&`TFkY_|Kt zWTyt@xdN*QyOS-t%&9!K45|?{2PU+oY~Kww%!f-8TQj#V$P&69E=_3NyP5v3(nwk} zokEAxzL8To38Qk@OO-zIYZacZ^0_vvfUmW3ekzgrghi>EC+zp3O&7y=NzKR|$HP-? zxB>I}8K^!H2KrQTTiVW5^DhRHckHw3f{);N)3%CSkKkzsH;dr={C&@XM}hC@(g`l< z*mH{B4}bSQS!*WHH|V|6Hd@NWqMOU9@=b6B!miAVWRF&vNqfN_?NC44R*Bw1cIH*& z;TJ73JFmiNe|kAHhvFaU0z>_)O7Dds_f0$5Y2X%-Rn5i*qwJje4KlVh|tB%_$TDVZNOnqgs)SAhn+h8EM+cgA{^#W*qMNDLb5Z1WQq{+ z=2IfJfgh0ij9u1=T>>xI3~Pk58#rP}faV8gP@J>;G38u*op7AcG$oQVKvCh@TMVDD z=#fVUsSodA@&$0?-8I6(r%Ny6er?V6J8(bz0$AQsc=P>o{(g#b^L9A#fYh|E%s?hb z;&JL1ETkSBupz>?0J7}b3_UQQHWOiyOe1I!ZX?F!HAX$H=?r~RfMU08Deb`7fzk&` z_m)lzQ2x26OKTzBkN~xdFwik>-z@Z+0>VN;i`V)od<+vi{F~i)lS%uMTz4VDO%>Sy zU67Y@N@h|^4D0tzgyt#h-uvBDrX~6SG;#r9!Hd?fLU{%!W~QGHVZYv7pFuwE(yY|K zLA9 z)0GNdOX>?F0go#E-Ev1l5akB5Nj|AB1-?lv9}-wRni9*KCGd-OFwmq3fb*Oc#M&^P zuh>U(UCgmr3-50Rf;d>7va0VVS!J*Y$Z?F^c2IfsrSZJ34AH#A+pp*K(kBVf?k7UG zEFKbKwKc|s=n;W||3H(sLJwpaV3eRX8QzaCYF>bM+YYRGL@iXocb|x#kP-(ld^TE{ z?pF7}vE@%>k-Kcu)cdVW*C+04;rNujx}EMin_8PK6xmb(r%k5*)O|Vn&X9DG#F8(} zw`Ey`w;C*Ql||>ISYR3hj|Dd7quwit94S|Umk2y736Qf`pj38A*pHyAC=q%d!rnGH z(lU57Ljp{C@yT?7norcmTrXG=gnB44$29WX}gff-w6tIt?xqdCc8ofIRlJ0YDXM=}Q}nu63T z@t0{5w#mG#uS_FHzrI|x#I`a+u*=D@#f24QGSm7hSn8gJrXXRLJ0rh}_G+D0*s9W! zY(;mrTgS1$OzJj7m*y+-U(qmyd&2Tv(nY9v?-PjDwS!fo5F|A4$H@K%w=Dxka;%3W{HZ?j(OhJ9rw z^*~%7mU@M)Qcmu*RGkgW{FkeGFi&+Jl6&$yK@mqSlg%>E3}Cnbon=!2{!;pbXE&-!dFy<-u_x zzE{>{cJN;FTjk)RQ9sv+@0O;8m`eIDy{*w5N)*1^(9 z@50}Z`Xth303YeC zA!4Mz%;1D(Si&I%XX5NNT&2I)1~kpI23SMz47o1}+VKR;RKRwEw4BW2%*gOf|4a1v zwKAXDgMWL}Een9Nh*&ec(-e3fk=%QNT43$yVVUr{x4BqYz_q;9q1~Exjy`GPpa!$Y zSMYttXbRF2r4CNOmCFOgs8QqSv%D^Ug69A%_DLuKdoCH8P*b-IUPn0VNx|8@#T=3f-4*a9fy@XCS~Ku*U~OPLElnlx+#QNOFvJx70lVMN zV7sO@QF*{ihC1eult8*iXsoYM;QO%}xmW3_)+)Tv2=*ipO@P~`@&ZHa+=257ud;Om zuKwq_l|NZ_~2kD!rsu4o+O!GpQ8q7Yg zho^Uwi}ouzdi`3u0*>`78lxlg$i~MA?Hx%2n%2?iXYv2QUYq7=gH8Ey_s%U>-Fcc7 zI&CM5oHMaw-h;W4`V@6qi@InpP({@7v`!8^z{K}}(dgc|wo{HC?XPLKCUvhaP3v5~ zse9A)K7pFu=o8f_@mO9-U9{KeJMMCQ;G*qo>JZOt-CLbet(_zd{3#!_-H5Re%W8!KQ;zP z_xgT+|5$${-LLh3)3fNIk54=vK1mge=H#dK<9$TGmm{R9LtB*p8@(iv{KyztEmNzM81r@ zzSSRiOS`4?f%zTSuN~)RaRXb$-gmS*?jm*-OW+K!o20Fqf%3oYQsnAJKa;^(@%Z98r)32MJozu^oS>Effr*BqfdYqBe4Y* z`yTijAXedPE#|(Wi&|>!&xRd0S5Gw$X53M&qN(Jb9C*aY!EMBmN}B}|f-3Uzu&g=9 zJPNPy04(5)$*+-mt}6Y!7u6wHRW{lhwQ{fyRsadZ&{6K{<4$45YXRcLQk`jEHsony zRsd;XPF(&xGo1-OrjmQ4t*XezVa$e*_o&aBtc@afOR*vsb<u8%px$TA;=9U*V<&m}#(VL96CsE=5<4$ad8ezeWz0 ztOWmIFwc{S2Qeg535_U!X^5B!BF&{<`mC3MRzmY#U7Ck6Yw94|vY|gU?K%YAsx+j4 z&yOnd(_sa;W2ohQe>mGIhs=5@nm@u!Heg0S4EFZNGWM;wy!@v`)v^iux)j2e^i{Q2 zFth$0b}@4ArKon~G16Oc4SaG`eru7vhaG4;cy~F}^5^gh6^4#Jfp{?Vuqu>B-;s}2 zGwox{qtO@PNkQ8Jm<{F$&2kTSV7J?hH+>w4Au4c

egHd$k_EQO#-1kR}5slsYgZ zo`R)G0ZV#s&3X4GumMoNzxQD?EmJMyHV5WsCPObF(~wNr{STLBHYIFR>oPi|+ZAmK zTq?afu+_DP-`zDoN98T}GPn|2wdf^~U!fuMZ8aQt&t-s5OGbwh~rYzU%BW^p+rrj zUadRhU?Z2~^0_Ot`>~e#Yu30RL2wCP+7eASTH=xmNC53){7L1o~(WnaNvL4{4qhyAcsSMbTodb#dJNAE;jIN|f zzRQ?FslVsgI&U~2;eC$RV4ipj`|m7TDx}kcmk;Pv9%bZxlvVq!a*53sp%?9}5yQ^| zF>QR?(Q-(73@=kjB5fzifY!MbLpvLn)JVORdW$xrqsb+0TjD+q&Rn%Fp$%Re+c&|JQ*)j)K#cd4jjTBg<@AJBiZ9+Ngf`10?nU# zAfrd)DT-EIV6kfx?h+6W^gWd-dip*?Qe zn<-;Q3RptvUVt?ejQ0zIqqLVdL+Y>QXfLKcM0BGEmyD#pOxM3ezW>r*lIB-=)SVQ~ zb*!gMxT)-7zU-(k#$!?|EhmBIWwA@@rTtkkHU=Se({g)ml>0Y`NBC~Je~-F+x7@UM zelrID|I7W4;hW1%$6cB~3FZD~?0rsqcq_(U$3{+$v1d4-);7AT+#9)tt}ZuxkhBJJ z3jO7WC>`Yq7@I5UTdPOel5gtK6b(w&!=hIkcu&r>U1KfNALH9HL}%6Jp$U+E9~y!N zG9n&G!?$4I=o3=N0QaB83cR0SB#ZoME-F!q{7YRzlo)Y{E-~a@c#vpA+=a4vV2;Eei!GKSbwe#Dr2RScph9-N=%s!@q82Q^DwVsDR1WD!_a=}u|4!*2{x zC%hCO^~B(LTdfp(-f+jkAum?xT>jaDpaR%7rmz*_hgek*I@K#BP9(v#N;{JDDie~IQpc4bpD(?9|Nl`K#AdHK=67;Rx;<1TcPthKA?^zT7?iK|_zBjk9SxfI1`IxyvaH)uVdjn$N zGmCuFbZKq_H%qsQdnw=wKo7RfUfNLVYLqn@_WJ{`1)5zUS43;-kh(;z2Vq-xyFS-0 zfJ~X@I?lc80`~VlHMXxfFeEARm#QV^YkR3^NdlN84g4 zemQp3)z%4+%3cO)*v;$q3qXFPT!j&M?tQa%C-L(gx1XKde7{aBZnfFIf9+O(XYKye zPPA#r`Yw{I3W+hVt6G)tQ&o2s^E=ig zzY6s&AD}3Ou$|95>dfeXPcOd%AUnWb?Vqz%XE*E{jEaV+#C(lQe?BwtKJ=@U_u~6= zSKr88&F8NFueqn*$o+o@k^9`S+#%17mpk3B2G%y6r7}ZlJ5@lpQbroa_jxLy(2PX? z73a&Hf7E%S)X+@lk~v#5I%ui)10hNcKLnSW+! z1)VnJ?+f9vI?*T7=Tb@ZQVj8J-~v`gghOg@CTpE3BtBIVdc#TQ8F+!FYr>EUz-ttln70Q*bCO?!ZTX%63tnNXdNnVC=qR!)~Wi= z8-Hgo9oN84jQ9QJjrW~~lHUBzFWz|P^oywEx#_ox4_x!;c5X+$J5_j<4Hjj21u@G@ThtL|SZBPW5c z`33Yl)W3fux_tCoqZ;F5&elR~uW7xts5kW!lK70!)Fwr4;Ug9vxcD2ow*uGvbxfOS z@H|iS>it^lL;SBsa6UVG}0qZHqpBu@iMeLtwWgQ^w-lD@=-6| zUoS8vYT5&8Slq`n;qwp!*%V0eEV`i^SD}rl_EG_#IU%pRq>;eC=o+hs;ee9I=b>v- zK58)%oj-!~Xgh^Z1pfz9H*$Wip6YI&qX-P+wSs>8daWq4;Xw53(Xm=h{iasvX-3FZ z^xvF#2CwO)PoC2SL^ob1Y&gK@3#7%doF~!t0&C*8bAET!i1uP~d-(QH`xCvs@fJ~j z(;`@_3W4TM+jZJECBW6|CHP`gi8rqF=ux*e$mv{-lDC(To@(4ha}aETL+r`+pB{a(@24fdB)PK? zzob6MxikD{S&_d?LGccB*gc<9p61G>$F&tIH7D{L_O%39SB<;CT&Tb?02Z6CFM z7npT;>xTW+GP?6x4C&vnpEZXdb5o6p7qd(}x*n;iWhKL(?CL_KG)?Jo84yQ&3F+wC z>9Z#E6qwcfseNHJFz|icYS$(3TU~bjJv{bgpfyL^Ml<|5ZkmG+T8#bpzY}OjkWG9V zCzU8H(1KBI_?SfT4q6Z~{)X?DC%6XSdKP0=>;l5-^9j!< zdxGdOZ0;3s8C6@8J&IjhKRaFucIwEy5hn8MA#r5Ipg1BKVk29@D!s`~(Ebzy*Ky~~ z$0yvD8`p0>2A}m#(JpWcbpIuT&6A#GiiOz)pKQ^75&hGULNHaEf_Zkcw$MfQB2#(Z zxg3|{7%>;RvfV;W9&EEri2+e~UqtVY<-5KNYls2I3t(eB4g|*&%6u2cUFR0O5M~O; z(iS7_SC|nCU7v(gz|tp2Y;Q^}WF^S^jyqYq+77y)%0Z-0sb%ep?M*=R`4T$mrb8l+ zsuS`O=9VP#^g?2kK(CtIb}hOswsD~dy2fI1E!q_OkJBSjeEiGu(-O(Y)8HW|0b2T1 zr^j~H!S<3st2G+@(&;RBE<7nI{s$YhY@sE(neb}#MaVfpM4?i~Znj4Zb~@Y%|4=qW zuTg$%e`CFiOw+^fgQ84vp<;5>{-slEXZ>Xe5ZYOJQYp=s?T<&R;$)hPqE-SaTj)2q z=r3bNtX8e8m2%yl=UY0}WNu)<0+d>!MbBL^&}&ylrVpf=O$}c};7IF@)Q&`|BzR|1_Ms@EAVt zhbd-c>z!A@b0hwkZyBGCqdU?%An2jh;8(rd^+A|X5hBDVG=-3|!$fr(K8%YYA0Y;s z#dQHbB7DU7M2;|7ZRNi?q;=DNG#&N)@eoUXWphchE%OL#&>rXmCVZ!@(6$Nws5zF6 z77iYdt+wWJm95u7@1ni!zM-w|Eszi1q+;@Q^cRCkS*e|S16R0A?N1iwxoG+~kw!E$i~ql3a4(Rvxz0?jcE8^B zyz?}?=+2` z8EciR(O7)!ex^m>W57F^8!!>-|MS9#xR;s!`w+=gn^Q5X>s{K;H|$-`3LyV4L;g!M zXbHrj6qE{)L~gxC;Mcq8^E&DCrY$_D1OkYu95D&OB#e6&qwT9`ZH$<5(K3(I) zq`5}MklKlOMJHkdY^nR^aS4u$PI&P6wcy7sCK7)sbm62NCEn!3cqT6Ztlma^xT|r!1Sc{Wq4En44ypOi6;k7 znSq`FKI9SBuV`k#%y1P9Q7L#!0>26VTz;*SH^zrL8&1Hx>$8hHulJ5y99n-?+jlC zbC2|6L|lRmq8PL4=&0Gvfg4okrM-MjT$mvUDiC(+vDSo)tx1tju^TZ`&vKuxDcMcm zAPN5NymtR-C)>&b6X2!u=nebSK=t->r%-Ff&J-|t%`B6)pkAJqFk{rNmtz$;3vd4| zz#mcvL@lX>AV}N%ns!zI>x>EB;?~KbKD)^4599+C>+@)TJi&j#U1>|vQ!PAn>^%a# z2HvK7+{uA0;2ukXNG~&SG_`$+;;94 zW~2jOFp&Zi@Q^hlXh5q!5pQqQ0|~sZaRw}+X2d-sa=huX3yk)6=8&mI1N!^#VzgYl zMoq+Ij6`?i>}s?I-U-!C;M|5j=%u*ir+cxl!hQ+-bY^DePFrfe3^`3j#EvIKgu@ zdVVCenLfL3zl4{4{W*$jR0cefTu-MCXSA^7|XZV6x==5VnSbPhl@)y(Rs6?M$_ry zv~CDku8;benc;rcBnuB3O%u;Nm0&sZi@Y#+uHd6K_BN(z=Y)xQc36Wehr(&b)P0)$ zGA_j}b611oyjq*$3iPWDsRuIl6O9@&q?+?{)!Z^*dQ&{(AAR6^67vaB z;1ho_9)}!iR4lj}^$aV@U71|15|}Ot<*OLZg}w5iyxd@;N81Ob<43<9l#~l?dN92n zFa6+AM)f}Czwge6;MyQ5M6fW~Z9?BO4bikT4bKPyzPo?Ng@_Z-*bVTwy%tp?Y6h`B z{Qo!KC+6>?^X#|t8yckP>D>G6>;K}f)A<-OF`_so!qX4Dd~s^WqDS38kRChg`_}VM z4?Dj1`G4i}qjJYL<)&k4VE8IDh$^s+^V~lBh*Q2Zu}#oSrm{e~FuC%2Rg>6k_LBs{ zOiK$Uyx2faYFPMPwgwn*I&KcUZdHVsRvFOW#5rl7sL1EAXJ1U3ntJ=pT&OPk5luRe zD|WNDK3!TjUl#Z*EDJcaZz*N4RvTR=@(9_Tk?^8L(`?NPCHOisdaKS<34F&na5HP6 zgADkr1w8-HquMa~i$mLxVRjM3S$-a^84(0N4Lh*2n2NI>;f(I^DpbG0wFbrQF-I3L+h(H_TS^)D+n?l;UGIbwyceoYRs}FaUZ`LTcUrH7PKF~#-YMV7OJJhr zufeta_979Svx!mEit#@}racfO*;F%iz=8?St0~f$QzY5Uv4M4oetH{> ze7sce4r>szSe0S5Nua;*X;Z&drgUH#OCkH-9;miT5baKa_n(IkT30qaq^FV^^y;>l z)L*QPR4f?JZ}+f`UmZlPQmhT$8)p)nwG96yz|5_+&Yw4HJoV<`nG40^?_|?(;XQ)D zMabGD>rar5fYClvSlIQHU%Jyq>;C7V8RfEOD$mmvd3czaJe5rF3!rtIaG>4(HgG!3 z4Ku*aD+8)sJZh$xHJeD*Q9h@cgywV=jNde;Lqn6w#aPS7a=H^e3UQvuf%Wu(J(}^< zH(=TX))gWyM{76j>}Lu`fo{K!tVLT?)FeXc{2^9+`3K;3rOFK57QgRtVKu6Ux!YV2_b(xJ|w~3Qx|$`T+;YDIv6`1V6xSr zW91TfXVBF*5{m;>;aMx?E4&)LWe6CMUGyjiXduiin%gTwzp|b_!@;+R;@&|n@0tkg z=2!ZON$VO4i(3~HOU?d!UPqMf{zVe+Ud%u95RbzY{I>r$<=F9s9;@nuC(X66qr$)m z0{?-2io5?1Qtv_;fZPqg`Oo1`l)Z#4+K-lb9W7H&>iCw~ftHySB2#wUJ*AhT*j|e+ z8`@eXLd_)OHTyMRvuxC3%XrPU@HL}XHt{uk8a1Ok_%{a+p=R{x4})UD+)8t^4n2#S zrC+bvbhazQ#T0G6UNheUjM0^M2zwr1FpXQPVP-trzw!=2sD!UiG(4w*vf*A0|CGR| z+xIBBx29oXGxSRK@~Pn2eL7$uv}Q#^QvXk(3ob-!K7+dH>@DQ)mDOd%sKwqv@K*tY zy@sy^-Oo*p{jgkwo@9iC|8>+9i%-tC;2nn6oS%ukm;L;GalQOhxb{Cx{9kZqDLx__PBNvkCRjkjZ85qT&Too zJT*l77QFqYBjOs2XOju(Wha+3z0o-4V=VKmYpT-68qYvWCG1IS}c9fV`RJ@uPt;2{!?9ajK=w zstOGOYryN<3cxkE129GutH(lnAZk)!&8l6pj&{o7Y z7L(gHt%t-rXAl}|*pq2W&j7UIh4JXTVR@UhYsnhLgvSa)y=TM_I#3<41Gu(Q`Uh`i^dtKk`HK+pUn2Kg8FQ|UAVG0kIqs{#*w;^-agXq^B)*E8Cc`1GxUPW1sZ$p;#R%e-fGH8a1gceOCGF3x6% z!PF{(Bn00|yI=c7_y_n$6!|&yp#KT|uC5MiY|{l&9R7e#4(`VS$iun+GhXg+ zbT~d%Ze4H_WO>u-qI_>9hS~#)$P-``{-&%NzN}d&Yey)ZFWnTBuKh;o{xtC4OLwT} z|E*-7heIJo^&~!#BMIxh;Om7K(G&(Yy}RxCfH-K23ySl(DP@f^{B)2X`y@U#Yiz1^M3THKK(Utq!(^F_UKjY8%+9)tVKV&!cuEEP zs_fzp(&D#E_6sAw!M@<{p>WvAmnCuiD~FN@^=kY_?_I0Gml(Rwpop9p5oHLV6*Q1r z@YMVGIvk8WX8+krA9Q~?wQFkg>=M&opsg`SlH=HoWiJoySvQ63ukBlxcB_s}v31s( z)?ccvUr&!O*S4?Et?OM+z}}NxXL`~_R@c=(N&i`cw%R%(%=o;H^5O^)KmHE1PXd2V zL+;8YB*qD98?Bk$j9Fl)wszL-x39rSth6a2kKrEs%FlwI*Sidzb_^CDO;);XuZo+X#WEv623RV%jA~1 zq5Dj1C$)>Q1)a5HM*`pF+MK#IbwZR#%hz&CFxP&|N)* zNkWb=t)R|_QjYCCb4P-3r$oy%T zFX?&3V6=Y$q^~ccW&Hal!ASq(bav(YOD9TpId~uPGe^8bkJ%sR`-!QxzBabGy|$#W zuh!XUs5{!|BK38|+=sW`GHd|vt{87!5y>2+Z(!o^U;CLU=7xmAY9gpLHyj0a&saOP z*X^;_kH7h!57*+pzF;rjd^_H}8E^jK;oZ1)mVfgP4)@~tOwddiLw+IWC@M<)An`B6 z9Pbyw4y^)8q#`l`w9oCR8=Jc=lvZw99pn6j-527>ug_F6x9Yg^+CPT{e#0b=Q%Z4&$fpGT-a|5ff%)uM|LQtcW~1a96*;|9yS$eWbFl z{O7ku)7!YVZ{-EPP2a@v=PSE|xr8z07it|vGZQ~dd`IA4+V4Pg3grb>V1NHh=;~?R zfi^=tJfC_La~YW|fq%wayk|2VW5wCrM6~IY(L>OjjPar?B8>xwthu2=GRq|FV9~fSW+!uN z0%}s=>)jQy3Wl~qz3caAdpe(AuOFS$CqOnn z8>g56wV^*?wtfbq*BqIH+20hxtl@ZLU9NpYSu>kp5!iBT2i7H6KsW#{u?o>?xz?6b zTe7~vUBxh#WLtyliS=qcwK0IX56@fU8e12NF>0p|vCzgb*-4PPuEzRbyFtC&egY>`4qa?Ep>~qrGXy|r+R{Ip~0^Tn0z9boG3Rzr)n3A#k zK0_o$ALa{TZZGvrec}mcuA>CV@F})x(Nw(I{Bp^@v62ru-*C!Ux$T?sCq|BpvTYBB ziznrCQ&Hai{Bvr;w3H$|Coz6^CY?`~j;}k2x5vs$|M8BNhhZ0fg04Tx7vwKU_lr8_ zot*bJZB5n7)r^UxlmQ7K(l9hOE1Vgicl{Ex{#--@lVBb^1a(j3Iu4Jwuef}yjQ_c* zb!oq$a~AD4*XJ!dXQ_@1M86mk5=q%WG#PTT7{5yVitww5iLmYuAXZs*?CT~*we(kv zs^e)!wG1Ds3pTHlqVLhD5&{`HF;Y6}IM!}AHF!CAUq=Q;%?&FwS#@89Q;skPSV$J} z=*4(FJR5Z^)oP^inqC1sJQGPe$pD5X19XFlPILKhtw8!S?6xpIrkJ&?(x`~uBK%mI z#ms%gnrCB*V3~AKIr(RriS)Xexvknd(Zno*tuMfRzu6u^I7r9&c}eANxFX9E9~^@856yli&SUFkFzj$wGzqzc?wpc zUe9tWG*zBBr_h|q}?B-rt+IuhKUtweY zYi!54qVnE*$y8y`+_bW(%4UkJ9qn5!$Z9KXU$MegUs|ovt<9cTJD=p*LN>INCA10O zw}sICjr1vVW1u zGN#0mfRS6RIL&Hph$-73FcWV}pxpM-viI(LX_;F7A@_u1&$2UI+~ji*?6Zl-)KuSu zJs>Qsr@G$?zc=|B`5LGfx$D}k#~~dhMotXB8GZ)y?`C`!i3zz6AId)#IWl9Bpoy)1 z_RtdBEei$PHdG0>S5qs#N7Ry6exj<$dUub&%pihH08bJEcAPoALf0#1y&|1ynQ(WyN6jog*Vmhlu30&vFJ4U&3vkBv6q@6 zZ9sooU1}sLkJ(FEQzEccV3E;;8x8&EOw14fKPwh$j2B|IVlu5$hk5Oc#_pcwp zecR*FCvK#q=^{r2h+}y1kOWw8B=l;p05i*b$my-hc=Vn)W72j|tNz;~S|Cc~VcuiT z)AQg+&t0G1?OZ~S-y3BIupsFo*=qTeaA${1V=F;+Z6B;ScST!_!64CNUZ9O zD&>wUo5G*gBKOF4B<_&xNaJw^NYBsC(>dx-Bj8#g(#E@?HVSv$#mQmV1Yfs(?^Y(fmtq|7eq zOYj-G-6*v@US@$zBe1<^kbA2|$4Rx~B&)HNR3_>-2fX){RLbOjZkeN`vY|B3Ame0C zKj(D_3g~-{RqeFC*HzNQ%xateX1D}>=nom^HJPcM7rEhw=B9iI(OT$_-?K>ve zbErl!9^E*ske!4Xf~23*0|kvW$+8R@87R*&2Q~^CF=snr@`Hn@^$JPixkC=jHGR z@K%U%clHC>!NeBYY6XNbCKifnH`PA2K)MrFzV4s&Yai9PDqT#0xbSP}L1{0Sgn+zJ zSYNAv=9!o!o*BJx1I(Qc4Q`#iMsK#i7VuhALSl0nG1e}#VSLO;j4VTxqzIOsL_}mV zz{&hYzkmoyV&SG*v8m49ZeM8g0d?HJHO;leHQ`a0sa#)QTfum&KM5vSs;pJ>lr1`w zzB3ixO?0Hn`BCMGC4ogCp?MRu-n07E6lFSeYd=OhaC}IppkE2!2Wlyjd&FiNG>>OE z&Ryl6xR#hzEwbihPcrX4J+&thUKO;z4^}b7{ZUms)t?SOio{@wUt)|^Rb^~1J)JJM ztek&Z#S}CH?eI9^{OR6U6~~n{RoXQEp{l9nvC3tfjN5u&R=EluO1Fk&;ButTPK5of zDg$WMU7vj>p}zgW^PhSuCC<%m-Gi(WO0? zaV9;%;^+J-rVzH>b1uT>zY#vJwGbx%HDKGQz?4PnSOp%xiEESnsurejOPCnm{%kJ# zOk6p(hN_Mr0&JLSa*1hPLp*v1WKQ6M@^TjwOpHjNIY>lArs|lKQ2p=x{Ae^b*t;ek z{b$_pup*-4@09~FO}IdAR79@E4A2)`z}4fWFZmeAxqq=69!ZF#5BIInZjqap*fv>{ zKS_u%!-fZFE^iI98LCk4niEY77@Ho2S!IobTmccwCn^sN$^=g%~dT*u<3Nt3-6Y5s{{ z7ecN%@oY*{-NST0mBh>Y^{Wyhz8HKl9xwnI>woxGd1#on%}?=-^(yW-MxXVU0Vewc z?9zcNHvDdw?g!BCjzBgJsgAwBoZ{9Egat$kK1U|RX&racbDNWe)ULH{avpc;gef*6 z=4|8*$DJqakt64%_v!bRN;2=Xf2@CAueThtDo-O)(|&6Cb1NE`>sS!z+EQ!_SE$7) zwmyrXjxj`lq$#R)yOWeENY>)?Tqf1myV~8(a4Wiji*@HMFcy3+XxA zP|aPiuyq^l#Ne}9=JkYCM_9X%oROYdE-`MiCCpH{+9MB^<&P;C-r9=u3*uh|yAsQ~v zAORIU|q4}%uB*VY3k4R$}KCcAiwKJ9|7bc43QX(*rV=UMNgoYuE2>6T}u7xFL zfn|y9xb$9|q!99LKF2MvIqq~Ekz_KE1;uk&#Nn_-%wz@mx%GJq_{M?1ztVQt=CPcV zS~#GVPQ#AG;W)-RQ*1+F+8WGc>47PTs7oQa^Abs+r45+MdGm7T6_eUqfie2o;cI4weMEB%`@C=Gr{Q-EP ziC?`|>!5Nh<70E?qD<192_ey(CARmLpW;|Yl{3fTcb4!^d_BlI>lzxZuZD7*FX8u4 z=t9Fj%vMMX?8kgZt6s{9ox;NDj#He*Iokny(bQeR3C_jNX>6J1frbw23nAhRISDJ{ zb~kK*h3(g2owH&st;5+c;}d`znm%6@dUtud-9>cE3mxrtSazUMpue;n?RJhk;dF#i z+kLdYdq%&&ox&V7f2RbkM9V$aO4ZKgVgF6%e&>BiE5^M2t1x|zEHw7-SS@{M+b*Xq z+{NF)I((?PcI_O8f9-6%!)Fd9?vn2;awfb;@+OAXlUu;2HBB?unaS=g&2!@I2U1-H z4T&zHi{!|IbDUG50jb~~MJwT5!l!}my%|%5bui54-5wGat+(Bx5xnq_{@)trgY`=ua9)Cjrh@xzSe*BpQ2eG8Le~N3=cp~wNL|@$8`jcynC$9UdugqV z?FYj27HwbpMeZ5xa-cC^;Z|4@IKS4f{WRULdCWp_s&s(^@QKbNQgR#~O{6Cna9~d_ zBCxJxK67Xi0ct`EQ^I=k%lj%3eFR+oWYWq_$JueMz|$W+I+$0Uy_o(7PhW3k27`4z zoBy{zdT=m*aV}(|xuL?vxr>EG`n)cTAGt53miS6)@tsM0p~_2@d%#;BsoZT92Ni8A zZIXi1Ql{Wu8}?T|ndUUNxb{+|qIHn7+9H+oKdWt^Qq3)_mHQ%6lj6Zkp)IPP zF91vV^|XXfOYi7EixKEOz5L|z3XbOTRd^@716km8odrKe)ru#UGBcyN?~CQ9$5YU| zu7%!1x(OkIbY?#F+h+wx&G;*%%T`oy^scMm0=Y!QTvj6XUS-a7VC287{rKKBS7Yc=fh6D?3DFPKO zv}j5JQ$P&j5c2aMu=mNW<)|>H=SZEj8et}1mBUt&CAoW)l z??Va)7gH}O+kIiye3@kdH}N`nqH1%wSvWBqQhhda1fJ*3!z>$Mo$4cVl%>xM>wva$ zGwk0WHWttG=HZqq^9W0mc_g$jgcGRk6gh6${O;vGk?n4^!aPgW3eWMvNiq|5%;0fY zVZVa%K&Tyysn80f9zViuWoj9)W~<8n50+Mm^D)e%P|T^m2wMfioU3a1KbSLa!A$W{ zDF}(J-2}cZWVzwV8n!Bt4|uSD)QP?Z-B*lN)EABAtw&HtqK*%bGe02$xoJjj6taBO4fU-Ft$3DFJWFQ}@*$I%O>INH@AIA{rM8FO zNK;Gf&m6YJadpJP?-1+=g=N!NHtxXzg{{8%eH?T%1b|lcak)p~R}&n0D>uO=<1Lrr zr}hubkYX|`K7xd~UIVX!T8zoU-s<1b^{ZN-giU`c*Xwux(903Zx4Z18J9*4Z#xU1o z0|q?T4k)X`TqfA|4|6>TDP`&}KuEN?N>~$tRS37+uLPE1Ksez|SnP#O|D#)sbas7S z7jkx~bScjFl-3jAmkR7}8d43Ma<#z}l+6%WHm}00w0&XxR?@nPuMcw>eNC$*guc`L zek%tA8{j@oYBXh*4Wwy{a4aKu)JS2yWK zIX3IU?4{MS0Y^J5)z9NM!qHZJ2EQSWZ;Yq0L*7kwc*tw;W5+pgH+sCz`1guhV{64T z^gZV$cACGV4TWX_5sZy={M(qK+@TY+5hW}iVTLvx-)oGh*g_`AyG>jsv=PUKI}(+A z`fm-E8dJ6!PcU^9-JRfs6#2I)J zW}c1j@fCZX!E;BpLLO`Qztj}+QbXAK+3OiLd!AuWiy>^o>?P zt83+wRp;3Vh5cAIA{z&~R;q(xXUjG^$Yh730o zb2CQZW@1i8jN^0j%#28fU|j@cll1FCA$7KST^zUvp92;+q!W@cd6aCKtEY8nH z>9~JGQ%JBhAgxxa>_a||_@3-F zd9%)oyIpZ%0_k>t+^@vEE-37FzuzBDE}*^-<3jO(hq)H^8qwDG z^m>lJPri`T^nXi-?w{04 z=llu1bgs|pg+GrmoNXWZyF3-&r}b(c9B=r6!J6KxAvmG83Gh!WjZwXv?REo~V|NOw zgMCr)&;%MQfMS{>Lx&C zXNjr{+T-`(Y(cHfhq(@VQ}O((mjlO?*r#5oQ4%i9^=>cK^R7{aaPU9|JuGkz8oG=P zxKN{ztVRt<5oJB$>*I_e>EaGC37N7>n@#w=Ei%4dnA52H&A~T>x$1g(o3gSD zDLmJ!sWwzn*-UVq)D5}{aH7IoE4-ze!<|-ga4whg&fF$vrO`sl%eZVCw8G>@E=z9M z>$DJI{>?HeN`zB1DK-eR8l6?fm&keCUMbL5huLkg>mFyE8!t0}|D-%OkF#lY3S)z| zs$i2IZ&}aaq`aAYR~9lpzC&&NzAT4? z$>jNyP#-UAPr<5t)t$exlK$aA@3g=}WX|q_E~5bFhGA{cTgA@)nNIk8#XcW4T{_j( zXDg!8$H0HnACON{8LgzsXe--Rwm4B#p9Za~)p4`p<6t#*teyHX5pEC3$Y>8y846Ct z)oLpX8nt5RMGYgOx+s!dE!B^c-DZxuEz~{QA<6$;?tQJOzfxL=A^^7oaN(J{ax=?IKlmYs9kZ5Z0HM6^QCi#yz7I?|e@8UHd(u zab#IR$dsL0qK+oweFtQcx|ehp?8XAozHI$jc}jK7){pLfpn5*BmvUJW>oq4z2A?8P zuT-lOKy3qQ%i$yR$$htBQ^6$;J*C>Kh?(!bA@}T zA1k^iu2F`$6yDNgVPcdWJ7^+O)no@~MrxF}+o2rDJ+KZ1El$@BKV2KBJn^^W^}`(O z=0|KFRv)>Oq)YA5SU0-e2fWouQg{KKo-1v~Sh2vu1@`2ZAXOr8On|&*GOZ;Q4f|k# zSB2G4=*WNoQd);DlGGWFVYbn*yTM!NIXyAqech#wh{i8vcbiXFB=J->z1)a%I;>l_ znd{j;=wC$&IeMS{g^RcoZYVciz?!LpT{Yr(_F}G_YFcf%7-55et(>!6BjrY!0-k)p z!J>9!qjrYaY#4*!7+U9Jej#T~7pd*Y*CEe(5Vl%uMtUO?V~Mqlggq*mMQ(|=Bv`oA zG)D|_Js#3J3fQUjyDR+Imy8|Z7>;uJ-1h#MgS1o&aJ!1?>evO}r!;2^DOnxWb85f8mA;V$~tVfL;7O;toRXH_!?=i>x{6)RWvM);ma$CkOx2d zsy5mpVznn95UC`r_J$7#RT4r|j2sXr%tmWY@RTMAA$#$z9g+jdYxPmq#GN+T=$-1F znw>aBcBEg3#0Vy5$6R<@x6VOSPZq`E?69R%qM?2QsTKU!*=?@;LZAnRd-yuqOQaqi zc8M|5IwCL78V7Wu<=Sf?cb^^(Wv%h63G|XKa4?8BX?nS9T*(ut)4YMD-uamNQH=I$a>Cl{6XXja~ z-Hv(@WC~DUdv&pAmBrwF$ZVt$bGlWrNq7FN811saF4$)!`*fil{JsydvfKc*5k;T} z%!LcDIAiZRE0^xO;fzkzIB34+5V7_ zc<{yOKC!>g?~g$)C5+a!K1wT$(XudF(f@~*=@wcMNl!b6C2e#@COzrocV;K0;jGQ? z9OEoaN^(w2QahuPC~ts+e$;%UO~&OXm1gP@w+Ki0GQR$vqQ)|K1h&(%?&;&fKj1Amw@0iO1`I)JE@mp+c%2CvJ<|qs`Sv@079D+|-wlI<6xo zX>=-SpU@MPl-)y8qF)Bj_-w?!V-la7wjp4KPf?d(|2Wc;}&R-n8 zhu-rDc1G7f%|fCZV=4sOW5l8Q==x}@p#GdTy8g5?rMQOtqb#NPQ>9$xq4m>Y}lF``lZ5o8{9;hvH8*do5aA zE?)#6j^Mt?!N+S~06vV*{dn&@CzZ>fx3yn)H##RIo$1a=`m%d?lD>OH()8}qq&vDt zB~9yoFe$&Awt3kJVbmG?8_^Fs8ISat!_;4mpgw`*;*_iJh&0bJ=kYc2(Ks)S^+0GU zZ8F9smzl4XW=wEwye+%^J@KEBTqb-XgWGajbz{81W=$lwrP`GVv4re|1w*VFAIz*W zHen|o>llwyJ{dpCA!vX<(>yu{kB2s*;0$V{SAcb954giql#d0&H~;RHqBZ=(i0uRMiD$J!Q0MC zLE}dTSOGtr0BI=C@T7r_g!BU89Bw3h&RXQm#c?=QksOhAdw9U}w z5ZcO71~(*1e~sU#BW*8tu0%=bh+G{{(-96(jSAw}*-4Vpv10h#lf44l6jHGOU&?Lf zCU|xnLuMu4+bM#5NDYCd8SMBf;GPBXZRg0n*Kmg(I>sOz8obf1!e9Ez=tvMCrD{T`xb-Z65{%P%g# zjRo@iDf|_|$6f<&r|qHjVJLO@-(psV9vD_nwsS8Nb=X0_`$u0GtU-;iA2ZUG(3BjC zn%mSTz;k0CE#niACJlA1>q}+Q*<7}Syzit^FWI<3gcbqn-RD-rE+ed9ZKoc3HSmT+ z!(<3M581n7R;S+qTF4-WQ?PpsDNX*DQ%LBIB;{se)h1NVmOl{cDuX2|-abdkZmHla zgocg6ZUH)%fVw>3$V2u#)Ro|+&+{H`_Z%e|>pVZ!K=YXo3I99;4^9FZ`va2;r�h z{kQb=)QmodcZWxm_%G};ck8}%(Dx5KspKEd8a1zp;RJ?F1}?``fCrzb$@jOGW zfyn8-%x8Clcbr4-a47G|cU-K-z8?B#0@TQ6)PauGhG{0{5Z8eJ%h^L+RXEEx8M<(n zZ-S%;m6CP&>He8or9B94>8t2zk??NXiuS7NyJ$RsIT0;}+hC!ip1filaPI;ZPU8W- zv)Sj?d8&+M`Y5*FzHoT?o)AdThG!-c>iL#Rkc`$~r(}u8d`B{p9g@_zcF{gb&P@G4 z!XEwKbg>w7q%MbutWwnCQ@vu0S!nU@f-PK(*%0*A(tdG6C7mgDP^>`M3gF$uEdylc zEn4Vz@VoMwGY=^a4##YH*-Mf$o3CKUl=ruC+0P4i7YJ=KRfBATdKff|h8-e1U=e%a z{DqYTK6e32?<V{S9qHS16sB#eFT*S$-MC1daHxG0sta$K0@ z{$j%{!(E}4$emHUNOD?pTiGyJLEfXAY=^zrF>PhxmT-7IE7q@shqUxg>Fy}oYXxm( zVY{nl$cez1WL&9N$VI!W^r5?xj0*Ww<0E*N?5@ybzHE%x0UvisRgfFw+Jvxb0DWqk5TYpI z*u4rT31O{LiW?%SB|hV#L+Q*hMqm$(nzu?CZL(P4im=b3HlAQ{PZkZS-AF)1`pMw; zEP*BA7^H)oHO9iS=`kOCz>ye0-(V($ZzWiPxZ#ihf~5+ZLOu+4QR!Gc&$LBZVb>kE zm?C)8s+tjDX$Joeu@)*HLhn`w?^)@cEA9Csh?qo~2i#pg6pOVgE zvLP~AU}Q&uhc+BzBgvPAQ>Pl^#OJOWpm)+x)J_5Kua4jT24p}tVC@O%z&x6gOvYk; zJ&(2NcRM%9<=lXk6?3xdW3MPN)lSAt!OA+|zB$0zt}kf9`Kc$)6pyolw=_kV7>P3; z&t%BtBpa!ALIY1tniixH0anoW{Su@f>U!EkXVa%VdF)<8NJ>*~vU?+}l%#cHCT0th zC)Z%Y?<$Xmd_3V~&ZC9|L$ZP9`Xz8HiAMT1UoXLq0V4|M{lT@CY9@UQ{<|=T@_cy6 zWc%H1ev2uf!S6I!j6S6z%X5C;+#otzFo-VI|#L2pW$VLgG@f<79h_U6O-efb(6}2Z=+h zG%ai`T%$ahn}NCMLvU)|cP!033jQo)3xW3pt1}I_6jg?q#<@d-%JQ`y^njf5ZAl7k8^>mt}s(cYteQ|z1SiEzxs%AWfJUK z+v!fo2fsJ)QfNREU_uf0&v}uZAsQO7%TM7wcHp5 z-(W9xMuCU;96V*sfdu9vV~25%k<(bT1Y93+!wut6qX6@@$ylfR$}Zgw&$t~@@HViM zgIy4Mwv}RM)@BzsG@DmI&V#GFY!>DcoX}yX7utu!zV8CniNAu;BR*8R$+D?!6SQZP zvCoc#MB~E z^)O1I!00f2=M-mrp4uGwxSA5=V2y&t=TV={+{-sGj5+f7!}B2yg7 zBFwquj7o#2X5v?m!VVM*a78Tn(6r7p*_2xi-55K38t^ii-dqk@p7OYbiO(^)?miPY zK{!clYtmhEtb-oRHgKi6Dbo6Iv;@Y!<00q6u>KZ~`E7nb)?%f!(Wt-VUI>e9ADGOh zJX1E4!xGuoR+lRlCpO5((+rpHVhZ}W30IxMj6_hx zOqVv&PFt8bKJ39QNzO6TdeaosA@urQlW@`vwDMrs3Nz2bDE3Xqt34!%_MnNdgKH(y zv`D*X&oLQpTpT-lG9X{pY~H|Xwt1a2w~tX0K|XoFEx{~B$1btUd+4aT!!x1>8W;9Y zJF_A6IRzyR50>H$ror=9mwS?bun!3){o>>yF(*i(r5L3BF=%JrQW7!J5KOx1 z6kA1&OZ2oPul6c?1nK|VHY0Co8`_dD^$G%QqY>{8x7;1fwO}YmJ-vap$z$zq2KIHQ zkmY7DCp1^Iq*uB#&?^6_i(AY627GOGbfZNellNe^*d~}zp%?9$Dwn3kuy0S}+rc)G z21`P%q0=1Rjx>e2Z$JX+gKk(4O%^wwm5nfk9U5U8sisgkAUanO$ARvV>KJ8Uo})77 z;mvf8gQu091MbW|adYDnkT5ZmRJmgjqyl-zI>;~Tab|I|?Me6(NmV)|4O(MJ9pyud@{Ib)cjw7;kT_AQ zq5p2)Y_dDWNvrgE^63bhyx=p_CQ~3rzlKV{ppUKj#3_C==_x^KIArt5jtI;m@AV22 z?>H|3pIDmysl&YBZKn`Eb?Dk5#f|hzLg(fRQgQbot+yFzG7`MT^ql?}K+vAf@fTPp~+u70_8BV?f?gicmoObR@ z{>_S5|V#*DoIr4fcs7_)%F|?NXu^JI7mju8K_iBszLSCFlopVX*JnW$ojF4Hvy@Q6l zhFXw-&pn=%(u{P{y!>7XS*<7IhCy;5lXSULV83;8VCx9^#?~4ns;tqDj!M*8eH{Q~Ia;gf6yiO~Q-1D0n%ah55$cPw9m? zMl^)DW*t|gTh zG0Lc(reoC7FP6}a_u zB<7q@&nHcDDdt7U8-zL3GjuqJ#=aQ7JvX69h1p3`JkI=@~ zC9>Ls#Rsw%CHC0#}vC54&gBqb<2kT$hEA~Nx40~4&=jy6?gA}5% zL&+jC?<3<3lQQ=1MftzOdj4y@bz6D!#w!xbUod>5cY@q-4~f&y6_w={T9a^ zIUAwh{U-0!5{_O`)0BRhl0;Qd_C*pGWPfkwJ3)H0sLbsj6EJ{^pHaKxY!_5pjV1SJJ5 zmQ&u+06ZSjnh_CLoH3!3GhfQy+FTxfboy{3nw&_k*g!l1B}KU2n`*g zao@lojW6t@ockHZc%&(|D_NczFpg>mesS7ZjLIK|{x;11I&4Xt8p80q$9V^-oUs4i zvz_6Ffl3%K!}gMKM<_1%u`1G#>2og{_`6LY zJqhGiU?oG{kaKR?l=bV@Q(3II<;T`9THd?fx_rupbIaFnhYuwnnIL4*ZB~m^(jm5*0PljyyC28aYv9&9MTbH#Ikf$xRr@Bs7XH3Qt;)n582bZ zJ~>;#`?KNW#_%Pm8$ey`T*xTYV@%yjd)B~O=iMyk8N}c=6*uIVTTzA*MtjP7GG>v1 z)?CkAwR4H)?w&%1y&5@@+)^8Uce^LU*@b8+Cg#4mQ*(Py*9s0ZA90ABp$$_= zS!NBm>)~0IG9@@;e+iBmI>!I#$>`z6z-KX)2kaSc8)3~OjlfyqlaLTt*l;EMkZ?`f zD&^q^vEQxn-;9^QKCf`RsG~g?CimX~`5NB(L;TJ72I&=PKeV{k#{W|uYT zos7n86POcx?hpK!E8s_p&Ipp=oOy9BEUm$}!uoCzuocG1;2^-OJgn#BV4eKRLtCeF z?l0hNaGDyme#zz~xWzs?U-2qvGp{L#M!wFa~m`Ru^$odKOMfE77j{fdW zfL#Vr;qUG{dto&PzxrMw>@m>asN*}I=b}dZg^OAVTMU%Xqkrg`!{>~OYWRS#s9`ZA zlEBKjn#*~;mh3InuhxV2SKn3J4E;P#Njc-nT7j)bPW5Ug6Pb*&Cc2b9+%D$&Wd!r{ z6<9Ku@es8vLdM=^*Wi3Q+@V_0g;OKFnN1+{G)Y(GCivM~D9a>?F3zV}Q7+dkNhOa# zUv31nLU7v0*%e|$7FbVl&*z-#0EZYBoSmDnnsUH*X|y+IflFrhg(6fKwb}E|<2*=q^gQy#=<1VNH6<*%o}6 z9!E7{ve9ZzSP!>gu7{k;>#&VU&!?J)pi7JW9j}yja=B=?ymYith@GUvCjd0HqM&QV z)n}MC=KsU#Pyf+gqxlS)1$BFSfetAoFXxWM~=eh+c~{g+Q}=e*<)S59gmYlL%K$4eKe zlzbq+2Xt>ZelzDlCOTH%wE1E45tf&(&8Bs{h9{kmSoK_byj`lir!x$7JlqkDnK^-| zrg7tbZ%+t$eQjiNhPG>MvH5jb#v_6(LB^GKs{ebrz1A6x`_hZf8wo`HCvLC<=5=xLIj3Fc@>`(d51{O-sIky;`( zQ7W7kw0`#*p9B`f1j-1^D^lBokhXn`RLS{0u&ci$12QYHhHa)=IB&_Ka2Hz5TJ&Du zmI9J`2|OvHmR04GC~)Y-_4#ITgU|wh=5<NNx2RlY;0xo zv75-J_KO-`usfyupy>*U)v$EZQS0QvRpT;$8mg6dJ8x|@Vn5x(@6wJV?Q5}%jZ}{| zPoI{L8X@+T@LD6tDMVgIqdu-cr<|Ubh81y|9RVL+*ZNw+fD@AD+}fm zf5rSoT+Y3)1~O{y^o(C|3Y(q-d8~0?J6`W;hy3gQe+r|NCxuZp8lf`Kj(0i#J1@`l zG(AUmG2@(F>^BYV+VzA~2|gG0v_xaojcdQK;q?tAI8hNt9LjWs(`Jg z0<(}k8mFZiQsysYRcrT<`PF z5X%|Zt}0EmP7kdQZ6sT(#Yn4=o$G`&zg8P-+gNAd<_!97=$8+W zpX9^gAu*AV)Dd+hCqgEiOX6TTic%Z_io|iV^PBU6ka+nWV@U_+j7%13 zM}jv&cpyWmn_=u4t8yl6_q8sD51RxVV_O(E3I4az*5ddf6BBFFpO^z8n-5Ht6*!y^om~qRr? z)JL>bY$R$^xRuMiSAS;_m$gEFO!ob#Peh+Yd?E|8eiHM&g2KNozN2IbuomclW>n_O z!}iq2%m)oh;Z>7h!XYP@a|&ZgzPc1%Wa!--ykgrdknI#eZlX@hTZh5t^ax8#+#>z3 z2KW!cPBx-Gyj~EnF4QjX3B}EFdS^uAh=z5t>H38-qKPL7&_fV6815WyAJ!n1#nwrQ zxKnI?OI~1pP5!J|kZF_0?tK>8vW5aKb4x)?Lx{`?-xsH~|I(h(TEO2PVY=JomkF{l zPc%dm#p(}qU$u*wy^?4v)%Xn$-kX1fGZI}J>u?a67fs055Q*Q9b1fCAJx{u~Q|hw+#&OIoqm`YL8mYd2@TceNCjg=!{M!tN0d-${pbT)PyKYCn@> z71G=~d5x$hLRKL)2^ykg0eF@v3^hsHz*@1*B*^N5^%UuDX@f#BOTQ5IEyH9nt9KXR z#y&X~Qkk%=g|jNZH_~*!`7YBwvmoase6tt&kfAuGCCQe|Xx9DgxDQrZs=GPmyO(Y) zJFN>2J9R2wpos`oSaeinX`!3zO%>O2OQ0Py!&B!O-W`7zbo~9;8+RI4YRR zOu&&vsadBnAML*gdAyHcC&7Vz`&sbh2uB()NBtfmijpDhc{}b*LPb%-@o%CyL_})v z&*2|j9?05>$Tijz#-kmQ>{o+*Iuq>>i*&NdVV2_vz=JuK03OUS*GI=sJ)g?3dQppq zv#@vPOPuEzRRL_Y-fsV{WC|N8l`s$U1+0y#O^+saaO zu@pbWSFJ@S8T?T&#?Ic}Ma;3H_AIIMLza^hu&O-Qek52v8FJDDjBH|L*n1fK0fS!# zJeaHPfCqE+9LvYxT(Jc)uVJpBedVd%K%bb)-X0IWEe!UMhl1}lEY^tcUJkb862Lpr zl9WaT;JmC~dg@tjAHc2LRC{f(-fEHC*@z#^RRQ3w!JeTF*3RT$YI%s;9Hf~IxTa`& zFeU?UPX<#?2E0C4Z=(S}j+&ymkOQ`7B{&~pxky4T?y)Zq&YX0n4M99nA7;1$2480I zfcHOhl^gJ2PHzCdKbV`V-axAczP^N*vS1m0^xoR0-v{3UwP_E&6$VRj65q`Ue)k#R zS;3rt47fe36*k1_D)Uc|IB}XiFPL-M+HWEr2838{|H|OBAjN$wUxV%1fVlC&cCGgY z+BG_exh+@%dGLJ`%iCFA6?|WhZz*o4dR%7;%g1JqB(cao@|Ip_1Wq>TWcgUa;5r6Z zFt~xi_W&NO!MT73dtebuKQ-$tzXv{t+cC!J_%qL*v`b5uOU1_ zc!cq!4)Ha>`{J}PDjaY(%V9QZ3VtJkJ&o4XD5N-r1Zpap!FHCbFu+Q6pr42sT*kuv zp8w?53z+6M*J)?e1t|X{`rT|C_;C!J7QmL;K2Ln|y`1@)3$(XTwuAT@D+N#AXn%i& zQLE=eg6TGbhAXR8y{G$iMx)6uNsP7c#$F?5h{j*=P0lSeHhQv*^!rWSjqIDPxJQe$ zzjRBDt_Ib?InM~VI?L&NiQ%qA9<%LRZmFL##AgRU)r3qya-@zaKk= z?f8zUAGl;>;R&dVn~voS9)&W_u-_9b<8}9dzp^;ZsDKyBNe(mHm0X85_+aj@yRQKb z01(|Jfj|Y*IUh=5Q18AXL-&`?~uH|9^HW*WHieO{s3g zPUE`!Az)#oz-Qs-eF==V8Mlj*?Bby|xb9wzE!it5O?F>vK^ev^9oIYXOUE;Z(TtlI z@-fEyn^?mq;Qu7XFHau(YYY zXOVq9_OtJxbzv=}*UZAlqgDj=M-cvD)^BY7zY57-Nc7kr3f93v;9qx3Q5vQC0$^G; z4sR-TCWHHYbnlu8ns@arV>E^MUTD7`G*2P)KyM`r^@30NyW@Ta-vlhM-wTXSv)*@> zv#=}FH;8>c`d>%ZiJp5|*iQpu>|RR{b_JC7_0DIZ-vBejKJ%9L{t$V%k=4{w%;LYm zR|5MT_^L(|>72>JjtxjKD@?iNn|=5uFygMe8vzGK+;z7F@L->P0dQ(oO!p*4qXD@V z+OelWzWwg=-awCe0inD-sRXxl-rE@77KBLcql2r^b==@$hn%&bCym8E%5o<|?pm{o zdy-k$N|b1nJvNxTMpol@;j3&ycMsRyg}zp{`w5H?9b#&--sm31zAZs&oCE#5R{)xI znqA;)_M_ctUozqMZu}4K2@e4N0{@-(r~AUY@&7#jFXLZ`edOSNvJ?I43-q6mV$)H@ zitzXmgjdBV&%@`p*j0(^3sw9L_qsmQaj|O_E<;-jT4`FiTM^>k>n<${@RobP5y zTr>Q0HEl(>72ipAw&8uM|FgUDjCR~rul45{|5a$ul)9ex<{8@&vH~Gr7Pcc~GeW2h zl}i7y;%P?33TbX2Hz&Nby~VDTJ}y2LZTYB2X*^LV#TT=^5|zuCjQ+pCFU{p}fXBV4 zXE3aIC~T}p6vUez4D-8_AQ8S?MXB5adIuRjomXj$LJpLO^Q)o|Hw$rox6JQXDUDLs zbkB}rrBPlhb>(<=2B99$3&qK7)xqtb>p|}@q~v!;K!=FtCeo8{e6~ag`_Xh=q8Q77 zaTyr>KFp~NQkU41XOtn$9$&sOTqT3evvmv?@;D6dauDx3niG{QQ{wXZA7^P(_*eg9 zL0IYv@o0=IOJq4bz7s;e>~!$U2z<%mOQ~z5=Yb*YZNR3f-8Ymol~=}6{2TiYvodl- zF%}GA$b)&`%P=Ia{r&(($q+_#5aWd)#>@T~WwKH1S~DQa4Yb~P4;O5U4L*diT8c*w z_oEJ$`jp13ZTnHKul<4`meIGLVM!p*KNxo3P}slFQX5tDi&j7fKtl%_YqlLg$Xi4B z1-=788a9ScV`0bEs04nxFM+k6GB?mZA9|u#3ywtzXbZ-nebD;&Lg!Z$=b`l}oa5)z zQN@ZCv09+MxMci5w8660PSh{=q16J?`gJ`Kh5lz;2CejXza29J9Hirw33+s8@+=n{P1e@u4uY@2jG(i@z?3H7Jc=7nfyb82pg?QW{ScmZ40Q zXfch7LQ4P{&~~#CmqrW-DP`?Sp}PUKBJOs?ajI5?+<}k)vI zbAB0X^K9go)`hP>-*~X324y-JEE91#fJ4Wvl9fr~Qe$*bj8}#*P6aU{gBWsOp3#id zyr5k*ApR?;g$BgE1)9970X4KAAx4C}h7d?20D3YANg#s~2$Q(p z0c1kl_Wq@;_DsRrGy0{h_AJONt-bsED~fN&jA)uzRzk-VaT$O?>uwV;GST*121<+X zpcs<^@e70T4SOL2dr#hRd35f$UH{za(`ZsBF8Awm=fS>fg8_o zwFt>aNcA=fT?dq-qRu)xd!K^M zzjF~E!!Ri{5>Qqxg<1g}23}{M(il^C7$LMBKS0R$2qCHu5ONkFClT^h-|)`BUWd*Z zbS}~UNR)qEga35=R^yk>A9OCE^MwHQKL#!EY2V3-fi|dz_4`2B`$J)MD6b2&_an8m zZ7!tt2}1lT3Vq%$4&v|Yb1@oNyMgB}q_KZNt~&AMW`vwnbs}UJLM|g@JwnW?%LsX4 zKw~V6_an^Ir$K#D7<&VRMuPHvux#>hpFfzpB!qIR07fz>g=Et2?q>O-u*9WAXch}C z?AwIZxscE|i7OE~p3K6h^$nJ=pl|ZT0AWFCK$_OR0scV7Vx`Mvv?ZcvBB)p*@pB&Ze^*^!F-_Erk@8xU&0` z(SP6Ro1W_rt`es}xw&L|W_2}<{|aw~?5hjC!e9=6?kz-0({+?CEZp?c5m47h!vbT# zh5DGszWFCo;#3rtxE=+iU3bmPoXqn77~awt&QahH6@?|R-yRxF;>&3EWkc^^O}^3_J%l}ds0Z!3C3I6i9qY7ypBoDGyC3Wwto53qP>HJ+>B(6N z4 zxLiYRKWzxZ4}Z}y$}w2KM|;^){HY6zCNq^K#5g$LjO zj>J_4Djkf9+j|@9IUUH?tv$!<4U9%--`F{vDwAPLTs?i6C?EY&;*tO!UEC3D6L)VW zN)w1Vh?s+n`bqDo;z{V22PgT1GwO%^ffeQy=u_Q|r@fK?gYixfjO525=NI^WQ_h3;blsqA8<@VjSte?uu;#uT*v^In!4HlLqC z9m-WSub5E)|6F`9Sf0PJ+6}~f3iusX9s{e}0GxLVJls1-eX;i)T2@AV52H@8C9t-p zG@dPfCrG^pZ&FntrXKKzjCvNM7=S}=fxEE_J;gAT-p`7m$8A0}!9O8T7h_RdbYHJR zNvX6@hv%c&9~P%joS{0`px;uQ$Y6~+Jn#Guh9XGC=LxjRn@G{YQgnL$%5WV+)P@DA zT@K>z_w4x}3~>Bf_3sDVm@VQzQynZ@S0oTO28Kw z#%@44Dhgx%_r@qwu#9{0sY@!q_o**Rq^mVP%2uuC746Y!2r0 zPT*FuuU6q)7MLp@^;8ax*b&HKFY*r3nCPhvrjD~7zFf#?B;ceHNMnp=;ZW|DgTn1| zC`MMT1pEc1QJ|u4n7070VP6u^m|RO?tRFbNUS=ag;8{a!g!NfHdNK|5xjp_hlcwwZ zlR{c(jXLqAP!;%cviBrg*8*?XL46%4`XKkssgjHtE7qZRhC$vsx~otIy*Sr-oR8rp z%(cfme74f~G{gPKAH~|@X`~#6-59a^F48gUbAOBzD%JO>^-G2@X#5{6KKy_77IduB zxqyy)A9$66>m8*4`D5c&mf9Bom6E}7J@4N-RN6BrRaPy_IKTJTD36InM9+ulR$(`1vee0^4P${wsd}MY<-z7Dh0Btmo7J zihnuyeRhz3Cw793EGG*8(Gt2+(w5Tr8;45t4f5(`7@>Z;TGRMgzc(0Plj3v#8#F#4 zHyDlw@LvllEOwoMwV-yn51I@bV~p}AxyaQuKu1$e3f2ys$v+|O@{KBqD-5u7625HKBNsy8cHX62+Xs~j&%f;~K zslkr_GH9Uvec%Qr_JhCMvq($P29isg_ zFn*G+W~UZn7hI$#Bp-aBZAqs2cowyACotY3W$@FDe!|L82FjU$u)9Nv)(p{F?puU> z(%wUJ_aIK+l!Dmxb}(;QwPIHTU=B4Qb~OX~Q9d`A^1m(w`t*E!m5Cmi=zCVJG1im4 zvYA1Q&x07#8Ak0Gu?uzraI4>dw9=59z4B>6%%c|qr5Nk0OQF=nt^vf;+JRjmKz^3~ zRF?h#wG4{=g4mUT_Za1mXwClqKu8usAjXNjdI8ay=0{NASo&huy5RQ*gWqrU)0r>{ zwdWeRB&TbPn4a0yam8`q;X#trZn{8}*W9D}adw6jrqEU97rH9^vBmH^^lx4Rizl#A z>T`>HLh#B&*sZ75_}n9dZ(sHM+;P4E_rpFKn&=Ch8wS_)rAk8R*rvRRuOUN3xoslX ztBgXFkHYo%e!9;E{uH0VIcN)qqCKDYT^VmO_*gj{7I zmv5o0$4Sr!nfL$DIqj!(P9kJ5^)^3E-R^e<(}J%q@NE3JLmK=Fz8_gg>MbETEF=>l z0Xlx@euv_#skem8WFa#=E~A*0!tdVU;eoRqID;X(SxDn8Ax$h~|1EU%eU!4c?>}i3 zvyfT0ge+wtm3@P?3U7WaHiq-v=0};p20No@HP=|0nCD)DAkM}L4(tMz3%{I zXP@i&OAn6`3E@>cH_J4W_D#C?^-;&d0m0)!I3v-|gJbg;^Op110998a$lr)9MhwV>Miu=Vj8 zb<@fizOf}0+F^5XgBfXGt{GFEN{&2y9X_!R*U<1-f742gSx1XTU2S=oesPuyd@+gL ziuwazJbvBX?Ne8qHd~(Kax9xo$G5g9)%5!$V0~#PYE5;FlBT)5TIBky_wduLPR~&u zmO7u)Jve_RU*iM>~Yqu1G;@8+=4He$u*o_P;%&0IdRrj`PLT0iV&B{=Q*xk*-YAG^4eEl*bXgQUPaUk?>TnQcHqNv8sH-d zr(|1OVt9&Q=HqhTYH510S=ZGL8)vW#D+lhQIKcF_I)BYv9C zTwfaITale>G^~(hZEXp0eF~kspWQ$Cl;j%L5$b*Gs4lCGYMG^yg3KDClqD7kRj{_= zy6nBy@*$+XGd*Z0{MLHLt6zEH)q7}7M)~RUjIV}%&s}lq_$az=jmlfpOn?j%WsqTXR zMD=96Io+$liAg0_+|Q#tux|_+0#&%{v=@}HN?vn+)6XH^P0tKSqlu*vgEUU`XEWWg zpWUbXCKF1JQk&VEiq^d1UItq~@#+xVmpa|kdWkw7d3U<|y&m|$ke(86}7v34R;o_ynniDP?xZO2>X}A3qxJb-W(FIjz#I5?r88rsK>k0 z4C5o1^rO6X{2U^HGoE{`CjsCmH{y zqfYnVy^z;)@9n3$X&mN?RJ_^xc}>?nLbx5a!Fsv6mM;v4SflB9JKD;I@9B33p?i1@ zJYahFhSp#$wy{5>R#JE>Zfi@ZE2WQPVUPCns_J{V$uukh_qtBVG`sQrRxej~&AkL| zbqzdbK1qUp+_bk^!X{8XO3MBCZXgq7z2=_P&rJ;} zehn%aU1d__@UI^Cac=6;mY<#BW1%sDIVf!EB_}uG59fdKP3QjEunR!jXf8@l?K*Zs zJC$;}TYcOFu67CLd+^R-b&Qa}S}_556h99orWV0YqW)>GKj7ol!op4W6e=+0@xBe; zv=-3v!KYu*FYden(h_w%MmG4K`9JTe|MRY7?;P%p0^iHn`-q|Mqu6`Y(7W`1-pSCr z=jbpZOvxojRwU)7VjkcfBG<1T&vB8<@1dS3^RZ%Sar%!%uTc@~B+%nUuJB%Huo5X! z4<|{PQJ7PfB0LKGc9H9Tj~YFHRd(#tu{C^lY)$ObeD>0uz%PBm)}{KXoH)cSssY7p zYfWeopC4BvQP*aLK_@#7x-7AJsoDa+glgy#Zpkhu&rXP~(bPmyUoqIP!bfHiQT;+S zU{GtV1=*+vx^`^J*?O3RjaEgikUXc0=@^4?{eAD2i8-|rv;yonyAAysQk$bNi%6VA z_zj)GeSOrrD{oz|9~CnNI;hMSa>g15ZKc!xz_|0f$NKlHnzj`eEmow;o|PYIImJUJ z#_|j9DQaLndn?{>zu^C*B~H_Q-$>1c`!=@-EPXOt%c(f=p>la!jmS2yCZQI(IMbSS z@#pxxY2-eACf4L*eF9snqBTxvgSBdzxLH=i+ZyCQx!*=OOx(&~odTf^HFQS%*}c7w zYL@;LdXdoPo3>c5A)9g%YcZN{&jPI-L$qM6B1o$Yv}*sqv{v?Qf~6{Af5J&H_8>>% z%c-TB(UO>UIdtG_e}X5Z%`IF5Zz#Ob{c17Gu2HcArEY0^7T^HE|bf zoe%%bT*h>Vut8wM4TJvwG4}3pQCIo@_<6tQ$}lhkczH83;9Nw30YfMgDZ`l-1+2VP zDlUy;HGtcW+7@2QcbYY#6*6itqh;E*3To~o?QSif*laIm`~A#l?t*BcC~q&>PS*B@ z;WFRn8L(_W-^cIs`vc~E&ikD6K9|=y=XHNE`Cp2${YIYdPyuHJ_0Sg)XAK=sHoDt5 zntvU->=rkt%UfsUJLR34G8*xKtUwU^dF9H6l}=ZlvOK1d*UhkF7>F~qMfat6F$`aK zCQj#wwhMijh2kSUl zXiD#4tiqw7m5hgP7@0>3dFEb|s_q0!dz&yM$Jd5OjffGLc_ni0bL-vt#BQ%i)hA*; zd>s0N7QONVaLnZeAFbm5??ar}X+qAIe!RO(Gbyy6LH@02?itOCYZ9Q3$M@(hqibhwiQb%DE$1oz5XYZQy zx->Kf-f8cwqqeTEcVQ2#-H=Jz>$|wa50z+v1;|281BT`dkJd82NrySRV`mN`F@7?* zz^sNpRXStDJkP||-(Qk=n5kDc!G|E)$1PBQN29?j5B+M0wOlK&ai7-sxH7HRze$&L za3fdBCm}96G>Tr4c~A0)1LxMin(Zc;bAvzA-_XVJ$8}rzF<2KGojUGZ(gD`;akI-{u^ zeh1E}ycEy>S`;JWoAek*kGKr6-Vm|gBljw(#pUT4!reGM+Du6$^kn`@tm~8b)gBJL z2=y>|vjk;yR++T6&OSuZpn)6n+uo88=f>p9~&<is!%<}pTRz*jf>4T9GO~i=g9v#ZZ zz~`i#LOJGF)2Z{x8| zkEnf`rZ$fFV|-ek;}^LR2_0WK-i31l9>ZF@^zM_o`FxDe>d`c3p)c+{U5&z`E6gJj z#HfwK7lwD(@Y(!ybf1xWVp4gf@V71@xv)*AmSM7yo%MFtm?I0ZvvRPr2E%l;T8lZl zv#=WhL1PCNU_Yrw_SQos>`ta$HL|O;N3t7pu(Nd7S0{kauPWCx(-SzwU8v>#nYx67 zD!!^H9iwsczj79%2Qa`gdLS|03No>xgU0v4m(QGn2jCv z>wZ=91jI$8`!&W}rlqhj3VY}jS8G#uY7P>ksvMTVMl&EodM>G1;f-ndTAV#(9@$mD z>xZ4)-SDw>`aa=e5B1yt+CNO;cbq%cH`9I}a07~SB)h+W&alMassBRrJz(V-?HkE? z*l#Ldgqy09;B<%=%G`zU15L8opx#}^6(HR&z@pG!%9kadc$oY8a zF8AKrY~5kp9(VEA#L7rENB7y8K?}SJzlilUl6U4B%J7JrfnBi}< zC7-2ZD31mHR#!a^Pz-IUfq_YqRPj=Ja&%$@{!<15wXzX8vy=5i}qZ_`=*g^*J zh|OeUt`;pUw3lkzxG%&{huU#RvYBT_-Ym3#CnzT=f-Z9`D zLzyI#tOE*<1YC2HUKOBoP#6Z~6`hs0`kMX3q{cZ%wGKb-lSNOwRD3V4j-Gko9C)sZ zSxCp%QS2@M2xusrC5pk^C>3~ByfZ9mEW%y8pq~K;tISpu-AxNTGhd&*YyQqzJ0IFP zXJ?OC9iD8a>u_Csd+0dUR*tU?_T?c@i7#G<-t=FQdksE0G)P|))k7BYJTT)U;3s}^ z!9sXEQ-4;O@LN}ATL8?fC<^fpdFBA}?g1q(X{00b^)n++yZYIYr^tYG+wDwG7?>-zD08W<3GMEp-*^kU#IfjQL}c+q z=Pn|q^`+wXs`vuFaBJqIn7P-Grt=1m#ZmklG(T|Rp+S0fQ|u`Psa=B-@3=Ze;{<$@ zYW7zKvT$O5Ej~Q3*OUn?DcWvd{(-L%orX8%H&I&UinuDmV=rt04)xDo-gI2U0TYz? zPn6KNO58>v(1$eFu0`}=%T+{LjcL$rQ~KaH;e2(GciTx#8JFk>PGFOs*IKfg=B$<2 z=dWTiq(PdRyEYaniXq4w5JM;G0i515iSRM5f>pDRdjoe%l4o|*^CrbZ;=H49KGT^R z4J?a#C(z^ekcR%$2Mf`_dsxF9%)Asi0a%5Rz>J=*viCi$awz=CG1p1qjON*%{N@r*ZK=XL(<8G; zaLWM(0sEf~N`XDE18uL^MR6^*C*xg}dBVZ`BU6bKJlH$USqF3Q)EZ{Y*WCsDb@zL` zvH2m7sd5U?1y$=g=RdRyUU0%vJ~E! zs4w`7wG;w4-6q@<`)VgN>v;3l4E)dY(>TVgHMxVNDdFd4^!X2==}%W|NZb+mneAsY zvi+nC+$@I{3Ala>IVDeqS7$gI+ zzM>`$cWi3&!WY{&Yf5#dneYTK%QFG11&8QZuLZk$#Jt}8<}Abun1DILn%;G5mL~RQ z`L0a3xDax;2Y(K|~W_202CIxdZuq|rND=DCQmE#{YDY>P2AX>@E{$MDG3{V=k~ z(D29#FtU>)Bb$8N$fOtpgVPu!V3mhI9W6oO#Y8w8~;gcw&>bF(#I~oMY-^y{T``BiiyY-a_3RdxF=McPcsM%~Q$a-aMsG#BaUd0KW^q@^6V&<^lhsZydXrGTslWaA5^;a+cFOSRd<}bgKy?b-Pi-$ zigzy5m2uZWr8#+~fZiGOwjh?%pk?T;dc<>C92d!Nnt-ShUyB#}hGFEgI6C4G%+nhQwD>o4qfvNG-uUjfL;xM0aZQ*%u@}DaNRThYa|&fVUfR{%1m*PuftKx)5;s zZaB&3Kt%0LevZ;vQA$nfjmNY8wG2|g$NCz8TWsu)^(T8)J9VC9_<7QM^j=-mi;TvT zx9-*|+~Q|w8eMttUsOH@{ES)lVQ$73u)Z?*Qgjkuwm(Wed!OTdx_B>B;I)->f}*z0 z3}}7n50%0Hkanc)-9>TU(V)0yb|TsaM(`nGg&|Hx^eHDG^I8o%ZOmC}ZKCq(u?M1Q z+!*>-bbeKRe52Z1Ycm8)2TMUWat*#(W-9TUo0R-~c-N5ui{FZ~lF6ITo8Qf9o&Y#C z0Zs>c3*54uOkM%6+6j+X@H-^Mh_#+rfzoGm4^rHvx+wWotYXvObSF6vzr;kNuvZr8 z-CMS4dAgFPv66G5D>>YAtPrpRQ`1BB*s-R$poIT`w7F?ceMVDp{f}#$J+#`X^?J)c zKy)d+myTE#pnWqRqi7f9&`wNY$fZSMqN3Y2?E@vEzlrBLjE;sf#q*cXJR4-MlF z@F6)6Uzg|JJ5f1uhelXRsl~vTY-k_>Z-()Pi+zb`_nP=zU;dFKNXx#)y*SJRxdMG& zh56gHibjw9+f@E__&Ow)3{S4q0(qy3ogNlh&SsXJ!Rv)h&bXaIzXRe zy_EAZi432XkM`xItc-6+7 zhULt_uWJ#f#CwBF1huXNjMFnaqc5A2H!RpC34J)IAb`|6Cc)R<)OB1T2|NevN*Sdu zW9yQlC(?&Fky4xYY(~75hA+g}KKSSLe<42C8}CcUoqL>1ZPNRbUSa`@sZCQs9eHgF z&JFh=wfP=Eanx7jl=uC9!DTGilG>EWCDGlM{DpY3Z=Ey7UrfrlSWm%!?60}tbes7&S+GdlcVPHh61gBlxE7{};X~MeLk)_Hl^?fU6jA&sI~&#F?3enMTw=dV0R< zg)BG`yw7^Sy1uF?2N0k|tUVtWhrc8*y|>{FDD)CMi_uy91o#{2`MAR~G=W{lj8F+aH*o55YFDk?PHx*KDB<|B`hYG*Fr`Irh^iuGOAb;JDOZg8D% z=MP(*?T^Jr`NNXXgh4e>CF{DJ5e_viyCTo^124H6WpV!EUXp~gg9*M^jDyp;c#73t z5f4IRf!>qrOCQ}id~e>mF@aJ1a8oAZrrc_~`}8(&L}(AcgwEF5au+ExF_hVCn z+gF=$gr2N9{CoU-H}3OoM$)MBao^%pU3vTch?|a{osW2mcU=}=14cLjnDGs9-q0;5 z-rT=XSX^rM9L6nK;5Hq}13A5m#c6yY_(~BxI1o$b%T_jtq9N?WcbFQGu1kHYozRx3kjaw`xcl)~l1;qgcE$U!IF&kywzO9*tuH{}uW6zsZ+LEZeTZkpUZd4apJDWlYxNmwu6}^3!FyqOE;V2;L}!4 z5*Y#>^fmB6+9neJN9-q>d@`QnN@!l&5Nt&2#zdb#z%yGnD*Aj3&yu>t=<|^w>nlyQ zm9L!QmTRxq!aw1jdVd+0p!fNU_3WO>e6qe+zY>tXlpD|Gka?UT+0TE+Qw zXnh*SY7DT}^uVvTrTZnJH^MIa;=9_CjGJld^>C5BU(=avex*$NeUi`b<$THJ%@vzX z(QmCC`PTb`VrzHGF=OY3LP%qlo6d_L4Q}@TGa41)TR}wJw;D20-~JJr(#H&3kE0$;Z;}~Bc2vnzWitf zV-#EB)EM#h_;|Pfn2CA!2JS7ljqNxuK0oO8TMf&zNylhnc_4*V=AGSeJf&j; zzfBTKhX3kN%hp-VN7?Owe8|n2^m`Bo{jzujbTj>Z2Qu-b>^p;Prj0oFuZjOP*k*bG zPx2`5=66Ub{Le>kglpnaq}JnE7JYYcQ0k{GZ0##B{0_XYJcG{PgkLLu_u-B$NjHem&Iy$3?o6ka2axFcIp9pn}6(K%K3438Ob}fSHv&F!#tfS z+$0_nA>^Flj@eA%b7@)v8X-9BA4k9#z{**tun(Q{(iz|%VJ0P zvbd#xOApm`xh&fIHwhGXqI@QtO})oV#pJxWxxb>y?Z35pDTjyQH6H7Ss1A^(zSFbZ zG|Mi7j^uf9b^jID8$Id#?%VPz`wzHw^dw}*Vjo)J7SuOb8TW|k5TI5abo_q_`Eowf3um*aq#p`nTj>o3+*b2Uq%j=#Ck?e zCYG@Wz7gMtRE7S2A6D0mv4kNZSyz6*zq_clR)?pbC2J4H@sAg6+~{58C(bb^a>@ul#_SgNZ@ zY$h3#;Imu;8F6AW5A6z#MSV!0Og!-xJ>rN@9I$jT)=_~r<1y2R+uAS(bR~7+RkU5c zfaDqJ&R>X@z2OznmaB^-4aw^&hug+3Io73fshiKP_O2c`e$)|lb54!^`Mvf|C1+PR z1=r=c^4yMDTa?92{W?iutUZrEr7V-3B4wH+`)U`JL#C*tzTKSF&w(0XLzalcF88%1 zExwE6vi<62ZWFZNLR{p2yTW%V$&ieAOx`7%q`sJj-Jshp>DZ8Jqy~prO%2h~%x$I5 zZBlvjNYcSXPziB;FPl#hc+>SsK-o*cxr4`BkIb7-@z21$Ldqe!rcOiy_(ps@tZw)Q z{Q5Zj&ks{bTaS3T^!Isaq)`31f!;Qg8GLQ32}cG@r54^wvT#awDkNv3x>^H!`3y4l zKtycrH)CIoMGvHXS1z&Er2m-h3Ru?B+0HZe>AxRB(RWO5GmVWH54p4vH`*m}-yoCz*Wli2lKu(Kd!y-+*f{u+P#P_H zAk3!52FFFqy^3=0Mavw^|)K z)Jr8OI|N#9Z}s1WyQAgSpqvEd)S=$+OF~{W@0UO1T?wxj?uh0+{zD!KuR^pbIxl7L zGB_z(cRl#g^cyRBB{k44v1)=0z7Y%m0yJ0Xvm&Jq-3ti~&3!a7SJ+!^g+>WuiiLhR zeRrlW+w_%?5AD!dk?d&c34N6Y0ou8=Z%_43#r;NgaqHl}#({Oe2Y);8+<-qH{@%pj ze*FCge~0n+Tl}@)?+^HE#h--SnFpEmX72uX=5Yc5t;}QBoeEJ9hHWWnnRC;u3)8Fog-c z&;OM``xP0CK#xQVESX|7(h?tOMElc${lSj_FiYBh>bpjYHSG~ua0*BoVw9Nf$@_K1 zy}2o_q#7gHYEN=WCtIQ3B8a~ovO*tKUQ8k7#6Tu`K<~{5qwSrHxLS*IS*_9}HA9b2 zdcQ0(`R(}5_(*Q4eVM&Y-WE^eyh?J*66zB={ipnj9KAG=Elkh>1JK$d=0v&Hu5Cqs zW>Q*1N%kMr;4A9~BxH0!ryui#NaGi~rXuetXkv_phvSP~l0#G{B-q5R=!c_Z}axBM^V?}!*TN5q}c@{X;DE%3jT9~*IOqS5AQe~jBA;N4Ug z(H=cwXQhbmDUW zqG`w0ui%r0eqnYrZG7b`#5<=wyni^28TkiV{C-2GrK^0-beH{I(>eIzacs^(`dyRD zevYp7OLPq&umRan-xcQ+Ok~7kYc7sOo6sCYw8i_ z4o)WTESrd$e~i|g-E}og6gO|3W`=? z9$PHOe9FLg8~)0*kv7VEpFk;P$k?YTR)#YAjMd7}JA-npM32}$@J_|$WoeIFu#aP+ z`}lIWxAimJThx~q)xW2{U4s(|(HF4VIe1RUXR$7q#1F&AtEA8)jt%g*9h8AZRU~6{ zASU!K>|Xa)_lVsCmKF4E*NR(jRd~A>Z@X6XK(Aig%3v%F1J?!myJO&cVOAAgPwJ_S z4F$mMs8~i7zm7Z<{JsKD2MtlZC zz(SV6H+HdNi-tiYQj(DpU^8&_l7H-zJFGR(X3w*_-opEq zLE|rameKp!vI4!cW(In2;?cQ9>>|v?GMwbGHf3P%3cX_7nI7PjtZ6T1_MokCFnFN((i>P^(FB@lmfp5Kd5$CQ0=j?flVv+*zN!T zS%~BAX*ElMgV0+dA}#~vYza;v3#I_7L#@#Kr?!}Es130k$HM-GK0nh3z2wlR;er~( zB`7Fx(YzIX1-ON1ih9Lc7`^ZQ5EfgNQ62Rh%;1X{*?9c&h;%fZJ3eQ;i47@`Z-C}H z8)ES$)N<^B3rC^zhF%{+d_kN&fw&8F3?)%pfJ>sSPg+McW!Px$j6VI5qC=3E)=6Q* z_8Iu@*Tp*q_L}CJPq5O4t77ROjoB-;C<+~GbKMR0_uL<04JikrLvs>TqR&75;3-aF zSMf5>ldD#{5fiE5G;}OIkOfoS8F{0k?m?WN$NPATk1fObIR~C z8Xvl~OW)k!PIfPLce6t3Cxh#3*wW#TFbJv(+?nG&Z@7(qTcCERFdBVpOz0EkT(kA zy1uH?vYih>8cX}LUz!#bRy{75Vhos-k?kzfSU2GZJ3l1{P!8sI}TQV8ny$ZkS)kTUr{RaAVr3ZYk zzLL_IhKD?l?qEYldg%;QU(`46c0H*dt(!7-XjP|hqeSgt`X1#7G-6T}F19Bo=B`R}PJh=3 zIrX)zr#MpIR9RWM7ZmiAK4>ugB)1E>);?8T#a5a3!NaFH9kh6)4b3k<`ubx#y2T!P z(?d75=`~`UTCU&5?vlU3?0Twb$}42ob#W-1N%SUZL$`P;Vj?lvBN@FR_+g|zJD1`3 zV<5Aja*M}y9ori3df+pZIS0ynD%vyjYwK2Tq59$LFEEHp2`T;s=prIM z(&{a$MnvxkCS4$wSkHTv%rxRzT?u`DjPCW`Sf8@4ypGmWUdY>$=!u6;LJV|{n9$pi zM4t?r;R!x9XiAg_40MIIDts%WwgH4aCk})o7HOiSP~+L}AM454#@tEuCz#M7a4~YW zy^Vdtr_uD=5e<#+q+4kJrTspxAaNARj`c0h(Q_Q$?u?dx&b~Ou7_I$Eq^d~ctABN& zJ)5&8YCLJsi-5f3RZZh!esnahL&g1z?A+lElhfTNl9HQZxCDMwE2_pd-85rELg_e+p|cwlQ84V!On8z@suli`HEP*;^cT9p5{DXZm5K zZ)H^P8#`j~LEu=@hDAHOVR1+0c`~o=UADfeWGX0$MANeJMUA9>IwZTBUpa7LhPEMSy62;*zQcTKsx}Dl-(7W2}J)voS{`w*$3(Pu7^V3(r_;Rmxt*W z%EEMZa>L+}H87#y4t;c)0h|!Tr@hjX=T7vC+sK?L44tTi7oUmKlDNW1Rrl=;r$ z$z!|YoD3t^*XlVvG*}TEs5TD&;~L6pH`z=9#)zEfB!%Vxh#s`6#5a~iU>{SmsJ6`? zD^0e`dPS$=N6U@1CsbJg$o5U*$UKvyxQ^ajpqx)bi=A4ac>2J?uyQV!UJ%(;I* zrO`3pp>HCQ5HOb4j>a5G1eVN(CiLz@y!E{}i$07-a_+ zA}Sn>Z$;}!Jo*|9a|CYcgkvV*5| zOhbdMkCXlp1LjDa71~dJf_)PEj{(lGu0C(6quw`V@T)DAN$nuh0@uiSW zJrQ5}_b0YKAvetjj@4}6YG?DI;R%dQ6?!c~@itZHg~&!=+dbmAA&SK<1pe4o^yW(p zS-NHjaXnSA7Hxa#9CWzgyZC(96SPbbI17xW`-xsbWj_9twq>z>(^E5^IyY9ITv50c zQk+-<%Z|>EpNNQ)QBv~MpPsUz)DmuoE%qGAlAMR!<7}Bt@`U86MI3`tskA+^a&k<~ z35E2G2l^nJo{~IqQ(&J63AFY`T3d(Oov3{lwa<^#*3sG#`1Ac~ZTk1}1F&GV~_#KeSTgTr&QD)Oy>IAkNa z;eqR88*MkwF~I}2f3>SHcNZYLQiWo`l^+|bjaXJ(TQVurg0IJhDq&CM0)>;dA{H>Y zIMuR3iM_KKQKvP=7wlAG2=7cCq{M& zqoOGvQujq(6B07M4J2mt22`Q#5w}47JyV`i-BC(^Ul#v4=qw_kPlm>nRuv)6rR5j` zk(b##FDI2ci}X&iLxpIw&k(&+;Zb@jVI?2q!L}WW$6L84u2iv;@hEr3>>?pyXjm6m z0*72Lqvc{E2|X3j9;NX3-!ob5rHjP)**Rj|@(8Q_Gt%0YEs*36M)?Eu=?=gFwTV?* zvZmzLsEN)tCYVHE4*fH0y4zCXP&XF;f-kG3}jV{LuYHN~uz*v@zg*d@I)V zPQ%HPfc^9v_i(?>xCZN5i^crC$FNgv-C%ox0 zrH=%+tYFil4 zKP#f^LMfpq@dVw1qfEWz6)7x2a6+{IJeAs7@57jAEM$3VT3`&QrYqw1Aqo5@ve4~s zA4n{b)DiUKiulqH+bBWQs^k7;_rL4cf>Wpo)Yut6(pe+GC>rK&WkX)hKG`t(v9AsNd*g($&~$-Qx79okh1eC7h8h3C?(hm?L6S^!%fK z%va-H=|)s2DmSCQbRDmX12{FTlcXc1J(1O|s!0Pu<_L{DD~Q*Js13&2fl(zg%o*)_ z`p|VvSu!FW!fvQc%cOHbNU(Joq!WC1;+Gjv?JP;l_CN6o6Sb6x!1krZb{af)DuM16 zKkfUw!1=Y@Wnp*>-Qt&!#$OeGAGKDKh5kIin1_A1K7gK6eoHJ?NQGWJ364w52=sJg zj_Assz>L$Cz6n2&bOiQIzvIe7EXa-Hze%Oa1Cw@f?J&cOnQ=B5pj2|u%2{rC9^G_|ja zzZ^J<=wq5Ru8X#GReTg9=@DP;XX@zO{RWoOZ`!m$0u8db;N#1PS#}qli5nZb;j56| zSOWYJ&=qE;{1e;?%1yco_=Z1)5@U4VT?bE35TAzCdym-CuYIV%30qs(*f4;qrEJp!h z5ZT>GCOD5GI;AY2H8)2s7_uBgt;;J(*4M$XFs>zOq@IdYLaU}7Gz9$5LyOAih86Qs z(kiJ@)p(H8pmWVEtSPN&(}e|zTjl;C&t2-KdBh!y-(g<9%=z-s>Pm3HtZYE%tc9)= zF;>-{lAVf^)JqyS!b?kRJKz~ufi#fnSnR-N>{>!4Us%Oa6KC3+oJ>wIS>@d3_Urc9 zF1K%8&q8AJnfq<78d&Hx)LG&X1ZYPDPdfkR-o0czcN6-PNx^s{+YBtYl;u^m#Iwc8 zLYHnicq-k2X6V9w=o~-~3$>^@p21BxTsr0_r61_qYx``ZbepcT*#^>J5@*&bgeq zc9wfF?86fiNDQTa3lUvUnFl&2=0m=8jmB8;g50876Xs7ovhD?i<>VtDzRxn=zdH^3>7|Zd1weq~PbG=WV z_xXM1>uWuBE~seUT?8$1wvDSOn&jm8X6Iz$B`Kx#O5$-8(OLd&uO#(10bXCIt#;}k z*(VfQ-$cw~B5mWEos*nil2odwBc6Jt)H0bUpfTNu@+A1G!0UPKWue+B^?H{;;1qmO zXm%zqq0-n5LiIXk+G4xa3A-AODbUxH`JX}L?WKYqYjFquD6COla3Qd)ys)~|yx!tq zU=>#3AeQ|OWnPlK5S}M2Pg^SGCAz|mmQE(gZdp2D=_Hnysg6}46CxYPP^34ygT^9y z_jt4vA5L>T>G-vy$I;tL*G>)%xO-=j(1jszrm*XdKo^4v_4nmJFu`GUnn|kZ?pdrS z%fW_{`y7tpoyi*W)=O;az)hzF77)KHXK~g`8rRxSIJeuFQ=9C0Pn$`^l98L_n(y+s z`o(7u-OL`88A<4)K?Qu#5okzTN?B}>d;^q`NgsSV>~#?1W$|*aaVh=1(AyRLJ>RP< zF)joDy7G$X8yrimPQdZrHOM08vY1FEB2|~g_&!5>q&|N7jFmm&6VP0-Iw)Tv z%i#d8it>x;IodCd5C4_w^gO{BXXBhZ@h_siBA00+5ewhm#OS)##TDO;%mToixXS7NJdM8)eCgI~; zGih7IeB9|>dUh#=0fs`stmwXkM|$w|L$3|dHfaAP&UW;d!U^^()@>a0DlIOybpKMe zw0o(xRi%>T)-lV8q|${b^7O2ah_6J_muBI7ObWze-7gOgulqv42I*rh%hsehz)4+6 zS6(`c4W;%vml_GhNq0QX7!PkD+S~hMi}q(`v_JGc#gk?5u3|)AI(pNc5=4}M_pMs+ zNop&2J4VU`Or&9^tCdAxt~)Cn-w9Id&7d4!8erQ)J#&W zinKJ@r9-^+{s3Jcnor-;{Sgtrju5@JmA53dbb_ygbA@cIN`{Prz~5+h<+7?%&~oP! zIc^N7O(k>~m9um%61p^~D5Vm54zRHYI)U`}joz@(Oz$Dg?GE7HV#^~BGHE&B(|;OS zP@*77H4A1{7bc;!#=89froaX`XtP9qPLPQOd%Dk;sZ(bvpXoX}8y;EP?P zF}AP~XPT6Him_W=I)(o8i&Z3(I~TT%`J8x@Y^o^#K>=-whMC=!daiqEMHMDt+5YH^ z(Ojh^vnC03yQ})S?q$S!SLePeP@U&5F56#8-&>%au?aL#g%kS)vkd?FGvBJ}uG(rd zcCxf?p**%9pF3h57Z`;SvoP|F&@w2rbuA;A-=HoFc@s@7wAp8r0q?+VU(CiKOStdw&^ z&u+66@B#b{Ym+~p)zbB$^=KWeMd+)r!aKqhH|70wUo(;ced z@LTF>i-fu`Pwnt$Nj%K%F9q7C8P4b)%U}Zp@bXzCbv7;ccSNF=!17`DkRIcpIave4 zJFXD;FA4PyTAj^+lJO44h}lU?DxE%AUn42>lGvK&s3xrhT3eJm^*^Db0;?p&O2d*O zaG|ncW&~a@hxaP&&#n1&wZulp3&~`t3cVpgSF6PNo=qCGJNMgq10?JF0L7?DsAAw> zSQlD%i|*6065{6O6owIDUfVLqo=nb)lW>2MAd{nQy}Jb*XUh%jfFJi-+TaB<*(oor z2hK-A+XimmdDAiX?@I{zf7Oc_{Mtfx`baJnUx!@(QSW%wM!-4KSy+XAUpXMqNJikw zmrLPUpwL~f4{Ek>Rc@<05oBYrcAMX)*Tb+SEQ;A8Z@y38!GGk3w<+=%509xR88cGy9{m!uKS6EuTWa z^%MNSMfs8voSszXo`YE*gE{{ztTncl zZ$27FKD4pt5fuls$(lC-CaYi#_We1j$yQG4rAU#+THDv1a-^AhInoT$J)Mk^Ou7`1 z9D)fBw(Ugtt%A=N^s@uhkKR3;Ye8Nd^8PzY5#3&rMeZm6QL=aFj{@zR6uo%)DC431 zW4xfwCVFh#IXQAA9u|2L*s*HQ5!zRe6loS|CC0s}oc7LZV>`(tNsvs0H*t&!-1{xE zLuTGY5E+`#UVZ{z}SRO1Aq3DNy^~FSzjp+D~*M} zU@o!gcB8$wbt*ZA62&OLeZUI8UcCP-{4`q4ZT@*SoBf~3a`U71h<_Rp^!xRz?9W5` zIwf(R?rnXwy~@4*aj>4P|G1A#=lj zgXQe$_CE`mi1H498025VD3BW|z&WlVFO3+WSxouswCam@SS9hqiSCC=Wv_?p35+&R7eyRsyn0wt!@-ktgv;nu#X~ ze4WY812b`PWC82;njP@00RE_}<$k9eV?+B{iomZc(SEihpaR-VOS?e%(VMu?8S7Ay z*gTRh4}3yf&SDX*doNmpUJGa+@HS>sUKj5BUIw&}t5penwb>R1-a|s?d%wfj=~#MO z#u7Pr5V3I8s17J=qJG27(o}iCj{8>@-0zHmQjWClNX4+HLW=Y=l_JqF>GkCAKRi$K1NQxU-6|kl5Uor`PtBstt^$u_qv}6ge zVrG_zJ`7-fNe0I6{B#a*ec%@o=LxRFfoF?kGKFDDUZb5s+JzPg;?t4PZ{YP~G;Vch zyb}14h2&!y_z(1Hsgr=p&&0SR;^&e5&c~w^(ytxqn3Estzxe@6X%(fS`o-ny;+ zA0idbUq|adeye^e#^RKK4panBaK(ruJi|dU#s*(-xLP+l|Gtp=*4^wN*-Y?fj(-E= z&pAh0rFTMtJ4HqxpF7fk3In%O<=2i zcY=|QgCI~y=^*^__@(nREBgDlg`l}`b`vvQD+X%>*mp9yWn7u_dr;d^D-es#>9t9M zo17GX9oBj}X41CMeVaBAEkiWBKQXV z7CvE*K~k{@9^}eMU~!?1_^(H8TIgHUS^RITV4w>L|4{fbO&4r)iPKL=RaKFNEhGdQn9LwS1rE($8wES?FV9Zc=u#jnA5g2o=t$xOQn=IpEM@+_-9q}1A zJ0yAE2**$#-ZeA31INtsNH4gPa$wcWc#_7{Q~!?=aGf)V1ZO;Ww!S2r0y~SYashhy z2>8mlIefVUTw+fS^74^e3eTw;(uH+55UH=urabGmDbN2*$LXE+xw^CBvtdax-Mtpl zkMBwXx=JQj2P%0n)^xGM>zv1V9cKZ3|L*8;e2YECV;y5y3FwGz{VecrN&}4QCdMnE zA8Gtc2GJ-XHv)z(0gcIoegmD%7un(W1X{m};?uCBHaK4dw#=BkYijM@m5{#WYBO(w zyVzC~T25(RjCVpz=~v_uM{#ilu>D|!nD?(SJKnSJU%8KG?$Ty|4fq`{4?HwY3ier6 zVO-%MTUn4~#RepLDUs%p%te8?8fIFW3qD&X@3ws(G-f{BF3o(hos8dSD-Fc`Jmq2L z&OSk1W1MDi&8}JE+E%mM^;yk1mwJt1~u zZ0)&K>UDd|W0B1HW(+Ld)Am|%={qQ zFA~gY9qw7Lpmw5Xj@iy7j&07}j?bLu9O_EL(%F?umTs%uz4Wt6)Ld%J^9bgIApu~h2WRdvN_OCgmi2FQ)bS;XA{wS6@gmcforiD+kzqhh$?&kuN zr?p-M=a0g&#DdiTXV#dJ1Yf7p3`GZKH6Pq>b99Bk8=e83sKhRou2X)4?cc#G!v9!} zd}GcRf&?Yp&>g^Oj5bvmLz&H(F{+*Z{@8Bhwss>wX}9P9+3xw<+J)84Dfa^0dNV^U zh(f!aHAy}3&EskkeQaHFA-qKHiQBF5Y8zzR#|0DKU?wLQl1VY(Z!18{vqANQJm_{J ze|o~MoC%UHW0oW^3A<~rt*>jpeEYPi9xSi`+1FdT$Z+jdBdle93VT0Z*TI) zI?Df+;e;#60<*avpi?fn_1D?T*M`upQnVR73*7=gXwr|@1A`tkcVG4-n$`bZXsqgnQ z|4X>vz@og-C~0K(9GD4C9m*fqd2Kh_e-G?_=g}B=M}+pkNe$80DCH8IeTOKq_DRNLb{5;Cqaw%)vF!W*%6^epcU`)Zl=46sCVtla}$sHGPFaPP*` z-f29UB;I#c9PHgzq-i|mpUX+e34cr`dYBvZ8z(9cv?VhSFEcDJ;>gk>12hgkuq6i5 zd`!K}Gu|iPC55L+$xhaz1x6YRy*L%Lq+nw)l#D)(A_4T#cNCsox5w6}65}3VYQbZr zY7d#X>jE<+4Y$F1!!#1>Q@48z6x}YsPlfgfU&j6u&*wdOeuow5G&w2b`Z} zO=^35W3erMdkPstz7SNt)zNn0mzU^j7LL^Zwj-6Ox-v8SgH|UyMdj(VtGu0Kb%m;W z>0PT0@a0pp!WtKlwL4*_ zX*C6Sj18(CHRXoo>Ci-PUkHp{-<}3ulS7!3P69s{j24!7?b?EcnJWWxGM@-C(5s+z z%4#05J{!RdmbizxH(MX?U58ymIt&+7dw$pDN|&|&GW}1dD$$lfXcc~y{$Zdd{SSfF zNRJY%DPuiWrv{!RDPBoWHH~*PEOIizqhc#2 zL9Zki(5IbgB<6zB@=M4stPHR}t z>9GkOt*5jwzF`z}O%-+X3snuHJ@UFy@ROu%NN7ydZJj~tp`EfL);EpL51{fL*1P9=KmHXgi4b74~8))?v7=s4pWl{*yhZ~?Du+gVSNbAc0F*&RM1 zBPDVB1)1hde4}iK6z^G&WII!D#oHf8_|o7j0_}ASdd;G}TV)xP-HB0rcc$KdQ-D7) z^u-wMi^_K{naxYY%2Tahl{X%`nP0aDdNe+jCnWs1+l@xL-#_nR?)na6q7XM+Khd|? zkXRq@U9Z2y(KC9m#|rH>mFJg+OnOf2iEBJC^IoC>BXi-;DK?n|2nzvvRPc92GOq>4 z`0gN}tAk_rJpMnvmI%*sW%|x!kL{b&Uju(p9~;*qKcxIjMaT}s@tq~vLH$@uk81y@ z{3Cmmn|TK7s%ROev>C$AqBh&{z*A{HkjM&Ljso1cEZ}Tj9@Zh;g&+W`N0#?-=iF2Blg=-Y9z&+I>8c zEV?EzIh$?&Mr#*@{ZSvnTW#lph!6%nD=BE6QQ#}3VnoyXCxSjELFof>->)5(r3zn< zqXM$pVcEq4;F1{IC#O#iXmCDG!f9(vFAA7(df<@hnwXvz$Vu-D>eYH_e%Jl!VZ7H^ z^3wAH1?k@fZU{x`qXRP`f4?G(Evd6<0^0WZ>FR*A{Xv|%^U}Km=Y&M$e;L?{GpoUN zCK$1d>C(W;SA#O~`29W*S9(*3D~T_ygG4kAInwC=wxGI{>7r*mwHQ*B_6t;p|55x& zw1nKFB;;rKTLd)-Drb$KN{Af!RBxE-47aVZ+ZIv|{meF5TfD@eNGBZ%OFPm8_Qv)# zlujIjx!1J+X$_N6(4iuwsl-`EUL&2!$GLHCX4<=$<9ae?4)hYSL;f8sHONhi00*#H z!ni3Mc*#btjIafbhOxo!HKr1(tL^2wSI#5UiZW$h_nMRvSo)JxTsPE`lre8C+`lFX z)Z6F6KNknN*Z3}h$|5 zF6nLQHAqA2^@sN>k*4!_t9&KWD$Mh(^irf_Z%Z#idN|GoIGgz1T%@VbnOo(HkxslV zJp<{a+tT?+kGd^QbzP~h8O{$&RZ$XO>o?-Om=IBbL!lxjJR4Es$G2wWj2(GPzn_4& z6VSgOOXQ%0e5Ax=JQI}ov44G#HPiSRwDml^{RV0Jd?%i-k37?MFXMUIPueX&iL*nB z+uAyfG88Uvjr}Cj_adz#FH(*H10TW2`SJaSNZD>H{~przpM2wfeB;1RzVQ~yP`JPK zjYg!4e^TcG)Oi(kRAlqWS6@aMT7E9xynyE)=Vl&qYNGA`n8#wYPa&_Zi0-vp-+3JM z=w7>({yEZRx1}FO`sX8Q2U>jqXXc=ZCLSkJ&-zt$95@^F9ZPcoHr7cIn zFa!umh9#L%T%tA$C_RdATZ*D+t;M!8AQlorCJ8cCYNcvDNhX>3UiX<``}X_3pWpZQ z2jrYHXLY1MU{a>mnqftaJ^#*n&P;kYay8)X0lZyRhFI9z2yi@P z$DwbW!aaAFNykieTsGvmz^byTwX4dq>d3!vds$X(E{mKPM+7wk?noW@ZfSZASGYdU zbUwWjDWgiuR;1UKm8Rp3m&QwB9a?#-1=h_4{^j^y-#BNRUc)tI|8%Nd?RS)MUSs9o zpiK>gDr?52Q^<{ob@A+sjcgv*w(Z<#Oq&DFAZA6{~- zEeE1(&Y%5rvI+7*V{6Umqk-qW-YT7R*r)csR*@9M*X&g zQsnRX{J+Iol=IUpdt88OQ7PAgoyjsDgJimpfmsJ-s6-h~Kz8Ut|4|>VfDMG&ncAEB zqzO0=28_x_`1d+~=WL3frlS{OS+y#E>XDB~UKmF|*=l;7z%jt?7Q14I(y@{(u1-Q5 zA;(yLEXEX>=c6k8Hhk=6UbO(uW#ryTDAX+%hELFbQkn&?ft{Wgcy;MY z2WM|~D9=atpt@hx4>yFJ;rs>`_FXZiW5lf)pL5vU28DJ6B{ka9#8U zPn12aoBi2E&brExig&fyZBu>hEB>AuogI+^3tq76S>Zpu*|`T}5xI9zI+E~~M1L77laUpP5DVBx zk&qH-zf`85zYFs(RrVBo0%Sk+doOUN4*|QE?tB<61ok$H`YfDrTz@PG0%rEsL zl&dTeek`RWo9T*oIg{*@14fp3TjCPYk$&D?{!vsRL~gb>$J>HCoq zl%Vzmn;s6$hHvldt&p{BwZ{}pY0n5W0T1&56Dm(uD%WK!fLX(0tK7rxHgNMhs?9T@ zjTfjEh>ouy!!mOWQ9&rG{;0Z4!#?8=Li!uvqlll)#}`hPtO!S=bnPTh9wv;WEMQK+ zuz}ba)Wm`g1xE#Zuv#EVsEs(p<i@p=$L#qbX0=Dy2gWg+oqXndcdZIkqvy9!kfeN1s=!G z&nnvJ{>N}X#~ko^d7Y)G?~9RGJwxLMLO|D<*MN~dwPzYe8{?auCub)3cjFg@Ime4z_`twr8N)s`A$Ac=s9v-$^byh-i zVvE)@$&WrUZ*!#jpMXxOv1z?VXyJKeV>HDB9sNNt3IG2#$iWx%bs!zHRYCXIkuS}E ze;MiU$z5k_Q#>iYIL}pHg@{B#_wEZ4@|#_33KBo5C4jT(@t(WN^!rRTsr&Sus#e4i z__Sbj!Q5tOLl3OY`(P3B`PPEpBY<3Yh2`MI<_@vENfXWkRCQ-^|Kn!M7A&;cM5UVK4Sjw zO9b1k54bIbhrXr>BzhG-pD`Y524fDu_bb;Asto%I?`nx}+6f!KQWhm^idlMOhj6d#+5xRSiY zKx$bEYC@wG*U)Q8|2%Ik3mr1#)ukMWhm9#I?{EI@wei3oBmsqA7UCAA9QXuwi^U<* z)oC0sF&cg8PR3r3Qv*i{#BuW!#8-f0aTf2-xONEfA4M$Vnm4S;();7f=D=;swUHeB zf~gRZqFU5zIzM{fAYwfaIYtB0i96S>yPLb|@1fmzwtzI zYgF(L=kn+apUIfZx5M`%olvYLPsuRmA3aa2egacALyoa1fY{Js6>g3=GqsFX`3P)9 zG5v$t3fQT;xwbs~{seY#+7+Z@ao^`B?6d*}+#av#g{YS&R6 zyb+K&fP;f4*^}B$N808%PZ~-^R#Bzk6xhsM;8%0}80W}_ky8fNXGEB@85-i3-lfJ^ z?nBSByeR=TFVWB4lvfuIYkd-sEJ`{1MU}hyW@5e|ovl9WgRQHrjN6AJHIh9Ux;4_ zY!k~3%Pag-@YSbrh~FEfJev%Pe^ljBI6{iX94R48u49xeYAxju)*r`~HFw#Iy?nw`?(GYZe{}FE4R&`UTW_nbzppsm$>GdgpHTZcydXpM(Eo;Q zd!DOq-+>ZZ2Bn*097AkSdTcn!B7cW0w*tkJ?>(yVXql>6-IBnXAsxIKBs>Q+qYE3M zV^S6aHEi71&(xkGlyVOoI)%Q=*bGdZ$&}q+*DZNBr4mBg9~H3fWo&o5t%y=IV_c=OeHJ;1lE<#UiR-F~>wk+BWJ1&InU$Fe<`KwDJyskk~d_JyQ<$UsA_@YOKI#TTKceuub*dQ*(!Ws&$8&_uPz$`N0Y$e^WN z*mz^~#uvrBJ)iDg1D1G`$tUV5KTj^uN(IpZJurzlf}bo)EHn}iz-s&Jd8$5&fW9#N z*X^|@jyg1bg3Zc&3Yx`Zk*`BX9bfhch^qG~EbQz5@oQIi&)oBSd=38P|L3p0Fg*Jy z`kEGBgI#dqd+$cR!uS4;?@T z^&W6Co!PiBicH8>wg4Gk=7_7bEr?f#4Sd#eFr6;+(@a`p_&DVaz5w}#@~uCwP&EH1 zzq{mvlyx_+)IX|^7nLmq$S1D!zJUy7`kty1))J5X1$LeBCqy+OC8N^HXbgq+ljuu3 zuU>LrPq+zVLpr9Q55|Z{9FZKC}I2abDqC{9Ql=B*rOJoke@#o9sF;<9T;DS z-<}kKR>Pe8pL();&&ECf?>(tSPY%Ln^1xHndz;W!M;+=uhSsF>Ns%wny4QN(_pw>v zUHYHCw`ou3|Bt?meeXBX!}9kECJa0db1u+=#M?I zeNghkdRKdFuI;^wJ?K$qV33lbBW7m(KtFP=(~hsg(X$a%6Fn0NrXDdv zRZl+L59=~woH}U@VB?h*4YD61iomUy??Wc!Jb|(y#8{OJ*#fX2s1T)dLqL#Mlc@AQ zIGzNHs>#&w0Y@CLHg^%2m~Fy~Qj=L)q*3JrsyoL)H z@hq=$mh%f1crX(=TP#XtOxiJiwAuz9SoYD+gA6Rm3a}*0(O-D)q2TL#9^TVVvwuN! z0dXR!J>&4viMt=(BN$H_1yKQg5c57iny(OlvG=m^G-hhR7>70d^pp?yd+oc;g>1TL zN1dK<+|#GCQcmJEj@8S`9hr8O@93t>#xd!x@lnfHjXS~S`)6rEWIATVVTbzSCPy}V zTE-o!#R5nYKi;G9 z&_GHe_?f4RIg9q)(6uF4$@ zusK0FZ)!gf+`XZsIoXgq`lW-T%DTDM*DDN6VI{`(l)%Uy4oFcd!5+CC+8ytHTZa2a z-;}x1dm-apqdOOW3i;zo>2|Yyt zO}_BKpM^d*%oO7pU2To{Cw@4$?iQ(RWu}4SB%##+ANIR<9GYno!?5Xm;8ukX9Vl5XVs zz8jT_Cg$$7k^k+@OXN2fXDW~x(@}vutcb&b?$iU@nUE18UhmWp^~VPzu~p#oNSaO4 z<>M1xF)~%teAFQ8a8ybRtDubxN)L@{y3-&rgMqLw8N5_iq;7D(Qr)pSjWFA;((3B= zN=}QZm<~7u8VdgB% zZlFx8kJOn|rnM&I7Mio9FBv&1uSmCz36=s`W*L-j903AGk>@Ed%Q`#_+Ac&# zWK~P(E@Cr0FYU-V&@Y)rZp7?TSRSq*&GR84p+k|q?0%MQzd!lNZ+3@wQ*FS0w*RI* zE#i7`u0ea`2OM^m4NbQkC?G=Fu_I1<^7`OGo~{z)^& z(yjSp((fT*!zWU+%E2QZqNh^9ZiHnIad!_ms|LYFqCcTvx8llhz`0pj{g06T*xQw? zW>AX5FO20MYd)IEGGslIwD#1>L1`?UdNlvU5WHAffpkRAK3{2Osg?BAec_stG32IA zC<7}G*EZ{#m7dGenz8sMx~nVP8)~oVNBMugN1@+>f7gzk0$QVA znh73Bnn!uVsfTq<}jcoHR#oW z3Ke$UHxNCi!Dz28i9e9zj(=JZUp5?uoSd-lfsz*yFSw3R+?Uj(d|J`^2FCeLu|<5d zzIew-{o^~HbL3p)3hu(m;#~tdLM4#RRR4#t5-Yq)WDYa! zYyiI&BBpj?Wz=V3&t!d?Od;EL*vyV7LehI92wsuL{_n?hZTTGo(zWP=W%*t6VJj#= zzDJq|g`S)CFW7fUii71!*|tc0h>=v*9W37atHxMwdXVYTcDVg9wg{3fo5&YIq!0BYy0T zio~|b?nFaETfDd2nACQ_U^gn-CUxyDQMO?fLQe|fWZ^EsBlv~g%kQ|zkr3fJ2+KkE4B4K6zp425-VZtb zd8|KN;XM-tG5J^voFTYAC*o*kG$d7yRJ$23Uo%c&DD-?+SoD|zTIbF%1yf_ zzJ6H9d@@<>t-#3GWVv`iQ zFQ3&3$ZSK%1mO75#zE;~M8MyjIC@sbyl_mp0=fcZnE~ni2ugY4YqS;J?{OVtoqz^@%Ui~aSI^q*tOMlBE`Ebz+#RSsYj(xYQ+`grEmt!bTwPF>U0$4EYT zI8wa(#_h;9xV5mO(D_`>)yJ+#mm^snSEN6Ozflx+8)1W>`!0`UeS5qltg>F+YGEGd z)yJ?8H2k)-csuP8mBa61oX}35f^l;1@H-P{$v9gz{MN)-63)tob!|$~-jV1TkOszn zUH07r%aCpOX3ymA<(Q?8ecFB4)f!dgvp9d(z|UObceTEmz|UQ~C(d&LIl{HR`!d_X zfXZ^egw44e*~c~Bu*~ zgl6Gm0lsK|e{g}d5V?`Zq~+sgYgXrE9NEW5T$+DtoGNL6o&*BaR?wE`_QrgOa{M81Q{9kuy za0lf8N}hPfjsJc}*IDjvtZr$WXyuQMxV3ffOnhbK-KVbmdO*xzr;T6YbeJ3 zui@_a5JyOnkjfIyq@L<|Y&G_SlO=?Kq`mX{x|R`-d5eG7j(q~uz$NMD;3lILyK~fn zH7sL(R!0~}MzZQ`561Fd4}tj`+AzET5_sa@FHMzs`-Y@0TvcMFp5l?Dx{>Fy)8y+B z>16nGMLP5xy8i)iy77220rD0Hdf1Fw* z$wM5PDV}fmRP3zzMsxRhf%M?^@wQS^(_%b7B;6Xx>O3W`>PW!s9~|9RcK`m>p5@*D z;mPm*9%NZn;avx{2Q>#_x8JS73c#J;fVR~523_T>4H@12ZYTB_JMTw+RVCSy|TNv8?(m6#t^>UV+Fn<5lm+D)0z6VGepp4WJO zA8Kz%dFCpg_6&UdMvo8*X?;F9+h)7VhZP4lH9w+)V0%jN-pg#8?&Zzh+$>_3H@ff0 zY8B$#tBgii+_;;}9ctfMcpq8MTS2a%MKpJ7EEUM6s&CVRW3lSy7Ey~Fy9#7jg+-%p z#Q?(!GrdzMD6-ewuX~2FuckGY3aT0X_ZM|%czU<)6?~fB~T6xa9Mc4L5JrFE=F#UakJzWZ0lnTNAx;Jn}5`6?JA>-4%)6w^QO! z`&Gv2ouz_Nn|6+e9XTEOUb!U)9SJ?0xu`1>xt@vTdX=8Duj2n~nBH|zz*+_Gxe-#z z6iClp@gYZiPf>R!Rt?fk6PCrpW_HLhz59|d)JXmGgFt(u8h@(;l{PDMa&z&$j(*%dw8% zH)^)#cIM;gd!y5j+`YdY{E zq)fE`DTDAMG`wUD(~JMz1(NEyScuo{wtuxwZ_`(vwb_KB`5 zSig=bArTHq508;|^JEEOu&*6kShfQaMiL~jb^a$^r?FEq?2?MkctIim#R!)FHV7KX zuBum03yZO8d}lNl?~>>L7_D4{hWZn{btGZ-jfSNoBk`7xrQd*~l8H;*9I`TyEw;_A z=tjPBG0c}670BJF>MnN|WG;ff4KyOWy9%7Qh$yd70bX{eAh?(E9~cxJPY7>gk6y*M zi0=r`H+DL7fdSWMwsFl)welQzql$@5N6|^E*@I#7o5Q{mWsETA*MK$HdlWG~oh0?p z9ScU0j{tucjjk_^n^=E83s-$B6BF-iCF-U{t%jt&aK(faJp>u*zKOfYbL*G=2b56= ze57I?`$NiRe$ujZ%%imi()`nx>FtzDP5_o8FEeQl>r1kkfUZzxCP5>iV@O4rN%LaI zYENNi(%jfF!)Q`?O*?^U!F?>-ggk<_#%{-*7usE)F)#XObwy$aAWb>V_b(GvIS23m zVTt14qMgr*^@1j+<$mtazLNN^H1{FL(q63M?$~?J8pGfiVu#|p-D0^r@zqAh!d_ye zk$<(^Yg~r$1+JY|^`W?(J4}j0ilvDiZ#r^&)rVRPJNYMssuE3Wvl!>q8x=)~UE7zN zdm%gUAMglLv1;2AF(%a*lSV(4lm*hh3!W_Wgvxi;80EFXJ0WG;y+%7A48rElAwbVXE`_zS7rgPjjlWb+5*;|<$7?6nyV_%P?-31ng)+3VR6CDH9fBp8u0mAaMuxk61RXd#=QtWlGu9) zeZI@VUr@3|(0F^nH!onXr}Fkk2VD=#Z=cU*;r&#K-m&Xn_#4XezkeYhe?e#@OnnC8 zFNn2+xWSVBg^e5{_~OsPUdK*A$HC5F?uN$quBp8d9;4*F~Lf$3RHBI zJStQJVDjdw`~sL|=ArFDAvyqJ`kEI~Wkh1yRJ@9;^ z8@8Sw#yL4N=Xfu0Z)&eT!Krkd45(YwkTcDAXY$yu zLW(&~xeT+>PJPHTpuzu&Xe_5O%kA{5I;q9hPkenLN~&g0IG*vB-S!LgFn#lQ_@#O( z;c{?#vp`dbn=$12A@h~5!57n=g#WHb-buRi{O>@^2=EDRZ|V|9x_=G+M~s1WQT|lTf^+J+Nsjq}tp$h!5tMTF z)Y#1Wd*u1XLChZCntPz?Do}F;kejh`C^7%k&DU$*ETajQgksOF3HM1)M*6_PK5paf zkzzs(%nr5J&k70Fbmxa5&73rpD;ect0dweW*BZ8JO={{Lsho2$YBD911|)YzNbOk_ zQX&)a6Y?z24@;2SuIrgJwv*wp9K1rU`6%!TebVg_;N)S6%V(p~?c;rj!-}CA!Z`lT z_zR5(&%<#b{m!UFr7pz`bnQnm_1Qrp|PxI$i=+6bwg& zbnUyTf70LNoaB%K^Bw>2w}Kf&$Uz(@-t$E;R_lJ)t^1_>u(B>aZ#r~_EvO%GfwuN~ zYh!yO^u4om%vo4=(DicT!_2hie)MRuGr^&mSjpZTZM(u1UIAwGHL<$rOUrTR}p z8F`t37aD6&dhl!F4egj+EMRNII4u6eMdxV0@_>F-YP?h7xIkQ@$oJ4*|7FP5I2uaJ zy8~YFs8m0yXlif#50oh#9%|0~iR<}^C;ub$jJ^O*{sy&0UQzkWe?R|x{THFpZzG;57BHaHS{RXA=2yI#n3FZ-bUPw4%{&L5O42C{}L)_o@^ z`^G=~gd!47jQ{Qv+B<$VwyyDigR^ho%+Uv6>)>{R9m(4^h<#EGadeBzz_<^bzmPcH19L$Co`N&T2eOR3Pq%V-Qj{b&VQ=L7xLcSIn=`2;r za@e309@l|EP|IGDH5RpJQ2G)~`%3Wz`CNnZ&&HoC%{>ARM6coiYf*w(Z=EX_sIKoL z=aLWBl|kvkIQEIAHe^tvvoko;HXWEaJ56V7-^AIwbSG<`I6DD5iq`9EIAfUSUc|q} zYrKaHZ}BQ`zhR2tau)&_xJYb-?vtLW@~#$&v8Ja3drh^e2Lgcbh1BxD9Lf6^4D2l7 zGg#aIBHy){eB!wKMkMG2BLeo9+aT$&io4zL>FUPTl z-7Oz49Zza9b$lYVhfQ5%E9ys_tFCQR$?lTp8jgs@U2}l@O>C{cd3y<0d_+9UUxoY% zJ5htSEw|$|pU~zL*WJu5Caq7`rfw18FHU)-fftc$Y@xuiTN>Mp4+`qG)BG7;)%K+j zl-fs3-LpNj%5sqn30N&p-hqV&XYKEkP7Is62qpcAB!qKi-MCMB4VX#tlMG6KMXpe- zI88pjGL}`E{0i5i*v}3sq3f)30kApH=gWW=z!{E8Yc^CS@^JWI4l^OT1aMi;1K+?&O^nRGxs;emb_S8B(tQJb}Gl!)eBiYq7 z_a>yZ>Eug6ZfWr4oN7odwE(F-D6Jf$Ic8zW$mzo2d>L{Kl4Yq}-w&*E)X4dkiagJW zMeLmPi|}^wXd{^D&T~cEp=C!Pzg};LYw!^rJW7aS>u$u(w0IFWW!tW@4Q2+mk}X`Y z*h)GqC5qWqhZBD}IZAODyMAU19!v z@ItpYDBIEn+b&IqM;Ik9bZ&wleQ<5XD6=ZDHn5fqxU)2!mnAJSE5g#d^PhD{mFqxq z1&u+H+KJ6pla=KUN-xVROHg`qWV>T>UjkN#e6;i3;rLP=vD3So6UXh;c9H7La2nnQa^PsZ_x}kd8j`sR| zmwp@GP(^#+ z$&w$V-RkgfAO4+c)F0c0+_&2rchNj5ZWG_G=XL}o-6*t9XjjrPEwa!SLC2Yl7Wvx< zvtWmA;-FIl{46(F81 zn~*h3B0wZ*aj3`wV|Fr;okC5Ir;J%7s zidpQJzArz!c6fcM5_@{3YfwrZt&(>%I!+j^luRPOyP10uCgz z12+D=%&B6fYbHvx5IsfFw7R*~kWZ7W7KRb#fqx}J_4|D!1@WKcC+3Q|JmYz)|DUjC z(%-+pN;-o3Mi7H=)RB0x+Qr=jloKLhN2Jk6rzwt)6BVufc!zZpp>+nO*N}ULgSSSJ z>+ma~RdBf4FV)I%A0yzKpl7RhQM^18yO0&(NFY|9a#P2-5lO`Fe~kRIPP(2E?877A zO0M3e%QuvHfSV!zr{nBeD9%E0 z{zz@iWL^#IS!AonTn8c%*7GRou+=+|OU!Z!(Y)Z2mB+;hjQo6&P7Td}FB5RYLkJ z^IVjUjH!b&nSI4Yu(oo!$NbU>dgBXGCD6O)LbtfM*_kNYzNjke@BWM6Vc=jt+=wq+ zl)_k1izdEQJ65+NAMd_p_!4CLi_(*L{zBlhP#iKnPFRyflI;IR#m&+f82sL{IDi`*`@9h__#;Lx%Rwi0SB z+UbrXD*U1(MYwDg)@<@mbi(U-QR2{lk0O34DxDkWkXOzIPvlU2KWr6Ji0r<y*x;>Q7qx7z7w8ne>p~e?rMfNz(_YBq3)w_^eJOe(*R4{MR`5m}R#9b`! zeP~*L4Vf?|ZF`66e-Vn$dlTc#7~SspMc`M^zy3@9%1=;Bs_oChb)_0vqZyD|qK|%C zuHDg?JpZsPzw6+I-4-SJzE(bu!}*rz9KKuBcfmdz zR60Knn^+TvbvX+3k&Ue@y%CscGn-mBAgzg>6t#$h(D+jz6>>Lia;#l;6^IS8uixaq z3_Y7alF)>3ApcK-`mPN4C+^$|8Lauvm0WWg{G+U8z@_(&A%8ld1k^xU{;gtDNoxbF zxLqvoQGa`b4syItOc%J~Q@lq=@O{$oU!npl_LISQUvdZH-E2q1b2{(F3D(kqIV`K9@gAk%=mRUs2FkMI919Bjb*jv!5} zSOZ_(Nq)%n7Xg+9|IdQ$4T$LU^h?vn8Dy?^jD$H*d+mBXUoXyuocIb*2lxuI|Ef?T z;A7Bw^yK9$s@75XK7v=km5Q7~KO5%|AC(B(=w3^YK~kN8{?@vwYN{KJaA7 zvMUZ~i=Cp*$Su|bbFu?#Dak}6Gtqkbukt_Ho=GpDy7i3-Ch{zm>q%2eKEf^CB=j1n z1+EI0rCmT+FTs5~A-BFlx+7#?!i$#cj|*R=9D@9-mvz#JFd#h?DP~2&pi2XOfy>yz z%i$w0a1)=QZC4x+B!q&VC3FidGCIdj_at)yq{m)z#ITAVnQ_Zh{5il61SQ z`G3G&Lf$-*%J9zVMGN!ll9^53H?`+ixJIQF&`BP~S2CTmYbg?le3%1LY9!{vr1D(9 zrk%J(JYgi`)gJ}dQ}jxs>PU%`M)g3{*0?BbF8t*t$o{j8!zu|u;E{lHh{U}65@(Tjy;M#yCz4U?K;{om5ozd zaw9XKFBjdQ%uNXt*D2+CD6s#JN|#4Tw^~xCgdA90OVO}8c$hztzCWf0s&Gj_X)T_R z7h?B+IJyBywX&Nui}lc?)TtD{lY{?r-Goykk; z%5`1Nc&A;zq_(=AY`Oi=!)#b-5Di{9*ce4lUb43KOPSFA`jOl4II^4((;b(Wb^iOV zR~#lVsa!7wyTEdCnf{u8jLRRDd||9TvNvod@T>Z3C&n~Bc);c={A782bX1M-fu9F> zdCeJ+9OIKqwG(UAjpG>;UQ-R$qJ==VDLkoVaj!5SH(8Sg5kNDszKuyoM+)7#wsLh( ze0&+zSBH$)y^2*_Z!*=LYMw4U8lpKux-#i2a{R9{h&WUod;Vw&*2vEwS5C^+2a0eU z99FSebEX6cvsW~M*-Hv6b48`>s5Z#w{uT1WFR*jw4Rg6y{Iv4-OHCuAh-O(WKmS`< zMvY4T$PhA}E7Qz~mySwrMQn}a1*3IS6F?r_LQnWx=7cAiRshe7N z@~EVjAM%aQ8iDDA-1d0v0(+Cd$P>^xrOhIKXtnl&uroFh5 z!j_8j1Pz|>!eVm9_-kBS!e$9ChEnG|AeXgvSlL7){PBpUi6kWzO6o#MwOG-R>cDoT zqF?$Y*64c2?bw6n%I9y4);m@NG(Od#3S{_Rl-6$$Yz4?YS0X%r9GoI_J&wcsDK4P)mF^d0h$qK#$IU1!@N4n=OK3a zUVfv{36w{d@R{4kUq!wZW;GyEe?+=6ru6X-E|IPL*!>X|I2(Qo>PZe-g3`JeeW+%T zsL}3J*W^g9z!GZ&OQ?O1QW)Cf1TvbR!!8&?Em&=?+ItZPmmVrY{?L9%E%f)#kSEjT zZp1t3SXqa7KiHJHP~OA{G1?W_%N1anF0B3L%1_`~)nngQ<$V(<0d77Q-q(-AC&g&) z-yp+9rC*QdHJW&EOXOXV&wn$1RURirX#HO4=TQM!3bl+{GcEuwdvC`4BGhv3IA)Rm z{VN}aNU!{QMCvaRqkL>+C3{SDOGWvO7k(8~%Cy6J7gG=IuHRyEqh7& zP)6W!mTCdD-JQ{46E-!zA+`(MjYGhp8|!R8Jrf6Cvoo#B_K2n}-Ax&!R=c&3qnyam z6pvke8!|H~y}CA_Y1k=Y1S|%d_Dt^j3bKO%R_8kfFpTzmx~JT@T2Og4uxC<9&^}$O z-JkB^ipzn^P{MMzRGbWq+vJK$pa;MdsJ=uoEPsWc@6n?h0ZuEc&De}w{rj79Yyp(lrIJfAOt*V)cBU6G{kqiTp93fB3CgifmXL~kC(R! zFW_74!f`NNWh_v@@5*-!Nvp>BE?C7Nf1E%LH(+gCyo`Ar0%KD6GI)X82p2gd8OOf9 z9K)ggt2{<}F3mT}Dn|CQ6_8g{tXu={xNKn>k*-DT*1S5Bhv2t@-G-3eI?TzxL~U#Z z#+FH|_^8q~0$e!B1K_lS{Guzou%lm^H9~gWZByxZI*#f6T5IeJGm9yNN;ka>D()!o|!Wo9adlBc;GKy2z`rhZ4iWy8lN&R_-|i3`t8@K{r)&%-=XnBwm#3%n8h^N z{Yb3;hZh+O;jMW{miRWi5gUp87kQ%o2>D3jfT8?lq}nyht@d=g;c1Zjgm^dl5l>IM zcOa4=|2-8^`80BmXb~$wJ<_8&lcH$xX%y%aqf>!(fv`09qF1y5+ti+|DntbU^Wml6 zs$8((U^H4IY`T`^FtyJI+a6&oxWGbY3@YH0VUR`Q!7mer?yL31d58Fgz|b$gSW=d< z-&B**sRmC|JWyb2U-?>!AB5F#-h4tw;mJ)0GUC#g;O1tRgAZLqzrQ9)}DXU=_8b9VPbaM-l zZQKaF$T%U|VXhh1$bT=4$9i&(*sswxMJMLhG+76Gd;AS~eqHZL7MSML_;jyu`(ttb zmm1w6vUxg4f&+-x8kQbGp7yh_1MLtK z5tT3u{g7;KiTk>D%mtH4d?)WQ0#o;8#V&Uoda)cMeE&)>;w~Q#GPBS4mvy;SX11v+ zsTpzA5#;Yhgwl89Se}z9T`tJOeOIe0Y+TM~8#lUumqTA0>%gs8ODtY~QDIf!xVq%i zb(^XtdDG!98irqIGPvp!JBB4aEMB_q_)d!9IPG3J@%2aLuYVW>N2vdUpwFoG>JaAu z1hR3GCw+g$ek#e*NFMqzRu*;L5$)$Glf7#Alv4Yqc&Ie7a-_G3&Phl@&VcYZhq3^X zRh!;4srh+r+g2JIhF5SV zJ1c!We!Xq0!F3ql6>Htt`s6b*WO9b@)3K({Y*n|W;@uVSIXuY(BenXc>z*{uta4Qq zeHR{y{fO-!pUEa;tPD$k7*}R7wDx4L1~t?6RaiO86pyO=3?D<%Q49VEc0sfs-t*7) z%el?#nBB+b%mRDaDu)h|L=ih0a~$Q1b-K3V2|&o$YH)d+oF7oxAk zzA z-gR!i+V__DT~iSs_lgd&0!OeH^JReAcn{;^&6VMk>=ILR7k8e1nVj zwUld$@kM2tCR2?XcAVB*5}OhaRl2^))FLkT%S?}>64J$er75A8j~w@BP+ zv?h_yFc~BGz}N;Co67=o*)c~7bgz_aKZCt8CR?R{v@Daf$$P_<$vk~A_O*Y1D>uCq|7s7$o3Z5bavk^K5&$F#oK zS{MoCpcJdeDqSlU(F&lmEv&=(6c_=g`-UoAr?!=A4oe>m>#UVkg|K<FsoIr{j+y zcY+eR6NZ6$)Y(=nS_sK8g@GkHV2A9e@Q+Am@I0HR!W#?f$k+G-tV-a}#`j}f|C3e@ z15=+NkJMj=v*B(0byoHI6${OUidmD-$MQUDbMop6AuXx{LoTi`hOX-womqE-{TI%~ z&Y5zJ((uMvbzbKzutc6LxjtqoA6X*%E|9G7HJ}AnI$oZt%TKQxsQSl__jXvS<5#{^ zJy2~~|C}YkzM=Xhlr6pX(BeL6(W1uy>^Ngd!Ss1aU|#+GDB0VU)(cZo?H}+v^>qJt zhRN$bbKVvI?0F@)=a-|go#(mH*v|7ZED$sfv`xmiN%ojrHx>KNCG3gx_9sUVVfRr& zj_BQ5uC<+`Uy2|VfD6Er{HkLAIv4mFz2sZoIGm3%zZ)%fb3ooCLf4~c(fCY-u*JRX zzg=+%uZJ2|TntT`cNBH&f%l8-^*z$d(HTtB6yJ#ve#0ec{%CRCe=igIb#%+W?S)gF z#LY1XhN1SUy?YDTS5MlQuCRA6!#pY6_Q+#>Qgx(oD@iw8Vc}x~o2(B!Q1)P@SlNb% zA}>&if@PzOB?wASgaymBC(Kqt83d)r!}(8YWy_ud{>Z843%Al=!}$zYy30!y`^ifF zP(|XatYw`m8TB8PK8?mt$ey&eKQ6EB9Jq!GADcls$qmJI@vo%YnN{7Q%!~Jb<$g$B z6U$0X$iS=Uv$6a_nj28 zwXC>dNnN!oUbe$jo>zMlJ6TI|7qv)d#KyGdrFFVOtsU#zLFGK=AHI_O3e{lNw>5}E z4T@N@H~z>vSX_6&Z#rDj?Vcr<%_O!ureJq!pW44S6`X^~t&)@&(O~U$I){0!@7j~p z;)UCQN$O;tYWU{{!I2-=9p6Da_bK#xOl}~l;rJEmpTy3uo=o^K%H6G8+GJP5-Lb&{OJ>)$&+_UbA3uLa$-d zXRt}|uc*E3fC@XvDD1Yy&>WzPpvF2MNsI}7I>@ZbXJaz!b>_#*0p-CsXe_W=Lr%T` zjYSPc$5G@Y`2UcTvq?^#S_^6QVDkQy{oRg5fvGGer%H&mRr}rn=Mz`J;JbzO#(WhP zQC05|{&y)?r|bb2F$ZKV$OVvspK6<=Nn} zPI^`)_R4$x$xT49BQl)$Oo5h{5hcoreaQCFCCM@J0~eyFugx3bauy9=6n?X6iHr7X+MN#9{RS9B|HT@rDfK{4z-fM zD0RvCF0LKBcf}rHBYUK`WxV=i>~%e0BrD5Ujw4w4Ed;EdJ=ji;mj+dEJx84*D)yF8;$Ft)&WLx?1-p5 zXoI!tkmK2&D%Wf5&-`LHYgH94<5h?ngA|D~O(&v11RI-$nW1dm>Q=(Ot?J%t=!d=R zDj)Z18F)3oKh&wlyKji9tXm%E7I~ao9(qFzgrEm@khiVh^uDml?K9GTc@1-UrH*VL zablnJ4N$IhtSANY30966CM;$<2?Bc(v&X6LxDYXTbHR%&tdn^5E_>hmcq&&@mv z*n5G9r2nxKQw+yoN`|3YKbE5OQj3~Qzu~{!ZMf|&gd8h;)4^;JyE`o~A0?2alqlJ# z`=A3*7C|c8tckK2BNpRpAytQj95J~}wO@SzXk*xCpLJ`>5}L3dl_fT*I+FG!AB;x? z_mt?R(A0AZ{pxp_{?7kUz(=?PHZQO>NV9?2f6kGKeL5Gt9|bpqU`diOjAR@Cc~mVD z-g;9cu1x(3#}xbEA={USECA$VGs9Z>H8jLnd?VTCXfGk(*Irq^dH^_qNx4Q@2B`u< zA|0p|l0&NSO=|rG5%?_7mQ+Jg_Hmnyt(dpS8!xDX^I86i9_b};-CgpNwQc5Xbs#7i zfzUuaN%S9~NwdF_-?k8M4#M|>Jqxqt@Tg{DCQd;dKo9DtWr|mjO&hK6j&wJu4wKiy zifrq7yB4!{c-&!G6(ngtFc5@NjKFqq9i?btny!reLFx6;ZaiT_4DDk1IWwNyw2Pj4 z98VpUpX&Mcsf>J0mjyd@+h}{}9>fWgt!f9>z*t^|NN60KZOk@{DVl(5eX4zTY7A#M zGd5P_LrgG)a^1_uiz4{GIRn`aJ2q=iGD8Irl8@ zdG}XZZ%;x0K2cf|*TA-sW`7*)+r}3}NqO+QCc%(ZkkU~EzPy42_Yiy@NLEm=vFZV> zL=gNt_-`Uu(?4|HlUv}0HB*dR292uW(``uHHuy}12;Yjmurf+<$Gy=b{wF{YpO*~D zpy|Q#|KlRKv=TM|C&cu?BaL~*q(Mi!H`i}$NH5E>{~b0#%(cC52tE`P8E?CK#C{r;)=-vZsRiEdgmDGlIE zmddwH!E@?6@CE5x6+@#TA5DS3rfWAiQ?89bYKJ5(j)l(N*Bg7qvmv=NM|&-NCTT&> z9})A14wm(f(U!JuUIV;xZib>gr;l2z4e;JjG;&iBNC(@js`3w*V4 zMI&qzQdT(jY%FTb!CjFfDCS9LeNe0n5NL>7+c^XE))zbq5A|`N z#3P(fcu093c75FBg7!EkH$~ob))NoO>v6H$kFUml?}5j;9>_!bH_H)Gk`*Z3hCcuc zc8~C!S#r(o8)3j-qojmaX$GjMt{VZ;3>!CiL&@_0E`&QsnK;`@W$1EUHc=frG&1{)}> zA;{?I`W5KNQ3YXm_mwwhcX;j12*d$KEd(VLw}GqgARWTav$^mc_0@1g5Wgq z7pTrXQl0-so%G&~(5H#pL-f;e$PrYa<6vtUP~rV3oCC$gQ*v(|ptU#ME8h|nxA;p9 z@Z}GQt8A}R%bPmAYjp>aqYICSO@2@`-A@gtaXf$)YnLHTlA6C08+9o8IjZ} zr1&jqkyIB_N|qc+x&3do8ym&sQ>h%RjxT9j8^<}GPnJ1faeM%uhE8~?;hoSfYt(A{ z9OPBHqH#m&CV03ZDdtFE+(w6%@NP$Yg!i5VxuOO?k}nS1dI%kdXLbPAc8lGRfzxj4 z79Rm_M%Vj8Dy+wwah@k)uTsu3;;&ezf?sJZ6vbZ!WEna4tK2f2<5O9#)q=dqft>p% zqc6nCe5>z9K#~Wph4qxL2vBmeof|LfDq)#L_x8!gpLZKx?-5hM*Xa>A_{c7E#~|B6 zSLfiKN^nag4dmbWnUgfi@9aI$&Wslplwh`}xt0`>kF!=&S8oZkMDC{@m+rIfzNds) zi?G{Jb|JJ2s}@XSRjJ(xhv3nqA~`BG>}j}!p$?RdYA;ARpHP)trAgJMrgn`<)s~ea zo@;yNqz4Ljm`0wMwpeE1A!+69O&-)LwfY=dLe0|shdm|WLzFCD>j__FMj6(x2hn}M zMEkZ#KUSI6_TDSCSHgCi29DQAZ-1TgRl=O)IT~19q)?>V`K2XnnN(`T6}_rT=^j(1 zHJ1|STX}*;uVisiLn}CUm60}!ptn|RFT>fzTs^`0L1U6W&M?Knf3tJq_Z zd`tI0dvOkSC24oR;FC+^eZnh~uBW`SB;9v<*5or+vdA3#!B=s4KGyqYR4O9*t9(J* zyEgb^YykvGZ8BZg%UX883g=Kt47_cS1`_Cn$GQA0x7Ij>dpYLfe2O!rx_oZg5wUM@ z8Y{W4aFPx&Me^Lgw;>XJuN)S`>_jn3vAzfx-!qVAq4nSz4Ess$7Ndi%fss;OG_U8i zM^m~m(qAn|$$IRbxOVt?N`V%Yb6$!9eTZuR#B+W9(TE@A68H6tGqCIjijDB4+*D?? z-?$jI%7di)^DLlokN8_J+k(;Y_K2T*6a?)5^7Gj&TDRx;|ZA9w&9t|sW| z-8+yAO=0TE>Y!yH3A6Zk-vRwU00n3!4i5rCv>%jGJhW^6A*ByUX&KUgm(rb5nnU_6 zDg8Go&5+(FrQep)q8uxd8oglmQOX@UleL7k9?PszV0Jg+!6M7;aaeIpBd`on!{qpaxeWN7a-)|RD> zC`itSMPflaBB{Y5k#~5`QX4OXex1BjGahpmS1?I}HB*Q92AP54lqKela+k0NKv_?P zrMe2%Irn;}r*Q`2p{l&XfL~m6IbG^KH!z~4sjL@}nz{aZ_NVuFyjSU+o^i(G7iZx* zAX%Tbouw}cz|Nko!N7gk8w@HbOEf0I{BmJ>f@E!P`e$wAP(bD$@zV^93u8-yax))J%@_!9qL9Gjv z@K2+LztfvSI6Ihn59v%FhYttZQ%VUNcrT!YHyi7=;kRbvE%hF@1K#5!Z*`010p-3oOyi|5$#&6~ z6gjeh!Bf8phgldXYP3ww2Q5}?sCWFian$a;ptaQd&O7Lw{S>mjaP65*Sx;v_QwR@z z=>hOG!5`f3p}u^MzN~=nmRcLet#=`OEA8)v&!|1OITruISw_0J!{-_8N7|R15!Q;< zDpOevs2FgrG#%4%w^zCYTSb3Kti(N)ibd2VbBzwxT)pDdAb1hD24G)HR#Ux@WRicx zKh4|=daqlY;g@aUa_#_!sT;ASiRSGVPl6^+ns6Ipd9-0yorGWL1Nv8Sr^M!~rU%SoYI>7@ zOh|iA>F>%?+6tmmw(FlUJd^qKCGiuC-*M3!{Ls^ov3~lmWG6k2?1xw{xN`4EV>T1C zJN3TOUmH1TPJ-t)U-E4;6`Fo0#ovbJN_v7*FX=J}H_*w@cOtl>h6{Xrphz zOYMqnTI1k?6x_eFk=wqroO4FKw)3Xia^*Hfi_x(cF_dc@N<`6+H?3*kkg8~kYdf0K z?|8v+THHKDcsIe<i``eO6?Wbz*ix~ zRGFVP$5mT)e9RZ^UuZK&WVS=D14&77YG(TZ{a-e6&T-INB))FUYdS}cc9&ylqufcc zbQU=j&W23~Qu-Y91z!XSBTUCSpwtPZlq@xp`Y%#sldY|!Xa5Nr8#!qH86B;S&nMS5 zzT&t$wZCzZgK)kSK#p-k2lOexjtMU3ds8A`a^nyWt|DLRY@eI4Mv9)W2m59V_QlnD zW{U=7nmh2LeM5Y;xTci7N(8b;#3tx1rb@A!5}MMatEMSE9LuRGL%OP))@)X{%q!aj z%|>XQ>?AwnSa9~!H^e&0nxX)ng8sHS#_81VG|75%7;(JbvBC5Aj#f4g-p+Kcl6scC z6Fgo>Yo}GQ)CGx{xoyeO+oGEjTeg@+_sVq94YJbhiICw0O>CEsoD~e+Sy4t?YrMOE8tTr0z`)ZOL&^F%u!scDJd1V`rp9#L)t{UC~ zh{ZU}Qykl+-@5;hOwPWCUFR-++?GSw`J{chOCK-Ye=qJse!`XslC18exOZq5AkTOy z6^nh=Dy4I!bPUo?DV;5)qmgbxI%-SU4*Dea3%wn-A*Nlrc4!&w+50!|HOXO>bX+VA zkd<%0ZFjpfS=|&14JbMEPDz^`V~gl>TvN1@HN_y()~ASkp>_1zT9OkRW74A9|BBPI zBu&+v+`dZk-sao{`<%(LYh75ciQ1p^@JSC)p$W%k7dx6}62;L?8JS{QEnPnB11f~bDr#a_+zQ! zCej-D%Hy%!!Y(1@Oipe8(o>&7_6v);y2XS3Zs@9z_Z2SZu$$Z0E&k0v5k1HW=-A}O z6XMLk(#irY!OfH4I~{0;*RPyX^hd|WZ5kA#eZNZiU25y*0tr7(VSj9Y_t&a!ef?Zk zI-e_AtsT+6$MnMq#Ck+cQv+u=GW~<81zH{ZPW)%6fAi~+w+d1U+IO^X#+!Y%1?*b9 z*^W1#HvP~8Pc@M9^uu14xmS8#ed6>JG&_ZXM_^;a^d#f>4jj(cL0!BHyf_p57ek;M zdJNs-1^)|A{>m(ahrU>Mw>TR)w@1E`x#oLF`=qw^PS5ElcbL9)v7E2nY51aU_!uDC zqS8a$oI|d-f?K88sPew@_cR{NesLfBWwS>qwbx0iOE<1#{E$1b? zPXHgrhgdQffX9>XN67{%1e=~2|AN)A9hsWb$ zf?ot)^9RU<5icmT3Ro}kvrdZ7`c+#jw(KQC;(XuZ=7|h3Cbu-tSPTDc@IG~uqNxE9 z9Ku{ZHFzHU7G+ahj-u-UGiNwhs?#HmG2+Saz~g=tw*;f!;2{Z`25F-Vae#___e!2F zCiqBJQwR+E5%OHWsm7*kV(=J*=IH%l&m#2 z^pT}7^{*7s3}sDy;G&mT_Aey(c~aE+`!Eh=5tx~X6xlsK(Ow$KQ6q=!9&eD+JRo7n zM>*@;uZxrreNoU*FVJ!~oJzeLyc$H|(sEn(w$Evl!6V%>sdF=w&Jo%cc=sfFK@I-? zjgSBvF?))p8^N!`ND58_50yaxRzIhWaBH}@@O zal8+j?TxMJJ?m|lp|{#kt{<^M0UvslRywzB=vfcT@0R9`V-OMe8mt11mWOYOHpfxG zlx2?ds3FEj5?N+=5b&1dholchyh<*UG17}7e%mn5Xc%`O4u2Qy(n-$KB`$y`u2b-N zn0x&f?cffLkLn_hHr5Yp)d=3x|9d6AK97@&JezNTq^e3aA9xyMGjK9ZE4nqJdL28CR}3PUsv|F-sW-F4LRvwWwtL7QR{5bP(FOGUrY} zihgjp(@L4~@v@>jCNe8(*A5k8Pu3x#ILV5l@TJojx8sty89LsurNB4u!Z#XpjC~0h za27wJ8eq>Gk#+M+)=7R#H<^~YrkYD_8Hh`N*t>rQG%9-vv`W?no<)(FV!%&e*$WBQ zhJXQshYLw2|9V)?J|w>F1(y~UA!=g?a>eSwCrpYS;tvt8`~+xEdhZ4=2da}woe*b3 zhJPvf+LY&^t60~_84e{AH-pL!pe&Qh{86ffB5;Lkd0MJPF4Yn)@#Gb?z4kl?#THvJB+d)uL)$I}o*BBtI$+#HQT2$o zL}ISZh9o{D&I6D2I0Tm%JoW{~|4-k^K)cBdvkPI<(@+KKKe>!U{9dx$Rkcie!;_Q!ye5zO6j@6XHk^$LHi1vWJ6EM>r zg_8CldF-c>zlAJIfwIt^8lv9jvU8H&1@%Xcwa)_vr8a0fs#N@E@Xikp3y{9UOF!vk zkSBhoIsi}nG-h%pt>+Nrs;n7aGgRnF0QzbQ>ADY+G7DB@a;VMpo!jdn-8GUUZjI=? zE7@I$@>PXcsEC&rG}e=RxfcINLN@|F{+!|H&V*$Zo9oKM@p30cARM|XZ1P@^tlF5c z5NGmN;67Nuc~H3m;zO`PquOYd<$Lp(ehKyCb7`Hv6rwg$j(Kd*nHA!^MA60xQQnD? z2FWGyTyWSwDZS@~ow@NTmY;~aLZUX9WQJv{HG4_(j8(~$vl!zaK5efJ?Dkm8e-s^| z7_+sUYrXvs?3P#iI~Yh!tX?{hv3ai_|abc!#CkG@DJb1;J<}s#oruF z`iuH3ixRLVI*@7QjITix&Crm~_Q1O!`FuJG{EjoWLE~JHb0s9+7RqN@=Iv}dgNH_< zYPhYkt+L$|jW#5H2Hy&|yR+C`u&POg$4L&6iEl<^*-Dq`7N#$^j!-VfnIKfLG|tJ;)G>gIGZql&VDK+9YU`U#9~~vCi5cZhx_Y_u zAZ#rzxe#x7H|#{nTeBT#yn(PqGR(AzxR2_u){O5)ZYW$f*-}V zgE3}#n*uW;-yV+{iD`<(jKo2^AR0dvX5_0N!9|*rtLKAXLLM4eewk~fk=q^P2!W3T ziF8hho4(%!-w4Jfli0ir#1n%yH?6X{J{qO_gFlVZHCK$%7ePAVQ!z4{W5y+%VO~a` z%?sYZS?I;Z3jYX_mhC0+6-dEiTzxgtH)TLK?eaJA{uP};P-1eXSW<_t9f$8GYZq#B zH})Gn*%H}b*~lxvzPjt$;hlAzs|Y)DNL2bJVgH9j_0XgSW}Jf^c*d4wAKr8D6?A!q z-QY-ucTz7rFw)M+Jw`pfA3g1}UBZb)yJa+HaqQ(intpkYhQz-HKf@lSHa{60CAE1t z@E_#F3NwQ=dtu)VO9I1l*5nIgkUt`RW$Z8RBQ^GsTG~em!F~_HPlDgW`{~NP1YMye zv?87kfQDRxQ!W?246j2RK%}Ku+50%mT`A_#GL#5xkRaw(NgpR9zU_Okk>BujGGfzf zTc0X`cbW$sMUGy?nOp}C?{vxq;Pdr*sRodLHAJP~DS; z;v;p}0&AeM8+`SRYy))NQ?)5pN9$8GKKYIS_-;SdSAzOhMCv179e;!!c9*ycG#>|f z`c&NOd}Mvw1<%FMl7mMX%(ZVU_D$S`GU@pUA7@R<<)z*6Xy`l7$jkTVJ&BR~J)yIn z5s~|cLZ>|H$o<-2w`XPK{t)EaGDMoE@qzDL|0f>LBL(1}H-D=p9zTMX)J|9qIyyl`_zYo0vy8d;LXR}d*oHTv?rk>BIzcrB#2evNZw=;_ zaPoLiWXJkv0l~npFy|L%}t0wbRe0tg4HgX3s}{tp=h|a?Sa?6_jj_ZwPA3OuW8q3+b=u;0bMFl#9K9F7t^g;XwJ+SFGvQesclc~$~ zRc-#lBc6%ybSrb`EoniN&GU#}H)=w)v=UU{5YSjh4az|01Vj(~tB|C?GeG;CGy+m7 z?LIX?vHAMMrC#!*7RBq(*5|OU49_qRyRqdflgd^+9QHA$<*K4TVH&yuZ;2-|5vi*&JUw5Z?@a+Uw{OM}qbV z^M_7|YXg1YScbVnC&b?&^;SFi%noyi_@)!^{}0?uf2~%9bFS6fzvL}gDkqyESp}_j z9g{H?ILe0xF$RsJz%k8nSR1Ld#kS0GLcAjowQoJNYaqJ{^u6P6{pLxd@gB`p+X@W#;hTKI6ha znC={YU*Pu{eqHz-$FC2+7+`}5;JL>a$*z;JX{E>7$1@gHSR4ia{Ho$K`vSYHWCt)u zp)*4VY7;w&1i0ZBNPR?Z&g9aPEmqRm;;mIu33`XhD9oJYpv7cC z3|51>Fh=MA7Ek)97qDJQ2a&Xt*|xE$YcJ}Wc7))7I~0P&!dlbhBUxqxcXYv29oM81 z-VAX&;D=jyX^=t7JI_6hKOd>%iNWJ|BG31@dHq=recMhW zMK3>imxAHYf?r_X+FRE=L(s>Xqc}ZmL(CaFrVB=6X<-T3ZzdR26GxT;Z<+>;2AAym z8dJ^mwmN1-ufg?YL!r=4NS3HR!j}~8);cYo{Tnt4gDy>HxUG-qS;0v6nmU#r>(XMh zqcGaN812?Nxjx;pt4<}%3B6p+jDh0*8nDo6?RZnXTx*`&krf)Zl!fcwjJowMm9W&; zTE`i**81|3>AZC!tHM_pS)gcs{T}!~r~ff71M9XGHsnm2eS43Mn>4Mor)GXVH)(#Y zN?7Ro+#`0b?AU1x_dO21pW=R^4qnUMa-B-(3GS*^TBt>qGv2+VP$jr=jvJtnrbArI ze9YQ&!PdGAOD1w|OH;ab)n!9djahlUTzDQ&=)DARh@ycX@rVEl{#TQ1n_QR$j}O4C zTu!UCym`jT&RoH=n$bT~(;e?$kr#fk{`tt@T8%`(4``bP0pflCQVz9yr?;ACHFKeo<+hy0_^-Q`YvVjY>v?KLpk zm2KHf@P`;YRLk~eraZ*blEZJD*Pg-~&zcflt3aEbvOWuY;rZ6ZckR(Wd&hh$BGI(Z zxAfrJW8o&A^-$zPng=G_3kzKMy9qTJovdGb0`~7rsP*UIOVn@jmwFyK-%w{l$L8qhJ4yjE72C ze7Rq-t`zj^rMptF&yTdH)MCF+qy4_b`(>n;)JF&QlAO%}<`N?ug0&+v;H%IN^azqC zbf;sQdD<*r_PYHnQ(eTG@+~^!TWpDCpXJ(__0_LcU#Jd=Cqg?7oNf+lyZv)9*GGC2 zpNm<(Yi8+;*R18nu^lT-RNlHae`c;F{LUL|zlApP`*<%I@4bfi;(Xke6y4`y6g;b^ z;i~ZQTT*f5d^%&sEViS*y1qQuvZHZ{C3kJ|hJBX0wL3PPTbn#{_u6nDoLAK4fn5yM z)jy~+CPvDykip7Ts>_|X&YUpzxM^(-&e z9WC`U9yKsSY8_bugUdj%Yrrp;3#Fi_U$TDV(K8Wi`pS1z(tGgh2IzwC2jqLn%CR5e zK|>)-@rJ+C3!ZU28^hF>%fb%5j?QK(O=UT~LU_{a#Wz#k0(?yqHlYxnfR`&~=y4b~ zaJye_Jkz)#J7z^{w0T8>`P*?HuaX-dV)2f|8$&l9w%>Ap-13dfVToVN-B=JkBKlwV z|9g4D{ZHOMYkAD-5#Y7P2%lj85pHmxoRcy5m{YP?`ucH&c=lv)Zz{ZUbmuoLwj1q` zK^9;1l(GZuVPC$n=8xvG0+lNtexy=i*9_dq{kqie-C0WW*R1w7rTMfL{v|`TcOTGN z?yw|>zgvc5h7=d<9WO}b%1}7`Q4lD|C6y-!d+tS=Zxn2-z)m~{%J)q%MTl)GM(@f{7)^vZ7Pd0#0WS0 zMwq`r)SfZmA(0%X5Tk#vVRb{QEU7H2gljqsAFxga$7R~6iCjyJQ0(KJZ&|<4p7l({ zD!y>L!kjtc!tFGIQL<2o=4l%GQi31R`D78H7PN!##K$;TDCRM!KVk;&@ySRx$@0+U z^&Af!k2P}<%f!8EHue3?T{9nvzW>Z!BeZ93kFly*6-L;&L95lR;&htMB-R3`?RW36 zoRiki_810x2_JD1no0=R^T5SSy!~rCpsc< zP28;fhW9R3Jr#R%uPX5~_?r^$@v@v)*8+oD;?Zn_^gty%>{V7OkyZhZrjz!78~!Uk zW4h@^#tMNyDpZ7{gvjTYwdy{?Oep0-%6U0;2&vvkN-k^$=LNkHOp)tyT*L6B%+^q( zZLrS>6jJn84p0Vj4LEUgJmJ_1=G?D(&1^`(*b=1v0e-y#MNXSSPZ6Y;Zo(r~rsUEU zX^>bq?R`wvl>ZptRR5T~X+5MAFZWeHbX$e8t$K|{U;S{*b*CTB)XzwdG7LVPHLm6X zWt(E!f#eq-;HSy#%C>)|^STPN_hF;sy^>H#t9_MG{f6&h`M4_B%B(KwzrW_eTS^QM zz4)-QO+9IZ*0?;ct*R-?-7B^Jhn3?L`lz;l zKAhOb*$Z^a-KE-0{lN0p6$1~nKG^>tXP+SDsqEM2O0{+6N_+exBifYqiP65e9Pe)Fny`-=d^>Fqwy|OJzYc0Pin?0t61VP#6Nah@g6=1ZiuQVv(4G^)*9#6EJ zrTZj%sUdl9ie1lQCdCM^dI1Np4-}ao(*R3k`0=H0Jj<@t(%y* z=(a^k_M{cv#j__RJ#hP?rbXCQy2Y%n-C*T|6VQDoAJNBO7_l?F!T42k|3X0t; z8Wc@jeu4X9gDyYYJ!OOH8Y8%G2}SU6Rx}Or9==)L6fL|FQalHKtZN#R@8FxGg-=8J z$NL_Ol0|7Pk9!_x@+j@D$Jw(?8Ku=(jlY{wU-LUUF)udg!T;g1uN+?_>4e=GBN%0sF59;bJ%C8|`f7Ph_pM%z#EbQ#A$rJ3fR<>MGn^UUo zKsk-iZ2bNgO+@3yve)mIy$(6T5O};pFFeK@OAQP*g>pdyc;*&YAb-`+=--Ss>mMsM zd~1P^!Kb0SzFm$IA;@gqVhu{zhZ4-y|L6I)((^fZZW%JLz$BC~j<6|&s6kHGRjjkq zxJ^a>UWn&4r}2}4wl2FLG7PrH5^Ej>E);K}bw3I#j`l$!uJo;OgM>#vhp{Lg(qqog z1J9u~LHojvZ=zUQRYOMBP?Qc&G$we`UkjNT=xb2+shAnS)X-!*%}o}*pXTTB$vK#z z1=uYYuwUiE8Sj4h-Fne5s$$g4Il!`Vd|4Q2nlGwjFhF(KLKCDq0!7_4zctL@LM`)a zK)*|M9Kh)ycfV?oSIi-cIM8bJE$;%)p?O(=-+j{D&^aR?V%WzaaTlb9;T;6qsDQkH ztiC9JJ8&xUx-lBxMm&=X0lBfr{uNd_)3tzCWozK_;@s!4B9$%!;(Y1ylih{((ZyWf zBzr=!N_V}*+qt_jv6Q(Iv1Ul;i8JhNWV)o%{(JW}Zqp`}w%$9*e!;_|)-OG@*EjA5 zXC`1R=Y?3n0iwh0g{&!RyIfd~a}9i&fD#%WDWJo7(4yAzkob?G=>3{bf-^VcNAnQR zo|N|F`T*C)3+Eu=ig^a!dd=MK*ry*ajC&p0UfU8!W_;pfULqMk*wZ2@vi~d#lv8Za+_}uz|~l zMh;0Q202DO3ZqV*4K$It zj?i zCSwFS?6Mmn={#fOnqIJRd$ICDobyH75$%gLhWbP+qNrQoZ3aFk^{l_9cw$roWLWMI zzzj(~OaAXC7aQ%zrIFnhVp*SiM(avVz@2ofz$s3i8pfo;dEx(w5&DhrE8>MZA<5QU z#dldZGED!6F*Bm|c!?iMdx_IE6f|Fibq%8hil$50(F=e3~DE zT6|OV-i*eWy>d3T5mt)ZRKnvv-U)kr_(|cOr9Ll2?YV`}WW`s=aq1!9O!jp6ncD__ z%mPb_IknOVC`Y4_T&croBv;;AIDetT5GtGlsybRY=MQt$7FeFQoV3t5^=nUBUWi;@ zj$C&~uCL=dF#D#Gf!Q4q3Hmv-PY@0C_*LUZ`d`qe0^PwfY4^9{OeGrRE?en%a5FPW z+sc76-Hx%bcRV5K7~Vg)(^y#PWM^j6x7|ND0TiL4X@Xg{9he8S8-Pm;QXkIFw26463gJG66SadhhC# zLZhE$E0`A0kGCkROAD34=g>sE9oPGY5G4^hE39b_C{wLoDcFL~Qk%0A%xZ(8DW2YG zlL2$A^b@yJDJ%?9y(e&v1z`(LUfO@eURj9oSOtFMhkAwPal%dTJAwUv^?aWg6NViP z&=VpUGo>T`X5#Ji2I6MLRpc?cA2o>my)C8^tU74jN8enBrhpB!Ug4`n7!wjZ4yHp_4mxqb($f)Hr6JmY?-ZW#PSBIZ1rsX0 z%=s&L6lOR#xZ<6ruif80lEb16OjwI2T5S+>#hc}o>Y^kIGu~#g&wxG{_Q(aaOT6ni za7s3jex-A9>Q0ji`~!VMn18?(vz&{Ntp+8YE=69!+8Z)jWzeOn0uD?VFk<&*$Z(E- z6XF?J=n_5iBXA;urUVt}j^f##B<-s5*U&EE8RV%XY-KHkO2JPNIyUXEFCPWIq@oD+ z^AD>TSHQZWv!Y(hWrxK#hyLB3#HJLfSZ{k&uBe87*$mp}D|31)8)QM!V#-wDE={vjV;}nu9Jx79 z;>|4I=VE>AJyGJJGyKuMV3|R2f{&zV3Q5+bV|x)Xg)9D|{d-SHXYU-Aqw&HvtSWGi zJCqfKYyI2HnzokUU{V)>qjAcA&n`Oq4o1!3a=46GG?i`^T~47Wreg3Qa(BMLK?o-jW}G| zBj@jtLqew%`l0U(yvni0&h7X*SuQ*iykOxbBq4@VluL#y^c4k-Po`J)k*w_tz+9Q2 z_D#gPmI(EX(n-o%E~a!aQJ`a^d?S4#Q>My0Sk{Dm#_jT0fagpP|rE?kT6<wMc@C4zT>ogjrv2q0F4zSZ*@xHU(hunpFAqS4wtblhB*%5MN3zd^>c(LUrv!i@{EA+)C4z zk-l&^kywrjlDSe76WoJx%mVGMBpoN5f=)p*VyY6Zz=VU)j}ttOj&Cn2))21r?L`f) zN|#c4`sN^A9i7~7*eO5izAl}|{)2?iwbrV@s3jm`gOMebjs*7lfi)p-R9BRq=_*Vz z!Rlq1I>7mZINyJ8Cz?~(mPs1O_!3=!IDUD?NZ{!g4Xt)&G}v1${T9S^GcU5tzxNA| zf_Xf0ct+9ayY6Gc+rD!ig`R5smG{4%mmthKok4w&18VRM7olM%*JIwZsKf;CQWHr< z)}T%J+Je-EWWEW|X@O@H;r+lawEv@<6Po=jtFB>r9Q@sgD63(OWnC7O>dVRS zy2(dm&0F@)E^7?&f5!8!9VQVngC9NNc<$O#!9%?7wHQa{_I4W6;SpD?^jhez_`JIr!fGQo2%-fai}nH!rlnz6y zn>`J5AjoKh>>9-Gxk^ zNwq&7T8L2%cG5ao{?-T9k!2s^%%v~wurk=!Q0%{RzOOxd!9j)`2xm{v$~sUq3qq=l z1eeT^58sEdibP!9dfQI;yyk=od?D!>af0Ay&mI4zwJ5DAPPj1yNz~=F_%zny{;Sq) z3M^25>Nkx^xYv5A*ZU*A{?HnGx!0U<-V2KntZzB{+VkMpNS$jjUo^+KjzXPEm%QO3 za>(}~bP7-}jm4!Pjr4wu^tZsHeQtiLSE>m*MX2W&_LTHiZ}8`PDw)US``Z<$ZfOZ(#AVdNx7rx`x6#jr?Y+ z|Em0GH#u9jmdZ3yIs*T&B}1EGCQ2a>*l;dYFi|5?nadGS%0q zi#C~}p?Ndc+E{k0H7ey+3mdO?-zD`j;j>tn;hqL-IZ!dPEW|pMesq=?pt)-DHaI;_Eg+Q)BsCWpy!@ zGVAneuB6PubgRKr0NkHJu)z-wG2U6nLpwa(#WD{!^fa`aG)GfdrDd~)DiiL8 zAB0K3!Z;y*a4OQhl3#?sT5Y!2!YCmlFlc-Ql2gC6-%dX6z(opW_N}w-MNcldsv6eh zU&Oh=glW(jp9VkA1d|DB{RQnRna$>~#!ie9{Qiq5&$-StqyTHkVZ_0REes(RrdQHa zCK)nW1rhxBh0jFy@R?W=pxH?2Bg{Z6wK&Sn1X&2WEnpvV(9@vy9Y{}P4r`4qO8C&v zbmy&WOo;Ac4|Y;J-v$*}rxRI?^i6MqmK-#K4rlrHefDoLHqnSM2%QNhuVeZDa)F%E zaY8O&vD&4;i94^332z3!y%@FTdCMt_O!u|~tB9|XfV2F6_4|~c`kmefelaZaOI#c< zfsmLE7&4Xmfl;yhDQ@cdh9dhoaJFNo(31)1&7NQ@W(ud3F4#%4wFSNR0;6EUdgyLr zrVN}g)k|}wz+C09zv8QDu4eiNjr;8Rm@C3l&!eX2gU2IZ^;dk=8hq8?adQ0hRTa`# z{Sll5nXWAY|490b+1Mi6%5tKyJJqhk;uL75%9;<0MP8OXHb;3}9y!&Q`dQ|qeLP|b z@I_5!v9NYi?BJZ{GEo25=v^h&cda+n{k{$nuYhF{p6Rz1<;#I*p7QuHo4{}2VVgJP z0}CC6r+iDh>CWzGz01QU_}y&0#?AHJz~s;70MFYcVW6ol@H>NYz&D&41>@WqO#d6Q zO!VFd-o%h1LkrAJR@3M{SSFwk>xbkSqp_aDd-P`CpwVb&=r?F3=e?GG`^y&W z>i}y8WzhmXOkhZZz!Fb-aVp#|`mUrtk}&t%rMXwSiLywO=5S+x>mxagJR=q>;l~IqGGJe1A$r7E zU0ZE@=(t3Ca6%L)0R>=DcVvC%f#-O4outtU&vR-CuM-CeS4-}bbYmNS1Qs_8eZCr$ z>%Q~wzlX%a%~zkdePk)C28?!Tt2yI^8elFD**iaIaI0dEy>H!(cwHgrg=(ZaKON+C zpTVB_0#@^&Ynv+O*jPk4?z7gXwcJ^jHt)`@@DAMbFcaDX6WMJ#CVU4xl&EIf=f4Zc zbZenm@ejed`XB(iN`{&*D1t zr{BX(JJK$Dh)%kb?wY#QCeEd=ORUz{v0S68vRbBVNjtLggl$ecD@cc@@ScZTu}>2v z*i!-ThGaR(+yn+_wgu=lvEl8t2)>T_~Ksq}Nbt%<`I+mB^x~*E4 zwI;21yk{PT`arRn*Gq9P2tho1Ni`*vP`HNI&V8`$;Rlx50x}}7chF)vy;F#WLXCr z@=ZF|Si=EpS#ryrAKLnnj&rpFXJPJ57zd1IQSZu(v?_Q@50B=;ItH(6WA%|W<)Ss! z2z}*WqG5=>=LCoMN?I&2?-y}XX${wVe~!oQ_li>6oGN-F ziz$u8sd5CojRZiKbDpEpnL`kzS%N4daGIR)g-?@9m-!j7l`-bUmRDAtUDa~$QO_7Q zaG9eK5^wQ&B&foKfzU^o`(TJMg6Y-Q{KVI|bj4a`!jaJbXlGGAkj6I(#!?Q~gJgWf5 zXp_WWh>~zA6}UO~_y~t$LL&C9hA3=l{6E~V9kJZGNvl_B8O!}17${CjX&w@>Dwtpm z@w#5DR+8Nhw-Dy#(9?OLFvkj!9N_<#_*Gu_bBOMo%W8ED@iqv{lSi;B=z<#0fwCBg z?4$p+W+9LJ8UNtc2}JA1V#Qp^`66ncFvv@ULEcX0J z3CqiOwbu33ch^DU=IXDdIqIqI0gOy_8y}Uy-T~HN1<9`ddRrP-bYx}k$~o;-@HeQD zF!uVvzIrA+F-X|+*+Juyv$f}|`9A0gmcL>AJ*}8)9Y%|;=wawu6fla zj41C)s%FNrYOYURnN-V+2dhDILtfQWH?Mj`a*tHzYd2SUv_^>3%NfV&H63O4gW7p_ zMwz24t6+&Hciolt#ma^4n@!5&A6V8{wpgeI@Eto-m=jvKH0H!};LLOD&>M+=$&8Sm zk|uJg zh1^&MDo|c|&~jV-n#c&ut|d7F^=~Zn)y=?>h~66>FTkUoe}Rf#C6(^Rc)uPHYsBz{x3Y`5QQN*B)!G*InNo9K?xg^D*Ga3jWym^_ek2ucfv{$9Fh>?y%42# zDs->?wQ9Trd_TN@l4o7OTN$qYI<7Y%EXB-#~UpFE67Z0t1r}eJO5m^CjWxe((d3nU?d^&AS?ZT2(Ul zQEOR#R0PWhJP)wU7y9T#{t@(s(zOC5z&~;A>x(a?w>DonoZm~_J51j-^P-W~j}XA%JET-^T_@0|q?ey(ep)aD2) zkJytH*kKw-em+O!KpE;}X%+ z@C#}GdAJr7Wq(aR8#0uZT-3JK%A7T8`)f1J*|m#mi!6FrmRG6tpS@gPjFUMBn%Cd@ zGt3#4^(Y6aV=c6><>zY^&ioo+v-gHX4b}{4=7r@RL9r;v@62ZHp6lUragRE2+9&#L ztT0_IeBwU_%%xNsS?0PG-;emED(0Gj7{=<#nTTt`x^D55M%EJ1sxMENe`ZG!ula5Y zuX#HZT1n^qn)*>J8Jc`chjg%VBiXMDK44%Q9`pllmH|o?<%0*9KHb){5_VKWTn2RF z476tYBnhmXIj{;TFA;hF4b?Un!Qoe=3zU?@YRbXk6e zi^uxn^7YV)@(lH%jSR_#XJ2ShgRH>lPC`rWp(OLK?akEI>KAL7VSY7zN6Qe?^>|{< zDUZtXWNw1#r@-?h3X2IJ`gq;Po{;!=j7~`G4IJ?>T?n!G&UmO_v`6h7V{hh};ZdfO z3DvU3K%Tr>AsRp8|KZA~m({OV62_VfY#zqqtd2A2)N) zQgEb#u{YN*+f~EqNb-i*Zj3DG)b6jAo?eo(EF{JScP$Lt+Sxm4U3A~TOMHy0aVElL zh`wM#sqaeq;_T%Ai(dh^!U^Z-Bn|<|CTVPLz*@VyPSxc)NBgd%L=F`b{s(xDwtkKS z(i`E~7?R|l`#T|jLn}VdBRJofp|B%%R{athxwN{?rr2(-dbQ;sP6{6BW=nNSGO!al)tR+hjrod&aTLx%utTqBdXSw?U!#LNAIED1Aej&Vb zE=gh9i9s<2IC(5=2lb5C-B(v%9Ta>0^>{<(hBr`fuKF7|M0?e->bem8rBKcPbuR=^3GNuNc7Rz=v& za)=yy(Zfkx`Z2CJv)1~F*cfmaxv5q1W>fr;kTI$^>>V*#X_>JzW6i&|@X$W~(6Yu75})u!o3)ncnK4o>?4G3D$GlO=aKfbu4Y$;=fdtrc2Lz@?}xUGy9HT?+A#@{{cl>30N0j}J2Zjzn|f%}j5sb{JD-wbeHn`z`Ti z18cQtjjh#j=D3+ge8(Kb5mmSi@Ug_U#LVP{&xV3xALzQM3eq3=5o^OS9b<7Ec*bd_ zn}Ys-cRjDU9@lh^bIirH5V{i9av7|9CVf2VgH&shB`Au}ZqZs4`wIap-^D(@{Y+SA zBNpc%FYJUrmRPs4;>C1jvFxbAyp6eGfi?*UGi&0ZZ?~dzDe7%ZB>i;Yk6y-99Ws*4 z809&}u2014{d}}$bQ(&7qBJH{XwdJ5Aw2AC_PwjhN#+?UghQhLhev_nc4Asxds9f^o|NOe4j+~Uh+mPuu%O6d^%Y4TXr zVfu^eeiviNV?|$`2Ms8p$lWpzL6IGB_C$G8I-U$(Ms- zcIY)|QEq~6yBxE!11BAwmsIyIjNegdPI)WlO;7gCIER6O^VUS1G?dZ+&hp?-aC*|w zSsmoTD<96)`++7E6M<_r3Sfcb49u^~kN?+Ha`DzccK?(c(@HNEvJbQk49vzL={7l!C6 z#~$Rar~J)cHh#cOUK6H=^k`oW-vPOhLq|}K z=prxH+pZ@#7G490wuCyNCmSTJo7T+dD2wM(sd-B{3ghxH4%P3ir%C;us6tBMO_H(H?)>hcv$=|bcwaN9>Eo* zM-ZGNng2QTdMeg!gEUrlY27xOq97CN^q;r(OPB-oJG^eMeE$0X$MffY;W_pllT}i` zz6byAK>5Woi4TM`J|0#b8Uyt@m#uTGyI&124QCLiSjQICEUE<`Glcte8T6iLw5b1K zU88Z>ySEJL*f&=76m21!5H0EDIbl(f2x%j%)dIY5JGeN9#XJ0yFy8mpT!bu{b|<|# zG4f{4V>0iX7)DFHDi%oQgN^t-S~efP?=j894r$&N3TXgD&M^F$(T@${<7k z!Ie`eddNl~7V%4>5ramp(=V`CYgR(*e=$7ZLOiQs88!F4>=4LI8A(ho(Jf`C( zy<>#kQZ?y7uBnbTXR(9TA!E*Del0Kj&70Fe_PZ7fb`D^w3wQYqyqy;gdhMO1rUYrt z%G+4hukVSQsb8fo)LG81(!r}Dr>|Mnx+-h+%MVnTG=(z3Kd3Y>0+k0CRitC-cH$3E zzn7p7V{YO#Wq|#u_2>coDjbAWti_7h$aU3qa_BS9@>;B?rMtD>T5DSEFti*^@DdQ& zVqH|t*S}KT3T+EIq2W~nZ%y(_&=b$?owNfFhhU2?&ExP}XYp1m@cMB1JFhDLmQ-F- zNSZEk;dN-;gk@2H;RL@?)7Y$VO|5Bn|JIfUDFdWu)Y6U!7o`te6mY82jzUL_E2(OS zEC#qP2TADBFl3iblW?C1YFHqprk;;MoDQnzG+>5Z(gqj{sXAGOeHf~Rl*a;of*P?= z0e73^g^0E&jE=nVFT4>%o26DYAlSoLkM~PEKb*b~>2+a<5ZUh`#HOvarqsVkvUNiW z*wNwr4I2f_iw55qP8VXoI|2j;2xqlJrw%ifPCk}mujSLpFK;0`ufZowGpCZiih<+l)eXx?UlS4i?g>QlSuLgLXbp z{(c3?WVxm_OK8^t9zw%oyg^%`of(=W1B`|Tszto@gN3O$;f#!HxgBw(i(nPAr~GzEvxQ?ZjX6k*TKF?}!bHaO=uz(F?So8QE* zU z6~vR!DnE<42t!bUJ!2zfMoV@8C6JqiOKwETaJjJcei(nyNwsK#@KYFhO6!Q$*_F?g zS3M^wJZ~M1o+O}^d{zpJhhmPfF~sz9<+JIM{Sz$G05Nqetq@v{u-H!+8pajGPMPo` z^nufgeb({Gu@k|i-^%h5AUEgSyzmF_b<&y^0~|C!xn_lcm~+A|=rdCbyzqNKvBTm{ zFEgC6eB)uP5aTarW6bOJ)A;8hE+_vqMa8z39~L)wIf=HToR_2=2Q=rXzwp!UHcCAu zZS?Rs{6DO{d3;k<`UiaOy-AvGG;LYZq%BEq3td1;3kVb?O&~N0Vg;N5ihA1$+_oUa zZR*c)44@9U0tE*e9D%9>qBB^nGb2`uxFL)tEWc@~jD>=688wQU?s>n@P0KRl`+k0Z zyzseAa__lkKhJs2vwWX(n78AwkKKV1Qt?@Z&j`;?V-T6+A7V^o%<*B7y{?HyK|(|f zLdd4?<=7K-&Cy)yM63QVC>7QD<4~sJSFd7Y&~Mf$MvUV2IR&Ug9_$w4;cXY`F|B`( zTp^cWHC)E?;e+u5Y`odm0EtDc(wiTL2Dwra?lrg zR@*l;vP9cR2TgYm_fdYGK0f%*aEC(csAfgKP&4W);CcRH&06}EnqhyUno-Zaf||XI zT@DCqN;yxVW{3NSY8J_BsAjqUQ8P|y%e{RK$d79FC~AhYNR=Jlc!y+@Dzu2=;eHxfynP5fVg8c||!BD=I`bRoO>~UYy4`5>6Pmmk-{D z{Ta4UN^a!wICXH=^1&O>w^@1r2vtD?$L+1C;DeRj$<4kdvOQMeoiDn^l&>h?RSCYf zJD(K-jV@BNlU=?Da^zlE4T2i+!8wuKF)EjHPebll5umzHWAD#Z=DI&jHJSp?0H*L* zd=U7p7EXD#Im|=jCrY#*Tj3iDS>Xey1?2m}12ntfQK0ZwL+y(1uE70Rzc~2x!hi`i zJ=DdCCaFxSxQ9yO&>rF@xV`YS3jWwd%(_LYkgD;H)|Z9!`?_-EYT0AhQABUiI{~bQ z>zngn&-pO?m*5o?Z0*Vh-UQ(d?UlcjSv?0FZ+DTfmvZ8RpA4>^p?V$aqIx`lb<32R zkc}ecd$21Rt0$Iv*33*IxC<(AmvmOL++$)D_e8KMXobO!D)U zCVxIcNQ&e=c`yy>ZcJn6cW)@Xf%UbepM zaGCH>%^V-~FL-F$b=E63Mk?PJi`uC!=7SISXhA<*$~aKE4Y*#xMg1@gvsmnXzLJfP z0}Z2eQ&1Cd!KoEx{@?6L?JWD>-!zo*!LhyYD}cU)bj;Ux*I=eAdiCHl*h}~z-%DD9 z$ejbqodnzoBL9tuT{sG5eBbjt)|(2sWc!4dNgpBv+q?PT1;WFt>x48_<(p z<9jZk#BUXQv;=rfP})ym!%0zP!=ZODUx*jo1xrujEa_=yH(|$9yWYmdM7y+J;tDuP zxQpa@0%P~HEVVE0C^IF=^)@Te=4$2yA#oMthYxUdx$H6P1jOaUniqd<75>2OSj1El zqnGmAwOAo}CeF%oa1zQ!B*g+#?st9;>khKe?2u2#CNRDI_tqEW>uo{5DO>HIz=Rzs z_NT1Z+rIFV{DS&ei~WZO^-NRh%ct|FnaOllO|wI5mR|+N=+O<%`y}}WJ7?Z(HR?-K zDx?P4$Hm(7>R z$u3d*8Kk$6%fUKY;p3$u+)a^sp>t)BD`{Y1O;!#|B!finC=wnZOo@nF1-*F==Zl5Z z@o{k4u`+U0?3Zjv87qM%S2wb49!OwRGKVwEk?gs~dpT?&E?yPjR3Y^$Mc)WHj0u=!gk?~IO+KRX`%GT@#Kap(qD@mT96Te9<6u^F}M+d#Gf0b!Kp0) zGVp|AwuOi9QM#zNRI(K7H__Sl$I=(rJM|NRutZkN+%%V+n+i=vnh6{%aTr7kuWcTU z`l`4Q9zm{YYFGO0E%Fpzk{iS4WVxeC>@2AV30;vqZ?G3O5B=8ECSCLMrKhuN zx$)om4tn$EscAl#`7)Ch1IY`B5HxD%V5jtbYs;9|+3v+j zhG@+Hb0sWixSuy`3(hVa=Dx6$EV9on99ei)uatJj_Bp2moI)#~3v-z#10PZei=@TS zp0_14ULFqJ->x~|2Vy`Z1vzg9&BeOmpet7jh&13!=o|PwR`D4 z&|fYyx1(XzCS&HPy;2u~@sY%G#}lrtWfk>;GTd zdu3a%o+AS0$YEuU%!kj(gn|Ft9BD`YZCgQegs2fw7Y_QBbNaNxb3nf6plczWQPPzD zh0T&eBO>Dm$$oB}AE?iH=ay*P=jKl-IH%A1kN2*@dp)4zlz-&i!=j32>%!rM=a!Py z9!@u#4@7EoQ2Y?R(XnU?dZ^N| zXAvQ3H6w=$dXjn2+&|slg0mH^b5(xiIt*Dq_23}o!x~H^ZuY;{S7eUGV2;ILj&Z?h z;iDFga$0Dbz6Udz&g|jP-@?hwf~#R+Z-CYl&9Ctov#zEz&g{p$j(b5Ygzf6s~ls#_(#^MdMziru-^yqD(14~%$BwsVF#-+pa_blbc zXZktVt6jO;Ynl(?`R+xqL2qj)q3^pEjh@Gi&+;Pz&2geRXBT~hxEKsk3JmTG3whDR z8g9m!q5mu_Puu+T#-2s>wzIwyfrH{9^xhWq`EGCrEc;`>kQwLlu6%xB4BB}lz+prh zZa#>9+Ovpg**cWTvlLm+;#anqH?p!td*{3!AbLY<`|`YI7T$esAR>KE&a!D>CXB!*Uc;khMK3(hSJBhF6{JsRP(h%S@QKIKdEoz{L$)0>dv z3D|#2vBoQIA;hbL*k5)nhDJ~({&m-4s~O)g?`a%6N;t9N=F2--WG_Udp*ciz{=Jl> zjo#Jg8*$bg9pQ{4ysjX}-asW#E8hd&DEtC0^(P^ zFk~m5#g2s%2I9P``gXYv9+Cp?l*(~Cw$B+VF9jTI-b8IJZ;z=l;OsInKe6W7hsl3! zh`;**?IqrGKGxygxYpp1M&qVyYQfAZMembtQ^nGX4`!Mq6MLDx*1 z-RSjap7=HpY8rVA(P!R;k^6y0uJ9K7vXoq) zsL+T-pQIV|E-Z|6pmgyHrQ6suQ9%rg8l*`;&ym|fbtlve)hBd`kET9;9Q{j}v3Cvf z>{OSlXO;nVF(`FeO?4S_X%-dUYJVXmpXKEz)*c z%SKHmPNDM_;R8nWQ}Du3PJ&*Pde?u|>lnuU@|utAhg{we5P=!_ES`!uvSO=)ka7iW~r->}iv zi_xR)xs0EAKSs`g7AMsnA8fH2EjIX)oJqyWXz@qg6BQY*0Pj8;n_*$z@&HCG4`VVB z5$AXAl%IW#d=EIi5@6aW?wQ4 z0ZmE|+}oROxgT?{2XhZ=y>N;BMLl8oL}p(^0;ft(@{M$kEFOjSySnS1colffWN9(n zIlP!{{WLH!eL3$d!T?#L|jVJgk0H=MAxb2 zU!WgRllq-^2wv*RD4zfdeDPtG*N7fXuDK8hKHM4j8vRG-=b?7QfMiC4mi>SCX%hN0 zNomPyw1igwH_>U-r`J{g*J}73;wPyQWlviS{u1_dXPy|E|gN6L=$LPK7?H5E9HN zaE5dZ#T)wsQdnAtMvN$(Gl^ak-5x5F_UdvQWF(Uhmgl3sdp%=jDuw*c#nmK0^){5h5G&wxLo$o*@c;i zn_mxkTZ+45X>3+*>k-%-X<~AQnY$Lzsr+Sd zd*wG9!A-Fo9qg-PT6yp{v}e)@nsjPjr6;K#Z9P2!73eN~--Z+5)g0l!1H{#QsXV>4 z=R!cp{m#c_s$I`7)J)%1qME+DM4R8R@Vi0&i_Vo5nO<)9~#IZ5^#CaLq zoin{sf!&tUt%L8DUFDks3m;7}3r-u*xRPsN8-zERul#jNuY+u~2-nbioSTr=Bl$#R z-K5Fnd$`H)dc^GDgXx2aW~_&Lg?f#&FnloB%}tKPpX7rlyJ_qpvm8wO71|3Kr)9{d zHzG?X$vWNp6z7J>)1UE;qOGb~A_IS#9qlJior7U+67jOC9enUlkf55G3X#(fg}Z@y z_SmgUQaQh#@g3_Su_=b+J#He@cbrhPu0NQhb%_~*vP`yIy|zu6m8Cf zZR&sKuwgKV%kO{tU+?e3`}YsNA8K;Q1uVZHwU&*`_hSdcOwF$n*g9LTZ=E5pvY=dN zEwD8HisfXqo7s`jg@H+9LkPwN|IZ0PZ!ycV00tR z5yT4y8lj=4ys_$HRZ>cIQDgbV@=)_DKobO35u+S8gii%RK-(g`yy^HYh3D82%ZYtv zjAy?oKL@SDI`T<1AtGGc4%^0}Vg&>CFn0v zYO>Y!ujnwKMPF9!utlBV{rjpm+k_Lq1IBD!)N!}GtLki3lHswU6xLa(V=I6QlYvwX zmFsP$6O$}^(B|y+BcYXuvsM7ErIezz=jwb7GInm9Trd(Mr2Wtvd-RKoD)7wMUhX&& zDjxVfPSR0KtP1PJ%F))`s)LAC_7RZQN5QU#1^>6N6RqFrh-H$4nU93D;g16Xayb&} z95@>&kf$ovx2PpX0@00G7JO750F~UM=!bHvsw%T80q|%oP;A1;mysc;+zyOq3og4H zY>IH1D)a{QG(Jy9zQR}j7NcuKp4e5;evK?_qH`X`o=tZa7PF@rVm;-tY0d7eRUpvG>lVu$fmC!-_`hzxU^$t%bJ}r zK=)ZGyCrxK`;STNns|SuM1D?*9V_H#Z9ld0{;`OJ^nL3Xc3%E>;CqSYm2l!4|Ng2v z+gHaUmPw?Gx(=wooBJx{GztFReGv^5JoEc<<(0}#AY#1{4TE$#Scm6h7$;7gQczQY zIXhC(aZMVikk3^umNye#kv~P=gP9xMT7|dg%N3G{bYJ*3VJt5M$P=mnEq!316=y;f zc=LGZPg(G$KBB|A0WIRCk=}sS72x-ysM(Uf(4bBXn%TZ8c>ydfwf=U<8y29oiw9WH zi8_I@<#zi{%X@6y{&Vta>7rt1qhJpQMJ4ZZ{T1@gsxwtAII)jPARQVI&p`o+7V>Tb ztS4XYBO1L=q2~f{Nk}GRQ0P3}BVE@FJ#<;nLz5jnG*HE~PtS!}Al-*mlK9cBD)Gpz zLNF0N6tvH?;Q2w@CHnrO@}1pZGbaK2De1D|b1=^iZ&Cg(6=r2T;+D(6{wnWb<70e4 z4U|)*a*3ju--5e$DHgNKfN9m@s6lxx$C>F(Ts0_XgnQ%-lwTIo&OzFuo(9xV?Mrl) z%dzOOWPgm5fc*AEEDDu$1xV-Y5$`9hscAG9TmuV*n&uS9FdA&VewXz5f0XkD%Az)r z2GYcIKs2)94T|4tn8$63)IJ({3O%FTsj%@+^hb?P$C?{n%q!k9>bi!~dyL>V*)Mgp&r}~in z2k{eFPw)vKjzXOt-wyOwqi2%mUsRbYwDgsWp(v!ha7k6rEEo&6cR=)j>yZ zo?gJ*Gt^FibdM_#CE5>j5QRmHy?j9r%lQfTAY8$>@SA%C_O{elEe;>*aU54SF49BW zAy3!iTo4Y$g}JFiI^syLeXn2)2tHaj(CZcwR%Rr<3h93wxH|O@zmVEG7)uVE3ECYR zlw%lIJ*g+lK#Pos?SAfQ;vh@GL2}+j#)0PBQd4S8tZpUu2i(aE0(0mq*iA>IF~(I- z=_jL)MENhkP#$`3ud%B+qBpar!WJ6H=&<}ldBhLVKAk{TUoGL#GXulGwHlaQP=R@@ z&5w0jq>3^IY)Gk$xMWy}!|o>v*3K;WK`)RfuntF}&o-d1YE#rY9+w(d3iyI(tSJNb zU~Rr!0J{&#S}6pV_2P7qCQ2%I1y=gwppCj_de4Nb23H>%suTxpC-I;BI+072ixNa#tJ%RsG|+s!g|*+%*y=L){loi|?ZvyM0VOjsSsxbye!#H}xX$6;Ox*h#pH_VSjL+-v83O0`8wc!ogH^rUR>BSik5g!b6*J5HGwi*A z#u=POe727R-W6+ui7-}=Dp(0?0HDvPgCPuOXr zUXQ5p+wDwrOUZ6-lOC3SdP!gTkb?ua@X##Dp)cD`zqXgpN;1@!k;Tsna5R00fx?2d zPK~>I!5Z(sMIeCwtdhkf!=YLC2>8oFwSIA!h*YClQ^z6 zx8{6fMf%Pn7W{KpM`J`r4@wx^+?827rUttC;2xmV)xcg67;aq}GeyhzvKzje8L+b6 z%LSk9r8To@0C;xzwY`^{0YA9lh5QFr-cr@eMQJmpK!8SK?B;aN1IKV6HG(qLV95Mz9;9G~g5P-Xz-JK=)6E z-@bU`Q>M53v9G*~dmQdr;g$J!eDC&gXy@#n7RRet-@zt?;9_Rkd%(@2n0kvh;fY28 zr-mDBvBQgsbAUS@4%NY4EPrZvYI0UW>xVek#8fO>QMsym^{~tT)?8b>TMmbQrywX? z7oJ>PhF`yd4N|nPK&cnmolOi+ELQIbhpNMQO6nDmU0>s>*Fyu?Hr_?&>hUgSs>6Q6 zObtLV6nyO~xx9Amc6+Bh)=4t&#n9m~e}*&Dg*D*Ma9ya(C>FNCN^aY-N^V2i{qj285CTu`$a>EqmDy8`OKuU1~uHCqv#q|s>FRmT9 z!ideh9rNlu`t~pAdzPx!?Zx$XT!(PIhwGgI_8`$dqI>m7^Bk@Z($u;(Jj=)DpK*=E z_c6F8<0{6r6ju$d2XSqq@7Vu{*COACCl8=i?dG|8;4{d#ZB6fJH@CG@FKi>*i8S|4 z;6kP1Z;t=#YQC4K1(?q`iXdPPxr7#hjUTfK-fl53FRP{p1@*vhK&ipl0>lcG9_oLoW=_ zJF$oe02u}3GK7(?c1G92i>ej0#1*vUS#hFNkud0j-&^pdpzBnj$FE zCNtxd)YoIZ{NK_8?-99QnLY;fz#5VT*vDP22Qv$%UEszq=c{W{7x#r)KsVp$6Cl4K z=`cP2aj>3v?ot=yeqnM=U+5*Idq?5_sST8dIG!u5k2%~K;)Cc65b;{=4IKq-ARpD5 zrV+5*ds6=zcxRG3*l4&js5h)^qJ=2|%*Tl9r4c3WykSUKQ!1Ailo zSmTgst9>UG`gt5Re!h#^UpI4FG*+PF_cwh`FpGG=CFemeZdN7#>xD^g8N7L`G6sRr=4!V|oAWHkI@p&bX1c)(yV3 z_&6+2T&;0c?!YyO91E z(m!uI`f03NsIR}7v*a-vbI3um-fnO4#Y3x6fAjsfaFd0)_b^UQ%&!SJqsSGUX+6GE z|J{NydvI_sfG-}r5UF(*mJS;NYTb=!T`TVX2rsQDwC#yV+b|=@>zd};43sw7moVmz zS>$;|cl5aPO*?4@6I}7&d=hVo$&LXUZj8v85^v6}IU9(JmiEWPOv>OUI&jJ5CP*qshaeG#;ko>5*Gk=K>ara{IM zd3HJdgiH6}9SZsW_lgDdmFU#w_zb&MBk`f8c&*g6y+)b zQj2itJb2u_wwU&57^7=|xvchU+|R*E^l4a#cc3I7Vg(oW(uj8r(wSke1rZ5};wJ6H zib`&0B79o+3UvdhlWOlk=y>=ArcO`0F%GS`wl^7XHs2IkiJAk!H??mH;EpNXpAbQZ zZBp$eG{=F^i(yD*ErR#pO^_|!OxNdu0Z7Qz>Fqw~Z}xg|mK=b6Z>*PR!ahV_cxEr; zGZ*0NqV8p0qJsx-IvTjLjdwvZp?9ib6)You2kjWcaoW7MISV@Wk3zR%MFDF+k7CJj zpiWsh9e)&Bpxotgcc72Y2n2F#t+3isSt?U0=3mkPxAROuMu9=(+!;J^>B? zHLhY@;qUTNA#)*38hpmRz$(qyFwx?ezm(( z;rnkx9*^Lf5oCJZ5HafL$3{(Bx>Pg#nv1Yp_}3cZ$;jJ$3=66q7nPol-@_ z1gc9cWShCVp3sDTs+AUF@h_}hmH#?RWZfR=8r^&bbqL`aWs1~~{51Zl)Q{p#0TqGp zrsSTG2pa^!F9LmDEWZ{wTz~Ho(t9B5i|B~Lp}*pcQ;0l9aJ)yTN^ar`g>rf?4amvS z;6HXFz1mMSgLm>6p=W!Nn{Pn+QAkhy5=l$@7-K}2DT*93Yb_MpsG*uN~~?+q)h_KbIlDhX>n1s4VS+{S0*leJrP5zsWDQfVbLkp19R;)>^EB}aD|WfgofO^7ZQ4i!UQSWyPQYm13p zS74~I;@&$L-4@4k#wp^6^ZCM z6Pr;`R+gG)s99WNvIs%0pLu~S?)^p|CBAHY#vbjx0E;(x5WA!6qP;Jauc&A!3!$vt zCEh58s9F&E+9^}8}T_C%89!>icz3mngEp8cLF;1c3WI4#g0I1+|UPoyUJNs zv%)j}bwF)u1ovyTeIM9UwVkak;R+f-dkFuYnO+DG{@n8q3A$dwp1X$p&IpTy+Ddv3 zDr0#iV(&sPUr~0Q5_b`}R2lU2Q9Q-|Ac{5Ynx7zV>xHaE#VBSIjrOp?*vK?HnvpF$oeuB}_pbV#msqkEPw3u!F7iITM|zT} zV<2n9DZ!T~+{a0a(;q9^qTUi;DkR%Img5W@yz9gY;l3rd1x3Od%3I5HB?9qX%RR7# zNa9k`v;`lnIK6_NG1Lh?QW9!1m)S$ z)x0a&N>Av1I1~=&H9eSNw%#>kuAL#~nQxLsI+>@c^#V-l=JXefyz%n|gPm+plkFNitJ7ghvKXgo#mh!2=90U~w zQi=!C_&a*Sfy@6b4=hNpFM3FvFXY&bd}KVu2WULSdus4LBmn4>cvp(`C=}|Y(27u* z!;~`P#Kra^ee7V#DqrhF3yVhC*A13UZ6^LT4Lz=bWkM?a6E(iO3M=e~VST?Hb;-J_ zE^#Kw4&BWIx=99hQ~IMt51FY}(R_?uIOO#o54|w9iK478=m^|wti!GA$_z~Nxpc+JQVLrqZ?^aPJ(gj`^Et%4>xs6+xtFXE^6OW`PB+{h6$&q;dybE0Y#2kp<}SJ7F=kHGJnArv^^&17@h~wuMZ#aSe*0ba|N>V zhGd%_80^KaiLAKz8c7Jcdw{tnd@kiKgKt2uB*O|DXSf!#$x`HYvLz)3iB3lzOMyI} zPqyiNkf~S--6tnn?rA8Csj)CgZp}}YB33-$T=?8&1#-K_e6m3H3iI*TsM4PDSn}MG zOsf`Bax-!C(BP{yr*xtu=Pm=rmU2&rGV1Jy5N(mK<3yqExxoHah`}gw^#;&jN#2i? zrFgdi@+sbz3oTFsI3s$h8hlD;41O#p9<HDs^mMH$$mt{6x7EhCKy zXo0$>%cH9T=e7vFNw#k^$0-es88G_5)enRk!ZDBs#QCBjaf_fDXdx-7kOo5QAPpFR ztc|EOu+;pBVTAYI%#6qZzIjB@5iT2N)?zPG71DfL%mm;ddRUU&vS<@ZGkpdeJX}nC z=T=w=S$&oyxPNkp5KuFxuB7S7{N<$YR6NZ*5;g^4Y< z0*?T)=ZO}wI~)jU`yNf_rY*27DRSEu7aear(#V2Zq-=5g7WDTGTvVQ}X#w7eamEx+ z%O41R+q<@g%U1b)BD`@mi_4L3b{~9eB6X@O|2c5^-IiOqJUZz?64o>~HOcpQW7;@X z+ii+YbRcx3S3CC!mU~mw+_h^hQoO}3@ipkpW-aSe@;Hw2huRG~j8k2l#dGUM!fyla znyz{F;{x~_Z3YK_3w|24;Bm%sqJ4zAq;h)Ml0^?m7W)#=P{L$waqL9@5lxCiKWJ`P z&lWF+(P;2v;0?x^D{kE*;ft-$Jx=x$QnQ7i?+07Tuo{?K#% zBVm|HI`e1ye{O7Pd<64$oCQ{(=-VZTy>tEAx9%ieRe$I&{Rz&g5(|C;3M@dQH@OF# zBt9qhr z^P_c4Z#6&?6|?%dHu4=-p4g4MnrbuX42kufztC=w>sFJ8Gf<&s&`E*Lji3&4{c4uO z`;3+M-^@+sOu$WobsViTqx`sjH%^#3W?V(6-KMNQAf|H@^<{*pWe1MA#y4Mkym8%~ z=moU!Hbpi_ah4Q23beMxv8#i|W;85oV$3Qx$zQqP=zh@jMp}i{hHMFW&YPaWaIve&_3u?1K9A`RH!VoN?H|=^G=94#{&-w;^(` z3;T%%qfTe%PVEo+i%X-%jAmo3AuDH2fcAoaO(xDX8H(d%V(I0hti<_r@Ho7>+G?3>m7Jzw>TVGYTYNO|8MXKo*N7-X@beh z`5JSsdz@<=-Z|J6myt3|&uiXm4En>FI%Oy+Mu54$rl*%5Jw_>m5Gc_XH#+fr+V~Sa@ zq>pV=i<~*bm4RQ*z6^K9JO$UV4oKmcnI&PsSJ9e#T8&>$Xp89tz_vx*BkjIJbwjEP^#8@~8o?6Fp`Fq%EW$=k~I#e6S3tfo7)OtHSrv0XNQ~ zvLm@hwGZ^VYXr`zS*&svAAGZ43+W*D8ea@;Fc3=E+h&ddJ8m62uD6OnJd|5lg|#I^ zw0bgbSH_%ox9E$oZd5Itm03CPpe?LLKU%cPw1a@>!@Ve~n;!9oVL={aUt*0D4OYl9 zIKdv_>*-yM@}3|^s}@_~Daoe{rbv+xV-9&-dM+r>x&M3~WjUKO|-M6%4$Yh=REOtTdFn2oq(A>5~FZF93|#jztNIC_OsU8Q#>NYGe!BBtD_~t zU}Qy{Ro6uNsncP~DMi+}HnPV{;!SEN3wFTnH6C;E7^H;Ii+svV{yG6zC6O{&W~9u7 zF;uF~eO@1B`C6+*?Tm|atXtR#>u7eZwZJw^!Qdd-JMGFzvIgGUCl(P$L)aYPPbR02 zKa1F@R2M3P6MdHTs8y1tu3T-dD`;E227S5sp;)Vd3=%>pUOQ)A} z-ks12nOJ@YsI7NN`b&_tOumnqU*`9KqQbLm;$o}d&6kb0IQd*VXi!;!Y)Jd(>RVP- zr$18^>xE_>yhR+alGS#6AD;yI7HIYAWZPGeK7JA)Oqkv%?&Qpw6z(`Wd!%zzGG0JZI7F*RavGmutpQGuVHzYuCUI12woMeZguI?F#0{QOAk*F>xdR zJnGIB+;1)AW9=TZlMU7H_+b5_2kRGeseW32fwGT$jeP|1wr=JoeH7rQ9)re0!_?3w zghR`Lb0%rc%$o8(@NXf1GO5jy{e80eL(4dJdU?96%D>a98Iy1IjJcOfx93Zo#RRPI zM5ZrK$YO0=w4UwC<0OjGcY68zp;e&1!(3XirU_9!eC_%;SNz;$Dc+SVrNLfgn>_~- zr)3%N9a$sfpIM$NovC=HVncyJ3PTo5bbAqr={g4a_8_x@Gd8s@FG6IWC?7mbxfHur zsz)78FQ+r_7S3STNg+i;qJ1f|mSwPQ{8nx&$>K@-L7J1R?_Y;#&UxTNz?J5CWe+=4 zLOYeRTbTuSinLDItuW_tR>;6UCTsxr8j}hXYwzG*3A>;EQnhh}s-Q)$YhDGq+>ir% zBYdi+X$^KQPFb;P-xEl!!p;i2jDA(I-tGZP$)`y3hrzV0BOLyvy_3rPrTba9&so-i zwg8{mN^yl-p+!bLi4TW%j?kLv0tezI{h{X^?h|i~ixX+3=rP`3VT~}x54N3XCAE|I zInp%z6=)~4!+#gnLJkw<+Y6oO8nXsFELo3b^hYpPDegl}^FKJI`#0LtIM|*b=F}vd zs1opgU3jirH_0pS!3yR#;jB{cbl2Nf_};)=Ue__leZnvyS865A5@h&hVH16O85S6~ zJ@tOb0{yGj_Ylq{PnxfDU+=oU*a_a_^FBK7Om)`V5vNpq+@ZlI&aLs@SK8RHhU~Fbc`eXT31KmfW7KEE!*OD@J*-c6@A4RG(`w#WlL!1A z(o^O!zMjLkHq5nPGZaevmw{n!uI{bC2)EIwEnK2C#;SbV%t`KKR~#%QlH3g*e7ARc z&IGu+&jRz!I&fc*TTXl;K;uAtDq{#N=+lRW=1Frn{CWjv+W+E^$q}YU0Lb+z^GB7WW$`z&hfu zW{cb664ATbj`u?=;1QViAC;eDNsG5SnB~pc z!~BoRdS~KIdRJm?a?L9WFUTw-2YJ1&W{tTL@zu2cIJ3(h<$P2hHg8^&;N0x_Jiz70 zO;+W6>px_U!^uo2emg+zor^Yn4PK4b(B1e>Z5`?lYCEk7hJN^+(pHvXVjeR$DI8iK zHbLVHR$0F6yS2vU=#< z4Q7Me;4)%vzusG&uF2(F@4{bITbg;4d$?;v@ehGN+f;3$dAK{#l}Om*UasC4U1w7r zAB&NT!KxJFT@$5yq<~+b`e_$z#cG{21!42LJX2K5e;b z-D9}+;0huxJR;Sb$Oh`!UZ9KZV^Z!B65 zS`eZ2v7q&jgVqykJC*YaluSY}= zcA{p^k}BZcN3uk3luG7Kx0dDo*Cfca|PZEaxv zC4^&OsD0Evkr{B78s1M<`p`M`T|l2??i6&?7gHs*mHLDFC)l(RC;^bQ!@l76VU<_? ztWft9YHatfw-vQ<882DUPkp9&osChO?yk_(rGq{iYk>$*-`SXKrzoJR`rI@xtG_A5 zt;U(?tCE5$5p=y^rHBz^CS|lNh{7jDDK#YwwnnTz9aba@p6(8Z=7yiLeFZ-Y!Mon} zd8?+L_f9H@g-ZS17=h%Pe+4)t-u;#1Np=4WV>XP=Q{y5!vv6pZ(nC?Oi;OCcE$3=? z*tx;Eq8j82h`$}mhw@NkmsH_g*Dk2gui!^SqpF+cjz_T4TqizDqwrac-DU_P--qsw z%Xlw3$~VmYjBP~ggOD(>lyPjf7Cg7*?s6~JR6cG>0Zs&T9@^f$n{%dk@YdlTte;GN z?$^khVhEBhjOL2QL^I$apw?yjhQrQHRO*uKO2%0Ze_=`VsJsa)HZq2P3rpg;Dl=PP zy~9FuVBEy{TnyGGA%%+-kWq56C|M92Zm(&kmYfa@wL_7if*0ci9LYr9KSDhKc2 zQCnZMXrL)DNE2Y^d0JAt5~U>y4UC+7cq=>5!nW=eae|JvELov(tEZpFUjt4EL!Sm{ zO-R10g3SFxIzQsfGXv|Ewa~dmhrXQBt7@UjoKb)~rzOs7|;Vn*RwNuPvnj`Kq| zZ%#nkx!roVU^d8Fae;L-dTOLA!IUh8LwVi2WjM+l?%tw5y&~DI&0n&@xXKviO@Otb z@7_yua#I&X=w=Uc90jYrXTfpZiaADgQtE~}QQdxv-@h&4tRz2G;iCF`kS+^zayvc+ zNXG?d>?*G|+1BerED42kODv(NBA%$01f_plG}h5>ldGo5AdQ}9a+~HBKwiE_k(a06 zFdB1g%!vW;d};0iNG#epPeHHWYB9QvbL&?uSz%aldbt6!X4Hw4xrQ5BEGD*3=7QG^ zyd-^hQCJVj2mB-0Tj5X+tY~KS4TPdWb+rH3KIeFV^yohgXeWI}a~<>i?SEiKVtx!f zID^q#`K^wbJh;N)Fvo&uC%)6g7%uQRccMDS~adf2f3GCV&mWO!`l-rJJ=tQ*}Z{&-ibDl{a^{? z-RCpZx;xRKNcLLM1Mdda$<%RvH5u3-X>7Uhf9_IV`F7bQj7TeD6sk&df=uLwyBMMEz6EOR6Uo#8^{6 zk4hD~1^QuTmTv>x_-=ocWig&!Za3Nau@>+jsE2cppew_rgFnKKN>CNQUM727=q}{# zl{)-B(n#_aNM}vnN@FzHp+~-#D&I-3480`FSzEn!0rUdAc_8%tK#cgst@goRUk&8S z9#~Dz=kg{Z;zYH8I4doP-}9Kl2Q{Q~GZxwGMUrh+QM>S*Allv57IQQoYyB<|gsk)T z2hv&AjdA;hErba_4YE(z@zwQ(5_>Y7s!hW7zEE6`#d#PrkHcL}j|tz^+j)Fvz%p%V z48z+LmiqO^--1u|rCU;f@&I3pFb{+W0nrFYz@zl%KsXDCoY*g+akL~t(*8|=5Xk#N z1CZrpNwmIy55G@9q{>r)NYIY!Rpe&ZHn)hh-%{CnlsO3($2cys9_B;e zN;V@^@S5G4=1+@-R*n-%Ca&%>)sDn7`gf(A59cq?iQ%xC<{^(!`ARX@RjBnS=>8+` z>6)pm8>yTtg~gMIRv|%6Fn^ZBKCw& zdT=TRw@zH5BxOp3FGc(b*#NIrjiz~+KM~c zqsE-twF-U~*h#+cj_IK9MPVwH<$mC=xFg+afPOX)x<85&@>YNw!-6+<57p{N|Esuj zukG!C88zt(O&w?sP!5*xN#!#=jFXyUkVnTXeiD5VX=||QeFsx~Mm>(Y#yFM|pzwNFdgF8)Kxim8Vtg)bAiyVHT@n?;LyT&Ax_>&sUwT zERE8fs*qa@B6^KOB;6JR6L}U%b0gABfmH&tl*3!f*x0bvBDJd)pR_y7)#(z;Mx?mG z{<1pyLjMH52s4QlV#kHXDh9a z6;*%37+n0cVWZUo-q+r+)@l;PVG}Oe}L?!HieG_RA!1}dsjG1Vp%`HPnf|k zF-~L|g^J&@b_J)54Tlp8`V!ptBBd|se&qN3OTU9n>mfT#WZa8t_yI5P*Q8GYogjQY zRr*90PU^#)GloaQ_-+8D9l>tmp`BThM(*nSWgWXMz8o z7b8n5_ zhZQ|<$m<+gyRm$uTn0wX?(u&I)4I5zZ^^yFJva;VM!4RUxs5D#xY zb?dsg;p~C@-{Q{Bz<}j<8C%%)fXY5s(nGRD@B6r;6m4L> zMwHo(+Ptgm&5_#JQX00Js*?<_8|Ld9XS4Pb z9i1!BR^Dn`;7GUTL(@R5v8PT4jW<_UNMfakefny?M(82F#)N&a4*TE&#~+RHgLVv> zE`%KPSIDp03@0q|mXtplEz)vHi*q)I_vGldJHJj(o-z+hQJc{j@fsE zzcoUywP$UlhkpgjWfvV z+4i1>jVw@cMeJkc|m#p4P2;Hv_ffDxZLKqN=6`o{#khM)DKk{1iU z*fT94R%85NX;LAdtzM$MzpCfk&&y@8a;KxrA6(#nC@|B($8X^7k>jMTY zW3k z#+O|=%kZ2-uH?4b5X;Axuufl_I$tNv+Tz#*?ZG++&q_fjd>x4>uP;>8MN!kg>fq|L zD_L+{|Nf1&;A1`T0o=cKKH`^;E9=m|;h4cr7_y|Qvi;J0htt7=OZ)fBsm7Ni$b`n` z$_r-Yf&zNw-Lq1ScE?VM`8Nfqmisrd3H$x|@^9qL4(*iZ0@OmFW5LH^Jb1_bw?;VG z{orKp13lQ`sCN`FW|{};vBLqaUe*NPtB$wOwu6o=Ij6F^auYCQUzB(18)jF0S~{DZ zS=X_$YCes@cETwLwJ-EZ2oy8{n37W*UDNpi!8?ER6c+Sl@m*M>ZOhQua$Zn77|TPD^dS6>WzeBrwys9C6v- zaQr%Olf#0Q^BS;#vY9a@SE5vIq}uLV6=2(YLucS2#(dKPY-e_*3HIxM4|^>8L67d9 zZfvwjw*-Edx-ziDaTChi(znF1Uta3)8um-Maw*2--T?Tu`ecdvx;Vf=!|>kctS|iF zgD|8YfGs^_cn|(fq*IcYeV}Je8yw)~CnWpsm*0eyLL4YIkhI%|fy?I*5f>uYIT}0o z&Fg+RJ`*$WYw(1Tb4ORx9LL8FPt)JVdK_=FIkPq@`3xV-Ctk@XYA_$N1hYD@k0?2P zujKRjWRE@UG!r3J#c5ZK^CB~~ zvs`H;?1rrPPE?}`Xcd0wvcGN*S`a0QPqu1Y9@ADw#VpdX6-Z=jj*;ZfgT9b0KuyzQ z8`nX}700|$QKv*^2lkCv#^K1!lQq(Q%C8xaU25?Ay`fro6sG$;mJ#lY6%89rQnH=Z z8ym~ZxcY{*Cd4G?{khnU&MNekaCPE9b#*>L*`>&L*Vy=NfKF!h>Q7DzmO49+dkt$3 zEBDR@=xi}`R_+bil(P}_%jJ6;F5L?@{n|m4k?3MPi=DjwKolD}KC4xi&DsuiKpxVq z%LI0(>DauBK(bvbYo~+c_)E_UV!2#zPiE)j-SS7$W^jO=`o+L8gKZS3@J{$oX!EY7 zeNo`1*{MHt?86$`iku(m?h?ZVh*8kG_^cem{7-hMV2?8C>{M~PV{f!)*0j7s>@V}y z=(W?1$-80QJyha+V?qu)qd&`XT22e#W3?USjtW>LN+@SfA-F@{4$o^aQY9fEuibJv+dgO^c}kJ^hd4jY>n(qiLvjH z@02>F-O^6!7`XEFx*gWdw&KADQ?6GeY@kX0B62aj@0P&HbHz%rm@)Mc+tk6SYS-Z{q3g} zt_pV@Xkil2T)2GZFFY%`Xzm(gjRNdBc1#65%IXu?S_fCa{N32eI`!)@E|yP-*Lv65 z@6O9%eRNyc$!w~oix%ISo~xOTZ)iEs*CetxWYeU{Y>?JXk;noKF)3<<5$o8*vDanU zn#(d|d5}a+7Z;IdiY$o0$^c&%wI=)5B(cS?9H(le>SWX`MH575DM{>M?Nsd%l@Bz! zcQh#rsc}PgyLgyh?K+ef?-DLk&(_vTC>mujO$y{SZ0IMoojX9qsM|TwxicDBm2U z%{4RfUhoFGsOJTxq92cHUxqY3&-LWjmU#AorAo(B?nav$EjuiJk#Cewfy{kneg&f# z>5-{<6*70u!YH&sT`@lCsmjz6?Q*RQHFa03P+kqjr4LtHmL;0pLLS`f7NNqxx(%y> zMO>j#qt~!v8(S=k%*8DA;i#QYeK%_JdrKU?9MXwNCO)ski+N(+)aiEVZXi3V)z*eA zd7<(}%XD`^)R1z&s5i<|P{S zoo-`-&2(A!x^6qC_rN{Nq+jH~5Y{%HG3O`^1@=r6})K z1M;@v@otBm0qmc>Y)Qc?F4G>c$o?kNA6X6{|8Bj?udKr3ZSFZ4c+O;Nd&K*gVIN?I zl{7?f_-ggj~F$)VU2q$=|c{;bT3*sk9v(^1nbtb_u?8J?}Ush%HC1t2irC5EVm>!xX2|6k+f@=%H2hr~o}mQ4ff&4YcT9qz!1DX?qaK!#sCv^q zt64^4G~l?78dUB{T-4xqC11D=F!>|9BSzGR87P$u?5PXW&ezS-ey00GYt>2m|Du(| z9fp?n?#2v=L8RO-J|T$TyK6a7T%Gzm81*eOexGLSB@_(bBV_vTA+q?GAW;xOCLd8; znQ?at6G!t-8c(6qqaK)AtS;EeFDFf0J=Ut+%Qr}o19zSFE8qCTjFKtLu-5C1r@W&? zW%Q2br%L(L`ncA;oVD)DjFd_S_0WZCU(&s({Z#j{)`D99j9Q=kuUdEc$6C`m%i=Gf zb{9~)5-V^rH`X`>wNe?c7V!wbJI{>x>F{AUl0yR0qk(epd&iX9f+#1`QmZ#gq)BvXk#K zm65Qn^EKfmClD3m%b9`4hyhn1W5Rf;C?qH-or&8Hj>5)Mei*H@=r$TY`n*Q!hQD4gY2s!FHcEv$Kp-?BdybSx(nZ}Xr9sExYTwaN?)*TeW9wLorTLgs> ziHx47a79ipPha@5OBSOPY;nusXMGMot-F!>jdNbfE~*5=yuqb=DUA>XVWp*3&Foiv zlYHanyaepoNBl2Y~vBmhvedh9k_Uc zF%#$5?|yL|NZs6lhIyz*B&NQydzpLu?3eP3NJOeO+x5Adlia%AG`Y?#74`^FO+>CS zZH)qZc3(hytuLM~I_%chqyXZg06sq_ttPGef_}ZNrx-6x4{;0pzWBI!-t~-jqwVZTC3f)jQRpqK(lr)3rxcK(r9UG zvq4E416Rt*5QwxE@yzzQExF?Y4I8i!lS!D9|2;omr5&i~AlimzLdD zkvvNKI5zPGWQO)7#qZA-^Ci?5cjbI>1=g@v+MXpliK@g=nds-qq!Nr_$HgJqZJ)OO9ZhM) zo_~s_ATpIY2cFUH7iF%qZYFWDo88N@SYDqH6SbI$e3w>E)Uk4{Je85t@td961=%bH z7j0=g%RlJwR~*PQMYX_2(tOTJZFvVOQ`)?Hom5@0jPxC3BA-wsUDL9RC6S|H**oGY zwEle^F_ioh(AIRP2$cdb)0?Orzk69COP?-8Txx!*EWWF07cA-2SGvTnWlusw<+3M$ z)wkPDv@Yc$W39HrCfc4{tjHw#Jl8+hu;-}Vw!ihVwZctUO5`7?c4ol>d2_z? zGoZ=DkPAQ8#YFFAutPA5ecwuRWA8T8`u=4c&F+Pyq^NS)fBgaXqDWMure}A%gRLQiz0O*bdTWjizf*B*s+Pgg7mvi{PyH2UZgPmz86r z3ID_S9z0M*M-GLsf9Hl-kzi}jH7N59dXPFFo9_t-4G--5gg`2yP z54HdWyh)y!{uKfnLIN9tr}Ikk9(zNIU05n_lR(MSxhFY33As;h&QJG@#LOt^ovkJk zjA%KS8qh}A64a(pVvhug8e()<6yYX*RA@QQfY%kOWUv}YRBxkn{LG*o>Sz);J{sr$ zbTd0_3J>nrFr#E#NYHk5Z+bOnVf;}h$neZyhVJFg8TIB)A7>N-b3WY%8%Mdz&dvC7 z#^ejL5hb_kdm6ybF2pOq>j7j5M1vgW;WH zCpqc;n+d$);Wo6T@hJ6&sb6e9diJ20xMgRv61^}>&^Wz`kF&C5;3k@856a@ugHlDB zNRMbS*cKJ`*uw5$2=D&YN$nD?RF9re1n2{|5XBE{?3aG}V7*um-v>Q6+Bk*n4u-~H zbN6W2a2%gOvniQvka-*9v?q0MYEyzx23YNuXx*ZFRtX1+4cpnzVeyOg3f$k*I41;1 zqaxtIjkoE1)+4XmBPTpIiw%#>W(N`>yCCj=7t9(29P6#L~h>q)G`0$^p1@6%h|42E?nu1qP@IJH@vt9}Z_BoRvR?urcV zTk}~@Qb=Y7`DQF42|-daDMUHgorogumrrKbv!a~ItjAXO9kd2hBa6#LdA|A_AoySj zZwzVi%_mW3jgf`2bmX4z|KV--txW9uHJJ)gURSkm#%^nJh`Zi5BMLps;ACGZtP@L>8y60~oDbf@YB=yah5+Wta!Pp0n=ZBN&>=bz9qMQxz$xd1E z>BtJd20^JnVxydC4w>adj#%^J^Yi6@Eum{vj@4ZEm!&BULODpxt z^Uen!fO@V`84-G*OZvF*G*%=PWpq_fa<+du%fzPO%+qWZJ%Ls4nwiH*)xb8dT<^RT zHugXkE7BhZ+El^ycx=mnvh;s@aXbr%2*{CH)YB0Ulq%x@;IEbnYl-iz!8 z);&+f`fR!6#*`v6qb;^DIM`F4f|5K9h6GXp*;V-K>1sku7tJCA6DQK2Gt)NGb`{nB zQ@a?21Q||r+-SXbBYTdb*S$!#+C96Ytp?L{mYxlas6ji;ryz~5wK3s*5_=#z-c#?B zbJEyTp^S(;V44zeU<*4YZjQ!Bf5_^qml$%`kgj0l+b<(NsNdzcX`Ufz-1{g6cm@4y zQ#(qI@BxlG3s^e+W}Dr|P$CN`to*<;Cy%|Mt_+mL6NM;8vc-L?f%VsK!o1!BJ0+wa z^6s7(!<$XCo!*%*yLdlqipVxj{@^toBXqx7-~}HNjaqwB^Eqc|g`_CP=`6Fa<@E;y#&8^F=Rs8!fR7l&wPW7MxtV?r?X3RhVhapd9_5o zkIiOhcD5q0TE)g{6IlsLdEHs7d!6kF=GyUDgJi_F&URR<3Zc2DvokbI+yHII9i;jz zJlWk)iHO!|(9HT0Skw|=D^ecQYGO-J9#v(UeSs$gf|23EhC zDCr-oRY4*#U1j(XW6&YQ2Nxtw0NzMURQW{-%8~PhL8*K|*nVY0> zN*m;Evn=yey_$7sw|n(eCOve|C3<0&dFy#`UDct5vdj#*M^}k{Xp(P^ALP%&;+rAL zTZj?6UMGPD{i#05dA|wulPJ2Xsjm3qrsK)CU3oW=R90#za+G>D<)5yVbIDxcWK~E~JR3pI+g`%@M2uHz8F^sRWEK7HtnCNbS;SaU8;~2A zN906t*7h~Np{*ao$!Q+zYZx6(IQJIx6{@^Ka~E_(9t?lx}X;AyE(r$7%i*}^w$60@MOETx1V#Y38fF} zAK#P2-7}`PqgU=f(Q~A9TxaP|_Z<^AzJZDJ#D19Fm=R*|X(Y1KSbyy#t!MrW&9~Zj zwQfMdAJ&Eff2KM^I53foDD>3^LzR)DBI^ zZ)`y^RuF6?csDu6Cjv6{c>kcVi??uL%Otj3+h6lt-8XOCjw@9Ly^O#kGN zLmH+Rsp?hZlmD%j?zde6Ere01{bB3}94IFH9~hhKc} znE|4%Zp@GYYH@mqi0;3PA|dKVlUI(nKDIDL=9B#rRymxK)Y{Q6lbmH%x6o&48ibf% zgPrp&EDsqRRkLdS4PA-Ufap*4%o-BoQSD=x8x#j^{3ax=LqjG**6v^>?;7uKND1af zxjM1NA$_FcNR4~`bvIIautu8apMP1lUe*;jC8 zWw*I@j?QvtnO+#3Q}qrlZ3lC+Lz{8dP9?Z|Td5UCx+ST$jH2sI4Cia)A&U7yt2ke# zy&gDSOZPZYS*5$(&fBuMHShDfaD{JvzB&aOi^i5N)Q(2>&-bwFQ%JPhT^|T*id1CO z2IN!AGmGt__cgqP8n3No@xQe;iA})!u^L68Kp$Sn*M}AIV69T@P{k6xFc(%(0kE99AGf z)CWw=EnP!Nb%CXj(`x_XBq;V764c{=NYDvx^#TWebB6@QM+kG9Z7H)YSqIM59zhnzt8}r~z`Rl`y+_zHMJ=@}w?~ooa05!|kEq+wz^=F*$6 zmquD*3lFkh+r4*$0=Vo&+_^RR?PlgVWo&FZQ8>OkYkQ@cPv~A95A_{HW@*_z+q|}T zZ)G{{aSS=^+LFLPCThQ6kUe3B7ZK8eutu7DVG-bc+Xj_o;_q|QA2dEX8%_es0 zHxK7;A2rcl%7t#rW3j5j8v(yCb|3a^d6uSUz<1r!GPl0t36z_d-tk5g?LF*kY5D1y ztD_YCL3;5_(A@CxWw0_k*2E{R%yBibIHLt!Rk6Irhg%P%c}uh#u^vpqe5NZ!&w3$F zL4C4~pE+v~*A)BZbM?=vGpQbqr@z|ZliO}{#|~7xEu;BM*grU>pw(3&(z{z7>orAk z4_O@&9*0<`fmI?>hWYWtjN>Uhb12h=iWM1zxlH3tyH6Iis=%jEi#c)gZjEQYkAeCC zA;i~!nQI(n@xj@lO7MMz8S14&Ez~ljGqD7GLtt=5M2Xt^VfuP$Z;K-T#uM|;&E#*W z2w^G>2}3J<4ZLB#`UUK`2!F$5_((HCBMQT|8n=%d{0BJOcj#W`TS(( zeZRERHbmC{uQu#&chtVjGC?I6FX^YNkVLFyMP_O%w80jq`T%R>bCNzO)uTB7kJ`Qt z>)^5dCUZXVQ#{eRMgq?jgEM(|d%%HVoTqx2-3M!knEOCOxkr@P7PP+^s_fS*-SKHD z7=}fWja9K|RKWfh;XUfvTy`VtONPmn{p*W(!)9wj(&4F<<(Y>mrbFuUX(j`kqGAvw zW#Y!Nm!wzldy^?(|3z8SMJI^JJTj5{os)$X`b7B9*ELutVNOIeY5qJoho(ag*ExriE3^P><99#)Ao{IhMOOy}3h1ORYhM zsUbgG6^6&_W4})OaX!UaAoG7ca`f`91|N*QLj$PmB?eKR6o`!hPvcckJRO;%8Immb z{C3-Sj{*+#;YJ}Edd5><0qLuH+isiGELI4Sx#l^Hj@6Iw-RQU4X2-h$x}JW%%e}YT z65HwLc3Y&~@os*Eyep?oDZsk}v!yxI6tmp`>m!7CVqd#k7O(MxM-J4s-S&Q4P!{&y zAZ{WAW=l-_&CqAoo^STPj&C8kleGdS!w!(I2uyQRe*4Z^RU}F&(M7f!$vuBUIh{|#|=JSnIxg&V64MSbWF3SiJeg9zx}KVi_*FpoX9igpOIr?c-` zg+PEQx*kN*Qbbc|?k&ejjJK8YSWY?A**4z|?@yon zd#iAuh(i#);djJoDQfq31d$>HA|QxEfFL@0ynppxM~|acPa}w*a0nt~*B?Zn-MIi6cYTl3&ge2H@PTrA-&WcGO)0`~tsNk+XI zE(%hHC?%#JrP>fg~XYQX-rY>ZU-h4B{VGg^mbFKN9PVfe7;w z*>$i(eYS`{z65XXW*v=yi1pJgp1DG2{KvC1{xh$E#(!v>NZa6u6U}I#dgB42Q3lo# zjUtUEyOfJYWkY+3kUw~>L1-Au?#2$MXUC#w4I;=4#A1Xw)7b$i(V=ZfW3k;6c&#V! zTB>;y+ko|Ro;5{&9ldtZ{46cx>BN37H+Z5f51rRD5L{2a$cf+{M_YtIaOrprenc_c zd-Z;p=X9=9{FBc6$2yQSzGHXdo;RBi7x^b0NRa|k(Nat8kz8cjImT{7gUA^dAx8L? z@GyTj|2-xmcE&_zO)6{*x0CF0q~A zVgO&)bzqn!Hk?TUYlSqv$;E7PI}zbwk1oOLaUjCbqtKuZDNSj}bgl+->*uhJbzxS$ z(D~hTCtAymNa;YUW6b`Jbh|V-&~V39Yc0>diix{d|75GbZ~xSZ7k^*haR(_);qcVRVhXTQ%gNWOcD4^36R-g2 z3jS&nUHw(C73n9Oo$FZtJMX1ExxAgmYl*40;c>(kGc@*`6*CvUe{3Pe8-+O?2tbML zt-m1vCALLRApk;y&$bDeGZYD+IDlB6RsY{8YUO{SsPFtw6gA@?P*e%Vy31BEP}CAz z9w$SoD0!)tiS>o`;;WTFU(VGeQ~w({>Ol@i6?fvOPvYw0CvbHUyf=pq-tEL0wsAP> zqk4*~e^mWgB4^QOn##@5&%_OUI#G3gB~}=Cp?-D$3sawt>mOt47wYNS7r>!UUbP*o z-(yUjS3C9@n7X6hqn-60+KH*d9zZOl7&^g-7lDqTx`M7|9Z0*HdtL>e7tYxbk5P6< zyzw!1PrWq9b9|l8as59)*^dLq0P|H_$Gs1n*vBmnPo{F)@k<9TQ|bKWuU7AHid+N3 z-rs> zy6Oz_|Ci`CbK|oK;}b!$Sq&RYUZ8OgCkDK4+pQQkz2i1B1y z2L?Y!9-$y2zVbYPwDIJK6AiurG~Xfl3px7+*)KqY zYwN#7Ztr;~j+2Xet?krhQ=Qi(H90WFBBuw=YfN(f@?6tnoN$xH743?Ioq#NwExE|{ zc+y6)+b%URabiTHC0jb8(f(Qq7s*W2it}l-*%4vuVhJVG3ZWSzsj#OU(TH|%G<4LT z`u`M7vU50T9wf5}@$G5 zm16TRb&i)qmO?vGXak2r_wPiZ#hoa$5J=&PPQAGR76t9YnNAdXYv&xMHZuKXBGytS2-&;4Y)zPl2&e_2B$iBV4gMxFf+7O?0-J*E?*j@bWC7 zX`op1P!4N$cu&eI4JX5?Phri89M()FU6`{7`>!0R^^#81T9`Atfg;-h2Pm=~HiXWq zWQ;tC?gC8O8<;fJFcTZ%Nc8ysH1y`4pzNF(B^)AsxpP$Rad`#pIMv>PLCt;6Oj(KI8f%{PPBQ2^L>C5g+A7lgb4LX z?y7d%pH7VWUBoKsntTy5cLlG;qyB^^4;>dqHmuvL(W@7*`ejMrMhenjUKg=&B5ut9GuHE)l8|6Ksx%^7x zeH#t}vxtg8mi!{@1TS1hvIW^B%9m!z4^2_=aIn~&WjqpUNMq?qE$=&Xvf0z821+)(auRD;VG)!*x?`t%SE|sd})eXubUBRLY)4*dzqn#^!n9Q zAkPfXA(=!Lzg$&or28J)Y+p6)UKf#8;Z}8%a*&amv(t8I5e(~9#q9}^xt2lNXbH^V z8))(JmeW?ctH#~A`-pPB*%0rfJxF)fbi-+HL=llTM;oC%V-;a%L_Efx?jwp<9p*T_ zp4x~+5o8UChG|E6v!V3|N%`y8SA8I3VshJUlIRE%3 zsh?b>$!7C3IN2a)T1XPkwk@{#gI|g@^74rSIgsHD(7rwFA!L4^WDl@Z!omnYXAUd4 zBEgYIQ`J7=>FVMjzWBN{T1Nyy0+D!KP@tHIeFP$zk2qLtkh%LAq#_(|EfNO{g4De8 zI}?7n&Non;B3L(w*!tXb$ zZeM5e=ORj6h$t~FRc!j_XMtVvsoZ?JpML`O^CzG`1JHVA;f{j>!rR9Gh%(?6yHz~1w+P*JwKYrQPMDvgw^<98p>2I^!iQF~I(TZZ6O-4^DcQr_nFIj?f zBZmPCC zoa;7sL|$eFgR5R2O=xbTpcJTCuz<5mT{&cQeeHJS*ih@vtm$E(Na%I!tojkn4Qp=eVGwYiUjdJ`5Wl)`==@)8J@Z|;Rn0@s#JTCiLP-_VlPKJF z%$Z9f0{fDx@ES%gh)W?-;->`vTI_LEQ+ev#aO}TQ*q5{6bG>3nSwKxNS0{O`YrYq9 zMnh|7CSB)ta;4}5IWGF1_?1D9`>-}T?t*+5gQFj7TT5)kkCvgg{(3~eJ!5llo6}!Q zZ2xLWMwVg{G7FS(zUgiT+UHDk0`>xo#t2=-86;TY@LjRZjFp=h)9QF~H^XF2vWBPk zCp%d$Gm#I+mEUw;$qXpA{lKmA1pBET*W+W<<2^*_OK^smqaL3i!^JV$B{q*1Ie9r$ z87oWYadp_o7OG5`qdO4;rZVVgi?)g0>8MW;o`G5AY-h18i`LH+gm@Cg-u&xc4h_nf z$hw)q#ShG!_lP&5S4LNivy2Ssb>9enoowF6%)o$jQipE-U;u1^SggN3cwrT8C!}d) zs`}MApRKt*^6*9NhRF37Mz+55$wXhxjgeYhi(~HN8O*q)WRZ~0y6=+sTe*2>R9j9Z z(K*J$c!*6ge0LL_ZL|)BkB%qhv%)w!=U5Bgj_+eUP`!^JLyZQGJO<7Ep{ z7SKq|8Qb|5zCx1KC7TCUdnwM`@yt^Yrsp{5(Tx-OswjIc_-6F6y2Uz-fBPZ{eCC)x zont1>^2`<^yFilL1tk@<(9iB@F;2BZIYj<;QnBq6m&FKNx{a4xV%yV3uRmkk(*9-= zkr&$**xyKUAy=htxQm!xt;3wxyBQ>UdVh)S-)%lyeYd$1$qrr8f>1gSlmmlw({+Cp zy}&X9{j&XYc>2I?CAN3ksEj%8DR1&aj)f}`=3;$y}F*TyrLSa4~XCe#u65U~IEg1&|f z$_FOVY&(bS3){VkD`rncYbNHhC)X~=99{&pKM7o3YRuuvBI@(2kZnbu;g~5RJm)*3 z#PB>@f&4(J!DqXxepL-lT#FiE?2%9NtXyi{3^PNM*!_q}->#hrLUr6+;a|6%737;W zfn>Huki$e!3EP1)yt|tP&}Y|WDXKh3ryxh9Pj8@e$h#+I1?Gm5n;(rMnKrw2nXD{6nKdGh z#4X2NPZ`mWbqa4>l%OUZf}IuIw;@;^U2%mVk6z>7cAOPt?Xiw!r-BD2lIqyXrB+w$++&8h z>S>-Ry^7Z+G_2ri>{I7~ei2mlz;UajdH_DTVb=Z|ey#%1)5EZ9@}QF=xTlRli4CoN zkx|+Yy^b?{uofwmOG5^y-;t>k?p9*tdmdt6L{v6};0zm~fhAZhN zECBHFP#H5LE{WJva2g-ytR-ot>PX|!Rw{wVEa7rqE+ji1=cnL_?m)Xvw$jyt7(cV% z6d7no55CA$k>mj#D=;wFNg;q7ZHEmaGGKQZq)u-!AqKd>62+dB{(%+vIcNb!tFID zIKCl4el9ZMs5Fmf1BpQ20*pY&SsSFP*zBQ)J%h2!#corqa@BTQaVs$%Gz)TF&<<+l zectM@zUo`BR`tN_jhuyDvXfzT^i%kvw{fbc-Z4g{Em*UR{jGx_U$oYXYUnyNQ{}D5 zPmGSQBsZ{YJq2sciq@DeR7XP(nC{l_AcIWLoC&;~zBn)I$u;R!WI;JrrF%G=3OVBS z^sbZjujy#-yw%bVySU@h#QpL^a)?;jYFqY*G7r(;CbkK(WEO5rOarVzR!*9$Tr7^Y z$hW2^bZMp9Rlf^61*n}z^Bdm8-*hde_m4qad&1U3KF=_^BGX>7+rnDuI;U)QtaIV5 zFLCSK!&VnEFX^h3$muHeB6@7qqbL#wiRWh*+bEX*Jh(PRu8VQzGnI~FTLiuv1!e)- zo8LeNneJ}-o+!T=(j>(D#THisWFP(7PvMdNz9oSj$8NIxE)yB{vy?M-4okX=^x_70 zXsR6Ow{l3y^C9S=>N>MSTMWX{>@o`-VVTKxWL-%y1KV8*!tLjY>gND6` z`tWu*`pzFV#lKn|>-L90r-^BoS(;DnK-Zj!z|?uIu7>4YzaSn(`02Dwk8pkh2JC}4 z&hGPz|L?V`TRdH_+zsX6J>(e**%4$&bShXTd4@p*dIJ6QV}s*Y`r9BP_;`QAK!ptW zX{u!`>%!^O*TK=i5UN4f0P`W$?^~+5z7^+qI{WrDZvKF0%;JF+kyK5xQfa_E!0sWb zJ_%AGY@w&8@^Y!g#wbf{;wCC3XKZcF8cvR`x2QRLN%9fUbLaqud-9zYhqg?@bB9;+ z3`4M2U1aD7yG>*rf?VW5gtlOa{N>O|>|AF%)R2dnA@thcpfRmg_bpUnNqBGAN`p8% zsMz)wMT1T4maeecWf{t-7NgYQs-NCKZ460%60-KB`J-4^8eGpOKw_~rVn$WMHosyy zfw|JpxeC=cc^F&?)g5m7sr7U&$*Sn8F}dC$b@eTQJB(H-B*#_H%S(o*YPWT5!8&g0 zRzDo;xUAj{wz1vzG0Jh%$51?(&@p>#Yfzh{@#s(NzgU*_$S6Mgdh|%++tGuJsW``k z@>-Da5GSW@RM|tFhg3hFx*6SMYnub z5Kb|uCvg^=ZOSuo7JBC3)R(DD^TsqPpWsOR8$M;T?R@6_;87sO3q4`?x*H40St+>N zBfX709ZsK8@Keuf(@#an1rg!op>5YA^IQ^n7hF;ItxS(E<6rNZLm2Ltt*|5iGA3wO zYwN9~m#Z;Jmru?vq+BBIT6$iGgWGx;D+If>ClRNC`#8c+iIY3}g$f3WUr+~&lhqG{ z28k2BbYmzTQ7#=L@P&J! zJh3F!9uWkuQWzWT9^{4+V}nI`c<03$gyrCOP7%5qnOMHI&T7EDJozuyaCtTABmoBq z6JZB8Iit{|@>3~}>cDy^d!zZNUz!((o%xebRf38*5=eT$`VS#-VEjI*dq)TRt%B)i zw*}e#0+R9!BUF0$;1?G^H3ME!t>v%>dKIlt(`-?cU?E}6)?6E zd9ZFQ=58qRCYT*jYX^#Ft8;=9HNk=alpd#Mb$sn0!AS8ptnf#Q;>}SfX&_nR6^M}t zl>1c;WwWryvZJ=^z|%J;;j=O|tQ)UtzCkdIs@vk=kCAFDTSb`pAqe3m1cL(Ezkhrkg8?)rM-J(|R{N!I&BauZ~{tYENP#wS27$ zsj#||>sF6M><=aRQ;7n+v+bGeN#r)u>w2`iK%c9@Kgv%fisN(n+9Qym$o?*p*LYa5 zz;8lPLW&W3Voto!#lRlcq_8tW3UwpTlT@gP_ zEj*)UGk^Fcew*rkSu#5djPs0f2FvR|2Q1#q@Q_qG8yUmn*~otiRpkA^JG)JFtK9K! zE331*r}5J$&seU^$CN|-2Ke)^W^5~6e0ZBf~bTU42&7;ttnN+r%M zqk9ADzK35L+~CTSiYkjWt)x^o&5ZG#6q zo0X-GVIQ-=<2+{Q6z@k4Ia$W4Q~!XRG#+IlLdXj6I z=KHGYS%pDH9ZR<2{5oiMr3q(i?pU09G?kvT%nTTiN_zVlgOawh0~9zrK`Mp)I9w~$ z2AP?Cw4WG5xNTteSbv!>ndLOH}dZ>mxsV1pB;O6jFVG7a3;%(Ac7FR z(CDiZ>Ne@Zhz4xihu1myw)>^2WO_C|t%Ge_3%2d4nkc%nc>BRuNq_o{+j#H zwywn`lyZ0XOKY*cX+ONK7xrhnh3t^of(9hvHRwZL*dRuM(fa@z+!HN{o|veYFkfN6H!9bd>4^ zsvnYGF(1ujy`Xaq0%fT$c(wK52-6kLLaC8-=bM=Ug8pBrkSs_dbn&oK zUk7j2eG~G;74)f3%32ayG@a!~tXCUkiL4%6`dipqNM5c}w z?F4wil3`!9f-{kxdy$C~MwYQ_F>_mBjWdyaoO{CzYme?z4rKAG8F4Ch2y_i;)Hc!c z3wjwzWSDVC2I=l*R_LaO$hF`*9B@?SfBl`AyK%0{ZY_!avtn18Ud2?p_xjBw$Gz>g zBZz3;F+FB}i)Wi)g)v{17Y#{gdX#mZm-8E9dwxW$xDM7rFL;6-%!M*1bD_XQV_{$} zR8!tUIkY{sKfqVmd0q|!w!-vN1&dm22V0uK)z)G=;N&Q*M%i77PtwYR!C=AzzjZG$ zctnLpb9m^~Xeg0`IMKk%C;+Rpd(wR?-6>&~Gy6ZD8V)Cn$my?*CSVcT^XtLTaKH2(JY&mVj(kO=S+;pK%_(=mah4KISfNf&vX=J}W2UYmE| zk2db?bjzAo0Na)LK~cc#roZk|G}>d5G6^=eq@IPaU7>Z}dgKqrXpn;&mV2 z>4J%50cbkuYi(B|nTvP&O2^+FpXuN9JNo(kCte%zcR#_ZI@Od3;r+sl&-c zVk4xbwe``XM^JL*ciTht?TW3BW);~df8Ktm%zo8s-+kSlS=?TGulioWKb!6SwzubAwvXM{e%fqbbhv%o{`PaV z_QZYd3A?I&J%^z|hB*Z;B~pLqVA``hoo z{PK(Gx~aaQ!QSwl{rqD4ovV$1J-B%B;%`S%%gX*^ul&qj^R@kquFdwl{nC5(>p3ka zUbJ6XX}@*B-ulq~;Fi7lp8dDdOD78M-Mjbj;ln#$FQ_~Es{Pcg{rmU-^wUp8MMd9y z^UX)O+dlsIPMnyWoIG{v)alcw&zw1P)~s1`=FEBN zrI!{gSg>f(qV)9iH{X2oop;`O@4fdxVYhPS%C&3PZrHHl!w)|!EiJWLt+#LAzJLGz zpZ6cwe=^vA{>t9oX218d{ip5rYa3dA+G#ttr0LZBJ4fd=H#gm@JX!glt96xEDz2Zc z`>FWLFTbq6{AojNmGOAi3opFz5ew^@H#I^;`Y@zwSM_UG|{v z(wVP!pFjQ8e?EWtOwrcsKmBxVfBLuI9QuCWTccK%9^AEh$g=W`oG;cE9R23nuix!m z62IbR=GJ|g+xCxLeQnLQU1L`LsNHzF&-=efGk*X0RE_H!ZRB-3v)Dd*XS>&1wt%H= zv76dcKWp!{s_prm_9;8hm)!n%yFPV$)vH;DSAJD9W!;5t?^!?lWTS5L*B|EY zaLoP)yT^otDaqNcTiwAd}T_aH>ZXa`K*ZB?7 zxCK=g5AFW`!*KQbkg-L3F6kqa56rk!wD+n^nKs{1t6jZor#;FWFwb@0Z>}3NhYn0T z`Dx^!@J*v@bt!v8Cr%!G`|9sA3)SQ0@v<{#e>o(bAe#_)?T?zhJC~PNN(MBC4-g#A>3Mc{L2OCG_qSaShSVJY;zUvJhR~lI zWBLC%`CDwU-_H+6UFq_{XvuGzrtJ7LSNLwBI$mG0_K#owZQZ`7*}9?mFU#SJch7!$ zs`cU0x%nCP(92gw+%K=+*-JA%&pvMtqZz;S?rW=q-rb(*OUOp6d4)2s(Jf$TTjqwa z_wVnlSsn6l+0L-zZ3X;*4{{q#-b;nA@g$K=X0^}Qj5FVF?0@x^%f>#t$T^Yf{yqN6 zc-LO_S(<>f`s^_;yfKp`UERX){gi}knKU^*cpQIX-Wd`!b?hj8j0?sS;|d>$^bP_{ zh4cjsn3#N1u684t2U7@-$6Y{GH!g@JZUl>kFo68JpC6x9a5(7SjfbLz#p}1e)Qbol zWx=B-y`{KR#9bOhlD3>E`f+>a3gPodZl&JdFyalN_w>BT-r-!qD2-kXkO|Kw!f=wj z@bKt=bJYxhs*+EmN)T@rq9zPblPWa&z3I?7WF7NOmhI7)376y=YXW z8NONJnlh&UgY%*1md8v{x;t)iK1qo%BW*%g^3Bp9>7~%2M94@MoXOfLPOQAreY-F- zb(5B19yeMFl+S~!8>m(f-k5(abQlqKxp2U=E5ajY*4>>+V-BTy$i9wTaF+>xs!8-V z`k*lK+fvh>gzSLC?7RE<+Rt4w*Tl$=#rxFnJij3(-#GwWivr>A;KWz18yFHlzwh;r zR#e{F?<+K~-xwfK94q^C)y{+sF=|AZjWd%d`dcH^Gu^-J8pJ{>oyW%gHHhc3w;P6sahd_Yuw(C)zp z=X{^ZJ(Lr%0N70u?xD!!z(Xhea;)#Q)0(0+uY{Ag9)6sbHtNvq4I#ZIV~6aDU1vY! zxhxA2IeV3pKz{@ceYpGk(fbEy?Krilvawt}I=x`%yV=9f=tgDl+BlB)oo4<0aU0eL zc)ENU-tFKt@AVPMt{uY3z*~Zck8^p^^jJVF>$FPT4m%8^{**&AKl zw8y$130#-6ah*#_dYVtBas9f;-~jOxvg8Mp&yOo+0IkfJtnguP-FDp-J$T}d(|teI z?VHG)y&33!;md`G-<}wDdj9n3YeORclw@khX%2*3%F;TCc(ew;UX&-oj1uZ-8~*6;D|O5VJCH{s7IyH|bx;fR&Y;QNPMJ!QRz%Vu=+51*iA zzN9A#qAeRtuH|{4AaM2HUHZ+gb=MCsR!_-oneDw})Z(T{lkUu+x*RfMXo<4nl3!o{ z5bp!s$_}0XVa1b@?+aMVQP@Co4f>z}3Y^?DRX*HX^HFL{#)z}udqoUgGV92Zvg0NR z*&MSV_k`-Ye&Z%#^812v)!s9Xap#287rwuvr~%}jvnbc{^434+1s@Dh_FuYljU;pE z(piazbZ7ca8nrp(=#12+2KT<3{ktrmkyrF|S9R-b;l1)XT&3JhzaC!Wo#+wp>FF}{ znu7)3EZQ>nh>qE9zObo(WJ1O2S1SXPdk=hJc+;VVMB;3rvs#MIYF+!)QJApw&{?<7 z6Fgr0cVidLR0tR(BEHuxW2)!BW;K=v2d(oFukrJIYsNaCRL2N9OOiWF>JKg9=qsV8 zSMtu1b)WWax!Jw<+N(bY{_8vOv9hw||A~9ArR>m+HGfR=+Uz^zfaV=#_+xeB3lFA4 z6h2HFRn)sQaLFwaIpbp1&jUx3=|_lJwF{c+e)lQgU;X)`n5gNR)Z-I(X{7z<9?ZJv zEQp(Gz9hm~qakF)^EZx+O&;*xU0RTY4C{Jz`jPPa8o5U@6j;i>%|8c@A0QYoC32En zJnhqQmm-H0&ASA^{fQax3umZ9u$c4>_ZxB!FKW5TOucxprliM!>B?!QUAwl;e^@qT z?wUUm`>yebeqm**d%1t&r}AS&G;@J0Y@ldsiJNx;^ ztR3^3Np)fCB8$v5{_P37O9H}|g*qp5947P4`F%-d z7oKmF-|<_1;yx>dU6$4K%6aZh58q=`%XZE2h`DyG=IqzMZP>HXeZ+w(sf6ozZVvhb zYI3L+94jf*%%1>hcUv{n#G7}~FFLWHT)k#ucy@qWif&=Qx*rBExqqvC&I|qOE^IpM zTp>9za1??+h0t$WMxAy!`h{M{sle|%yL!g-&ogfAS%uNN)$hHFrqm4|#%PTfBb*B% zU3q&407Z7_$G*fRSNLaxdr|bPyN7&>5AIaTW2Q@{%}$u;A>DG!^zy|+bIz@e8$RI9 zn4Hve{+%6y#WauvBko3ZKrg6-rn))bf3)b~&!QPZ?GHO;F>-e0&R;JNSuJ%*oU*fU z+Jz5e-X)!@DxdWBA~dt27w)zbHz>9A@SXC>>m|I2u-cZ77mP|9m0i1DT@tz=AkeRNK;l2A?U^CEzc=9^x^6QQ{O47opUB&^#b>WpUy76qIxdu z*wo3sM7eC-u5P8r<q z;){XL#aHE{%^Az4Nw*abFblGN;pd1Oi?UC* zF_D?urJ02*ZA@pcbNv>Cev9htw~66Im9WPzLQqg}c8$xbuFJ3QntfijMmVZ!aMq+v z>-jT|OQudj#%oAdp7e$64dJTf)soNG?i-u9ytkWlfhs|i?eCQ$$$Nb<*&V?Dc-*8~ zUj5mCHLtk04lXeI?&|D<>Jt#X%7NIoXL@Y`;AK-l zO2p8!3v6E=-ZZ*AVBw*;by=sEr?jmq6ZcE`HrQ~{fB3{zKW3x6e>t9)zcZRU0 zh5Pm?`z+6!$S&0nXt?xAa?Yk5lcfvS^jT?YKbk%0w-U*`>pk8$`DbheZpa%P%rJgFMB61hfWK|r zJF~m=n%L*eTG`^E=fBUr^jyUpOG;rtbCYLD#z{to2%0bGKf(XZ7#{U5&HL z#zu}gbJgWSm-tQJc}_)no?Z2gZumEvekr?% zl)t(5_!~d^FId%U+rpM^X`A0l8nn1&qD#aLq8wIVDf?6X%id{$d#a|JcZPZ`3k%|S(?`MIk<9D zzd4(83utGr={}cs_LcvP4&w_W&XJz|Z)ul%gbvQ6J)RKIU7WQlOtqZ|+@I@K;}Z7X zP0g;ru}zsgNl#(T=zszyyl&$Hr-_QwqDgNtf?eIHZ|77GS?1XJ%YBBXyg;2gvOQwK zs6)Hlwd#NoRa4W;HB`){W3tD_Z4NPfq3f4<$tNm#wckS1*`UNVKh8LkzH_d-|ENjF z`!C#CV)=1d$qOg4V)tfE$Wp(o96mJMJ*m%>?FTjGye_3LrMShPDzB~oF}3$zzgF$L&D}Fnmyqm>4eQx3N64f{3TvC_! z$uAI)hCk!AqrKk=I9`9NDD>l(bzZ-fODnY+q2h;^KN3}z?H_&Tt+JAR^GU%FwtPhK zpjR(^Y$$kt?MF@IEAJ16gqd4*zE-{A=LuHn=j-17L-zHC3~TP(HE` zCaU2XB_hwI7i(556=x=8elT}brT5a#(Rk}#O@hyJ1#s$?3Nn1j5r0AbB&W`Cg(HT+ z2*6;(aD(B^dD!v96&`j*L3xBmIi)!MjeS99HwX+73sMgzcxbOG`v}sPg9#H#9c|mf}3OwG;Qt*RK11WsD?Z<)yU>eUBH8r_U`bk&a6p z;M!*zb9l8fdyOFWwVGsY*@g`TA?cGE#+LIZZtJt~f@xLwm-C+QeR6Pp%;hZc7cJd| zQzOWk72Zc8w`XZ;mu={Ked*`6|BtdK0chgrdXr7ENeDSO19F5@M8JqhqoM=|3WydJ zE%gkDii$QUD)k~4H!3Q%cq5|XQAI_I_6nEcjn=QlqwOkMwY7@1)wHGNf3q8q`uTtV z|LtaX-@ci7^RAhBJDW+;Y7Z54q`AE?A4=b7_^S9`SAE^wuLrz)Fr+nOaE!mRWb^bz z>$5W2_!B-JTbJ}=?iJ3IBmSf12XB8}qVM$8Qs{G*iD^^=*p74t4#`%ANSodwr95tIL*YMf<#R zwBps}Nt1Zu=p6A#t3uKDH~*o~K9oXDltSBON?vqqahOjX*Q==n$Ag9??^dr#y%dy| zD3!H)IoeLH$&5;B8IbBd%EMu#@1Byru{GS#R=?_ty2kqIFx9LCiQiz`!!n1BsT}vg zQvzJVQ~@y|W7382je?f)=+J_}69X>Bo_FfM`anwlK+~@BVY&RU@RMpRpx-AE>u<@% zP183f{pw!h-M?wJfp=Q{nLOrjGd@i`nM=CgYyBdG^W{bF_7txqnG}w{YCBW7|kdfR^K?|^sK%?3%8#7 zKzA@+B>bj&#j-1>n`TZ;tZEx&mh-RvytZ1CX!haHFj_j!kgh>@S0#H_oGHoCMXJ&Y z+^3nJc}6iZmXZ38+3H45^PTZ!V!^n$GGj_tDl?kV)mESkxaX9Huj;B)$KZ_0s$wG5 zfeyNGc+K^X?!*>7LaAYz0CzxhL^`8bG;~`=XJxHlzFk&)dd9g>ql3FgX6Qv_$;M#L z0rT(UQd{-J)~q3??w;Gwm%T#1!F7&3&{NUu&(m8Qr-z~QHqvKM% zoP`q=i(NvMa(`w?${o8!dGf>dxOC7B{kh^D1#Ls8{>$xJ9S{8Gz2`}j9RPW_soKfcUu7{LNnyt%<`Tp;Sdw#pF1aA5Q8e?eHCHD4N zo4y-_RW*%M5AwZreDJ+bcRoA7z44BDX2IFWgO?Nh>Xo;IGln?_w5I<4h*Lc1`jgL} zM?23yD$31_-m~%#|GQs*<-kPUN%Xa+8HyPz#o^}X9iOiMejVfQKU(@u$I^lv@)znh zi#bs%(szBoxbNdyT+AJjaVPH)qpZa<X>fcky1xCQPm#&D#aYo3MPb zkDWkyG%dDB63i5jjFn;~QpZV|;fG+(Ks-;Cb+Rxmj^BqhzFPmVdW=4C%c-n&xt#?Od4Y$VOGU+IPc5 zUoXetZ7D5^aOKDoVq+|icc<(-BNp1K^3^PCRpm;&3;Q1D%+L=`Pz5#IeWr9O2_1TJ zo1OB^7uzI$v+Iq6SW(iv-)kR7r?kdwDtNY_(Rd{FYw>&HySFn3tA5zKCf2xSSo;EF zfBhY&xT&d&Z(ov*oFVjTpKTnzCCRy-Rj+g`Jt;Cc%-*x|!*B0?9n<{l9=$>HQ(n+X9vJDG!^WS zcMCklzop(S3W%0_htR>!%6s-$#Le|n8T#oDdX-M2v&c)$%|Us~E8j^rM;jArGuUNrfR}fb1Q*P0ODn3~D=2VWB~`W; zI|WwDKWxvO-?ZCylDJ6P64W4IF|KFG;u2JjjduFNQDtQ&$Ns)fSzG1W<0W{3cx;X| z%ivccnVfaIGAkxEP<*iSXE`Qso;rDGom*DC3Y+f}`o8K$>YCYWr$q!s-^h-M`UJ0@ z)S8~~^LfF7Plf)&yuSazmMI%w5%6nld+B=npy=&G9Urw18}(D;7b_M$!oIJY=ko6N zYo2e*Y2A2a@$|cE!#X>1&n@&8H4J#$ z>Zb==M>IB&CIMFvI8~v+w0evq-S{xM17cL;`|^Ljq34Y$zU(kNfIEpHSu^h1+QN4_b$YDmaY#$MPkW2MI}E=MPx$O= zD)OAbO4_~qPRYB9s+RWBnNv#{2j;D;Sf4QRc!=`>^W!0dTLJ_{WiQ%4^qRj8s|*Nw ze6uY2>f!$OkMEqWEbnO9IHN0c@2SP|7Q8*{dH&EP!_KuxZ*RPPX7f{Woo}>Ao?lsU z<1lVE|JpKY^8L<^3p*{xjLg|7*#YK(ZR;!+{MkO->0fo271&b+RJ7WS*P4>R)L# znr#xv1!cH?>`^%bYMl_-y~tJ8=s1U^VQPpD^F+h^q-yn z{pW3C+)Sb3_Zmj5;xBh_F1){PsUgzA-{oP;1=H`Gzp6#uvyGlu5FZrfV^vfn@;`Nh zz!&^4PSeaa2&4(g(kytL;yhe^JEv^-*%DD?8VkF#y>%mt5jM;rk6RUUS-+hX)#kF% zDVTdQeWbw`IXA2%B$93c>%RWK6BAC(E{>#=Bnw;~95(&8?t)HqL$iH9h&_(H6VX(jgw|^{3-@zWUs_HN5@!r;;za)$4Tg6pF^nYM}~ZRA5)lGANTU7WVB;9e6E z&%KxD?35OFhp^{6?D8zJdLjXTy%xlSX(V5m>_?vHf)rdC#gPbM+!Hr9a6P06LEMHr z%_UNo@vW`v$r4xQP0@uHSs`zU;Ev*xH*AR>4EXhys?IfG2!nwXh(n4H&}Wg8zQJ+eha1Bc#&@Fnw;!GI!-%6SLmb&OD5djqADgYuA6}VxL)iE458t`^;kx%@ zzWP%7WawS-N<+yoJZRcQuTjoJ&2vZ{*T1H0*+s$ioyt{Ghh0ihXq)Uq_TT^(uB=Qd zb7nsC^2TL$My6Ph*_zn>1n-Uoabd2_AHFV*ls$}AwhjYjE97{dK@cI|mZ34K41xfv z*^dqR5RcCgo35lwr zm7G)HKQ4b!Ki^nh14J7xVf&Br);oo;#(35F7B@If9yfAYYF@(iyu`9%x6txJ#}NA| zZg!`*Px;O<{a%QFym}+4zx&5-Q{&s_7JT6@_=L=8m1&o;eqd;dANtDI6^)I4*8cvz z2Wy+gPI~h2arND`W9H>#N45K;SGe9^bg$^MPsyU;EBibjb96w=clGSx&%Yb?OT+Bu zVL=-f)N&U6&|ni<4AV>(B4-F^tM7b2YM18|znjwZ=lfPj!#g{Ee)jzw+o-{PKVSCH z-ha%N;n5G@5o0`F1}K}KP7P*w$b(<@C4J~_)?E-$gPF}E@pQGJ=;Wh;=5Ar z7J3P<7YN;ZUdq8!JNmy-e|Xh~lpaqh9leoty{Ii?vhu{XU-l8xZ)Ba)E64fhZQWz? zS(wr{N-RyBe6ei&p3!!Vn^d}MRUGfA3##P-Lp0}ic@R^&?3O0!n0XAQz+t3Hw%%_N z%W>+}$FeJhjrC6cE|6@P4)a$ziY*$b1?$uUP(Z~yGm4|Fs1HkR-9)$ziKqcz{plwXOixp?@R^68!_Y~knxtK=I^XCWVKs|jpzm)pzRdaf-Z5)j7H&~1voNe8{D*1R zLB@nC}aln?_YiQ+99tWm#5Z+2W`dpYQmyvi>=qlbE$) z&WeJQzh@gU%wIt1@qvQVF1Li80S6ZMkHiE{_aKRriMmbs*&i*CVx_X zaOuH4s(R9kI?5z;g*?xyVcno4njlm&Q-Hdp_T9KEJxGVb{p*?mib;KZ&u#DpvgG zF+-pEe7!Gecf$6B69@jaE7?<)qh0b7#xhl^R~GKcPLtH~b9%Bg8T zH0bzMKI4M2dVeRAnOe8((!$TaWn446+txhFx%1q(<8 zJgHxqxntO!7rq^g%Y))q>pqZ(^eId7siw2G6yE-b7UVPHV!Fj7V6cK$tF{n-flF~l zDT`1=>sqUQ%f=;aIj>BPzZuYP{61)-%hxe}{0cJDZZSiu65-j5r7^fmx4VK6b`XE~A#1Ut)qU5d&)t!cz+C^+mov%n3uR4@o`0Y7 z^fSEqgN#0?&PC@`LhMp`U;9sk*Zi{lE3!7{wm=;xnmoA8b$ATb+Hn-oc)-bp zasq|&e0~(L9G505qn*IDGjaQcgNWs?$Oi#-v&&BDo-gACeD*_U{mQWeIN~#R!WWdX z7}l;sh=|#MnvtT1C`XwPvDP$o1x;)+YuwKAi%TeCwdNtr3C)cB!57_VV(%SxUl;n0 z#$OmpON>^91qDK9Af!5jex?FVobSl+mU}+pB+5S%KAD`y*bs)*Bgs!VSB3KLIsVq47tcze*E6O=;3FM73xz7U0NaZgBYimgh$?Bwny zt#qj^n!0U_K%LlvIp^ zG#nG3+sRxZcCGxi!@k<@y^sR~O=8Cy*8HG({z>d{hnQ2szUFS)JLuRf;-q5h$?D^K z7Btyyaa{&tj=6P`8(2E;rfVaMld|C?JGHpU^klGtElJ*J&-<_|UUjzt`)c(8@=yCu zqRz%`O$>kd$FH%5z{AlCUQAq&bf|&b5X}5^;S~3@Go?jguz26uuXabq*JorQhf;(m z2Qr+lY#GdIDv#CWtNpy@>h8H{XNz9cH>~F{y1$HJ)r#{QTEUqtSv5;i?yAZkGR3G- zV}av@C&^>gY1o{>lj}6cnu{Hs@hK|aY&o`@5nPzE-#hl4y(4RiEN$-5&Bbdb<{zqQ zPpfEAPgS4Rj31}Aal8cbd5`CRy?5-OK-P=wxbcVN6S+1r!EBq_A=}x7#V6Gze)Dgg zc64}eVM2YQ=4RghaBSlj?{4*dobhSPfc=-QY$Jll~?_DFKQf4e3to1Ug+Lni#oqnlGT~35bO2bVKsm5YK)|nMYvSf=ojV}0) zTu(1X+w#;wm1CmpGsd}9+q)m)g=Yjx97=t^&3Dmf)wbVXJV)y~aA@hLw%rZ~igEz= zc~enL9Lw-;6;}l$6bD5sV1S;JC;&yJgWbkd2{P_9w%PR?oy^UQQdKlyjTLoC3t?yPx;|=^d|I&ayo(qcP%Imue>&9mlsdK5=_vZ~C=C@)`fzP+=Hiu?# zZ<_wvBWQ@If9A1k5P8Y@{sjX59(1tmb(3?1cj4$&p|!~=WJ<02(xw2(y;6Qdfe7ag zOYYdkS6!Cbh1EC5mN@mVatLfzscmA$z}i*$V;}o|6O0mX-wd^lcfWTyiZF7fq@OD6 zg(_^;%rj17D{92^j_);nlsIDiz~<{e7H?w||HgX%BXx<_yB{vi%lWlm)zS1_4uUf7 zFHKHCm;>v_Z|2*cVpLr}5&voB*IxuTb7XaOPtMN9pEIBQRbG3`DNy{u^urzM z4$%y5)y?mjZGpz-1j<0u;8w>8NU9hVRUnL)jI2#Tj${bdb&(*VM1j|FGCUquR6?FGzLE$=G945w@xhM`{)_Op20%@ditkqunGg-tP1+qr8# z%hn$MV)it-TWw*cnS@A7WVI-2)FtCy8%)l=H&z+hts@v#h)<|9OMvZoGy zene6Y zE4yJ&K(u!-dwP0wUPeMOp6sx>UEuR^G=4bk_Z#EOzCMcYs_QB`Sy|%G5Nuy?u*&Dw zN&E+nyuZ_to7l9!POiFUr=0M4{O*v=B_DCIb(om9w|)2f$-0Ss`y?N|_p2#p3-2^J zSF@RasDIE)--^P!W3O-u#zoZKth6%@Cf80}u1WdDpcje`MRA{L)h!aQ;HQCHyiYsSi(=EtbF>M}{vYx@YbZ9_!P(dvP_^GRXzQ{J_6X%TVT2hBg-HE={N z>wE3%&IpbF(lL z_n7}5ufAdBJWF}ZX>aoHGDUooSL0Q|Dg2$W>V-hQ`$6;HIt(kDME6ZNayao@REHae z3`^%;wTBlRETlT`sQ#1d0$Q8lYX?N0>zEcS3d=urcj{Hv_TL}QPdYSl&QeMAdhSx`&$`^N!}sgTG`DvX1(hS? z3j0MlHesagiid3*yp1U#M=EB0hz0e{)Vl1RBkVIEhw*u^SNlj(@;T!-@l>C-Gru~s z{#7yL`OH76hOsVaH;<5wt`47b{f&eeNlXq9^B;yIENXcEtJ%Z~6yN-GLMtP43U8r)|Q~XhYho|?J@pfrv z119iKU00Y=M$QbL#GMdYo?)9Ra6XY9s$yR)&`ZN@Zv6HWrV_CCRNwX9_bnsHi7nlf z+;*cNX=nDTgUp|Hotm?vW=a0H{oAp|KqpXhR|%I9Mvi+w^f&M02L7T<1km^4!>3!JL8%U(Ke zUx~l(M?zKh!1bo;@x%dfxU!oV#@K{P+xKPz)kX>7fCVU2#^8UKR7WrrlvnnCru z{bp9*K66-^do z?qaSVgxL}tnMzezoF816bWU1%qnOcuQ`kV(qS!(C4C5!o*D89+mbgp(eD!(eM>V`l7sOe%+YW|9V){R(l;| zguUYG*>bJ@0M12;^t**0zhmq3=$8%8N~X(PR$(HKrliD0rU4HtH?O^_xZ11NM-8u6 z2pRywkn%Bef&I*nN=0?e!inm zCN(_Vr5fqPo;c)QT1U%l7S3IK^=`al-#)WK-%pmCY1$L)zdmAo}REdS-MmeVu;nl!clxZUKb)E4Hj z%&hnc2XlVl%y(7JyLTW84@>p__O86pE^pj#H}x0N+fwZNF7V1Y(Ck0W>!jx4V9oe| zMShFE&ls`*J9}*ST}P+Ce5(9cgUIQ(s7?#F);OsiE-^6n?B+AtvX*9 zv8r?Xn&~WqSIVQ(Es=Ul+lOZ6(BlK=UvB5wVSk$J;(K1WLhF;ftC#3)V*}$6E151vK_@bhoEx}?9%g6kjl_hT;ooW}H zF)n3f@s!9=PVnYg+FI@k?m<`6k)+ep^Y)8Rp9;hRh>jg!r0lLdf10sHd@TC*`D0(T z+N8OBy=QdwfVPH;oc`4^&{x;ze;d9dcb;DUjX?VOmwlDfWOKO(hCF*|+%X7$k^HU@ z3vHpjjEcxmZ1Lv9Av{Hcvd(KA3z4$KrVWn76q&bCuG|=aPu7eZZxqMrf~P75JzO7` z5H*3z3vAv~S^NwVx{uQSb%YkCKQ^i9}cmppKwsoAN374HsT zAZv{Anv!|{C%Ng!QT7CmO|3)ld(LAnp1yx`W^nr{FMGcr{X6%*+nX~bF|j`V@YUi4 zpPo#K^4lk`j-T?IY4gU=7T1-cV`G*N+JC=pS-^xp{?~=Qpw_ zLo#_?vLc~h=$<1Vc;&n(d=#oKupPiS^JhlW=j6_#(ZVzFUpgw?2G8fN&AM<_5cN*v zkAK>j2Fb=qr+zs))B5mC1rV?G^FzNIPQ&}Bj2AYdh$_(>{#+y=JxXYTRx3Des$Za z7gr~A#)%IHh|^Bpd?0hXo^ZeV#iG5kkd_RNIX*ay9=@pF`L)b1UdzmLk4|o4JH(9M zBJ&M+{9cJ+u#mm=VP>8wAciA2r6?<`HC$dUP^axFE{`4?C%m_4gKU>8URZxGGz%Vw zSQ1|P__!aN%a|oogPM;&Q2HwgsVjVi*M1*st1YIrKiJ@h8(n@6>}=D{nt4uWBioc2 zb$se~cC7vrpD3f5+xINt2Wgd<>fQm(rip&<$E@c4^m{`3?uOKqqPU3m<_^`C;g=R= zCuBT5Ut{mQWN<+1!KBZ^x7w)^oiNAfNgV%?3%-3^z!%KtJm zG2(ifsW>{8E9sXLm)4N#zB6psv1VY;m2myJCSB>}XwMEQif_qN`i)&AJmi%~%Gc!& z<-6wuC~IBAdHtph#S*l$-KQO@OepjF)^JI>YH&(=YrFnZ?GDG9=#*NI`GovxPWC4< zosnES?W*xn@`1}-ru?@Pa~sq?AG?OP3+9Yf`HM!L+pjNcGuiKM-qzlHH0olsy?f^9 z6E`O51BI(>XTM+h(KlIFei9GbJGz=N!}K^s^?NfGp2`1nSFvACL-_mkKmOs~C(czr z&saKq*BsO4;n!x`^qxpUe(|O<#^iVDtExCvF_)NbZd_&3nxaDPm`r^fY75nMvWJbE zRr)c70?pC%V)(}HNW0`aht%aCO{!6>|FA7@r0(*_Me7@9c}J=2oE>M4zy9#zY`nNM z$h&oJLkwOkRHvO#S7Gmb=9+x8W_PlcZ-e)Svuo>yk3&2J0JYzG}(p|`)j_=V9`KUZ7pcx+VV4*Qdg z6ss}@qZseCGOqPB5_rw&(iUA=Ig8-IH+6jO4oH>cNhERU=ddXDdtrkDN-t;~V_1P% zX|-otbtU18yi^%8n>R|?t{n`^iqt)6Hb z&BOfWM@bpA%iSvil-G~q0^7KvrP{Opj%Q!Ae#l)gO$Q^u{cA><*Y2_Ji9_3io?Q8u z6ZPu0OV;{xg;Vvx3rE*_-H%m?5|$ollJu(EBYPSEEDCXjD1-^iK`6Cdx4?|ej82!$v&T-0u=}a~#)`eM zUQyHbCeBU0v%xARtl>e<;n}l>3a#)1{tTR31I6_Xq|*4P?Z#ix&q{`iF#W2555~Gj zFTNGfAPcBHqjbDbIDEy(_)Yu`a;pspdU0O&8mb}GvO~lm_iJ8t<=E5)Q)TWdtq zj1zBNjP1n6ZU17x-g)A3$!M9)j2W;S+45=@IqE{=^ zW^>ug<1&(DjRm3~bPZ>PRk6m$ovU`;gQaA;AXp)~@5wG$vtJ0_ zWmR7HO1*IGyFH`n<%68SMB;<3!`C;(ycWQ1pFsHY`&dxQFQ#9sJ&x zHPz)!=?&e{4YjPXd--5Ec5BaQXS5QLLkN=#)_DxgFmeAUY_;g&?+8!V^1%&lvMXoh_&!#3f|rcYNOqrIkz76OC;3Z zuo$*f#;Q!a0BiUhjvarQdFISUOkMHoy?C3FjXh82lz{!L#D-%1YDSNePlNA4+jC?! zYooA*>%Bp)GIgV#+xP_s+F2L4!tb4;R|SFA zHF0vx6L>2_yoqL;3a)qz&t}=%8Ao|}t?6%Wm)ve&sEjtsBUar&izMGAtPaLP?&=8d zRV9>w@E7oV`c#Ao70Ox)5B6R(27-C1 zfG`X`1OV`Z(y&2x3&{YKCjfAP4FR196^S4dU~mL`KI#m-*!J>uV zm!MFHek28%USR_$0Dd2yreGl>uo)Bzn58KoX1}6Q@QYG303>p0h@@Bs7)a0<5Q*ji zxVBON5}wvXMBx=G(}j2-5g9F@Kn(~Fca#Js$Y7$l1T<6zIY=N1TzXn8I$CRR7NJ@Z zu_i2E=akUXg1>s)U^y`^9e>g`Ot zLInTGs#V5+3Pfqg(ya-gg^W!%kvH^(wE6}L>E6_>!q*le5eh71HJT^n>NZ*~#`XFUl!!UcPJ@yE$W8n~c z*fW2GYcU+|E}m4L`v5z*I5SaxUl??89znqY0CT+rIHDO(!wdw^1DMYjG7-ECV6oVN z`3&HX0mgZJ9JS!BC_gS>z5sX!!n1f3z7k-*D<4B;8vqu&*i&^qNBLdsS%?P#1RmY^ z5dceE>?uC8X*>n*?S;SHE58t8obIwpfV;~srSVkR8h~+o9{vRCsztDrhEJjV5(g$~ zL*FBq=fM08;9q;;ogwTJx!O}Yi33>X=}YOP8DJ+@X9^a;6OFyAGnFR+U?*1>3cmqh z2UjVD{~BOBS0@SO$eK0gSuyDf`|ASm3>r zX^sY1UkR|()q{f1Q+Zq|*oKQ?E>`-}0JgL8S%L6wbiJJbJ6P)-$U`tK*CK%J zU7e_UYbluK?Fqn+);xp2`DCtMlzq1X+>Ivzc6OCg`2O%?eBE^B0?hH^Q@*4JxZ5{& z(|D?`&jGfz6;pn44PZy6y#>^VwF6ABc~qY70G8O>GmuR=0`LJ>2a4uU1l!wDcs0Nh zR|hJ81%;>ce+e+*%BS%ELij#3-o}=)HAN=^VBD2U!6O0Yc=IS()BuZJ?I?UXm4~3< z9RN%1-I$1L)+g3|yNTk(YeOZw1x8UYsBOQ^bj1Q^;lB|9O8 zxf(AXUnA{Y20j41Z(n!lo6x%g4Y2|8;fXYsw>^LSeMRrD-S42E_>kv{q{N>VfYz3C9 z_3R|N@YT2oCpzd|w0J~rSEN})qUlv=lJLxxgOQ?64rVbywFIV7C~&MvE9JOhWR?jp zD23jW#B%d7hFJsF!%dhXSIa1Pg~7jwU`;xcP|Cqblbj%Mtp-@tT1*POi=id742TT0 zqAtcA(oM)Pq0=2w7=bO*5}nve3>diLmh<6R{5I*i7BiC~A*SgR6*P6_{@r8|icHY= z|Ec6~1Olm4A&1`{RFmDC8t&u@sZ=1~;3l;kKsSLw6*i$!9dBpA~JZt+fr8GD5-!xocf7?I7O zav-9BR5NB~nDKgCK`4X@H-%K8P-qlt1*t%SLnwoCS$9u}IM!LtVz`!Jg32}6kj}_g zo|bin2UsUCg{q~Jy0E9%VlWu0hs1DNH698OpXR!Qd}_9Ib&cp0(h`z{n$UoHB1S}Z z!N?3_I#n|VD7wKL*KT1=3=>0(!%nLNeeGBX-s%QB(J6W*0u7w))IpaAi*uR27NbdNmjh+=$vpC<5(;zR_wyeIvl> zfhA894%sn6D>8X%bAbw&85FFA?!lCM$I{XCltJML5Lbaw9isPh-(!>jEsPA*b@bA29r>TMdV=5NCv3-bIhX?8>Yn|_Vu)MSYB!H z%h+%eUJpJiB!S>!tw%0+-!qFv0Y(&3iqqnhijn?aLTqjEgdiRkpTfh+D}r1(0?X;d z9%yl3MuXv6q#gwZ2I>X6n}9t2JqF!Sju~$-d*T)|Zb9_W0}}8kgq{c(aU-GYhdN{Pg$k$|DzyTr%l^vpq!;FO66GAw)1j>k zN)eEYVSmL|*swglJI;Day2x#oYi;% z8L^u2fE2FAUXlb%K#=$==&Tv9pud3TgQn1+Gl8Fm#v4dzAE+ro-wCDy&jcHQ3xYYo zIv6xJunM#id>h8Nf-yQw46>6!j(|>=vNIM5EdrjU)`8!QAffbXC`FK9&ef3Qfg*}^ zmL@GY$3LBv#(+otCuV@kTbLobnHkby@+3P6U19dOjNR!n+wHjzc3=>FCU>FHLife(+|B13Tgg3qZ?ac+bghwZ_lL3#U zo-k_y^*}>~c0n>8XrbY0NTNU+;l?mQ2dsq-7$X&gLF)$L776XZ4gM}u3p#Z-f$$&- zbiZbbOWY*Vz>x!{hC`?z(9sFsM$n+c%?*YvH=!Z|9UdMEh0qNhZs^DnMYw5TxPN^> z$O56o>jOp?@IC72#8#Myb(kUtTrq;snP41wM&fHxZw<}?b2(ZV@xbkeX`vsD$YC^? zJVXp=ofw!N`hE@eQj41)Jm`ep7y>?AM~WCGH{68iftZkoa6>&1I029X>D(}|1{eX< z#4sUA2@DLtoIm%qg2F$5+JBV_nqJdFj0aw7$eLbYZY&P z)>*ntaunI2zzzj^G60kaK%pK)dJyPYEN9)a{_T?sGc{NaZi-~I3&;+Ro2J7cbvI=~ z)QdJ#XD10p>=bp0EF%0YNQC-vHw?Vr^Z8C_uMc2Y`;hF)eY&&b>>ZMX46pa@D9P*r z(Fqj^k_5eX3e6r}5l_3Gnmd3viWVb0a=@Ce%K}7bh#cWc4?3d4dJQ8mYKYEy{5P5Lv!we;c$g%Rp;v5zdZjibOIVtUkO328sZ~LCJS8)q8?$TE{yo2 zsXz#-fUXhTOk=$eXFXp=S|TEIAf%!h?><9_C0ZF7`O@t^ZfHZIr)!jdYT^?YrK)zGAdkP#4iz7oA+bYUIj1M^den*SGn7-6CO zp+`pWB;wAxt}B)~hL_sEpvQZI^l);78RFb^e>a%B-I9(sI$r)|Sw|RjCQ_qt6B0ND zU?LMty+wGC!?Z$Zcexk@I9hnZfZ@B#GuI3=ml)Xnip8?6$NYDi9-P(wyS=RD!@ERX zk-1MS+g2+y@bs~baTe>)-Z5$5X;b0mMhNk>fLR7Aa5oVq6vjf+>2$;EJ@MNj-DSe` zz(8g-)obqDR%o8Mxy=*`vn~^g2l%$d+Q%;1)ew(^wha*bc0x}B-4TZRx(GMaBZ@SH z21lJ6kc9??JP&GAP%Q{@Ayybo6f3}s8+^G7Sh-BG0wX74g;p18#~#oz!9x~wGgxjH zJfB1Ok5l@AT1AkqVUUE@13Dzim&}C76FBJJ6lT&4758kO@W5i-Ok}4S^w7Pzc@mz` zd-rVSPEvt&;a#31B0Nb?s32;*YGVA@cV*Gzqhey>-<9?6FN3MXq|8~Vi)Zm?ez0)i zteM$-%?Hb7Ey4z5e6V2FfLV*Pmdsr=_k#h87p7_kq%KNdGI!wz1HuOm2(iKg2M^Gs z&YYh*XV&7Lxg>qoYeY)?&5yfTQ;S2!<1BFWo6|*Gx_@ZTBwgN zg%40<9;nHP2t1If2%r$D>o=rx#s2X{`E)s1Qek0|Y5lvrN|Oo&rs#UWCnWrec`MMBymHVi{E{ zg;1zede~Gd82->EmM4j+Z6$rLQ0bX0DJ*<@Mc?NbnJfj1$u#EB_bh>fugdreIHvEr zKo)ba^a!O^Ti*;7Sn02ZZxA8j(4-XFfW8Wjo^%9{915AN^dSqdZsndTLEraC3wly& zL3uFI*}cK+LN|zER2s@dqbPZxddymXMD%9(4~jiIln}L{O)L%wP^ngeO6YsDQE!9; zPV{|5GzbV=bVN@&(qB*dD@a2+=++myH=}!PukzdU`tI`Z4;IEQbTZQEq|&;P^gWZ_ zdh}x~EUPqCmK7SU{86OQsf*4J=LT(qwhH!g*b8AtTTfzRV^!6L4aLRz`7{dY8*Sb8 zL9&7{Jw;xpb2+F4t&7+7L%LS&#_TEoiuRr!`%=Vv(MR_xRX{+u{edLnPfKwck4=Q# z8!epc-XJ&R4FE1_3@Q$Y9{R7CEU;#ef07g}>O`UfRKt>qsaA#VNm^)Sg&-@e|Ne(4*Y>~ zik@^iou9?k018M^^o>^k!IYTQfvow(n4D6VSWGbr`K=yAr<<&~l}c-V_#dBZ8_?Es z|4;fLhs%%jaJol;KU!WlJ&-uj?i zCP3Vi4)+^29C&Rw)WJe8+mmiBPwNM;T`aC#Nw*K^`Ov1M&N3j`BRvA()|x)8Lx?nvQ>^0a9B@a;#gBt*y13A9YDEgXVgFn0~tibW}}?|SD! zaIURq9=izF<9eo!fO~Y<=xucT0zzj)?R=e0K2ysmVdz+fnZbHO$IfSKIXb3}1^lt# z%0Xu>0cVDe3-?SdFQ1_m070f+pk?Iqv;aX05YQ0-v!Fz;(psRWBlLteSKw&m=X3Q; zr~`6R2d;;5dcKiwu*t)9xSl~#g)2~C8*v@SfTNsxRvuo+(BpY5{ZbAPVCq>~9I|BF z>eyP)FFGi0|6SJ{Dun|Qp@Sf(3j$GA`uxvANNm`xWNpPd9_$<~L&wlEi|{;-frBIk zPJsn&ZukV?4>&Af6d;)h-JC4YHLhoCSvnRR&MA3}ybKx_3fy+{N^|_boP%WsqJU*! zfbeWkG8@#`ex8~ESPvwM6(kA$IVqC#8)VdNMI z16R+}gI|;|O42;@I0Y;u63q%t+sMsBPSjnLfmlF!ir9Ixe1Q(nz%y`l7)2R513G|1 zFgXj(00Cv5)&J7ni|``cdV?9+MN9*7Ru0fdJ5@(-`Z6P@5Z5C*G-dE-9mB{friwwv z9;TpnsFh-jRS1l^L8W}e9Eiq82NXnCR11Bci}X(OiO%#v)nrw|>o!E|tVd{2Xd%)P z7z--xWh9z&1GAWAq!_g_4XV)Nh3x!U{gK-AVbnRa_f3xj&DV4Fgn@vDVym~+3t-O` zjLT=_+ru$44IvByy{*ogNuTQ|&SQasP+MYy_K<-&Ivx-~JNPol?*j)`gVM@BuL$3rkG>*1Ls`lz!HbQA&KY(asG4oC zEy#2<*uc&QVm#}?h3tg&=xLHgtdedl)0z_lWxJ5UH+xBj+q^^3Fo>|DspKb^0f~JF12CbV7&dY+{3D^fw&>+FnVFq3S z*TB$29!Q~jZ^(smqf)3ePrp?7)*5?pQOqcw?4;-GaRb-Tb3k9kfdl`yEAo8g^>1F$ zkcYhe%`2in>&1G7K@2r^)FRM1*TEjS9y$!5LnBB?)d^>i1?r)4qV|Vc5Jd^(LM@6q zL+=Ltk{;2f`Q-q80$M6^HLgCF@(pBfXzR$o!3&@W6%>F7Z(Jb_`7bb|N1o0p=H=(| zCB;;`gA_E@_dWiVmcZ?db#cp(xlw2M2^lBNsZ* z7z%!`;~DvS8~s8j=&m_H1kON$I)l4l;8@6E;0graxIzl-kc)OyG&-TZ=L*!I1kj_d zQ0W_20|$ZuG)Qptxqc$VIzV(xh#DyqN?O^ZSmZ-_5EC_85Cp^m1t1|IA7Huq3=xom zWFP_F54u4zBOMTwbr?Db1Py{WTx==oI|ZNs8$H!Ez5xMt4P%YQ#)zYU@&B_!PCJIy zMhjN|FU~?9l>2|thjxt{9mJpojM6l+3hL`}Kgi8>FZH)E;CT#?m+o&+%ZIx>+>q<~ z9ttBsX(;xvfzBK+q5}$~WTZsgfahZdrje;n755qz7!Z?U`4C~ixQ03rWT9>sqAWqh zB{)h)`E(4!g7F4U0Yr>cO{j0BI!Gu?xdz}_1sub4m!3KxEYPv?fngZVQ3piZy;mLJ z2MCYSQ9hJ^UdlhBSa4Yg!04wBAkZDH@{u?oF7Ta?<i;1gu<@4a z1t1G8JPL+bMVvhQf9TA}M!EovS#^f=_8*UV^q41tOmE-&|6dupi!ngKTo-8B^bQXb z&=ycLrTc#v3G&$a2n)>?aMTXzs1dXD6X;sHX}$g0KbH+w#tk529+DEd3@CvbTqs@B z8vlQvbNftzAp5`8*mNUN2$h4|(Op1y-$z}o9SIKUtU|)L0BZQJ{g~6^p#lHqBUIP) zpI!8Iq~$pfHA85Ys6%>lAC_Qb7a&U@_k=#mNaPbn6uiP6sFhj3%9{kiGqp4Gusmd{ zH+Jx|ffJDy{?7w7E~=gD&?7_IC@6q}6UrHYDx!@Tp&`T&9lF3{8}zR!^HG-zDC=2^ z!80g&n8x5h`x{r7J3w&-!qOdo?<@4qU?cj-WsF5kz#T0dR1Ez%#|RGk~*>hUSQk(SaU0VTTY7J%BpI6)}q7k%rp2kZ6Sf zo6LcSA!~=#E7s#dCi+RPSFDH9^?ZYn)hpv0$^T1=9m7CBBmOfx)Br)mTWW_W+g@To zK7qzH9Q2M%hG_{yZf=lEE^Lvxxv|A;YKOc2a7;Avtb4A)r$DsEW*u)mkqE?-h0 zE)*Av3dIGId^^AZ-sp((Y{ID>R7feRjN79qN=a`hs+**3iLgjqA}n>tcQiUdHUCha z(bmW`3i5DNHjf8v_EyH2SV|4{@RV&=ATeMDbckWhLfRJsAt7|G$SMK@Xp`2cfo~uT zJaAr^`+%JXcYyhrN$rwfDL3+}2653B8ABpJ}V-CgMvS{B;{x++1@Gy6WQ32u~buqe^KvyV&)j zO%)M4np)@aS*s9M%Jc~04FTgxA=#N?<7Y6}aLWAG|2zwjN z2SYJh(8K1x$x}3#lJLaIC<*TtlMt*#p{(;+uUw~t5FyI#>N2)gvr)cQk2P2lc5A<3 zB8Wo={iep~)0XSYd^ZL>V6{eCZ);Nwquaa%*86P!rTTIx2~eol=`rkxhXj(F-$q@z zW~;hXwpL}+kov&L@SbkIXn|Ba)jD;FVl(z?rSf&qNozGIcL-Dx<^T0cT_3q^SEt<_D%x*SZwlI|-xyfpR~%T(6$jV?Z5(|5wji5d zF<|RpGq~Yv>tyq}1@yMtY`XtJ=xan|qh{+R|ei zzoT0zvjuOG+k!VLY{4Z;Td+-S3*Mly1+UlHg4g=kg4Y;8`Tx$JRc5u6^xfM1!C-f{ z1U(*DrYVJ1+T>rtm7tL&)L;>|4#f~ev3E!Kuj}Nl*r4J;XdId+0*$0*dj2-`bN}^i z^Og23l|o`J;FN2y5~H91y)OOe;Pawd20D*gQsl(wYLSXYcJMs5NxX3 zz~TWL`)%sErPt;@rTsSd-r93}_Z|Ei&8C4H2bBye4#gjA8(c4O8`il8S#hUgU9o#0 z7DEoj?IpRCV9=7RHX1etlxj-bJswoi;jzw-cG=l&M~^N2ils+F>bt=(`=vbn+ zbtv(%wJ-4%5maKZwJY(n1(x{R0yY9A*lv^r*!)WZZGI)~Y<>sSH~sbYYN&UkJ^uTw z)@~K;D}wfV{@Oi`KS`$OaVZ=1y~n4vbuCtub+*a3cC@hv+wX1nMBtMF`?$@TGJo1| zZ44+el(Z}Hh3vR>9VKbsByWk6B=ycVJtR)>v2}#RJJ^WQP~5KAuLP5BBjmo(P!b5K z2a?oxL+THQ?C61MH`SU~4283!TdTqeDpi*TZuB9AQ-UdrJ_{`NBTlyVHUqedW4pK` zDVlZuwoq}pQeE`6&KtC49X6=9wzDZ846rF4=4|pu{B5#bem1t-uvJs$TkgBbr;ID{ zDGe;qZwe~bZ|qR4E9r>Q(%I%lvDVhb<_+D3F18y0HKyOtxfpP(x{g#MsKEB5ZctNF zk{sIWyD@N+rZi}8`#l{o%DO%jvZLqb{>4+Q){f$|ktUC5?+<$be;d#g{7J58Q{$+4 zZitfu4fVJ;`=qeP{=G{=Y8wKfHmk2Sx47Sy9y_}2?DA;m$2#u8C@9rzY6sZ|l%U5T zdk)KkzgzYs|69Qyc_<&{M{glFdTFC(6V0uz5AoZ0(pkiP6L^90_X5r(`p!n{Wrapg9FKh15o)Z6BEu8lMk|Bz={3o6rWY`4j$M4Emy^)T(Q zoEeHcY%mme+<>J_1WqyDfaU8}xN%8?*1@tQp}0ed9>AT?8+}RwH~E%urM}q28Ok(U z{2pUA|3_suZl~N9@Q}h5xI<}cw^hBNLzxyMO7EVZ)a96WqD;_6k`ZK2ql@}O9AV;O z7J$BL2f4Q2BQ0jZ4~dIeak99+_q=IwZ-*VRXd-`?5Kr;ZVq)JizpeTQb=!T*#o&0@ z_uWq)$I_EM*SE~S+_2S9E-S(-*fP9?UCUvQ?zjGLV;$)355kAnor-!Db-TYk-ZBKN z{o7pJC9CjEgbzE*@K#T(oqt(BYv-ci`@5{`y#9~=Zd=#&{%%Ec)^u6>M>#0|wzXZ? zSbMd#+81s9bFTU_d``4gUZj3dT_oF%_sQkDb+`RtEu<1;ZmFW)|5;JgUGl$diqA~~ z(yj^oFFR0<#wv^CVsrn!I(Ul{pK_M@to;+=;5;*VnI8P50r@vu=n>`LDaO-hcvbX2 zJ03li!8ca^atQq=1M`1kI(ql!|AHX?r>p$$4Zs^GK}f4=vvz9p@{FzAr*wajYs_6q zca0gdC~47{u47h?>Dp=3>QSA#&RjLKYu9_M_uvBs*(oT{%Jof1NEk6{Vq)Up*zN&3%}}Hc9haEczZ-t2kHTZ2p_|TM8^z| ziOvYp24yIe%an@rI}@kiiZBq<*DrYnk5ws`$(6)ChAA{!#;2w(i?QOnw8QZgwakjIIxl1Kt71^Un92Dx>3jjf#okS9V4Hx{iu5#*D%jL;J-~E-x=%8K0RtIi6{UqI>Wqdi2py zEu-qmNA>C1XH>Vnd(#6)f_4QeG~>?hGiEH0?T+fkcAtSd^QkkI$M|-eo)EEk=O-;Yv{c2XG&Pbs4u1sC2*I5%INPZC$ zCQOKkn24_nj*N}%zGCFq7=9UhtfFGo2()O#Xh>=FDEcP(gw=_0^9F`H!Uqbv{@3_Q z+iINxtd^tZ@vCC-b;F4f!((E4tY9nj`n*+!&VyI=>EA!RAFTd;j1#8B@WaKy25WdY z_ug|y!?}J@&5Yeg17|=`j~=kJ`|+jP{rhL&526t86=zOh7*OQHuU0v(hO0r)fw)E_ z<6j60YEU|Yf;w^`9R5R)8bV|>pl67pND9(a2EE$|Vh{rt3@97!YI7(Xh)YM}*FXu4 zU`3`;^mPpKuy245)gZDEDuaf<0~X>?Ne&eX5|BkqM5OqWg&H#OAuCu5{$wy-hR3fQ zFknm&zG$vi%U9zsV@6_Z1`5D z4(CdE;wjI;rxEvplDnX z7yyg}CIYj8g}@4+1b7744;%$P0L}o-fPNWhfdRlsU?MOZSO}~DN`U>qQQ!mM3~(7} z2K3882TTNJ0}Fu_Knd^&upc-Id;pvQE(6Vgeg(<|1^^?0iNI`NA+Q1{0UiPN14n@m zfHS~lpc&BL2YO%tFcO#uOa>MM8-b62W?F3CK;RlBmkKNgb_3r5J?~d? z6M#bCb>KWOXD!+XIDpV~N^S}8D)1}dzh24B03HT9J)q?70?L8I!1qAM4N7htFdHxd z%Yi3>i-6XqGUD1eO4Yfd(L8qmqjPW&)dlV?g^& zN-iE)3+x6y0hFamZWxdZO#2UT2WT?gbop?v0dZwYZWo}~tmGB|{{qIAE4gAoxkbrY zf&Zke{|%al{$|}8z4Gtg`royy=QfP5zlkX1pYEo~hr4(?#{LfIS0Lv>B{%RPj5FZ# zhm~B~PRy}KFxMXa`{n%Idi{Sf|02lc?;;m8>)mwQ;EvjbaSk*9a~{K-1)_H=xsyPT zJxcBiU@q3ezgy1#h5Tw9xTe+V6dH|Itx&5po(-Q?t5B%bYOT%_f#20>^qzp0d`gW{ zqf=?f;AA4DO0Cpt@TV5JAV#H7Y1JyNww+)50JT=@tEW^PT;w(yji1iX(3uMe4CMUV z1*#1JhW3H&a1Isc7wF&7pW}1}ov%UX=Wp=$)B5}4pd@t%+J$L-HGaN<27|A`VDOju zdYb@$-!84j-#g`x{aw702Kf30dj&P{2j66dwVIm}{==YGalXDh{#(rrDgSZ6vqx*6 z*0x8pm>4$+$N**n?Sauif4~ZS1>6TD<}69i&dTJoA~N{&%uM_wHlKOLnexo(nf$!M zoQ#4jOU?}`OY^b{%xy{W<|SDfW0v4NX&MRPJ6H`*z*z^KZTzanPrWB+X zus9=&Gfii4m`w$F%S~~XOmk}>F=w8I#T!}tV8UP^0*C~nSo{bUKi!nF6uja=9}m9M z^9ww#DGtRZ7+C_65^^y2Ofyo(vT<&LaWhQQ&H1^OoP0BbKhJz`p&7K}%>^c^pI9$X zAOi)EKQ2yk5=Cdqy!j@vc9fKyoYF>y*5VwgmWF<4FwTEtbr< z=_tceV40GI`_w%JOif{}{FB}FM|soZ?_|kYIrG_c^Fo{;07q&=ia7&q^Y**j*;+4; zM=U?ZGEb75r*dvrN<_s9^VuD7NmHjvlD;E;3Y(dpRls^1qY6jjAcNld;~>~bV+0S) z$0x>*?41E|F6o`2_fE^o$tvK@d3lyRJ?oth0zSQDEbwIg4^EOLK^%cV<{`V?^d1yxSAY=NIPYW-k}j@p8%mk$MvUB3DFcenI+t zGY>njpfHz+-SXun(VH_VZn6a{NXkq;Y3dE3apUyNysTglPqoUJ#rMwVvoc5b&V(l~ zed%c9G6-@OQAmm8<1KR+_RbWOhG!#0so zr7mFO@>ohbo0y(cn4Y(sjWf^96FpPX^D-8&*xbCVY&Io*Ih$CRV}_NzoW&N-FT^}c zfle^vD2hCmlu=+IcdBKH6cKOEkUV-elnujyJR?{bZb%4a;W+?_jeqNJo;b6z^_ zR>ZwXhGlUs%0($lvv6id4qvdq%v0TnH*#iKGTDrr{9JQJ*1Rm_nx2}J;^yx@g2a?X zS~4d++cYmbJ%0h;rw=cBOy*@-1*T5>>2w77SJOy ze#X3|ww?QrojiL*U^2M^PgfePPRfZVrglN?J9O-X^O?H_cMIXW_vqQHcb~rf`VSa5 zC^RhGI5;9QYRJ%G!$*v~ebneN(J`@Ojh~P>anj@|QWP=;57@Ji6<#-FqtbKK{g$`<{CGnP>O^u(%CQTgUuZ@=^IKmYaK`yYIG@}rMWRekd5XP*^b>UTeJG)ZF55x&$2Wux8EuQXPs*HkEGPvTeshJ0IO$ z@%X-{_dkE&rNeU<=dxTZ>QfU^Q{rNi6WI8~acuaAbn1tLdKI_+5gE4#ps>fpsPKjz z0fN#EbPprQ08iSj(vd9EkW2Z=5RJDXo@Bh!sR98&ASJ*MZ@ijkI)FYGq-6)yVmP8& zx1YZ_XFL7rLjxzjqI+ZIi>o!EuU*;_ ze4;#)do{R@Ke%why+`W5i#@(>)#qn!`{nzyi>Dp_yy0K#KU;gp!`baBpIMZ-qG_)4 z*Z0jONq5VFPG_q#GDiD1Uo~h;-{W&`zlY13{C#ZN7kT&2fBcj06{E&~uAJmtZ}@c4 zVg0`5XATd^e)y%aU%r3ro0z88pSzg-bwuIa)d{BzUw(V%=uiIfobhy@k?gx^Mbo}| zuS0s(iNg&qcklVmp*wc&IC{!|-y5&(eofv_Yg3tCI_>+z55Ir9e~*W& z4!-=%SO4lb`p}(g3@?Y>e)k)%KA(NGl3)AUZ?7CW@rdt*R}_zY`eMO|@n2j%u=LZ% z+V}YeKMD9YKhP)R;=0>2w~tx4*znBkg)4kc`F;PGpxf5>1*U&-w`NuRHvgJWpU`et zP$%o=dP|)(XXf0-59gbU?j4%l`I353&XO*lyUq>#ta$c{Gu+9EXXjh0k2E#ekC(+A zf3@QmWe3xKdg9A3S8w}d?>ldOJ$!mybyDs8W1q~Q`TA35)rX@e4Si|CnSq9{CwI{w zxHeHSG;M`4_HBDw^^EHI&)Cay1}{IJHEz?P^bc=aJMZ<1Pc6NNURW@F$5P*uit#?j zj&zXs2=Aksas2k9@AmU~$UmmDjcj(@e&kF#-7 z&_aLVgWJ{f?)H%d2)oUjvtF2c{WD=vdcvvf4$Cg+E3SNM_$qa+a_U=$6eH66%zwJE zLt538@mY!AEX^4+ap5N~d^`Kg)AM|)V`^^ydRWQ}uRr_l?qlCsPrWq$XW_81Yuy`f zl)QEH1LL+sDNjA|axc};s-xS~Uwzbn=69(l=AZ5vwqo9)*CwXFBk!_c&h~+p0mF{_ zyu7!}_w6p#s@bJ>d1zuho+ANLjpRDaiqilO}npXz^_ufQ)c zDtZr&>OXkQpo-q*!E=Jr@nYph`d*!@dz|LWgL`#;v)!WxyLwuHs#8UWIYH9`9yOSB z|5ARg9phW<=gJI?){AYdvpmh;MUCcU3(4~ zJbXmNz+S-}{5y8*Jt%VI?NOn9Li&ac88v!n_^>h2_M%PL)8ZYP)<F`W( z7l%FHt4gi|&>83ogaAE&-hlELzGI-3-|!6ZHgk|-jH zB9bT~i6W9HB8eh`C?bd=f+!-0B7!I)hyr~Mizv|Nu!sVE4vQ$z=dg$ZeGZE#(C4s- z0(}mPDA4Dyhyr~Mizv|Nu!sVE4vQ#^gBiLVUPK`YS&$VZASD)H1(p#Qz$n`rppX+?p3g1bBKDYt|13iIRz<3}Cr~x_xb-)qiT@80T+&*v{fRA6p_j}-8 z2Y8?vZ~$?@^X~j-;NJwefU(HG<_JEMgewP>fEutN?I++eKxOO!?Tf%`@E?Zz1Ym{V z2YET5JwSOV?``nAUcvVY;ir5QcR#QWcmVL!`wgVY5vH<;H}Sohr#CNe9z^HiQx3Wk zgsDwsKsm4#*bY1hJPbSn>;iTJRG$jqao|bdDc~7kKkyvz0&oy`33wTJ1t6L~k^%ME zQKY{P90z;>4NwWZ1-t|N6L=5suJZ>7KM&cTg!?g21$+v84txoG4cy#k-y-fi;2dxP zXoj4>hx;Qya{LMSt3C_DJFefN+U6w9<4it+r#XptdkpXY*x;Tx7QU3(*X@G4N&0k; z*&lx#i^m`28M?cEzR-e!`k?*86xLy!)@$Ec)8J_Q{AwJQhtviI*;GuVucmo zq?|+@J#ja?ME42GEA=Xq=wk4~h^j~F2fWgVK9iU9)ve0(@c*l{`$ovQ`G6-s@uW5q z-Oj&J-Y0$k`??&vUC!+Ts4ic)-AcSX^5|nv9X)O)pUKC#>*|T~xJnt?0owO`RNNQw zZSDIxLGs7qPoHMS6KQH_ll8hCt3+8>`+h2z<;QFeF0QycFEA;w})#+8l256Gjhk+E~8 zcGvI8IjB12+Tx}Hx%RA)JUMUB zsVYa}1!OR9U{&lXraT$LrZ|wJu~Q|J)v1u{SWXPYQxD=Fzfly08-tHlKv>l=AumsG zRVq$6VqQW`Q8(POg9}2KqSmL}KPCwu@;%D-?>e*HH zBmS<+>XkLxO24#w7~95dPrapc#Y{Q-;@EA;Y&yn5GFnn0B191C6(bJeS13|grnuHE z?ff8=s}PzLksMQ84U0khW0>+BV~{@Mgi;)emf5D=^oEhU=NrfUg=`LZf(zR|*Rdf-HHvYsEb?WO0-!fJ8&)gnCa6T3v z|MM=U1S6k=j6odidA!8Ib*b8OD5(hJkYlpl7<9)oaw`4Pn1!9>2Ug1M!Ugv2*vVBU zo`uY)WAdwhUkv$<-DbbcDNbDG!=IdVzKpS-A7kun(!Ko!+#S1{$vL!FeobTEd{A%y ziiM?!O@oZ4f8Xj4n|{sEy-J*-_*5agPFD6M^T#C8x1eGjub|;7gfI$eoJ2+%$xp@; zrq|zoUqK*uH}Q-OsAGx)FRH)0pLI<`0t|KJ?t&cZ$QtxeC1YhgQ={?XdF068Q-se2 z%HhejpNU~?^pjkN(@ge*?#ja-lZGpSEV$m$UW}Yn2jPayI>$O8M!1fcVb>6&d+!`$kCjD6S(l+> zakdLj{#sdld@N-kAY54%8OeLXNE?f|rknHKGB4;+XGb#C`5IM?zp>6oD0oDF z5f){+jygNiz)AblIh5Y&L0Q627b7Egx5l)2$~;DniYnt@m&U*@FNbGG{SI$V8|5kj zRZ?;pQ(i;MqH|dp?gC?FVU@6c#q`*G&}u}2{yZ#b0$ANDV3FsKfnVaFcGP>QbR#<6 zwHagK#82N=u%z9k;YP!TpQ?7L&#f+%UHU=uQT-3x!mZmh4p1vxHCj}e_O{qflU&46f#5QVC5OvvK6r`&0E=X3rel`ly zR->b#X@2d#9ZnbFO=1=J2SpEe7yTBBK7*p=*HE;oUbfr$IQuwrQ7)-1x?7E@ojc%L zc!gN+VLVgSM(-Q{3!7yBS^U{mulP6OW5j9Cb|HtZ64os}i1c|DsYieBfhY{y8?X@h zUSHs3I&k(q2*FlD6UwgA{nlknTSGcJBu$0ReV)CK#j7FOh*^A;$}@>-?~15cu^!3m zLef}tEz?#(|8D$|8FHbSeteXL^Rlao+9a+Ni0E( zX5mJ*TU2{LQI%EoKZ3~D35!L?z>J-}EC*>03#i2+S6 zCd23P@k5c%vH4o*;8L8_^t->oo3G6Q5iLAL4BzO%HsnSxxOiec-V^n`>*crj>s^1M zp4P2y?=bE93Uy~^+%A#RyosjjT0ImINk(00{JP9 z(hv-ZL3?QR4T;g(-)Yb{P7uaI$2K5qctQ=5klzyXLdNO_R^~{Gffb|wVt7M1&o-H^ zToFv&0|LVF%`e^cao@95t|GSkqN*WQTggrdHT^&1wN)4{H~h2Jj;Uz}3ar<_*JQ3? z>>5h)pL>m|ujv}c3&|S$J2dQ~`42O54k})77PU1N(MQW#_!I9gt~!p*0UFx?T)hF$ zu%m9n^at5akYIlV-%Zwj_0)T-D?sVRy=&!B*-3V^>nH5ksWf)toAd0AfNzl=oqH53 ziH9xRBfFd1SAXu)lJMJ)6YGwn;>_x@6jICa7Pt8m8Pf(F^2EL=J_?vOSOJ6s&ilZ7Mx@L7Pb;ye4s)m#4uF@ z^Et8sMaHpsaEx z+Xh>8(x~3+f6WIgWSf!S2hGZqj|oB*HjvO_PKX0ebrsVK!YkZw2x8UpLy)#|6y#ci z36z;P*f^ZH!&J_5%7MbKuHk)mos`uGU1G?c=FYhQhn3lE54fEh$*Y|PkfSv)vSiT-rZpB1 zg<@o|a3M4e0T*B0$PmEVeJ=t`E4UD#y&wWu=*0kIt0*8EYZ~*pV86yrTu%}f37;rY z2nRu($4*GN#(acoA?<`SNVt0H6P9$XBcA!vKo$VN2xM8h3xSOo(CI=4AuXgyCUARd zE$86)T{}<&N85ZV4UXDzpa@T<+7@dShzyM(RQt`f8et0?Amrkq{EEFm{>U6lbSg@C~l4R32s+S4(3M09#HGOYWYl2GY%4oI)vFdG(8-0^FqQW8OLe zMJ3D-Tq9gDdoFH9p_XgU4FFFe|3{iYf`HLy5x%ktSUD|1xxw2_5^{Y=q|#TCu(ApV zDIhlJ)(#2~AfYfg=srB*iQN}Uf#o~z|E}N8hwxB>=6RduL#LiQN#+BlK6dQbQ6nl& z=_r`An!1JQ#36GkIjM?@4?kbMZY*O_lbUE`$-oeqAKr*b@8;@paoeV7u)iP^$z-L% zKbf6PMeO(0O5qTjjJu}MeHdnzO5!AxB{SJ~S1=hx)1yZZxZM$tUGsIJ<#mpAYY-e9 z25hCv{!@IJi*wzE)Hj)v^*cs;P$thstMQM^Qg1R*$`4O^3x2A(ytvznS}Fo@_@bd4C5 z^*wilT)+IqZ>d5N+)V~7S1W(e$s%@!g8CMcel#g9clbJcX8dOfm6 z3qp(_G~geBq<=erTXF062$edlazQvuLu87&fGL@1(FRj8U<&hZ2EY`?L7mOU`d?s* z7Jrvf+2SuWkR_y&)l8PqYJCZxGYHn3$kM`;Exr{@LA@%PK+#qRY2=2HMxy=|V(_vH zOfce3!Ey0e4`JMQzt$;sl1WyH!!4IelY|AQfd+;kd_wGCqR~sy7+%p({T_tC&rZ>< z`DW`J;+_OxK0+QbBTF6aR=B(77XzF67pn(e>2&i{HBD}w| zNUWkTT6F4U0nv>CD8nmTYryw25N1(hA9lC0S|s9$AsN{nndB%=xa>{fVQuCV)!(CX z6}p$Z3CT$U?<4dP&f5juDIr5>J|W=!UaD}dn=q}qMJF6o*e@uJCMc^x!j6UFfKIG- zZY73p^AYd%Y`)5Z=EWeOv_FRhe+ztFF?6T6jPUKb`j5f(2BvvY1&wTVaTpR2t%{jUoEeA_&6q05 z^%aUl4<^F>++OLBO>dQI9(tw@P1*R$x%2)H~ zU2#Oq?Jp%yWU?@4aKq+<7=;*&EwsL!5?TVgqs@CNMP_%w)>M#JD=wE>FeU#EI2c?i zDxw_9{NSE)h{wrdkW;};=Ha~J19t3GO&D=)U~s6}VJ@-pVGuJ+m}raN9cEgo70}l8 zTCAMqq&P>QrL}DHsZ%w0p-{_)hi@+uJuDo>iF-}*DD<^PF(%~0>(^QMFUO97?gEJo z^>Xsa38Vc4N`C|SFlj5`Ak}&D0x3b+g~O1Kq2e*&h2f*sK&|1zFT$=@abOqGGjcf#X+yswbQ)`Z}d>P3Ll;3booZ zc#}Vu_=?6NG@%nPj2>>(KDAkBy0ct(25S1GfAeP4rj`QObpJ^Jl@)4)i-A3QboYlB z;(hMq$q$nmON8#(!Nfi3HRi-_C+QjQ?;CP0k3Af`+G zf#0&-u5NP+%u2V3D4o_qR+@2}|6-C}-FYPe+O~ z1e4nzq>!5+q(t%vJS4QtWWx0W!auM33nhYM;$8||>_Guqk`bWwSqu!BPJtMz2hDOT zt%|5A3WPa8mTYq~MkqGa0{ZO)vT@>My~-5uLlv4}uB`e1)Tx&1m%Niarhd~2O9z$4j<#WU<2pCGnn1wvO9#@+1lI+lS8P#um9G! zaOd`k504!?@gef@=rraKPC==jI(gG}+dcnO)d#8m8a&Iw>4b7}8S78wF?KsS*Tq(o z(joy0P&CR%_Cp-tjpt$a0^lbpKZGkO8ZN{DV-ROECg33ihRm2DCnj|bq^ZJbQ&lI_ z!yC~f1h&vfmav&DXnL4G^Oo#~F@kHa8H1@L#Q_jNmB>#BuJ16~A@Rd_tSl1_R?|9; zHR@_7tah&VIAt2N05a21@fCJNtwP5#ISG6z0PlmMLz`Zy5ok@C6s0;t?pn7d zw`;&WDh^wec~+rmUb0ljA>tTI?n=9;cjRJRT6lenb@4U15dP}b>a_5>7VDf_2gGd9 zzA(v}*TJCNU4343mC`r`Q^GTLsWe2r7f9BfCs(gGA{+LzZr=3ht$!g>ZT*%j1q0K8l?tn(h*s* zP6xg}%8V){+-4chB!$~Ujzb0EPL!vK^;jvF;-8dP;J2lWeIid2)0^Z>r0=7s5W`ay z;ICzDHn~2`xk!O}XqjvyxoReV!X18F!NmN(D2n|249q!B8Kd{r3+#Sng(q8 zPwhXiEcekP+)kCI)55)7bq;hgmZ7Q=(|4%Sd?^20s$``c?n#wVqX8egibJ}Lbyp{g z`4iP?1|Nir)KdQE)s><=e^&Eic^xzeqaK+WqZrMg1~OC&~GKG0dF1bw;g5Et4P8F^xvXgjaQG zT9sU;dmS$1#J<&)>$E;H2HA_@ez=H5=L31-ejQ3*p|4S@5q?yEkm8*mA)WF!>CY+T zaFsqxsq%9<`}$O9DL%zVioeIF%Fm$1H)MT~AMQ&&=Wt#VV_#C(N9L6Kisd+?d@EHd zq)+fg{g9sNTcuK?ow$NqqcN~F4MwFLa@gq(zi!}hTohBhXE>))tC;#LLz+^F@L2=%^Y_PO_G5m2)IM?zOt|I_ z$N7uno~`glJm$kiw>z0bKOo=BoD?4%fH3F_1ElbG0ceLW6SRRv_(e1mCI%wikGYNp zA|3fO?Z6lOrnign)%(d@55qMe+)OU`CIw0ElW-~hGF(3>wS@MSS{>4h-0rdVQa-K& zTqRQs=pfbO{tiU}f#9d>Sm_^t_7!(TxuE;LBl2Nhbm}CzlRF_F>T{rzR4)g)pfh)t z^VZp}WL? zNDt1>AAIp)iDcl4J5u+yv{enZX7J?G(;H`)hI+Y=O4*3Pt&?lovNMC67N%CCWO$x} zaVYVjzOXu;D>sI{ag(jw=ZZ^7q=cmIW(M@&nFv2(JHK>x()pTC2 zR-#Q>6s2LmFee+mFkA~dY_a;*c!)#CLf>g8qB8i>8k__*oia;F2^1k{JB zVu((1WNZLk&8qpy0-~~!68?wSu@sf;i}vvZy;$lum;y}E_@`56!*gIKz5>YgZ4Uj z5+znJ;O=sYHITyYI4810_{=Gj!xke&8v&}4hg#|$s*(fUDMK;ps|}6RYqg?S6plKK zV(dX64>@aUWLH~STAG~A%+X9ge4r{pWFlwDazR!Qv7@C$aL*Sp6F7)j-8nIT$q-?i za7fVJtfVxtXRcEFF*|71d2NZ2CMFXvGIA-Xz{o@QdK%e;G9aOr<|dk;;v^2F&O|TB z@ewqcUmO~ZtC7i_?5g0D*SN4=Tz6hab1_{p+NkarIL%EM_a5U>H=ZyG5vW8OS2r4g zYNZqutVQk;nyD@TqFjOtJ&Wv+Eh!>V;M8Z5fe)SNY{K{fV`&7s#}bAi6@q@Ju9xcs z2*ssju0|(D%vFb+`p?ybzL(@9Cvi9^H*?4wG-uqVwJcAB+r2@kH>KSiyt%bErhAQj zB%rm_V39<$+^r%SabBT!wBdO+KtwhH|`)Hto96F`^ zHy9SqgI^rV7RPnWdyE}dOA~6ZQM+nceT%BG7Ts`_bePzua;H*Gs~fW5h!|QD$cPTD zspxeQ137fY2hCI$PTIgPwVdK16y5_-gCAVoVCrdXgGmR41FNVD-F2p;( zcanEJ{OA(uhu;|&q)L4v4|cdT>SojiYlT;?i#OE>Nu-5DO$0p$*^}732*lAQcCsi0 zhuCi@oVYfl%Rovh9(B3mXher&cs9F-282apP-NPopjqAG!t`|tF1eWHS4go1GX%8K zM1m+C$oB6W_o@OWpb_;A4S#o)5OtY3uA?!vv?{m_^bbufrITrVpjj07t!%SGha+0O z1>@%f;kp9#m=L7Lv1ga20P$#*x>)#cP8a61G$-99NX}mncJ8SfP53<= zelIgot>Q+DFJ7S;aI}10iDyi8phKpDyM^$$lFJb>W}X?jJ{##d_z_Kt-#H-6D#LShhMb^ zJsp76v2$m_ZE)ar?5uFt6%}Q@80y)#FYDWPEIbUaYkKMi|5vq} zGgZ#@2Jku$0|aMy;I;VK>{e?Ai8v?Mv)S?aSOYa7g$X-zG|MJ?r9xCHUB@m-AU?uB(HvOR%*}c1(9Jb=@swZ%leJ^^N6U&arP> zIb_H6!{2o1?FZK8De0SHQU52-d(toR*t$bB+NWM(;++@ji!h_p9BD0Sj&t>CzZ6|qTNigherE5H z1q;=)_a*ikVM#eTwtvKi?l0u~W@yJMyHo#k9Csu ze(M42r`BJr%~rw64+^_|WT;8}&EJtV^bHlsy!(LUr{9s%?*Z3tmviZ*Qrx}U=y%`P zsAD;zv=KYn=!lwr6B!S+Mz0Adz5Nq%F3X+A`6SWa&(>q=P+IJMIade}-4?h+`wnR1 z7ML>@@pCQ9+&l)qDCaIdFXdbFiX3O^ebQHjy4lyfhLat|V;u+U-JS@KCsHco5a_nJ zX{Ws`@hCzWV%?6)xkUh#zwdRae0qaRX}^6W=i=U$(qcb$r=iSLI*rm@uhP$?bP7KY zKh?j|&3o19wzPmVly*OR7ioW7Ur)uOJf0!M_vYWv?)^&QTZy`Sjo)!j`>w5=Rn?Mz zJytPl!+k%>ISW91_QH)~-Pk&J{jOe?bB6&+8~m$OcTc};sh4w`uSjX3%~GG?5g9Ln ziXO+oqHMWxX~&Fw-4?XnSxu7IJ`>W zMkAj@fkk7If}5J2W8tTZ=U(!0mYf_qsn=sv8U@!KxObj{OP{UaWHS|<6S#N2g1b0f z!TkV?PL*IzQE=_G3T}i>!3}}msYW`&0SHe)crW}%5cdXf0(cWR3yc8&RlpJ82cTZB z;93BMkAkD`gy!MI=0f~&+u74;^rT0H*>f+=sADL-q4nIAoxH!>5BOwGor=war?xdqGn^=FiPLqzxj%VKl5 zIse|mESz5&o}ZJR8=jt*S(ue$2_HH*Jk0GMJS03fJ!27$=*@3U_8ccF9!_e?K_`Sq zgbfWF9G+pp(eJIVyvQ^eZWWs;g zJ=__47rY3ei3)B9;7Osi%Hto6`Q-6?@(-B`T>-2DJ^^-4fery)1daespflp%g!?db zJ<%s3yclSrcwi6G-T-z0hk@s#72Gl4AMktY4juCL27W_4>5kvGy)b{SN7k|V%X2c4 za;3)8@V#(o28TTdx#|>6J{D2If&?gTj`g0O z&-dYR9%OP-;?z`A!qnKYlM~|mL#Hk?(Q1yVDQ*>T+V@~%L=@|eqqxO7nKQ92ljy}{ zoSIGtozu*1y=(=t$;S0ANJy8CK?hG>;wceH;z2e~?}hz&U$PY1w9JLpn9tM2Ed}Nr z>VN`^h0mrl&%;=E9G>o0Yfxr4n}2tIS4;anj7i$xjRxib2>|WyW&qy%yYue6l;0Zx zsaW5U_cuVP&?!48j5sqn0zYbrVnbR_)bF5}ffIwrVoCGfjcDDmfr`aA`QD73VHkFW zc{mSWEplm_CkxWEJ@XHz_-C3jAeAf(KT|&Tw>XmCl%AV~)7!hJ=b5Er8J_mjA6#DOJ?2UjX_@}^?A^s!yDK8EzPcO`F+w8rG zv`|Z%4yHV0y!)B_q(|RCK93%K6Mk{7lm;K+?%i&%xyjb4g{crc4p89$Ao;R1LpWZt(Dsv>? z+lcEnm_8+$=XrNXKY6-WAUVz}uq+wdE>E^(BJu>LcmxVAC3JVL<|H)vxL1#cu{7!x3na#KhC>`?=_e0>)2h6}x{0uA< zkrAdTv9s8y!kir3k&!uu@uM&gNj76p$2KV>&{Z=$-OocJkV23h*1nNEu3VXgXYowP zqjx3`2^VIIUU#-BSUVsL2x}6q!!T#_BDF}CJ!=q;rGhr}ZQ&_&&qrG@#f*K|0z755 zMM3De*CW|t$!?2FSb`Rgqh+uyPTZZh1>F@9H|cG$vH2J);`x_EpCtEVG>9gdx zb1^;5W+V*kjUgm8{*LtQLQj=2CJXcOP`-N@LJo9aOrobzJnl=%Tkd8iJ$}#%ctZr* z)EZ9q_)svUj>cja1JMuSmt^H<6^!H;6cps+d#=|l!i^KE7&D25BqAgu?Gpmm! zAA9K0ILxaLJ*0cCzd>MeF7C_eBPAC0DVSd{dTQ*{B$M=3#YA@#CB&sNuMsLWS?qlb z&%YXocnlD4E)i8rHiE>diK(WjKsua8KDO_2+lJNc=sxbXIeumEe$%NotI}>{O?jr zSHysGj(O>gm&|~5n;E4O1)5A>!f`L$g)|dWpJ?l$P_;0noWFemR>GY0=xROiH z$ewU`enBRBnvsh~V{&jS&0lp3ZB_H397LCvBXLvTw)E!};LaKM>eV)zq+NPeCQHY4 zPuP-(yAijxFqvu6(G4^6^KY3hUDb4=o`FVG&? z--x++yd791u9{HgQcPivcigQ@YSkdErJ?aTh1uD;1-Nd>qh9#*40`oJD9)vtelu|o^uCmGV)%=L0p0r;l?z@%WTL zG!*ae6(8Ug-_9$ZKHVcj`8&e(@aZhZO7UI1;)A{7X*PN0kULuBgI8FseDKO#G{m1? zXM6bLW82nv&(|BNU7n9pDZigre$N9x#nUJ7|4(~o9~;GShVj`u8wdijB9KtWM9cRX z47RZgC^6>DnX?VXxPi7%hz?^P*l_;9cYvW(u`0KP2DP-MDphC$2t`UDN=xi2e;CCr zmO>LCriFx71ck&Qq%sYEK!AwWeV*NS)=Qy)C~0Yxk$(5g%)YxbH#_?=@9y2`?F?}? zW0(7|Cx4hHKgE-u>dC)Z{Z+d^sO!u)>&dd<-4C*EI!RBd+%&%hLOfaqcf|&wZrhdcV-dyM4C5wsGHJ!1i@J(_XhN<7`iD&ov z5NBE1-YpCEx)0OdTNccnfPD4=y{_8_u&(Z(T-WUbh_er9d$$k3UiY_uRn~bN`@1&b z+015)m7ejNpCEk+{2F;*`kupZ=tM9bpx|eRZ9Td@)*^n1?YoPvZeh5?P9y<+Rd}3gFpE z0%!9?8W-kTg=NL_B4xN$3C;Uz=>pHG_>K$3e7aI5WAVyzp4aVYMNIKp7r_YH%EMri zmlro97gzJS5%@w&BPH`fbLQVo(e5;IxI^R=a!g0)4a~5M;Y}oNAM7~2GpcG`q#{;c zU4zePd4o(XS6LUSsHs%d4XY!V7C4f?#Wa$ri@+ZcwI4>Q`dG|%?kN38DN+unPYpaB z30QN+J8n3NZz$4a6fW6+Hrr@qw+tH)!SMS=noz!VP91YmJqgYXy22 zjkTt(!S(SjcD>saH=9w<{?ZxtCvT@P?8TgKAif)W`XmHHFiNlp6{qh*c zQ0p!GNWdLAXUA-aRIQtshm#_`(ar(s9NyS{_q<)~0yFGSv<+tljW%LJPTPxLFqfmk zWxW%PThn-6!J!e2a0C<$*h5e}Fq(a@>SdoVakAnxoS2pqeSKNPnZ(?CI=l5!e2;W@ zZghAY%3bfo$T9JeGB$bK8S6499S;y|qu3kH)U^G_j~{Q9<(C$REX4Y|bE)H~!$U0# z7pXXBEydKmbq$=`w7wjU=Jj~D(720}WW2swE>(=x)WxfLzOm!g@j9g=Ix}7oTV-c5 z;%3I9F~w7MoLx1?>ArRnU69=_P(ueFuXoNeJBel4X^QVVL~BtH8vUlW}9 zpt7KLfQQiu0S2Au)lKI0A;}GrpKk}_Cc!b7X$QRfc|+iGORDkTl#>{PgiwL9dGm`G zN<}6?d4GNKkl!3F9QDL?p4Rdn9AvG>~CEI#s0zq#)XDVOVkZj@o?NgYl}nH!;B1Ha*N$(zk}VR!WR zz2%=ny0|oqtMqaOFPp-vGnkM?Pr{myS7l~}xl4NUoEcY{7od{@5709a@9nTo4DE`^`T9rvD6mPvY%eezP9y-44B-+iCj;esc=8Njt6Ats~2r zciI#8+9b*MVP3i??zOpDd?{?V1D30KQS!9?FHt{xyU;Sw2;Pu-{O*jiEJfOec5P^z z|HOWTla)8uI49$`;N_+EzE@4}OwC>yA z$bBvT^tGC+f|g(WX?>{i zF9jTI&~PaDvFv(46r8r6jU$C^gRtSOgP}~b)i=k;-d@Oj1Etu%K_wu%-2d?co7UMsUDZ zBY3$rNsTJP$oxXXmA-0Zk-AWOrH>i`U3taWsxthYYLd~Z0?Eg|J0f+?@Y%z$BzmRi z@+&>B7XGSGSv{AJ_6!`=&uSl$qMF0LvBk+N!kbq14Q9^7zrv31)44rmV8DOUYBV12 zx7^548Ofb$g1@t0t?@*l-uSYqhK0@^GctQF@9i<3-Co#p`MI9U2QX8ynuQZ~7$@(K z@P5weamnTw%pr53HEC>;8m@+^mhdF?SV$eaZ~!gS=^J;pDsN_=&cCMgo#a0`sL^=h z`K3mdn%LdBBFrV{I-jpHraxS7O#a{_qs3R$95&jP7OL0IJO_WCCw+dG^Q`oo->`ot zcTBx%=ICTZ7CCu!H$C29Jvyn+5QZ*YAxlIi+|B<=coB<=c{B<&N`LcfnU zxV|*WbbWV{cKv{o);>|a4ejIAY40-;=6Qa`W1G;Y=M67Em~8&>75sYWJ`R7&!+W_k z&a)Z%k{Ryf>V9rjvsM_E8Z@r23MK{ZLYhSFg!f4G?oMwHl4ffysxq>E5LSit;RmJ} z#hVJ%f%2dG@!Of}Ls_;`C13$~67Zf@TXa02tn~iM+6Hvq{ieD_24x@Fn=`oPZ1?Hp z8;*zjtAwnvYj26ya)kmYDG?Sx$r7OwN@79+N;V43P_jkX1|>U$Jy5bwXn~S8p#w?|3&)}4 zl+Xnw-NHpExhCLOJQf)s41tnVVKkJa3pr4dD-=LUiLd}lmI#$l;@lhi)T|_BF8aIA re95QGT^Y*UyjYnhHYl@rqcRU5|Al0~`7wTrv>ET<&VBUy_jLaOU$fT^ diff --git a/examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/02_designing_the_button/sketch.json b/examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/02_designing_the_button/sketch.json deleted file mode 100644 index abdab11..0000000 --- a/examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/02_designing_the_button/sketch.json +++ /dev/null @@ -1,6 +0,0 @@ -{ - "cpu": { - "fqbn": "arduino:mbed_nano:nanorp2040connect", - "port": "" - } -} \ No newline at end of file diff --git a/examples/Platform_Tutorials/lessons/03-important-programming-concepts/Braccio_moving_range_angles/Braccio_moving_range_angles.ino b/examples/Platform_Tutorials/lessons/03-important-programming-concepts/Braccio_moving_range_angles/Braccio_moving_range_angles.ino new file mode 100644 index 0000000..5d22936 --- /dev/null +++ b/examples/Platform_Tutorials/lessons/03-important-programming-concepts/Braccio_moving_range_angles/Braccio_moving_range_angles.ino @@ -0,0 +1,119 @@ +/************************************************************************************** + * INCLUDE + **************************************************************************************/ + +#include + +/************************************************************************************** + * DEFINES + **************************************************************************************/ + +#define BUTTON_SELECT 3 +#define BUTTON_ENTER 6 +#define TIME_DELAY 2000 + +/************************************************************************************** + * CONSTANTS + **************************************************************************************/ + +static float const HOME_POS[6] = {157.5, 157.5, 157.5, 157.5, 157.5, 90.0}; + +/************************************************************************************** + * GLOBAL VARIABLES + **************************************************************************************/ + +static auto gripper = Braccio.get(1); +static auto wristRoll = Braccio.get(2); +static auto wristPitch = Braccio.get(3); +static auto elbow = Braccio.get(4); +static auto shoulder = Braccio.get(5); +static auto base = Braccio.get(6); + +float angles[6]; + +/************************************************************************************** + * SETUP/LOOP + **************************************************************************************/ + +void setup() { + if (Braccio.begin()) + { + /* Configure Braccio speed. */ + /* Warning: keep a safe distance from the robot and watch out for the robot's + movement. It could be speedy and hit someone. */ + Braccio.speed(speed_grade_t(1000)/*SLOW*/); + /* Move to home position. */ + Braccio.moveTo(HOME_POS[0], HOME_POS[1], HOME_POS[2], HOME_POS[3], HOME_POS[4], HOME_POS[5]); + delay(TIME_DELAY); + } +} + +void loop() { + int pressedKey = Braccio.getKey(); + + if (pressedKey == BUTTON_ENTER) + { + // Pinch movement + gripper.move().to(230.0f); delay(TIME_DELAY); + gripper.move().to(HOME_POS[0]); delay(TIME_DELAY); + + // // Wrist Roll movement + wristRoll.move().to(0.0f); delay(TIME_DELAY); + wristRoll.move().to(HOME_POS[1]); delay(TIME_DELAY); + wristRoll.move().to(315.0f); delay(TIME_DELAY); + wristRoll.move().to(HOME_POS[1]); delay(TIME_DELAY); + + // // Wrist Pitch movement + wristPitch.move().to(70.0f); delay(TIME_DELAY); + wristPitch.move().to(HOME_POS[2]); delay(TIME_DELAY); + wristPitch.move().to(260.0f); delay(TIME_DELAY); + wristPitch.move().to(HOME_POS[2]); delay(TIME_DELAY); + + // Elbow movement + for(float i=HOME_POS[3]; i >= 70.0; i-=5) + { elbow.move().to(i); delay(TIME_DELAY/2000); } + elbow.move().to(HOME_POS[3]); delay(TIME_DELAY); + for(float i=HOME_POS[3]; i <= 260.0; i+=5) + { elbow.move().to(i); delay(TIME_DELAY/2000); } + elbow.move().to(HOME_POS[3]); delay(TIME_DELAY); + + // Shoulder movement + shoulder.move().to(120.0f); delay(TIME_DELAY/2); + shoulder.move().to(90.0f); delay(TIME_DELAY/2); + shoulder.move().to(120.0f); delay(TIME_DELAY/2); + shoulder.move().to(HOME_POS[4]); delay(TIME_DELAY); + shoulder.move().to(200.0f); delay(TIME_DELAY/2); + shoulder.move().to(230.0f); delay(TIME_DELAY/2); + shoulder.move().to(200.0f); delay(TIME_DELAY/2); + shoulder.move().to(HOME_POS[4]); delay(TIME_DELAY); + + // Base movement + base.move().to(0.0f); delay(TIME_DELAY); + base.move().to(HOME_POS[5]); delay(TIME_DELAY); + base.move().to(315.0f); delay(TIME_DELAY); + base.move().to(HOME_POS[5]); delay(TIME_DELAY); + + while(pressedKey == BUTTON_ENTER) { pressedKey = Braccio.getKey(); } + } + + if (pressedKey == BUTTON_SELECT) + { + // Fetch the joints positions + Braccio.positions(angles); + + // Print the joint angles + Serial.println("************* Joints Angles *************"); + Serial.println("|\tMotor ID\t|\tAngle\t|"); + Serial.println("----------------------------------------"); + Serial.print("| 1 - Gripper\t\t|\t" + String(angles[0]) + "\t|\n" + + "| 2 - Wrist Rotation\t|\t" + String(angles[1]) + "\t|\n" + + "| 3 - Wrist Vertical\t|\t" + String(angles[2]) + "\t|\n" + + "| 4 - Elbow\t\t|\t" + String(angles[3]) + "\t|\n" + + "| 5 - Shoulder\t\t|\t" + String(angles[4]) + "\t|\n" + + "| 6 - Base\t\t|\t" + String(angles[5]) + "\t|\n" + + "*****************************************\n\n\n\n\n"); + + while(pressedKey == BUTTON_SELECT) { pressedKey = Braccio.getKey(); } + + } +} \ No newline at end of file diff --git a/examples/Platform_Tutorials/lessons/03-important-programming-concepts/Navigating_the_display_menu/Navigating_the_display_menu.ino b/examples/Platform_Tutorials/lessons/03-important-programming-concepts/Navigating_the_display_menu/Navigating_the_display_menu.ino new file mode 100644 index 0000000..a6b107b --- /dev/null +++ b/examples/Platform_Tutorials/lessons/03-important-programming-concepts/Navigating_the_display_menu/Navigating_the_display_menu.ino @@ -0,0 +1,81 @@ +#include + +#define MARGIN_LEFT 0 +#define MARGIN_TOP 0 + +// Arduino Colors +#define COLOR_TEAL 0x00878F +#define COLOR_LIGHT_TEAL 0x62AEB2 +#define COLOR_ORANGE 0xE47128 +#define COLOR_YELLOW 0xE5AD24 +#define COLOR_WHITE 0xFFFFFF + +static const char * btnm_map[] = {"Option 1", "Option 2", "\n", + "Option 3", "Option 4", "\n", + "Option 5", "Option 6", "\0" + }; + +void setup() { + if (!Braccio.begin(customMenu)) { + if (Serial) Serial.println("Braccio.begin() failed."); + for(;;) { } + } +} + +void loop() { + // Let here empty. +} + +void customMenu(){ + Braccio.lvgl_lock(); + + static lv_style_t style_bg; + lv_style_init(&style_bg); + lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_WHITE)); + + static lv_style_t style_btn; + lv_style_init(&style_btn); + lv_style_set_bg_color(&style_btn, lv_color_hex(COLOR_YELLOW)); + lv_style_set_border_color(&style_btn, lv_color_hex(COLOR_LIGHT_TEAL)); + lv_style_set_border_width(&style_btn, 2); + lv_style_set_text_color(&style_btn, lv_color_hex(COLOR_TEAL)); + + + lv_obj_t * btnm = lv_btnmatrix_create(lv_scr_act()); + lv_btnmatrix_set_map(btnm, btnm_map); + lv_obj_align(btnm, LV_ALIGN_CENTER, MARGIN_LEFT, MARGIN_TOP); + + lv_obj_add_style(btnm, &style_bg, 0); + lv_obj_add_style(btnm, &style_btn, LV_PART_ITEMS); + + lv_btnmatrix_set_btn_ctrl(btnm, 0, LV_BTNMATRIX_CTRL_CHECKABLE); + lv_btnmatrix_set_btn_ctrl(btnm, 1, LV_BTNMATRIX_CTRL_CHECKABLE); + lv_btnmatrix_set_btn_ctrl(btnm, 2, LV_BTNMATRIX_CTRL_CHECKABLE); + lv_btnmatrix_set_btn_ctrl(btnm, 3, LV_BTNMATRIX_CTRL_CHECKABLE); + lv_btnmatrix_set_btn_ctrl(btnm, 4, LV_BTNMATRIX_CTRL_CHECKABLE); + lv_btnmatrix_set_btn_ctrl(btnm, 5, LV_BTNMATRIX_CTRL_CHECKABLE); + + lv_btnmatrix_set_one_checked(btnm, true); + + lv_obj_add_event_cb(btnm, eventHandler, LV_EVENT_ALL, NULL); + + Braccio.lvgl_unlock(); + + Braccio.connectJoystickTo(btnm); +} + +static void eventHandler(lv_event_t * e){ + Braccio.lvgl_lock(); + + lv_event_code_t code = lv_event_get_code(e); + lv_obj_t * obj = lv_event_get_target(e); + if (code == LV_EVENT_CLICKED) { + uint32_t id = lv_btnmatrix_get_selected_btn(obj); + const char * txt = lv_btnmatrix_get_btn_text(obj, id); + + LV_LOG_USER("%s was selected\n", txt); + Serial.println(String(txt) + " was selected."); + } + + Braccio.lvgl_unlock(); +} \ No newline at end of file diff --git a/examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/01_creating_a_button/01_creating_a_button.ino b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/01_creating_a_button/01_creating_a_button.ino similarity index 75% rename from examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/01_creating_a_button/01_creating_a_button.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/01_creating_a_button/01_creating_a_button.ino index 2ee6ed1..7f3d00e 100644 --- a/examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/01_creating_a_button/01_creating_a_button.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/01_creating_a_button/01_creating_a_button.ino @@ -1,19 +1,24 @@ - #include +#include void customMenu() { Braccio.lvgl_lock(); + lv_obj_t * btn1 = lv_btn_create(lv_scr_act()); lv_obj_set_size(btn1, 120, 75); lv_obj_t * label1 = lv_label_create(btn1); lv_label_set_text(label1, "BTN 1"); lv_obj_align(btn1, LV_ALIGN_CENTER, 0, 0); lv_obj_center(label1); + Braccio.lvgl_unlock(); } void setup() { // put your setup code here, to run once: - Braccio.begin(customMenu); + if (!Braccio.begin(customMenu)) { + if (Serial) Serial.println("Braccio.begin() failed."); + for(;;) { } + } } void loop() { diff --git a/examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/02_designing_the_button/02_designing_the_button.ino b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/02_styling_the_button/02_styling_the_button.ino similarity index 84% rename from examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/02_designing_the_button/02_designing_the_button.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/02_styling_the_button/02_styling_the_button.ino index 295e3eb..9347adf 100644 --- a/examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/02_designing_the_button/02_designing_the_button.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/02_styling_the_button/02_styling_the_button.ino @@ -1,41 +1,44 @@ -#include - -// Arduino Colors -#define COLOR_TEAL 0x00878F -#define COLOR_LIGHT_TEAL 0x62AEB2 -#define COLOR_ORANGE 0xE47128 -#define COLOR_YELLOW 0xE5AD24 -#define COLOR_WHITE 0xFFFFFF - - -void customMenu() { - Braccio.lvgl_lock(); - static lv_style_t style; - lv_style_init(&style); - lv_style_set_bg_color(&style, lv_color_hex(COLOR_WHITE)); - lv_style_set_border_color(&style, lv_color_hex(COLOR_TEAL)); - lv_style_set_border_width(&style, 5); - lv_style_set_text_color(&style, lv_color_hex(COLOR_ORANGE)); - - lv_obj_t * btn1 = lv_btn_create(lv_scr_act()); - lv_obj_set_size(btn1, 120, 75); - - lv_obj_t * label1 = lv_label_create(btn1); - lv_label_set_text(label1, "BTN 1"); - - lv_obj_align(btn1, LV_ALIGN_CENTER, 0, 0); - lv_obj_center(label1); - - lv_obj_add_style(btn1, &style, 0); - Braccio.lvgl_unlock(); -} - -void setup() { - // put your setup code here, to run once: - Braccio.begin(customMenu); -} - -void loop() { - // put your main code here, to run repeatedly: - -} +#include + +// Arduino Colors +#define COLOR_TEAL 0x00878F +#define COLOR_LIGHT_TEAL 0x62AEB2 +#define COLOR_ORANGE 0xE47128 +#define COLOR_YELLOW 0xE5AD24 +#define COLOR_WHITE 0xFFFFFF + + +void customMenu() { + Braccio.lvgl_lock(); + static lv_style_t style; + lv_style_init(&style); + lv_style_set_bg_color(&style, lv_color_hex(COLOR_WHITE)); + lv_style_set_border_color(&style, lv_color_hex(COLOR_TEAL)); + lv_style_set_border_width(&style, 5); + lv_style_set_text_color(&style, lv_color_hex(COLOR_ORANGE)); + + lv_obj_t * btn1 = lv_btn_create(lv_scr_act()); + lv_obj_set_size(btn1, 120, 75); + + lv_obj_t * label1 = lv_label_create(btn1); + lv_label_set_text(label1, "BTN 1"); + + lv_obj_align(btn1, LV_ALIGN_CENTER, 0, 0); + lv_obj_center(label1); + + lv_obj_add_style(btn1, &style, 0); + Braccio.lvgl_unlock(); +} + +void setup() { + // put your setup code here, to run once: + if (!Braccio.begin(customMenu)) { + if (Serial) Serial.println("Braccio.begin() failed."); + for(;;) { } + } +} + +void loop() { + // put your main code here, to run repeatedly: + +} diff --git a/examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/03_creating_a_menu/03_creating_a_menu.ino b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/03_designing_a_menu/03_designing_a_menu.ino similarity index 91% rename from examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/03_creating_a_menu/03_creating_a_menu.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/03_designing_a_menu/03_designing_a_menu.ino index e5ab044..6f5d7e2 100644 --- a/examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/03_creating_a_menu/03_creating_a_menu.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/03_designing_a_menu/03_designing_a_menu.ino @@ -1,48 +1,53 @@ -#include - -#define MARGIN_LEFT 0 -#define MARGIN_TOP 0 - -// Arduino Colors -#define COLOR_TEAL 0x00878F -#define COLOR_LIGHT_TEAL 0x62AEB2 -#define COLOR_ORANGE 0xE47128 -#define COLOR_YELLOW 0xE5AD24 -#define COLOR_WHITE 0xFFFFFF - -static const char * btnm_map[] = {"OPTION 1", "OPTION 2", "\n", - "OPTION 3", "OPTION 4", "\0" - }; - -void customMenu() { - Braccio.lvgl_lock(); - static lv_style_t style_bg; - lv_style_init(&style_bg); - lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_LIGHT_TEAL)); - - static lv_style_t style_btn; - lv_style_init(&style_btn); - lv_style_set_bg_color(&style_btn, lv_color_hex(COLOR_WHITE)); - lv_style_set_border_color(&style_btn, lv_color_hex(COLOR_YELLOW)); - lv_style_set_border_width(&style_btn, 2); - lv_style_set_text_color(&style_btn, lv_color_hex(COLOR_TEAL)); - - - lv_obj_t * btnm1 = lv_btnmatrix_create(lv_scr_act()); - lv_btnmatrix_set_map(btnm1, btnm_map); - lv_obj_align(btnm1, LV_ALIGN_CENTER, MARGIN_LEFT, MARGIN_TOP); - - lv_obj_add_style(btnm1, &style_bg, 0); - lv_obj_add_style(btnm1, &style_btn, LV_PART_ITEMS); - Braccio.lvgl_unlock(); -} - -void setup() { - // put your setup code here, to run once: - Braccio.begin(customMenu); -} - -void loop() { - // put your main code here, to run repeatedly: - -} +#include + +#define MARGIN_LEFT 0 +#define MARGIN_TOP 0 + +// Arduino Colors +#define COLOR_TEAL 0x00878F +#define COLOR_LIGHT_TEAL 0x62AEB2 +#define COLOR_ORANGE 0xE47128 +#define COLOR_YELLOW 0xE5AD24 +#define COLOR_WHITE 0xFFFFFF + +static const char * btnm_map[] = {"OPTION 1", "OPTION 2", "\n", + "OPTION 3", "OPTION 4", "\0" + }; + +void customMenu() { + Braccio.lvgl_lock(); + + static lv_style_t style_bg; + lv_style_init(&style_bg); + lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_LIGHT_TEAL)); + + static lv_style_t style_btn; + lv_style_init(&style_btn); + lv_style_set_bg_color(&style_btn, lv_color_hex(COLOR_WHITE)); + lv_style_set_border_color(&style_btn, lv_color_hex(COLOR_YELLOW)); + lv_style_set_border_width(&style_btn, 2); + lv_style_set_text_color(&style_btn, lv_color_hex(COLOR_TEAL)); + + + lv_obj_t * btnm1 = lv_btnmatrix_create(lv_scr_act()); + lv_btnmatrix_set_map(btnm1, btnm_map); + lv_obj_align(btnm1, LV_ALIGN_CENTER, MARGIN_LEFT, MARGIN_TOP); + + lv_obj_add_style(btnm1, &style_bg, 0); + lv_obj_add_style(btnm1, &style_btn, LV_PART_ITEMS); + + Braccio.lvgl_unlock(); +} + +void setup() { + // put your setup code here, to run once: + if (!Braccio.begin(customMenu)) { + if (Serial) Serial.println("Braccio.begin() failed."); + for(;;) { } + } +} + +void loop() { + // put your main code here, to run repeatedly: + +} diff --git a/examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/04_testing_it_out/04_testing_it_out.ino b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/04_adding_an_extra_button/04_adding_an_extra_button.ino similarity index 87% rename from examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/04_testing_it_out/04_testing_it_out.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/04_adding_an_extra_button/04_adding_an_extra_button.ino index 12c0601..9f45754 100644 --- a/examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/04_testing_it_out/04_testing_it_out.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/04_adding_an_extra_button/04_adding_an_extra_button.ino @@ -1,48 +1,53 @@ -#include - -#define MARGIN_LEFT 0 -#define MARGIN_TOP 0 - -// Arduino Colors -#define COLOR_TEAL 0x00878F -#define COLOR_LIGHT_TEAL 0x62AEB2 -#define COLOR_ORANGE 0xE47128 -#define COLOR_YELLOW 0xE5AD24 - -static const char * btnm_map[] = {"OPTION 1", "OPTION 2", "OPTION 3", "\n", - "OPTION 4", "OPTION 5", "\0" - }; - -void customMenu() { - Braccio.lvgl_lock(); - static lv_style_t style_bg; - lv_style_init(&style_bg); - lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_LIGHT_TEAL)); - - static lv_style_t style_btn; - lv_style_init(&style_btn); - lv_style_set_bg_color(&style_btn, lv_color_hex(0xFFFFFF)); - lv_style_set_border_color(&style_btn, lv_color_hex(COLOR_YELLOW)); - lv_style_set_border_width(&style_btn, 2); - lv_style_set_text_color(&style_btn, lv_color_hex(COLOR_TEAL)); - - - lv_obj_t * btnm1 = lv_btnmatrix_create(lv_scr_act()); - lv_btnmatrix_set_map(btnm1, btnm_map); - lv_btnmatrix_set_btn_width(btnm1, 3, 2); // Make "Option 4" twice as wide as "Option 5" - lv_obj_align(btnm1, LV_ALIGN_CENTER, MARGIN_LEFT, MARGIN_TOP); - - lv_obj_add_style(btnm1, &style_bg, 0); - lv_obj_add_style(btnm1, &style_btn, LV_PART_ITEMS); - Braccio.lvgl_unlock(); -} - -void setup() { - // put your setup code here, to run once: - Braccio.begin(customMenu); -} - -void loop() { - // put your main code here, to run repeatedly: - -} +#include + +#define MARGIN_LEFT 0 +#define MARGIN_TOP 0 + +// Arduino Colors +#define COLOR_TEAL 0x00878F +#define COLOR_LIGHT_TEAL 0x62AEB2 +#define COLOR_ORANGE 0xE47128 +#define COLOR_YELLOW 0xE5AD24 + +static const char * btnm_map[] = {"OPTION 1", "OPTION 2", "OPTION 3", "\n", + "OPTION 4", "OPTION 5", "\0" + }; + +void customMenu() { + Braccio.lvgl_lock(); + + static lv_style_t style_bg; + lv_style_init(&style_bg); + lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_LIGHT_TEAL)); + + static lv_style_t style_btn; + lv_style_init(&style_btn); + lv_style_set_bg_color(&style_btn, lv_color_hex(0xFFFFFF)); + lv_style_set_border_color(&style_btn, lv_color_hex(COLOR_YELLOW)); + lv_style_set_border_width(&style_btn, 2); + lv_style_set_text_color(&style_btn, lv_color_hex(COLOR_TEAL)); + + + lv_obj_t * btnm1 = lv_btnmatrix_create(lv_scr_act()); + lv_btnmatrix_set_map(btnm1, btnm_map); + lv_btnmatrix_set_btn_width(btnm1, 3, 2); // Make "Option 4" twice as wide as "Option 5" + lv_obj_align(btnm1, LV_ALIGN_CENTER, MARGIN_LEFT, MARGIN_TOP); + + lv_obj_add_style(btnm1, &style_bg, 0); + lv_obj_add_style(btnm1, &style_btn, LV_PART_ITEMS); + + Braccio.lvgl_unlock(); +} + +void setup() { + // put your setup code here, to run once: + if (!Braccio.begin(customMenu)) { + if (Serial) Serial.println("Braccio.begin() failed."); + for(;;) { } + } +} + +void loop() { + // put your main code here, to run repeatedly: + +} diff --git a/examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/05_display_challenge/05_display_challenge.ino b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/05_display_challenge/05_display_challenge.ino similarity index 92% rename from examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/05_display_challenge/05_display_challenge.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/05_display_challenge/05_display_challenge.ino index 9209311..d29e555 100644 --- a/examples/Platform_Tutorials/lessons/01-programming-the-braccio-display/05_display_challenge/05_display_challenge.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/05_display_challenge/05_display_challenge.ino @@ -15,6 +15,7 @@ static const char * btnm_map[] = {"BTN 1", "\n", void customMenu() { Braccio.lvgl_lock(); + static lv_style_t style_bg; lv_style_init(&style_bg); lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_BG)); @@ -34,12 +35,16 @@ void customMenu() { lv_obj_add_style(btnm1, &style_bg, 0); lv_obj_add_style(btnm1, &style_btn, LV_PART_ITEMS); + Braccio.lvgl_unlock(); } void setup() { // put your setup code here, to run once: - Braccio.begin(customMenu); + if (!Braccio.begin(customMenu)) { + if (Serial) Serial.println("Braccio.begin() failed."); + for(;;) { } + } } void loop() { diff --git a/examples/Platform_Tutorials/lessons/02-navigatting-the-display-menu/01_playing_with_the_Joystick/01_playing_with_the_Joystick.ino b/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/01_playing_with_the_Joystick/01_playing_with_the_Joystick.ino similarity index 93% rename from examples/Platform_Tutorials/lessons/02-navigatting-the-display-menu/01_playing_with_the_Joystick/01_playing_with_the_Joystick.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/01_playing_with_the_Joystick/01_playing_with_the_Joystick.ino index 70fd320..6911840 100644 --- a/examples/Platform_Tutorials/lessons/02-navigatting-the-display-menu/01_playing_with_the_Joystick/01_playing_with_the_Joystick.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/01_playing_with_the_Joystick/01_playing_with_the_Joystick.ino @@ -14,7 +14,7 @@ String checkJoystick(int input){ void setup() { Serial.begin(115200); - while(!Serial){} + while (!Serial) {} Braccio.begin(); Serial.println("Press any button or move the joystick."); } @@ -22,7 +22,7 @@ void setup() { void loop() { int joystickPos = Braccio.getKey(); message = checkJoystick(joystickPos); - if(message != ""){ + if (message != "") { Serial.println(message); message = ""; } diff --git a/examples/Platform_Tutorials/lessons/02-navigatting-the-display-menu/02_handling_events_in_the_menu/02_handling_events_in_the_menu.ino b/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/02_handling_events_in_the_menu/02_handling_events_in_the_menu.ino similarity index 92% rename from examples/Platform_Tutorials/lessons/02-navigatting-the-display-menu/02_handling_events_in_the_menu/02_handling_events_in_the_menu.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/02_handling_events_in_the_menu/02_handling_events_in_the_menu.ino index 45c392b..7e200d3 100644 --- a/examples/Platform_Tutorials/lessons/02-navigatting-the-display-menu/02_handling_events_in_the_menu/02_handling_events_in_the_menu.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/02_handling_events_in_the_menu/02_handling_events_in_the_menu.ino @@ -15,8 +15,9 @@ static const char * btnm_map[] = {"Option 1", "Option 2", "\n", "Option 5", "Option 6", "\0" }; -static void eventHandler(lv_event_t * e) { +static void eventHandler(lv_event_t * e){ Braccio.lvgl_lock(); + lv_event_code_t code = lv_event_get_code(e); lv_obj_t * obj = lv_event_get_target(e); if (code == LV_EVENT_PRESSED) { @@ -26,11 +27,13 @@ static void eventHandler(lv_event_t * e) { LV_LOG_USER("%s was selected\n", txt); Serial.println(String(txt) + " was selected."); } + Braccio.lvgl_unlock(); } -void customMenu() { +void customMenu(){ Braccio.lvgl_lock(); + static lv_style_t style_bg; lv_style_init(&style_bg); lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_WHITE)); @@ -60,13 +63,17 @@ void customMenu() { lv_btnmatrix_set_one_checked(btnm1, true); lv_obj_add_event_cb(btnm1, eventHandler, LV_EVENT_ALL, NULL); - Braccio.lvgl_unlock(); + Braccio.lvgl_unlock(); + Braccio.connectJoystickTo(btnm1); } void setup() { - Braccio.begin(customMenu); + if (!Braccio.begin(customMenu)) { + if (Serial) Serial.println("Braccio.begin() failed."); + for(;;) { } + } } void loop() { diff --git a/examples/Platform_Tutorials/lessons/02-navigatting-the-display-menu/03_navigate_challenge_I/03_navigate_challenge_I.ino b/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/03_navigate_challenge_I/03_navigate_challenge_I.ino similarity index 95% rename from examples/Platform_Tutorials/lessons/02-navigatting-the-display-menu/03_navigate_challenge_I/03_navigate_challenge_I.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/03_navigate_challenge_I/03_navigate_challenge_I.ino index a531642..9891585 100644 --- a/examples/Platform_Tutorials/lessons/02-navigatting-the-display-menu/03_navigate_challenge_I/03_navigate_challenge_I.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/03_navigate_challenge_I/03_navigate_challenge_I.ino @@ -17,6 +17,7 @@ static const char * btnm_map[] = {"Option 1", "Option 2", "\n", static void eventHandler(lv_event_t * e) { Braccio.lvgl_lock(); + lv_event_code_t code = lv_event_get_code(e); lv_obj_t * obj = lv_event_get_target(e); if (code == LV_EVENT_PRESSING) { @@ -26,11 +27,13 @@ static void eventHandler(lv_event_t * e) { LV_LOG_USER("%s is pressed\n", txt); Serial.println(String(txt) + " is pressed."); } + Braccio.lvgl_unlock(); } void customMenu() { Braccio.lvgl_lock(); + static lv_style_t style_bg; lv_style_init(&style_bg); lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_LIGHT_TEAL)); @@ -60,13 +63,17 @@ void customMenu() { lv_btnmatrix_set_one_checked(btnm1, true); lv_obj_add_event_cb(btnm1, eventHandler, LV_EVENT_ALL, NULL); - Braccio.lvgl_unlock(); Braccio.connectJoystickTo(btnm1); + + Braccio.lvgl_unlock(); } void setup() { - Braccio.begin(customMenu); + if (!Braccio.begin(customMenu)) { + if (Serial) Serial.println("Braccio.begin() failed."); + for(;;) { } + } } void loop() { diff --git a/examples/Platform_Tutorials/lessons/02-navigatting-the-display-menu/04_navigate_challenge_II/04_navigate_challenge_II.ino b/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/04_navigate_challenge_II/04_navigate_challenge_II.ino similarity index 94% rename from examples/Platform_Tutorials/lessons/02-navigatting-the-display-menu/04_navigate_challenge_II/04_navigate_challenge_II.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/04_navigate_challenge_II/04_navigate_challenge_II.ino index 63358b2..10ad8f5 100644 --- a/examples/Platform_Tutorials/lessons/02-navigatting-the-display-menu/04_navigate_challenge_II/04_navigate_challenge_II.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/04_navigate_challenge_II/04_navigate_challenge_II.ino @@ -17,6 +17,7 @@ static const char * btnm_map[] = {"Option 1", "Option 2", "\n", static void eventHandler(lv_event_t * e) { Braccio.lvgl_lock(); + lv_event_code_t code = lv_event_get_code(e); lv_obj_t * obj = lv_event_get_target(e); if (code == LV_EVENT_RELEASED) { @@ -26,11 +27,13 @@ static void eventHandler(lv_event_t * e) { LV_LOG_USER("%s was released\n", txt); Serial.println(String(txt) + " was released."); } + Braccio.lvgl_unlock(); } void customMenu() { Braccio.lvgl_lock(); + static lv_style_t style_bg; lv_style_init(&style_bg); lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_LIGHT_TEAL)); @@ -60,13 +63,17 @@ void customMenu() { lv_btnmatrix_set_one_checked(btnm1, true); lv_obj_add_event_cb(btnm1, eventHandler, LV_EVENT_ALL, NULL); + Braccio.lvgl_unlock(); Braccio.connectJoystickTo(btnm1); } void setup() { - Braccio.begin(customMenu); + if (!Braccio.begin(customMenu)) { + if (Serial) Serial.println("Braccio.begin() failed."); + for(;;) { } + } } void loop() { diff --git a/examples/Platform_Tutorials/lessons/03-playing-with-the-motors/01_playing_with_the_motors/01_playing_with_the_motors.ino b/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/01_playing_with_the_motors/01_playing_with_the_motors.ino similarity index 76% rename from examples/Platform_Tutorials/lessons/03-playing-with-the-motors/01_playing_with_the_motors/01_playing_with_the_motors.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/01_playing_with_the_motors/01_playing_with_the_motors.ino index 6b7399f..07c8a1f 100644 --- a/examples/Platform_Tutorials/lessons/03-playing-with-the-motors/01_playing_with_the_motors/01_playing_with_the_motors.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/01_playing_with_the_motors/01_playing_with_the_motors.ino @@ -1,24 +1,28 @@ #include -int motorID= 0; +int motorID = 0; void setup() { - Braccio.begin(); + if (!Braccio.begin()) { + if (Serial) Serial.println("Braccio.begin() failed."); + for(;;) { } + } delay(500); - + Serial.begin(115200); - while(!Serial){} + while (!Serial) {} } void loop() { Serial.println("To start, send any key to the serial port:"); - while((Serial.available() <= 0)){}; + while ((Serial.available() <= 0)) {}; Serial.read(); // Clear the serial buffer - - for(motorID = 1; motorID <=6; motorID++){ + Serial.read(); // It is necessary to clean '\n' + + for (motorID = 1; motorID <= 6; motorID++) { Serial.println("\nMoving the motor " + String(motorID)); Serial.println("Current angle 0.0 (zero)"); - + Braccio.move(motorID).to(0.0f); delay(2000); // delay between movements diff --git a/examples/Platform_Tutorials/lessons/03-playing-with-the-motors/02_selecting_the_motor_with_the_enter_button/02_selecting_the_motor_with_the_enter_button.ino b/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/02_selecting_each_motor/02_selecting_each_motor.ino similarity index 71% rename from examples/Platform_Tutorials/lessons/03-playing-with-the-motors/02_selecting_the_motor_with_the_enter_button/02_selecting_the_motor_with_the_enter_button.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/02_selecting_each_motor/02_selecting_each_motor.ino index c3f2270..83dac2f 100644 --- a/examples/Platform_Tutorials/lessons/03-playing-with-the-motors/02_selecting_the_motor_with_the_enter_button/02_selecting_the_motor_with_the_enter_button.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/02_selecting_each_motor/02_selecting_each_motor.ino @@ -7,60 +7,63 @@ boolean movement = false; float initialAngle = 0.0; void setup() { - Braccio.begin(); + if (!Braccio.begin()) { + if (Serial) Serial.println("Braccio.begin() failed."); + for(;;) { } + } delay(500); // Waits for the Braccio initialization // Sets the initial angle for the motors - for(int i = 1; i <= 6; i++){ + for (int i = 1; i <= 6; i++) { Braccio.move(i).to(0.0f); delay(1000); // Necessary to set the motor ID correctly } - + Serial.begin(115200); - + Serial.println("Press the Enter Button to select the motor 1."); } void loop() { // Check if the control key pressed is the Enter Button - if(Braccio.getKey() == BUTTON_ENTER){ - - if(motorID <= 6){ - + if (Braccio.getKey() == BUTTON_ENTER) { + + if (motorID <= 6) { + motorID++; // Increment the ID - - if(motorID > 6){ + + if (motorID > 6) { motorID = 1; // Restart the ID to motor 1 } } - + movement = true; // Flag allows the motor to move - - while(Braccio.getKey() == BUTTON_ENTER); // Avoids more than one increment + + while (Braccio.getKey() == BUTTON_ENTER); // Avoids more than one increment Serial.println("Motor " + String(motorID) + " selected."); } - if(movement){ - - for (float angle = 0.0; angle <= 315.0; angle+=45.0){ + if (movement) { + + for (float angle = 0.0; angle <= 315.0; angle += 45.0) { Braccio.move(motorID).to(angle); - + Serial.println("Motor " + String(motorID) + " - current angle: " + String(angle)); delay(250); } delay(500); - - for (float angle = 315.0; angle >= 0.0; angle-=45.0){ + + for (float angle = 315.0; angle >= 0.0; angle -= 45.0) { Braccio.move(motorID).to(angle); - + Serial.println("Motor " + String(motorID) + " - current angle: " + String(angle)); delay(250); } - + movement = false; - + Serial.println("\n\nPress the Enter Button to select the next motor.\n\n"); } } diff --git a/examples/Platform_Tutorials/lessons/03-playing-with-the-motors/03_moving_the_motors_with_the_joystick/03_moving_the_motors_with_the_joystick.ino b/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/03_servo_motors_using_the_joystick/03_servo_motors_using_the_joystick.ino similarity index 93% rename from examples/Platform_Tutorials/lessons/03-playing-with-the-motors/03_moving_the_motors_with_the_joystick/03_moving_the_motors_with_the_joystick.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/03_servo_motors_using_the_joystick/03_servo_motors_using_the_joystick.ino index 10b5be0..a9b350a 100644 --- a/examples/Platform_Tutorials/lessons/03-playing-with-the-motors/03_moving_the_motors_with_the_joystick/03_moving_the_motors_with_the_joystick.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/03_servo_motors_using_the_joystick/03_servo_motors_using_the_joystick.ino @@ -12,7 +12,10 @@ float initialAngle = SmartServoClass::MAX_ANGLE / 2.0f; // 315 degrees / 2 = 157 float currentAngle = initialAngle; void setup() { - Braccio.begin(); // Initialize Braccio + if (!Braccio.begin()) { + if (Serial) Serial.println("Braccio.begin() failed."); + for(;;) { } + } delay(500); // Waits for the Braccio initialization diff --git a/examples/Platform_Tutorials/lessons/03-playing-with-the-motors/04_servo_motors_challenge/04_servo_motors_challenge.ino b/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/04_servo_motors_challenge/04_servo_motors_challenge.ino similarity index 95% rename from examples/Platform_Tutorials/lessons/03-playing-with-the-motors/04_servo_motors_challenge/04_servo_motors_challenge.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/04_servo_motors_challenge/04_servo_motors_challenge.ino index 04503c1..c8407f5 100644 --- a/examples/Platform_Tutorials/lessons/03-playing-with-the-motors/04_servo_motors_challenge/04_servo_motors_challenge.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/04_servo_motors_challenge/04_servo_motors_challenge.ino @@ -12,7 +12,10 @@ float initialAngle = SmartServoClass::MAX_ANGLE / 2.0f; float currentAngle = initialAngle; void setup() { - Braccio.begin(); + if (!Braccio.begin()) { + if (Serial) Serial.println("Braccio.begin() failed."); + for(;;) { } + } delay(500); // Waits for the Braccio initialization // Sets the initial angle for the motors diff --git a/examples/Platform_Tutorials/lessons/04-integration-of-previous-learnings/01_playing_with_a_joint_angle_gauge/01_playing_with_a_joint_angle_gauge.ino b/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/01_designing_a_gauge_interface/01_designing_a_gauge_interface.ino similarity index 94% rename from examples/Platform_Tutorials/lessons/04-integration-of-previous-learnings/01_playing_with_a_joint_angle_gauge/01_playing_with_a_joint_angle_gauge.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/01_designing_a_gauge_interface/01_designing_a_gauge_interface.ino index 9bdc746..6e6101b 100644 --- a/examples/Platform_Tutorials/lessons/04-integration-of-previous-learnings/01_playing_with_a_joint_angle_gauge/01_playing_with_a_joint_angle_gauge.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/01_designing_a_gauge_interface/01_designing_a_gauge_interface.ino @@ -22,16 +22,18 @@ lv_meter_indicator_t * indic; static void eventHandlerMeter(lv_event_t * e) { - /* Set the meter value */ Braccio.lvgl_lock(); + + /* Set the meter value */ lv_meter_set_indicator_end_value(meter, indic, (int32_t)angles[motorID - 1]); + Braccio.lvgl_unlock(); } -void meterScreen(void) -{ +void meterScreen(void) { Braccio.lvgl_lock(); + meter = lv_meter_create(lv_scr_act()); lv_obj_center(meter); @@ -55,14 +57,17 @@ void meterScreen(void) indic = lv_meter_add_arc(meter, scale, 10, lv_color_hex(COLOR_LIGHT_TEAL), 0); lv_obj_add_event_cb(meter, eventHandlerMeter, LV_EVENT_KEY, NULL); + Braccio.lvgl_unlock(); Braccio.connectJoystickTo(meter); } void setup() { - Braccio.begin(meterScreen); - + if (!Braccio.begin(meterScreen)) { + if (Serial) Serial.println("Braccio.begin() failed."); + for(;;) { } + } delay(500); // Waits for the Braccio initialization // Sets the initial angle for the motors diff --git a/examples/Platform_Tutorials/lessons/04-integration-of-previous-learnings/02_selecting_the_motor_in_the_LCD_menu/02_selecting_the_motor_in_the_LCD_menu.ino b/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/02_completing_the_screen_ui/02_completing_the_screen_ui.ino similarity index 95% rename from examples/Platform_Tutorials/lessons/04-integration-of-previous-learnings/02_selecting_the_motor_in_the_LCD_menu/02_selecting_the_motor_in_the_LCD_menu.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/02_completing_the_screen_ui/02_completing_the_screen_ui.ino index a682875..2223e02 100644 --- a/examples/Platform_Tutorials/lessons/04-integration-of-previous-learnings/02_selecting_the_motor_in_the_LCD_menu/02_selecting_the_motor_in_the_LCD_menu.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/02_completing_the_screen_ui/02_completing_the_screen_ui.ino @@ -33,6 +33,8 @@ lv_meter_indicator_t * indic; // Indication of selected motor angle // Event Handlers static void eventHandlerMeter(lv_event_t * e) { + Braccio.lvgl_lock(); + uint32_t pressed_key = Braccio.getKey(); if (pressed_key == BUTTON_ENTER) { @@ -43,9 +45,13 @@ static void eventHandlerMeter(lv_event_t * e) { else { lv_meter_set_indicator_end_value(meter, indic, (int32_t)angles[motorID - 1]); } + + Braccio.lvgl_unlock(); } static void eventHandlerMenu(lv_event_t * e) { + Braccio.lvgl_lock(); + lv_obj_t * obj = lv_event_get_target(e); uint32_t id = lv_btnmatrix_get_selected_btn(obj); @@ -53,12 +59,14 @@ static void eventHandlerMenu(lv_event_t * e) { currentAngle = angles[motorID - 1]; meterScreen(); // Load meter screen lv_obj_del(btnm); // Delete the object + + Braccio.lvgl_unlock(); } // Screens functions -void meterScreen(void) -{ +void meterScreen(void) { Braccio.lvgl_lock(); + meter = lv_meter_create(lv_scr_act()); lv_obj_center(meter); @@ -84,6 +92,7 @@ void meterScreen(void) lv_obj_add_event_cb(meter, eventHandlerMeter, LV_EVENT_KEY, NULL); lv_meter_set_indicator_end_value(meter, indic, (int32_t)angles[motorID - 1]); + Braccio.lvgl_unlock(); Braccio.connectJoystickTo(meter); @@ -91,6 +100,7 @@ void meterScreen(void) void motorMenu() { Braccio.lvgl_lock(); + static lv_style_t style_bg; lv_style_init(&style_bg); lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_WHITE)); @@ -119,14 +129,17 @@ void motorMenu() { lv_btnmatrix_set_one_checked(btnm, true); lv_obj_add_event_cb(btnm, eventHandlerMenu, LV_EVENT_PRESSED, NULL); + Braccio.lvgl_unlock(); Braccio.connectJoystickTo(btnm); } void setup() { - Braccio.begin(motorMenu); - + if (!Braccio.begin(motorMenu)) { + if (Serial) Serial.println("Braccio.begin() failed."); + for(;;) { } + } delay(5000); // Waits for the Braccio initialization // Sets the initial angle for the motors diff --git a/examples/Platform_Tutorials/lessons/04-integration-of-previous-learnings/03_learnings_challenge_I/03_learnings_challenge_I.ino b/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/03_learnings_challenge_I/03_learnings_challenge_I.ino similarity index 94% rename from examples/Platform_Tutorials/lessons/04-integration-of-previous-learnings/03_learnings_challenge_I/03_learnings_challenge_I.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/03_learnings_challenge_I/03_learnings_challenge_I.ino index c09064b..f36e9cc 100644 --- a/examples/Platform_Tutorials/lessons/04-integration-of-previous-learnings/03_learnings_challenge_I/03_learnings_challenge_I.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/03_learnings_challenge_I/03_learnings_challenge_I.ino @@ -17,7 +17,7 @@ // Variables int motorID = 0; // Selected motor ID -float initialAngle = 0.0; +float initialAngle = SmartServoClass::MAX_ANGLE / 2.0f; float currentAngle = initialAngle; // Selected motor current angle float angles[6]; // All motors current angles @@ -33,6 +33,8 @@ lv_meter_indicator_t * indic; // Indication of selected motor angle // Event Handlers static void eventHandlerMeter(lv_event_t * e) { + Braccio.lvgl_lock(); + uint32_t pressed_key = Braccio.getKey(); if (pressed_key == BUTTON_ENTER) { @@ -43,9 +45,13 @@ static void eventHandlerMeter(lv_event_t * e) { else { lv_meter_set_indicator_end_value(meter, indic, (int32_t)angles[motorID - 1]); } + + Braccio.lvgl_unlock(); } static void eventHandlerMenu(lv_event_t * e) { + Braccio.lvgl_lock(); + lv_obj_t * obj = lv_event_get_target(e); uint32_t id = lv_btnmatrix_get_selected_btn(obj); @@ -53,12 +59,14 @@ static void eventHandlerMenu(lv_event_t * e) { currentAngle = angles[motorID - 1]; meterScreen(); lv_obj_del(btnm); + + Braccio.lvgl_unlock(); } // Screens functions -void meterScreen(void) -{ +void meterScreen(void) { Braccio.lvgl_lock(); + meter = lv_meter_create(lv_scr_act()); lv_obj_center(meter); @@ -84,6 +92,7 @@ void meterScreen(void) lv_obj_add_event_cb(meter, eventHandlerMeter, LV_EVENT_KEY, NULL); lv_meter_set_indicator_end_value(meter, indic, (int32_t)angles[motorID - 1]); + Braccio.lvgl_unlock(); Braccio.connectJoystickTo(meter); @@ -91,6 +100,7 @@ void meterScreen(void) void motorMenu() { Braccio.lvgl_lock(); + static lv_style_t style_bg; lv_style_init(&style_bg); lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_WHITE)); @@ -119,14 +129,17 @@ void motorMenu() { lv_btnmatrix_set_one_checked(btnm, true); lv_obj_add_event_cb(btnm, eventHandlerMenu, LV_EVENT_PRESSED, NULL); + Braccio.lvgl_unlock(); Braccio.connectJoystickTo(btnm); } void setup() { - Braccio.begin(motorMenu); - + if (!Braccio.begin(motorMenu)) { + if (Serial) Serial.println("Braccio.begin() failed."); + for(;;) { } + } delay(500); // Waits for the Braccio initialization // Sets the initial angle for the motors diff --git a/examples/Platform_Tutorials/lessons/04-integration-of-previous-learnings/04_learnings_challenge_II/04_learnings_challenge_II.ino b/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/04_learnings_challenge_II/04_learnings_challenge_II.ino similarity index 94% rename from examples/Platform_Tutorials/lessons/04-integration-of-previous-learnings/04_learnings_challenge_II/04_learnings_challenge_II.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/04_learnings_challenge_II/04_learnings_challenge_II.ino index ade5d8c..3b22970 100644 --- a/examples/Platform_Tutorials/lessons/04-integration-of-previous-learnings/04_learnings_challenge_II/04_learnings_challenge_II.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/04_learnings_challenge_II/04_learnings_challenge_II.ino @@ -17,7 +17,7 @@ // Variables int motorID = 0; // Selected motor ID -float initialAngle = 0.0; +float initialAngle = SmartServoClass::MAX_ANGLE / 2.0f; float currentAngle = initialAngle; // Selected motor current angle float angles[6]; // All motors current angles @@ -33,6 +33,8 @@ lv_meter_indicator_t * indic; // Indication of selected motor angle // Event Handlers static void eventHandlerMeter(lv_event_t * e) { + Braccio.lvgl_lock(); + uint32_t pressed_key = Braccio.getKey(); if (pressed_key == BUTTON_ENTER) { @@ -43,9 +45,13 @@ static void eventHandlerMeter(lv_event_t * e) { else { lv_meter_set_indicator_end_value(meter, indic, (int32_t)angles[motorID - 1]); } + + Braccio.lvgl_unlock(); } static void eventHandlerMenu(lv_event_t * e) { + Braccio.lvgl_lock(); + lv_obj_t * obj = lv_event_get_target(e); uint32_t id = lv_btnmatrix_get_selected_btn(obj); @@ -53,12 +59,14 @@ static void eventHandlerMenu(lv_event_t * e) { currentAngle = angles[motorID - 1]; meterScreen(); lv_obj_del(btnm); + + Braccio.lvgl_unlock(); } // Screens functions -void meterScreen(void) -{ +void meterScreen(void) { Braccio.lvgl_lock(); + meter = lv_meter_create(lv_scr_act()); lv_obj_center(meter); @@ -84,6 +92,7 @@ void meterScreen(void) lv_obj_add_event_cb(meter, eventHandlerMeter, LV_EVENT_KEY, NULL); lv_meter_set_indicator_end_value(meter, indic, (int32_t)angles[motorID - 1]); + Braccio.lvgl_unlock(); Braccio.connectJoystickTo(meter); @@ -91,6 +100,7 @@ void meterScreen(void) void motorMenu() { Braccio.lvgl_lock(); + static lv_style_t style_bg; lv_style_init(&style_bg); lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_WHITE)); @@ -119,14 +129,17 @@ void motorMenu() { lv_btnmatrix_set_one_checked(btnm, true); lv_obj_add_event_cb(btnm, eventHandlerMenu, LV_EVENT_PRESSED, NULL); + Braccio.lvgl_unlock(); Braccio.connectJoystickTo(btnm); } void setup() { - Braccio.begin(motorMenu); - + if (!Braccio.begin(motorMenu)) { + if (Serial) Serial.println("Braccio.begin() failed."); + for(;;) { } + } delay(500); // Waits for the Braccio initialization // Sets the initial angle for the motors From 196949d7801880f36790110ea9da38675b027974 Mon Sep 17 00:00:00 2001 From: Esquirio Date: Wed, 31 Aug 2022 11:35:24 +0200 Subject: [PATCH 28/41] fix: old lessons codes --- .../01_creating_a_button.ino | 9 +- .../01_creating_a_button/sketch.json | 7 ++ .../02_designing_the_button.ino} | 85 +++++++-------- .../btn_style.ino.NANO_RP2040_CONNECT.bin | Bin 0 -> 345140 bytes .../02_designing_the_button/sketch.json | 6 ++ .../03_creating_a_menu.ino} | 101 +++++++++--------- .../04_testing_it_out.ino} | 101 +++++++++--------- .../05_display_challenge.ino | 7 +- .../01_playing_with_the_Joystick.ino | 4 +- .../02_handling_events_in_the_menu.ino | 15 +-- .../03_navigate_challenge_I.ino | 11 +- .../04_navigate_challenge_II.ino | 9 +- .../01_playing_with_the_motors.ino | 20 ++-- ...cting_the_motor_with_the_enter_button.ino} | 47 ++++---- ...3_moving_the_motors_with_the_joystick.ino} | 5 +- .../04_servo_motors_challenge.ino | 5 +- .../01_playing_with_a_joint_angle_gauge.ino} | 15 +-- ...2_selecting_the_motor_in_the_LCD_menu.ino} | 21 +--- .../03_learnings_challenge_I.ino | 23 +--- .../04_learnings_challenge_II.ino | 23 +--- 20 files changed, 213 insertions(+), 301 deletions(-) create mode 100644 examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/01_creating_a_button/sketch.json rename examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/{02_styling_the_button/02_styling_the_button.ino => 02_designing_the_button/02_designing_the_button.ino} (84%) create mode 100755 examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/02_designing_the_button/btn_style.ino.NANO_RP2040_CONNECT.bin create mode 100644 examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/02_designing_the_button/sketch.json rename examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/{03_designing_a_menu/03_designing_a_menu.ino => 03_creating_a_menu/03_creating_a_menu.ino} (91%) rename examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/{04_adding_an_extra_button/04_adding_an_extra_button.ino => 04_testing_it_out/04_testing_it_out.ino} (87%) rename examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/{02_selecting_each_motor/02_selecting_each_motor.ino => 02_selecting_the_motor_with_the_enter_button/02_selecting_the_motor_with_the_enter_button.ino} (71%) rename examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/{03_servo_motors_using_the_joystick/03_servo_motors_using_the_joystick.ino => 03_moving_the_motors_with_the_joystick/03_moving_the_motors_with_the_joystick.ino} (93%) rename examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/{01_designing_a_gauge_interface/01_designing_a_gauge_interface.ino => 01_playing_with_a_joint_angle_gauge/01_playing_with_a_joint_angle_gauge.ino} (94%) rename examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/{02_completing_the_screen_ui/02_completing_the_screen_ui.ino => 02_selecting_the_motor_in_the_LCD_menu/02_selecting_the_motor_in_the_LCD_menu.ino} (95%) diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/01_creating_a_button/01_creating_a_button.ino b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/01_creating_a_button/01_creating_a_button.ino index 7f3d00e..2ee6ed1 100644 --- a/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/01_creating_a_button/01_creating_a_button.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/01_creating_a_button/01_creating_a_button.ino @@ -1,24 +1,19 @@ -#include + #include void customMenu() { Braccio.lvgl_lock(); - lv_obj_t * btn1 = lv_btn_create(lv_scr_act()); lv_obj_set_size(btn1, 120, 75); lv_obj_t * label1 = lv_label_create(btn1); lv_label_set_text(label1, "BTN 1"); lv_obj_align(btn1, LV_ALIGN_CENTER, 0, 0); lv_obj_center(label1); - Braccio.lvgl_unlock(); } void setup() { // put your setup code here, to run once: - if (!Braccio.begin(customMenu)) { - if (Serial) Serial.println("Braccio.begin() failed."); - for(;;) { } - } + Braccio.begin(customMenu); } void loop() { diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/01_creating_a_button/sketch.json b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/01_creating_a_button/sketch.json new file mode 100644 index 0000000..45332f0 --- /dev/null +++ b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/01_creating_a_button/sketch.json @@ -0,0 +1,7 @@ +{ + "cpu": { + "fqbn": "arduino:mbed_nano:nanorp2040connect", + "name": "Arduino Nano RP2040 Connect", + "port": "serial:///dev/ttyACM0" + } +} \ No newline at end of file diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/02_styling_the_button/02_styling_the_button.ino b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/02_designing_the_button/02_designing_the_button.ino similarity index 84% rename from examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/02_styling_the_button/02_styling_the_button.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/02_designing_the_button/02_designing_the_button.ino index 9347adf..295e3eb 100644 --- a/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/02_styling_the_button/02_styling_the_button.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/02_designing_the_button/02_designing_the_button.ino @@ -1,44 +1,41 @@ -#include - -// Arduino Colors -#define COLOR_TEAL 0x00878F -#define COLOR_LIGHT_TEAL 0x62AEB2 -#define COLOR_ORANGE 0xE47128 -#define COLOR_YELLOW 0xE5AD24 -#define COLOR_WHITE 0xFFFFFF - - -void customMenu() { - Braccio.lvgl_lock(); - static lv_style_t style; - lv_style_init(&style); - lv_style_set_bg_color(&style, lv_color_hex(COLOR_WHITE)); - lv_style_set_border_color(&style, lv_color_hex(COLOR_TEAL)); - lv_style_set_border_width(&style, 5); - lv_style_set_text_color(&style, lv_color_hex(COLOR_ORANGE)); - - lv_obj_t * btn1 = lv_btn_create(lv_scr_act()); - lv_obj_set_size(btn1, 120, 75); - - lv_obj_t * label1 = lv_label_create(btn1); - lv_label_set_text(label1, "BTN 1"); - - lv_obj_align(btn1, LV_ALIGN_CENTER, 0, 0); - lv_obj_center(label1); - - lv_obj_add_style(btn1, &style, 0); - Braccio.lvgl_unlock(); -} - -void setup() { - // put your setup code here, to run once: - if (!Braccio.begin(customMenu)) { - if (Serial) Serial.println("Braccio.begin() failed."); - for(;;) { } - } -} - -void loop() { - // put your main code here, to run repeatedly: - -} +#include + +// Arduino Colors +#define COLOR_TEAL 0x00878F +#define COLOR_LIGHT_TEAL 0x62AEB2 +#define COLOR_ORANGE 0xE47128 +#define COLOR_YELLOW 0xE5AD24 +#define COLOR_WHITE 0xFFFFFF + + +void customMenu() { + Braccio.lvgl_lock(); + static lv_style_t style; + lv_style_init(&style); + lv_style_set_bg_color(&style, lv_color_hex(COLOR_WHITE)); + lv_style_set_border_color(&style, lv_color_hex(COLOR_TEAL)); + lv_style_set_border_width(&style, 5); + lv_style_set_text_color(&style, lv_color_hex(COLOR_ORANGE)); + + lv_obj_t * btn1 = lv_btn_create(lv_scr_act()); + lv_obj_set_size(btn1, 120, 75); + + lv_obj_t * label1 = lv_label_create(btn1); + lv_label_set_text(label1, "BTN 1"); + + lv_obj_align(btn1, LV_ALIGN_CENTER, 0, 0); + lv_obj_center(label1); + + lv_obj_add_style(btn1, &style, 0); + Braccio.lvgl_unlock(); +} + +void setup() { + // put your setup code here, to run once: + Braccio.begin(customMenu); +} + +void loop() { + // put your main code here, to run repeatedly: + +} diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/02_designing_the_button/btn_style.ino.NANO_RP2040_CONNECT.bin b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/02_designing_the_button/btn_style.ino.NANO_RP2040_CONNECT.bin new file mode 100755 index 0000000000000000000000000000000000000000..00d92a93265760362103ada747d8b42903bd1c1d GIT binary patch literal 345140 zcmd?Sd3Y36);N5ss<(7^l1{?XOO{?pNYVsCny@4yovKjT09jnX044;bfe{*=(I7K# z0*EH!0%_2sTM!lfp}1f)4lZa$+)!t%CNcvFI31Ssj1FTts0k$9{heFgVHthjcYe?F zJYhfn9;y6ZXjo_n@?s)UY$DvNnxO{q#i)uAu^Q@K$OZw*lFL&nR5i?}jTcl+sxqddZI#SS zv4aAIe+T@`A-Y3C z&`rf>vl-V-@##ifH(gnJIk+G@&#&E^@CD@10*JbSi$Oz$u@cM>p#HF(9rEidn##xz z-U|h(Bh&|8cCgD`cHJbot`orgk`Bz1O65ATR^%t;b(kkV{O2xHmroNv3q#p=7vznd z?d~#w*jft*v9EarW&R@#y1WgH?v|SY20A+Vfp=B!?&jTPB(LjG%(B&kUFnxsft?m) z<+xApQ#PAhcj(~92qpfzAN$LybRA%41g0X|LU*W>Cw1>)8&W?CdxL*O)h^y?ZK1u! z79K2H`9waYd_-lku~W<4i(N4#dYL$jBXew2jWBKck`X9ab4eCh-=)qlAab<4>>u0sw45!gJs%xnGbgJ z=~ar)x3lSjs@PZqIdKAMX`b3tCw7+dv-z9(+jy~a+iG3D_~{=01-_kshi|+P*JPe5 zeoC7=IkKv%Mt{&<7GIg-YGW@Qr#hNp!NMo`#7_e_gRX|GBh^tL4u+X`ALTy@lKksZ z{tv-}GBCfJDA(z1vVhq}2l8zYaN3^a#W!TH{D%LViXw17kZ?odpAtVwd^hnECttzO z=d1a|PtyK05uR5=mu%viI5=89G2;^g_e%b|3nLz=`=o}aDkh8SNNE7fRJqJTRq4w* z6=44UDMm-Xv5v1$RY2U$74T>&{jR&LlfPWH_(~ZgwQ~ZtTuMqAY`NKFmwx^}`QhuwH=cIg_JIA zr2JMX&q?_zDNi8B9#Z}=;)3l#YA@xtN_m1K)m0_sON?-o;^&v>aAza9pGc>oI6xD6 z&*>NLL0VvV4cGA1|G!seN#L_Y5Gq(agu?XNbvm9x_>l7)t6<$_b$qo1Z**7XxT}ye zAdJF2CFewNYEu2qCwX&Gms8KpXX|(mrtY%sP9}AmRPJ#ar1CCI-DUUly3}R-!@ME2 zj)y=epV2{yTLvJT`U)(cvKfbvV~VFDPL|5oVV)B2C3QVu)*YhoM|dwK-bu<%U0nuZ zB!XopuPytLlyzSzOSMooldKh~7PPu)Cbg7PtEQRaq+FbA8vTrJu~Sd*k})(*;XlGJ z$-fd-<@^u(8%cjtYFb)4{>zB{1N%rnk;Mc6;e$?HJi!L$zU%-VEAzxAASfNcPM|V2SkqD#E4ef$WpmaRblu zf95+oWU%Q#JZ$G%`K|1PJHWeLHpl@L1imn!r!G*a~o85@CkwaEaiWO)gIq#+*LxE#~AJ` z0Sk5g82#)L7_Siav;RDSPo#AGfS-)MfCs}$gwEDuhxvS$GZ&Wgr=6*=fFB89&+Ey8 zTln{!4#k+n|M$B(|ji!geO1DfT}pd4yS5+&DLpf)VSN}cRuAz z;C8WaYF_UW)9O@G``cc#<%n@QV)2->$$84TKK-$hiJ-J*b0?gTspN{BkQ*l?+KQbr zyId$vdxw3$q=7wR$N(~H*6CHLA6MNZzcb#;f?v`5VP!<6b}mrPr;E8{&7%RLZygM* zPOX+#$5VDVnID7w&63ZJ_prN74jPWl>Ln}uv>$h33}m`VpOfbT1e48ySLbxFH9}+7 zWZ4w%AU_pruJ7ge6fOhqOMjwdhWRWMZHzZPL-Z(v>j2I7z3*kX7cA%X{^l8@q%iRQpM!}n|K5oW+!o-P^J7# z_1lV06~jHkx`brrPIk$60MGP2W?}%1_{?a-)rJvn?eYKc8(g zF6Rs3vp%Jj&;tlR^%0E9D|73RRIa4L-ox@+;08 zCpwFq@Ah2}*;5~I!q}(!rXqF!VaS~SXx|k|_{2oc133%zeF;zu3J&)uuhvh_%Ma4N znR=J=(?AE)g2o%(Veb{zrX`ZNUcIscNBd%otfUYvINQVZ7E)DDU$?6oY$b|E2F9#6gcZ z{H71=BZO-yQ7H_mQjreVD+QH`>*Xylizk#w=+HI$t-dsAS33J3ui76Ea@@DmeM^u= z4g_jvzrtn+ghJMxBzQg^FlQ#hdE={yrxIR7JZJOMxe0I+zYpnUX8OL8rcx#MzWxcM zl6h=NX(1H#5jr7MxTQ}64DJC4bqM2+LiE(!*B7N-r8P>uMNV>ZkM(hQat+QS=cdBS zzW@Cs(tVQ=($9p(%sgD99Pas`iYrNPDtR7f0)Kg5ls{hKF;&N+``Ci}IG=4cDy_@; zB4^7vic18-?{)=KArZ{i1*5bu=8Un;869yd_uD?gmoodV9f4rUog;XTn62w;#1_d+ zBd#otGW|P=hagR5ek+ZmL=IA){vdLYmB9ybt$ZaVrPb^aeIY!1j&Qy|2}xp{m=ViLEN-&ippbxLTfEB)LEmZJb3JJdP7eByXGA@9Af>P_%1dJ3&XG85tN zv`v)-V__TZ`7HQ3Uj%d;wUhFBc{*pTz@TQ;c$&&774ED6-@|-eX)3_DsizhwK}b1$ zR8`IQP;ti=@hhqf&aHf-Pc34vYKBmzfD<9kLFC8W$|E#Q|!k8-&xm9v2Sz;!VlWj|^ulyyFf+Nz02ke7Q2SAwx8 zgHa5Y3PjdCBuUMkml)6#ry}id=uNYB8E@q&=ys~6J?cz>+a!D+bIz!OER&I}E$x{f zEa4ZREmmCNBP)h*gQps`pkhC518X`*TWW)Z@_qaiJOP9{m-RaNNPq3+c^352cwSUR z+nr5(8gij|{0XN9OElPL0cv7K0AFUslYC7ngDWHLsbxx#vAxE_HfK?w(#$++A4S=vGCjn7V(%0Uk5ati5U$h z%`-ezITv*uLW9&$B=SYFOc!AY4~vAu5-&?^jK^|nAQHKNgP$QnGrM5@<_Y73>ET@rKv~n?V8PZh(z^Ij7LI=($djdU`+1IUHnM!SHd&UY zt>#B)t#}4Z+FLnh$7-&Wqj$PElVPOxTm6$n`yR8L-ixc4svRjap}ua`FEMOn@9nx< z&>Ekq{GI7l)N6L&4mPlLr2$haJb>%d6Clvcj6t2FRbGL5#xT?mUWR%iLS4x>^EtBF zF{pEfaYU%2IBv$)Gi1%iB4C~}a!9oZ??P@PPq&WLuH`sxCWou2y`S$f)RjI(pf)?{ z`}x~T%lQlx<|Y|ve`nC^Utr^5!imCQ z6@OB>P_+TiLqs_#2xDGln~#>2md)H-f~ShzYgn$Qil1lGkM3dbJP!Uh17nOnzCOsn zt$cQ|7iH~szNv2^Qmgu+IsdLc2DNcg?%~1uM&Dd44-c60y?xKKr~L1lC&ImsRGc31ZAFYYV2Blz(@i0A9^P8PUj$l>9DaV3s zv=cG1fGx>60%SQm{Z=4c%cMD~8jYv$`E!l7MYu=9=S)$#>)au>{kV^ZG4J;^&U~xO z2#3kJBWDfIS-K41di)LBefOi~*T@^@=$S-jHh^X^Y~p9226-fLJHI@>Cy_FDuxjBA zmJyyqYwMPoTH%WBcn9hx{r;EOAN@D-Be;M0Df6c@zw@`TN&)h|_1EzkNQY(V2TRTc z!F(om_J`-44V@hc%#p;0_;D2(%wlNdC*!Q!ac(l}Bk0w9m>q@Vr2F%^`*|2g`HMK4 zu#AUXqu`yHBh2GzGc`@+q^4ehXBuiE=LFj9WPb?ebC(dZL;=PnV$YzU4Nz99*u&|8 z%0CxGd(sT{UZE#g#P#{TGymd$jy-nrIac2D9_v4@LYx0R_UO^MJY}P%wsKVd7r{?w zesmlVzaP3j4w7~JIUeJG5f44$k%V~YV|b(^G^w~YWd8iCu*eM%=)XbeGXweDAi|!7 zuxDZGG5#yKjt-C&NW>NBMTiNsr;ZyWXw_FiE4vEUE2~q)35e-O*zfSk0OHdr;d7?z zd<>tfbpiz>qE7H2>I7*p19gHgB%NSw;A_+g(8{qzkRN7ncPAEel&8B2#-g;g`S_n; zW2v24iQIlZdJ!t(&nFV^$CiLl)rLIp?f}PkLnC^2Qn>m27v=L4???GHA6KHb^e8l! zT41FUwm-~MmWtAc_{0ftVq4(Diud8mMen0VKxP7ARWE7;Vwc*gY-ISg5lIfKcKpP_lZJXv1E(N2>bwRdkd_|Xp1aQR>WRWC^Z*O-PKD0hvRN_w(@B?bwdDy?fu%a}i-^VZE^9;|idrLe- z2JweWPnJH0vbPoauxDmV$zCFz*akL(o2;GBE@$62Skb~*#!uCA^wD^xErnY}t0lf$ z%b$t@@+zAT4dObj8%~cgRY3^%f0avZE&bqM_#w|NFk4PG`&MC{53%ayzC_Cn} zK0OU5DA}>bF^2N9z&LL#)tBFoUXiiErO307sxmZn@=;uMd^>97Z9M8$xQ9M|c^_k= zp4iB1$NKoCeaNRITDb>H8FL25@$34o=uO%b)SJ-eBf8Sn`V-h1$AV`D16f?v=03_- z0DE!Y-F+|dYx)|;Qf)JsX>6WQ%-a1K+ze)h26m2usa0$GsLVXm)I7A?`!e#JCkx9{ zVQ%Rtl&kkU|0zk{C<_sb3Nnjt1``{7ho#Diay=&Rv#6Fk z`xYXtCx^`Ww_KL@DQGWxP~M086bDHxQAsN^D*_bpe;FPF| zjv~^~3^pB+hS_hSG$bpVfzl8?SvCbiF$}{ffU2-$^9;+p0knIF)$=t^JZ1s(nDL3X z!9*?{J!bc)Q7c9Z=hHd2Lnm4@N8!%+XZVeLL;REcHvad>zupQ|^HkQ|P9OhI)3Y;) z4++NCokBh#ycVdFJU6!9yVJ>ef4lbqV;z6s-~4E0=trwkx1w%IwDo4`>_0R#>`Oy$ znKd7MX(i~XZ*$VH+o_iPX{#>#({`XgO$UW=#Q3PQTk@!_OMkQ^N%E*crh+So`O_Sd zKh2T$I(irGL7gOB@~2Hlf7%in+`}`xr2NL@}Y>a7`=!l^sL?1JB9Pc{A%k--;}ab8EV%Bwhc&RerVi0(ZvzYDWXBEAN*4Y6;Htm|ra&G1?hSCmu>+ zX3!a2h9ehUJMyV-0~t7eQLh6%w&vo$I*Y+PUM@JtzHhpNcyN&i@%&xskC!;OZpl|O z;&gPUT)mC9Ip}309ySF>d~7v%*Q!U~MjhH^M^#Ieqqqyu#vg&Z5=+s~R>gmAgx91WnbGA^tEjWUJteW zcJu*!6kN;`A4hM1csni#ccUNWrCv+bQ#gB3?*+-%wpQ}BJ=|-~Oh8}CE6xMF0(~i8 zJ7@BR+<5e*oN(@Q*73xfQjMPbd~TGn9k~?V9ii84I=q2iFhVmRobA(8{iM2#ov*2jFQ)lp4}Yvx{ci;=?lZYCqg&G1Gh9rH)7z^fAhdCi+SMwgdVu@=z%Lh z58MlV@1y@M$w?r1wyyv^aGRWv^#JF4&cC~Fm|{LQl5<4-Z;R3Ywt`o1C`a>_ zO8&PC63wOeqCJ3XHZJ(W4ezlVgmn16Pj`*~&FdV+-JQN0{cqAKLI2z4;3zzy?Ktux z^mA*Bt!Pse^dT*s+8;2FeaGbG>-byvcbskL?Z1J)fWF>hyc>Aic}x1+B`Mr8{$J>W zYwi0FTN*sfgZR;e#uMb|8pOqoc6#n zgdklYbhB3Sz&(K;xL>B4VGrEHr3&s%{o|4cuC{bKWcE#$XtVyZ|LrF9iv5U?5n8#k z?`nDmEAhSweZ1s-Yd`lIzohSfKcnBBn}$$+etDht#k_CN;EI6%I;4pQj9(%>_)v}y z;+~o4Ime>=IP8DJGh^L=-nRrGyz!}E8YH0K?4NitB;R|?Z?+L{wm6>n_4M4YB`@6Q zzH7%pY|jyz8abPa`QX;$+Wzubb8sv&TROKQ_yDe#ucTJ;!cB*V&z130BrjYEU*N3h zgRw=>cP=W+$@y`2Xy?Q;sZ0e_L!PE0evGC%{x#fdMFp6*vW$NOX9nUkcOQ~-lo|3a z`M;OWUVg`j*=nW=lCk}fL>RN5O**BU^(?D9iM|NN$|cM?Ys?s@Jr!Sm*hp;R#Vpao zQ_h5k}7Zg#-=68e0+Sj%w#MB5CNTu4K^(1E`c{GoQyaDFg?Fk+04aCr1b z`X$Z}6SMJr=3g9HWipa`7j^c?Q<|w;oM6pk@-%?bDUVUd=V_AVxm^5glROvi!>-&p zxDU|?#>j&0PBmyOD&t2^((4R*4^UUn1nbv9BBzONqwA2RXA0r|!GRH%XG+GI?#G$N zFk_^d#^6k2a3(9Kon?|+rI{9~bU26QsyRM%lJOJeTQ9n{0_W7C7z7WBb!lICii9^N2+;~bc2ev`LW*w=AnMJ5j}GA_!>;r z@D5vhe5pXjSj3YXOx1o3gOIf6QPqcWK>u)LnyFz%C+=doQrS|A;D0&m6+tBGfz+-TatO>&MFg!U8d zPNPLZaXSCD_BN82QJmVZqYX5uI=nfLxj%r^8xUj!31&N08>R<0&|(F0M>5A+I?6Tt=C$oiK&-Jgh%?AG2-SS zGg!st_;-T1Yv8A#*b$HS1{ev^BC~zA6l`BERoK2*`WF+8Pl$2)2*3M~3vv8MvRtoDL(KIL*FAU^}o*@QD$Q8MZV77{*2LF&4r?1eNA+B8|W*{AC zD{{r(4}h(}8i#bE5?>g!ilIw#@z}s9F&L47ykeC2T?A|+tV*fA4fnC^*D~F&7s_-` z+jJd1G`l+&cD7Ft-y1;7D|@`~jLioDsib27?*_6nh377pyfnaINviPd<&tLyWLT0S z?7dv#9gt&*T6q3)$@T%3om--?Ia$U@qC|8ZN#$DPVDCqCl}x%`pe)qXr|*_$%a4cp zXAG&e2|7lVY)h$0an;oz2ew@djk`KbKD^rdo zSM}-hv2AfA>2llGBKeRQYr9lx`%+jdwJQ`eao;WZk$jo>w~P5mInxH;2o9eyLWkRP zK<8u=Vea85Ee>=jP}U$Vz}J(fxc5#nyBP7n#cWVxw8dBX)5LQFkDHx{-(SO6<1(#m zEj!54=zSe89=%*b_SjKxcE#Bfk29`nY~!fEHT7HlSB?U=-aXt8vitm}gJk^Xivx!S zIvCjRFw|4Urg|EBxR(l&>#L12j9LNfzDYgp^tA1)>Qq*)LKq1z7tUNl6;zvg+J6Xc z)W1AYEu+LWirk}e5YFuP}?ZqS%(Ru zbHU#ffJ_R#2Sbk3RfFxcXS}#Hd`Iejh)mYcBkQ&0(s=Qv@aj|_tm5_aY><54iw>ik zw%+QdtY+}KBmK`r#*3xl{n$c3&x~}l6rZmPTi{!%bPMBApTz^OUo9&DT z>;(eh-r30UdLxvTo-`5jd)sNTJ3>u~AJ^xnTMNbPOP9=zxWnIsRtLw6e+do4k$TAr zdkRuqlq03a22VOnE)utl;x<3he`9#O_(6!kNZG2{mx5GmmRBN-_w!)nM}X`Yugk%- zzeBXzXC)yg12H9J18VG9M}}L4_Zr~Is-TLq${BIWK#TdHbCP%@B1gWs%{o=w7qJ6m zWmIl+xKeMe{kkT-HiDe-<%>3qR2p&^%hQ(0#Qz$wSq$a0xHPiI##nvOH&^C3J@=^L z%3qm-DLRd%+Je(_6U(DD$X_qUmlui;;@^ql*CEQPt(woCo~x9V4Hz$~f@MkUoGdWXt=7KJt2D6AV;fVuB$`#vXV#i>w<&*LXI#2xV z0BzCXIdO$3+lMzyuYdnS^?B&-k3*zpS?KM` zcPjERH#P*BZ&lh+$w}U)ZHeC*>3<`X`~snosh5(GL%cThdaPF6qQTndLOSy#F*`CI zPxHq$k^ZNLM*6<3LC>a8?Mi+j8(PaC%MOh7c@z@k#PSFk4pIP^rhOw12GUUf#V z2N_c1*@35!&z;i~syiMcfBz8rQ?^V1o7^LB9gPw<8z>7c7KL_SZr2!=Z-eaf!fWkd z#oEcVxFeh}zTZ!@kCE8+k??TtcTz3|%Qj<a+ScX*I zG4Qk`b7)Iv`*?BpP*jpdpPm?s%B<+qwxOuJias?DMI~JHY12?taz&pu3@OAfBk!9( zwY*_#giL)i)anWR)%e26>*4={^AX-{5w~LghDslto_j;(2&7L{@i{!{7V*{a?_(=q z5g&>C-bNz@pT4oIl2C6p)_Wo|@g0`HTyk#eLNb)mAih5YQo1=JO6P~1DoUgWi!02C z>;6mSwxZdTXRZT0*IB1ljl;I|P7qH(66Hos6L7Dh; zctTZRF4AvUfl-oU@%@76JU2vgapdvhErZFkr=pqgMwU$c-Nk#L-4=12Sxnn`LDo7+ z{3eovR3Q`H7qc-6gwRLTkQ%9@bCA^bM}k4ZDW4wvDro)$%#8w=1wWXd?7?$|=V#{w zjP7^iK=&NVrYcN{j3Tm1Hx?287|cXx67j!tSpG*l=*Hml{kO?ejLY>^Q-WG}vp|=a|nL8>hM|XvS3l zx2?L>cCgG2c{jZ1$Y_*#Xote1@Y<`gA*Im{uQ-gL#0b?ClqJ6%l6kYLMmH+Fq>i#F zy+ehh+&whjZA020a+p?S+<@H9P1%MyNa~!OY?O!C{|zs~L%J>zY@CCdO0C30`1_ZT){thkqzpCng%(_soIkg^`d=LyK) zrec)RM7SRAH7cGcGYyW8=x=i>pSah!K}U^cJn|>@vGhp_Z)fG(WZS{EZ04*}GVkMT zW)IV<^iqyZMy4hCnAJtuQ~W6_%|r`_L|+aZER*{f?|Hq(ZkPwaL6xfvn}P z!NgYBb`;x=#E4DI~U9U9j!XD@mCd4wR8YiL$cZSCHZc`z*f~WjNT&{h5`N z1K$O*q=4X3;oC|w>j_s9n=iDvE(Hl>wyPjZk|0ZtL6(b<{r7MMB)F1S5x8;@s&5dg zcVkeET9pfL1gSA)!d;Fz1$@YOx#`){hU}jv4oL|}uPK@uS z^c+paPM^JIBMaSc2V85D^{zFWF#kqiA1UiO5cnH;?s+LN z0rsVR+~A#ZkN)pzM;dON^^hJ~is~U(FVHU*yBSByx)j{=8!B#H$9U(I(bHIEAGtEI<>nfC;txT3j2wF_x{kZdSf*;CC$`r76wE(F`m3unl_s=- zeUwk%Xq_)JAk_}}bv8xCXVRV|T4cBffiRix#;?(i2AE6w(degYEYNkNxEHvY72FEu z4(<-dC4*|@n>N>;J4~z1sE^oOfjg>WxjieQWq}pM{_5|5Oc@kb&8$&5m>Mose%H*q zPTjjX?bN-8(=gKa-W;G>8>eW^G;VbG0MgH@kPbkGV&!yLsK?>yE9fyZzbQ zZJ2tYHGZCvt_NhpAL)G2z}Mhp(o+M9U~F zQ%QZ+V;=(u){S`D=GFQp7vT9c_;c~^D8K!Gph-qtj4)iGN!7s5Y4ShEi>y4^mx6!8 z>&+0sYwTsb7Svvg*YlyD)ei!hdn&fa@#e)UY+nKU}bi4mri z0+o|1JeWPkKgr_1H{05MuS#lrYozX1XO=(vE8FdAbDn5Idh|*1x6)6zNEup#l*9fr z$udEbEPx}OxVJm_V7A7ejrl?x)g_HOA@VGaTKB82V6@EzY$Nv<#%BK1@&~DWu5~~v zCw(Vj-+h)qa4zNn%L#utZep4zR3aO=Zd3ckQ)`Sm8sTd+!c%*+}I3T4rhKr>1Z0IH_orQDfiSglf>FGpB zE2SmjXgWO{?L95*kje{V>BR8wrRP6{3Z*nB{En2q70Q-UOSn@?UyF@r2!9|wzYwCN zG%1Y!ErcpQd{|0%g>+IX4}U17J40qE4TV0I(nmsxQu<>^kkT!oy;6EU^t6=zJru=m zeXPDWhV?15G08k9LQzfNSZtO2F*yGiDv;`rgi59KqYx{le+Vh0^iU{4O5X}4OKC@F zgp|G(8ZD(ShkB)SdTie3V)H&7n|D`i-nQ7hJ7e>14^5Q%JrcT6N}EGvQo1EJ-^Ng? z^!&TnJnKUy>G?OIbSYgIvPdZv%9YZPWYb0ZZ;#Di8%vjj&Pnx)LUt+rd#v5OSpDqS zepG~JNcA&Agz{|?UoiVszsMI<676^LL~kHxlAKR!tlFG`Cwbjal!kAs9g8O+Ekr2y zuS5S%{gxQ@r%Tj7LgKhL#(EN&WJKyeekn(SXxk7O8Ke`1IBltEWSq`XEi7dy5dP?tMxrP#zQ?3*P`@MUJq+N1(~#OKRfDFqebEUR(I6UwK&e3>r5&!V8pE) z+n{fgSUm-{Dw#4UXcV<{BLPJBnu&-%xt{ z{kPwrcCJC0zeayvf4Jc~ga}$xUZ0-w=xmo_762or4_?u9l$JcCwx=)V+TOX!0$@b# z|1ONA(KNZnUmsr`ff%ZwKC~GoHh1(5vQUd>$+x=v7!Wuz{o3_zd`bQtai{Fs)DW zgJ9Cv&4iPG>!oauvq?S68WgSbIDAim)tqA5YGJ zztL-Idx%|y?{K;>_RU+6gkOaiC8W3+Yx4fjDvaxHTbJTJQl5-5Flms;z z-PDVG;6udzs{zJ)cbcjITFk(BC*m27i^y$DFnaD#W%9n4_1`Qu-bgv*_Dg=SsjPG+ zx9&~!c=3y`XLE(GUE|RjG47@&?yiyN{NQhZNc#y_4wjkPsG_6oZ8eblH-yWFHwR?R z*7tfRS*6^sd#M7eJF$RR*u$1K_?Psyxh@8yqndViAw5TZ4szRSF3uzKsah0h?aT3p z{sW&J-xH1V?x^b0%e}tEc$OxxexuKXXX$!By~_?Nhti`$UxAU06J$O)o}V_o&6Nw} z^ceB|dbo|7t%0iQA2O3P2dy`_FVzB1RIgHc(?QWj?hB>ar$=W$-`-$>pV)^w>RU= z_*domJ?l8JnomVer1q@l&6sLDkd^Q_^SBOI1*z}&*1!&4{c^F5&kK4h=dube9fj!i1@Wk*e(K%+Ws^dwYv%#x%;Ej7^x@-6T3MY;K z#eKh4T0Di`fMG8VdRZ@yL{3V036Y7!<|0yW*ghGJ7K$FNNych-%k~@B(M1;Yw;-*S z%ka!jL4ON_-%_~31&O^F#&^KA$WQRTsptZ}Swl{45qjEulOp~05bWRB*$a2 zt^68je;A0$wyW1e>_|tOfOrHS#Cue*uktf%ztl5po?>tB*^Gaeb#rTv=?|~j#V+YC zS@Q@>ci(Be#}E%M5)RkB)CA+_ow9+~!Jst(c6>j<#&|O;2#<ylp3M!T)|pi&{WidjVn{?w=bWSf~3LADO}EXV8C`;!cq4 zieIoQB+O~?bF^l!?9;sx=KmAkEB)Nszvwx{czF-A_K*6_i1BURAFO$TUEEEt*@<|+ zjChZ{3h%l9A>N#X_vWABtw6l-?x45`J(uuAr2o2Wus#<4C9D(w7p&)Ag*7b>MSf|& zGh+L_McVK6xZjOy{;1!={<^zv?Vt5$*6e22c3Wc@Hz3BfYaV4~-D>YW#uh^Ys9U}< zY{Q)|GpW7pdJju=qj>hfgqu#0uRF|_*2IWX0O{U}I?;ZnfY5!W!4dC1>Sb)7eAZ7;Vk z;pV$;GVEJ_JJv&cSI|7&oBndUB9}UTTi)l#Y5O?;;ffdGp@oW;4=U#`QMTx;nik7i zmG@!3cI`5JM5Xe!#hKU4*KcC!p6A!RhW=|!n|k+3)GF@4C#FZ; z)`zLSN9kL_Ww-ANcBjj8wa2xVMchl3`{3q<^Y!ywjf*OlD7GoLC*Sv35Uh$8O^dSS z<6vAHHFhJb>v?+3Lu@?mdo8AMJsPhXXAIzs{?Q*NZerJ!eA!N;NBXs1rO&!j;pow6 zJ!f1VRwht+v=r|;ws%;l4?M+Lh5#L)z72td5l~x~6o0thDW#(r;s> zC#2Fe3A%k{aVWEP1ebEEwtEqBRd=ro?>)AI=Vr8bh~9EQfBvS%f_D=2b@w(YkLHnq!QG^jgFX_ZzOWE7iw_$7{Q$*J`EanEb!#wIAyg|4rSu zO7Ah{HFY<|AlX;;NKo$W(rdkP&kkOV*s4*}sw-7^WdCNffbb2{gcr4JDH0vEM58(w~NO1)|K8GYT~E3B2n)l2+OZpi>1<9wEet5<%2d#J2K$d(k|VFr z7w%|?^R44}?vHx4?_Nf_AXScWZsQPO89XBx)NzR((q0ORJ|GtJ)RV4{|4W``Xo>2E0E=bH=wS+Xnj`m+oj#qy9FJQ~7xAh#oDG z!VCI1PrUDZd$l1Rb#iL@`SwVj1$A!a?pAzH z*XqFOXb(ltrNK{5<$tSPNj_(c-$Z}Huz!daKOL-TQ2G{fJI+S$yofH$z?2R$BC)4O z#i*9Ct>RPG-Ly_qL3uS8HS{K0t+e>lrRZ4X#43?y@4HCiMV~D2O-gaw+*3%LU+kWZ z@BnuQ%4pmHtjC*r)T?o)?z}{NWLGqT|6PwqEd*!1q7keZB=Lk->+xF-kS{uU3p0S+ zHN^bSSIfR^`e#DZw?qc3Jb+hmwP3zTh2y~B-~o)_A} z{rwkxlcu9a#+qqQKUwQ!V4So!s zYJj{^{tT-Yc5t2Jl>UdP0sKma+R5IJU#+^gFPJFRSRpX(ul_iuUVE(ERC`IQpU8rJlN}iAhCYu5Iyc=f z^EKH2aa`uTqspf@7aQyG?z7;i>L}m~zfjwtnq0*-70Ny831)w;i}+;hHDJ520<|lf z%yT^GPnYLtkCQPzL+z)MyQ!jCU+IdDq`B{8kjka-UH{`jl}%wihTQoH3Ccua9(Q4_ z8NNiH0=Y4LkX4+@b;%_O5gp$Ktx`)BTJvTwt)76fj|W-&ik!_}V{IT_%coZTYpvZS zL#^gu*@d-wy||(|sGgufj|o^*1^yMa4WBFV8Pu<6xQ+XE zZR9fC>Qi8|!nZ3NuBHORhPsB~`N)f$1cRn2U?0Zedc@&?ghO%7GQ@#K&VqE?a$3@K zi(E3_-`5_%2o3N0x`qYZH*01#18>81HO?6WFohD+b|#;tkLaD0 znX5=vagFWaLk!+WQ`UVB`d$Nm{S^HDhX@bYQD|?hY}PjK%uhD8wBz^JkRyNJtsS$N zt90$vTkpG>{i*%l_ILRS_3zGvQ{&ys*C!i}w#({oZpW`!oub`Da-7B38L{JlBfSZ1 zo%v5+SJO$@gG)-xDq&5}1&gvPsu7<4fepW6-BbM;};GXFkL_c1P2cG=wQ1NG}pQwS}d6z*bz7 zU{k;7)9afY7$a+Nox$i5j50+z`uWY(?3op-d0(>=;yey`2|b}2OqK!0B z(p+3MWOf;SDD$IUD6}Iy58ZrbZ9Ym~^dVvC2+2nk>Hld+?PEOA`3m5}0u$nNbn%Pq zZ%)D3Vo0#6Uzo3-2%k<&Zi;g?FMbPUYd##$2UiQMI;n~Z7OQ|9;;i4anG=b^^j+%6az+gr=xwyox6 zZN}z&i1S7IpAW0O4EPNNxH2PFD!qHq{-CBD48r#0RZQCme3yrmb)#Hm{BndKxt(dD z9Ov=*TfxOc^F$YHi(7@dBfN+{t9;l~Ci5XTw8zD26<++l&Z^-$s<0tA5$)P9CdRo` z1)neW<0@6_yH-T{cMSc|M{1fTzFiRKN^UAdO?4&zCSGmmm&P@}QD|=>@5Lk=d$C8j zf8L ze7DPt>I~!V4a#!9l3JP_r-QnVk8C$cFnDl$%0^bpD8aflVg?yTdlFc;L>L>!g-GQM zSdQ^#Qu+Ew1mD|;!hJXPCu@V>c$U^CBepis1`W zFIgWV>xFnrup+4c%M<>;6jXw>#`$A@H6dJtoy$y2m+_t1+b zGk(RwY>n9HHlvf&Jv}tKoD$z0g6t%LLj79lPr>K6hvYu}P1L02?cW9Mq6_2dJB^gD zl@+^?M(|q%X4_BtpV~jdn=Y`c1-p35{OnyCq+f>1vs?*mabOZ_|et{v4{-R|Wen-Vl!cRPu|w_=3ny)hrq zB&2=H?JiSxC@Z8M|y{bA`ziT*S*WE4=~GQzIfo4HLk?3A!Mt1I@>9W9clB~m0&sEZWnJ1 z2UcDwKNUK&l9I~H(WeGh^U7?b4iY_^1Ey82Wp11wK}HCw@oBgx;E4I*;St{n?TL*@ z%EyrLF}m9>z8cb@#MX6WOBxd6r>txZdACTy4dK3s`eJ^^rOeH>j1R^fu4Uk5*is{( zo$XK+%4FlcfB)Yswd3c|S(hR7^&@!BzlHixR2uYx1>YL1jh_#wH(ASWkJH8hGjzm895`gJZ?IGN zU7w3VDsD<2H$Rns23O94C37Z5`n^~-&9A{0c5JDZM!g@)zQT56(dTx$mauMUcd*GJ*#CnF>w^8BEg(z7F1vD?D?u(iV^M>^f;Z@*?SLaNFu^U2|BYiU?|J+GtH{?+mnVp1REzCv8?I^P-TYkMBZzJ)& zj2Dy8-c#c`eiMf5ZvQ=pjQE`_FQ>*{jG&73ut6ol;ZyW{MZLlx#cz;VTP?7eyho*;Zodj7CY9L zVf|NFpJ|(cJEg`lGU|0$dIU>P+c+#uu=GkhG!aY5JYicYmL^(4QfU^JzK*44OL1(5 z6t{62WsCG1u;zKJxptouu+)bXMOo+Jc~RiWuR%NK3*MYv2`JsFAE_4qEkz`z`&9gUmZPuzh0FzN** z0Y>`*{kk}{gL`Y;#kAseRR+qV0rVhwx3fln#Ja>l<>$H^;oG8BZj=6-f*0LArX@w+ zxO>`*VwC&qkUTxfPdH9%SvJIzI}@+-GiWJLC%7x!1=`6854r#3mQ6es)MfrNn4FxP zG6i*#Q)vubkF@SYTDQA%krv~mb4}jQB9wIfp))Qyjz~BMo-zw1?dSDa`@QfT$`K{{ zgOpWs3&5kSqC6?}lwEdw74HKdzCDckfm!Ds3|7~IZuK(IW!RKfjgxU}6uv~xU8RoG zq&SnDo85mv`On-(tU;w6PN1fF7kSTuylp458tT=Y5$nklefcTr|KaRy;G3%M|M7Eg zlBSO|w1wV0wB(_M(o!gGL9jYvq7_v1S*KW^eTUjMHB-%^_YEhT0Jl2TpL*J0yKCv5!~MW%PkGnXr?Rknq;#mh|_6Yi|# zi>!(}ovsPC9!H7;Si?9@p;*D5^+ux;9N639E&OMjh?YtP?exT9*{dZu^-sbadocPp z$8ZYtl5wKR)Ts*DfXX!JN;NIEs;a>t5306vV@WdlMsa#dUTs=xSZTyoV@KbNZ>#vFppdTxqaZa3v7y7%M1!kvPZ zC^MIHcf;a^sD~%7=?Ut`5_pct#Y~unnZWYeEW*Ic@FFOmxq~6tfqifKgvQ-2zF6ay z6`S0h$vYHWagy7iaHQ=>yT_5WwcX)yaOLDB!vUtWBh88Qg^mu#M~?AZxxBA@0!R}n zRY9pc(meR)D_=CfCRLkUWUgh49a~HVX0_SOHdeGdmcXwDlXzfHLYKU_OxGlP)c}i- zQi&El7&dTX;vK4Mjl5m9Ua=LmQnGT|MziNSu z#8bLM2cKNK_$=#ZSbw$wXUIbOL(rFG_sq55{(UxCIV1g)!c-1E{sJc3)#`#4Mu*~1 zA$CKqlf3^U3V;WvUBE1Ak|9z7-?h4Bv6X>Wl7EKp>Xq)hER)V$Y9YN5?TN|E=Nnh` z23st2HgT{P=iR+6&cxF$NdB5QBdtD)gU4HTC4!T(V6pX=?3SgwEev0A<>y`R`0|br z9VBPm&*n(y!>Iq(h>-=GreQVi!ur@@N%I&tE#E;a_}*x-w3EufBaQ8%{-a{eSz-Qi zc^T|z*gD`N_bP`zB+Dv&M4y}CPBqPJ`l_kgI@QIdrVb`8;PkbE*8X{l$#$gazXdCX;|~vQP~0*=6hrd{*He87d&IPJjx8y%5K@pts@QSHk_W40smW3&Or4^1g-`8 z-~($1>6lNzd$~up36gH?_kp8@;N?@@=MjwnDazNL2e;<0qwhF9tw(&d%obZg`YU62 zEoak=@HBw^GCBep(xy5}>9ktQSxdRm!Lywut);L&0~Jf-E3Z~Jjre~ODum52t=IjP zvvKxFt8VNgOAHw!yNs5YC4^*Yv3J{4c8`(Z|IY};94ax^;Qj;LH{#nJK8#>uQ^HjPPplmpiT_Q+AvVkp7*!YgqU+)raIVu6u`i63?N;4!9p8rPkx znTpN@J27MBjE7eTY9D8+fkksA`qK|Q*b92_YhPm@*{bB&SC}}12C|D7M1=%VI+;`_ zGU}y$=%u?b8)AK=>MIm)06oZ8shVoQHylgnj3WB_NkqID4=;PTQglmnYX(vz3H`b1gH4eF*+Si(j9 zZ@{XWL2o_>y6^fN86;6tk$O2uJ;rt9w!CV|bayq)gwTm{yI~Q+8FL&a=;4F9FcdOy znI-r%^9j4UP%k4mc!I-VFR!RC)i!0cq#*}yIBF*q34^-w0{o#>?H*$3KtID)4({{z=$Oy!u03N8?KWyEF;aomo(DY+DZBK)3i^lhJvg%#-8K-DCTbdE;~|s!Yqc`xg9W#|RuC9Dh z#~sAUAP1aGK%5J{B6pDBdO{}Duhz~Tq<)+U>WBx2BHLz9`xkpQ}EN>0sezNq*VX%TU-$Bg=qhnUf1ACEGqZmZ!}YIh5b z(`t-g3=bv&+D^j@r5PD6j9pFTAt%f(yQ^PI2Y(X;(b?*bli``!Oe&>G?v%z%*Da zcS!!cpwnFTqY_!;I>31icE!`+Ac9~aqFTqe{}onFp?sj?-ypri)$o7kKb5JlXN(6w zPlh#8?O5tqww9kJ^Bi|Y{eQwbK|D3GmR0rblhzswhvvOBMMFLJ&BAcEaE_< zvvfmrcHhQz8|CbhCdJ%_wI|J-U}7^=Zf-`7I|2H?52%aSA^3nGY+4aMFss0E1oZEb zwf>_VTQ(E=xGlrb`aXyrq#Qj_&iPZE{m%M0RyXqtUrc9kVgB7^Palq!CGCW~e^xfL z+y^?eaE@o)hDD{sm*+h9Ku0(EP-6?Nh3e2xOttLXGH8hv>fC?bV64K1;Wk#SX@N(f zorN1XXzKF2SVwMEqH``wg2#YyBfXGz$=%e4J1@a;MsU#Xx4k$ayMP(!rh?RDrT;!#@blio*>sx3fvJ7+B zi2t>~c9%lG!q8+L@#l_~!9C2hDy1Riz%23E!1&%5ugUr1H93={oF?Qc zT>Egf;G+IKjNhN&68k1Fo<&O+Z``#}$=VL%jI8ehot_Sjk{j9GrBT>+AHaP1&9dqn zqc<+K{t6lpNuC2(x0Qy+s>pLha-f8fy}}_{KlMq4>8DgI;2()96gunUJC2_`bvnVg z*m|HW2niak+J_?x4bhpKma(E?&jI62Y!Q3&o@jafMy|Ae?WTJM;P3KTIx!S!Fte4f z@&`{mTGq(Fl37*@$(owY!Ok^1P}WpabqjWGzW4O^r?Ok%%>fbvXSw)p)a{c)6NUI1 z<>Jxk2fl^X%7dyh>xb5N5Xs?S$D=16%`9^Y8kS+=U#S&h@FoZNUg!7ugU7!Qd`6_O z49K*tRcCyxFwK*N6D@ymk>F$}YUTm2<*EbWYJx!HCM@pf|h1py(X&D*`)QvYm>~6^4L+L)78o z+X?R)fp_Q7zue9&q(2gsI~^`V6>E>x;m+t1AFP|9<#(?S8u=wP))j^k|L+5ePMMVd zUI`AM0N373eAPi-qy8=LQHyA*`5< z611WKw~tchA?jTce7C1yPo=1~+)X8o=Uv=v(Pztj{1z{KhUr;I^0|TYt^EU6%=1+n zh&zM;U~eyfXCa*fWT1>lCQDpwnSIY{&eVjzeG za|h~G-~v!glTqx5vHWtk6Z!gu{w;U|?+rnp0`XGm-0=*!3{KWBl!%M4|6%X@Rg4dA z)|ZGs3o4k#bgoV?ovoWD4u&28pL`4U##H?{Rw8y^_jV+-20fU+e43aMPO4s6DeFk8 zhLy|(tL%r_qm;}QNxd9L9JIMv~(tWC-MBENfYmL~A%`34UfzLEe z>sD?KY8Hj`9~Jy*nJ2d9be1p8fz!zD+H zv4*kdriooaYi{Q)X7)AqM@Z9*#||$xvko3R#{$s(kO-`tCLRD4mW@+YbV{gHFMd^f@l5GRb1(f=B4$6_#Le0N-p_WegU&$1^jP5^29#J6a_na zcnd2)8Q%@b3Pw)_{Pyteyjo2daj6CsfJd3Oy#1_j2`f~(VbMD?I+JqSLeN;bo9-Gy zpZKQXY!oVgu>QyO7wbjLF-orvtcSc@jG14&HmIkyowdQF+?~?CBNqOLW1;jU!nMP;8lr+DiD7#`nW}QTvnaOdFw!1 zNto7O`7X}6qb5*-`Icsfk?^hArja}lD3;&0TxR2%7lCNdmz0Z3C2uhI)$gqzs&7L% z7vN#)!a@~1_t4!rT*JZ;aF#p(naie1SoK=W%MkFZI^-}W;M~hPGPoj0&`ZQh$Za2! zaGHGlt&ng#Lm%}YfGj-|zx$(#JEmeEBWegfwj>F9iI@$aj3nDF!Hc2wOqBx4s|2#$ z?7Sxrue>#-@tFPLTLt*4VY`Ox&=0>|-=qY-1o|u+Wp)K{>wjEM`?zF^90{w3DV?_$ z*?(=7Tb*{2QFh)g>lePvzGL=SDQD~{ z&_KvMN-F~S-4hVAnQ*@rxUV{TL!T9AYMch4*R~rxjn$Q1EwUY578TA4nhnGDM1x?T zCjKTgY@f>L?qo=xlK>nj7srp>fUn=f*Q{9Xkz>ZcKH{}0Y{RfoqS%)uNI5i;W$dX_ zFqNUcE<pe#AxR76U*f`mUr9QTW#{S@7lO+mTk@3N{;>x zeeQ?;Le&5Fh?1q?_p=D;FW`(GVR@WUs8-)OXD;E-wyJVh%QD;2ZMwDe zb?n>HDDf%C*Adl&#*_3R5;3-toY0da8b)Qg%q?3P^N~orksL8wO0!;($%m)S)h2Tn-&s>u^F?~%P?roarh$F4&A6|x*^63oDt;; z{*3onWyH@$FWBIo8t-3-j>CK6B}~Hm-^Sk$j+%hOZvjT44rdcy zJTd}bm7X~)0lZKpViiqCt(f~8w5r1zyz_PiJ8XH$&5D2Kxq&?o{uX_+8{ZsuUy(FK zm}eLGKC$+6VlUAdxcNEaL3qEp<3Y@jzGOW0M&!9PUUEZ@xHl3qfVZ<*&r;0d+!X6M zn{m16vHIn){D?PhBYDhx-~#S}Ik9`$W>w#5rR*cVO12>CUm)=pzo_F?pWwRwU4`_{ zk8~fdL=(Tcu`km)K`CdSr^_CzRVID}Tl^@E%jc}aS_Euv1P@{;`VVk8X$N2hGu=7j zpFqdzJZP6#inb=Xd+anj74FkmUwgoJ28SxzgA`uM6B_NY7qGpy9C-dn$W25`Wyl2% z0mdRnJRCXYliTR7Cvq4#Pvdh0dRL9WbzbC0H^3ZmWAq4egV$^9vSGi(_p76S@#ToMk&8YVWIXTKGqJK}+94N(77j&t`x?4C z3?2))gK6M!ieZxfj3aIf$$K_;DUYYOTGVb18pu1%yMzvF3hGYlAC*6hx)S!@9wF=` z?wdQzK>||1Wa3jJjaWkyax2`t_=A8v_XhBrxy@>G8G6_asy0VVLL1;y&c4r52z+Km zD)%J&Z_u|?>s+b*bi(`zAgbf|UO!@5dBH~QBaElgb5MGsR66z5PUMxv^WFiEsMI?- z;!qeCSJ<1`W{0vroz4I`;-I8+Vs2_y@+X;*uh!UN@A@mx06!BAfj%p^<|#M@Fk_pQ zuea3mD=aIljrvvEJAbmOz(zjyGTo|K+jN*umUYsgH+;S)tgo{tY9-TQBO`h z42{94|AT0%x1s4YY=ug};V!^;H%i|f#djCnfup71h*RneDbc2a##;esxH zo@Im4G6C=vEPb-IzPbKby>&(N3iGU~O+U9zZR8BC)|ai8HL|Ma<;RvcKY8rQOyB^0 zKQ`Y84pHDTyU>Ic96C2ND<->nlVwAu)w(7hD|s{Um>KiXBhZa%;%L7)g;-y1+3Ft9 zqSjSC@ShJ&!TLQ|>6`IHIN4m^2rjIwVUOiY_vb#Hcp^elcHWbLIsc{4x}gZLuZ1>V zf;R5ILeq(^2sAq-h+nub`KaDfJB-#1s=f|DlQW%oD$>0|C!UPhR^Tj((h?o>vG(&u zDyhQ?*)%Y&){^3=c3k!)8k_4<9Lf0a$2>@e-Ux4J`i!PlD+en=bD7Y@lnl5b%T-?Y zj(JYu%*RXwrPGoEsq`3hg(pjbIT8P>Q7)a16XX3zeLL3YRBz&4j>DYLV#h{*>1k#v z;FI*WTvn_cBz`<6o`EkORxrWyg|7!Rsm9*RI%}f-bHD?ihr1cOkbyJ}Kfvns7tAk( zI04i$E53}igA+fD$S|yOXVIXezL2mD4|Z`!47p+b7|?H5GdS)`Ora zM-6Hm{#B!d#|cvEw}J-nVtSDRy0<8nHb+W(326;DV~hjdfxEh#6X!$P1<4a?B6s_b z_TU}!{MoBtRfM&Sxd*(a9WS>m-*H?s+>+s{)o2X1I$_G$`?W5!%DAmz+XB@hRjo=Z zvG z$NE5{PP{K{TM>g{M%rm5`{*X04KVHx-!8#84H)cHsn1fKAVE<|P+BD@Q!qDg#`h*4 zqCRt+__CC0@O^bL0q2RATN<_+x3Ypoo+7)czM-DRRlpZ{@VwK|MC)J!X|=6@wp8O% z%$%i-@V0I@J=yT2X?eqPTDv^bN_US0^~;Ml*f(MP*vY?Lq?HX3?~$J4F0fauZpMyM zk%JhhVq=)K&soh1mbp1`RhU6Pd>i&dR`_k?i~2ta5r=RZzT;4*iUz`ge1h)z!^O8R zmfB^&m>)`IYLMFF{sq#&kM}=4O5drFHrsvvnl)6ShfrENu#NIg}3FV4?N2}kp?>MZpnc!)L`m@7JZBU0BHq@eLp7QqHC4Z&Ft`p~n%I)&r z)0;q-U}h$TndxVD7TM&zU7JjH;~K6|;nA(c7>7dT-UpOkXsZ?CYe8aZ9aG9_pWaGOUvHM7pJ#bGFK~uI_m2=yy^(z|I7}rjD zgv~hbrj_i6L0Z55f)kLUi|aUx7N4^@H<{Lg&EVeYC3<|eM<>1)RP45`NQNFfee*<+ zi;vKz5tUa9U3W^|7%a8x4VQgMQ&aIw5oEUnDgEc8BwPI(&VXs|gT9oh%J|zx>Fwds zFMO1%Hpq;(qQ<+)gAihXB%@WFv0+0dW;e~uUFb=g*%Jq(RBOW;1?;cRqi*X_Zubg> z;dNhZ^_w|D<-LaT{^DNii@|Way8)vSFlc6fFrX8cp+(&*b%dB`Ax;n8|{FIRUYN8XxPw! zdhYTi;=79hQ;xu7z{`hFGv?0sHEe(uEu{Mi)kMqCS_R)X(0}>1RPzZ}_iI=&Ni@xS z(%boXd%>OHlVf~-em2oS*xj%}ZRQH^@{oLLMNVuV9mCKA zzE~gaL=T(=mMPF<5!jtjudG1YXKv%g7=Ct0_z6~`gr83VKU2}`D19m~VduBePt3E* zmx=%1l`!wv$U(227{p+r5$NPl>c>**^B0n(5&P!I`%)S2k8lOY2lU9t ziJy!d#k|h6{K_+4lAl$N^if}UHeHB~IgR-DE@VpI!#nFNvTIKrlrx!E8Z}5##&Bbg zXm*UREx@4?sKxw{R~otr>k6(s_%|1e5#@29t( zqzk$W@aH%34_}EP#jHY^pPWB&evIyg-NwiYn2&-py7`KR;tdxtqJK#q=J!83TC6U1 z$z5N8kKcA!!IV4UnZH9OmX9iPaSqXwEb?Z=jxS(x(L1`jl5bDM>|utvRR!Qv$>EP| zb)~GGW)$}44u!Z6v3<(!khgOkoRjt|g=Yq0(hs_A7UnwT>$P)TTG+V#xu$3ViCYrvg<9AuHD^sQ<8s+F6$LzCqC zFntN))~s$@B>c6NE34HcbZT8%jiNKdC1{SNYX!cuR+S{Y=TixcjmH(8gtG+x$o3`` z)PdfR+^c}@;iM)`d8-*dl~d5VKK9LML)=o$JeL6I zZXe{RQVqf*v#!?0Kf+H3mti`zr>7e{pGtL^=bDK8zx1tc`|LlKYF1IX@2lszPPZ;< zJLdatyc7+-+Up}KB5e>@Hpt(U2m20gh%e7`$&ADB6R1<~SM9>75Ej87)6v9Y=yhd&JbI}UFi`F9+C z6lvGu@J)zf^nb-+Cccjo;usDy@eMp(kHc9K4);npEJ!$9^#2owXSTVn!{H*}@GJkH zI6T%r*WmD~r^yo%;%{E|Hn;MvPN8|5rS%wok8O+K{3)|fUZveEe_jS#R+`oDP&b`< zy1gpQQ3fkZ9+5Lrr5U>b&la?nd3JhBusS>q3(QXuAL$(YM#lW=Pc$^t4P@5})#fhv z$A`@GMZTj1d^tZjUVN9#Tx-#od6Uen+(i*o`7V04Dw(oB`*e1NS!pi83X`}?CQb?@ zwU^-Zt`8(jzfFM@>G!ih60nUwL%x{C!#4$S5hs#d2I~$xEqW2#&OH(JkvVHEUGVhb z^QIsVtkw%MhLlonNs1%o9`Yt4CBaSgAIpEjOYq6cJ)wijU}xAAg22wypGCXR)W91M zt?c)my$WaW+h=*F3?~+>$}?f9q`wI|c+KG1!DgYDdG>peW?)k&wE&hMazu*DY;+iY zRR7R&CORXqg?8`33FVdQgV1^yk62|o$n;ClCe*|8qiWOk^7#Er)jiuw60m0b?aI%RM*hKn)IQblEN%vH0^KJJ_-I#&ryBAPP9}juA(^q}?YA(LA;H!H*S%~O1A8~0Y$H}mMdzKXC?KbI)KZd)v z&+=)I!(0`ES`Vli;6%Qft~G z8OE3DQjIdmdJriNt>_N1DG6)>R^LSElmS28`!A+=!G9n6cf8+w@n7fCa~J6>AiH?Y zY#It(*l|%>S72j-y>XS~Q4cu2-J8H}nqAfe&I9zuBL1ym$bZ}Uj@r#;+J8D2MH<4Y z(Y>5%Iuhm~H--1MaJp%BldL`0oC@50+{>nDOkT{yDa~(M?uS;7-1(uV#(KrCi`bee zzXozs`W+w9NSIpz+@;Z)7DCiCr>&XxI$nGr+5_Cb8Q%2BM+c>hgkwE48YX<*g&t52 zF+^4-J4M-U%26GqJuH^n8t>1(2<6^(P41bD@1or0QAJm>G}|&qd1FIUra8f5pm{$t zxoI10;Ckvw%Ne|8L}#P5snpnA_m%Jv7F}-ew=@@|XFLtjQyD9+DweQpPH?tR>f%gY zKH2m=@OC4hH+bhm=nc&^y#e3XQg3__j`ha!h=6g&sK0O{dI$QSK@RdGeKRwz#|bDf z3SAP^p+qWk%GElQ|4SXx7Nmf>gCFqFcJ)lu;S(Q#onGfNTX;OJmY$mN#NmnW+Jt?0 z3=c?Zkp}PbX>OL6iW9#PyxA4`ERVM@+I&bu`e3A|uSe=--+5s*G^_-6#a|l6z7C6N zioKp>9uIR^=Xr5bI76aXO4vVIW#Zm&vG9fVEthW_H}9e5G*C4qtPkms zJva-5evQM`y)Chto1vMrtuyp z)71>YAJlHkKTbX1?P!60Wa>jjHcyuQxG%w}g@h>?^tljBYftW!BVJ>IQ?|RS1-kc3 zyI_5r>TJe&BSrG-lrunH+mhhNEDI$kIrmxqf)#L`mEUcIe~q({pQ{~)l}j8i*#~U! zRk~EOwcf5-zRI4#XCyDR$((#ymrtrY&XH$W(4M1SZ5I%UR4xvT2JI>BIzw-(~O$6;jXf7!?aANf8O`+fq7C*pq~ zpa73P;=d1jUPkd!U?Sa<6(V1BgL^r2R|(d4LcB?lJKe)En~|O$482<=b5Xo0c%}yb z?;U7EQe+^RxFj^u_-5Vfu0554X|zsb*i@JG3hQ{Y)!}k#QydM5h+FMo&ew&0;dc(M z%VvMZp@m-w(xu>_V?6~}U@#I~oV7yzu28|{fvLgy9%dwvMxHe1=zk``D!W79COeCkA*uhO9)al2xK?x ztfKpopkNBuO^nz5jn+MtJ+2Ql@L-nja4CM8p|Ra+aCjYTch-R(N4RGwNeL`j^uWi10eV^`xK9s$$0vYBT@Cqn*xwqJy{b6G+DZ2l>#mp_En!;G z4Q>|myzf>1lu92RaTpB71w6IvDd?(oujLC8pr@gar)>*%I~<0Y@uy9cV?AFm9yu0P z#lBh-WUlUJz&w+B7AMkp&Ig0GW`|*ZJkR~XN+aLf?}87RM!rBj@VL=o$lzk%-;M8W zPtf;YcpZkD<6l$;QHSlf#-Ys%>Ys2JO5^Y51dq8wMJcCxHuk%$R&7R&wP$T5^lDkM zQ|MkVG%9<$Ho}LZ$GHWRt*5e#KZtW3ba@v;kIoi{I5CL!OQXcZpGI}i^P14XnzYzAn1q(F>JEjE0Xc`-_KFF@M;uPe}AIpicJs43QWY`lE z#7C~??2cr4`zwnE*X3En-_!o6oGTG#S7(nFC5j*ZA7n*S^QZ zRH!-_Bs_k8)Bu~gNz(nZqlC`_=Ay&JbjafL6>7YsI-EVd#x0#ArY!&KP~wkTib*TK-w&*QlVNY{g7viVH>*(f?(tb{~Kb(G2@o5<`;McDJko}U;YDc%#&Ut-noH`U5>AW49hx9AEm@daoDFvRq^ zl#qIoKS&zJkSm1gmqP?7{uTPYONshyAe|@4E$4+D z93sHz475T`2&Z`U2Arxq|Kly3p6-#0ngGjBV11Cz6aCj?Kgb{jo#n1!h;4h>mj;@o z-Fs}MMk$=6veaQk6K^bn*35Y5y>Ni}2VW7(sOYeshQCJa7)Xiww?>nTKX$+CJDu>+ zNhVIlY;j{R;6*WzfSrvO>%n&-XkUe7O&LYwq<0TXyB>qATV{GYTWwAfcBmGplUyqA zc+j}?Rc$=S4N;CA%a-W{vsrMc3N)OHtiE_r7TW8}gw`D0YXZ&66K>$t8RFLeX^7G$ z$G;!{FD1mj?hbDDWnpLDgq55VN2ATkcdvf`mh^o>{QEB>|62Z#Z`|}E&#{$G1%Hx5 zyv@s!BsDu4_MZY>9tO{sC?}+r%pF|h@&PG?+whVf+he)NG5(W0BZo$>2vJgG!L2hDP+$wF*6#&26#HVcr7jr zgunI~r%yq=K7v#d$ipv{ z;9I*txJV`bEd1WZOyD5(%jeKWrgI2sVk`8D~py{~uF_}>(%$xBSWcYrJU#Rm;XO!9iA=FQ2>bsj9*y`!NRj)cyB{sf^vFxJ z;toi>KDEhh@W+t z-pQ|f$DqSRd(xxuw!uR?hW3>20OuiZixOV+M?^y==yaM*zn0eetq9chR!{-Y2b9Z$ zIV_XEFt zZsf&w=~?W{f>#Hd5&G09b9*Fe(mP0FR1P};>Py6?Zjara0XI|D&KK|l98M33@Q?#u zQ)$oIp7oiH%JSj$<7r&PSp6zi~0LQ{PK|suM z*TmoW!|<5~h$#d2##84vc&tuXyB_cP0a+J+Gye9IuotsW?Vb`Z|6_dL{XM=w zHQ==?#MBYK;C|0-@w|wWRi$4ZgLEw1y=@9By`ciMQL+1Re4W8jul*t%qnSw+Y7jJKw)PO%!;SH94@Qsej)~KPk3gPH-7&@ct(|edn~;@tbYQr){9C{@m-7I zgG8H5TCTSB9q=ySK$4 zH-rm~-tWck?+cUVi~g|}Ae9Ie{b_*YGIlgBVyxV1>(g*>eaK3E>Gtm3Y zN9Gvkn2#ZSri4S?>yyF#;l;m(lB)EuJ)ryHkbXVcjZyuVq8+ukmSNseo9@Hah`LuA zV>SOHPODzbjho{&pBk^ZcVn#P-nGLU`J(9qIHAZ*wlUe(7{|27F(!8!OBr^|H^yqw z4anVV$sQmv-s&HQ^irD7I|bKAR}IDMd+TZwT=ewHrnE2IwDzc$&JmZMQr44YYEeq z{9DcXD;J?&j~fGhW3@URRD%8}#V%M9FXgzDlHo3nKmQ&lY`!3QpfLXYPLR3!)!m>z zutT`=aYPkSbqc@<(yFqq9;6s!4IcE7OSRbwXTb6B2W(i!FKBs1w;`+V2V)v>eO z*jaXLo;LQ;DQi9`j;zsq==9Q=f^$!VztYCr*J1yIzgKv3*qg)Pw+R-N20bfsg#5`k zAM{G{d_DHAcSm1_?euEsizT{GY`gZ&FGklLmEsKn&g1ZQ`m&w;>%ck^6c#V$qhE-o zAsOdbnl_$B^69a(@#r1Ow+i!dEKM2DNBqvQwD4#Qo+LMomvK3sM(fuNeen1WKNg7# zz!?+&5+RLl&e@A|53HIBLeNc?>=(rRkt;sszvch!f6bqb{E5il2zx>5u@4c&ohX1$ zps#;@nfw1Mj6Vio8S!srKJ{Poe}Mc%zy7B(8~aigkOv7LbmO6~51n9=F%?1wA>dY2 z8PIn7sKZ5TeZNZtkDGIFF`C%)j?S}1)t6#Dv0f&A8sMep*wbGFW>8U_TZhQeWbXt| z9XLhF#J2;~(sQt%pmjdwj+8r1_Hk^9&R|nQ^PvEgZ)-r73mq%awR*dvYMXEz{EkVs zIvcS66Q=+E1DqZ-+@watFQVQfm>U8yFSq2&r}5~uy3kPUt!r~=@c%>TMH77{6Mqv> z@{F_7>W5lI*5?) zM5!H)l##?6nh&*Ft=7z7XpXwY@;1ivJ{Hg06`ussNET+|Ef$kwB7T!x z4Gsan(56N&_0}b`VTT4*e$)r`5mSpG=pA(bV5Fx-&~!`pb0Q5$w@LRmMTU{?bu=E$ z>_aT;pBmXT1J@DqXFzMzTQ?DN5GN<^_3z|iKK_pL5iTH-yOkQlgWxH{ zIvO(Em%s~8(qw3k2@dsK$3{oMv8r+^D`0P;w{u1ka{r7I057hI%5#r{-k-{{O6gpr z!VLTX+!o@`XQ14_x!(a-KjeQC<$MSpV#wc*yWdK8@8RxWoY=04nT&-Zs=WLY%zko zB)MGRW>W|kdZIn8@`IU<;nu|tQ(K3lq3wj@DC~6-ULm+UA~&*xSL6q93LPQ67n(aLElGYrj3o#2TNzV!z^muc;wYE*cXf<-Wlz2mt3;T_7aOICfd5Y?rf!I#-=L_ah z(`nQ+<(eAH;x+h5L& zKO{V&x=;Jp{{ZK&5?w*GLiELGG_{1WG+e}!ip^Ye@c%k<_l05Sj=d-iv-0CekA3ep z+CQ>P@71L_CYs)f;)xI?eHvqsoCj6#gB? zv6YoXEqFoG&1CjUwU~`{O9e?x0sDZ9_>V&NhDeeo9=pMKq?y+6FNC1ko3{b{ZvY5-i3(HMcwxmKA1ClzgsqJM6$F+z=neaTl|904vGqi;_rM2fEN7va0+J;-X zS)Xf|sTkN!x+A=YbWC8kZA$A(#R|iTi6dihWL;YLcuMdzw4IB??X{2vEv$~hJ+0%U z^-c8(t#Di?t#MNrt>YSS301F*JD?UPMzd~6!1~5vW>$xWTLHb|KJ^35up)piYS#`9 z9Nb&a;cLvko^9g}PQ^|V^52R$J4OT78S>8?p|Zju+H)b-kl@Z?Y7yRxr-Rak-5m2Y z`3Sl$#O1H^{Q)Nn%DFuJVYR|_Nmy!Gd`rLaG-iBkHmfjl37%2oyVb{8k$E7!%W~H( zq>KD~@a=CZ+mC`Td&Wz=@bQ45mgvA+p@%_rm_7Qst3+tV8HaX~{L$IM5!{oW|A`>9 z$hus2?G=gz+Pf|X747sz(kS(@yn`#KLL6n%uU+jqP`%G`ubX!+@b=i{l6LLKHTxIL z0mg5H6t2ue+Q>Ubx!g2QH)Ld-7!DnCCBmkVGxfWwjLqg~X(s$Q3(yP6GHk4KYTy~m zl08_)CU~F6`bS@!#~GCD_E%O`wEZf+-X-dj>NN0@`2sZic*H}?b;%*Mm&0~|YW0Sv z8MR7w%bfev4v9xCcNgjUfRSao9G3%dsYibq+FXToUb=UMAiHmfh^+nh;FFKF zW{uRE%&V<2qBW_Who#oMfYvDEt!XxQK(jj;ZFv)IsgJh>Win`?c~`_+^MiP6R#nbv zd$Se(U!XBUc04jjb@!n)G6;7Q;;p#@8md2me}8$|z!telZJy{^P(_$g3mCt|+@&$O z4?4f}d)tUZ{RGAjG{MMr^&zZ)t-evyy!lRWcVc^yGQLXxDyVRM-**f6Owgoof|lHHc%||qJHpS2D=*4sLt zt|DEr3wVrk`6Snb_}C5NoE@WE5q%*DZy~NECt=!Cu+R!$AbNGiDV$ia?vU&N(lSVw zIB5;1Gb4{nhKtsCqH7hn5^(j{`M7@gtOXSNLk$^MvBUu{7*RkAM+v=*8C9e?-i6by ztRVT6#(1P|VtlM&yD?bAa$H&7DOCzcxH<7joPSAQwXyATe54Tp1>?LI<19zx71)uu zGQOkP$BK8x$C;PLS&+v0A$)&0KF%v8DH~R)z}Ps?3D7vta6O7~PQy48?Ljn0Qhc0$ zJF0ZS-msOcI3bvt-?)G?WV{c?+D-jK`x9){VVy$q!hFd3&go8UNwG|Fx8a0I<7t%m z>GuU$@dS5zy#F;pk~F2cQzeVxq!TIC{Q@pX83jRRzXg`rB+vM#tclLs|KlT>4xJ}4 zGLz^`iF1e~uTJq$R8jEAMtIcXOWlWvlvilxJjTYxqrKJ-*VAdNH~N+DR}Gw=eDNwe z#=(0U18!0L2_-OUFiNW@@d|ffKG5$IBdk3FKZKy0IwStqqc~d%G8gNVbwvC-qu{}~ zNWT|5CvwnO|47QwEK$JFC!X@j{So-T$P;=%XRoeI%+uX3$DT3{*bqS+6Ru#Hgcs)m zGunDvqt>XvIX_V^^vXNAIavi0LCLHfxsz2eG5Q?a#=2P{JIDlflpSM(Y?yt@qAZb1 z=O%MAx!EwWW_fH%xtCh`D+wNVLlD*kpQIDiEviqnq;GFl%@gLK&Qbqw0uQ%cYURp@ zk%uTG(2SstVtJNJP=5HoK%pKnMc+hQvrPUv<|O@pMb}$GR71PhIWOyE;-*mv`Q|E#6_ER6FmtNPuJ}Ir>y0m!$;kB+)>HWg>{9ZFGk&kI6xyJGz^A%t;k7-KU`ZY&d`!!0}m%c~aMD%r@ z=G6ZQ(xYu$xrnm&{Rc<{yI<391@AKNX6ZdWJxXgs`FTyAYdBq}{wMcYiTWM`-CL_V zuUUUJ_rq;U*Qc#|&7*C3n&10M+Kx!;%E_yDA78!utB=OWIHHw!d3+Tonn#F37vs+{ zW3qwSgZ=>Y7vOcr&WWE#4dS5ydFmp1bs|P^^GFZ;OK3phEK+N>Ep6SUUb>CqBSidR zP@yT_)$rR9^Vkvb-!vjKq#Aqesb=-&{cNYzU{zo9wis_q z;&1b~vA4~3i2EQ_72xl|0h|72d%E;ovzbXY{=_|{w=DiP_T)&2<&~aV;ZF%Xq8Q(m zd}Nr_&_{qbZla{3@ZA^V!Se2!|B#ah_ZT_RKhR-CPVyoii!0=Z9}-TyBg!UEzJs+h zXgZd8Naju_+BE?ad;!MpR|gD|#GTR~2xzMl*dFxHs=RhyTv1;UW=ov3pGQI2X=I?jiQ{e335e>}Yj}{o1BG&5Ajj$Ks%HQ%S?);OF_|L?brZ$e*r%>DdeZ(1qJsVo8@bpNWb`{n< z;yiKUcOn?OJE;Xn;$x@BiKHWnu>=2w?w^j5Pe&SkCO#RZvD=HWGfHE3AE+|o(3s#a zOXAdoY3yi~kBuE+%x@xNV+Y;E!6J;^+wcf+?b!VZTAT@<3TfKV%PRXNA@p#OJobV)HQgPy7J^lJU9K{By9@nUM$GX+f+EnVCZc?w&yqe-rr~ zywP@A%mV^TmCg}&M68yij^vKw>Ny%2{)6&6n1minM7-Od!A5nehhQS+NO26>4HC3M z3EB_i&~mOqyD<(;S6u*T>g%Aj02(hrn-HP%mt6?SlU0qi1}#y~|Y8CwG5~kN1m`J$*QlCGO;R zC4)P&AgqGkOxXW5PUOrp|19<7Z^8=9Rrr7jb3aS~9mykpb{6acUy|lN6W2w$s}j&U z;$%G%IpP8h)v>3l8E2E2#XOxtRyupdDxFA@5-6pFuUaTZAtYS+T9rcL@D_$Z}H0I1)xkpNa{ZJMta&UoLlATL(+isc3YAtH>B7xs+GABE# zT22Vn4kOfK$;bEl$WrtwJG0dHsHK4A!RNIq?6t6u7W+s;{Nc9q7>!dcOTk}~?_S!H z;;g|q^+SSisrB7-z3?Gca6c;e^JkRVuc4@K%oU>tXA2Mb2zv{F zy*%uYndcE7SuRPvf!U1U=IUk}CBL7H4xw09bo;K-zja9fpr*jR%;?g@v zZ$0r`Rw>t9vhx~bh7?z=Wsk)@cn54Q|LBX=0}%xv6Qp{`LaZ2N=hJ#w5wf7{4Cx#n z_5T!QQ)&sI(r;yGtn5M^&XCvvCZKF;TVr1iU{RDp_zQ`SMVj~n_G|L&J`SmeVM~l1 z7<2l5oG@{Yn8rNo&@%F}pH&j|^AXw+?hYF8P6Usc%X|KCIxKUUafM|())5o*#o2R$ zcmO;e6ZkK(PI`JNM7E4!|M^ixdn)D@WNs48zCTEw)B;|n7sRqrc{`8N{w}@wJ!~k5 z#`Olt{xIsF6UvZ&4~EjE-)DoVCafy?0{JDwSHoV}H0D0(O>-*tLVFYTi9^|+Yd%j; za5|OD{bw&TrFQIv7W_NV6EA_xfczXd46dq__62+iR-kF2)s+szxb`_X6)fNn;k-*$ zQ-+Yk&bm4SE0ReX-<Hyx=s83z6C(e3E>ET6nn z5N{cg!*4Sy`pPo_^AV%%o{sdO|L|z46bbP?*JPh!Z=R1vw9qG;mgvbqZZ?$XOP7B2 zK8=sQ%9g%*epH6_Z@g~;q-bPiK>a&E*1rSa^!?G7+|}cHt}+vm(5XMicZ|n#tUsB@ z;+u$GlXWeIG?IQ#ASOaem++MHDXws#2NKXZT?o*#%cXH-2whU&DxG>wzs81seQp$7 z81&iZKysdpHC)rP-wW8{J-co6iFnVhMlPEb{x9P_+i*2cBj8Za-fE;?b+)C^e}R0= zeBG+Ri4f<@scP`X(z=#8VC7?7*QQlFvAdjb3|}m5JApf=tHYtiYMALbB-vQe8pf%> z+i@Op)v!!pLmIHbtaZ4OopLpU#e={u`^!i3@a=vVceBa0LcQ4W5hS#))ycbF7CJ05 z2Nh1H*QsULUza%qF*T5!e?9id0%O>t!f82ANWhHQW0^1n>8Jj_mgKx_@vA7>Yl^iu zTfBs)7`6pQnq8lxSBJp+{~C6N^4$sWs-tucYic!QE8KK34KU7Y;29(TJXZ8P*BM8) z_#xu0{1bb##beR2^4%lIqv56U+36)0sRlz*4Ss%I4Gvzd!7r!=fPA0Bg53A1Z*~k> zXSXSwkEt(fetfY9vLBgq8B;oST7~nxCK1HKaWD5a-~iV8w|Pgveb_Y(Y7m~ z8h+zo`fRZ%dOenAi^i)EW{fcKZ6QO1?e?sTOn+1=FXOuMQm*C}q~5#Pp}%;2Tfauh z!>Dnw)KWUD-GnxN5xE|7vc-#$v5~tRkfYo@Vb3+K{5Wzg*0}K$!Xo7R2x2F6PBO;@=-2D*Iui zAdccIbRKaA+A&cc8_SHh{ zz@V2wC1d{|q5pTl`+-*a#vA8cE*hB&Zk=@Q0sm|qJdXmx^rWFjEa1!!!Aq-=b54~w z*dL7ekFx0@z#kproHw$W>@xOOSopS2oe$n0<97+--=V9G+I2A4B66K%<)Coxv5Y{M zS3h46eW59Kxl`8uqGdMDa7Un{E}FEmeU=%Xo)+RT^X}~GE=vLAP6jV;7`0zwCxpQb z$?!`i8Z%@sU>92|*%!JXsTJ%mwW!5SL26yL_+He&lqlglAv!U2tA(2t<=DOVmlpN@i$QV5D_)L;JpsC)DHrpkPO z{5jc|E@`@Ol9V=0DBS>C3J6psv`EG}t5EeU9n!zSg< zg%(B(;#{{8#c>9`Gm{h@yKyH_Br58}Wu|-cdp{>d(0hO1*Z1G=>qW_V&hqT*=kxx& zKcn=#`YkL!pc{>S2AK`cp;pOMX6M2ka&ks~%GsRcgSVIDU@v&#$KUFKCFUm&Uk@Ex zg_GGsEg=trdyy&qGP1zRlo)K2Z*AD|0V%bmat%+UAfNv6h8>^P&^-Q~Y_ach5YPJt zBB*X+%7}*)8A9NrMxRufzjmTz&GC5AnSUF&y`~1$ z?FGooC(sd?gKBR)r^kY|7UHA*zd5GJ`gd3WkfMXZ4HNga#@>Z&$R8|q7GxGfLcT4K zpFm_RCnv2D=K6n+Nd5gtM_?rY@)yUJYc~VZ933k@{Rb2hSr1 z@Dm4##2Z1$^EioJ4<7=a=U{73Ja@vo+-~&#BrK`Wtwg znMuO%dT0jcdTe0&_-|mPOP?MXf6;ZpNzjL+Bh;>8M!Afb8mWgjQdANggNz|&HOaDU z1-D(6X+MsS&8fil6=IAH4;%y99(I?b@%s!ccBX~ivKI$CWHUZ0lIMR!pROK%3%$QV zuK5`DWXxnRwNjfyXwZVR_U+??m_hy))Z@%b!|#sk%1OX$|MP?f1J+aH3F4jif^XSB zLVJ%5RE~5;XuCThU-=$+TsBJUf%aR9`KR?D>XPsqg@1DD<4nGjSW8IZGMp90z;I+; zw8b)|iq^3N5#yri5sg(em9I zqcfn?59Hp%M*F)#X7-zrc|_({&3m0)zes&X{qA3Bo1z?aj1Iy-Iz82ui(|xNPw1xj zo3JxP)GLp`XJ9lZLA05G?gyGZ68&zJ@^Sng7|g-9n3?*rjgTi*d&aXN=Sg0s#)z;jOJOSFEYC$(4^fHs|? za6Wl_(~eHLJE_IKw)+Ek#{Aa#C!9^+1@o;uXm`FO&dRUD_Kqp}B67sF2p+cBu2}`@ zuF`^{PBZ+m7E}NAMN9gQHct(g6%2u6J0}<`Dhqz$oK|s7U(!yb<19EA8ZR>Sed(08)BgPTK_-umH>r?q zdL(QA!tb1n_lV0v*p&uYJ(BBW!FJaXkpuFHaZxr}cOkO1DBRZ>8HdlZX)V2x!j_}W zyBvA4JWjJ*FUzxSa9B9ia#^Xx)@kb1t>CKEe>dD<%S*U{I}~^?@(WCn6z85j7*{ddnkJaS;*kvcXij7Xk3GoYO z>K#Cdg=N@*pJFwC(!3|z!^~`O)b04p>1(oLol})IC&@hJSsweBT@8)}7NKQ9iE??0 z?E_-P_(>rRPq5KhBaG#X zMy#`Rg)V~!g9Bg#mV$Q^oS30)&V%@shMHV$F26k*WW*R>9DF0f6u*sp(seKjPa90$ z)5j%P(PiR_juG!^PI|_kd^SE$%)Eup6GcDF6Q_p5HL!L8CigNqjorz7*zr_4nSFG% zf8MSYR|SdB5Um)L_!)7{DIcS)%gp{LvVKQ)IUPkIBHy{xF5M~3+2J_L_9C7;vzWqc z?0dc81n-wU`V!GM|9t{+F3VFp|mGiONEpc&9d#c#KOXMPn1Z`b2oYM!HU3Q`WqVXM}Av zvcr?2_YCXHZ^AiQU(VzxJSpX}T}nt=w4MY{tTfS6=8_#w@;u_IvL|~+oZ#T-=wwqH zw}a=Ytd4lpo=ISNq!NeNR;=sjmml{K-Gg03mwt}Q_~|@9n>=}(?#kkO+7nqf|6WjPGv+2bQ@g@r0omDXK&%z zH+XZd7~AKV(31E+TbnYV2GK00CU$*<-+NZ ztEAzNVmYp0Bd_ceui$E~;AyB_Ie9K2N%*^B+j4^{ZkIM6ztqlUA^z<6E4jFQT?k*w4S1Tn~G)cP2jWohNvW#`jg%WtUI;;itDsfp`Vh#hr}{)`$Lb3w5gBw z_&u9=kLK^{y*c7Ny05!>Z<=_IVuY^VvxxU7X6EWWR=lVF(Y++`9<{Z*`kqX@NAq~~ z-Y|6TryR8YuHK7^_h>n&c8J3+o%&N@$v}j2Qmr~Y1A(a)SQYIp`Pe~GF74!?y&k>* z!tXnMq^@ z)8uR>e_DBkt6(MGq$gJy-o4p54VJQWe*8u}#r_B8E@sLGJGG0VR?8H-f7}jV!n3}C zy#^qT(0vUJ{298hX~DRz;19s5=3!188Q22UzL{i1-^1Ky!JW~8e-1Uky9Oz`0h|Wg z@pNJRDQ6qmftmE(mAi4)I?XckcGwHf-VgiaNzu8nXbmlyYJ8(84vk0@`osn))F;YDzjM&Uu~NoZTacTsdlkQCe&9EAlBt+jxN;+zq?+qsSW-YM~v zItlnrDf%s&a)u?&EnVdY!llN|?Sk=2~Xr4a1pN-cvHzZ_d9zUytBLvUkGoI-$6RYW@oJY+wJf*Yaa^Tc{|P}sMjH| zfYa3Pj19gOWNpqMypj3v{Oic(llMCQ%^_>n!nV`V#S_wBVFU6v%%+#orpeG1Q=68Nfs12` ztXuHz=m0yaI7V&4>2=jugQL(TxaN^gV_rO;^4gN8mMdI;Yr#2hC8eZW9kpaX;aB=PNk z4$InE@hXZdgLrj$nCc1R$OFx>PgYVcsL=uK82$fkSPAlAtu5jkT!qABY~VXwk|U?t z4*s(16!>jaNbeq`2agy>XusTsGvXganHFtxSj2>~;Q?r9Ksik9@be+xiw)c_%D&pc zZUB}FaeRZVDvxO;FEGM>dn#-(;(6UaJd?!p>c>?)ue%{HpxDn`vF2Y#%?DRfIgTQf zZ{)xva5?~A1K0ONXgW8>h9bAaCr9+;tGB*zyx5r$wU3s9m*GixT+(<>!?y(W-e<)O ztN~M2iL-5;20rCFox1u{%A}8o6}wkF`vx)`*4YMjzc1m%gcJ?on}0_1^={=?ANQ{V zfs&KMGZH!)wh~=wf~VLjdDMvg(P!r?z;*HId4-wy^^fXo3LK*S;RDW8o21oTG&j`N z@+laDtS#$X7*DN(@loxrA<&R1K*w9oRcApXjXk`i>{rI;?32zCA;DMWf{jR-5bzt< zn22zp$>d_7eWKxmP3s-lxcl#FvNlnD^)JKOE@qze1*I#Szt8b@vyzt-cSp`DDnC|X zR(^X#XT4P2)^aj{G)-46O5~VZ^gw4HFpD~wXBnT$)8C@ZFF4Lo_;DcTOnO>C(D0$PdfI|4RiDLEdYN9N@y~zT!*38Uw&sp&* z4O$<@FHjz~9%2RCFwtXYEA`0087YO-)(q6Fi0r~hO&_6clpI_SFKY=wjZf`VKY9k< ze9qUA0$K1y=XS`uW}QD+GYP#|Auuhy%5%^`!et1AhB$=d^-$FJ;KTU0VJk_H49&$Ma9?e-`E@;aP>>+N44ms4X6|SBi308K7x8=LyRN zQ$1y1c~-o_4*w(IC{Qmw>wv`Y(|R$I1Ru47x^qk}2((`ZA4N?`{0&?c{#LE?`0_ z0*+ES>Ya6t<{j$54vd|3H_Q99KE1%q{E*dpK8~n;w-K%HuT^h4)?!Xnk#!E){&!X+ z`-;KaUu97Hn3BIos!YSQ3_eDr~gsjf&26A0NP=5G77ZWo$ z74be~FqlhNB0mxvC;Y)AM_WSy6VAi3q;j>A&o_Hq=J4qaL*(2iSn>1kP)3eYH=2k&U*O~fGGL`inc5&z3$+757O9{+3}Q9Idr?L-edt~XGxso0 zca(WUlHW3OKjZ0ISB&rs>_0yXnw?UVEb(J2nN_Ozv*L6+JX^pkdPNOvq`QM`^qJwm zMYf^lm>~7|N%CkK{gv>$+Lc{o>YC~5g;#U`Q=42pPX%1Yr@wVoKHYACulY)NN3ZCM z43SwS>%gQ>(@Vf^{CJ4D{_Q|tq#cwo)FXY7tL>=fT<`02`h_P=#*6Jw`rfb&DYv(F8FhdO=-UhIi*ip_}Lh5DZnEO0VH!qE?a88?$N zxa-AEEd$cKBJ2VstzO)jF;a+k=!_<9W$|q42$g%Apg&FSEP|dT2m79#PpxwahR{ zr7Zo$=!L|z-QpDMfp~;UDWo-|cPqv-&;u;3Em|JbK$r*$ufh2t;%K7h9ZT0%i5QdI z+k{`K0DC#qiPEDKajCE}U&MH{j}mVx^oJRgdu{4%x5$X1Dc_kMeFy$G4>bK!ygnN% zax!znO(v(@7tf&v@im1rqGXV+hk{G*im$5@_%FEW76p7XFv71gt6*CkGv+%N1k$4~ z$DXp^*h^zRikPJVi7)JwVGX`{Nbw_wH&Dw(U zf6D>}_$AgkC$Oz<9vSE1s}g$TM_kOzvqp)}6!5|JYIfEaeRO{Yyc*hQ_3&i)mD0iZ z9GWHQmDWVCR{9mCy_oqmz#IG?wkwfy61V;ql9vzvyIGGi)-2oa(UIU)^F{iY%&L2q11Zw zGRu^C>`CVW_G7_Wuos(NZfTl}Uz77-6MW9L+|_iU>9)u$XwIq7(szvR z0Lw13u<63;o!;Bul!4uj47*@eD6?GdqcwK5MQBb8z~)lC?&%1=Z@Cnim?uAmECOgL zvvVn#RXi!We9#R4F0;WaIVtKGY`5az@eHMN^#nocPCFwG(M(_@N z>m@q=Y5C~M-sZ#!591sB2Y8?EZs^XPTF>ZCQqHpRf$`YjfFJUK^yu#KA)KOGfl;EM~QCqPjLKn9`_LK536^ zr`$c6By?oCtXq`evrXxiV8;kg48fC-lE(&mV~K)<`W=7%J*)|GzsxrmzLTk}I(jl2 z-e{BHLyAhnlRKzQkFFg^zeeZ@NZm}d#LQNDQV~-8uLSyyslXo{3tTp?!0$z@KfCy^ z*pGQ?Y4Qr@<`?Xe?z#oB1we*-TkW!L38|YOo9_-VZka!5lmsX?Pww6ceFe3f*`Q-) zSpyVrM6J{+aWa>9q606+Ds$e$_tAkpu~PvVBu(M-GOVoV$JkN+1^XU&jOhL#3~!>L zxmf4^3bfpw7AZv;aYd$6si)W!q4N5bJbm^Kyjs1A`)!8!{pkiTMxqR8@{H&SJX^_~ zO1;^@c=1K?IiBE)!=qB%orQQ(pd-oTcfvZlNK8i%(~-o}nTW6Q`Yth@XYkdJ(lK34 zXR8?F)pXW~={$hcKZr>3XNKmI%3_*w1LA)ru&*VaLfb@14jEW6h1Fs#nL7nmtixG|#0IDaF&tM{F^S@CQX#^GiS-Y_n$pothC1V?{!1a+nJzzKFN%M0cM;cp{K-qOQUG@ECioR5!TpzzihoawLfB_a5$2e(e#rark(w_fyB;;3L`S)D(xJ7vKzUIm!cp1&MAUdY@-%f?NU@5 z&Fe)LHbdldAOyJ(t^4XrSL*&(6SW}oUt16G(!zr$+#AndWpTCGOV%OAAE$G*wpNTt z_c=Il)<$m?bMurv;T+B9VuWa|D1iy1bwLbW{0yZ24KR#2NnFB26`XX5*?R-IQnDE% zmGIFLmks8RJY}CM*1T2B=aq6^X)QXcz$Gr${k3(rQmlL04*P$oTZx$aUqPq;NklpY zV>meZQhfA&^66{Xt8YJkk7NC|l=h59eY?JKGSPLI8kKHlMrk+2D1b8^S~3k`i0W{9 zRF2s+4>MWTh?1m73r1z&hh$ph9(&7Ddxc$fSRYVhZSDu(#a!nU*rCB5uO7M{>?Yt# z9#S3D?eo-*knFy>zG}Ow9h|}5!;2}Ng>t{E-08@H+@o-3;5V&9?N<1c2)wTrEN{_t0gOAvd24)7)GDt2WJzaw0c0FZ8WF$aE#q^YS7aV-E%BVk2Bc$ZAP!+~FOc05*i>uU8PAjTDgnqR zqbGgGwMQwMD~U{kvJJeFRtwPblwGWiC(&J_QtbNg!rm5Ib598=!+ipO+y;EB zJIRVG$!~$+vOXRwwLI3pi7Bn+V`ZtF^+6rD3Z&WKoi%HUm@Z~naP`K;<~Javw`%g0 zT}x|inibZsng zKEm&D$iP&C5#=_uyumAQ&0B~0Dw)p?Y<U9ogW`$Aa!^x^dZ7iP5v~F|(0gbds zG&*K+mAM{0>srM=%)jQUU|;8lAtM~&b?s809zCEP=aM&r8bN=A0k1wiHz|eo zy6n1Al<#;X=_L!w3O@Dd^LX!YP-=d|HGg9Nxsp@ijP=3@w27^{!%`kQ#2k))!?lec zah>MVqszxAT2ku)n`(7}M}liP{-?fg&Kec4&ZS6LIri7mb24v6biwe$kt=zsL0ZM| zZ;;?)fq2!z+G3SaCZJs44Pl~lU{9!qM39NvM(LN9VR}7()EWV57hWFKC<`rx?y#vY z(UZ8JmL#F0swJVFDP7TY79;O$6C^e8BM@ite=Smkz9WT)Yak&SC1okZJa26Q(|uN5 zMdE!&N{Z*63aG&qS5w4vo6C9w3-L$H@*jHNDMu;d*m%+`_SzLAF)PV!dq`gXX^pi; zUM@G+*0j~6N3V~4`j8p?9-k@XI*PNQcFIcB#AH`;M^>Y*BO6Tr@|_AdY+W(4NnT){ zpUgj5rv#gc9R2O^V!DTko_rY?NA*sX$Mfq9GG`C$bGlv;Jp+-@@vwM0fkZLYNoS?Z z!wOG&^fl4S=wP^Xs|Gke26ogM&!(*&Xleanpe(LAQ7HVXyieBZb2e48M>-9O*b(Vn z8eZm?n03_|xtrFeyIIT0YP-Q5SjI!Y7Tg{t7NwiY@svL5LrNvAWH)bB_=qP-m;|0( zrEr>+d)Q+V%4p?>L<<}Skeu~Ai~K76URFb`c!IBlDKcN_ll$*5ZrVyPud&fZgFnt0 zEBX_Icn7lMeE!6*Gd!D}37!*9tw-xm5P+-bN+k*Y1drBzVymE>6f_@2PmX2}pJ=x7 zuxWUtiq5krxiqI1Ut2ew*xIYo+Ki-j3$)%`?Ix@Ee!*~QOB>IMJIqu_6?Hhhsl>Bq zvL}A-doWyrHjudATxLDSxM@wLVH6U#$_JmW(68nXQr5gmoOh^~2ux_b_eNfHChk=k z-P+pO&jT{j3{@mb5^kIk!AePBl3wPYT+gY{&W7rgEKr18${mVRdO|JzqPGyhWZ>d3hp`Ha}ZOy?Nxu67J0?qru zpuBY+MhNxyR~`9jjZcbhkNvd9mqg&xr9IV^?lZhl#isIz%Wv=rMo3M&e;t-sPHauZ zEY#pwHj_#fO_%}9@cZhkW{-Z5T*0n$Rp=_%66X|`D)*MPpC>Ohz^gN>4`dy&gRw^K zPvF6?KE#Nz7!gbPL@XsvDbKdAa3wS^Z8jO;`_89#Eq!DuyvmvIEyru%Wn1kxcR*eQ ze7W4O@a<>gwS+lO?02t20?8hojGaG2OfD-Q?`2YWz&cUAX)E4B51RzO>z|f4ZVhEc z4>OB7Nc2^qj#uz<7%8j$3e+iN0X^fF|astRB(Ro*k~Je;b% zi{-@7VQM!XNrpb_gK@^P8TC{bGz!+DMEHJ}h77_aqVxPB!oXkA%V7yD(_Vrvq1zDt zdB}{`Sr#z}I=^647TH6|Le?=KOROKPuDla7R?%=MzmeK|DTx!mC&m^q3)sWB`t6vE ze1_llu_+8NB@e@|&R9yT6TdHxt+v!TQiNu9GBcf3yS`FoTl1kYWNmx72FJy~A(fn~ zVG@?d0@G|VE~Xlk+%4alsN@7Tn|~va=8@z{A}5-MBh>ztj6y4id8-w8yzIeP>~`4U zEXonsdWQ)sODZq9Zdu6WH~JLbwCKDst)Ophvs=X)G6%KbXPn%Xfd7r%bcFe;vko&@ z=Y(oz9_V7hK!M)jYhj!CM86vNR%`od^pK{(dZh4OGmZVkR-~n<0&X`$V2@E2vPww6 zVTs2ZF+-|-@GUzg+P{R3Tne-lVT9=YAFmk&r1gr$`h8=))1>@UF|mOlNTn(N^3W@ZEAb)?5~PuQahW+XLI;Hdy1wB?FkfPNKhtbZ`CF z>i2%elnzD+m>#8>DjCCh17O;eDVIyR9Glgqn_Oi)rCZ6_)Hc>^lP0hnO`Bo~|6hNf z;=73D$>Y*vg?y7!38ZMYg*3uLrY$8~QjpelN^vR)_Ugm)oTpT0Buf+T=MoI>1lDoT zTUb^BnH3vY9m{u7iL$a#ADZV(CG;(2$r;_P9OG}}o;NU-i@I5coGpHv#%5et$VVco z!t{_7`&>ni(N;lPjPsm_bo8q;tjE?&zwU}n3AP< zM?PO5XN`=1oo<(518bX=)0k|5eO4hjP=tBTOapJF@7~JwlHb6dzqGL@qMa`-{G|IZ z+L)r}vn|rbCyy(E-hB#MLpijRQfIHEDsc^W4=c^Rhnr(K-bhQOg?|N!lQGN6wsT%v zr=%iLIkQuDC-+~vhYT~<=xpplsu{J}PX!{8gd&v7GPyj(Mm!4ZQtZg2C>f1aU|Vd0 zZVmU4p>&PWrdinF2(JEXB(aDM=`8xCPDfGnHJ~wNR*TII)qa_CgZLFRi1;Si>ajg! zC|N^mquy~L5;G?iy&NiYKETHFTeGGevOaQWdn}wneTk^R82aRKlZ0EZ!4>f0l5Oh~ ztbeSg-gN&lur{X2RRr#}KgfM$_+6k8Htgxqlu>5RtJo256hoTPN-NXaWui}HxZY=i zEELz{BbupFXuOH{SEdH8kt=}(#XknF2UfzCvX+y=ns*HsUf*c=$H4TMEyY}W;8E~i z4&{P}f7a~$M)gglw&UP*&fiGye=sDm6x%qG-$;3$^EV!RRA#09&C2 z^3XxofjaB@r1A=Rr$!1q=LJ{WI#WUggPP!KxAE5V&4P4^iss^b;NaUHw6+|mZEK>f z=H+@(CoyRlKJA*1PbSz&W1WMgOo%tz$Tnb2nR(3o+5Ch2%lx;Z+$-5j^8UEC(Y}%+ zdS)&kDCVDVBzw=8BvWK-S8+9Vy=f&^iDzoP9?vBul9_y=v}QPQpBj9&(84yktq+8{@4g9pcLDTMkYB`dgl zQ(!xe{Z;`<-m{9!b4mAbTs^nJcu0SPLGGCX+cQWAcdd4%LVoCH-TH%UDwug>6JOVJ ztBlS1hgpS33y)Z-MCry!gjHY;{Ygh4ZFd+uE4L0DR0d$5U*RZ1)wA?q|aXGjGbdqna=K^Q3!? zUrp)-i_d-6k?vh#>*SlTX7O`-CUqLmPLg>37-)k`pzSe*hibrN*yUD1w~P1463Fol zjkWjGac5YG<$hKT?c&FyGMwL}e$C+&_<~u*NrY8g?LBAM``OsQA0c6r!LuJwFaA|r z19u0v{vPdN0cJn<<9qB`V6$(6uTS#Pe}|=l5i#G%K?lr!#ooV0wo_)#sa^(eZg+4R zazFdw>W2)+SIfmb#lLwk9Ls_BW1noV!vCRh4Y!HoxC-Ej<$_+nnX59G^nWp(3utYd zxeStI`!y%vPG_L)K}jL$eiGKq*+ep(bZ-l@gd$d23lh3%4OLXja@Vb8W-_@g(DIPn zt(LP!X9TuJxpzleuS@KX*OmgMf`?`c_PxEtvegR9GUIw^dSiJK&)UdT(g7(*?&O=` z6SFN-?&*FGJPdPI!4BElLiMU|jjB7S1kuzCZvvh#p7XP9NO@JY9?!9F8`a?H7tcwA zVqj<6GU?ZPu;9|KV*~p~wRjq@H}2zj3iOR)Lf-(_9+(#-!WYlQzm3NVp7~Muvi#xh zIWfjHh623*&FGyG)I(P?kP5_tvsX7AZ}bEigDzi!(=5=`9_n+9U{zA%TuRaW#*ntd z;3C&qLN7Kk)-{os6>HyvU(sLB7m-+@1lWPS+dq$}@m7PwyB$1UBl67i5yr3Sh!vg> zYLBRaH(^~dV1k&;o=6NFt^eNC9hpz^GeM;?a-iv~*q>EqYxSqiXN(&BK7G8?$XkC| zf1th!+$hFSI_a;^YgohG#+7q94O>mixVK@v{T4RL(%mLj26TZ*5BnJFr_~I2hO?oU zpqhiWhEgz?#>m?oq`aHD<{OBAh?CiA?nZ=B;Vron)HrnLw`9aB4i9gSY-t0fdmfG_| z_mYPV)Su~1BXmre8he$pk4LQsTY8D#9tie7%9u&fOE~ce&GnA9r>W-1?dpHJEwkro zXs4R3lY5?CRC?D2Gs)T*8_+pWjH#kT4ulpKn&;ek> zDFSzSJ@ix4U@h|~171xt-u~D40g+`qJ<1J*C$4T9GDD7326PDOk{Db`~y$Ce)T~7WWtuEoZH1a8;>SF|{tKP0Q8t*2Zm| zk+W=MtodQe2SanYJT`ghH}JJY7OX{t?A^l>+_0wr<07-keNQ*9s5 zhb(dm@o=Nl_>DYA&)vCv&o@{s?HfF;bwQxq4SUcd&rZW)TdEQn( zKCox({yL_W?&j8UOAQOTGdfubvCKtDo`C%JGvrRy`rj(pCkHljStQk`>X=FB(_i3e zH;^v-OdIVR!T$bH#7O8KkaQmmd&?DID1D(^XL(_%>afyN7#$ji4O(-mU!{@m-*4CV z6+cGPhi^&DAMtDLTxtG_uKVj~PW~~FI;@&ewuC87*?9X#aH`Jik0|r#u6H@74ScS9 ziDNt)SjDl;^^8}Jwf^}ba5zEx<&Km-3Vm{Dv(x8HfMtlx4~}q~$^w)O)?1m-XtQN97)v+^>M9}-VYq*iTi_i^( zd0{A$Ga0%%oHc>Q$DAbb(d!S!BzsOptc~j&Wec+{T3g9uy@3>4QUM8GUM`kYA%XrHN?s3m%RJ!a693v*o{Q9 za^s-0X|;c&%zw;yFMNcdhW4U{;GbGrD)qP6FZSINAyf*0J$Y2zlWQNPykFp9FPafr z;!KOSjMZTbeltw+YcK}uoOG=H3=-W{p$2HV)gfJRdi2&o=X%;_#v?k+I&Z+6eSN*; z$eGn4oK#gsL!o@Jhf1?0;7u(;uL5teSstcL80Ahc=98~ObSK>46r3IFzKNX9rfsz| zJU;OKNJG66a}-iBr$WuXb8wpnQF=9RwDZ;!~3d>Vj4xQV6H%fA|rxL6)uRvZe1ImfseRj0XS&ubb(y_A9*Jx_w zRlTY`j=LSHjb~IRxH8z*EU-?wjkTq^Y)qL=%BAupwkr7Sz9(^E|r8%piaIIYL}!%ZLngcJU3qlt+=NMQp!UEjYBD+W^d+o+uU zWg`Dz`T+v(sMDOK3@W@ph_t364h`Zyu=pY9sZbZ_j|sukNSQ(TfeS{iWMZ!VfDu;< z1cdIS9I@t&Qrz-*BrPWmm=`nAy+!MX+QO^wR5uzMxQvyGz9BD{LTkX`ZyWwjBZhcg z{(BOmyI0TX9!_R-_u-lW3S%Mu9>?E1_=Equ<_9_jnPb`|~VDcgHP^?&TcZpUUV4;B&6h ze98pvSYUp| z{N#8xSq;ocHCW0LcBj8Ib6Y z57@@5g{m!rQb=ywh%2-a34IBzMSo4TaB!1pOWT7D4loftlXheexJ$4L48#%4>b+XJ zXMffU=4I?Iq2WO2xpH1AP=>N(Pi2-2Y&TT~A)o_hNC>omgT2~!i!0+ug~<(;m_xY3 z%uL{IhALAU_+$i}6qn!~XifS~gsHa?0?*`V?Y?8-ca~)ymPXqKNlxZr_^}#?e$e{n zva}->-1XwF1$Vo~%Sav2XZqF?DC_g#QZWRSNvJjKw8ly)-lQ!IymI%Ua2c=-rQl{E zo&+!=X?z@jh+3d}R1&4=2U>e^oXgj+)vwIi z2A)N^=j(wyXda#rwbj3Z|8E5t^vg(PsR=wmR1>r}j5avy4=XXAR*qC!oSX~@1D4fy zfRv6;!QER%R$C}iKzhx6749z_sTS{F`+l(~FG!1)j;yrYj4!@QU1P{ULgP}AHU7zb zYV-XkP;_(W(46 zd`Icw+u@hv8fX9|K@F~J#%T?28>h9;kN*PeN*o{bvq;@dv725EtN;%g3GNDG$NpUY zu@13csJsn)8s)w~iQ+l`40sHRAxVpN4O8qv0n9e9ls2DVs0W!?5A@9x?_}IPG)!wW|Hze8 z;&r{ouR=<1PoxyDpTEPFXg_$r7KCVu_roqd{}>h_3oQ%P-Ke~m5#OU?zG<%GC35~y zqWe(JHU2B<0VC_O=vpytBK^K$4!SYSR)UG(0&;GK{b6^EqLQjvZe z`Yew(FcO3RINz4V6y4eN$a(Ccw-TJ@B}LftPPmq5oL*uH2!pDQ3&@=I&; zGJ3)CALZa4?*jfocYOOfdB`wPQkJdUo(OQ##6#I>%G~RV0 zpOzP~7n6AWGT^d+Y7WpE>>Z*lf3@8Y^R$NthvKz&rB>s$M=eON_Jt(mooeP%FVK?G zUWRzDXUgV^@xJtvc=LHW&JO*r@xJ?`crT0qQ4=zqr(<6~M*Dg4813f?W2xx*{iAd& zgh#KAg`QD5Us4&+7T}Sl0QJ=1$oe&V)CyEd0gxTBfuT{U-|AWeM7@=7a~TiARsb5} zTA&PS`F{LwA^m8Xt;j_>c1OMNQk9SNV7r?`e;)wn-VEr*X#d|e0yG`C?&$sZM&l`{ zkiwt-uTr=bDS&L_60yEJk%nX<4LguGSJGGyJh3EtAJWiWqBGQYm+0K3^zJpLMP)<( zbLP3yEB-aO8gtlB=c>ztSH|ISc8!6KHxi&D@$Z8x|9?l~Fm^asXDZ_ea?xcz{~nz$ zyBi-ByrnO)WXtOWI|8xc3hx<%X6=nn*_%v<`{weZ1 zyT5ZTp*f^;=pMArY^0KZ?CP9DdwdbN;I8DIjx4K~lPlxu%KXa?E<(#)OwBZ`@zb$( z6#en~AC>VJ!?gAvxKxi;IN5zo8$7qhf3*!LgDUXA_?rFE*K<+-bgbShqSdB~{mObt z%=`6ok@wW-C*T01eJB4I3$%jLn;QKKGzk>J_d{L-snPdv?@IaTOpzLWBUV5bao}^E z$o-c{yJv*<^Q=o(*1Dk~7HxA#tWOpGmlRDx{mMg$@QF<4(BIj=rzLtOANqK@XIbOt z@GCsWkZqV#n6lISM-f{4B>4TOWZLJ!Z$71KV+dBO(#$_AmdKN2UnTKL|4K65CMi^O zaZEmZ2K-CHa>X3{yvZ&m9WrE3eFdxSEHcYhEq^s>4!gh%#=>p|QP{d5Rk+!ZZGIAA zIg#5gN@9g_$Yma4=GuxmGj}es4IJO>MA#;`C7QYMf&Ur`VXqxOhx}P_t2{v_&HO6q z)uf9Pd5C|1Q9@%Fe2bNxN-`VY<1S7z+p?z|a+qza!Tm7D^gZrOwJn%3)z+uDm^9t= zCBnJjP06*rhg?t@7R^Opq{i{T<)P)8Jp4s*iOzy?k7vb#mN*)$* z+2$u48&YIqsW)=8F8+TF(AR2XsMK!?fJD4|PwJJ9={G@ibEJ z@NCQI;6IeNni|zR6&|)@a^vX0z&J%crbgR`$#p5AQfDtDawK$5cy!>4aaAk1t|TOZ z)RW36_uBR6Qm}hbSxRBAlWO}cL;`${EIhn=r`^497$<8ZGz|lNeUM!P*N!jt!4{91 z9gfsFRG1Z6r^Ma7ooP?u3j@Sm8u(+K8n~nXT+Gb*EYjw(xZ+j^8c)A#{lqn}T~?V# z=GOv&^UgVvYYcB$Lkcs33ZF_?#??9W8rErbU5RzQOXjOGPz(rhzgq|UA0qdu{l^zG zvo$~kobQWK#761gA`{>fU8sCtCp?GntzrY92d}J<@i$`ygx)I*qB=i%g6DLS7JGX4 zcGGsftTU;SOLEh=ZzL69M5*MG#ZdNCDvzuL7Fg--g`az%FJI80rhsAUTN;6UYs%@R z<(MN?eqW0W%9^FX6$&Jm@RwaK|VH{M8?S(2G5q<^aKnjBdbRNv*<8=|gZB_RwA>E6XL<6Yxj%C}8&|m_}f^Q_-gd+oKFfJ*HIc zc|TI>tjtUg$x1UR(~CoBQTnmB$TZf_>waDmRtnad+8Qt!&XEDNr<&CnAw>hhnT@eR zmhKc=to$Zi8^r5cK7ebZc-_W-i|by*dEVtk8D5Bmd3ZB-dnlpyp*;Hp#XjX^%JhMTT|^)`v;;I>#vqXkydFnOFKnf0A%55{5b z&Ha7qJu=~t*o#y`j0G+jc0@sFZt{ZC>DFNWG6rKoed&K62Wo+~A-QfE@_i##)OnfS z?ewg#M$e76>zAL(_K>N%@T6tuB9oT&M)J@8HnY0b-<}CG%HTF!nI$K|9#!qfEIeC@S@IGPehC6I z=PXkGQ-tJxA4wM~ubFd^_lY^To^)0*M>PM(*up(Zf4Vqd$^GeIVUEX3%di)-`Bzvc zXg$gI|G1vi;Nx1&bs9HdCf`6*?i(g*NxqAjDVZ{BEv+TfHMR6tmd@QN=V{MWqrNn> zzMv;iz&H7I-AW;S-)aI)hMn}Tk657Pg54KnOPKxRIm3KJTmCDcB5TRVY=KMRAFLc3 zczKMOg}oK#xNrM@`ffb7GDyI`j->A!n3(VWf_X%{TUG{?C}tw`qTWK(o*X?Fa-^w~ z!a1&d*Vw?5V`g3(mRb}-s$CaUKvPXUb;Jt)5h?!AJ7@H2uk94HXlxjV1Ax|bqqafEVO%h{naMgk# zp$+T^{YYhErkhRYx~qAZJduaWi9DG?^ectnp9mX5GzNvxgK!`6+!Z|U`V3_mW3_sEN`!?;$D9l-pT=m%QX=tqxI1m(UmL!u#8C<~QUX;;u0 zYGw9kI=Kk9;+b)_~` z;A17dzq~|pKaWfUlZ|A$9&=n$kj`*bmkMuzhsddPKD*LuZpIihhI4QEHj;ZwRO}I* ztlF*i4ORjH=mJ6-D-pF)p)0TUCq0PHW~8t9lGrN*6Y_p#Hj3xHhL~6b@~-yKcvzl6 z3%A)npNQvbOVZvLZ_9X$O2qhiz_nOF2hVJPWAJ$j&5>)}?c6TCMQ^ zS_}WLZSeov&yP}m3!;zeM=UOBi@LSbXyFgKY%S~H9iiW)Hkyn|?>hb<-_JAA$}v6k zY}p~+I@4Jt^Fu41f^jq{ltj-|K_5lrZh>_?FkLer(fIW6m?Lq2yG7}RV@3;c>-?hw zz2oyRGbIU>3s8bys1b6GQvPg>AWZC|l06dG7yvQ7?|9j`fRlB+0K^0TzpyD!10( z%mN+nZL&xD6h2A2p7Oc(5K96qFLpqNmgu)0UB4(1$l^}69elDEutUATYw)ec{rgDi zBlC$#X##TfyDd4uM@g(oXcE){{4v8%GXp6qWG6g!m3ceh|pD`A2vhQ$G>ycK3>{vZ7O|?+UoW{Fg8#)dSXit*BQt_e_RpV zv_%MXsw%lj?wQT;{Wa^Jxh1~0PIadUNq$LQDrfL0LNT0O^a`-sqKB@{q-b7gFu_O9 z#%G7oD{HK)}vUZ&OR5WeWah)3DXEus`EU9nb$~QU5nAOCTK!= za}WF3Oo|&ar~_jItHxD=$v{03uDp}hjmQQvJK6J_$o!nlcAUQ&EAPzgFg+L8LJH>v zGyL6}JGe=H`;ulh+rpOsgOHeF+u^8`XZYMn%Q)88tEgZze7#BKT&jnWU6V9|5r&Qg@f)k(CO29j;{aatnfikG;PDj14uT<@rohkz2*au4K4ka{XF1Sb3H z$@Yrl*!?8=kyD%)ll^YwiWL4Pm@HI6d#aZ}%IybRX<rwWIwmN#2$5Wk4(aw1?3)>%ji}_DH;!9T+Od zzVgaGHhOaJaoNr^V$Z3^8g79FGR?mgwmMVjoK8|a%nZ`So*$b*x?@wJB?#%yv&Se0 zNCD=kl&DvfQL4@tG-I|1$L(l;b5V8eq6AMT&bTO8An?j5vm{Rj-U;s#dF$wm%&r%f$Qp_H6|f!bUOvV7Cie2XmLGD+_sk|!R>#0q z_5hcwfxP8sOtIJgU1)oG*2eAS*)`kCu)@KW=AwY({0P z%qyGv)Y=+Wv+Fo)V(vFGC7PWwp9H>JiCNLwg14HD3fxhcRnZkM;S4$b4jg97~hKqalYAWdiJOT7Co&# zjA)8IO!TK=J#q)qf#x&?w(&Rff8ZHDoAU=s9jZF72%fL5{a5+dFoc3b>Wi55#G$;S_03k3nOa(H1e%YDXcPSyjp`7r;Akd zV-_<^l_Bj|B4)kMt2;v5jaC^t;wo~{6Z24qzfzmr zdwR9XE4`EMcNN{kwtpFzSubNGvv>XzUx3{R`wBAk`v~eF=h`}`5bFRwa!?B^hA+Fw z6gn;&_{;oTkp;jZyt#of+b$6E8?}si1;QNuZp0t8{{Q1~b*pA)qFVxn2b?8Be+!q1 zdf?8mln{8`)Di-Fc{RoZtObb#ef$ZWH-VZBy%WBiTxF=z!3)f>sgynSoFemI#u>bL z-J{6dXZS6zKb(+>ch99|UNkP^#p|B5Op_te&ydr+K578p8wu@!Y>AFHC3a2pSB3SP zqP*zdUPOEOaVoHm!aoN_Zm`J6-{cNyWtvG6eW$T! z{oVK@TTIH-k2Ub@VRFqlY&1!**D)C?TvetN(;;>tf0t=qd!la}#uM@}z8JlIWWYU| z65Tg8V+z>rfqC~F&D+4}+K3YKs6P7q zxB_;ul`RI?6uAv&aOzc3Th!>37^LsO8l{0%Nsm&fe7hW)uq^kHwcG9HUO!ubb1<;Q zrTTyYUwG`_^hqp_Y?*f~-d1H>;9ecAWyR7!TkFhVgNvRmF(Slq`MZe1d}H-ju>Cq> z@9n8|wEavA8}$Y{fBA&%m=}R`FzukWm)G2*{b>iqBtWVl_QO{(=QBCX4eND6%hld> zj>jFQds%`}&tkhc>~$Vd^s>YcDlUYVOTBqF6W+bESRP6 zewxw|NIT+gdE#c~9B{(h<=#%C26i0v4uw~|+e7dA*%m$tt6C>Ut`74TY~Wx=mlFLQ zblD{IuTL546#ZnI);}HIcMiduQUGZVhO>5b7>o!B+vk|RVlz!(igqXXrw8T$wZeF? zFX`)stQc(8yA(baHv0?58LJjMXw=R^fKQ~77$ZFXE@Vcbg8(jm6WGzF`%+&Awq*+rt- z@e)Gc_{CTW(YE3q_B9EuBLfXM2c|?H8c92mz3)6>k+I)_|H`>m;ECb*RR$YYXQ z{agklaxa4mRPOWeOItSM$`mLdEBLd#KH5Agfo%zF5OS)j&$2+=SQVbM3A=W^cydso zKi+*V9Q#HsEy|Hu~okt_2+{7gq@f{}su$LWmo+Ayul`D3&muZJBaMXJy` zC>eu{4%f66ipF&C-76VO!T+&QE&d-JO~C)q&wr}L3b2yty(Gsun6?m&?QVFXA>h}U zN#w#5NN}^Z3oW$9wVo=&g9eldt-&4!n-c1mu^>%6GnrTw8jq zX5yJPUVg{;cNkrCXJ96qu?Fg+pN!C2Js(-|rcC$$G4}R>O;z{*__;UFY15=>X>T4V zd1#@u1xs77P@EybN+~{2WGgMymZGMhTbynSf-`{5(1I%sXphF3jv7U zhH2}wE#Q#}P9&{X(ODK~dD!uGCFpz5OK9A{$LR;bg*Oo1m@$zsIbWS+vgIKW=;Hs~ z4W?_W?4z~TCabuIZJm6c@t@UP{0M%;(3kciYQSklOwT#)JezeEb}SB0At8Tn3HhR- z+~!x4siGdN<~?_0?3?#a;N7stI@kq1PR%#}iO=0(y<^^$z#H_xZl)lf+1a3Gt86Xm zG_}bh3^uH8*OuFK>WkW_?gxbAz{lbiHS#!WRrbVffZqX@?bfAhRx`6G!{uS? zJKby+A~c-2Rw)?l!Lobqq44Ysa&Ao+aZbGsJ^A>4wB06LUm4bDvGwEBk>3v$hf_&s z!*bi%^plA2I;pJVX!KNVnDL&}Y=OMi5LUCvB%a9>EVIQ6s%+1tZdUItHCnc(ina?8 z+x3<1c}Rf!;5EGR+=Cf(2lm(A%MI05+S*_%%u}J=u)6dJ5ydp#X5%%Tq$x&C-yJP> zkm(#!9R^=p+$i*))OL>FzYO;MGPTZmGC*+=Z*HH1quCC23axDkklyIMG>FMlY~C%rTgeldOgVP zNxRviB)q9tbIri~?5q(O4qLOj z*biGbF}x2F;Q;ytMUe}eS?PkR0Z`>y0h zUT3>8R)f0U!@0_Cn*U*IayM;J781$W{mcl-lfh?wxc^n4E{~44_Xg7GcSi`BX z4|)&A@IPVttdl*1;Q`z6^kU1?)<{=}P6i!G0*CR5`^eNV#v#Wo>t$wc(oNHffNUnl zjzG8hb@*Ag1m zWck2xjz+N>$O&6lI%i@0MlHuBN8XFmwqRzwL`zLh*_hU@bd4n$DCN(FD>%v>dRqH( zc#Ty8Z<2L7rsRK@v(RryKWev%&xvTfBUTjxAIZw40)Mqmj_XqR6Rfs+m(wVXt1)`q zdLJ|MweRF{&2}wtnUj9hhV}Y-KHahZmd}Sb@}c!Q+YNmB{F`gTqBc4$G;Tc_)PdH( z0`518PWnx&kSy9RpTc&EX!W~3C68;S*v}!-NCZotD)(9lS`KUEm}7BWttv1CUE})? zFa~g{WM+^ou!YfiP}CwX*DV9eW5}+ja~knXvWt9$d|#)SQ(pz4`3x~x(xOY__d^R} zl#(jFC@5G+Ic~i7p5c}u9)RZU0ERx3NhV7d_F*@mousz!2NzClh7>-l8TNSee4Hst z&iglFE*!^bdLTor6#}0zAw<#1r9mxNuf*pn?a7gvk=ll2L=mZuRW&eks_KR)n?t7f zuIy!W=1-2?J(8`_8}&uWku#%?y#IjP%kdy%7(f~kNx7SuvKtIG`F2}IE8^7#j`fkN zm2`e!id1<6A!7JCtX<0j;Xp%F25pUhy>v!4DS_rAIdTm8m&<6ki{a!*!{ESpoxy$R zk#-VzsLG&=O+xfyI{4NYNch`FDb_xED(b-8&fIo;U>Zh%sHX%jLK8_LA-f1hh`^{r zRBHPM^Ln|3VgQ*RC;rJB9^AM~cQyS>?z0V7bjvK4(=TyVmWMX{4soy05Oovt6rh1a zwSH@fGuh$+A}PFD7nC^8*S%C{s5L&C0<@Foz_H;n%pexQx3o628P z#7nV${}!>70+V^A8Gc%()fpkySOWf?5{E}capSzUX>xiEtmP1ZcynE($v7X60gM7uu*NBEiUtKn+v-@{+eWuQlU23P@dv=!T| z1go{c^XfFF=hfRNav=4&OpdGvMjYMEJ7bn)fzPE`m3$E#xQO*=He=n zY&6v}Cex!nM7FoggM9>;aP1pD+c0^oz|5SkOMEBYEd*)7vctzyb94)Jre`DdgvH|Ew4r0S3-MoVS{-i>uVqH zC+&~_xty5HwXAu{h6gw7-e7)ohjn6)-ta~lMJTA|xGA6B&%F32Yg(wXfyrX>E94-ot&k@vWJf#xg$RuB_P zCxTv8!w(t`VW*%kbmT^GH6x@qBu5SoOZaFay)ha5e+(iWO6t~>7Tf*qhw4f;jg81> zVqyd1uhBbf$&nqy#fYRzLUhr(2BvUb9b;DF{WE@D@{kGPJl22oq+kuk4yLx6u!SeM zSS{mkBj$<3bAmfs%OKk7RkOfB%tQ7R*HYIT_-+qJ&|6*@W{hZ$iF*SlIGK+1Ob#Sq z1v;!s^`sE4gEVt3iWbqf0HRKbLDGzXBb&kgEcY4w$b18pewUQ)S}o+pr`2>?X9q#P9bgV3=*iVVB2ad z*4p2@?+N>9E*X9{GA0?ZtGv!NbisxjHaf#Qn@RcU9l4 zdv&V_EerDl@wQok*TNgftE$w4ixvwqMLUZuO#Y(9!tC84;?=^_>m--BjrFFsQp9-J zQn2@D0`hGl?}99ueS1I+bonxk%qj3B<66DG%&rTZgpF9_-E2P@kZoIQ-^@wy&q*gmCnKw}*#Yf^zbgZ>EqF%IC&`TFkY_|Kt zWTyt@xdN*QyOS-t%&9!K45|?{2PU+oY~Kww%!f-8TQj#V$P&69E=_3NyP5v3(nwk} zokEAxzL8To38Qk@OO-zIYZacZ^0_vvfUmW3ekzgrghi>EC+zp3O&7y=NzKR|$HP-? zxB>I}8K^!H2KrQTTiVW5^DhRHckHw3f{);N)3%CSkKkzsH;dr={C&@XM}hC@(g`l< z*mH{B4}bSQS!*WHH|V|6Hd@NWqMOU9@=b6B!miAVWRF&vNqfN_?NC44R*Bw1cIH*& z;TJ73JFmiNe|kAHhvFaU0z>_)O7Dds_f0$5Y2X%-Rn5i*qwJje4KlVh|tB%_$TDVZNOnqgs)SAhn+h8EM+cgA{^#W*qMNDLb5Z1WQq{+ z=2IfJfgh0ij9u1=T>>xI3~Pk58#rP}faV8gP@J>;G38u*op7AcG$oQVKvCh@TMVDD z=#fVUsSodA@&$0?-8I6(r%Ny6er?V6J8(bz0$AQsc=P>o{(g#b^L9A#fYh|E%s?hb z;&JL1ETkSBupz>?0J7}b3_UQQHWOiyOe1I!ZX?F!HAX$H=?r~RfMU08Deb`7fzk&` z_m)lzQ2x26OKTzBkN~xdFwik>-z@Z+0>VN;i`V)od<+vi{F~i)lS%uMTz4VDO%>Sy zU67Y@N@h|^4D0tzgyt#h-uvBDrX~6SG;#r9!Hd?fLU{%!W~QGHVZYv7pFuwE(yY|K zLA9 z)0GNdOX>?F0go#E-Ev1l5akB5Nj|AB1-?lv9}-wRni9*KCGd-OFwmq3fb*Oc#M&^P zuh>U(UCgmr3-50Rf;d>7va0VVS!J*Y$Z?F^c2IfsrSZJ34AH#A+pp*K(kBVf?k7UG zEFKbKwKc|s=n;W||3H(sLJwpaV3eRX8QzaCYF>bM+YYRGL@iXocb|x#kP-(ld^TE{ z?pF7}vE@%>k-Kcu)cdVW*C+04;rNujx}EMin_8PK6xmb(r%k5*)O|Vn&X9DG#F8(} zw`Ey`w;C*Ql||>ISYR3hj|Dd7quwit94S|Umk2y736Qf`pj38A*pHyAC=q%d!rnGH z(lU57Ljp{C@yT?7norcmTrXG=gnB44$29WX}gff-w6tIt?xqdCc8ofIRlJ0YDXM=}Q}nu63T z@t0{5w#mG#uS_FHzrI|x#I`a+u*=D@#f24QGSm7hSn8gJrXXRLJ0rh}_G+D0*s9W! zY(;mrTgS1$OzJj7m*y+-U(qmyd&2Tv(nY9v?-PjDwS!fo5F|A4$H@K%w=Dxka;%3W{HZ?j(OhJ9rw z^*~%7mU@M)Qcmu*RGkgW{FkeGFi&+Jl6&$yK@mqSlg%>E3}Cnbon=!2{!;pbXE&-!dFy<-u_x zzE{>{cJN;FTjk)RQ9sv+@0O;8m`eIDy{*w5N)*1^(9 z@50}Z`Xth303YeC zA!4Mz%;1D(Si&I%XX5NNT&2I)1~kpI23SMz47o1}+VKR;RKRwEw4BW2%*gOf|4a1v zwKAXDgMWL}Een9Nh*&ec(-e3fk=%QNT43$yVVUr{x4BqYz_q;9q1~Exjy`GPpa!$Y zSMYttXbRF2r4CNOmCFOgs8QqSv%D^Ug69A%_DLuKdoCH8P*b-IUPn0VNx|8@#T=3f-4*a9fy@XCS~Ku*U~OPLElnlx+#QNOFvJx70lVMN zV7sO@QF*{ihC1eult8*iXsoYM;QO%}xmW3_)+)Tv2=*ipO@P~`@&ZHa+=257ud;Om zuKwq_l|NZ_~2kD!rsu4o+O!GpQ8q7Yg zho^Uwi}ouzdi`3u0*>`78lxlg$i~MA?Hx%2n%2?iXYv2QUYq7=gH8Ey_s%U>-Fcc7 zI&CM5oHMaw-h;W4`V@6qi@InpP({@7v`!8^z{K}}(dgc|wo{HC?XPLKCUvhaP3v5~ zse9A)K7pFu=o8f_@mO9-U9{KeJMMCQ;G*qo>JZOt-CLbet(_zd{3#!_-H5Re%W8!KQ;zP z_xgT+|5$${-LLh3)3fNIk54=vK1mge=H#dK<9$TGmm{R9LtB*p8@(iv{KyztEmNzM81r@ zzSSRiOS`4?f%zTSuN~)RaRXb$-gmS*?jm*-OW+K!o20Fqf%3oYQsnAJKa;^(@%Z98r)32MJozu^oS>Effr*BqfdYqBe4Y* z`yTijAXedPE#|(Wi&|>!&xRd0S5Gw$X53M&qN(Jb9C*aY!EMBmN}B}|f-3Uzu&g=9 zJPNPy04(5)$*+-mt}6Y!7u6wHRW{lhwQ{fyRsadZ&{6K{<4$45YXRcLQk`jEHsony zRsd;XPF(&xGo1-OrjmQ4t*XezVa$e*_o&aBtc@afOR*vsb<u8%px$TA;=9U*V<&m}#(VL96CsE=5<4$ad8ezeWz0 ztOWmIFwc{S2Qeg535_U!X^5B!BF&{<`mC3MRzmY#U7Ck6Yw94|vY|gU?K%YAsx+j4 z&yOnd(_sa;W2ohQe>mGIhs=5@nm@u!Heg0S4EFZNGWM;wy!@v`)v^iux)j2e^i{Q2 zFth$0b}@4ArKon~G16Oc4SaG`eru7vhaG4;cy~F}^5^gh6^4#Jfp{?Vuqu>B-;s}2 zGwox{qtO@PNkQ8Jm<{F$&2kTSV7J?hH+>w4Au4c

egHd$k_EQO#-1kR}5slsYgZ zo`R)G0ZV#s&3X4GumMoNzxQD?EmJMyHV5WsCPObF(~wNr{STLBHYIFR>oPi|+ZAmK zTq?afu+_DP-`zDoN98T}GPn|2wdf^~U!fuMZ8aQt&t-s5OGbwh~rYzU%BW^p+rrj zUadRhU?Z2~^0_Ot`>~e#Yu30RL2wCP+7eASTH=xmNC53){7L1o~(WnaNvL4{4qhyAcsSMbTodb#dJNAE;jIN|f zzRQ?FslVsgI&U~2;eC$RV4ipj`|m7TDx}kcmk;Pv9%bZxlvVq!a*53sp%?9}5yQ^| zF>QR?(Q-(73@=kjB5fzifY!MbLpvLn)JVORdW$xrqsb+0TjD+q&Rn%Fp$%Re+c&|JQ*)j)K#cd4jjTBg<@AJBiZ9+Ngf`10?nU# zAfrd)DT-EIV6kfx?h+6W^gWd-dip*?Qe zn<-;Q3RptvUVt?ejQ0zIqqLVdL+Y>QXfLKcM0BGEmyD#pOxM3ezW>r*lIB-=)SVQ~ zb*!gMxT)-7zU-(k#$!?|EhmBIWwA@@rTtkkHU=Se({g)ml>0Y`NBC~Je~-F+x7@UM zelrID|I7W4;hW1%$6cB~3FZD~?0rsqcq_(U$3{+$v1d4-);7AT+#9)tt}ZuxkhBJJ z3jO7WC>`Yq7@I5UTdPOel5gtK6b(w&!=hIkcu&r>U1KfNALH9HL}%6Jp$U+E9~y!N zG9n&G!?$4I=o3=N0QaB83cR0SB#ZoME-F!q{7YRzlo)Y{E-~a@c#vpA+=a4vV2;Eei!GKSbwe#Dr2RScph9-N=%s!@q82Q^DwVsDR1WD!_a=}u|4!*2{x zC%hCO^~B(LTdfp(-f+jkAum?xT>jaDpaR%7rmz*_hgek*I@K#BP9(v#N;{JDDie~IQpc4bpD(?9|Nl`K#AdHK=67;Rx;<1TcPthKA?^zT7?iK|_zBjk9SxfI1`IxyvaH)uVdjn$N zGmCuFbZKq_H%qsQdnw=wKo7RfUfNLVYLqn@_WJ{`1)5zUS43;-kh(;z2Vq-xyFS-0 zfJ~X@I?lc80`~VlHMXxfFeEARm#QV^YkR3^NdlN84g4 zemQp3)z%4+%3cO)*v;$q3qXFPT!j&M?tQa%C-L(gx1XKde7{aBZnfFIf9+O(XYKye zPPA#r`Yw{I3W+hVt6G)tQ&o2s^E=ig zzY6s&AD}3Ou$|95>dfeXPcOd%AUnWb?Vqz%XE*E{jEaV+#C(lQe?BwtKJ=@U_u~6= zSKr88&F8NFueqn*$o+o@k^9`S+#%17mpk3B2G%y6r7}ZlJ5@lpQbroa_jxLy(2PX? z73a&Hf7E%S)X+@lk~v#5I%ui)10hNcKLnSW+! z1)VnJ?+f9vI?*T7=Tb@ZQVj8J-~v`gghOg@CTpE3BtBIVdc#TQ8F+!FYr>EUz-ttln70Q*bCO?!ZTX%63tnNXdNnVC=qR!)~Wi= z8-Hgo9oN84jQ9QJjrW~~lHUBzFWz|P^oywEx#_ox4_x!;c5X+$J5_j<4Hjj21u@G@ThtL|SZBPW5c z`33Yl)W3fux_tCoqZ;F5&elR~uW7xts5kW!lK70!)Fwr4;Ug9vxcD2ow*uGvbxfOS z@H|iS>it^lL;SBsa6UVG}0qZHqpBu@iMeLtwWgQ^w-lD@=-6| zUoS8vYT5&8Slq`n;qwp!*%V0eEV`i^SD}rl_EG_#IU%pRq>;eC=o+hs;ee9I=b>v- zK58)%oj-!~Xgh^Z1pfz9H*$Wip6YI&qX-P+wSs>8daWq4;Xw53(Xm=h{iasvX-3FZ z^xvF#2CwO)PoC2SL^ob1Y&gK@3#7%doF~!t0&C*8bAET!i1uP~d-(QH`xCvs@fJ~j z(;`@_3W4TM+jZJECBW6|CHP`gi8rqF=ux*e$mv{-lDC(To@(4ha}aETL+r`+pB{a(@24fdB)PK? zzob6MxikD{S&_d?LGccB*gc<9p61G>$F&tIH7D{L_O%39SB<;CT&Tb?02Z6CFM z7npT;>xTW+GP?6x4C&vnpEZXdb5o6p7qd(}x*n;iWhKL(?CL_KG)?Jo84yQ&3F+wC z>9Z#E6qwcfseNHJFz|icYS$(3TU~bjJv{bgpfyL^Ml<|5ZkmG+T8#bpzY}OjkWG9V zCzU8H(1KBI_?SfT4q6Z~{)X?DC%6XSdKP0=>;l5-^9j!< zdxGdOZ0;3s8C6@8J&IjhKRaFucIwEy5hn8MA#r5Ipg1BKVk29@D!s`~(Ebzy*Ky~~ z$0yvD8`p0>2A}m#(JpWcbpIuT&6A#GiiOz)pKQ^75&hGULNHaEf_Zkcw$MfQB2#(Z zxg3|{7%>;RvfV;W9&EEri2+e~UqtVY<-5KNYls2I3t(eB4g|*&%6u2cUFR0O5M~O; z(iS7_SC|nCU7v(gz|tp2Y;Q^}WF^S^jyqYq+77y)%0Z-0sb%ep?M*=R`4T$mrb8l+ zsuS`O=9VP#^g?2kK(CtIb}hOswsD~dy2fI1E!q_OkJBSjeEiGu(-O(Y)8HW|0b2T1 zr^j~H!S<3st2G+@(&;RBE<7nI{s$YhY@sE(neb}#MaVfpM4?i~Znj4Zb~@Y%|4=qW zuTg$%e`CFiOw+^fgQ84vp<;5>{-slEXZ>Xe5ZYOJQYp=s?T<&R;$)hPqE-SaTj)2q z=r3bNtX8e8m2%yl=UY0}WNu)<0+d>!MbBL^&}&ylrVpf=O$}c};7IF@)Q&`|BzR|1_Ms@EAVt zhbd-c>z!A@b0hwkZyBGCqdU?%An2jh;8(rd^+A|X5hBDVG=-3|!$fr(K8%YYA0Y;s z#dQHbB7DU7M2;|7ZRNi?q;=DNG#&N)@eoUXWphchE%OL#&>rXmCVZ!@(6$Nws5zF6 z77iYdt+wWJm95u7@1ni!zM-w|Eszi1q+;@Q^cRCkS*e|S16R0A?N1iwxoG+~kw!E$i~ql3a4(Rvxz0?jcE8^B zyz?}?=+2` z8EciR(O7)!ex^m>W57F^8!!>-|MS9#xR;s!`w+=gn^Q5X>s{K;H|$-`3LyV4L;g!M zXbHrj6qE{)L~gxC;Mcq8^E&DCrY$_D1OkYu95D&OB#e6&qwT9`ZH$<5(K3(I) zq`5}MklKlOMJHkdY^nR^aS4u$PI&P6wcy7sCK7)sbm62NCEn!3cqT6Ztlma^xT|r!1Sc{Wq4En44ypOi6;k7 znSq`FKI9SBuV`k#%y1P9Q7L#!0>26VTz;*SH^zrL8&1Hx>$8hHulJ5y99n-?+jlC zbC2|6L|lRmq8PL4=&0Gvfg4okrM-MjT$mvUDiC(+vDSo)tx1tju^TZ`&vKuxDcMcm zAPN5NymtR-C)>&b6X2!u=nebSK=t->r%-Ff&J-|t%`B6)pkAJqFk{rNmtz$;3vd4| zz#mcvL@lX>AV}N%ns!zI>x>EB;?~KbKD)^4599+C>+@)TJi&j#U1>|vQ!PAn>^%a# z2HvK7+{uA0;2ukXNG~&SG_`$+;;94 zW~2jOFp&Zi@Q^hlXh5q!5pQqQ0|~sZaRw}+X2d-sa=huX3yk)6=8&mI1N!^#VzgYl zMoq+Ij6`?i>}s?I-U-!C;M|5j=%u*ir+cxl!hQ+-bY^DePFrfe3^`3j#EvIKgu@ zdVVCenLfL3zl4{4{W*$jR0cefTu-MCXSA^7|XZV6x==5VnSbPhl@)y(Rs6?M$_ry zv~CDku8;benc;rcBnuB3O%u;Nm0&sZi@Y#+uHd6K_BN(z=Y)xQc36Wehr(&b)P0)$ zGA_j}b611oyjq*$3iPWDsRuIl6O9@&q?+?{)!Z^*dQ&{(AAR6^67vaB z;1ho_9)}!iR4lj}^$aV@U71|15|}Ot<*OLZg}w5iyxd@;N81Ob<43<9l#~l?dN92n zFa6+AM)f}Czwge6;MyQ5M6fW~Z9?BO4bikT4bKPyzPo?Ng@_Z-*bVTwy%tp?Y6h`B z{Qo!KC+6>?^X#|t8yckP>D>G6>;K}f)A<-OF`_so!qX4Dd~s^WqDS38kRChg`_}VM z4?Dj1`G4i}qjJYL<)&k4VE8IDh$^s+^V~lBh*Q2Zu}#oSrm{e~FuC%2Rg>6k_LBs{ zOiK$Uyx2faYFPMPwgwn*I&KcUZdHVsRvFOW#5rl7sL1EAXJ1U3ntJ=pT&OPk5luRe zD|WNDK3!TjUl#Z*EDJcaZz*N4RvTR=@(9_Tk?^8L(`?NPCHOisdaKS<34F&na5HP6 zgADkr1w8-HquMa~i$mLxVRjM3S$-a^84(0N4Lh*2n2NI>;f(I^DpbG0wFbrQF-I3L+h(H_TS^)D+n?l;UGIbwyceoYRs}FaUZ`LTcUrH7PKF~#-YMV7OJJhr zufeta_979Svx!mEit#@}racfO*;F%iz=8?St0~f$QzY5Uv4M4oetH{> ze7sce4r>szSe0S5Nua;*X;Z&drgUH#OCkH-9;miT5baKa_n(IkT30qaq^FV^^y;>l z)L*QPR4f?JZ}+f`UmZlPQmhT$8)p)nwG96yz|5_+&Yw4HJoV<`nG40^?_|?(;XQ)D zMabGD>rar5fYClvSlIQHU%Jyq>;C7V8RfEOD$mmvd3czaJe5rF3!rtIaG>4(HgG!3 z4Ku*aD+8)sJZh$xHJeD*Q9h@cgywV=jNde;Lqn6w#aPS7a=H^e3UQvuf%Wu(J(}^< zH(=TX))gWyM{76j>}Lu`fo{K!tVLT?)FeXc{2^9+`3K;3rOFK57QgRtVKu6Ux!YV2_b(xJ|w~3Qx|$`T+;YDIv6`1V6xSr zW91TfXVBF*5{m;>;aMx?E4&)LWe6CMUGyjiXduiin%gTwzp|b_!@;+R;@&|n@0tkg z=2!ZON$VO4i(3~HOU?d!UPqMf{zVe+Ud%u95RbzY{I>r$<=F9s9;@nuC(X66qr$)m z0{?-2io5?1Qtv_;fZPqg`Oo1`l)Z#4+K-lb9W7H&>iCw~ftHySB2#wUJ*AhT*j|e+ z8`@eXLd_)OHTyMRvuxC3%XrPU@HL}XHt{uk8a1Ok_%{a+p=R{x4})UD+)8t^4n2#S zrC+bvbhazQ#T0G6UNheUjM0^M2zwr1FpXQPVP-trzw!=2sD!UiG(4w*vf*A0|CGR| z+xIBBx29oXGxSRK@~Pn2eL7$uv}Q#^QvXk(3ob-!K7+dH>@DQ)mDOd%sKwqv@K*tY zy@sy^-Oo*p{jgkwo@9iC|8>+9i%-tC;2nn6oS%ukm;L;GalQOhxb{Cx{9kZqDLx__PBNvkCRjkjZ85qT&Too zJT*l77QFqYBjOs2XOju(Wha+3z0o-4V=VKmYpT-68qYvWCG1IS}c9fV`RJ@uPt;2{!?9ajK=w zstOGOYryN<3cxkE129GutH(lnAZk)!&8l6pj&{o7Y z7L(gHt%t-rXAl}|*pq2W&j7UIh4JXTVR@UhYsnhLgvSa)y=TM_I#3<41Gu(Q`Uh`i^dtKk`HK+pUn2Kg8FQ|UAVG0kIqs{#*w;^-agXq^B)*E8Cc`1GxUPW1sZ$p;#R%e-fGH8a1gceOCGF3x6% z!PF{(Bn00|yI=c7_y_n$6!|&yp#KT|uC5MiY|{l&9R7e#4(`VS$iun+GhXg+ zbT~d%Ze4H_WO>u-qI_>9hS~#)$P-``{-&%NzN}d&Yey)ZFWnTBuKh;o{xtC4OLwT} z|E*-7heIJo^&~!#BMIxh;Om7K(G&(Yy}RxCfH-K23ySl(DP@f^{B)2X`y@U#Yiz1^M3THKK(Utq!(^F_UKjY8%+9)tVKV&!cuEEP zs_fzp(&D#E_6sAw!M@<{p>WvAmnCuiD~FN@^=kY_?_I0Gml(Rwpop9p5oHLV6*Q1r z@YMVGIvk8WX8+krA9Q~?wQFkg>=M&opsg`SlH=HoWiJoySvQ63ukBlxcB_s}v31s( z)?ccvUr&!O*S4?Et?OM+z}}NxXL`~_R@c=(N&i`cw%R%(%=o;H^5O^)KmHE1PXd2V zL+;8YB*qD98?Bk$j9Fl)wszL-x39rSth6a2kKrEs%FlwI*Sidzb_^CDO;);XuZo+X#WEv623RV%jA~1 zq5Dj1C$)>Q1)a5HM*`pF+MK#IbwZR#%hz&CFxP&|N)* zNkWb=t)R|_QjYCCb4P-3r$oy%T zFX?&3V6=Y$q^~ccW&Hal!ASq(bav(YOD9TpId~uPGe^8bkJ%sR`-!QxzBabGy|$#W zuh!XUs5{!|BK38|+=sW`GHd|vt{87!5y>2+Z(!o^U;CLU=7xmAY9gpLHyj0a&saOP z*X^;_kH7h!57*+pzF;rjd^_H}8E^jK;oZ1)mVfgP4)@~tOwddiLw+IWC@M<)An`B6 z9Pbyw4y^)8q#`l`w9oCR8=Jc=lvZw99pn6j-527>ug_F6x9Yg^+CPT{e#0b=Q%Z4&$fpGT-a|5ff%)uM|LQtcW~1a96*;|9yS$eWbFl z{O7ku)7!YVZ{-EPP2a@v=PSE|xr8z07it|vGZQ~dd`IA4+V4Pg3grb>V1NHh=;~?R zfi^=tJfC_La~YW|fq%wayk|2VW5wCrM6~IY(L>OjjPar?B8>xwthu2=GRq|FV9~fSW+!uN z0%}s=>)jQy3Wl~qz3caAdpe(AuOFS$CqOnn z8>g56wV^*?wtfbq*BqIH+20hxtl@ZLU9NpYSu>kp5!iBT2i7H6KsW#{u?o>?xz?6b zTe7~vUBxh#WLtyliS=qcwK0IX56@fU8e12NF>0p|vCzgb*-4PPuEzRbyFtC&egY>`4qa?Ep>~qrGXy|r+R{Ip~0^Tn0z9boG3Rzr)n3A#k zK0_o$ALa{TZZGvrec}mcuA>CV@F})x(Nw(I{Bp^@v62ru-*C!Ux$T?sCq|BpvTYBB ziznrCQ&Hai{Bvr;w3H$|Coz6^CY?`~j;}k2x5vs$|M8BNhhZ0fg04Tx7vwKU_lr8_ zot*bJZB5n7)r^UxlmQ7K(l9hOE1Vgicl{Ex{#--@lVBb^1a(j3Iu4Jwuef}yjQ_c* zb!oq$a~AD4*XJ!dXQ_@1M86mk5=q%WG#PTT7{5yVitww5iLmYuAXZs*?CT~*we(kv zs^e)!wG1Ds3pTHlqVLhD5&{`HF;Y6}IM!}AHF!CAUq=Q;%?&FwS#@89Q;skPSV$J} z=*4(FJR5Z^)oP^inqC1sJQGPe$pD5X19XFlPILKhtw8!S?6xpIrkJ&?(x`~uBK%mI z#ms%gnrCB*V3~AKIr(RriS)Xexvknd(Zno*tuMfRzu6u^I7r9&c}eANxFX9E9~^@856yli&SUFkFzj$wGzqzc?wpc zUe9tWG*zBBr_h|q}?B-rt+IuhKUtweY zYi!54qVnE*$y8y`+_bW(%4UkJ9qn5!$Z9KXU$MegUs|ovt<9cTJD=p*LN>INCA10O zw}sICjr1vVW1u zGN#0mfRS6RIL&Hph$-73FcWV}pxpM-viI(LX_;F7A@_u1&$2UI+~ji*?6Zl-)KuSu zJs>Qsr@G$?zc=|B`5LGfx$D}k#~~dhMotXB8GZ)y?`C`!i3zz6AId)#IWl9Bpoy)1 z_RtdBEei$PHdG0>S5qs#N7Ry6exj<$dUub&%pihH08bJEcAPoALf0#1y&|1ynQ(WyN6jog*Vmhlu30&vFJ4U&3vkBv6q@6 zZ9sooU1}sLkJ(FEQzEccV3E;;8x8&EOw14fKPwh$j2B|IVlu5$hk5Oc#_pcwp zecR*FCvK#q=^{r2h+}y1kOWw8B=l;p05i*b$my-hc=Vn)W72j|tNz;~S|Cc~VcuiT z)AQg+&t0G1?OZ~S-y3BIupsFo*=qTeaA${1V=F;+Z6B;ScST!_!64CNUZ9O zD&>wUo5G*gBKOF4B<_&xNaJw^NYBsC(>dx-Bj8#g(#E@?HVSv$#mQmV1Yfs(?^Y(fmtq|7eq zOYj-G-6*v@US@$zBe1<^kbA2|$4Rx~B&)HNR3_>-2fX){RLbOjZkeN`vY|B3Ame0C zKj(D_3g~-{RqeFC*HzNQ%xateX1D}>=nom^HJPcM7rEhw=B9iI(OT$_-?K>ve zbErl!9^E*ske!4Xf~23*0|kvW$+8R@87R*&2Q~^CF=snr@`Hn@^$JPixkC=jHGR z@K%U%clHC>!NeBYY6XNbCKifnH`PA2K)MrFzV4s&Yai9PDqT#0xbSP}L1{0Sgn+zJ zSYNAv=9!o!o*BJx1I(Qc4Q`#iMsK#i7VuhALSl0nG1e}#VSLO;j4VTxqzIOsL_}mV zz{&hYzkmoyV&SG*v8m49ZeM8g0d?HJHO;leHQ`a0sa#)QTfum&KM5vSs;pJ>lr1`w zzB3ixO?0Hn`BCMGC4ogCp?MRu-n07E6lFSeYd=OhaC}IppkE2!2Wlyjd&FiNG>>OE z&Ryl6xR#hzEwbihPcrX4J+&thUKO;z4^}b7{ZUms)t?SOio{@wUt)|^Rb^~1J)JJM ztek&Z#S}CH?eI9^{OR6U6~~n{RoXQEp{l9nvC3tfjN5u&R=EluO1Fk&;ButTPK5of zDg$WMU7vj>p}zgW^PhSuCC<%m-Gi(WO0? zaV9;%;^+J-rVzH>b1uT>zY#vJwGbx%HDKGQz?4PnSOp%xiEESnsurejOPCnm{%kJ# zOk6p(hN_Mr0&JLSa*1hPLp*v1WKQ6M@^TjwOpHjNIY>lArs|lKQ2p=x{Ae^b*t;ek z{b$_pup*-4@09~FO}IdAR79@E4A2)`z}4fWFZmeAxqq=69!ZF#5BIInZjqap*fv>{ zKS_u%!-fZFE^iI98LCk4niEY77@Ho2S!IobTmccwCn^sN$^=g%~dT*u<3Nt3-6Y5s{{ z7ecN%@oY*{-NST0mBh>Y^{Wyhz8HKl9xwnI>woxGd1#on%}?=-^(yW-MxXVU0Vewc z?9zcNHvDdw?g!BCjzBgJsgAwBoZ{9Egat$kK1U|RX&racbDNWe)ULH{avpc;gef*6 z=4|8*$DJqakt64%_v!bRN;2=Xf2@CAueThtDo-O)(|&6Cb1NE`>sS!z+EQ!_SE$7) zwmyrXjxj`lq$#R)yOWeENY>)?Tqf1myV~8(a4Wiji*@HMFcy3+XxA zP|aPiuyq^l#Ne}9=JkYCM_9X%oROYdE-`MiCCpH{+9MB^<&P;C-r9=u3*uh|yAsQ~v zAORIU|q4}%uB*VY3k4R$}KCcAiwKJ9|7bc43QX(*rV=UMNgoYuE2>6T}u7xFL zfn|y9xb$9|q!99LKF2MvIqq~Ekz_KE1;uk&#Nn_-%wz@mx%GJq_{M?1ztVQt=CPcV zS~#GVPQ#AG;W)-RQ*1+F+8WGc>47PTs7oQa^Abs+r45+MdGm7T6_eUqfie2o;cI4weMEB%`@C=Gr{Q-EP ziC?`|>!5Nh<70E?qD<192_ey(CARmLpW;|Yl{3fTcb4!^d_BlI>lzxZuZD7*FX8u4 z=t9Fj%vMMX?8kgZt6s{9ox;NDj#He*Iokny(bQeR3C_jNX>6J1frbw23nAhRISDJ{ zb~kK*h3(g2owH&st;5+c;}d`znm%6@dUtud-9>cE3mxrtSazUMpue;n?RJhk;dF#i z+kLdYdq%&&ox&V7f2RbkM9V$aO4ZKgVgF6%e&>BiE5^M2t1x|zEHw7-SS@{M+b*Xq z+{NF)I((?PcI_O8f9-6%!)Fd9?vn2;awfb;@+OAXlUu;2HBB?unaS=g&2!@I2U1-H z4T&zHi{!|IbDUG50jb~~MJwT5!l!}my%|%5bui54-5wGat+(Bx5xnq_{@)trgY`=ua9)Cjrh@xzSe*BpQ2eG8Le~N3=cp~wNL|@$8`jcynC$9UdugqV z?FYj27HwbpMeZ5xa-cC^;Z|4@IKS4f{WRULdCWp_s&s(^@QKbNQgR#~O{6Cna9~d_ zBCxJxK67Xi0ct`EQ^I=k%lj%3eFR+oWYWq_$JueMz|$W+I+$0Uy_o(7PhW3k27`4z zoBy{zdT=m*aV}(|xuL?vxr>EG`n)cTAGt53miS6)@tsM0p~_2@d%#;BsoZT92Ni8A zZIXi1Ql{Wu8}?T|ndUUNxb{+|qIHn7+9H+oKdWt^Qq3)_mHQ%6lj6Zkp)IPP zF91vV^|XXfOYi7EixKEOz5L|z3XbOTRd^@716km8odrKe)ru#UGBcyN?~CQ9$5YU| zu7%!1x(OkIbY?#F+h+wx&G;*%%T`oy^scMm0=Y!QTvj6XUS-a7VC287{rKKBS7Yc=fh6D?3DFPKO zv}j5JQ$P&j5c2aMu=mNW<)|>H=SZEj8et}1mBUt&CAoW)l z??Va)7gH}O+kIiye3@kdH}N`nqH1%wSvWBqQhhda1fJ*3!z>$Mo$4cVl%>xM>wva$ zGwk0WHWttG=HZqq^9W0mc_g$jgcGRk6gh6${O;vGk?n4^!aPgW3eWMvNiq|5%;0fY zVZVa%K&Tyysn80f9zViuWoj9)W~<8n50+Mm^D)e%P|T^m2wMfioU3a1KbSLa!A$W{ zDF}(J-2}cZWVzwV8n!Bt4|uSD)QP?Z-B*lN)EABAtw&HtqK*%bGe02$xoJjj6taBO4fU-Ft$3DFJWFQ}@*$I%O>INH@AIA{rM8FO zNK;Gf&m6YJadpJP?-1+=g=N!NHtxXzg{{8%eH?T%1b|lcak)p~R}&n0D>uO=<1Lrr zr}hubkYX|`K7xd~UIVX!T8zoU-s<1b^{ZN-giU`c*Xwux(903Zx4Z18J9*4Z#xU1o z0|q?T4k)X`TqfA|4|6>TDP`&}KuEN?N>~$tRS37+uLPE1Ksez|SnP#O|D#)sbas7S z7jkx~bScjFl-3jAmkR7}8d43Ma<#z}l+6%WHm}00w0&XxR?@nPuMcw>eNC$*guc`L zek%tA8{j@oYBXh*4Wwy{a4aKu)JS2yWK zIX3IU?4{MS0Y^J5)z9NM!qHZJ2EQSWZ;Yq0L*7kwc*tw;W5+pgH+sCz`1guhV{64T z^gZV$cACGV4TWX_5sZy={M(qK+@TY+5hW}iVTLvx-)oGh*g_`AyG>jsv=PUKI}(+A z`fm-E8dJ6!PcU^9-JRfs6#2I)J zW}c1j@fCZX!E;BpLLO`Qztj}+QbXAK+3OiLd!AuWiy>^o>?P zt83+wRp;3Vh5cAIA{z&~R;q(xXUjG^$Yh730o zb2CQZW@1i8jN^0j%#28fU|j@cll1FCA$7KST^zUvp92;+q!W@cd6aCKtEY8nH z>9~JGQ%JBhAgxxa>_a||_@3-F zd9%)oyIpZ%0_k>t+^@vEE-37FzuzBDE}*^-<3jO(hq)H^8qwDG z^m>lJPri`T^nXi-?w{04 z=llu1bgs|pg+GrmoNXWZyF3-&r}b(c9B=r6!J6KxAvmG83Gh!WjZwXv?REo~V|NOw zgMCr)&;%MQfMS{>Lx&C zXNjr{+T-`(Y(cHfhq(@VQ}O((mjlO?*r#5oQ4%i9^=>cK^R7{aaPU9|JuGkz8oG=P zxKN{ztVRt<5oJB$>*I_e>EaGC37N7>n@#w=Ei%4dnA52H&A~T>x$1g(o3gSD zDLmJ!sWwzn*-UVq)D5}{aH7IoE4-ze!<|-ga4whg&fF$vrO`sl%eZVCw8G>@E=z9M z>$DJI{>?HeN`zB1DK-eR8l6?fm&keCUMbL5huLkg>mFyE8!t0}|D-%OkF#lY3S)z| zs$i2IZ&}aaq`aAYR~9lpzC&&NzAT4? z$>jNyP#-UAPr<5t)t$exlK$aA@3g=}WX|q_E~5bFhGA{cTgA@)nNIk8#XcW4T{_j( zXDg!8$H0HnACON{8LgzsXe--Rwm4B#p9Za~)p4`p<6t#*teyHX5pEC3$Y>8y846Ct z)oLpX8nt5RMGYgOx+s!dE!B^c-DZxuEz~{QA<6$;?tQJOzfxL=A^^7oaN(J{ax=?IKlmYs9kZ5Z0HM6^QCi#yz7I?|e@8UHd(u zab#IR$dsL0qK+oweFtQcx|ehp?8XAozHI$jc}jK7){pLfpn5*BmvUJW>oq4z2A?8P zuT-lOKy3qQ%i$yR$$htBQ^6$;J*C>Kh?(!bA@}T zA1k^iu2F`$6yDNgVPcdWJ7^+O)no@~MrxF}+o2rDJ+KZ1El$@BKV2KBJn^^W^}`(O z=0|KFRv)>Oq)YA5SU0-e2fWouQg{KKo-1v~Sh2vu1@`2ZAXOr8On|&*GOZ;Q4f|k# zSB2G4=*WNoQd);DlGGWFVYbn*yTM!NIXyAqech#wh{i8vcbiXFB=J->z1)a%I;>l_ znd{j;=wC$&IeMS{g^RcoZYVciz?!LpT{Yr(_F}G_YFcf%7-55et(>!6BjrY!0-k)p z!J>9!qjrYaY#4*!7+U9Jej#T~7pd*Y*CEe(5Vl%uMtUO?V~Mqlggq*mMQ(|=Bv`oA zG)D|_Js#3J3fQUjyDR+Imy8|Z7>;uJ-1h#MgS1o&aJ!1?>evO}r!;2^DOnxWb85f8mA;V$~tVfL;7O;toRXH_!?=i>x{6)RWvM);ma$CkOx2d zsy5mpVznn95UC`r_J$7#RT4r|j2sXr%tmWY@RTMAA$#$z9g+jdYxPmq#GN+T=$-1F znw>aBcBEg3#0Vy5$6R<@x6VOSPZq`E?69R%qM?2QsTKU!*=?@;LZAnRd-yuqOQaqi zc8M|5IwCL78V7Wu<=Sf?cb^^(Wv%h63G|XKa4?8BX?nS9T*(ut)4YMD-uamNQH=I$a>Cl{6XXja~ z-Hv(@WC~DUdv&pAmBrwF$ZVt$bGlWrNq7FN811saF4$)!`*fil{JsydvfKc*5k;T} z%!LcDIAiZRE0^xO;fzkzIB34+5V7_ zc<{yOKC!>g?~g$)C5+a!K1wT$(XudF(f@~*=@wcMNl!b6C2e#@COzrocV;K0;jGQ? z9OEoaN^(w2QahuPC~ts+e$;%UO~&OXm1gP@w+Ki0GQR$vqQ)|K1h&(%?&;&fKj1Amw@0iO1`I)JE@mp+c%2CvJ<|qs`Sv@079D+|-wlI<6xo zX>=-SpU@MPl-)y8qF)Bj_-w?!V-la7wjp4KPf?d(|2Wc;}&R-n8 zhu-rDc1G7f%|fCZV=4sOW5l8Q==x}@p#GdTy8g5?rMQOtqb#NPQ>9$xq4m>Y}lF``lZ5o8{9;hvH8*do5aA zE?)#6j^Mt?!N+S~06vV*{dn&@CzZ>fx3yn)H##RIo$1a=`m%d?lD>OH()8}qq&vDt zB~9yoFe$&Awt3kJVbmG?8_^Fs8ISat!_;4mpgw`*;*_iJh&0bJ=kYc2(Ks)S^+0GU zZ8F9smzl4XW=wEwye+%^J@KEBTqb-XgWGajbz{81W=$lwrP`GVv4re|1w*VFAIz*W zHen|o>llwyJ{dpCA!vX<(>yu{kB2s*;0$V{SAcb954giql#d0&H~;RHqBZ=(i0uRMiD$J!Q0MC zLE}dTSOGtr0BI=C@T7r_g!BU89Bw3h&RXQm#c?=QksOhAdw9U}w z5ZcO71~(*1e~sU#BW*8tu0%=bh+G{{(-96(jSAw}*-4Vpv10h#lf44l6jHGOU&?Lf zCU|xnLuMu4+bM#5NDYCd8SMBf;GPBXZRg0n*Kmg(I>sOz8obf1!e9Ez=tvMCrD{T`xb-Z65{%P%g# zjRo@iDf|_|$6f<&r|qHjVJLO@-(psV9vD_nwsS8Nb=X0_`$u0GtU-;iA2ZUG(3BjC zn%mSTz;k0CE#niACJlA1>q}+Q*<7}Syzit^FWI<3gcbqn-RD-rE+ed9ZKoc3HSmT+ z!(<3M581n7R;S+qTF4-WQ?PpsDNX*DQ%LBIB;{se)h1NVmOl{cDuX2|-abdkZmHla zgocg6ZUH)%fVw>3$V2u#)Ro|+&+{H`_Z%e|>pVZ!K=YXo3I99;4^9FZ`va2;r�h z{kQb=)QmodcZWxm_%G};ck8}%(Dx5KspKEd8a1zp;RJ?F1}?``fCrzb$@jOGW zfyn8-%x8Clcbr4-a47G|cU-K-z8?B#0@TQ6)PauGhG{0{5Z8eJ%h^L+RXEEx8M<(n zZ-S%;m6CP&>He8or9B94>8t2zk??NXiuS7NyJ$RsIT0;}+hC!ip1filaPI;ZPU8W- zv)Sj?d8&+M`Y5*FzHoT?o)AdThG!-c>iL#Rkc`$~r(}u8d`B{p9g@_zcF{gb&P@G4 z!XEwKbg>w7q%MbutWwnCQ@vu0S!nU@f-PK(*%0*A(tdG6C7mgDP^>`M3gF$uEdylc zEn4Vz@VoMwGY=^a4##YH*-Mf$o3CKUl=ruC+0P4i7YJ=KRfBATdKff|h8-e1U=e%a z{DqYTK6e32?<V{S9qHS16sB#eFT*S$-MC1daHxG0sta$K0@ z{$j%{!(E}4$emHUNOD?pTiGyJLEfXAY=^zrF>PhxmT-7IE7q@shqUxg>Fy}oYXxm( zVY{nl$cez1WL&9N$VI!W^r5?xj0*Ww<0E*N?5@ybzHE%x0UvisRgfFw+Jvxb0DWqk5TYpI z*u4rT31O{LiW?%SB|hV#L+Q*hMqm$(nzu?CZL(P4im=b3HlAQ{PZkZS-AF)1`pMw; zEP*BA7^H)oHO9iS=`kOCz>ye0-(V($ZzWiPxZ#ihf~5+ZLOu+4QR!Gc&$LBZVb>kE zm?C)8s+tjDX$Joeu@)*HLhn`w?^)@cEA9Csh?qo~2i#pg6pOVgE zvLP~AU}Q&uhc+BzBgvPAQ>Pl^#OJOWpm)+x)J_5Kua4jT24p}tVC@O%z&x6gOvYk; zJ&(2NcRM%9<=lXk6?3xdW3MPN)lSAt!OA+|zB$0zt}kf9`Kc$)6pyolw=_kV7>P3; z&t%BtBpa!ALIY1tniixH0anoW{Su@f>U!EkXVa%VdF)<8NJ>*~vU?+}l%#cHCT0th zC)Z%Y?<$Xmd_3V~&ZC9|L$ZP9`Xz8HiAMT1UoXLq0V4|M{lT@CY9@UQ{<|=T@_cy6 zWc%H1ev2uf!S6I!j6S6z%X5C;+#otzFo-VI|#L2pW$VLgG@f<79h_U6O-efb(6}2Z=+h zG%ai`T%$ahn}NCMLvU)|cP!033jQo)3xW3pt1}I_6jg?q#<@d-%JQ`y^njf5ZAl7k8^>mt}s(cYteQ|z1SiEzxs%AWfJUK z+v!fo2fsJ)QfNREU_uf0&v}uZAsQO7%TM7wcHp5 z-(W9xMuCU;96V*sfdu9vV~25%k<(bT1Y93+!wut6qX6@@$ylfR$}Zgw&$t~@@HViM zgIy4Mwv}RM)@BzsG@DmI&V#GFY!>DcoX}yX7utu!zV8CniNAu;BR*8R$+D?!6SQZP zvCoc#MB~E z^)O1I!00f2=M-mrp4uGwxSA5=V2y&t=TV={+{-sGj5+f7!}B2yg7 zBFwquj7o#2X5v?m!VVM*a78Tn(6r7p*_2xi-55K38t^ii-dqk@p7OYbiO(^)?miPY zK{!clYtmhEtb-oRHgKi6Dbo6Iv;@Y!<00q6u>KZ~`E7nb)?%f!(Wt-VUI>e9ADGOh zJX1E4!xGuoR+lRlCpO5((+rpHVhZ}W30IxMj6_hx zOqVv&PFt8bKJ39QNzO6TdeaosA@urQlW@`vwDMrs3Nz2bDE3Xqt34!%_MnNdgKH(y zv`D*X&oLQpTpT-lG9X{pY~H|Xwt1a2w~tX0K|XoFEx{~B$1btUd+4aT!!x1>8W;9Y zJF_A6IRzyR50>H$ror=9mwS?bun!3){o>>yF(*i(r5L3BF=%JrQW7!J5KOx1 z6kA1&OZ2oPul6c?1nK|VHY0Co8`_dD^$G%QqY>{8x7;1fwO}YmJ-vap$z$zq2KIHQ zkmY7DCp1^Iq*uB#&?^6_i(AY627GOGbfZNellNe^*d~}zp%?9$Dwn3kuy0S}+rc)G z21`P%q0=1Rjx>e2Z$JX+gKk(4O%^wwm5nfk9U5U8sisgkAUanO$ARvV>KJ8Uo})77 z;mvf8gQu091MbW|adYDnkT5ZmRJmgjqyl-zI>;~Tab|I|?Me6(NmV)|4O(MJ9pyud@{Ib)cjw7;kT_AQ zq5p2)Y_dDWNvrgE^63bhyx=p_CQ~3rzlKV{ppUKj#3_C==_x^KIArt5jtI;m@AV22 z?>H|3pIDmysl&YBZKn`Eb?Dk5#f|hzLg(fRQgQbot+yFzG7`MT^ql?}K+vAf@fTPp~+u70_8BV?f?gicmoObR@ z{>_S5|V#*DoIr4fcs7_)%F|?NXu^JI7mju8K_iBszLSCFlopVX*JnW$ojF4Hvy@Q6l zhFXw-&pn=%(u{P{y!>7XS*<7IhCy;5lXSULV83;8VCx9^#?~4ns;tqDj!M*8eH{Q~Ia;gf6yiO~Q-1D0n%ah55$cPw9m? zMl^)DW*t|gTh zG0Lc(reoC7FP6}a_u zB<7q@&nHcDDdt7U8-zL3GjuqJ#=aQ7JvX69h1p3`JkI=@~ zC9>Ls#Rsw%CHC0#}vC54&gBqb<2kT$hEA~Nx40~4&=jy6?gA}5% zL&+jC?<3<3lQQ=1MftzOdj4y@bz6D!#w!xbUod>5cY@q-4~f&y6_w={T9a^ zIUAwh{U-0!5{_O`)0BRhl0;Qd_C*pGWPfkwJ3)H0sLbsj6EJ{^pHaKxY!_5pjV1SJJ5 zmQ&u+06ZSjnh_CLoH3!3GhfQy+FTxfboy{3nw&_k*g!l1B}KU2n`*g zao@lojW6t@ockHZc%&(|D_NczFpg>mesS7ZjLIK|{x;11I&4Xt8p80q$9V^-oUs4i zvz_6Ffl3%K!}gMKM<_1%u`1G#>2og{_`6LY zJqhGiU?oG{kaKR?l=bV@Q(3II<;T`9THd?fx_rupbIaFnhYuwnnIL4*ZB~m^(jm5*0PljyyC28aYv9&9MTbH#Ikf$xRr@Bs7XH3Qt;)n582bZ zJ~>;#`?KNW#_%Pm8$ey`T*xTYV@%yjd)B~O=iMyk8N}c=6*uIVTTzA*MtjP7GG>v1 z)?CkAwR4H)?w&%1y&5@@+)^8Uce^LU*@b8+Cg#4mQ*(Py*9s0ZA90ABp$$_= zS!NBm>)~0IG9@@;e+iBmI>!I#$>`z6z-KX)2kaSc8)3~OjlfyqlaLTt*l;EMkZ?`f zD&^q^vEQxn-;9^QKCf`RsG~g?CimX~`5NB(L;TJ72I&=PKeV{k#{W|uYT zos7n86POcx?hpK!E8s_p&Ipp=oOy9BEUm$}!uoCzuocG1;2^-OJgn#BV4eKRLtCeF z?l0hNaGDyme#zz~xWzs?U-2qvGp{L#M!wFa~m`Ru^$odKOMfE77j{fdW zfL#Vr;qUG{dto&PzxrMw>@m>asN*}I=b}dZg^OAVTMU%Xqkrg`!{>~OYWRS#s9`ZA zlEBKjn#*~;mh3InuhxV2SKn3J4E;P#Njc-nT7j)bPW5Ug6Pb*&Cc2b9+%D$&Wd!r{ z6<9Ku@es8vLdM=^*Wi3Q+@V_0g;OKFnN1+{G)Y(GCivM~D9a>?F3zV}Q7+dkNhOa# zUv31nLU7v0*%e|$7FbVl&*z-#0EZYBoSmDnnsUH*X|y+IflFrhg(6fKwb}E|<2*=q^gQy#=<1VNH6<*%o}6 z9!E7{ve9ZzSP!>gu7{k;>#&VU&!?J)pi7JW9j}yja=B=?ymYith@GUvCjd0HqM&QV z)n}MC=KsU#Pyf+gqxlS)1$BFSfetAoFXxWM~=eh+c~{g+Q}=e*<)S59gmYlL%K$4eKe zlzbq+2Xt>ZelzDlCOTH%wE1E45tf&(&8Bs{h9{kmSoK_byj`lir!x$7JlqkDnK^-| zrg7tbZ%+t$eQjiNhPG>MvH5jb#v_6(LB^GKs{ebrz1A6x`_hZf8wo`HCvLC<=5=xLIj3Fc@>`(d51{O-sIky;`( zQ7W7kw0`#*p9B`f1j-1^D^lBokhXn`RLS{0u&ci$12QYHhHa)=IB&_Ka2Hz5TJ&Du zmI9J`2|OvHmR04GC~)Y-_4#ITgU|wh=5<NNx2RlY;0xo zv75-J_KO-`usfyupy>*U)v$EZQS0QvRpT;$8mg6dJ8x|@Vn5x(@6wJV?Q5}%jZ}{| zPoI{L8X@+T@LD6tDMVgIqdu-cr<|Ubh81y|9RVL+*ZNw+fD@AD+}fm zf5rSoT+Y3)1~O{y^o(C|3Y(q-d8~0?J6`W;hy3gQe+r|NCxuZp8lf`Kj(0i#J1@`l zG(AUmG2@(F>^BYV+VzA~2|gG0v_xaojcdQK;q?tAI8hNt9LjWs(`Jg z0<(}k8mFZiQsysYRcrT<`PF z5X%|Zt}0EmP7kdQZ6sT(#Yn4=o$G`&zg8P-+gNAd<_!97=$8+W zpX9^gAu*AV)Dd+hCqgEiOX6TTic%Z_io|iV^PBU6ka+nWV@U_+j7%13 zM}jv&cpyWmn_=u4t8yl6_q8sD51RxVV_O(E3I4az*5ddf6BBFFpO^z8n-5Ht6*!y^om~qRr? z)JL>bY$R$^xRuMiSAS;_m$gEFO!ob#Peh+Yd?E|8eiHM&g2KNozN2IbuomclW>n_O z!}iq2%m)oh;Z>7h!XYP@a|&ZgzPc1%Wa!--ykgrdknI#eZlX@hTZh5t^ax8#+#>z3 z2KW!cPBx-Gyj~EnF4QjX3B}EFdS^uAh=z5t>H38-qKPL7&_fV6815WyAJ!n1#nwrQ zxKnI?OI~1pP5!J|kZF_0?tK>8vW5aKb4x)?Lx{`?-xsH~|I(h(TEO2PVY=JomkF{l zPc%dm#p(}qU$u*wy^?4v)%Xn$-kX1fGZI}J>u?a67fs055Q*Q9b1fCAJx{u~Q|hw+#&OIoqm`YL8mYd2@TceNCjg=!{M!tN0d-${pbT)PyKYCn@> z71G=~d5x$hLRKL)2^ykg0eF@v3^hsHz*@1*B*^N5^%UuDX@f#BOTQ5IEyH9nt9KXR z#y&X~Qkk%=g|jNZH_~*!`7YBwvmoase6tt&kfAuGCCQe|Xx9DgxDQrZs=GPmyO(Y) zJFN>2J9R2wpos`oSaeinX`!3zO%>O2OQ0Py!&B!O-W`7zbo~9;8+RI4YRR zOu&&vsadBnAML*gdAyHcC&7Vz`&sbh2uB()NBtfmijpDhc{}b*LPb%-@o%CyL_})v z&*2|j9?05>$Tijz#-kmQ>{o+*Iuq>>i*&NdVV2_vz=JuK03OUS*GI=sJ)g?3dQppq zv#@vPOPuEzRRL_Y-fsV{WC|N8l`s$U1+0y#O^+saaO zu@pbWSFJ@S8T?T&#?Ic}Ma;3H_AIIMLza^hu&O-Qek52v8FJDDjBH|L*n1fK0fS!# zJeaHPfCqE+9LvYxT(Jc)uVJpBedVd%K%bb)-X0IWEe!UMhl1}lEY^tcUJkb862Lpr zl9WaT;JmC~dg@tjAHc2LRC{f(-fEHC*@z#^RRQ3w!JeTF*3RT$YI%s;9Hf~IxTa`& zFeU?UPX<#?2E0C4Z=(S}j+&ymkOQ`7B{&~pxky4T?y)Zq&YX0n4M99nA7;1$2480I zfcHOhl^gJ2PHzCdKbV`V-axAczP^N*vS1m0^xoR0-v{3UwP_E&6$VRj65q`Ue)k#R zS;3rt47fe36*k1_D)Uc|IB}XiFPL-M+HWEr2838{|H|OBAjN$wUxV%1fVlC&cCGgY z+BG_exh+@%dGLJ`%iCFA6?|WhZz*o4dR%7;%g1JqB(cao@|Ip_1Wq>TWcgUa;5r6Z zFt~xi_W&NO!MT73dtebuKQ-$tzXv{t+cC!J_%qL*v`b5uOU1_ zc!cq!4)Ha>`{J}PDjaY(%V9QZ3VtJkJ&o4XD5N-r1Zpap!FHCbFu+Q6pr42sT*kuv zp8w?53z+6M*J)?e1t|X{`rT|C_;C!J7QmL;K2Ln|y`1@)3$(XTwuAT@D+N#AXn%i& zQLE=eg6TGbhAXR8y{G$iMx)6uNsP7c#$F?5h{j*=P0lSeHhQv*^!rWSjqIDPxJQe$ zzjRBDt_Ib?InM~VI?L&NiQ%qA9<%LRZmFL##AgRU)r3qya-@zaKk= z?f8zUAGl;>;R&dVn~voS9)&W_u-_9b<8}9dzp^;ZsDKyBNe(mHm0X85_+aj@yRQKb z01(|Jfj|Y*IUh=5Q18AXL-&`?~uH|9^HW*WHieO{s3g zPUE`!Az)#oz-Qs-eF==V8Mlj*?Bby|xb9wzE!it5O?F>vK^ev^9oIYXOUE;Z(TtlI z@-fEyn^?mq;Qu7XFHau(YYY zXOVq9_OtJxbzv=}*UZAlqgDj=M-cvD)^BY7zY57-Nc7kr3f93v;9qx3Q5vQC0$^G; z4sR-TCWHHYbnlu8ns@arV>E^MUTD7`G*2P)KyM`r^@30NyW@Ta-vlhM-wTXSv)*@> zv#=}FH;8>c`d>%ZiJp5|*iQpu>|RR{b_JC7_0DIZ-vBejKJ%9L{t$V%k=4{w%;LYm zR|5MT_^L(|>72>JjtxjKD@?iNn|=5uFygMe8vzGK+;z7F@L->P0dQ(oO!p*4qXD@V z+OelWzWwg=-awCe0inD-sRXxl-rE@77KBLcql2r^b==@$hn%&bCym8E%5o<|?pm{o zdy-k$N|b1nJvNxTMpol@;j3&ycMsRyg}zp{`w5H?9b#&--sm31zAZs&oCE#5R{)xI znqA;)_M_ctUozqMZu}4K2@e4N0{@-(r~AUY@&7#jFXLZ`edOSNvJ?I43-q6mV$)H@ zitzXmgjdBV&%@`p*j0(^3sw9L_qsmQaj|O_E<;-jT4`FiTM^>k>n<${@RobP5y zTr>Q0HEl(>72ipAw&8uM|FgUDjCR~rul45{|5a$ul)9ex<{8@&vH~Gr7Pcc~GeW2h zl}i7y;%P?33TbX2Hz&Nby~VDTJ}y2LZTYB2X*^LV#TT=^5|zuCjQ+pCFU{p}fXBV4 zXE3aIC~T}p6vUez4D-8_AQ8S?MXB5adIuRjomXj$LJpLO^Q)o|Hw$rox6JQXDUDLs zbkB}rrBPlhb>(<=2B99$3&qK7)xqtb>p|}@q~v!;K!=FtCeo8{e6~ag`_Xh=q8Q77 zaTyr>KFp~NQkU41XOtn$9$&sOTqT3evvmv?@;D6dauDx3niG{QQ{wXZA7^P(_*eg9 zL0IYv@o0=IOJq4bz7s;e>~!$U2z<%mOQ~z5=Yb*YZNR3f-8Ymol~=}6{2TiYvodl- zF%}GA$b)&`%P=Ia{r&(($q+_#5aWd)#>@T~WwKH1S~DQa4Yb~P4;O5U4L*diT8c*w z_oEJ$`jp13ZTnHKul<4`meIGLVM!p*KNxo3P}slFQX5tDi&j7fKtl%_YqlLg$Xi4B z1-=788a9ScV`0bEs04nxFM+k6GB?mZA9|u#3ywtzXbZ-nebD;&Lg!Z$=b`l}oa5)z zQN@ZCv09+MxMci5w8660PSh{=q16J?`gJ`Kh5lz;2CejXza29J9Hirw33+s8@+=n{P1e@u4uY@2jG(i@z?3H7Jc=7nfyb82pg?QW{ScmZ40Q zXfch7LQ4P{&~~#CmqrW-DP`?Sp}PUKBJOs?ajI5?+<}k)vI zbAB0X^K9go)`hP>-*~X324y-JEE91#fJ4Wvl9fr~Qe$*bj8}#*P6aU{gBWsOp3#id zyr5k*ApR?;g$BgE1)9970X4KAAx4C}h7d?20D3YANg#s~2$Q(p z0c1kl_Wq@;_DsRrGy0{h_AJONt-bsED~fN&jA)uzRzk-VaT$O?>uwV;GST*121<+X zpcs<^@e70T4SOL2dr#hRd35f$UH{za(`ZsBF8Awm=fS>fg8_o zwFt>aNcA=fT?dq-qRu)xd!K^M zzjF~E!!Ri{5>Qqxg<1g}23}{M(il^C7$LMBKS0R$2qCHu5ONkFClT^h-|)`BUWd*Z zbS}~UNR)qEga35=R^yk>A9OCE^MwHQKL#!EY2V3-fi|dz_4`2B`$J)MD6b2&_an8m zZ7!tt2}1lT3Vq%$4&v|Yb1@oNyMgB}q_KZNt~&AMW`vwnbs}UJLM|g@JwnW?%LsX4 zKw~V6_an^Ir$K#D7<&VRMuPHvux#>hpFfzpB!qIR07fz>g=Et2?q>O-u*9WAXch}C z?AwIZxscE|i7OE~p3K6h^$nJ=pl|ZT0AWFCK$_OR0scV7Vx`Mvv?ZcvBB)p*@pB&Ze^*^!F-_Erk@8xU&0` z(SP6Ro1W_rt`es}xw&L|W_2}<{|aw~?5hjC!e9=6?kz-0({+?CEZp?c5m47h!vbT# zh5DGszWFCo;#3rtxE=+iU3bmPoXqn77~awt&QahH6@?|R-yRxF;>&3EWkc^^O}^3_J%l}ds0Z!3C3I6i9qY7ypBoDGyC3Wwto53qP>HJ+>B(6N z4 zxLiYRKWzxZ4}Z}y$}w2KM|;^){HY6zCNq^K#5g$LjO zj>J_4Djkf9+j|@9IUUH?tv$!<4U9%--`F{vDwAPLTs?i6C?EY&;*tO!UEC3D6L)VW zN)w1Vh?s+n`bqDo;z{V22PgT1GwO%^ffeQy=u_Q|r@fK?gYixfjO525=NI^WQ_h3;blsqA8<@VjSte?uu;#uT*v^In!4HlLqC z9m-WSub5E)|6F`9Sf0PJ+6}~f3iusX9s{e}0GxLVJls1-eX;i)T2@AV52H@8C9t-p zG@dPfCrG^pZ&FntrXKKzjCvNM7=S}=fxEE_J;gAT-p`7m$8A0}!9O8T7h_RdbYHJR zNvX6@hv%c&9~P%joS{0`px;uQ$Y6~+Jn#Guh9XGC=LxjRn@G{YQgnL$%5WV+)P@DA zT@K>z_w4x}3~>Bf_3sDVm@VQzQynZ@S0oTO28Kw z#%@44Dhgx%_r@qwu#9{0sY@!q_o**Rq^mVP%2uuC746Y!2r0 zPT*FuuU6q)7MLp@^;8ax*b&HKFY*r3nCPhvrjD~7zFf#?B;ceHNMnp=;ZW|DgTn1| zC`MMT1pEc1QJ|u4n7070VP6u^m|RO?tRFbNUS=ag;8{a!g!NfHdNK|5xjp_hlcwwZ zlR{c(jXLqAP!;%cviBrg*8*?XL46%4`XKkssgjHtE7qZRhC$vsx~otIy*Sr-oR8rp z%(cfme74f~G{gPKAH~|@X`~#6-59a^F48gUbAOBzD%JO>^-G2@X#5{6KKy_77IduB zxqyy)A9$66>m8*4`D5c&mf9Bom6E}7J@4N-RN6BrRaPy_IKTJTD36InM9+ulR$(`1vee0^4P${wsd}MY<-z7Dh0Btmo7J zihnuyeRhz3Cw793EGG*8(Gt2+(w5Tr8;45t4f5(`7@>Z;TGRMgzc(0Plj3v#8#F#4 zHyDlw@LvllEOwoMwV-yn51I@bV~p}AxyaQuKu1$e3f2ys$v+|O@{KBqD-5u7625HKBNsy8cHX62+Xs~j&%f;~K zslkr_GH9Uvec%Qr_JhCMvq($P29isg_ zFn*G+W~UZn7hI$#Bp-aBZAqs2cowyACotY3W$@FDe!|L82FjU$u)9Nv)(p{F?puU> z(%wUJ_aIK+l!Dmxb}(;QwPIHTU=B4Qb~OX~Q9d`A^1m(w`t*E!m5Cmi=zCVJG1im4 zvYA1Q&x07#8Ak0Gu?uzraI4>dw9=59z4B>6%%c|qr5Nk0OQF=nt^vf;+JRjmKz^3~ zRF?h#wG4{=g4mUT_Za1mXwClqKu8usAjXNjdI8ay=0{NASo&huy5RQ*gWqrU)0r>{ zwdWeRB&TbPn4a0yam8`q;X#trZn{8}*W9D}adw6jrqEU97rH9^vBmH^^lx4Rizl#A z>T`>HLh#B&*sZ75_}n9dZ(sHM+;P4E_rpFKn&=Ch8wS_)rAk8R*rvRRuOUN3xoslX ztBgXFkHYo%e!9;E{uH0VIcN)qqCKDYT^VmO_*gj{7I zmv5o0$4Sr!nfL$DIqj!(P9kJ5^)^3E-R^e<(}J%q@NE3JLmK=Fz8_gg>MbETEF=>l z0Xlx@euv_#skem8WFa#=E~A*0!tdVU;eoRqID;X(SxDn8Ax$h~|1EU%eU!4c?>}i3 zvyfT0ge+wtm3@P?3U7WaHiq-v=0};p20No@HP=|0nCD)DAkM}L4(tMz3%{I zXP@i&OAn6`3E@>cH_J4W_D#C?^-;&d0m0)!I3v-|gJbg;^Op110998a$lr)9MhwV>Miu=Vj8 zb<@fizOf}0+F^5XgBfXGt{GFEN{&2y9X_!R*U<1-f742gSx1XTU2S=oesPuyd@+gL ziuwazJbvBX?Ne8qHd~(Kax9xo$G5g9)%5!$V0~#PYE5;FlBT)5TIBky_wduLPR~&u zmO7u)Jve_RU*iM>~Yqu1G;@8+=4He$u*o_P;%&0IdRrj`PLT0iV&B{=Q*xk*-YAG^4eEl*bXgQUPaUk?>TnQcHqNv8sH-d zr(|1OVt9&Q=HqhTYH510S=ZGL8)vW#D+lhQIKcF_I)BYv9C zTwfaITale>G^~(hZEXp0eF~kspWQ$Cl;j%L5$b*Gs4lCGYMG^yg3KDClqD7kRj{_= zy6nBy@*$+XGd*Z0{MLHLt6zEH)q7}7M)~RUjIV}%&s}lq_$az=jmlfpOn?j%WsqTXR zMD=96Io+$liAg0_+|Q#tux|_+0#&%{v=@}HN?vn+)6XH^P0tKSqlu*vgEUU`XEWWg zpWUbXCKF1JQk&VEiq^d1UItq~@#+xVmpa|kdWkw7d3U<|y&m|$ke(86}7v34R;o_ynniDP?xZO2>X}A3qxJb-W(FIjz#I5?r88rsK>k0 z4C5o1^rO6X{2U^HGoE{`CjsCmH{y zqfYnVy^z;)@9n3$X&mN?RJ_^xc}>?nLbx5a!Fsv6mM;v4SflB9JKD;I@9B33p?i1@ zJYahFhSp#$wy{5>R#JE>Zfi@ZE2WQPVUPCns_J{V$uukh_qtBVG`sQrRxej~&AkL| zbqzdbK1qUp+_bk^!X{8XO3MBCZXgq7z2=_P&rJ;} zehn%aU1d__@UI^Cac=6;mY<#BW1%sDIVf!EB_}uG59fdKP3QjEunR!jXf8@l?K*Zs zJC$;}TYcOFu67CLd+^R-b&Qa}S}_556h99orWV0YqW)>GKj7ol!op4W6e=+0@xBe; zv=-3v!KYu*FYden(h_w%MmG4K`9JTe|MRY7?;P%p0^iHn`-q|Mqu6`Y(7W`1-pSCr z=jbpZOvxojRwU)7VjkcfBG<1T&vB8<@1dS3^RZ%Sar%!%uTc@~B+%nUuJB%Huo5X! z4<|{PQJ7PfB0LKGc9H9Tj~YFHRd(#tu{C^lY)$ObeD>0uz%PBm)}{KXoH)cSssY7p zYfWeopC4BvQP*aLK_@#7x-7AJsoDa+glgy#Zpkhu&rXP~(bPmyUoqIP!bfHiQT;+S zU{GtV1=*+vx^`^J*?O3RjaEgikUXc0=@^4?{eAD2i8-|rv;yonyAAysQk$bNi%6VA z_zj)GeSOrrD{oz|9~CnNI;hMSa>g15ZKc!xz_|0f$NKlHnzj`eEmow;o|PYIImJUJ z#_|j9DQaLndn?{>zu^C*B~H_Q-$>1c`!=@-EPXOt%c(f=p>la!jmS2yCZQI(IMbSS z@#pxxY2-eACf4L*eF9snqBTxvgSBdzxLH=i+ZyCQx!*=OOx(&~odTf^HFQS%*}c7w zYL@;LdXdoPo3>c5A)9g%YcZN{&jPI-L$qM6B1o$Yv}*sqv{v?Qf~6{Af5J&H_8>>% z%c-TB(UO>UIdtG_e}X5Z%`IF5Zz#Ob{c17Gu2HcArEY0^7T^HE|bf zoe%%bT*h>Vut8wM4TJvwG4}3pQCIo@_<6tQ$}lhkczH83;9Nw30YfMgDZ`l-1+2VP zDlUy;HGtcW+7@2QcbYY#6*6itqh;E*3To~o?QSif*laIm`~A#l?t*BcC~q&>PS*B@ z;WFRn8L(_W-^cIs`vc~E&ikD6K9|=y=XHNE`Cp2${YIYdPyuHJ_0Sg)XAK=sHoDt5 zntvU->=rkt%UfsUJLR34G8*xKtUwU^dF9H6l}=ZlvOK1d*UhkF7>F~qMfat6F$`aK zCQj#wwhMijh2kSUl zXiD#4tiqw7m5hgP7@0>3dFEb|s_q0!dz&yM$Jd5OjffGLc_ni0bL-vt#BQ%i)hA*; zd>s0N7QONVaLnZeAFbm5??ar}X+qAIe!RO(Gbyy6LH@02?itOCYZ9Q3$M@(hqibhwiQb%DE$1oz5XYZQy zx->Kf-f8cwqqeTEcVQ2#-H=Jz>$|wa50z+v1;|281BT`dkJd82NrySRV`mN`F@7?* zz^sNpRXStDJkP||-(Qk=n5kDc!G|E)$1PBQN29?j5B+M0wOlK&ai7-sxH7HRze$&L za3fdBCm}96G>Tr4c~A0)1LxMin(Zc;bAvzA-_XVJ$8}rzF<2KGojUGZ(gD`;akI-{u^ zeh1E}ycEy>S`;JWoAek*kGKr6-Vm|gBljw(#pUT4!reGM+Du6$^kn`@tm~8b)gBJL z2=y>|vjk;yR++T6&OSuZpn)6n+uo88=f>p9~&<is!%<}pTRz*jf>4T9GO~i=g9v#ZZ zz~`i#LOJGF)2Z{x8| zkEnf`rZ$fFV|-ek;}^LR2_0WK-i31l9>ZF@^zM_o`FxDe>d`c3p)c+{U5&z`E6gJj z#HfwK7lwD(@Y(!ybf1xWVp4gf@V71@xv)*AmSM7yo%MFtm?I0ZvvRPr2E%l;T8lZl zv#=WhL1PCNU_Yrw_SQos>`ta$HL|O;N3t7pu(Nd7S0{kauPWCx(-SzwU8v>#nYx67 zD!!^H9iwsczj79%2Qa`gdLS|03No>xgU0v4m(QGn2jCv z>wZ=91jI$8`!&W}rlqhj3VY}jS8G#uY7P>ksvMTVMl&EodM>G1;f-ndTAV#(9@$mD z>xZ4)-SDw>`aa=e5B1yt+CNO;cbq%cH`9I}a07~SB)h+W&alMassBRrJz(V-?HkE? z*l#Ldgqy09;B<%=%G`zU15L8opx#}^6(HR&z@pG!%9kadc$oY8a zF8AKrY~5kp9(VEA#L7rENB7y8K?}SJzlilUl6U4B%J7JrfnBi}< zC7-2ZD31mHR#!a^Pz-IUfq_YqRPj=Ja&%$@{!<15wXzX8vy=5i}qZ_`=*g^*J zh|OeUt`;pUw3lkzxG%&{huU#RvYBT_-Ym3#CnzT=f-Z9`D zLzyI#tOE*<1YC2HUKOBoP#6Z~6`hs0`kMX3q{cZ%wGKb-lSNOwRD3V4j-Gko9C)sZ zSxCp%QS2@M2xusrC5pk^C>3~ByfZ9mEW%y8pq~K;tISpu-AxNTGhd&*YyQqzJ0IFP zXJ?OC9iD8a>u_Csd+0dUR*tU?_T?c@i7#G<-t=FQdksE0G)P|))k7BYJTT)U;3s}^ z!9sXEQ-4;O@LN}ATL8?fC<^fpdFBA}?g1q(X{00b^)n++yZYIYr^tYG+wDwG7?>-zD08W<3GMEp-*^kU#IfjQL}c+q z=Pn|q^`+wXs`vuFaBJqIn7P-Grt=1m#ZmklG(T|Rp+S0fQ|u`Psa=B-@3=Ze;{<$@ zYW7zKvT$O5Ej~Q3*OUn?DcWvd{(-L%orX8%H&I&UinuDmV=rt04)xDo-gI2U0TYz? zPn6KNO58>v(1$eFu0`}=%T+{LjcL$rQ~KaH;e2(GciTx#8JFk>PGFOs*IKfg=B$<2 z=dWTiq(PdRyEYaniXq4w5JM;G0i515iSRM5f>pDRdjoe%l4o|*^CrbZ;=H49KGT^R z4J?a#C(z^ekcR%$2Mf`_dsxF9%)Asi0a%5Rz>J=*viCi$awz=CG1p1qjON*%{N@r*ZK=XL(<8G; zaLWM(0sEf~N`XDE18uL^MR6^*C*xg}dBVZ`BU6bKJlH$USqF3Q)EZ{Y*WCsDb@zL` zvH2m7sd5U?1y$=g=RdRyUU0%vJ~E! zs4w`7wG;w4-6q@<`)VgN>v;3l4E)dY(>TVgHMxVNDdFd4^!X2==}%W|NZb+mneAsY zvi+nC+$@I{3Ala>IVDeqS7$gI+ zzM>`$cWi3&!WY{&Yf5#dneYTK%QFG11&8QZuLZk$#Jt}8<}Abun1DILn%;G5mL~RQ z`L0a3xDax;2Y(K|~W_202CIxdZuq|rND=DCQmE#{YDY>P2AX>@E{$MDG3{V=k~ z(D29#FtU>)Bb$8N$fOtpgVPu!V3mhI9W6oO#Y8w8~;gcw&>bF(#I~oMY-^y{T``BiiyY-a_3RdxF=McPcsM%~Q$a-aMsG#BaUd0KW^q@^6V&<^lhsZydXrGTslWaA5^;a+cFOSRd<}bgKy?b-Pi-$ zigzy5m2uZWr8#+~fZiGOwjh?%pk?T;dc<>C92d!Nnt-ShUyB#}hGFEgI6C4G%+nhQwD>o4qfvNG-uUjfL;xM0aZQ*%u@}DaNRThYa|&fVUfR{%1m*PuftKx)5;s zZaB&3Kt%0LevZ;vQA$nfjmNY8wG2|g$NCz8TWsu)^(T8)J9VC9_<7QM^j=-mi;TvT zx9-*|+~Q|w8eMttUsOH@{ES)lVQ$73u)Z?*Qgjkuwm(Wed!OTdx_B>B;I)->f}*z0 z3}}7n50%0Hkanc)-9>TU(V)0yb|TsaM(`nGg&|Hx^eHDG^I8o%ZOmC}ZKCq(u?M1Q z+!*>-bbeKRe52Z1Ycm8)2TMUWat*#(W-9TUo0R-~c-N5ui{FZ~lF6ITo8Qf9o&Y#C z0Zs>c3*54uOkM%6+6j+X@H-^Mh_#+rfzoGm4^rHvx+wWotYXvObSF6vzr;kNuvZr8 z-CMS4dAgFPv66G5D>>YAtPrpRQ`1BB*s-R$poIT`w7F?ceMVDp{f}#$J+#`X^?J)c zKy)d+myTE#pnWqRqi7f9&`wNY$fZSMqN3Y2?E@vEzlrBLjE;sf#q*cXJR4-MlF z@F6)6Uzg|JJ5f1uhelXRsl~vTY-k_>Z-()Pi+zb`_nP=zU;dFKNXx#)y*SJRxdMG& zh56gHibjw9+f@E__&Ow)3{S4q0(qy3ogNlh&SsXJ!Rv)h&bXaIzXRe zy_EAZi432XkM`xItc-6+7 zhULt_uWJ#f#CwBF1huXNjMFnaqc5A2H!RpC34J)IAb`|6Cc)R<)OB1T2|NevN*Sdu zW9yQlC(?&Fky4xYY(~75hA+g}KKSSLe<42C8}CcUoqL>1ZPNRbUSa`@sZCQs9eHgF z&JFh=wfP=Eanx7jl=uC9!DTGilG>EWCDGlM{DpY3Z=Ey7UrfrlSWm%!?60}tbes7&S+GdlcVPHh61gBlxE7{};X~MeLk)_Hl^?fU6jA&sI~&#F?3enMTw=dV0R< zg)BG`yw7^Sy1uF?2N0k|tUVtWhrc8*y|>{FDD)CMi_uy91o#{2`MAR~G=W{lj8F+aH*o55YFDk?PHx*KDB<|B`hYG*Fr`Irh^iuGOAb;JDOZg8D% z=MP(*?T^Jr`NNXXgh4e>CF{DJ5e_viyCTo^124H6WpV!EUXp~gg9*M^jDyp;c#73t z5f4IRf!>qrOCQ}id~e>mF@aJ1a8oAZrrc_~`}8(&L}(AcgwEF5au+ExF_hVCn z+gF=$gr2N9{CoU-H}3OoM$)MBao^%pU3vTch?|a{osW2mcU=}=14cLjnDGs9-q0;5 z-rT=XSX^rM9L6nK;5Hq}13A5m#c6yY_(~BxI1o$b%T_jtq9N?WcbFQGu1kHYozRx3kjaw`xcl)~l1;qgcE$U!IF&kywzO9*tuH{}uW6zsZ+LEZeTZkpUZd4apJDWlYxNmwu6}^3!FyqOE;V2;L}!4 z5*Y#>^fmB6+9neJN9-q>d@`QnN@!l&5Nt&2#zdb#z%yGnD*Aj3&yu>t=<|^w>nlyQ zm9L!QmTRxq!aw1jdVd+0p!fNU_3WO>e6qe+zY>tXlpD|Gka?UT+0TE+Qw zXnh*SY7DT}^uVvTrTZnJH^MIa;=9_CjGJld^>C5BU(=avex*$NeUi`b<$THJ%@vzX z(QmCC`PTb`VrzHGF=OY3LP%qlo6d_L4Q}@TGa41)TR}wJw;D20-~JJr(#H&3kE0$;Z;}~Bc2vnzWitf zV-#EB)EM#h_;|Pfn2CA!2JS7ljqNxuK0oO8TMf&zNylhnc_4*V=AGSeJf&j; zzfBTKhX3kN%hp-VN7?Owe8|n2^m`Bo{jzujbTj>Z2Qu-b>^p;Prj0oFuZjOP*k*bG zPx2`5=66Ub{Le>kglpnaq}JnE7JYYcQ0k{GZ0##B{0_XYJcG{PgkLLu_u-B$NjHem&Iy$3?o6ka2axFcIp9pn}6(K%K3438Ob}fSHv&F!#tfS z+$0_nA>^Flj@eA%b7@)v8X-9BA4k9#z{**tun(Q{(iz|%VJ0P zvbd#xOApm`xh&fIHwhGXqI@QtO})oV#pJxWxxb>y?Z35pDTjyQH6H7Ss1A^(zSFbZ zG|Mi7j^uf9b^jID8$Id#?%VPz`wzHw^dw}*Vjo)J7SuOb8TW|k5TI5abo_q_`Eowf3um*aq#p`nTj>o3+*b2Uq%j=#Ck?e zCYG@Wz7gMtRE7S2A6D0mv4kNZSyz6*zq_clR)?pbC2J4H@sAg6+~{58C(bb^a>@ul#_SgNZ@ zY$h3#;Imu;8F6AW5A6z#MSV!0Og!-xJ>rN@9I$jT)=_~r<1y2R+uAS(bR~7+RkU5c zfaDqJ&R>X@z2OznmaB^-4aw^&hug+3Io73fshiKP_O2c`e$)|lb54!^`Mvf|C1+PR z1=r=c^4yMDTa?92{W?iutUZrEr7V-3B4wH+`)U`JL#C*tzTKSF&w(0XLzalcF88%1 zExwE6vi<62ZWFZNLR{p2yTW%V$&ieAOx`7%q`sJj-Jshp>DZ8Jqy~prO%2h~%x$I5 zZBlvjNYcSXPziB;FPl#hc+>SsK-o*cxr4`BkIb7-@z21$Ldqe!rcOiy_(ps@tZw)Q z{Q5Zj&ks{bTaS3T^!Isaq)`31f!;Qg8GLQ32}cG@r54^wvT#awDkNv3x>^H!`3y4l zKtycrH)CIoMGvHXS1z&Er2m-h3Ru?B+0HZe>AxRB(RWO5GmVWH54p4vH`*m}-yoCz*Wli2lKu(Kd!y-+*f{u+P#P_H zAk3!52FFFqy^3=0Mavw^|)K z)Jr8OI|N#9Z}s1WyQAgSpqvEd)S=$+OF~{W@0UO1T?wxj?uh0+{zD!KuR^pbIxl7L zGB_z(cRl#g^cyRBB{k44v1)=0z7Y%m0yJ0Xvm&Jq-3ti~&3!a7SJ+!^g+>WuiiLhR zeRrlW+w_%?5AD!dk?d&c34N6Y0ou8=Z%_43#r;NgaqHl}#({Oe2Y);8+<-qH{@%pj ze*FCge~0n+Tl}@)?+^HE#h--SnFpEmX72uX=5Yc5t;}QBoeEJ9hHWWnnRC;u3)8Fog-c z&;OM``xP0CK#xQVESX|7(h?tOMElc${lSj_FiYBh>bpjYHSG~ua0*BoVw9Nf$@_K1 zy}2o_q#7gHYEN=WCtIQ3B8a~ovO*tKUQ8k7#6Tu`K<~{5qwSrHxLS*IS*_9}HA9b2 zdcQ0(`R(}5_(*Q4eVM&Y-WE^eyh?J*66zB={ipnj9KAG=Elkh>1JK$d=0v&Hu5Cqs zW>Q*1N%kMr;4A9~BxH0!ryui#NaGi~rXuetXkv_phvSP~l0#G{B-q5R=!c_Z}axBM^V?}!*TN5q}c@{X;DE%3jT9~*IOqS5AQe~jBA;N4Ug z(H=cwXQhbmDUW zqG`w0ui%r0eqnYrZG7b`#5<=wyni^28TkiV{C-2GrK^0-beH{I(>eIzacs^(`dyRD zevYp7OLPq&umRan-xcQ+Ok~7kYc7sOo6sCYw8i_ z4o)WTESrd$e~i|g-E}og6gO|3W`=? z9$PHOe9FLg8~)0*kv7VEpFk;P$k?YTR)#YAjMd7}JA-npM32}$@J_|$WoeIFu#aP+ z`}lIWxAimJThx~q)xW2{U4s(|(HF4VIe1RUXR$7q#1F&AtEA8)jt%g*9h8AZRU~6{ zASU!K>|Xa)_lVsCmKF4E*NR(jRd~A>Z@X6XK(Aig%3v%F1J?!myJO&cVOAAgPwJ_S z4F$mMs8~i7zm7Z<{JsKD2MtlZC zz(SV6H+HdNi-tiYQj(DpU^8&_l7H-zJFGR(X3w*_-opEq zLE|rameKp!vI4!cW(In2;?cQ9>>|v?GMwbGHf3P%3cX_7nI7PjtZ6T1_MokCFnFN((i>P^(FB@lmfp5Kd5$CQ0=j?flVv+*zN!T zS%~BAX*ElMgV0+dA}#~vYza;v3#I_7L#@#Kr?!}Es130k$HM-GK0nh3z2wlR;er~( zB`7Fx(YzIX1-ON1ih9Lc7`^ZQ5EfgNQ62Rh%;1X{*?9c&h;%fZJ3eQ;i47@`Z-C}H z8)ES$)N<^B3rC^zhF%{+d_kN&fw&8F3?)%pfJ>sSPg+McW!Px$j6VI5qC=3E)=6Q* z_8Iu@*Tp*q_L}CJPq5O4t77ROjoB-;C<+~GbKMR0_uL<04JikrLvs>TqR&75;3-aF zSMf5>ldD#{5fiE5G;}OIkOfoS8F{0k?m?WN$NPATk1fObIR~C z8Xvl~OW)k!PIfPLce6t3Cxh#3*wW#TFbJv(+?nG&Z@7(qTcCERFdBVpOz0EkT(kA zy1uH?vYih>8cX}LUz!#bRy{75Vhos-k?kzfSU2GZJ3l1{P!8sI}TQV8ny$ZkS)kTUr{RaAVr3ZYk zzLL_IhKD?l?qEYldg%;QU(`46c0H*dt(!7-XjP|hqeSgt`X1#7G-6T}F19Bo=B`R}PJh=3 zIrX)zr#MpIR9RWM7ZmiAK4>ugB)1E>);?8T#a5a3!NaFH9kh6)4b3k<`ubx#y2T!P z(?d75=`~`UTCU&5?vlU3?0Twb$}42ob#W-1N%SUZL$`P;Vj?lvBN@FR_+g|zJD1`3 zV<5Aja*M}y9ori3df+pZIS0ynD%vyjYwK2Tq59$LFEEHp2`T;s=prIM z(&{a$MnvxkCS4$wSkHTv%rxRzT?u`DjPCW`Sf8@4ypGmWUdY>$=!u6;LJV|{n9$pi zM4t?r;R!x9XiAg_40MIIDts%WwgH4aCk})o7HOiSP~+L}AM454#@tEuCz#M7a4~YW zy^Vdtr_uD=5e<#+q+4kJrTspxAaNARj`c0h(Q_Q$?u?dx&b~Ou7_I$Eq^d~ctABN& zJ)5&8YCLJsi-5f3RZZh!esnahL&g1z?A+lElhfTNl9HQZxCDMwE2_pd-85rELg_e+p|cwlQ84V!On8z@suli`HEP*;^cT9p5{DXZm5K zZ)H^P8#`j~LEu=@hDAHOVR1+0c`~o=UADfeWGX0$MANeJMUA9>IwZTBUpa7LhPEMSy62;*zQcTKsx}Dl-(7W2}J)voS{`w*$3(Pu7^V3(r_;Rmxt*W z%EEMZa>L+}H87#y4t;c)0h|!Tr@hjX=T7vC+sK?L44tTi7oUmKlDNW1Rrl=;r$ z$z!|YoD3t^*XlVvG*}TEs5TD&;~L6pH`z=9#)zEfB!%Vxh#s`6#5a~iU>{SmsJ6`? zD^0e`dPS$=N6U@1CsbJg$o5U*$UKvyxQ^ajpqx)bi=A4ac>2J?uyQV!UJ%(;I* zrO`3pp>HCQ5HOb4j>a5G1eVN(CiLz@y!E{}i$07-a_+ zA}Sn>Z$;}!Jo*|9a|CYcgkvV*5| zOhbdMkCXlp1LjDa71~dJf_)PEj{(lGu0C(6quw`V@T)DAN$nuh0@uiSW zJrQ5}_b0YKAvetjj@4}6YG?DI;R%dQ6?!c~@itZHg~&!=+dbmAA&SK<1pe4o^yW(p zS-NHjaXnSA7Hxa#9CWzgyZC(96SPbbI17xW`-xsbWj_9twq>z>(^E5^IyY9ITv50c zQk+-<%Z|>EpNNQ)QBv~MpPsUz)DmuoE%qGAlAMR!<7}Bt@`U86MI3`tskA+^a&k<~ z35E2G2l^nJo{~IqQ(&J63AFY`T3d(Oov3{lwa<^#*3sG#`1Ac~ZTk1}1F&GV~_#KeSTgTr&QD)Oy>IAkNa z;eqR88*MkwF~I}2f3>SHcNZYLQiWo`l^+|bjaXJ(TQVurg0IJhDq&CM0)>;dA{H>Y zIMuR3iM_KKQKvP=7wlAG2=7cCq{M& zqoOGvQujq(6B07M4J2mt22`Q#5w}47JyV`i-BC(^Ul#v4=qw_kPlm>nRuv)6rR5j` zk(b##FDI2ci}X&iLxpIw&k(&+;Zb@jVI?2q!L}WW$6L84u2iv;@hEr3>>?pyXjm6m z0*72Lqvc{E2|X3j9;NX3-!ob5rHjP)**Rj|@(8Q_Gt%0YEs*36M)?Eu=?=gFwTV?* zvZmzLsEN)tCYVHE4*fH0y4zCXP&XF;f-kG3}jV{LuYHN~uz*v@zg*d@I)V zPQ%HPfc^9v_i(?>xCZN5i^crC$FNgv-C%ox0 zrH=%+tYFil4 zKP#f^LMfpq@dVw1qfEWz6)7x2a6+{IJeAs7@57jAEM$3VT3`&QrYqw1Aqo5@ve4~s zA4n{b)DiUKiulqH+bBWQs^k7;_rL4cf>Wpo)Yut6(pe+GC>rK&WkX)hKG`t(v9AsNd*g($&~$-Qx79okh1eC7h8h3C?(hm?L6S^!%fK z%va-H=|)s2DmSCQbRDmX12{FTlcXc1J(1O|s!0Pu<_L{DD~Q*Js13&2fl(zg%o*)_ z`p|VvSu!FW!fvQc%cOHbNU(Joq!WC1;+Gjv?JP;l_CN6o6Sb6x!1krZb{af)DuM16 zKkfUw!1=Y@Wnp*>-Qt&!#$OeGAGKDKh5kIin1_A1K7gK6eoHJ?NQGWJ364w52=sJg zj_Assz>L$Cz6n2&bOiQIzvIe7EXa-Hze%Oa1Cw@f?J&cOnQ=B5pj2|u%2{rC9^G_|ja zzZ^J<=wq5Ru8X#GReTg9=@DP;XX@zO{RWoOZ`!m$0u8db;N#1PS#}qli5nZb;j56| zSOWYJ&=qE;{1e;?%1yco_=Z1)5@U4VT?bE35TAzCdym-CuYIV%30qs(*f4;qrEJp!h z5ZT>GCOD5GI;AY2H8)2s7_uBgt;;J(*4M$XFs>zOq@IdYLaU}7Gz9$5LyOAih86Qs z(kiJ@)p(H8pmWVEtSPN&(}e|zTjl;C&t2-KdBh!y-(g<9%=z-s>Pm3HtZYE%tc9)= zF;>-{lAVf^)JqyS!b?kRJKz~ufi#fnSnR-N>{>!4Us%Oa6KC3+oJ>wIS>@d3_Urc9 zF1K%8&q8AJnfq<78d&Hx)LG&X1ZYPDPdfkR-o0czcN6-PNx^s{+YBtYl;u^m#Iwc8 zLYHnicq-k2X6V9w=o~-~3$>^@p21BxTsr0_r61_qYx``ZbepcT*#^>J5@*&bgeq zc9wfF?86fiNDQTa3lUvUnFl&2=0m=8jmB8;g50876Xs7ovhD?i<>VtDzRxn=zdH^3>7|Zd1weq~PbG=WV z_xXM1>uWuBE~seUT?8$1wvDSOn&jm8X6Iz$B`Kx#O5$-8(OLd&uO#(10bXCIt#;}k z*(VfQ-$cw~B5mWEos*nil2odwBc6Jt)H0bUpfTNu@+A1G!0UPKWue+B^?H{;;1qmO zXm%zqq0-n5LiIXk+G4xa3A-AODbUxH`JX}L?WKYqYjFquD6COla3Qd)ys)~|yx!tq zU=>#3AeQ|OWnPlK5S}M2Pg^SGCAz|mmQE(gZdp2D=_Hnysg6}46CxYPP^34ygT^9y z_jt4vA5L>T>G-vy$I;tL*G>)%xO-=j(1jszrm*XdKo^4v_4nmJFu`GUnn|kZ?pdrS z%fW_{`y7tpoyi*W)=O;az)hzF77)KHXK~g`8rRxSIJeuFQ=9C0Pn$`^l98L_n(y+s z`o(7u-OL`88A<4)K?Qu#5okzTN?B}>d;^q`NgsSV>~#?1W$|*aaVh=1(AyRLJ>RP< zF)joDy7G$X8yrimPQdZrHOM08vY1FEB2|~g_&!5>q&|N7jFmm&6VP0-Iw)Tv z%i#d8it>x;IodCd5C4_w^gO{BXXBhZ@h_siBA00+5ewhm#OS)##TDO;%mToixXS7NJdM8)eCgI~; zGih7IeB9|>dUh#=0fs`stmwXkM|$w|L$3|dHfaAP&UW;d!U^^()@>a0DlIOybpKMe zw0o(xRi%>T)-lV8q|${b^7O2ah_6J_muBI7ObWze-7gOgulqv42I*rh%hsehz)4+6 zS6(`c4W;%vml_GhNq0QX7!PkD+S~hMi}q(`v_JGc#gk?5u3|)AI(pNc5=4}M_pMs+ zNop&2J4VU`Or&9^tCdAxt~)Cn-w9Id&7d4!8erQ)J#&W zinKJ@r9-^+{s3Jcnor-;{Sgtrju5@JmA53dbb_ygbA@cIN`{Prz~5+h<+7?%&~oP! zIc^N7O(k>~m9um%61p^~D5Vm54zRHYI)U`}joz@(Oz$Dg?GE7HV#^~BGHE&B(|;OS zP@*77H4A1{7bc;!#=89froaX`XtP9qPLPQOd%Dk;sZ(bvpXoX}8y;EP?P zF}AP~XPT6Him_W=I)(o8i&Z3(I~TT%`J8x@Y^o^#K>=-whMC=!daiqEMHMDt+5YH^ z(Ojh^vnC03yQ})S?q$S!SLePeP@U&5F56#8-&>%au?aL#g%kS)vkd?FGvBJ}uG(rd zcCxf?p**%9pF3h57Z`;SvoP|F&@w2rbuA;A-=HoFc@s@7wAp8r0q?+VU(CiKOStdw&^ z&u+66@B#b{Ym+~p)zbB$^=KWeMd+)r!aKqhH|70wUo(;ced z@LTF>i-fu`Pwnt$Nj%K%F9q7C8P4b)%U}Zp@bXzCbv7;ccSNF=!17`DkRIcpIave4 zJFXD;FA4PyTAj^+lJO44h}lU?DxE%AUn42>lGvK&s3xrhT3eJm^*^Db0;?p&O2d*O zaG|ncW&~a@hxaP&&#n1&wZulp3&~`t3cVpgSF6PNo=qCGJNMgq10?JF0L7?DsAAw> zSQlD%i|*6065{6O6owIDUfVLqo=nb)lW>2MAd{nQy}Jb*XUh%jfFJi-+TaB<*(oor z2hK-A+XimmdDAiX?@I{zf7Oc_{Mtfx`baJnUx!@(QSW%wM!-4KSy+XAUpXMqNJikw zmrLPUpwL~f4{Ek>Rc@<05oBYrcAMX)*Tb+SEQ;A8Z@y38!GGk3w<+=%509xR88cGy9{m!uKS6EuTWa z^%MNSMfs8voSszXo`YE*gE{{ztTncl zZ$27FKD4pt5fuls$(lC-CaYi#_We1j$yQG4rAU#+THDv1a-^AhInoT$J)Mk^Ou7`1 z9D)fBw(Ugtt%A=N^s@uhkKR3;Ye8Nd^8PzY5#3&rMeZm6QL=aFj{@zR6uo%)DC431 zW4xfwCVFh#IXQAA9u|2L*s*HQ5!zRe6loS|CC0s}oc7LZV>`(tNsvs0H*t&!-1{xE zLuTGY5E+`#UVZ{z}SRO1Aq3DNy^~FSzjp+D~*M} zU@o!gcB8$wbt*ZA62&OLeZUI8UcCP-{4`q4ZT@*SoBf~3a`U71h<_Rp^!xRz?9W5` zIwf(R?rnXwy~@4*aj>4P|G1A#=lj zgXQe$_CE`mi1H498025VD3BW|z&WlVFO3+WSxouswCam@SS9hqiSCC=Wv_?p35+&R7eyRsyn0wt!@-ktgv;nu#X~ ze4WY812b`PWC82;njP@00RE_}<$k9eV?+B{iomZc(SEihpaR-VOS?e%(VMu?8S7Ay z*gTRh4}3yf&SDX*doNmpUJGa+@HS>sUKj5BUIw&}t5penwb>R1-a|s?d%wfj=~#MO z#u7Pr5V3I8s17J=qJG27(o}iCj{8>@-0zHmQjWClNX4+HLW=Y=l_JqF>GkCAKRi$K1NQxU-6|kl5Uor`PtBstt^$u_qv}6ge zVrG_zJ`7-fNe0I6{B#a*ec%@o=LxRFfoF?kGKFDDUZb5s+JzPg;?t4PZ{YP~G;Vch zyb}14h2&!y_z(1Hsgr=p&&0SR;^&e5&c~w^(ytxqn3Estzxe@6X%(fS`o-ny;+ zA0idbUq|adeye^e#^RKK4panBaK(ruJi|dU#s*(-xLP+l|Gtp=*4^wN*-Y?fj(-E= z&pAh0rFTMtJ4HqxpF7fk3In%O<=2i zcY=|QgCI~y=^*^__@(nREBgDlg`l}`b`vvQD+X%>*mp9yWn7u_dr;d^D-es#>9t9M zo17GX9oBj}X41CMeVaBAEkiWBKQXV z7CvE*K~k{@9^}eMU~!?1_^(H8TIgHUS^RITV4w>L|4{fbO&4r)iPKL=RaKFNEhGdQn9LwS1rE($8wES?FV9Zc=u#jnA5g2o=t$xOQn=IpEM@+_-9q}1A zJ0yAE2**$#-ZeA31INtsNH4gPa$wcWc#_7{Q~!?=aGf)V1ZO;Ww!S2r0y~SYashhy z2>8mlIefVUTw+fS^74^e3eTw;(uH+55UH=urabGmDbN2*$LXE+xw^CBvtdax-Mtpl zkMBwXx=JQj2P%0n)^xGM>zv1V9cKZ3|L*8;e2YECV;y5y3FwGz{VecrN&}4QCdMnE zA8Gtc2GJ-XHv)z(0gcIoegmD%7un(W1X{m};?uCBHaK4dw#=BkYijM@m5{#WYBO(w zyVzC~T25(RjCVpz=~v_uM{#ilu>D|!nD?(SJKnSJU%8KG?$Ty|4fq`{4?HwY3ier6 zVO-%MTUn4~#RepLDUs%p%te8?8fIFW3qD&X@3ws(G-f{BF3o(hos8dSD-Fc`Jmq2L z&OSk1W1MDi&8}JE+E%mM^;yk1mwJt1~u zZ0)&K>UDd|W0B1HW(+Ld)Am|%={qQ zFA~gY9qw7Lpmw5Xj@iy7j&07}j?bLu9O_EL(%F?umTs%uz4Wt6)Ld%J^9bgIApu~h2WRdvN_OCgmi2FQ)bS;XA{wS6@gmcforiD+kzqhh$?&kuN zr?p-M=a0g&#DdiTXV#dJ1Yf7p3`GZKH6Pq>b99Bk8=e83sKhRou2X)4?cc#G!v9!} zd}GcRf&?Yp&>g^Oj5bvmLz&H(F{+*Z{@8Bhwss>wX}9P9+3xw<+J)84Dfa^0dNV^U zh(f!aHAy}3&EskkeQaHFA-qKHiQBF5Y8zzR#|0DKU?wLQl1VY(Z!18{vqANQJm_{J ze|o~MoC%UHW0oW^3A<~rt*>jpeEYPi9xSi`+1FdT$Z+jdBdle93VT0Z*TI) zI?Df+;e;#60<*avpi?fn_1D?T*M`upQnVR73*7=gXwr|@1A`tkcVG4-n$`bZXsqgnQ z|4X>vz@og-C~0K(9GD4C9m*fqd2Kh_e-G?_=g}B=M}+pkNe$80DCH8IeTOKq_DRNLb{5;Cqaw%)vF!W*%6^epcU`)Zl=46sCVtla}$sHGPFaPP*` z-f29UB;I#c9PHgzq-i|mpUX+e34cr`dYBvZ8z(9cv?VhSFEcDJ;>gk>12hgkuq6i5 zd`!K}Gu|iPC55L+$xhaz1x6YRy*L%Lq+nw)l#D)(A_4T#cNCsox5w6}65}3VYQbZr zY7d#X>jE<+4Y$F1!!#1>Q@48z6x}YsPlfgfU&j6u&*wdOeuow5G&w2b`Z} zO=^35W3erMdkPstz7SNt)zNn0mzU^j7LL^Zwj-6Ox-v8SgH|UyMdj(VtGu0Kb%m;W z>0PT0@a0pp!WtKlwL4*_ zX*C6Sj18(CHRXoo>Ci-PUkHp{-<}3ulS7!3P69s{j24!7?b?EcnJWWxGM@-C(5s+z z%4#05J{!RdmbizxH(MX?U58ymIt&+7dw$pDN|&|&GW}1dD$$lfXcc~y{$Zdd{SSfF zNRJY%DPuiWrv{!RDPBoWHH~*PEOIizqhc#2 zL9Zki(5IbgB<6zB@=M4stPHR}t z>9GkOt*5jwzF`z}O%-+X3snuHJ@UFy@ROu%NN7ydZJj~tp`EfL);EpL51{fL*1P9=KmHXgi4b74~8))?v7=s4pWl{*yhZ~?Du+gVSNbAc0F*&RM1 zBPDVB1)1hde4}iK6z^G&WII!D#oHf8_|o7j0_}ASdd;G}TV)xP-HB0rcc$KdQ-D7) z^u-wMi^_K{naxYY%2Tahl{X%`nP0aDdNe+jCnWs1+l@xL-#_nR?)na6q7XM+Khd|? zkXRq@U9Z2y(KC9m#|rH>mFJg+OnOf2iEBJC^IoC>BXi-;DK?n|2nzvvRPc92GOq>4 z`0gN}tAk_rJpMnvmI%*sW%|x!kL{b&Uju(p9~;*qKcxIjMaT}s@tq~vLH$@uk81y@ z{3Cmmn|TK7s%ROev>C$AqBh&{z*A{HkjM&Ljso1cEZ}Tj9@Zh;g&+W`N0#?-=iF2Blg=-Y9z&+I>8c zEV?EzIh$?&Mr#*@{ZSvnTW#lph!6%nD=BE6QQ#}3VnoyXCxSjELFof>->)5(r3zn< zqXM$pVcEq4;F1{IC#O#iXmCDG!f9(vFAA7(df<@hnwXvz$Vu-D>eYH_e%Jl!VZ7H^ z^3wAH1?k@fZU{x`qXRP`f4?G(Evd6<0^0WZ>FR*A{Xv|%^U}Km=Y&M$e;L?{GpoUN zCK$1d>C(W;SA#O~`29W*S9(*3D~T_ygG4kAInwC=wxGI{>7r*mwHQ*B_6t;p|55x& zw1nKFB;;rKTLd)-Drb$KN{Af!RBxE-47aVZ+ZIv|{meF5TfD@eNGBZ%OFPm8_Qv)# zlujIjx!1J+X$_N6(4iuwsl-`EUL&2!$GLHCX4<=$<9ae?4)hYSL;f8sHONhi00*#H z!ni3Mc*#btjIafbhOxo!HKr1(tL^2wSI#5UiZW$h_nMRvSo)JxTsPE`lre8C+`lFX z)Z6F6KNknN*Z3}h$|5 zF6nLQHAqA2^@sN>k*4!_t9&KWD$Mh(^irf_Z%Z#idN|GoIGgz1T%@VbnOo(HkxslV zJp<{a+tT?+kGd^QbzP~h8O{$&RZ$XO>o?-Om=IBbL!lxjJR4Es$G2wWj2(GPzn_4& z6VSgOOXQ%0e5Ax=JQI}ov44G#HPiSRwDml^{RV0Jd?%i-k37?MFXMUIPueX&iL*nB z+uAyfG88Uvjr}Cj_adz#FH(*H10TW2`SJaSNZD>H{~przpM2wfeB;1RzVQ~yP`JPK zjYg!4e^TcG)Oi(kRAlqWS6@aMT7E9xynyE)=Vl&qYNGA`n8#wYPa&_Zi0-vp-+3JM z=w7>({yEZRx1}FO`sX8Q2U>jqXXc=ZCLSkJ&-zt$95@^F9ZPcoHr7cIn zFa!umh9#L%T%tA$C_RdATZ*D+t;M!8AQlorCJ8cCYNcvDNhX>3UiX<``}X_3pWpZQ z2jrYHXLY1MU{a>mnqftaJ^#*n&P;kYay8)X0lZyRhFI9z2yi@P z$DwbW!aaAFNykieTsGvmz^byTwX4dq>d3!vds$X(E{mKPM+7wk?noW@ZfSZASGYdU zbUwWjDWgiuR;1UKm8Rp3m&QwB9a?#-1=h_4{^j^y-#BNRUc)tI|8%Nd?RS)MUSs9o zpiK>gDr?52Q^<{ob@A+sjcgv*w(Z<#Oq&DFAZA6{~- zEeE1(&Y%5rvI+7*V{6Umqk-qW-YT7R*r)csR*@9M*X&g zQsnRX{J+Iol=IUpdt88OQ7PAgoyjsDgJimpfmsJ-s6-h~Kz8Ut|4|>VfDMG&ncAEB zqzO0=28_x_`1d+~=WL3frlS{OS+y#E>XDB~UKmF|*=l;7z%jt?7Q14I(y@{(u1-Q5 zA;(yLEXEX>=c6k8Hhk=6UbO(uW#ryTDAX+%hELFbQkn&?ft{Wgcy;MY z2WM|~D9=atpt@hx4>yFJ;rs>`_FXZiW5lf)pL5vU28DJ6B{ka9#8U zPn12aoBi2E&brExig&fyZBu>hEB>AuogI+^3tq76S>Zpu*|`T}5xI9zI+E~~M1L77laUpP5DVBx zk&qH-zf`85zYFs(RrVBo0%Sk+doOUN4*|QE?tB<61ok$H`YfDrTz@PG0%rEsL zl&dTeek`RWo9T*oIg{*@14fp3TjCPYk$&D?{!vsRL~gb>$J>HCoq zl%Vzmn;s6$hHvldt&p{BwZ{}pY0n5W0T1&56Dm(uD%WK!fLX(0tK7rxHgNMhs?9T@ zjTfjEh>ouy!!mOWQ9&rG{;0Z4!#?8=Li!uvqlll)#}`hPtO!S=bnPTh9wv;WEMQK+ zuz}ba)Wm`g1xE#Zuv#EVsEs(p<i@p=$L#qbX0=Dy2gWg+oqXndcdZIkqvy9!kfeN1s=!G z&nnvJ{>N}X#~ko^d7Y)G?~9RGJwxLMLO|D<*MN~dwPzYe8{?auCub)3cjFg@Ime4z_`twr8N)s`A$Ac=s9v-$^byh-i zVvE)@$&WrUZ*!#jpMXxOv1z?VXyJKeV>HDB9sNNt3IG2#$iWx%bs!zHRYCXIkuS}E ze;MiU$z5k_Q#>iYIL}pHg@{B#_wEZ4@|#_33KBo5C4jT(@t(WN^!rRTsr&Sus#e4i z__Sbj!Q5tOLl3OY`(P3B`PPEpBY<3Yh2`MI<_@vENfXWkRCQ-^|Kn!M7A&;cM5UVK4Sjw zO9b1k54bIbhrXr>BzhG-pD`Y524fDu_bb;Asto%I?`nx}+6f!KQWhm^idlMOhj6d#+5xRSiY zKx$bEYC@wG*U)Q8|2%Ik3mr1#)ukMWhm9#I?{EI@wei3oBmsqA7UCAA9QXuwi^U<* z)oC0sF&cg8PR3r3Qv*i{#BuW!#8-f0aTf2-xONEfA4M$Vnm4S;();7f=D=;swUHeB zf~gRZqFU5zIzM{fAYwfaIYtB0i96S>yPLb|@1fmzwtzI zYgF(L=kn+apUIfZx5M`%olvYLPsuRmA3aa2egacALyoa1fY{Js6>g3=GqsFX`3P)9 zG5v$t3fQT;xwbs~{seY#+7+Z@ao^`B?6d*}+#av#g{YS&R6 zyb+K&fP;f4*^}B$N808%PZ~-^R#Bzk6xhsM;8%0}80W}_ky8fNXGEB@85-i3-lfJ^ z?nBSByeR=TFVWB4lvfuIYkd-sEJ`{1MU}hyW@5e|ovl9WgRQHrjN6AJHIh9Ux;4_ zY!k~3%Pag-@YSbrh~FEfJev%Pe^ljBI6{iX94R48u49xeYAxju)*r`~HFw#Iy?nw`?(GYZe{}FE4R&`UTW_nbzppsm$>GdgpHTZcydXpM(Eo;Q zd!DOq-+>ZZ2Bn*097AkSdTcn!B7cW0w*tkJ?>(yVXql>6-IBnXAsxIKBs>Q+qYE3M zV^S6aHEi71&(xkGlyVOoI)%Q=*bGdZ$&}q+*DZNBr4mBg9~H3fWo&o5t%y=IV_c=OeHJ;1lE<#UiR-F~>wk+BWJ1&InU$Fe<`KwDJyskk~d_JyQ<$UsA_@YOKI#TTKceuub*dQ*(!Ws&$8&_uPz$`N0Y$e^WN z*mz^~#uvrBJ)iDg1D1G`$tUV5KTj^uN(IpZJurzlf}bo)EHn}iz-s&Jd8$5&fW9#N z*X^|@jyg1bg3Zc&3Yx`Zk*`BX9bfhch^qG~EbQz5@oQIi&)oBSd=38P|L3p0Fg*Jy z`kEGBgI#dqd+$cR!uS4;?@T z^&W6Co!PiBicH8>wg4Gk=7_7bEr?f#4Sd#eFr6;+(@a`p_&DVaz5w}#@~uCwP&EH1 zzq{mvlyx_+)IX|^7nLmq$S1D!zJUy7`kty1))J5X1$LeBCqy+OC8N^HXbgq+ljuu3 zuU>LrPq+zVLpr9Q55|Z{9FZKC}I2abDqC{9Ql=B*rOJoke@#o9sF;<9T;DS z-<}kKR>Pe8pL();&&ECf?>(tSPY%Ln^1xHndz;W!M;+=uhSsF>Ns%wny4QN(_pw>v zUHYHCw`ou3|Bt?meeXBX!}9kECJa0db1u+=#M?I zeNghkdRKdFuI;^wJ?K$qV33lbBW7m(KtFP=(~hsg(X$a%6Fn0NrXDdv zRZl+L59=~woH}U@VB?h*4YD61iomUy??Wc!Jb|(y#8{OJ*#fX2s1T)dLqL#Mlc@AQ zIGzNHs>#&w0Y@CLHg^%2m~Fy~Qj=L)q*3JrsyoL)H z@hq=$mh%f1crX(=TP#XtOxiJiwAuz9SoYD+gA6Rm3a}*0(O-D)q2TL#9^TVVvwuN! z0dXR!J>&4viMt=(BN$H_1yKQg5c57iny(OlvG=m^G-hhR7>70d^pp?yd+oc;g>1TL zN1dK<+|#GCQcmJEj@8S`9hr8O@93t>#xd!x@lnfHjXS~S`)6rEWIATVVTbzSCPy}V zTE-o!#R5nYKi;G9 z&_GHe_?f4RIg9q)(6uF4$@ zusK0FZ)!gf+`XZsIoXgq`lW-T%DTDM*DDN6VI{`(l)%Uy4oFcd!5+CC+8ytHTZa2a z-;}x1dm-apqdOOW3i;zo>2|Yyt zO}_BKpM^d*%oO7pU2To{Cw@4$?iQ(RWu}4SB%##+ANIR<9GYno!?5Xm;8ukX9Vl5XVs zz8jT_Cg$$7k^k+@OXN2fXDW~x(@}vutcb&b?$iU@nUE18UhmWp^~VPzu~p#oNSaO4 z<>M1xF)~%teAFQ8a8ybRtDubxN)L@{y3-&rgMqLw8N5_iq;7D(Qr)pSjWFA;((3B= zN=}QZm<~7u8VdgB% zZlFx8kJOn|rnM&I7Mio9FBv&1uSmCz36=s`W*L-j903AGk>@Ed%Q`#_+Ac&# zWK~P(E@Cr0FYU-V&@Y)rZp7?TSRSq*&GR84p+k|q?0%MQzd!lNZ+3@wQ*FS0w*RI* zE#i7`u0ea`2OM^m4NbQkC?G=Fu_I1<^7`OGo~{z)^& z(yjSp((fT*!zWU+%E2QZqNh^9ZiHnIad!_ms|LYFqCcTvx8llhz`0pj{g06T*xQw? zW>AX5FO20MYd)IEGGslIwD#1>L1`?UdNlvU5WHAffpkRAK3{2Osg?BAec_stG32IA zC<7}G*EZ{#m7dGenz8sMx~nVP8)~oVNBMugN1@+>f7gzk0$QVA znh73Bnn!uVsfTq<}jcoHR#oW z3Ke$UHxNCi!Dz28i9e9zj(=JZUp5?uoSd-lfsz*yFSw3R+?Uj(d|J`^2FCeLu|<5d zzIew-{o^~HbL3p)3hu(m;#~tdLM4#RRR4#t5-Yq)WDYa! zYyiI&BBpj?Wz=V3&t!d?Od;EL*vyV7LehI92wsuL{_n?hZTTGo(zWP=W%*t6VJj#= zzDJq|g`S)CFW7fUii71!*|tc0h>=v*9W37atHxMwdXVYTcDVg9wg{3fo5&YIq!0BYy0T zio~|b?nFaETfDd2nACQ_U^gn-CUxyDQMO?fLQe|fWZ^EsBlv~g%kQ|zkr3fJ2+KkE4B4K6zp425-VZtb zd8|KN;XM-tG5J^voFTYAC*o*kG$d7yRJ$23Uo%c&DD-?+SoD|zTIbF%1yf_ zzJ6H9d@@<>t-#3GWVv`iQ zFQ3&3$ZSK%1mO75#zE;~M8MyjIC@sbyl_mp0=fcZnE~ni2ugY4YqS;J?{OVtoqz^@%Ui~aSI^q*tOMlBE`Ebz+#RSsYj(xYQ+`grEmt!bTwPF>U0$4EYT zI8wa(#_h;9xV5mO(D_`>)yJ+#mm^snSEN6Ozflx+8)1W>`!0`UeS5qltg>F+YGEGd z)yJ?8H2k)-csuP8mBa61oX}35f^l;1@H-P{$v9gz{MN)-63)tob!|$~-jV1TkOszn zUH07r%aCpOX3ymA<(Q?8ecFB4)f!dgvp9d(z|UObceTEmz|UQ~C(d&LIl{HR`!d_X zfXZ^egw44e*~c~Bu*~ zgl6Gm0lsK|e{g}d5V?`Zq~+sgYgXrE9NEW5T$+DtoGNL6o&*BaR?wE`_QrgOa{M81Q{9kuy za0lf8N}hPfjsJc}*IDjvtZr$WXyuQMxV3ffOnhbK-KVbmdO*xzr;T6YbeJ3 zui@_a5JyOnkjfIyq@L<|Y&G_SlO=?Kq`mX{x|R`-d5eG7j(q~uz$NMD;3lILyK~fn zH7sL(R!0~}MzZQ`561Fd4}tj`+AzET5_sa@FHMzs`-Y@0TvcMFp5l?Dx{>Fy)8y+B z>16nGMLP5xy8i)iy77220rD0Hdf1Fw* z$wM5PDV}fmRP3zzMsxRhf%M?^@wQS^(_%b7B;6Xx>O3W`>PW!s9~|9RcK`m>p5@*D z;mPm*9%NZn;avx{2Q>#_x8JS73c#J;fVR~523_T>4H@12ZYTB_JMTw+RVCSy|TNv8?(m6#t^>UV+Fn<5lm+D)0z6VGepp4WJO zA8Kz%dFCpg_6&UdMvo8*X?;F9+h)7VhZP4lH9w+)V0%jN-pg#8?&Zzh+$>_3H@ff0 zY8B$#tBgii+_;;}9ctfMcpq8MTS2a%MKpJ7EEUM6s&CVRW3lSy7Ey~Fy9#7jg+-%p z#Q?(!GrdzMD6-ewuX~2FuckGY3aT0X_ZM|%czU<)6?~fB~T6xa9Mc4L5JrFE=F#UakJzWZ0lnTNAx;Jn}5`6?JA>-4%)6w^QO! z`&Gv2ouz_Nn|6+e9XTEOUb!U)9SJ?0xu`1>xt@vTdX=8Duj2n~nBH|zz*+_Gxe-#z z6iClp@gYZiPf>R!Rt?fk6PCrpW_HLhz59|d)JXmGgFt(u8h@(;l{PDMa&z&$j(*%dw8% zH)^)#cIM;gd!y5j+`YdY{E zq)fE`DTDAMG`wUD(~JMz1(NEyScuo{wtuxwZ_`(vwb_KB`5 zSig=bArTHq508;|^JEEOu&*6kShfQaMiL~jb^a$^r?FEq?2?MkctIim#R!)FHV7KX zuBum03yZO8d}lNl?~>>L7_D4{hWZn{btGZ-jfSNoBk`7xrQd*~l8H;*9I`TyEw;_A z=tjPBG0c}670BJF>MnN|WG;ff4KyOWy9%7Qh$yd70bX{eAh?(E9~cxJPY7>gk6y*M zi0=r`H+DL7fdSWMwsFl)welQzql$@5N6|^E*@I#7o5Q{mWsETA*MK$HdlWG~oh0?p z9ScU0j{tucjjk_^n^=E83s-$B6BF-iCF-U{t%jt&aK(faJp>u*zKOfYbL*G=2b56= ze57I?`$NiRe$ujZ%%imi()`nx>FtzDP5_o8FEeQl>r1kkfUZzxCP5>iV@O4rN%LaI zYENNi(%jfF!)Q`?O*?^U!F?>-ggk<_#%{-*7usE)F)#XObwy$aAWb>V_b(GvIS23m zVTt14qMgr*^@1j+<$mtazLNN^H1{FL(q63M?$~?J8pGfiVu#|p-D0^r@zqAh!d_ye zk$<(^Yg~r$1+JY|^`W?(J4}j0ilvDiZ#r^&)rVRPJNYMssuE3Wvl!>q8x=)~UE7zN zdm%gUAMglLv1;2AF(%a*lSV(4lm*hh3!W_Wgvxi;80EFXJ0WG;y+%7A48rElAwbVXE`_zS7rgPjjlWb+5*;|<$7?6nyV_%P?-31ng)+3VR6CDH9fBp8u0mAaMuxk61RXd#=QtWlGu9) zeZI@VUr@3|(0F^nH!onXr}Fkk2VD=#Z=cU*;r&#K-m&Xn_#4XezkeYhe?e#@OnnC8 zFNn2+xWSVBg^e5{_~OsPUdK*A$HC5F?uN$quBp8d9;4*F~Lf$3RHBI zJStQJVDjdw`~sL|=ArFDAvyqJ`kEI~Wkh1yRJ@9;^ z8@8Sw#yL4N=Xfu0Z)&eT!Krkd45(YwkTcDAXY$yu zLW(&~xeT+>PJPHTpuzu&Xe_5O%kA{5I;q9hPkenLN~&g0IG*vB-S!LgFn#lQ_@#O( z;c{?#vp`dbn=$12A@h~5!57n=g#WHb-buRi{O>@^2=EDRZ|V|9x_=G+M~s1WQT|lTf^+J+Nsjq}tp$h!5tMTF z)Y#1Wd*u1XLChZCntPz?Do}F;kejh`C^7%k&DU$*ETajQgksOF3HM1)M*6_PK5paf zkzzs(%nr5J&k70Fbmxa5&73rpD;ect0dweW*BZ8JO={{Lsho2$YBD911|)YzNbOk_ zQX&)a6Y?z24@;2SuIrgJwv*wp9K1rU`6%!TebVg_;N)S6%V(p~?c;rj!-}CA!Z`lT z_zR5(&%<#b{m!UFr7pz`bnQnm_1Qrp|PxI$i=+6bwg& zbnUyTf70LNoaB%K^Bw>2w}Kf&$Uz(@-t$E;R_lJ)t^1_>u(B>aZ#r~_EvO%GfwuN~ zYh!yO^u4om%vo4=(DicT!_2hie)MRuGr^&mSjpZTZM(u1UIAwGHL<$rOUrTR}p z8F`t37aD6&dhl!F4egj+EMRNII4u6eMdxV0@_>F-YP?h7xIkQ@$oJ4*|7FP5I2uaJ zy8~YFs8m0yXlif#50oh#9%|0~iR<}^C;ub$jJ^O*{sy&0UQzkWe?R|x{THFpZzG;57BHaHS{RXA=2yI#n3FZ-bUPw4%{&L5O42C{}L)_o@^ z`^G=~gd!47jQ{Qv+B<$VwyyDigR^ho%+Uv6>)>{R9m(4^h<#EGadeBzz_<^bzmPcH19L$Co`N&T2eOR3Pq%V-Qj{b&VQ=L7xLcSIn=`2;r za@e309@l|EP|IGDH5RpJQ2G)~`%3Wz`CNnZ&&HoC%{>ARM6coiYf*w(Z=EX_sIKoL z=aLWBl|kvkIQEIAHe^tvvoko;HXWEaJ56V7-^AIwbSG<`I6DD5iq`9EIAfUSUc|q} zYrKaHZ}BQ`zhR2tau)&_xJYb-?vtLW@~#$&v8Ja3drh^e2Lgcbh1BxD9Lf6^4D2l7 zGg#aIBHy){eB!wKMkMG2BLeo9+aT$&io4zL>FUPTl z-7Oz49Zza9b$lYVhfQ5%E9ys_tFCQR$?lTp8jgs@U2}l@O>C{cd3y<0d_+9UUxoY% zJ5htSEw|$|pU~zL*WJu5Caq7`rfw18FHU)-fftc$Y@xuiTN>Mp4+`qG)BG7;)%K+j zl-fs3-LpNj%5sqn30N&p-hqV&XYKEkP7Is62qpcAB!qKi-MCMB4VX#tlMG6KMXpe- zI88pjGL}`E{0i5i*v}3sq3f)30kApH=gWW=z!{E8Yc^CS@^JWI4l^OT1aMi;1K+?&O^nRGxs;emb_S8B(tQJb}Gl!)eBiYq7 z_a>yZ>Eug6ZfWr4oN7odwE(F-D6Jf$Ic8zW$mzo2d>L{Kl4Yq}-w&*E)X4dkiagJW zMeLmPi|}^wXd{^D&T~cEp=C!Pzg};LYw!^rJW7aS>u$u(w0IFWW!tW@4Q2+mk}X`Y z*h)GqC5qWqhZBD}IZAODyMAU19!v z@ItpYDBIEn+b&IqM;Ik9bZ&wleQ<5XD6=ZDHn5fqxU)2!mnAJSE5g#d^PhD{mFqxq z1&u+H+KJ6pla=KUN-xVROHg`qWV>T>UjkN#e6;i3;rLP=vD3So6UXh;c9H7La2nnQa^PsZ_x}kd8j`sR| zmwp@GP(^#+ z$&w$V-RkgfAO4+c)F0c0+_&2rchNj5ZWG_G=XL}o-6*t9XjjrPEwa!SLC2Yl7Wvx< zvtWmA;-FIl{46(F81 zn~*h3B0wZ*aj3`wV|Fr;okC5Ir;J%7s zidpQJzArz!c6fcM5_@{3YfwrZt&(>%I!+j^luRPOyP10uCgz z12+D=%&B6fYbHvx5IsfFw7R*~kWZ7W7KRb#fqx}J_4|D!1@WKcC+3Q|JmYz)|DUjC z(%-+pN;-o3Mi7H=)RB0x+Qr=jloKLhN2Jk6rzwt)6BVufc!zZpp>+nO*N}ULgSSSJ z>+ma~RdBf4FV)I%A0yzKpl7RhQM^18yO0&(NFY|9a#P2-5lO`Fe~kRIPP(2E?877A zO0M3e%QuvHfSV!zr{nBeD9%E0 z{zz@iWL^#IS!AonTn8c%*7GRou+=+|OU!Z!(Y)Z2mB+;hjQo6&P7Td}FB5RYLkJ z^IVjUjH!b&nSI4Yu(oo!$NbU>dgBXGCD6O)LbtfM*_kNYzNjke@BWM6Vc=jt+=wq+ zl)_k1izdEQJ65+NAMd_p_!4CLi_(*L{zBlhP#iKnPFRyflI;IR#m&+f82sL{IDi`*`@9h__#;Lx%Rwi0SB z+UbrXD*U1(MYwDg)@<@mbi(U-QR2{lk0O34DxDkWkXOzIPvlU2KWr6Ji0r<y*x;>Q7qx7z7w8ne>p~e?rMfNz(_YBq3)w_^eJOe(*R4{MR`5m}R#9b`! zeP~*L4Vf?|ZF`66e-Vn$dlTc#7~SspMc`M^zy3@9%1=;Bs_oChb)_0vqZyD|qK|%C zuHDg?JpZsPzw6+I-4-SJzE(bu!}*rz9KKuBcfmdz zR60Knn^+TvbvX+3k&Ue@y%CscGn-mBAgzg>6t#$h(D+jz6>>Lia;#l;6^IS8uixaq z3_Y7alF)>3ApcK-`mPN4C+^$|8Lauvm0WWg{G+U8z@_(&A%8ld1k^xU{;gtDNoxbF zxLqvoQGa`b4syItOc%J~Q@lq=@O{$oU!npl_LISQUvdZH-E2q1b2{(F3D(kqIV`K9@gAk%=mRUs2FkMI919Bjb*jv!5} zSOZ_(Nq)%n7Xg+9|IdQ$4T$LU^h?vn8Dy?^jD$H*d+mBXUoXyuocIb*2lxuI|Ef?T z;A7Bw^yK9$s@75XK7v=km5Q7~KO5%|AC(B(=w3^YK~kN8{?@vwYN{KJaA7 zvMUZ~i=Cp*$Su|bbFu?#Dak}6Gtqkbukt_Ho=GpDy7i3-Ch{zm>q%2eKEf^CB=j1n z1+EI0rCmT+FTs5~A-BFlx+7#?!i$#cj|*R=9D@9-mvz#JFd#h?DP~2&pi2XOfy>yz z%i$w0a1)=QZC4x+B!q&VC3FidGCIdj_at)yq{m)z#ITAVnQ_Zh{5il61SQ z`G3G&Lf$-*%J9zVMGN!ll9^53H?`+ixJIQF&`BP~S2CTmYbg?le3%1LY9!{vr1D(9 zrk%J(JYgi`)gJ}dQ}jxs>PU%`M)g3{*0?BbF8t*t$o{j8!zu|u;E{lHh{U}65@(Tjy;M#yCz4U?K;{om5ozd zaw9XKFBjdQ%uNXt*D2+CD6s#JN|#4Tw^~xCgdA90OVO}8c$hztzCWf0s&Gj_X)T_R z7h?B+IJyBywX&Nui}lc?)TtD{lY{?r-Goykk; z%5`1Nc&A;zq_(=AY`Oi=!)#b-5Di{9*ce4lUb43KOPSFA`jOl4II^4((;b(Wb^iOV zR~#lVsa!7wyTEdCnf{u8jLRRDd||9TvNvod@T>Z3C&n~Bc);c={A782bX1M-fu9F> zdCeJ+9OIKqwG(UAjpG>;UQ-R$qJ==VDLkoVaj!5SH(8Sg5kNDszKuyoM+)7#wsLh( ze0&+zSBH$)y^2*_Z!*=LYMw4U8lpKux-#i2a{R9{h&WUod;Vw&*2vEwS5C^+2a0eU z99FSebEX6cvsW~M*-Hv6b48`>s5Z#w{uT1WFR*jw4Rg6y{Iv4-OHCuAh-O(WKmS`< zMvY4T$PhA}E7Qz~mySwrMQn}a1*3IS6F?r_LQnWx=7cAiRshe7N z@~EVjAM%aQ8iDDA-1d0v0(+Cd$P>^xrOhIKXtnl&uroFh5 z!j_8j1Pz|>!eVm9_-kBS!e$9ChEnG|AeXgvSlL7){PBpUi6kWzO6o#MwOG-R>cDoT zqF?$Y*64c2?bw6n%I9y4);m@NG(Od#3S{_Rl-6$$Yz4?YS0X%r9GoI_J&wcsDK4P)mF^d0h$qK#$IU1!@N4n=OK3a zUVfv{36w{d@R{4kUq!wZW;GyEe?+=6ru6X-E|IPL*!>X|I2(Qo>PZe-g3`JeeW+%T zsL}3J*W^g9z!GZ&OQ?O1QW)Cf1TvbR!!8&?Em&=?+ItZPmmVrY{?L9%E%f)#kSEjT zZp1t3SXqa7KiHJHP~OA{G1?W_%N1anF0B3L%1_`~)nngQ<$V(<0d77Q-q(-AC&g&) z-yp+9rC*QdHJW&EOXOXV&wn$1RURirX#HO4=TQM!3bl+{GcEuwdvC`4BGhv3IA)Rm z{VN}aNU!{QMCvaRqkL>+C3{SDOGWvO7k(8~%Cy6J7gG=IuHRyEqh7& zP)6W!mTCdD-JQ{46E-!zA+`(MjYGhp8|!R8Jrf6Cvoo#B_K2n}-Ax&!R=c&3qnyam z6pvke8!|H~y}CA_Y1k=Y1S|%d_Dt^j3bKO%R_8kfFpTzmx~JT@T2Og4uxC<9&^}$O z-JkB^ipzn^P{MMzRGbWq+vJK$pa;MdsJ=uoEPsWc@6n?h0ZuEc&De}w{rj79Yyp(lrIJfAOt*V)cBU6G{kqiTp93fB3CgifmXL~kC(R! zFW_74!f`NNWh_v@@5*-!Nvp>BE?C7Nf1E%LH(+gCyo`Ar0%KD6GI)X82p2gd8OOf9 z9K)ggt2{<}F3mT}Dn|CQ6_8g{tXu={xNKn>k*-DT*1S5Bhv2t@-G-3eI?TzxL~U#Z z#+FH|_^8q~0$e!B1K_lS{Guzou%lm^H9~gWZByxZI*#f6T5IeJGm9yNN;ka>D()!o|!Wo9adlBc;GKy2z`rhZ4iWy8lN&R_-|i3`t8@K{r)&%-=XnBwm#3%n8h^N z{Yb3;hZh+O;jMW{miRWi5gUp87kQ%o2>D3jfT8?lq}nyht@d=g;c1Zjgm^dl5l>IM zcOa4=|2-8^`80BmXb~$wJ<_8&lcH$xX%y%aqf>!(fv`09qF1y5+ti+|DntbU^Wml6 zs$8((U^H4IY`T`^FtyJI+a6&oxWGbY3@YH0VUR`Q!7mer?yL31d58Fgz|b$gSW=d< z-&B**sRmC|JWyb2U-?>!AB5F#-h4tw;mJ)0GUC#g;O1tRgAZLqzrQ9)}DXU=_8b9VPbaM-l zZQKaF$T%U|VXhh1$bT=4$9i&(*sswxMJMLhG+76Gd;AS~eqHZL7MSML_;jyu`(ttb zmm1w6vUxg4f&+-x8kQbGp7yh_1MLtK z5tT3u{g7;KiTk>D%mtH4d?)WQ0#o;8#V&Uoda)cMeE&)>;w~Q#GPBS4mvy;SX11v+ zsTpzA5#;Yhgwl89Se}z9T`tJOeOIe0Y+TM~8#lUumqTA0>%gs8ODtY~QDIf!xVq%i zb(^XtdDG!98irqIGPvp!JBB4aEMB_q_)d!9IPG3J@%2aLuYVW>N2vdUpwFoG>JaAu z1hR3GCw+g$ek#e*NFMqzRu*;L5$)$Glf7#Alv4Yqc&Ie7a-_G3&Phl@&VcYZhq3^X zRh!;4srh+r+g2JIhF5SV zJ1c!We!Xq0!F3ql6>Htt`s6b*WO9b@)3K({Y*n|W;@uVSIXuY(BenXc>z*{uta4Qq zeHR{y{fO-!pUEa;tPD$k7*}R7wDx4L1~t?6RaiO86pyO=3?D<%Q49VEc0sfs-t*7) z%el?#nBB+b%mRDaDu)h|L=ih0a~$Q1b-K3V2|&o$YH)d+oF7oxAk zzA z-gR!i+V__DT~iSs_lgd&0!OeH^JReAcn{;^&6VMk>=ILR7k8e1nVj zwUld$@kM2tCR2?XcAVB*5}OhaRl2^))FLkT%S?}>64J$er75A8j~w@BP+ zv?h_yFc~BGz}N;Co67=o*)c~7bgz_aKZCt8CR?R{v@Daf$$P_<$vk~A_O*Y1D>uCq|7s7$o3Z5bavk^K5&$F#oK zS{MoCpcJdeDqSlU(F&lmEv&=(6c_=g`-UoAr?!=A4oe>m>#UVkg|K<FsoIr{j+y zcY+eR6NZ6$)Y(=nS_sK8g@GkHV2A9e@Q+Am@I0HR!W#?f$k+G-tV-a}#`j}f|C3e@ z15=+NkJMj=v*B(0byoHI6${OUidmD-$MQUDbMop6AuXx{LoTi`hOX-womqE-{TI%~ z&Y5zJ((uMvbzbKzutc6LxjtqoA6X*%E|9G7HJ}AnI$oZt%TKQxsQSl__jXvS<5#{^ zJy2~~|C}YkzM=Xhlr6pX(BeL6(W1uy>^Ngd!Ss1aU|#+GDB0VU)(cZo?H}+v^>qJt zhRN$bbKVvI?0F@)=a-|go#(mH*v|7ZED$sfv`xmiN%ojrHx>KNCG3gx_9sUVVfRr& zj_BQ5uC<+`Uy2|VfD6Er{HkLAIv4mFz2sZoIGm3%zZ)%fb3ooCLf4~c(fCY-u*JRX zzg=+%uZJ2|TntT`cNBH&f%l8-^*z$d(HTtB6yJ#ve#0ec{%CRCe=igIb#%+W?S)gF z#LY1XhN1SUy?YDTS5MlQuCRA6!#pY6_Q+#>Qgx(oD@iw8Vc}x~o2(B!Q1)P@SlNb% zA}>&if@PzOB?wASgaymBC(Kqt83d)r!}(8YWy_ud{>Z843%Al=!}$zYy30!y`^ifF zP(|XatYw`m8TB8PK8?mt$ey&eKQ6EB9Jq!GADcls$qmJI@vo%YnN{7Q%!~Jb<$g$B z6U$0X$iS=Uv$6a_nj28 zwXC>dNnN!oUbe$jo>zMlJ6TI|7qv)d#KyGdrFFVOtsU#zLFGK=AHI_O3e{lNw>5}E z4T@N@H~z>vSX_6&Z#rDj?Vcr<%_O!ureJq!pW44S6`X^~t&)@&(O~U$I){0!@7j~p z;)UCQN$O;tYWU{{!I2-=9p6Da_bK#xOl}~l;rJEmpTy3uo=o^K%H6G8+GJP5-Lb&{OJ>)$&+_UbA3uLa$-d zXRt}|uc*E3fC@XvDD1Yy&>WzPpvF2MNsI}7I>@ZbXJaz!b>_#*0p-CsXe_W=Lr%T` zjYSPc$5G@Y`2UcTvq?^#S_^6QVDkQy{oRg5fvGGer%H&mRr}rn=Mz`J;JbzO#(WhP zQC05|{&y)?r|bb2F$ZKV$OVvspK6<=Nn} zPI^`)_R4$x$xT49BQl)$Oo5h{5hcoreaQCFCCM@J0~eyFugx3bauy9=6n?X6iHr7X+MN#9{RS9B|HT@rDfK{4z-fM zD0RvCF0LKBcf}rHBYUK`WxV=i>~%e0BrD5Ujw4w4Ed;EdJ=ji;mj+dEJx84*D)yF8;$Ft)&WLx?1-p5 zXoI!tkmK2&D%Wf5&-`LHYgH94<5h?ngA|D~O(&v11RI-$nW1dm>Q=(Ot?J%t=!d=R zDj)Z18F)3oKh&wlyKji9tXm%E7I~ao9(qFzgrEm@khiVh^uDml?K9GTc@1-UrH*VL zablnJ4N$IhtSANY30966CM;$<2?Bc(v&X6LxDYXTbHR%&tdn^5E_>hmcq&&@mv z*n5G9r2nxKQw+yoN`|3YKbE5OQj3~Qzu~{!ZMf|&gd8h;)4^;JyE`o~A0?2alqlJ# z`=A3*7C|c8tckK2BNpRpAytQj95J~}wO@SzXk*xCpLJ`>5}L3dl_fT*I+FG!AB;x? z_mt?R(A0AZ{pxp_{?7kUz(=?PHZQO>NV9?2f6kGKeL5Gt9|bpqU`diOjAR@Cc~mVD z-g;9cu1x(3#}xbEA={USECA$VGs9Z>H8jLnd?VTCXfGk(*Irq^dH^_qNx4Q@2B`u< zA|0p|l0&NSO=|rG5%?_7mQ+Jg_Hmnyt(dpS8!xDX^I86i9_b};-CgpNwQc5Xbs#7i zfzUuaN%S9~NwdF_-?k8M4#M|>Jqxqt@Tg{DCQd;dKo9DtWr|mjO&hK6j&wJu4wKiy zifrq7yB4!{c-&!G6(ngtFc5@NjKFqq9i?btny!reLFx6;ZaiT_4DDk1IWwNyw2Pj4 z98VpUpX&Mcsf>J0mjyd@+h}{}9>fWgt!f9>z*t^|NN60KZOk@{DVl(5eX4zTY7A#M zGd5P_LrgG)a^1_uiz4{GIRn`aJ2q=iGD8Irl8@ zdG}XZZ%;x0K2cf|*TA-sW`7*)+r}3}NqO+QCc%(ZkkU~EzPy42_Yiy@NLEm=vFZV> zL=gNt_-`Uu(?4|HlUv}0HB*dR292uW(``uHHuy}12;Yjmurf+<$Gy=b{wF{YpO*~D zpy|Q#|KlRKv=TM|C&cu?BaL~*q(Mi!H`i}$NH5E>{~b0#%(cC52tE`P8E?CK#C{r;)=-vZsRiEdgmDGlIE zmddwH!E@?6@CE5x6+@#TA5DS3rfWAiQ?89bYKJ5(j)l(N*Bg7qvmv=NM|&-NCTT&> z9})A14wm(f(U!JuUIV;xZib>gr;l2z4e;JjG;&iBNC(@js`3w*V4 zMI&qzQdT(jY%FTb!CjFfDCS9LeNe0n5NL>7+c^XE))zbq5A|`N z#3P(fcu093c75FBg7!EkH$~ob))NoO>v6H$kFUml?}5j;9>_!bH_H)Gk`*Z3hCcuc zc8~C!S#r(o8)3j-qojmaX$GjMt{VZ;3>!CiL&@_0E`&QsnK;`@W$1EUHc=frG&1{)}> zA;{?I`W5KNQ3YXm_mwwhcX;j12*d$KEd(VLw}GqgARWTav$^mc_0@1g5Wgq z7pTrXQl0-so%G&~(5H#pL-f;e$PrYa<6vtUP~rV3oCC$gQ*v(|ptU#ME8h|nxA;p9 z@Z}GQt8A}R%bPmAYjp>aqYICSO@2@`-A@gtaXf$)YnLHTlA6C08+9o8IjZ} zr1&jqkyIB_N|qc+x&3do8ym&sQ>h%RjxT9j8^<}GPnJ1faeM%uhE8~?;hoSfYt(A{ z9OPBHqH#m&CV03ZDdtFE+(w6%@NP$Yg!i5VxuOO?k}nS1dI%kdXLbPAc8lGRfzxj4 z79Rm_M%Vj8Dy+wwah@k)uTsu3;;&ezf?sJZ6vbZ!WEna4tK2f2<5O9#)q=dqft>p% zqc6nCe5>z9K#~Wph4qxL2vBmeof|LfDq)#L_x8!gpLZKx?-5hM*Xa>A_{c7E#~|B6 zSLfiKN^nag4dmbWnUgfi@9aI$&Wslplwh`}xt0`>kF!=&S8oZkMDC{@m+rIfzNds) zi?G{Jb|JJ2s}@XSRjJ(xhv3nqA~`BG>}j}!p$?RdYA;ARpHP)trAgJMrgn`<)s~ea zo@;yNqz4Ljm`0wMwpeE1A!+69O&-)LwfY=dLe0|shdm|WLzFCD>j__FMj6(x2hn}M zMEkZ#KUSI6_TDSCSHgCi29DQAZ-1TgRl=O)IT~19q)?>V`K2XnnN(`T6}_rT=^j(1 zHJ1|STX}*;uVisiLn}CUm60}!ptn|RFT>fzTs^`0L1U6W&M?Knf3tJq_Z zd`tI0dvOkSC24oR;FC+^eZnh~uBW`SB;9v<*5or+vdA3#!B=s4KGyqYR4O9*t9(J* zyEgb^YykvGZ8BZg%UX883g=Kt47_cS1`_Cn$GQA0x7Ij>dpYLfe2O!rx_oZg5wUM@ z8Y{W4aFPx&Me^Lgw;>XJuN)S`>_jn3vAzfx-!qVAq4nSz4Ess$7Ndi%fss;OG_U8i zM^m~m(qAn|$$IRbxOVt?N`V%Yb6$!9eTZuR#B+W9(TE@A68H6tGqCIjijDB4+*D?? z-?$jI%7di)^DLlokN8_J+k(;Y_K2T*6a?)5^7Gj&TDRx;|ZA9w&9t|sW| z-8+yAO=0TE>Y!yH3A6Zk-vRwU00n3!4i5rCv>%jGJhW^6A*ByUX&KUgm(rb5nnU_6 zDg8Go&5+(FrQep)q8uxd8oglmQOX@UleL7k9?PszV0Jg+!6M7;aaeIpBd`on!{qpaxeWN7a-)|RD> zC`itSMPflaBB{Y5k#~5`QX4OXex1BjGahpmS1?I}HB*Q92AP54lqKela+k0NKv_?P zrMe2%Irn;}r*Q`2p{l&XfL~m6IbG^KH!z~4sjL@}nz{aZ_NVuFyjSU+o^i(G7iZx* zAX%Tbouw}cz|Nko!N7gk8w@HbOEf0I{BmJ>f@E!P`e$wAP(bD$@zV^93u8-yax))J%@_!9qL9Gjv z@K2+LztfvSI6Ihn59v%FhYttZQ%VUNcrT!YHyi7=;kRbvE%hF@1K#5!Z*`010p-3oOyi|5$#&6~ z6gjeh!Bf8phgldXYP3ww2Q5}?sCWFian$a;ptaQd&O7Lw{S>mjaP65*Sx;v_QwR@z z=>hOG!5`f3p}u^MzN~=nmRcLet#=`OEA8)v&!|1OITruISw_0J!{-_8N7|R15!Q;< zDpOevs2FgrG#%4%w^zCYTSb3Kti(N)ibd2VbBzwxT)pDdAb1hD24G)HR#Ux@WRicx zKh4|=daqlY;g@aUa_#_!sT;ASiRSGVPl6^+ns6Ipd9-0yorGWL1Nv8Sr^M!~rU%SoYI>7@ zOh|iA>F>%?+6tmmw(FlUJd^qKCGiuC-*M3!{Ls^ov3~lmWG6k2?1xw{xN`4EV>T1C zJN3TOUmH1TPJ-t)U-E4;6`Fo0#ovbJN_v7*FX=J}H_*w@cOtl>h6{Xrphz zOYMqnTI1k?6x_eFk=wqroO4FKw)3Xia^*Hfi_x(cF_dc@N<`6+H?3*kkg8~kYdf0K z?|8v+THHKDcsIe<i``eO6?Wbz*ix~ zRGFVP$5mT)e9RZ^UuZK&WVS=D14&77YG(TZ{a-e6&T-INB))FUYdS}cc9&ylqufcc zbQU=j&W23~Qu-Y91z!XSBTUCSpwtPZlq@xp`Y%#sldY|!Xa5Nr8#!qH86B;S&nMS5 zzT&t$wZCzZgK)kSK#p-k2lOexjtMU3ds8A`a^nyWt|DLRY@eI4Mv9)W2m59V_QlnD zW{U=7nmh2LeM5Y;xTci7N(8b;#3tx1rb@A!5}MMatEMSE9LuRGL%OP))@)X{%q!aj z%|>XQ>?AwnSa9~!H^e&0nxX)ng8sHS#_81VG|75%7;(JbvBC5Aj#f4g-p+Kcl6scC z6Fgo>Yo}GQ)CGx{xoyeO+oGEjTeg@+_sVq94YJbhiICw0O>CEsoD~e+Sy4t?YrMOE8tTr0z`)ZOL&^F%u!scDJd1V`rp9#L)t{UC~ zh{ZU}Qykl+-@5;hOwPWCUFR-++?GSw`J{chOCK-Ye=qJse!`XslC18exOZq5AkTOy z6^nh=Dy4I!bPUo?DV;5)qmgbxI%-SU4*Dea3%wn-A*Nlrc4!&w+50!|HOXO>bX+VA zkd<%0ZFjpfS=|&14JbMEPDz^`V~gl>TvN1@HN_y()~ASkp>_1zT9OkRW74A9|BBPI zBu&+v+`dZk-sao{`<%(LYh75ciQ1p^@JSC)p$W%k7dx6}62;L?8JS{QEnPnB11f~bDr#a_+zQ! zCej-D%Hy%!!Y(1@Oipe8(o>&7_6v);y2XS3Zs@9z_Z2SZu$$Z0E&k0v5k1HW=-A}O z6XMLk(#irY!OfH4I~{0;*RPyX^hd|WZ5kA#eZNZiU25y*0tr7(VSj9Y_t&a!ef?Zk zI-e_AtsT+6$MnMq#Ck+cQv+u=GW~<81zH{ZPW)%6fAi~+w+d1U+IO^X#+!Y%1?*b9 z*^W1#HvP~8Pc@M9^uu14xmS8#ed6>JG&_ZXM_^;a^d#f>4jj(cL0!BHyf_p57ek;M zdJNs-1^)|A{>m(ahrU>Mw>TR)w@1E`x#oLF`=qw^PS5ElcbL9)v7E2nY51aU_!uDC zqS8a$oI|d-f?K88sPew@_cR{NesLfBWwS>qwbx0iOE<1#{E$1b? zPXHgrhgdQffX9>XN67{%1e=~2|AN)A9hsWb$ zf?ot)^9RU<5icmT3Ro}kvrdZ7`c+#jw(KQC;(XuZ=7|h3Cbu-tSPTDc@IG~uqNxE9 z9Ku{ZHFzHU7G+ahj-u-UGiNwhs?#HmG2+Saz~g=tw*;f!;2{Z`25F-Vae#___e!2F zCiqBJQwR+E5%OHWsm7*kV(=J*=IH%l&m#2 z^pT}7^{*7s3}sDy;G&mT_Aey(c~aE+`!Eh=5tx~X6xlsK(Ow$KQ6q=!9&eD+JRo7n zM>*@;uZxrreNoU*FVJ!~oJzeLyc$H|(sEn(w$Evl!6V%>sdF=w&Jo%cc=sfFK@I-? zjgSBvF?))p8^N!`ND58_50yaxRzIhWaBH}@@O zal8+j?TxMJJ?m|lp|{#kt{<^M0UvslRywzB=vfcT@0R9`V-OMe8mt11mWOYOHpfxG zlx2?ds3FEj5?N+=5b&1dholchyh<*UG17}7e%mn5Xc%`O4u2Qy(n-$KB`$y`u2b-N zn0x&f?cffLkLn_hHr5Yp)d=3x|9d6AK97@&JezNTq^e3aA9xyMGjK9ZE4nqJdL28CR}3PUsv|F-sW-F4LRvwWwtL7QR{5bP(FOGUrY} zihgjp(@L4~@v@>jCNe8(*A5k8Pu3x#ILV5l@TJojx8sty89LsurNB4u!Z#XpjC~0h za27wJ8eq>Gk#+M+)=7R#H<^~YrkYD_8Hh`N*t>rQG%9-vv`W?no<)(FV!%&e*$WBQ zhJXQshYLw2|9V)?J|w>F1(y~UA!=g?a>eSwCrpYS;tvt8`~+xEdhZ4=2da}woe*b3 zhJPvf+LY&^t60~_84e{AH-pL!pe&Qh{86ffB5;Lkd0MJPF4Yn)@#Gb?z4kl?#THvJB+d)uL)$I}o*BBtI$+#HQT2$o zL}ISZh9o{D&I6D2I0Tm%JoW{~|4-k^K)cBdvkPI<(@+KKKe>!U{9dx$Rkcie!;_Q!ye5zO6j@6XHk^$LHi1vWJ6EM>r zg_8CldF-c>zlAJIfwIt^8lv9jvU8H&1@%Xcwa)_vr8a0fs#N@E@Xikp3y{9UOF!vk zkSBhoIsi}nG-h%pt>+Nrs;n7aGgRnF0QzbQ>ADY+G7DB@a;VMpo!jdn-8GUUZjI=? zE7@I$@>PXcsEC&rG}e=RxfcINLN@|F{+!|H&V*$Zo9oKM@p30cARM|XZ1P@^tlF5c z5NGmN;67Nuc~H3m;zO`PquOYd<$Lp(ehKyCb7`Hv6rwg$j(Kd*nHA!^MA60xQQnD? z2FWGyTyWSwDZS@~ow@NTmY;~aLZUX9WQJv{HG4_(j8(~$vl!zaK5efJ?Dkm8e-s^| z7_+sUYrXvs?3P#iI~Yh!tX?{hv3ai_|abc!#CkG@DJb1;J<}s#oruF z`iuH3ixRLVI*@7QjITix&Crm~_Q1O!`FuJG{EjoWLE~JHb0s9+7RqN@=Iv}dgNH_< zYPhYkt+L$|jW#5H2Hy&|yR+C`u&POg$4L&6iEl<^*-Dq`7N#$^j!-VfnIKfLG|tJ;)G>gIGZql&VDK+9YU`U#9~~vCi5cZhx_Y_u zAZ#rzxe#x7H|#{nTeBT#yn(PqGR(AzxR2_u){O5)ZYW$f*-}V zgE3}#n*uW;-yV+{iD`<(jKo2^AR0dvX5_0N!9|*rtLKAXLLM4eewk~fk=q^P2!W3T ziF8hho4(%!-w4Jfli0ir#1n%yH?6X{J{qO_gFlVZHCK$%7ePAVQ!z4{W5y+%VO~a` z%?sYZS?I;Z3jYX_mhC0+6-dEiTzxgtH)TLK?eaJA{uP};P-1eXSW<_t9f$8GYZq#B zH})Gn*%H}b*~lxvzPjt$;hlAzs|Y)DNL2bJVgH9j_0XgSW}Jf^c*d4wAKr8D6?A!q z-QY-ucTz7rFw)M+Jw`pfA3g1}UBZb)yJa+HaqQ(intpkYhQz-HKf@lSHa{60CAE1t z@E_#F3NwQ=dtu)VO9I1l*5nIgkUt`RW$Z8RBQ^GsTG~em!F~_HPlDgW`{~NP1YMye zv?87kfQDRxQ!W?246j2RK%}Ku+50%mT`A_#GL#5xkRaw(NgpR9zU_Okk>BujGGfzf zTc0X`cbW$sMUGy?nOp}C?{vxq;Pdr*sRodLHAJP~DS; z;v;p}0&AeM8+`SRYy))NQ?)5pN9$8GKKYIS_-;SdSAzOhMCv179e;!!c9*ycG#>|f z`c&NOd}Mvw1<%FMl7mMX%(ZVU_D$S`GU@pUA7@R<<)z*6Xy`l7$jkTVJ&BR~J)yIn z5s~|cLZ>|H$o<-2w`XPK{t)EaGDMoE@qzDL|0f>LBL(1}H-D=p9zTMX)J|9qIyyl`_zYo0vy8d;LXR}d*oHTv?rk>BIzcrB#2evNZw=;_ zaPoLiWXJkv0l~npFy|L%}t0wbRe0tg4HgX3s}{tp=h|a?Sa?6_jj_ZwPA3OuW8q3+b=u;0bMFl#9K9F7t^g;XwJ+SFGvQesclc~$~ zRc-#lBc6%ybSrb`EoniN&GU#}H)=w)v=UU{5YSjh4az|01Vj(~tB|C?GeG;CGy+m7 z?LIX?vHAMMrC#!*7RBq(*5|OU49_qRyRqdflgd^+9QHA$<*K4TVH&yuZ;2-|5vi*&JUw5Z?@a+Uw{OM}qbV z^M_7|YXg1YScbVnC&b?&^;SFi%noyi_@)!^{}0?uf2~%9bFS6fzvL}gDkqyESp}_j z9g{H?ILe0xF$RsJz%k8nSR1Ld#kS0GLcAjowQoJNYaqJ{^u6P6{pLxd@gB`p+X@W#;hTKI6ha znC={YU*Pu{eqHz-$FC2+7+`}5;JL>a$*z;JX{E>7$1@gHSR4ia{Ho$K`vSYHWCt)u zp)*4VY7;w&1i0ZBNPR?Z&g9aPEmqRm;;mIu33`XhD9oJYpv7cC z3|51>Fh=MA7Ek)97qDJQ2a&Xt*|xE$YcJ}Wc7))7I~0P&!dlbhBUxqxcXYv29oM81 z-VAX&;D=jyX^=t7JI_6hKOd>%iNWJ|BG31@dHq=recMhW zMK3>imxAHYf?r_X+FRE=L(s>Xqc}ZmL(CaFrVB=6X<-T3ZzdR26GxT;Z<+>;2AAym z8dJ^mwmN1-ufg?YL!r=4NS3HR!j}~8);cYo{Tnt4gDy>HxUG-qS;0v6nmU#r>(XMh zqcGaN812?Nxjx;pt4<}%3B6p+jDh0*8nDo6?RZnXTx*`&krf)Zl!fcwjJowMm9W&; zTE`i**81|3>AZC!tHM_pS)gcs{T}!~r~ff71M9XGHsnm2eS43Mn>4Mor)GXVH)(#Y zN?7Ro+#`0b?AU1x_dO21pW=R^4qnUMa-B-(3GS*^TBt>qGv2+VP$jr=jvJtnrbArI ze9YQ&!PdGAOD1w|OH;ab)n!9djahlUTzDQ&=)DARh@ycX@rVEl{#TQ1n_QR$j}O4C zTu!UCym`jT&RoH=n$bT~(;e?$kr#fk{`tt@T8%`(4``bP0pflCQVz9yr?;ACHFKeo<+hy0_^-Q`YvVjY>v?KLpk zm2KHf@P`;YRLk~eraZ*blEZJD*Pg-~&zcflt3aEbvOWuY;rZ6ZckR(Wd&hh$BGI(Z zxAfrJW8o&A^-$zPng=G_3kzKMy9qTJovdGb0`~7rsP*UIOVn@jmwFyK-%w{l$L8qhJ4yjE72C ze7Rq-t`zj^rMptF&yTdH)MCF+qy4_b`(>n;)JF&QlAO%}<`N?ug0&+v;H%IN^azqC zbf;sQdD<*r_PYHnQ(eTG@+~^!TWpDCpXJ(__0_LcU#Jd=Cqg?7oNf+lyZv)9*GGC2 zpNm<(Yi8+;*R18nu^lT-RNlHae`c;F{LUL|zlApP`*<%I@4bfi;(Xke6y4`y6g;b^ z;i~ZQTT*f5d^%&sEViS*y1qQuvZHZ{C3kJ|hJBX0wL3PPTbn#{_u6nDoLAK4fn5yM z)jy~+CPvDykip7Ts>_|X&YUpzxM^(-&e z9WC`U9yKsSY8_bugUdj%Yrrp;3#Fi_U$TDV(K8Wi`pS1z(tGgh2IzwC2jqLn%CR5e zK|>)-@rJ+C3!ZU28^hF>%fb%5j?QK(O=UT~LU_{a#Wz#k0(?yqHlYxnfR`&~=y4b~ zaJye_Jkz)#J7z^{w0T8>`P*?HuaX-dV)2f|8$&l9w%>Ap-13dfVToVN-B=JkBKlwV z|9g4D{ZHOMYkAD-5#Y7P2%lj85pHmxoRcy5m{YP?`ucH&c=lv)Zz{ZUbmuoLwj1q` zK^9;1l(GZuVPC$n=8xvG0+lNtexy=i*9_dq{kqie-C0WW*R1w7rTMfL{v|`TcOTGN z?yw|>zgvc5h7=d<9WO}b%1}7`Q4lD|C6y-!d+tS=Zxn2-z)m~{%J)q%MTl)GM(@f{7)^vZ7Pd0#0WS0 zMwq`r)SfZmA(0%X5Tk#vVRb{QEU7H2gljqsAFxga$7R~6iCjyJQ0(KJZ&|<4p7l({ zD!y>L!kjtc!tFGIQL<2o=4l%GQi31R`D78H7PN!##K$;TDCRM!KVk;&@ySRx$@0+U z^&Af!k2P}<%f!8EHue3?T{9nvzW>Z!BeZ93kFly*6-L;&L95lR;&htMB-R3`?RW36 zoRiki_810x2_JD1no0=R^T5SSy!~rCpsc< zP28;fhW9R3Jr#R%uPX5~_?r^$@v@v)*8+oD;?Zn_^gty%>{V7OkyZhZrjz!78~!Uk zW4h@^#tMNyDpZ7{gvjTYwdy{?Oep0-%6U0;2&vvkN-k^$=LNkHOp)tyT*L6B%+^q( zZLrS>6jJn84p0Vj4LEUgJmJ_1=G?D(&1^`(*b=1v0e-y#MNXSSPZ6Y;Zo(r~rsUEU zX^>bq?R`wvl>ZptRR5T~X+5MAFZWeHbX$e8t$K|{U;S{*b*CTB)XzwdG7LVPHLm6X zWt(E!f#eq-;HSy#%C>)|^STPN_hF;sy^>H#t9_MG{f6&h`M4_B%B(KwzrW_eTS^QM zz4)-QO+9IZ*0?;ct*R-?-7B^Jhn3?L`lz;l zKAhOb*$Z^a-KE-0{lN0p6$1~nKG^>tXP+SDsqEM2O0{+6N_+exBifYqiP65e9Pe)Fny`-=d^>Fqwy|OJzYc0Pin?0t61VP#6Nah@g6=1ZiuQVv(4G^)*9#6EJ zrTZj%sUdl9ie1lQCdCM^dI1Np4-}ao(*R3k`0=H0Jj<@t(%y* z=(a^k_M{cv#j__RJ#hP?rbXCQy2Y%n-C*T|6VQDoAJNBO7_l?F!T42k|3X0t; z8Wc@jeu4X9gDyYYJ!OOH8Y8%G2}SU6Rx}Or9==)L6fL|FQalHKtZN#R@8FxGg-=8J z$NL_Ol0|7Pk9!_x@+j@D$Jw(?8Ku=(jlY{wU-LUUF)udg!T;g1uN+?_>4e=GBN%0sF59;bJ%C8|`f7Ph_pM%z#EbQ#A$rJ3fR<>MGn^UUo zKsk-iZ2bNgO+@3yve)mIy$(6T5O};pFFeK@OAQP*g>pdyc;*&YAb-`+=--Ss>mMsM zd~1P^!Kb0SzFm$IA;@gqVhu{zhZ4-y|L6I)((^fZZW%JLz$BC~j<6|&s6kHGRjjkq zxJ^a>UWn&4r}2}4wl2FLG7PrH5^Ej>E);K}bw3I#j`l$!uJo;OgM>#vhp{Lg(qqog z1J9u~LHojvZ=zUQRYOMBP?Qc&G$we`UkjNT=xb2+shAnS)X-!*%}o}*pXTTB$vK#z z1=uYYuwUiE8Sj4h-Fne5s$$g4Il!`Vd|4Q2nlGwjFhF(KLKCDq0!7_4zctL@LM`)a zK)*|M9Kh)ycfV?oSIi-cIM8bJE$;%)p?O(=-+j{D&^aR?V%WzaaTlb9;T;6qsDQkH ztiC9JJ8&xUx-lBxMm&=X0lBfr{uNd_)3tzCWozK_;@s!4B9$%!;(Y1ylih{((ZyWf zBzr=!N_V}*+qt_jv6Q(Iv1Ul;i8JhNWV)o%{(JW}Zqp`}w%$9*e!;_|)-OG@*EjA5 zXC`1R=Y?3n0iwh0g{&!RyIfd~a}9i&fD#%WDWJo7(4yAzkob?G=>3{bf-^VcNAnQR zo|N|F`T*C)3+Eu=ig^a!dd=MK*ry*ajC&p0UfU8!W_;pfULqMk*wZ2@vi~d#lv8Za+_}uz|~l zMh;0Q202DO3ZqV*4K$It zj?i zCSwFS?6Mmn={#fOnqIJRd$ICDobyH75$%gLhWbP+qNrQoZ3aFk^{l_9cw$roWLWMI zzzj(~OaAXC7aQ%zrIFnhVp*SiM(avVz@2ofz$s3i8pfo;dEx(w5&DhrE8>MZA<5QU z#dldZGED!6F*Bm|c!?iMdx_IE6f|Fibq%8hil$50(F=e3~DE zT6|OV-i*eWy>d3T5mt)ZRKnvv-U)kr_(|cOr9Ll2?YV`}WW`s=aq1!9O!jp6ncD__ z%mPb_IknOVC`Y4_T&croBv;;AIDetT5GtGlsybRY=MQt$7FeFQoV3t5^=nUBUWi;@ zj$C&~uCL=dF#D#Gf!Q4q3Hmv-PY@0C_*LUZ`d`qe0^PwfY4^9{OeGrRE?en%a5FPW z+sc76-Hx%bcRV5K7~Vg)(^y#PWM^j6x7|ND0TiL4X@Xg{9he8S8-Pm;QXkIFw26463gJG66SadhhC# zLZhE$E0`A0kGCkROAD34=g>sE9oPGY5G4^hE39b_C{wLoDcFL~Qk%0A%xZ(8DW2YG zlL2$A^b@yJDJ%?9y(e&v1z`(LUfO@eURj9oSOtFMhkAwPal%dTJAwUv^?aWg6NViP z&=VpUGo>T`X5#Ji2I6MLRpc?cA2o>my)C8^tU74jN8enBrhpB!Ug4`n7!wjZ4yHp_4mxqb($f)Hr6JmY?-ZW#PSBIZ1rsX0 z%=s&L6lOR#xZ<6ruif80lEb16OjwI2T5S+>#hc}o>Y^kIGu~#g&wxG{_Q(aaOT6ni za7s3jex-A9>Q0ji`~!VMn18?(vz&{Ntp+8YE=69!+8Z)jWzeOn0uD?VFk<&*$Z(E- z6XF?J=n_5iBXA;urUVt}j^f##B<-s5*U&EE8RV%XY-KHkO2JPNIyUXEFCPWIq@oD+ z^AD>TSHQZWv!Y(hWrxK#hyLB3#HJLfSZ{k&uBe87*$mp}D|31)8)QM!V#-wDE={vjV;}nu9Jx79 z;>|4I=VE>AJyGJJGyKuMV3|R2f{&zV3Q5+bV|x)Xg)9D|{d-SHXYU-Aqw&HvtSWGi zJCqfKYyI2HnzokUU{V)>qjAcA&n`Oq4o1!3a=46GG?i`^T~47Wreg3Qa(BMLK?o-jW}G| zBj@jtLqew%`l0U(yvni0&h7X*SuQ*iykOxbBq4@VluL#y^c4k-Po`J)k*w_tz+9Q2 z_D#gPmI(EX(n-o%E~a!aQJ`a^d?S4#Q>My0Sk{Dm#_jT0fagpP|rE?kT6<wMc@C4zT>ogjrv2q0F4zSZ*@xHU(hunpFAqS4wtblhB*%5MN3zd^>c(LUrv!i@{EA+)C4z zk-l&^kywrjlDSe76WoJx%mVGMBpoN5f=)p*VyY6Zz=VU)j}ttOj&Cn2))21r?L`f) zN|#c4`sN^A9i7~7*eO5izAl}|{)2?iwbrV@s3jm`gOMebjs*7lfi)p-R9BRq=_*Vz z!Rlq1I>7mZINyJ8Cz?~(mPs1O_!3=!IDUD?NZ{!g4Xt)&G}v1${T9S^GcU5tzxNA| zf_Xf0ct+9ayY6Gc+rD!ig`R5smG{4%mmthKok4w&18VRM7olM%*JIwZsKf;CQWHr< z)}T%J+Je-EWWEW|X@O@H;r+lawEv@<6Po=jtFB>r9Q@sgD63(OWnC7O>dVRS zy2(dm&0F@)E^7?&f5!8!9VQVngC9NNc<$O#!9%?7wHQa{_I4W6;SpD?^jhez_`JIr!fGQo2%-fai}nH!rlnz6y zn>`J5AjoKh>>9-Gxk^ zNwq&7T8L2%cG5ao{?-T9k!2s^%%v~wurk=!Q0%{RzOOxd!9j)`2xm{v$~sUq3qq=l z1eeT^58sEdibP!9dfQI;yyk=od?D!>af0Ay&mI4zwJ5DAPPj1yNz~=F_%zny{;Sq) z3M^25>Nkx^xYv5A*ZU*A{?HnGx!0U<-V2KntZzB{+VkMpNS$jjUo^+KjzXPEm%QO3 za>(}~bP7-}jm4!Pjr4wu^tZsHeQtiLSE>m*MX2W&_LTHiZ}8`PDw)US``Z<$ZfOZ(#AVdNx7rx`x6#jr?Y+ z|Em0GH#u9jmdZ3yIs*T&B}1EGCQ2a>*l;dYFi|5?nadGS%0q zi#C~}p?Ndc+E{k0H7ey+3mdO?-zD`j;j>tn;hqL-IZ!dPEW|pMesq=?pt)-DHaI;_Eg+Q)BsCWpy!@ zGVAneuB6PubgRKr0NkHJu)z-wG2U6nLpwa(#WD{!^fa`aG)GfdrDd~)DiiL8 zAB0K3!Z;y*a4OQhl3#?sT5Y!2!YCmlFlc-Ql2gC6-%dX6z(opW_N}w-MNcldsv6eh zU&Oh=glW(jp9VkA1d|DB{RQnRna$>~#!ie9{Qiq5&$-StqyTHkVZ_0REes(RrdQHa zCK)nW1rhxBh0jFy@R?W=pxH?2Bg{Z6wK&Sn1X&2WEnpvV(9@vy9Y{}P4r`4qO8C&v zbmy&WOo;Ac4|Y;J-v$*}rxRI?^i6MqmK-#K4rlrHefDoLHqnSM2%QNhuVeZDa)F%E zaY8O&vD&4;i94^332z3!y%@FTdCMt_O!u|~tB9|XfV2F6_4|~c`kmefelaZaOI#c< zfsmLE7&4Xmfl;yhDQ@cdh9dhoaJFNo(31)1&7NQ@W(ud3F4#%4wFSNR0;6EUdgyLr zrVN}g)k|}wz+C09zv8QDu4eiNjr;8Rm@C3l&!eX2gU2IZ^;dk=8hq8?adQ0hRTa`# z{Sll5nXWAY|490b+1Mi6%5tKyJJqhk;uL75%9;<0MP8OXHb;3}9y!&Q`dQ|qeLP|b z@I_5!v9NYi?BJZ{GEo25=v^h&cda+n{k{$nuYhF{p6Rz1<;#I*p7QuHo4{}2VVgJP z0}CC6r+iDh>CWzGz01QU_}y&0#?AHJz~s;70MFYcVW6ol@H>NYz&D&41>@WqO#d6Q zO!VFd-o%h1LkrAJR@3M{SSFwk>xbkSqp_aDd-P`CpwVb&=r?F3=e?GG`^y&W z>i}y8WzhmXOkhZZz!Fb-aVp#|`mUrtk}&t%rMXwSiLywO=5S+x>mxagJR=q>;l~IqGGJe1A$r7E zU0ZE@=(t3Ca6%L)0R>=DcVvC%f#-O4outtU&vR-CuM-CeS4-}bbYmNS1Qs_8eZCr$ z>%Q~wzlX%a%~zkdePk)C28?!Tt2yI^8elFD**iaIaI0dEy>H!(cwHgrg=(ZaKON+C zpTVB_0#@^&Ynv+O*jPk4?z7gXwcJ^jHt)`@@DAMbFcaDX6WMJ#CVU4xl&EIf=f4Zc zbZenm@ejed`XB(iN`{&*D1t zr{BX(JJK$Dh)%kb?wY#QCeEd=ORUz{v0S68vRbBVNjtLggl$ecD@cc@@ScZTu}>2v z*i!-ThGaR(+yn+_wgu=lvEl8t2)>T_~Ksq}Nbt%<`I+mB^x~*E4 zwI;21yk{PT`arRn*Gq9P2tho1Ni`*vP`HNI&V8`$;Rlx50x}}7chF)vy;F#WLXCr z@=ZF|Si=EpS#ryrAKLnnj&rpFXJPJ57zd1IQSZu(v?_Q@50B=;ItH(6WA%|W<)Ss! z2z}*WqG5=>=LCoMN?I&2?-y}XX${wVe~!oQ_li>6oGN-F ziz$u8sd5CojRZiKbDpEpnL`kzS%N4daGIR)g-?@9m-!j7l`-bUmRDAtUDa~$QO_7Q zaG9eK5^wQ&B&foKfzU^o`(TJMg6Y-Q{KVI|bj4a`!jaJbXlGGAkj6I(#!?Q~gJgWf5 zXp_WWh>~zA6}UO~_y~t$LL&C9hA3=l{6E~V9kJZGNvl_B8O!}17${CjX&w@>Dwtpm z@w#5DR+8Nhw-Dy#(9?OLFvkj!9N_<#_*Gu_bBOMo%W8ED@iqv{lSi;B=z<#0fwCBg z?4$p+W+9LJ8UNtc2}JA1V#Qp^`66ncFvv@ULEcX0J z3CqiOwbu33ch^DU=IXDdIqIqI0gOy_8y}Uy-T~HN1<9`ddRrP-bYx}k$~o;-@HeQD zF!uVvzIrA+F-X|+*+Juyv$f}|`9A0gmcL>AJ*}8)9Y%|;=wawu6fla zj41C)s%FNrYOYURnN-V+2dhDILtfQWH?Mj`a*tHzYd2SUv_^>3%NfV&H63O4gW7p_ zMwz24t6+&Hciolt#ma^4n@!5&A6V8{wpgeI@Eto-m=jvKH0H!};LLOD&>M+=$&8Sm zk|uJg zh1^&MDo|c|&~jV-n#c&ut|d7F^=~Zn)y=?>h~66>FTkUoe}Rf#C6(^Rc)uPHYsBz{x3Y`5QQN*B)!G*InNo9K?xg^D*Ga3jWym^_ek2ucfv{$9Fh>?y%42# zDs->?wQ9Trd_TN@l4o7OTN$qYI<7Y%EXB-#~UpFE67Z0t1r}eJO5m^CjWxe((d3nU?d^&AS?ZT2(Ul zQEOR#R0PWhJP)wU7y9T#{t@(s(zOC5z&~;A>x(a?w>DonoZm~_J51j-^P-W~j}XA%JET-^T_@0|q?ey(ep)aD2) zkJytH*kKw-em+O!KpE;}X%+ z@C#}GdAJr7Wq(aR8#0uZT-3JK%A7T8`)f1J*|m#mi!6FrmRG6tpS@gPjFUMBn%Cd@ zGt3#4^(Y6aV=c6><>zY^&ioo+v-gHX4b}{4=7r@RL9r;v@62ZHp6lUragRE2+9&#L ztT0_IeBwU_%%xNsS?0PG-;emED(0Gj7{=<#nTTt`x^D55M%EJ1sxMENe`ZG!ula5Y zuX#HZT1n^qn)*>J8Jc`chjg%VBiXMDK44%Q9`pllmH|o?<%0*9KHb){5_VKWTn2RF z476tYBnhmXIj{;TFA;hF4b?Un!Qoe=3zU?@YRbXk6e zi^uxn^7YV)@(lH%jSR_#XJ2ShgRH>lPC`rWp(OLK?akEI>KAL7VSY7zN6Qe?^>|{< zDUZtXWNw1#r@-?h3X2IJ`gq;Po{;!=j7~`G4IJ?>T?n!G&UmO_v`6h7V{hh};ZdfO z3DvU3K%Tr>AsRp8|KZA~m({OV62_VfY#zqqtd2A2)N) zQgEb#u{YN*+f~EqNb-i*Zj3DG)b6jAo?eo(EF{JScP$Lt+Sxm4U3A~TOMHy0aVElL zh`wM#sqaeq;_T%Ai(dh^!U^Z-Bn|<|CTVPLz*@VyPSxc)NBgd%L=F`b{s(xDwtkKS z(i`E~7?R|l`#T|jLn}VdBRJofp|B%%R{athxwN{?rr2(-dbQ;sP6{6BW=nNSGO!al)tR+hjrod&aTLx%utTqBdXSw?U!#LNAIED1Aej&Vb zE=gh9i9s<2IC(5=2lb5C-B(v%9Ta>0^>{<(hBr`fuKF7|M0?e->bem8rBKcPbuR=^3GNuNc7Rz=v& za)=yy(Zfkx`Z2CJv)1~F*cfmaxv5q1W>fr;kTI$^>>V*#X_>JzW6i&|@X$W~(6Yu75})u!o3)ncnK4o>?4G3D$GlO=aKfbu4Y$;=fdtrc2Lz@?}xUGy9HT?+A#@{{cl>30N0j}J2Zjzn|f%}j5sb{JD-wbeHn`z`Ti z18cQtjjh#j=D3+ge8(Kb5mmSi@Ug_U#LVP{&xV3xALzQM3eq3=5o^OS9b<7Ec*bd_ zn}Ys-cRjDU9@lh^bIirH5V{i9av7|9CVf2VgH&shB`Au}ZqZs4`wIap-^D(@{Y+SA zBNpc%FYJUrmRPs4;>C1jvFxbAyp6eGfi?*UGi&0ZZ?~dzDe7%ZB>i;Yk6y-99Ws*4 z809&}u2014{d}}$bQ(&7qBJH{XwdJ5Aw2AC_PwjhN#+?UghQhLhev_nc4Asxds9f^o|NOe4j+~Uh+mPuu%O6d^%Y4TXr zVfu^eeiviNV?|$`2Ms8p$lWpzL6IGB_C$G8I-U$(Ms- zcIY)|QEq~6yBxE!11BAwmsIyIjNegdPI)WlO;7gCIER6O^VUS1G?dZ+&hp?-aC*|w zSsmoTD<96)`++7E6M<_r3Sfcb49u^~kN?+Ha`DzccK?(c(@HNEvJbQk49vzL={7l!C6 z#~$Rar~J)cHh#cOUK6H=^k`oW-vPOhLq|}K z=prxH+pZ@#7G490wuCyNCmSTJo7T+dD2wM(sd-B{3ghxH4%P3ir%C;us6tBMO_H(H?)>hcv$=|bcwaN9>Eo* zM-ZGNng2QTdMeg!gEUrlY27xOq97CN^q;r(OPB-oJG^eMeE$0X$MffY;W_pllT}i` zz6byAK>5Woi4TM`J|0#b8Uyt@m#uTGyI&124QCLiSjQICEUE<`Glcte8T6iLw5b1K zU88Z>ySEJL*f&=76m21!5H0EDIbl(f2x%j%)dIY5JGeN9#XJ0yFy8mpT!bu{b|<|# zG4f{4V>0iX7)DFHDi%oQgN^t-S~efP?=j894r$&N3TXgD&M^F$(T@${<7k z!Ie`eddNl~7V%4>5ramp(=V`CYgR(*e=$7ZLOiQs88!F4>=4LI8A(ho(Jf`C( zy<>#kQZ?y7uBnbTXR(9TA!E*Del0Kj&70Fe_PZ7fb`D^w3wQYqyqy;gdhMO1rUYrt z%G+4hukVSQsb8fo)LG81(!r}Dr>|Mnx+-h+%MVnTG=(z3Kd3Y>0+k0CRitC-cH$3E zzn7p7V{YO#Wq|#u_2>coDjbAWti_7h$aU3qa_BS9@>;B?rMtD>T5DSEFti*^@DdQ& zVqH|t*S}KT3T+EIq2W~nZ%y(_&=b$?owNfFhhU2?&ExP}XYp1m@cMB1JFhDLmQ-F- zNSZEk;dN-;gk@2H;RL@?)7Y$VO|5Bn|JIfUDFdWu)Y6U!7o`te6mY82jzUL_E2(OS zEC#qP2TADBFl3iblW?C1YFHqprk;;MoDQnzG+>5Z(gqj{sXAGOeHf~Rl*a;of*P?= z0e73^g^0E&jE=nVFT4>%o26DYAlSoLkM~PEKb*b~>2+a<5ZUh`#HOvarqsVkvUNiW z*wNwr4I2f_iw55qP8VXoI|2j;2xqlJrw%ifPCk}mujSLpFK;0`ufZowGpCZiih<+l)eXx?UlS4i?g>QlSuLgLXbp z{(c3?WVxm_OK8^t9zw%oyg^%`of(=W1B`|Tszto@gN3O$;f#!HxgBw(i(nPAr~GzEvxQ?ZjX6k*TKF?}!bHaO=uz(F?So8QE* zU z6~vR!DnE<42t!bUJ!2zfMoV@8C6JqiOKwETaJjJcei(nyNwsK#@KYFhO6!Q$*_F?g zS3M^wJZ~M1o+O}^d{zpJhhmPfF~sz9<+JIM{Sz$G05Nqetq@v{u-H!+8pajGPMPo` z^nufgeb({Gu@k|i-^%h5AUEgSyzmF_b<&y^0~|C!xn_lcm~+A|=rdCbyzqNKvBTm{ zFEgC6eB)uP5aTarW6bOJ)A;8hE+_vqMa8z39~L)wIf=HToR_2=2Q=rXzwp!UHcCAu zZS?Rs{6DO{d3;k<`UiaOy-AvGG;LYZq%BEq3td1;3kVb?O&~N0Vg;N5ihA1$+_oUa zZR*c)44@9U0tE*e9D%9>qBB^nGb2`uxFL)tEWc@~jD>=688wQU?s>n@P0KRl`+k0Z zyzseAa__lkKhJs2vwWX(n78AwkKKV1Qt?@Z&j`;?V-T6+A7V^o%<*B7y{?HyK|(|f zLdd4?<=7K-&Cy)yM63QVC>7QD<4~sJSFd7Y&~Mf$MvUV2IR&Ug9_$w4;cXY`F|B`( zTp^cWHC)E?;e+u5Y`odm0EtDc(wiTL2Dwra?lrg zR@*l;vP9cR2TgYm_fdYGK0f%*aEC(csAfgKP&4W);CcRH&06}EnqhyUno-Zaf||XI zT@DCqN;yxVW{3NSY8J_BsAjqUQ8P|y%e{RK$d79FC~AhYNR=Jlc!y+@Dzu2=;eHxfynP5fVg8c||!BD=I`bRoO>~UYy4`5>6Pmmk-{D z{Ta4UN^a!wICXH=^1&O>w^@1r2vtD?$L+1C;DeRj$<4kdvOQMeoiDn^l&>h?RSCYf zJD(K-jV@BNlU=?Da^zlE4T2i+!8wuKF)EjHPebll5umzHWAD#Z=DI&jHJSp?0H*L* zd=U7p7EXD#Im|=jCrY#*Tj3iDS>Xey1?2m}12ntfQK0ZwL+y(1uE70Rzc~2x!hi`i zJ=DdCCaFxSxQ9yO&>rF@xV`YS3jWwd%(_LYkgD;H)|Z9!`?_-EYT0AhQABUiI{~bQ z>zngn&-pO?m*5o?Z0*Vh-UQ(d?UlcjSv?0FZ+DTfmvZ8RpA4>^p?V$aqIx`lb<32R zkc}ecd$21Rt0$Iv*33*IxC<(AmvmOL++$)D_e8KMXobO!D)U zCVxIcNQ&e=c`yy>ZcJn6cW)@Xf%UbepM zaGCH>%^V-~FL-F$b=E63Mk?PJi`uC!=7SISXhA<*$~aKE4Y*#xMg1@gvsmnXzLJfP z0}Z2eQ&1Cd!KoEx{@?6L?JWD>-!zo*!LhyYD}cU)bj;Ux*I=eAdiCHl*h}~z-%DD9 z$ejbqodnzoBL9tuT{sG5eBbjt)|(2sWc!4dNgpBv+q?PT1;WFt>x48_<(p z<9jZk#BUXQv;=rfP})ym!%0zP!=ZODUx*jo1xrujEa_=yH(|$9yWYmdM7y+J;tDuP zxQpa@0%P~HEVVE0C^IF=^)@Te=4$2yA#oMthYxUdx$H6P1jOaUniqd<75>2OSj1El zqnGmAwOAo}CeF%oa1zQ!B*g+#?st9;>khKe?2u2#CNRDI_tqEW>uo{5DO>HIz=Rzs z_NT1Z+rIFV{DS&ei~WZO^-NRh%ct|FnaOllO|wI5mR|+N=+O<%`y}}WJ7?Z(HR?-K zDx?P4$Hm(7>R z$u3d*8Kk$6%fUKY;p3$u+)a^sp>t)BD`{Y1O;!#|B!finC=wnZOo@nF1-*F==Zl5Z z@o{k4u`+U0?3Zjv87qM%S2wb49!OwRGKVwEk?gs~dpT?&E?yPjR3Y^$Mc)WHj0u=!gk?~IO+KRX`%GT@#Kap(qD@mT96Te9<6u^F}M+d#Gf0b!Kp0) zGVp|AwuOi9QM#zNRI(K7H__Sl$I=(rJM|NRutZkN+%%V+n+i=vnh6{%aTr7kuWcTU z`l`4Q9zm{YYFGO0E%Fpzk{iS4WVxeC>@2AV30;vqZ?G3O5B=8ECSCLMrKhuN zx$)om4tn$EscAl#`7)Ch1IY`B5HxD%V5jtbYs;9|+3v+j zhG@+Hb0sWixSuy`3(hVa=Dx6$EV9on99ei)uatJj_Bp2moI)#~3v-z#10PZei=@TS zp0_14ULFqJ->x~|2Vy`Z1vzg9&BeOmpet7jh&13!=o|PwR`D4 z&|fYyx1(XzCS&HPy;2u~@sY%G#}lrtWfk>;GTd zdu3a%o+AS0$YEuU%!kj(gn|Ft9BD`YZCgQegs2fw7Y_QBbNaNxb3nf6plczWQPPzD zh0T&eBO>Dm$$oB}AE?iH=ay*P=jKl-IH%A1kN2*@dp)4zlz-&i!=j32>%!rM=a!Py z9!@u#4@7EoQ2Y?R(XnU?dZ^N| zXAvQ3H6w=$dXjn2+&|slg0mH^b5(xiIt*Dq_23}o!x~H^ZuY;{S7eUGV2;ILj&Z?h z;iDFga$0Dbz6Udz&g|jP-@?hwf~#R+Z-CYl&9Ctov#zEz&g{p$j(b5Ygzf6s~ls#_(#^MdMziru-^yqD(14~%$BwsVF#-+pa_blbc zXZktVt6jO;Ynl(?`R+xqL2qj)q3^pEjh@Gi&+;Pz&2geRXBT~hxEKsk3JmTG3whDR z8g9m!q5mu_Puu+T#-2s>wzIwyfrH{9^xhWq`EGCrEc;`>kQwLlu6%xB4BB}lz+prh zZa#>9+Ovpg**cWTvlLm+;#anqH?p!td*{3!AbLY<`|`YI7T$esAR>KE&a!D>CXB!*Uc;khMK3(hSJBhF6{JsRP(h%S@QKIKdEoz{L$)0>dv z3D|#2vBoQIA;hbL*k5)nhDJ~({&m-4s~O)g?`a%6N;t9N=F2--WG_Udp*ciz{=Jl> zjo#Jg8*$bg9pQ{4ysjX}-asW#E8hd&DEtC0^(P^ zFk~m5#g2s%2I9P``gXYv9+Cp?l*(~Cw$B+VF9jTI-b8IJZ;z=l;OsInKe6W7hsl3! zh`;**?IqrGKGxygxYpp1M&qVyYQfAZMembtQ^nGX4`!Mq6MLDx*1 z-RSjap7=HpY8rVA(P!R;k^6y0uJ9K7vXoq) zsL+T-pQIV|E-Z|6pmgyHrQ6suQ9%rg8l*`;&ym|fbtlve)hBd`kET9;9Q{j}v3Cvf z>{OSlXO;nVF(`FeO?4S_X%-dUYJVXmpXKEz)*c z%SKHmPNDM_;R8nWQ}Du3PJ&*Pde?u|>lnuU@|utAhg{we5P=!_ES`!uvSO=)ka7iW~r->}iv zi_xR)xs0EAKSs`g7AMsnA8fH2EjIX)oJqyWXz@qg6BQY*0Pj8;n_*$z@&HCG4`VVB z5$AXAl%IW#d=EIi5@6aW?wQ4 z0ZmE|+}oROxgT?{2XhZ=y>N;BMLl8oL}p(^0;ft(@{M$kEFOjSySnS1colffWN9(n zIlP!{{WLH!eL3$d!T?#L|jVJgk0H=MAxb2 zU!WgRllq-^2wv*RD4zfdeDPtG*N7fXuDK8hKHM4j8vRG-=b?7QfMiC4mi>SCX%hN0 zNomPyw1igwH_>U-r`J{g*J}73;wPyQWlviS{u1_dXPy|E|gN6L=$LPK7?H5E9HN zaE5dZ#T)wsQdnAtMvN$(Gl^ak-5x5F_UdvQWF(Uhmgl3sdp%=jDuw*c#nmK0^){5h5G&wxLo$o*@c;i zn_mxkTZ+45X>3+*>k-%-X<~AQnY$Lzsr+Sd zd*wG9!A-Fo9qg-PT6yp{v}e)@nsjPjr6;K#Z9P2!73eN~--Z+5)g0l!1H{#QsXV>4 z=R!cp{m#c_s$I`7)J)%1qME+DM4R8R@Vi0&i_Vo5nO<)9~#IZ5^#CaLq zoin{sf!&tUt%L8DUFDks3m;7}3r-u*xRPsN8-zERul#jNuY+u~2-nbioSTr=Bl$#R z-K5Fnd$`H)dc^GDgXx2aW~_&Lg?f#&FnloB%}tKPpX7rlyJ_qpvm8wO71|3Kr)9{d zHzG?X$vWNp6z7J>)1UE;qOGb~A_IS#9qlJior7U+67jOC9enUlkf55G3X#(fg}Z@y z_SmgUQaQh#@g3_Su_=b+J#He@cbrhPu0NQhb%_~*vP`yIy|zu6m8Cf zZR&sKuwgKV%kO{tU+?e3`}YsNA8K;Q1uVZHwU&*`_hSdcOwF$n*g9LTZ=E5pvY=dN zEwD8HisfXqo7s`jg@H+9LkPwN|IZ0PZ!ycV00tR z5yT4y8lj=4ys_$HRZ>cIQDgbV@=)_DKobO35u+S8gii%RK-(g`yy^HYh3D82%ZYtv zjAy?oKL@SDI`T<1AtGGc4%^0}Vg&>CFn0v zYO>Y!ujnwKMPF9!utlBV{rjpm+k_Lq1IBD!)N!}GtLki3lHswU6xLa(V=I6QlYvwX zmFsP$6O$}^(B|y+BcYXuvsM7ErIezz=jwb7GInm9Trd(Mr2Wtvd-RKoD)7wMUhX&& zDjxVfPSR0KtP1PJ%F))`s)LAC_7RZQN5QU#1^>6N6RqFrh-H$4nU93D;g16Xayb&} z95@>&kf$ovx2PpX0@00G7JO750F~UM=!bHvsw%T80q|%oP;A1;mysc;+zyOq3og4H zY>IH1D)a{QG(Jy9zQR}j7NcuKp4e5;evK?_qH`X`o=tZa7PF@rVm;-tY0d7eRUpvG>lVu$fmC!-_`hzxU^$t%bJ}r zK=)ZGyCrxK`;STNns|SuM1D?*9V_H#Z9ld0{;`OJ^nL3Xc3%E>;CqSYm2l!4|Ng2v z+gHaUmPw?Gx(=wooBJx{GztFReGv^5JoEc<<(0}#AY#1{4TE$#Scm6h7$;7gQczQY zIXhC(aZMVikk3^umNye#kv~P=gP9xMT7|dg%N3G{bYJ*3VJt5M$P=mnEq!316=y;f zc=LGZPg(G$KBB|A0WIRCk=}sS72x-ysM(Uf(4bBXn%TZ8c>ydfwf=U<8y29oiw9WH zi8_I@<#zi{%X@6y{&Vta>7rt1qhJpQMJ4ZZ{T1@gsxwtAII)jPARQVI&p`o+7V>Tb ztS4XYBO1L=q2~f{Nk}GRQ0P3}BVE@FJ#<;nLz5jnG*HE~PtS!}Al-*mlK9cBD)Gpz zLNF0N6tvH?;Q2w@CHnrO@}1pZGbaK2De1D|b1=^iZ&Cg(6=r2T;+D(6{wnWb<70e4 z4U|)*a*3ju--5e$DHgNKfN9m@s6lxx$C>F(Ts0_XgnQ%-lwTIo&OzFuo(9xV?Mrl) z%dzOOWPgm5fc*AEEDDu$1xV-Y5$`9hscAG9TmuV*n&uS9FdA&VewXz5f0XkD%Az)r z2GYcIKs2)94T|4tn8$63)IJ({3O%FTsj%@+^hb?P$C?{n%q!k9>bi!~dyL>V*)Mgp&r}~in z2k{eFPw)vKjzXOt-wyOwqi2%mUsRbYwDgsWp(v!ha7k6rEEo&6cR=)j>yZ zo?gJ*Gt^FibdM_#CE5>j5QRmHy?j9r%lQfTAY8$>@SA%C_O{elEe;>*aU54SF49BW zAy3!iTo4Y$g}JFiI^syLeXn2)2tHaj(CZcwR%Rr<3h93wxH|O@zmVEG7)uVE3ECYR zlw%lIJ*g+lK#Pos?SAfQ;vh@GL2}+j#)0PBQd4S8tZpUu2i(aE0(0mq*iA>IF~(I- z=_jL)MENhkP#$`3ud%B+qBpar!WJ6H=&<}ldBhLVKAk{TUoGL#GXulGwHlaQP=R@@ z&5w0jq>3^IY)Gk$xMWy}!|o>v*3K;WK`)RfuntF}&o-d1YE#rY9+w(d3iyI(tSJNb zU~Rr!0J{&#S}6pV_2P7qCQ2%I1y=gwppCj_de4Nb23H>%suTxpC-I;BI+072ixNa#tJ%RsG|+s!g|*+%*y=L){loi|?ZvyM0VOjsSsxbye!#H}xX$6;Ox*h#pH_VSjL+-v83O0`8wc!ogH^rUR>BSik5g!b6*J5HGwi*A z#u=POe727R-W6+ui7-}=Dp(0?0HDvPgCPuOXr zUXQ5p+wDwrOUZ6-lOC3SdP!gTkb?ua@X##Dp)cD`zqXgpN;1@!k;Tsna5R00fx?2d zPK~>I!5Z(sMIeCwtdhkf!=YLC2>8oFwSIA!h*YClQ^z6 zx8{6fMf%Pn7W{KpM`J`r4@wx^+?827rUttC;2xmV)xcg67;aq}GeyhzvKzje8L+b6 z%LSk9r8To@0C;xzwY`^{0YA9lh5QFr-cr@eMQJmpK!8SK?B;aN1IKV6HG(qLV95Mz9;9G~g5P-Xz-JK=)6E z-@bU`Q>M53v9G*~dmQdr;g$J!eDC&gXy@#n7RRet-@zt?;9_Rkd%(@2n0kvh;fY28 zr-mDBvBQgsbAUS@4%NY4EPrZvYI0UW>xVek#8fO>QMsym^{~tT)?8b>TMmbQrywX? z7oJ>PhF`yd4N|nPK&cnmolOi+ELQIbhpNMQO6nDmU0>s>*Fyu?Hr_?&>hUgSs>6Q6 zObtLV6nyO~xx9Amc6+Bh)=4t&#n9m~e}*&Dg*D*Ma9ya(C>FNCN^aY-N^V2i{qj285CTu`$a>EqmDy8`OKuU1~uHCqv#q|s>FRmT9 z!ideh9rNlu`t~pAdzPx!?Zx$XT!(PIhwGgI_8`$dqI>m7^Bk@Z($u;(Jj=)DpK*=E z_c6F8<0{6r6ju$d2XSqq@7Vu{*COACCl8=i?dG|8;4{d#ZB6fJH@CG@FKi>*i8S|4 z;6kP1Z;t=#YQC4K1(?q`iXdPPxr7#hjUTfK-fl53FRP{p1@*vhK&ipl0>lcG9_oLoW=_ zJF$oe02u}3GK7(?c1G92i>ej0#1*vUS#hFNkud0j-&^pdpzBnj$FE zCNtxd)YoIZ{NK_8?-99QnLY;fz#5VT*vDP22Qv$%UEszq=c{W{7x#r)KsVp$6Cl4K z=`cP2aj>3v?ot=yeqnM=U+5*Idq?5_sST8dIG!u5k2%~K;)Cc65b;{=4IKq-ARpD5 zrV+5*ds6=zcxRG3*l4&js5h)^qJ=2|%*Tl9r4c3WykSUKQ!1Ailo zSmTgst9>UG`gt5Re!h#^UpI4FG*+PF_cwh`FpGG=CFemeZdN7#>xD^g8N7L`G6sRr=4!V|oAWHkI@p&bX1c)(yV3 z_&6+2T&;0c?!YyO91E z(m!uI`f03NsIR}7v*a-vbI3um-fnO4#Y3x6fAjsfaFd0)_b^UQ%&!SJqsSGUX+6GE z|J{NydvI_sfG-}r5UF(*mJS;NYTb=!T`TVX2rsQDwC#yV+b|=@>zd};43sw7moVmz zS>$;|cl5aPO*?4@6I}7&d=hVo$&LXUZj8v85^v6}IU9(JmiEWPOv>OUI&jJ5CP*qshaeG#;ko>5*Gk=K>ara{IM zd3HJdgiH6}9SZsW_lgDdmFU#w_zb&MBk`f8c&*g6y+)b zQj2itJb2u_wwU&57^7=|xvchU+|R*E^l4a#cc3I7Vg(oW(uj8r(wSke1rZ5};wJ6H zib`&0B79o+3UvdhlWOlk=y>=ArcO`0F%GS`wl^7XHs2IkiJAk!H??mH;EpNXpAbQZ zZBp$eG{=F^i(yD*ErR#pO^_|!OxNdu0Z7Qz>Fqw~Z}xg|mK=b6Z>*PR!ahV_cxEr; zGZ*0NqV8p0qJsx-IvTjLjdwvZp?9ib6)You2kjWcaoW7MISV@Wk3zR%MFDF+k7CJj zpiWsh9e)&Bpxotgcc72Y2n2F#t+3isSt?U0=3mkPxAROuMu9=(+!;J^>B? zHLhY@;qUTNA#)*38hpmRz$(qyFwx?ezm(( z;rnkx9*^Lf5oCJZ5HafL$3{(Bx>Pg#nv1Yp_}3cZ$;jJ$3=66q7nPol-@_ z1gc9cWShCVp3sDTs+AUF@h_}hmH#?RWZfR=8r^&bbqL`aWs1~~{51Zl)Q{p#0TqGp zrsSTG2pa^!F9LmDEWZ{wTz~Ho(t9B5i|B~Lp}*pcQ;0l9aJ)yTN^ar`g>rf?4amvS z;6HXFz1mMSgLm>6p=W!Nn{Pn+QAkhy5=l$@7-K}2DT*93Yb_MpsG*uN~~?+q)h_KbIlDhX>n1s4VS+{S0*leJrP5zsWDQfVbLkp19R;)>^EB}aD|WfgofO^7ZQ4i!UQSWyPQYm13p zS74~I;@&$L-4@4k#wp^6^ZCM z6Pr;`R+gG)s99WNvIs%0pLu~S?)^p|CBAHY#vbjx0E;(x5WA!6qP;Jauc&A!3!$vt zCEh58s9F&E+9^}8}T_C%89!>icz3mngEp8cLF;1c3WI4#g0I1+|UPoyUJNs zv%)j}bwF)u1ovyTeIM9UwVkak;R+f-dkFuYnO+DG{@n8q3A$dwp1X$p&IpTy+Ddv3 zDr0#iV(&sPUr~0Q5_b`}R2lU2Q9Q-|Ac{5Ynx7zV>xHaE#VBSIjrOp?*vK?HnvpF$oeuB}_pbV#msqkEPw3u!F7iITM|zT} zV<2n9DZ!T~+{a0a(;q9^qTUi;DkR%Img5W@yz9gY;l3rd1x3Od%3I5HB?9qX%RR7# zNa9k`v;`lnIK6_NG1Lh?QW9!1m)S$ z)x0a&N>Av1I1~=&H9eSNw%#>kuAL#~nQxLsI+>@c^#V-l=JXefyz%n|gPm+plkFNitJ7ghvKXgo#mh!2=90U~w zQi=!C_&a*Sfy@6b4=hNpFM3FvFXY&bd}KVu2WULSdus4LBmn4>cvp(`C=}|Y(27u* z!;~`P#Kra^ee7V#DqrhF3yVhC*A13UZ6^LT4Lz=bWkM?a6E(iO3M=e~VST?Hb;-J_ zE^#Kw4&BWIx=99hQ~IMt51FY}(R_?uIOO#o54|w9iK478=m^|wti!GA$_z~Nxpc+JQVLrqZ?^aPJ(gj`^Et%4>xs6+xtFXE^6OW`PB+{h6$&q;dybE0Y#2kp<}SJ7F=kHGJnArv^^&17@h~wuMZ#aSe*0ba|N>V zhGd%_80^KaiLAKz8c7Jcdw{tnd@kiKgKt2uB*O|DXSf!#$x`HYvLz)3iB3lzOMyI} zPqyiNkf~S--6tnn?rA8Csj)CgZp}}YB33-$T=?8&1#-K_e6m3H3iI*TsM4PDSn}MG zOsf`Bax-!C(BP{yr*xtu=Pm=rmU2&rGV1Jy5N(mK<3yqExxoHah`}gw^#;&jN#2i? zrFgdi@+sbz3oTFsI3s$h8hlD;41O#p9<HDs^mMH$$mt{6x7EhCKy zXo0$>%cH9T=e7vFNw#k^$0-es88G_5)enRk!ZDBs#QCBjaf_fDXdx-7kOo5QAPpFR ztc|EOu+;pBVTAYI%#6qZzIjB@5iT2N)?zPG71DfL%mm;ddRUU&vS<@ZGkpdeJX}nC z=T=w=S$&oyxPNkp5KuFxuB7S7{N<$YR6NZ*5;g^4Y< z0*?T)=ZO}wI~)jU`yNf_rY*27DRSEu7aear(#V2Zq-=5g7WDTGTvVQ}X#w7eamEx+ z%O41R+q<@g%U1b)BD`@mi_4L3b{~9eB6X@O|2c5^-IiOqJUZz?64o>~HOcpQW7;@X z+ii+YbRcx3S3CC!mU~mw+_h^hQoO}3@ipkpW-aSe@;Hw2huRG~j8k2l#dGUM!fyla znyz{F;{x~_Z3YK_3w|24;Bm%sqJ4zAq;h)Ml0^?m7W)#=P{L$waqL9@5lxCiKWJ`P z&lWF+(P;2v;0?x^D{kE*;ft-$Jx=x$QnQ7i?+07Tuo{?K#% zBVm|HI`e1ye{O7Pd<64$oCQ{(=-VZTy>tEAx9%ieRe$I&{Rz&g5(|C;3M@dQH@OF# zBt9qhr z^P_c4Z#6&?6|?%dHu4=-p4g4MnrbuX42kufztC=w>sFJ8Gf<&s&`E*Lji3&4{c4uO z`;3+M-^@+sOu$WobsViTqx`sjH%^#3W?V(6-KMNQAf|H@^<{*pWe1MA#y4Mkym8%~ z=moU!Hbpi_ah4Q23beMxv8#i|W;85oV$3Qx$zQqP=zh@jMp}i{hHMFW&YPaWaIve&_3u?1K9A`RH!VoN?H|=^G=94#{&-w;^(` z3;T%%qfTe%PVEo+i%X-%jAmo3AuDH2fcAoaO(xDX8H(d%V(I0hti<_r@Ho7>+G?3>m7Jzw>TVGYTYNO|8MXKo*N7-X@beh z`5JSsdz@<=-Z|J6myt3|&uiXm4En>FI%Oy+Mu54$rl*%5Jw_>m5Gc_XH#+fr+V~Sa@ zq>pV=i<~*bm4RQ*z6^K9JO$UV4oKmcnI&PsSJ9e#T8&>$Xp89tz_vx*BkjIJbwjEP^#8@~8o?6Fp`Fq%EW$=k~I#e6S3tfo7)OtHSrv0XNQ~ zvLm@hwGZ^VYXr`zS*&svAAGZ43+W*D8ea@;Fc3=E+h&ddJ8m62uD6OnJd|5lg|#I^ zw0bgbSH_%ox9E$oZd5Itm03CPpe?LLKU%cPw1a@>!@Ve~n;!9oVL={aUt*0D4OYl9 zIKdv_>*-yM@}3|^s}@_~Daoe{rbv+xV-9&-dM+r>x&M3~WjUKO|-M6%4$Yh=REOtTdFn2oq(A>5~FZF93|#jztNIC_OsU8Q#>NYGe!BBtD_~t zU}Qy{Ro6uNsncP~DMi+}HnPV{;!SEN3wFTnH6C;E7^H;Ii+svV{yG6zC6O{&W~9u7 zF;uF~eO@1B`C6+*?Tm|atXtR#>u7eZwZJw^!Qdd-JMGFzvIgGUCl(P$L)aYPPbR02 zKa1F@R2M3P6MdHTs8y1tu3T-dD`;E227S5sp;)Vd3=%>pUOQ)A} z-ks12nOJ@YsI7NN`b&_tOumnqU*`9KqQbLm;$o}d&6kb0IQd*VXi!;!Y)Jd(>RVP- zr$18^>xE_>yhR+alGS#6AD;yI7HIYAWZPGeK7JA)Oqkv%?&Qpw6z(`Wd!%zzGG0JZI7F*RavGmutpQGuVHzYuCUI12woMeZguI?F#0{QOAk*F>xdR zJnGIB+;1)AW9=TZlMU7H_+b5_2kRGeseW32fwGT$jeP|1wr=JoeH7rQ9)re0!_?3w zghR`Lb0%rc%$o8(@NXf1GO5jy{e80eL(4dJdU?96%D>a98Iy1IjJcOfx93Zo#RRPI zM5ZrK$YO0=w4UwC<0OjGcY68zp;e&1!(3XirU_9!eC_%;SNz;$Dc+SVrNLfgn>_~- zr)3%N9a$sfpIM$NovC=HVncyJ3PTo5bbAqr={g4a_8_x@Gd8s@FG6IWC?7mbxfHur zsz)78FQ+r_7S3STNg+i;qJ1f|mSwPQ{8nx&$>K@-L7J1R?_Y;#&UxTNz?J5CWe+=4 zLOYeRTbTuSinLDItuW_tR>;6UCTsxr8j}hXYwzG*3A>;EQnhh}s-Q)$YhDGq+>ir% zBYdi+X$^KQPFb;P-xEl!!p;i2jDA(I-tGZP$)`y3hrzV0BOLyvy_3rPrTba9&so-i zwg8{mN^yl-p+!bLi4TW%j?kLv0tezI{h{X^?h|i~ixX+3=rP`3VT~}x54N3XCAE|I zInp%z6=)~4!+#gnLJkw<+Y6oO8nXsFELo3b^hYpPDegl}^FKJI`#0LtIM|*b=F}vd zs1opgU3jirH_0pS!3yR#;jB{cbl2Nf_};)=Ue__leZnvyS865A5@h&hVH16O85S6~ zJ@tOb0{yGj_Ylq{PnxfDU+=oU*a_a_^FBK7Om)`V5vNpq+@ZlI&aLs@SK8RHhU~Fbc`eXT31KmfW7KEE!*OD@J*-c6@A4RG(`w#WlL!1A z(o^O!zMjLkHq5nPGZaevmw{n!uI{bC2)EIwEnK2C#;SbV%t`KKR~#%QlH3g*e7ARc z&IGu+&jRz!I&fc*TTXl;K;uAtDq{#N=+lRW=1Frn{CWjv+W+E^$q}YU0Lb+z^GB7WW$`z&hfu zW{cb664ATbj`u?=;1QViAC;eDNsG5SnB~pc z!~BoRdS~KIdRJm?a?L9WFUTw-2YJ1&W{tTL@zu2cIJ3(h<$P2hHg8^&;N0x_Jiz70 zO;+W6>px_U!^uo2emg+zor^Yn4PK4b(B1e>Z5`?lYCEk7hJN^+(pHvXVjeR$DI8iK zHbLVHR$0F6yS2vU=#< z4Q7Me;4)%vzusG&uF2(F@4{bITbg;4d$?;v@ehGN+f;3$dAK{#l}Om*UasC4U1w7r zAB&NT!KxJFT@$5yq<~+b`e_$z#cG{21!42LJX2K5e;b z-D9}+;0huxJR;Sb$Oh`!UZ9KZV^Z!B65 zS`eZ2v7q&jgVqykJC*YaluSY}= zcA{p^k}BZcN3uk3luG7Kx0dDo*Cfca|PZEaxv zC4^&OsD0Evkr{B78s1M<`p`M`T|l2??i6&?7gHs*mHLDFC)l(RC;^bQ!@l76VU<_? ztWft9YHatfw-vQ<882DUPkp9&osChO?yk_(rGq{iYk>$*-`SXKrzoJR`rI@xtG_A5 zt;U(?tCE5$5p=y^rHBz^CS|lNh{7jDDK#YwwnnTz9aba@p6(8Z=7yiLeFZ-Y!Mon} zd8?+L_f9H@g-ZS17=h%Pe+4)t-u;#1Np=4WV>XP=Q{y5!vv6pZ(nC?Oi;OCcE$3=? z*tx;Eq8j82h`$}mhw@NkmsH_g*Dk2gui!^SqpF+cjz_T4TqizDqwrac-DU_P--qsw z%Xlw3$~VmYjBP~ggOD(>lyPjf7Cg7*?s6~JR6cG>0Zs&T9@^f$n{%dk@YdlTte;GN z?$^khVhEBhjOL2QL^I$apw?yjhQrQHRO*uKO2%0Ze_=`VsJsa)HZq2P3rpg;Dl=PP zy~9FuVBEy{TnyGGA%%+-kWq56C|M92Zm(&kmYfa@wL_7if*0ci9LYr9KSDhKc2 zQCnZMXrL)DNE2Y^d0JAt5~U>y4UC+7cq=>5!nW=eae|JvELov(tEZpFUjt4EL!Sm{ zO-R10g3SFxIzQsfGXv|Ewa~dmhrXQBt7@UjoKb)~rzOs7|;Vn*RwNuPvnj`Kq| zZ%#nkx!roVU^d8Fae;L-dTOLA!IUh8LwVi2WjM+l?%tw5y&~DI&0n&@xXKviO@Otb z@7_yua#I&X=w=Uc90jYrXTfpZiaADgQtE~}QQdxv-@h&4tRz2G;iCF`kS+^zayvc+ zNXG?d>?*G|+1BerED42kODv(NBA%$01f_plG}h5>ldGo5AdQ}9a+~HBKwiE_k(a06 zFdB1g%!vW;d};0iNG#epPeHHWYB9QvbL&?uSz%aldbt6!X4Hw4xrQ5BEGD*3=7QG^ zyd-^hQCJVj2mB-0Tj5X+tY~KS4TPdWb+rH3KIeFV^yohgXeWI}a~<>i?SEiKVtx!f zID^q#`K^wbJh;N)Fvo&uC%)6g7%uQRccMDS~adf2f3GCV&mWO!`l-rJJ=tQ*}Z{&-ibDl{a^{? z-RCpZx;xRKNcLLM1Mdda$<%RvH5u3-X>7Uhf9_IV`F7bQj7TeD6sk&df=uLwyBMMEz6EOR6Uo#8^{6 zk4hD~1^QuTmTv>x_-=ocWig&!Za3Nau@>+jsE2cppew_rgFnKKN>CNQUM727=q}{# zl{)-B(n#_aNM}vnN@FzHp+~-#D&I-3480`FSzEn!0rUdAc_8%tK#cgst@goRUk&8S z9#~Dz=kg{Z;zYH8I4doP-}9Kl2Q{Q~GZxwGMUrh+QM>S*Allv57IQQoYyB<|gsk)T z2hv&AjdA;hErba_4YE(z@zwQ(5_>Y7s!hW7zEE6`#d#PrkHcL}j|tz^+j)Fvz%p%V z48z+LmiqO^--1u|rCU;f@&I3pFb{+W0nrFYz@zl%KsXDCoY*g+akL~t(*8|=5Xk#N z1CZrpNwmIy55G@9q{>r)NYIY!Rpe&ZHn)hh-%{CnlsO3($2cys9_B;e zN;V@^@S5G4=1+@-R*n-%Ca&%>)sDn7`gf(A59cq?iQ%xC<{^(!`ARX@RjBnS=>8+` z>6)pm8>yTtg~gMIRv|%6Fn^ZBKCw& zdT=TRw@zH5BxOp3FGc(b*#NIrjiz~+KM~c zqsE-twF-U~*h#+cj_IK9MPVwH<$mC=xFg+afPOX)x<85&@>YNw!-6+<57p{N|Esuj zukG!C88zt(O&w?sP!5*xN#!#=jFXyUkVnTXeiD5VX=||QeFsx~Mm>(Y#yFM|pzwNFdgF8)Kxim8Vtg)bAiyVHT@n?;LyT&Ax_>&sUwT zERE8fs*qa@B6^KOB;6JR6L}U%b0gABfmH&tl*3!f*x0bvBDJd)pR_y7)#(z;Mx?mG z{<1pyLjMH52s4QlV#kHXDh9a z6;*%37+n0cVWZUo-q+r+)@l;PVG}Oe}L?!HieG_RA!1}dsjG1Vp%`HPnf|k zF-~L|g^J&@b_J)54Tlp8`V!ptBBd|se&qN3OTU9n>mfT#WZa8t_yI5P*Q8GYogjQY zRr*90PU^#)GloaQ_-+8D9l>tmp`BThM(*nSWgWXMz8o z7b8n5_ zhZQ|<$m<+gyRm$uTn0wX?(u&I)4I5zZ^^yFJva;VM!4RUxs5D#xY zb?dsg;p~C@-{Q{Bz<}j<8C%%)fXY5s(nGRD@B6r;6m4L> zMwHo(+Ptgm&5_#JQX00Js*?<_8|Ld9XS4Pb z9i1!BR^Dn`;7GUTL(@R5v8PT4jW<_UNMfakefny?M(82F#)N&a4*TE&#~+RHgLVv> zE`%KPSIDp03@0q|mXtplEz)vHi*q)I_vGldJHJj(o-z+hQJc{j@fsE zzcoUywP$UlhkpgjWfvV z+4i1>jVw@cMeJkc|m#p4P2;Hv_ffDxZLKqN=6`o{#khM)DKk{1iU z*fT94R%85NX;LAdtzM$MzpCfk&&y@8a;KxrA6(#nC@|B($8X^7k>jMTY zW3k z#+O|=%kZ2-uH?4b5X;Axuufl_I$tNv+Tz#*?ZG++&q_fjd>x4>uP;>8MN!kg>fq|L zD_L+{|Nf1&;A1`T0o=cKKH`^;E9=m|;h4cr7_y|Qvi;J0htt7=OZ)fBsm7Ni$b`n` z$_r-Yf&zNw-Lq1ScE?VM`8Nfqmisrd3H$x|@^9qL4(*iZ0@OmFW5LH^Jb1_bw?;VG z{orKp13lQ`sCN`FW|{};vBLqaUe*NPtB$wOwu6o=Ij6F^auYCQUzB(18)jF0S~{DZ zS=X_$YCes@cETwLwJ-EZ2oy8{n37W*UDNpi!8?ER6c+Sl@m*M>ZOhQua$Zn77|TPD^dS6>WzeBrwys9C6v- zaQr%Olf#0Q^BS;#vY9a@SE5vIq}uLV6=2(YLucS2#(dKPY-e_*3HIxM4|^>8L67d9 zZfvwjw*-Edx-ziDaTChi(znF1Uta3)8um-Maw*2--T?Tu`ecdvx;Vf=!|>kctS|iF zgD|8YfGs^_cn|(fq*IcYeV}Je8yw)~CnWpsm*0eyLL4YIkhI%|fy?I*5f>uYIT}0o z&Fg+RJ`*$WYw(1Tb4ORx9LL8FPt)JVdK_=FIkPq@`3xV-Ctk@XYA_$N1hYD@k0?2P zujKRjWRE@UG!r3J#c5ZK^CB~~ zvs`H;?1rrPPE?}`Xcd0wvcGN*S`a0QPqu1Y9@ADw#VpdX6-Z=jj*;ZfgT9b0KuyzQ z8`nX}700|$QKv*^2lkCv#^K1!lQq(Q%C8xaU25?Ay`fro6sG$;mJ#lY6%89rQnH=Z z8ym~ZxcY{*Cd4G?{khnU&MNekaCPE9b#*>L*`>&L*Vy=NfKF!h>Q7DzmO49+dkt$3 zEBDR@=xi}`R_+bil(P}_%jJ6;F5L?@{n|m4k?3MPi=DjwKolD}KC4xi&DsuiKpxVq z%LI0(>DauBK(bvbYo~+c_)E_UV!2#zPiE)j-SS7$W^jO=`o+L8gKZS3@J{$oX!EY7 zeNo`1*{MHt?86$`iku(m?h?ZVh*8kG_^cem{7-hMV2?8C>{M~PV{f!)*0j7s>@V}y z=(W?1$-80QJyha+V?qu)qd&`XT22e#W3?USjtW>LN+@SfA-F@{4$o^aQY9fEuibJv+dgO^c}kJ^hd4jY>n(qiLvjH z@02>F-O^6!7`XEFx*gWdw&KADQ?6GeY@kX0B62aj@0P&HbHz%rm@)Mc+tk6SYS-Z{q3g} zt_pV@Xkil2T)2GZFFY%`Xzm(gjRNdBc1#65%IXu?S_fCa{N32eI`!)@E|yP-*Lv65 z@6O9%eRNyc$!w~oix%ISo~xOTZ)iEs*CetxWYeU{Y>?JXk;noKF)3<<5$o8*vDanU zn#(d|d5}a+7Z;IdiY$o0$^c&%wI=)5B(cS?9H(le>SWX`MH575DM{>M?Nsd%l@Bz! zcQh#rsc}PgyLgyh?K+ef?-DLk&(_vTC>mujO$y{SZ0IMoojX9qsM|TwxicDBm2U z%{4RfUhoFGsOJTxq92cHUxqY3&-LWjmU#AorAo(B?nav$EjuiJk#Cewfy{kneg&f# z>5-{<6*70u!YH&sT`@lCsmjz6?Q*RQHFa03P+kqjr4LtHmL;0pLLS`f7NNqxx(%y> zMO>j#qt~!v8(S=k%*8DA;i#QYeK%_JdrKU?9MXwNCO)ski+N(+)aiEVZXi3V)z*eA zd7<(}%XD`^)R1z&s5i<|P{S zoo-`-&2(A!x^6qC_rN{Nq+jH~5Y{%HG3O`^1@=r6})K z1M;@v@otBm0qmc>Y)Qc?F4G>c$o?kNA6X6{|8Bj?udKr3ZSFZ4c+O;Nd&K*gVIN?I zl{7?f_-ggj~F$)VU2q$=|c{;bT3*sk9v(^1nbtb_u?8J?}Ush%HC1t2irC5EVm>!xX2|6k+f@=%H2hr~o}mQ4ff&4YcT9qz!1DX?qaK!#sCv^q zt64^4G~l?78dUB{T-4xqC11D=F!>|9BSzGR87P$u?5PXW&ezS-ey00GYt>2m|Du(| z9fp?n?#2v=L8RO-J|T$TyK6a7T%Gzm81*eOexGLSB@_(bBV_vTA+q?GAW;xOCLd8; znQ?at6G!t-8c(6qqaK)AtS;EeFDFf0J=Ut+%Qr}o19zSFE8qCTjFKtLu-5C1r@W&? zW%Q2br%L(L`ncA;oVD)DjFd_S_0WZCU(&s({Z#j{)`D99j9Q=kuUdEc$6C`m%i=Gf zb{9~)5-V^rH`X`>wNe?c7V!wbJI{>x>F{AUl0yR0qk(epd&iX9f+#1`QmZ#gq)BvXk#K zm65Qn^EKfmClD3m%b9`4hyhn1W5Rf;C?qH-or&8Hj>5)Mei*H@=r$TY`n*Q!hQD4gY2s!FHcEv$Kp-?BdybSx(nZ}Xr9sExYTwaN?)*TeW9wLorTLgs> ziHx47a79ipPha@5OBSOPY;nusXMGMot-F!>jdNbfE~*5=yuqb=DUA>XVWp*3&Foiv zlYHanyaepoNBl2Y~vBmhvedh9k_Uc zF%#$5?|yL|NZs6lhIyz*B&NQydzpLu?3eP3NJOeO+x5Adlia%AG`Y?#74`^FO+>CS zZH)qZc3(hytuLM~I_%chqyXZg06sq_ttPGef_}ZNrx-6x4{;0pzWBI!-t~-jqwVZTC3f)jQRpqK(lr)3rxcK(r9UG zvq4E416Rt*5QwxE@yzzQExF?Y4I8i!lS!D9|2;omr5&i~AlimzLdD zkvvNKI5zPGWQO)7#qZA-^Ci?5cjbI>1=g@v+MXpliK@g=nds-qq!Nr_$HgJqZJ)OO9ZhM) zo_~s_ATpIY2cFUH7iF%qZYFWDo88N@SYDqH6SbI$e3w>E)Uk4{Je85t@td961=%bH z7j0=g%RlJwR~*PQMYX_2(tOTJZFvVOQ`)?Hom5@0jPxC3BA-wsUDL9RC6S|H**oGY zwEle^F_ioh(AIRP2$cdb)0?Orzk69COP?-8Txx!*EWWF07cA-2SGvTnWlusw<+3M$ z)wkPDv@Yc$W39HrCfc4{tjHw#Jl8+hu;-}Vw!ihVwZctUO5`7?c4ol>d2_z? zGoZ=DkPAQ8#YFFAutPA5ecwuRWA8T8`u=4c&F+Pyq^NS)fBgaXqDWMure}A%gRLQiz0O*bdTWjizf*B*s+Pgg7mvi{PyH2UZgPmz86r z3ID_S9z0M*M-GLsf9Hl-kzi}jH7N59dXPFFo9_t-4G--5gg`2yP z54HdWyh)y!{uKfnLIN9tr}Ikk9(zNIU05n_lR(MSxhFY33As;h&QJG@#LOt^ovkJk zjA%KS8qh}A64a(pVvhug8e()<6yYX*RA@QQfY%kOWUv}YRBxkn{LG*o>Sz);J{sr$ zbTd0_3J>nrFr#E#NYHk5Z+bOnVf;}h$neZyhVJFg8TIB)A7>N-b3WY%8%Mdz&dvC7 z#^ejL5hb_kdm6ybF2pOq>j7j5M1vgW;WH zCpqc;n+d$);Wo6T@hJ6&sb6e9diJ20xMgRv61^}>&^Wz`kF&C5;3k@856a@ugHlDB zNRMbS*cKJ`*uw5$2=D&YN$nD?RF9re1n2{|5XBE{?3aG}V7*um-v>Q6+Bk*n4u-~H zbN6W2a2%gOvniQvka-*9v?q0MYEyzx23YNuXx*ZFRtX1+4cpnzVeyOg3f$k*I41;1 zqaxtIjkoE1)+4XmBPTpIiw%#>W(N`>yCCj=7t9(29P6#L~h>q)G`0$^p1@6%h|42E?nu1qP@IJH@vt9}Z_BoRvR?urcV zTk}~@Qb=Y7`DQF42|-daDMUHgorogumrrKbv!a~ItjAXO9kd2hBa6#LdA|A_AoySj zZwzVi%_mW3jgf`2bmX4z|KV--txW9uHJJ)gURSkm#%^nJh`Zi5BMLps;ACGZtP@L>8y60~oDbf@YB=yah5+Wta!Pp0n=ZBN&>=bz9qMQxz$xd1E z>BtJd20^JnVxydC4w>adj#%^J^Yi6@Eum{vj@4ZEm!&BULODpxt z^Uen!fO@V`84-G*OZvF*G*%=PWpq_fa<+du%fzPO%+qWZJ%Ls4nwiH*)xb8dT<^RT zHugXkE7BhZ+El^ycx=mnvh;s@aXbr%2*{CH)YB0Ulq%x@;IEbnYl-iz!8 z);&+f`fR!6#*`v6qb;^DIM`F4f|5K9h6GXp*;V-K>1sku7tJCA6DQK2Gt)NGb`{nB zQ@a?21Q||r+-SXbBYTdb*S$!#+C96Ytp?L{mYxlas6ji;ryz~5wK3s*5_=#z-c#?B zbJEyTp^S(;V44zeU<*4YZjQ!Bf5_^qml$%`kgj0l+b<(NsNdzcX`Ufz-1{g6cm@4y zQ#(qI@BxlG3s^e+W}Dr|P$CN`to*<;Cy%|Mt_+mL6NM;8vc-L?f%VsK!o1!BJ0+wa z^6s7(!<$XCo!*%*yLdlqipVxj{@^toBXqx7-~}HNjaqwB^Eqc|g`_CP=`6Fa<@E;y#&8^F=Rs8!fR7l&wPW7MxtV?r?X3RhVhapd9_5o zkIiOhcD5q0TE)g{6IlsLdEHs7d!6kF=GyUDgJi_F&URR<3Zc2DvokbI+yHII9i;jz zJlWk)iHO!|(9HT0Skw|=D^ecQYGO-J9#v(UeSs$gf|23EhC zDCr-oRY4*#U1j(XW6&YQ2Nxtw0NzMURQW{-%8~PhL8*K|*nVY0> zN*m;Evn=yey_$7sw|n(eCOve|C3<0&dFy#`UDct5vdj#*M^}k{Xp(P^ALP%&;+rAL zTZj?6UMGPD{i#05dA|wulPJ2Xsjm3qrsK)CU3oW=R90#za+G>D<)5yVbIDxcWK~E~JR3pI+g`%@M2uHz8F^sRWEK7HtnCNbS;SaU8;~2A zN906t*7h~Np{*ao$!Q+zYZx6(IQJIx6{@^Ka~E_(9t?lx}X;AyE(r$7%i*}^w$60@MOETx1V#Y38fF} zAK#P2-7}`PqgU=f(Q~A9TxaP|_Z<^AzJZDJ#D19Fm=R*|X(Y1KSbyy#t!MrW&9~Zj zwQfMdAJ&Eff2KM^I53foDD>3^LzR)DBI^ zZ)`y^RuF6?csDu6Cjv6{c>kcVi??uL%Otj3+h6lt-8XOCjw@9Ly^O#kGN zLmH+Rsp?hZlmD%j?zde6Ere01{bB3}94IFH9~hhKc} znE|4%Zp@GYYH@mqi0;3PA|dKVlUI(nKDIDL=9B#rRymxK)Y{Q6lbmH%x6o&48ibf% zgPrp&EDsqRRkLdS4PA-Ufap*4%o-BoQSD=x8x#j^{3ax=LqjG**6v^>?;7uKND1af zxjM1NA$_FcNR4~`bvIIautu8apMP1lUe*;jC8 zWw*I@j?QvtnO+#3Q}qrlZ3lC+Lz{8dP9?Z|Td5UCx+ST$jH2sI4Cia)A&U7yt2ke# zy&gDSOZPZYS*5$(&fBuMHShDfaD{JvzB&aOi^i5N)Q(2>&-bwFQ%JPhT^|T*id1CO z2IN!AGmGt__cgqP8n3No@xQe;iA})!u^L68Kp$Sn*M}AIV69T@P{k6xFc(%(0kE99AGf z)CWw=EnP!Nb%CXj(`x_XBq;V764c{=NYDvx^#TWebB6@QM+kG9Z7H)YSqIM59zhnzt8}r~z`Rl`y+_zHMJ=@}w?~ooa05!|kEq+wz^=F*$6 zmquD*3lFkh+r4*$0=Vo&+_^RR?PlgVWo&FZQ8>OkYkQ@cPv~A95A_{HW@*_z+q|}T zZ)G{{aSS=^+LFLPCThQ6kUe3B7ZK8eutu7DVG-bc+Xj_o;_q|QA2dEX8%_es0 zHxK7;A2rcl%7t#rW3j5j8v(yCb|3a^d6uSUz<1r!GPl0t36z_d-tk5g?LF*kY5D1y ztD_YCL3;5_(A@CxWw0_k*2E{R%yBibIHLt!Rk6Irhg%P%c}uh#u^vpqe5NZ!&w3$F zL4C4~pE+v~*A)BZbM?=vGpQbqr@z|ZliO}{#|~7xEu;BM*grU>pw(3&(z{z7>orAk z4_O@&9*0<`fmI?>hWYWtjN>Uhb12h=iWM1zxlH3tyH6Iis=%jEi#c)gZjEQYkAeCC zA;i~!nQI(n@xj@lO7MMz8S14&Ez~ljGqD7GLtt=5M2Xt^VfuP$Z;K-T#uM|;&E#*W z2w^G>2}3J<4ZLB#`UUK`2!F$5_((HCBMQT|8n=%d{0BJOcj#W`TS(( zeZRERHbmC{uQu#&chtVjGC?I6FX^YNkVLFyMP_O%w80jq`T%R>bCNzO)uTB7kJ`Qt z>)^5dCUZXVQ#{eRMgq?jgEM(|d%%HVoTqx2-3M!knEOCOxkr@P7PP+^s_fS*-SKHD z7=}fWja9K|RKWfh;XUfvTy`VtONPmn{p*W(!)9wj(&4F<<(Y>mrbFuUX(j`kqGAvw zW#Y!Nm!wzldy^?(|3z8SMJI^JJTj5{os)$X`b7B9*ELutVNOIeY5qJoho(ag*ExriE3^P><99#)Ao{IhMOOy}3h1ORYhM zsUbgG6^6&_W4})OaX!UaAoG7ca`f`91|N*QLj$PmB?eKR6o`!hPvcckJRO;%8Immb z{C3-Sj{*+#;YJ}Edd5><0qLuH+isiGELI4Sx#l^Hj@6Iw-RQU4X2-h$x}JW%%e}YT z65HwLc3Y&~@os*Eyep?oDZsk}v!yxI6tmp`>m!7CVqd#k7O(MxM-J4s-S&Q4P!{&y zAZ{WAW=l-_&CqAoo^STPj&C8kleGdS!w!(I2uyQRe*4Z^RU}F&(M7f!$vuBUIh{|#|=JSnIxg&V64MSbWF3SiJeg9zx}KVi_*FpoX9igpOIr?c-` zg+PEQx*kN*Qbbc|?k&ejjJK8YSWY?A**4z|?@yon zd#iAuh(i#);djJoDQfq31d$>HA|QxEfFL@0ynppxM~|acPa}w*a0nt~*B?Zn-MIi6cYTl3&ge2H@PTrA-&WcGO)0`~tsNk+XI zE(%hHC?%#JrP>fg~XYQX-rY>ZU-h4B{VGg^mbFKN9PVfe7;w z*>$i(eYS`{z65XXW*v=yi1pJgp1DG2{KvC1{xh$E#(!v>NZa6u6U}I#dgB42Q3lo# zjUtUEyOfJYWkY+3kUw~>L1-Au?#2$MXUC#w4I;=4#A1Xw)7b$i(V=ZfW3k;6c&#V! zTB>;y+ko|Ro;5{&9ldtZ{46cx>BN37H+Z5f51rRD5L{2a$cf+{M_YtIaOrprenc_c zd-Z;p=X9=9{FBc6$2yQSzGHXdo;RBi7x^b0NRa|k(Nat8kz8cjImT{7gUA^dAx8L? z@GyTj|2-xmcE&_zO)6{*x0CF0q~A zVgO&)bzqn!Hk?TUYlSqv$;E7PI}zbwk1oOLaUjCbqtKuZDNSj}bgl+->*uhJbzxS$ z(D~hTCtAymNa;YUW6b`Jbh|V-&~V39Yc0>diix{d|75GbZ~xSZ7k^*haR(_);qcVRVhXTQ%gNWOcD4^36R-g2 z3jS&nUHw(C73n9Oo$FZtJMX1ExxAgmYl*40;c>(kGc@*`6*CvUe{3Pe8-+O?2tbML zt-m1vCALLRApk;y&$bDeGZYD+IDlB6RsY{8YUO{SsPFtw6gA@?P*e%Vy31BEP}CAz z9w$SoD0!)tiS>o`;;WTFU(VGeQ~w({>Ol@i6?fvOPvYw0CvbHUyf=pq-tEL0wsAP> zqk4*~e^mWgB4^QOn##@5&%_OUI#G3gB~}=Cp?-D$3sawt>mOt47wYNS7r>!UUbP*o z-(yUjS3C9@n7X6hqn-60+KH*d9zZOl7&^g-7lDqTx`M7|9Z0*HdtL>e7tYxbk5P6< zyzw!1PrWq9b9|l8as59)*^dLq0P|H_$Gs1n*vBmnPo{F)@k<9TQ|bKWuU7AHid+N3 z-rs> zy6Oz_|Ci`CbK|oK;}b!$Sq&RYUZ8OgCkDK4+pQQkz2i1B1y z2L?Y!9-$y2zVbYPwDIJK6AiurG~Xfl3px7+*)KqY zYwN#7Ztr;~j+2Xet?krhQ=Qi(H90WFBBuw=YfN(f@?6tnoN$xH743?Ioq#NwExE|{ zc+y6)+b%URabiTHC0jb8(f(Qq7s*W2it}l-*%4vuVhJVG3ZWSzsj#OU(TH|%G<4LT z`u`M7vU50T9wf5}@$G5 zm16TRb&i)qmO?vGXak2r_wPiZ#hoa$5J=&PPQAGR76t9YnNAdXYv&xMHZuKXBGytS2-&;4Y)zPl2&e_2B$iBV4gMxFf+7O?0-J*E?*j@bWC7 zX`op1P!4N$cu&eI4JX5?Phri89M()FU6`{7`>!0R^^#81T9`Atfg;-h2Pm=~HiXWq zWQ;tC?gC8O8<;fJFcTZ%Nc8ysH1y`4pzNF(B^)AsxpP$Rad`#pIMv>PLCt;6Oj(KI8f%{PPBQ2^L>C5g+A7lgb4LX z?y7d%pH7VWUBoKsntTy5cLlG;qyB^^4;>dqHmuvL(W@7*`ejMrMhenjUKg=&B5ut9GuHE)l8|6Ksx%^7x zeH#t}vxtg8mi!{@1TS1hvIW^B%9m!z4^2_=aIn~&WjqpUNMq?qE$=&Xvf0z821+)(auRD;VG)!*x?`t%SE|sd})eXubUBRLY)4*dzqn#^!n9Q zAkPfXA(=!Lzg$&or28J)Y+p6)UKf#8;Z}8%a*&amv(t8I5e(~9#q9}^xt2lNXbH^V z8))(JmeW?ctH#~A`-pPB*%0rfJxF)fbi-+HL=llTM;oC%V-;a%L_Efx?jwp<9p*T_ zp4x~+5o8UChG|E6v!V3|N%`y8SA8I3VshJUlIRE%3 zsh?b>$!7C3IN2a)T1XPkwk@{#gI|g@^74rSIgsHD(7rwFA!L4^WDl@Z!omnYXAUd4 zBEgYIQ`J7=>FVMjzWBN{T1Nyy0+D!KP@tHIeFP$zk2qLtkh%LAq#_(|EfNO{g4De8 zI}?7n&Non;B3L(w*!tXb$ zZeM5e=ORj6h$t~FRc!j_XMtVvsoZ?JpML`O^CzG`1JHVA;f{j>!rR9Gh%(?6yHz~1w+P*JwKYrQPMDvgw^<98p>2I^!iQF~I(TZZ6O-4^DcQr_nFIj?f zBZmPCC zoa;7sL|$eFgR5R2O=xbTpcJTCuz<5mT{&cQeeHJS*ih@vtm$E(Na%I!tojkn4Qp=eVGwYiUjdJ`5Wl)`==@)8J@Z|;Rn0@s#JTCiLP-_VlPKJF z%$Z9f0{fDx@ES%gh)W?-;->`vTI_LEQ+ev#aO}TQ*q5{6bG>3nSwKxNS0{O`YrYq9 zMnh|7CSB)ta;4}5IWGF1_?1D9`>-}T?t*+5gQFj7TT5)kkCvgg{(3~eJ!5llo6}!Q zZ2xLWMwVg{G7FS(zUgiT+UHDk0`>xo#t2=-86;TY@LjRZjFp=h)9QF~H^XF2vWBPk zCp%d$Gm#I+mEUw;$qXpA{lKmA1pBET*W+W<<2^*_OK^smqaL3i!^JV$B{q*1Ie9r$ z87oWYadp_o7OG5`qdO4;rZVVgi?)g0>8MW;o`G5AY-h18i`LH+gm@Cg-u&xc4h_nf z$hw)q#ShG!_lP&5S4LNivy2Ssb>9enoowF6%)o$jQipE-U;u1^SggN3cwrT8C!}d) zs`}MApRKt*^6*9NhRF37Mz+55$wXhxjgeYhi(~HN8O*q)WRZ~0y6=+sTe*2>R9j9Z z(K*J$c!*6ge0LL_ZL|)BkB%qhv%)w!=U5Bgj_+eUP`!^JLyZQGJO<7Ep{ z7SKq|8Qb|5zCx1KC7TCUdnwM`@yt^Yrsp{5(Tx-OswjIc_-6F6y2Uz-fBPZ{eCC)x zont1>^2`<^yFilL1tk@<(9iB@F;2BZIYj<;QnBq6m&FKNx{a4xV%yV3uRmkk(*9-= zkr&$**xyKUAy=htxQm!xt;3wxyBQ>UdVh)S-)%lyeYd$1$qrr8f>1gSlmmlw({+Cp zy}&X9{j&XYc>2I?CAN3ksEj%8DR1&aj)f}`=3;$y}F*TyrLSa4~XCe#u65U~IEg1&|f z$_FOVY&(bS3){VkD`rncYbNHhC)X~=99{&pKM7o3YRuuvBI@(2kZnbu;g~5RJm)*3 z#PB>@f&4(J!DqXxepL-lT#FiE?2%9NtXyi{3^PNM*!_q}->#hrLUr6+;a|6%737;W zfn>Huki$e!3EP1)yt|tP&}Y|WDXKh3ryxh9Pj8@e$h#+I1?Gm5n;(rMnKrw2nXD{6nKdGh z#4X2NPZ`mWbqa4>l%OUZf}IuIw;@;^U2%mVk6z>7cAOPt?Xiw!r-BD2lIqyXrB+w$++&8h z>S>-Ry^7Z+G_2ri>{I7~ei2mlz;UajdH_DTVb=Z|ey#%1)5EZ9@}QF=xTlRli4CoN zkx|+Yy^b?{uofwmOG5^y-;t>k?p9*tdmdt6L{v6};0zm~fhAZhN zECBHFP#H5LE{WJva2g-ytR-ot>PX|!Rw{wVEa7rqE+ji1=cnL_?m)Xvw$jyt7(cV% z6d7no55CA$k>mj#D=;wFNg;q7ZHEmaGGKQZq)u-!AqKd>62+dB{(%+vIcNb!tFID zIKCl4el9ZMs5Fmf1BpQ20*pY&SsSFP*zBQ)J%h2!#corqa@BTQaVs$%Gz)TF&<<+l zectM@zUo`BR`tN_jhuyDvXfzT^i%kvw{fbc-Z4g{Em*UR{jGx_U$oYXYUnyNQ{}D5 zPmGSQBsZ{YJq2sciq@DeR7XP(nC{l_AcIWLoC&;~zBn)I$u;R!WI;JrrF%G=3OVBS z^sbZjujy#-yw%bVySU@h#QpL^a)?;jYFqY*G7r(;CbkK(WEO5rOarVzR!*9$Tr7^Y z$hW2^bZMp9Rlf^61*n}z^Bdm8-*hde_m4qad&1U3KF=_^BGX>7+rnDuI;U)QtaIV5 zFLCSK!&VnEFX^h3$muHeB6@7qqbL#wiRWh*+bEX*Jh(PRu8VQzGnI~FTLiuv1!e)- zo8LeNneJ}-o+!T=(j>(D#THisWFP(7PvMdNz9oSj$8NIxE)yB{vy?M-4okX=^x_70 zXsR6Ow{l3y^C9S=>N>MSTMWX{>@o`-VVTKxWL-%y1KV8*!tLjY>gND6` z`tWu*`pzFV#lKn|>-L90r-^BoS(;DnK-Zj!z|?uIu7>4YzaSn(`02Dwk8pkh2JC}4 z&hGPz|L?V`TRdH_+zsX6J>(e**%4$&bShXTd4@p*dIJ6QV}s*Y`r9BP_;`QAK!ptW zX{u!`>%!^O*TK=i5UN4f0P`W$?^~+5z7^+qI{WrDZvKF0%;JF+kyK5xQfa_E!0sWb zJ_%AGY@w&8@^Y!g#wbf{;wCC3XKZcF8cvR`x2QRLN%9fUbLaqud-9zYhqg?@bB9;+ z3`4M2U1aD7yG>*rf?VW5gtlOa{N>O|>|AF%)R2dnA@thcpfRmg_bpUnNqBGAN`p8% zsMz)wMT1T4maeecWf{t-7NgYQs-NCKZ460%60-KB`J-4^8eGpOKw_~rVn$WMHosyy zfw|JpxeC=cc^F&?)g5m7sr7U&$*Sn8F}dC$b@eTQJB(H-B*#_H%S(o*YPWT5!8&g0 zRzDo;xUAj{wz1vzG0Jh%$51?(&@p>#Yfzh{@#s(NzgU*_$S6Mgdh|%++tGuJsW``k z@>-Da5GSW@RM|tFhg3hFx*6SMYnub z5Kb|uCvg^=ZOSuo7JBC3)R(DD^TsqPpWsOR8$M;T?R@6_;87sO3q4`?x*H40St+>N zBfX709ZsK8@Keuf(@#an1rg!op>5YA^IQ^n7hF;ItxS(E<6rNZLm2Ltt*|5iGA3wO zYwN9~m#Z;Jmru?vq+BBIT6$iGgWGx;D+If>ClRNC`#8c+iIY3}g$f3WUr+~&lhqG{ z28k2BbYmzTQ7#=L@P&J! zJh3F!9uWkuQWzWT9^{4+V}nI`c<03$gyrCOP7%5qnOMHI&T7EDJozuyaCtTABmoBq z6JZB8Iit{|@>3~}>cDy^d!zZNUz!((o%xebRf38*5=eT$`VS#-VEjI*dq)TRt%B)i zw*}e#0+R9!BUF0$;1?G^H3ME!t>v%>dKIlt(`-?cU?E}6)?6E zd9ZFQ=58qRCYT*jYX^#Ft8;=9HNk=alpd#Mb$sn0!AS8ptnf#Q;>}SfX&_nR6^M}t zl>1c;WwWryvZJ=^z|%J;;j=O|tQ)UtzCkdIs@vk=kCAFDTSb`pAqe3m1cL(Ezkhrkg8?)rM-J(|R{N!I&BauZ~{tYENP#wS27$ zsj#||>sF6M><=aRQ;7n+v+bGeN#r)u>w2`iK%c9@Kgv%fisN(n+9Qym$o?*p*LYa5 zz;8lPLW&W3Voto!#lRlcq_8tW3UwpTlT@gP_ zEj*)UGk^Fcew*rkSu#5djPs0f2FvR|2Q1#q@Q_qG8yUmn*~otiRpkA^JG)JFtK9K! zE331*r}5J$&seU^$CN|-2Ke)^W^5~6e0ZBf~bTU42&7;ttnN+r%M zqk9ADzK35L+~CTSiYkjWt)x^o&5ZG#6q zo0X-GVIQ-=<2+{Q6z@k4Ia$W4Q~!XRG#+IlLdXj6I z=KHGYS%pDH9ZR<2{5oiMr3q(i?pU09G?kvT%nTTiN_zVlgOawh0~9zrK`Mp)I9w~$ z2AP?Cw4WG5xNTteSbv!>ndLOH}dZ>mxsV1pB;O6jFVG7a3;%(Ac7FR z(CDiZ>Ne@Zhz4xihu1myw)>^2WO_C|t%Ge_3%2d4nkc%nc>BRuNq_o{+j#H zwywn`lyZ0XOKY*cX+ONK7xrhnh3t^of(9hvHRwZL*dRuM(fa@z+!HN{o|veYFkfN6H!9bd>4^ zsvnYGF(1ujy`Xaq0%fT$c(wK52-6kLLaC8-=bM=Ug8pBrkSs_dbn&oK zUk7j2eG~G;74)f3%32ayG@a!~tXCUkiL4%6`dipqNM5c}w z?F4wil3`!9f-{kxdy$C~MwYQ_F>_mBjWdyaoO{CzYme?z4rKAG8F4Ch2y_i;)Hc!c z3wjwzWSDVC2I=l*R_LaO$hF`*9B@?SfBl`AyK%0{ZY_!avtn18Ud2?p_xjBw$Gz>g zBZz3;F+FB}i)Wi)g)v{17Y#{gdX#mZm-8E9dwxW$xDM7rFL;6-%!M*1bD_XQV_{$} zR8!tUIkY{sKfqVmd0q|!w!-vN1&dm22V0uK)z)G=;N&Q*M%i77PtwYR!C=AzzjZG$ zctnLpb9m^~Xeg0`IMKk%C;+Rpd(wR?-6>&~Gy6ZD8V)Cn$my?*CSVcT^XtLTaKH2(JY&mVj(kO=S+;pK%_(=mah4KISfNf&vX=J}W2UYmE| zk2db?bjzAo0Na)LK~cc#roZk|G}>d5G6^=eq@IPaU7>Z}dgKqrXpn;&mV2 z>4J%50cbkuYi(B|nTvP&O2^+FpXuN9JNo(kCte%zcR#_ZI@Od3;r+sl&-c zVk4xbwe``XM^JL*ciTht?TW3BW);~df8Ktm%zo8s-+kSlS=?TGulioWKb!6SwzubAwvXM{e%fqbbhv%o{`PaV z_QZYd3A?I&J%^z|hB*Z;B~pLqVA``hoo z{PK(Gx~aaQ!QSwl{rqD4ovV$1J-B%B;%`S%%gX*^ul&qj^R@kquFdwl{nC5(>p3ka zUbJ6XX}@*B-ulq~;Fi7lp8dDdOD78M-Mjbj;ln#$FQ_~Es{Pcg{rmU-^wUp8MMd9y z^UX)O+dlsIPMnyWoIG{v)alcw&zw1P)~s1`=FEBN zrI!{gSg>f(qV)9iH{X2oop;`O@4fdxVYhPS%C&3PZrHHl!w)|!EiJWLt+#LAzJLGz zpZ6cwe=^vA{>t9oX218d{ip5rYa3dA+G#ttr0LZBJ4fd=H#gm@JX!glt96xEDz2Zc z`>FWLFTbq6{AojNmGOAi3opFz5ew^@H#I^;`Y@zwSM_UG|{v z(wVP!pFjQ8e?EWtOwrcsKmBxVfBLuI9QuCWTccK%9^AEh$g=W`oG;cE9R23nuix!m z62IbR=GJ|g+xCxLeQnLQU1L`LsNHzF&-=efGk*X0RE_H!ZRB-3v)Dd*XS>&1wt%H= zv76dcKWp!{s_prm_9;8hm)!n%yFPV$)vH;DSAJD9W!;5t?^!?lWTS5L*B|EY zaLoP)yT^otDaqNcTiwAd}T_aH>ZXa`K*ZB?7 zxCK=g5AFW`!*KQbkg-L3F6kqa56rk!wD+n^nKs{1t6jZor#;FWFwb@0Z>}3NhYn0T z`Dx^!@J*v@bt!v8Cr%!G`|9sA3)SQ0@v<{#e>o(bAe#_)?T?zhJC~PNN(MBC4-g#A>3Mc{L2OCG_qSaShSVJY;zUvJhR~lI zWBLC%`CDwU-_H+6UFq_{XvuGzrtJ7LSNLwBI$mG0_K#owZQZ`7*}9?mFU#SJch7!$ zs`cU0x%nCP(92gw+%K=+*-JA%&pvMtqZz;S?rW=q-rb(*OUOp6d4)2s(Jf$TTjqwa z_wVnlSsn6l+0L-zZ3X;*4{{q#-b;nA@g$K=X0^}Qj5FVF?0@x^%f>#t$T^Yf{yqN6 zc-LO_S(<>f`s^_;yfKp`UERX){gi}knKU^*cpQIX-Wd`!b?hj8j0?sS;|d>$^bP_{ zh4cjsn3#N1u684t2U7@-$6Y{GH!g@JZUl>kFo68JpC6x9a5(7SjfbLz#p}1e)Qbol zWx=B-y`{KR#9bOhlD3>E`f+>a3gPodZl&JdFyalN_w>BT-r-!qD2-kXkO|Kw!f=wj z@bKt=bJYxhs*+EmN)T@rq9zPblPWa&z3I?7WF7NOmhI7)376y=YXW z8NONJnlh&UgY%*1md8v{x;t)iK1qo%BW*%g^3Bp9>7~%2M94@MoXOfLPOQAreY-F- zb(5B19yeMFl+S~!8>m(f-k5(abQlqKxp2U=E5ajY*4>>+V-BTy$i9wTaF+>xs!8-V z`k*lK+fvh>gzSLC?7RE<+Rt4w*Tl$=#rxFnJij3(-#GwWivr>A;KWz18yFHlzwh;r zR#e{F?<+K~-xwfK94q^C)y{+sF=|AZjWd%d`dcH^Gu^-J8pJ{>oyW%gHHhc3w;P6sahd_Yuw(C)zp z=X{^ZJ(Lr%0N70u?xD!!z(Xhea;)#Q)0(0+uY{Ag9)6sbHtNvq4I#ZIV~6aDU1vY! zxhxA2IeV3pKz{@ceYpGk(fbEy?Krilvawt}I=x`%yV=9f=tgDl+BlB)oo4<0aU0eL zc)ENU-tFKt@AVPMt{uY3z*~Zck8^p^^jJVF>$FPT4m%8^{**&AKl zw8y$130#-6ah*#_dYVtBas9f;-~jOxvg8Mp&yOo+0IkfJtnguP-FDp-J$T}d(|teI z?VHG)y&33!;md`G-<}wDdj9n3YeORclw@khX%2*3%F;TCc(ew;UX&-oj1uZ-8~*6;D|O5VJCH{s7IyH|bx;fR&Y;QNPMJ!QRz%Vu=+51*iA zzN9A#qAeRtuH|{4AaM2HUHZ+gb=MCsR!_-oneDw})Z(T{lkUu+x*RfMXo<4nl3!o{ z5bp!s$_}0XVa1b@?+aMVQP@Co4f>z}3Y^?DRX*HX^HFL{#)z}udqoUgGV92Zvg0NR z*&MSV_k`-Ye&Z%#^812v)!s9Xap#287rwuvr~%}jvnbc{^434+1s@Dh_FuYljU;pE z(piazbZ7ca8nrp(=#12+2KT<3{ktrmkyrF|S9R-b;l1)XT&3JhzaC!Wo#+wp>FF}{ znu7)3EZQ>nh>qE9zObo(WJ1O2S1SXPdk=hJc+;VVMB;3rvs#MIYF+!)QJApw&{?<7 z6Fgr0cVidLR0tR(BEHuxW2)!BW;K=v2d(oFukrJIYsNaCRL2N9OOiWF>JKg9=qsV8 zSMtu1b)WWax!Jw<+N(bY{_8vOv9hw||A~9ArR>m+HGfR=+Uz^zfaV=#_+xeB3lFA4 z6h2HFRn)sQaLFwaIpbp1&jUx3=|_lJwF{c+e)lQgU;X)`n5gNR)Z-I(X{7z<9?ZJv zEQp(Gz9hm~qakF)^EZx+O&;*xU0RTY4C{Jz`jPPa8o5U@6j;i>%|8c@A0QYoC32En zJnhqQmm-H0&ASA^{fQax3umZ9u$c4>_ZxB!FKW5TOucxprliM!>B?!QUAwl;e^@qT z?wUUm`>yebeqm**d%1t&r}AS&G;@J0Y@ldsiJNx;^ ztR3^3Np)fCB8$v5{_P37O9H}|g*qp5947P4`F%-d z7oKmF-|<_1;yx>dU6$4K%6aZh58q=`%XZE2h`DyG=IqzMZP>HXeZ+w(sf6ozZVvhb zYI3L+94jf*%%1>hcUv{n#G7}~FFLWHT)k#ucy@qWif&=Qx*rBExqqvC&I|qOE^IpM zTp>9za1??+h0t$WMxAy!`h{M{sle|%yL!g-&ogfAS%uNN)$hHFrqm4|#%PTfBb*B% zU3q&407Z7_$G*fRSNLaxdr|bPyN7&>5AIaTW2Q@{%}$u;A>DG!^zy|+bIz@e8$RI9 zn4Hve{+%6y#WauvBko3ZKrg6-rn))bf3)b~&!QPZ?GHO;F>-e0&R;JNSuJ%*oU*fU z+Jz5e-X)!@DxdWBA~dt27w)zbHz>9A@SXC>>m|I2u-cZ77mP|9m0i1DT@tz=AkeRNK;l2A?U^CEzc=9^x^6QQ{O47opUB&^#b>WpUy76qIxdu z*wo3sM7eC-u5P8r<q z;){XL#aHE{%^Az4Nw*abFblGN;pd1Oi?UC* zF_D?urJ02*ZA@pcbNv>Cev9htw~66Im9WPzLQqg}c8$xbuFJ3QntfijMmVZ!aMq+v z>-jT|OQudj#%oAdp7e$64dJTf)soNG?i-u9ytkWlfhs|i?eCQ$$$Nb<*&V?Dc-*8~ zUj5mCHLtk04lXeI?&|D<>Jt#X%7NIoXL@Y`;AK-l zO2p8!3v6E=-ZZ*AVBw*;by=sEr?jmq6ZcE`HrQ~{fB3{zKW3x6e>t9)zcZRU0 zh5Pm?`z+6!$S&0nXt?xAa?Yk5lcfvS^jT?YKbk%0w-U*`>pk8$`DbheZpa%P%rJgFMB61hfWK|r zJF~m=n%L*eTG`^E=fBUr^jyUpOG;rtbCYLD#z{to2%0bGKf(XZ7#{U5&HL z#zu}gbJgWSm-tQJc}_)no?Z2gZumEvekr?% zl)t(5_!~d^FId%U+rpM^X`A0l8nn1&qD#aLq8wIVDf?6X%id{$d#a|JcZPZ`3k%|S(?`MIk<9D zzd4(83utGr={}cs_LcvP4&w_W&XJz|Z)ul%gbvQ6J)RKIU7WQlOtqZ|+@I@K;}Z7X zP0g;ru}zsgNl#(T=zszyyl&$Hr-_QwqDgNtf?eIHZ|77GS?1XJ%YBBXyg;2gvOQwK zs6)Hlwd#NoRa4W;HB`){W3tD_Z4NPfq3f4<$tNm#wckS1*`UNVKh8LkzH_d-|ENjF z`!C#CV)=1d$qOg4V)tfE$Wp(o96mJMJ*m%>?FTjGye_3LrMShPDzB~oF}3$zzgF$L&D}Fnmyqm>4eQx3N64f{3TvC_! z$uAI)hCk!AqrKk=I9`9NDD>l(bzZ-fODnY+q2h;^KN3}z?H_&Tt+JAR^GU%FwtPhK zpjR(^Y$$kt?MF@IEAJ16gqd4*zE-{A=LuHn=j-17L-zHC3~TP(HE` zCaU2XB_hwI7i(556=x=8elT}brT5a#(Rk}#O@hyJ1#s$?3Nn1j5r0AbB&W`Cg(HT+ z2*6;(aD(B^dD!v96&`j*L3xBmIi)!MjeS99HwX+73sMgzcxbOG`v}sPg9#H#9c|mf}3OwG;Qt*RK11WsD?Z<)yU>eUBH8r_U`bk&a6p z;M!*zb9l8fdyOFWwVGsY*@g`TA?cGE#+LIZZtJt~f@xLwm-C+QeR6Pp%;hZc7cJd| zQzOWk72Zc8w`XZ;mu={Ked*`6|BtdK0chgrdXr7ENeDSO19F5@M8JqhqoM=|3WydJ zE%gkDii$QUD)k~4H!3Q%cq5|XQAI_I_6nEcjn=QlqwOkMwY7@1)wHGNf3q8q`uTtV z|LtaX-@ci7^RAhBJDW+;Y7Z54q`AE?A4=b7_^S9`SAE^wuLrz)Fr+nOaE!mRWb^bz z>$5W2_!B-JTbJ}=?iJ3IBmSf12XB8}qVM$8Qs{G*iD^^=*p74t4#`%ANSodwr95tIL*YMf<#R zwBps}Nt1Zu=p6A#t3uKDH~*o~K9oXDltSBON?vqqahOjX*Q==n$Ag9??^dr#y%dy| zD3!H)IoeLH$&5;B8IbBd%EMu#@1Byru{GS#R=?_ty2kqIFx9LCiQiz`!!n1BsT}vg zQvzJVQ~@y|W7382je?f)=+J_}69X>Bo_FfM`anwlK+~@BVY&RU@RMpRpx-AE>u<@% zP183f{pw!h-M?wJfp=Q{nLOrjGd@i`nM=CgYyBdG^W{bF_7txqnG}w{YCBW7|kdfR^K?|^sK%?3%8#7 zKzA@+B>bj&#j-1>n`TZ;tZEx&mh-RvytZ1CX!haHFj_j!kgh>@S0#H_oGHoCMXJ&Y z+^3nJc}6iZmXZ38+3H45^PTZ!V!^n$GGj_tDl?kV)mESkxaX9Huj;B)$KZ_0s$wG5 zfeyNGc+K^X?!*>7LaAYz0CzxhL^`8bG;~`=XJxHlzFk&)dd9g>ql3FgX6Qv_$;M#L z0rT(UQd{-J)~q3??w;Gwm%T#1!F7&3&{NUu&(m8Qr-z~QHqvKM% zoP`q=i(NvMa(`w?${o8!dGf>dxOC7B{kh^D1#Ls8{>$xJ9S{8Gz2`}j9RPW_soKfcUu7{LNnyt%<`Tp;Sdw#pF1aA5Q8e?eHCHD4N zo4y-_RW*%M5AwZreDJ+bcRoA7z44BDX2IFWgO?Nh>Xo;IGln?_w5I<4h*Lc1`jgL} zM?23yD$31_-m~%#|GQs*<-kPUN%Xa+8HyPz#o^}X9iOiMejVfQKU(@u$I^lv@)znh zi#bs%(szBoxbNdyT+AJjaVPH)qpZa<X>fcky1xCQPm#&D#aYo3MPb zkDWkyG%dDB63i5jjFn;~QpZV|;fG+(Ks-;Cb+Rxmj^BqhzFPmVdW=4C%c-n&xt#?Od4Y$VOGU+IPc5 zUoXetZ7D5^aOKDoVq+|icc<(-BNp1K^3^PCRpm;&3;Q1D%+L=`Pz5#IeWr9O2_1TJ zo1OB^7uzI$v+Iq6SW(iv-)kR7r?kdwDtNY_(Rd{FYw>&HySFn3tA5zKCf2xSSo;EF zfBhY&xT&d&Z(ov*oFVjTpKTnzCCRy-Rj+g`Jt;Cc%-*x|!*B0?9n<{l9=$>HQ(n+X9vJDG!^WS zcMCklzop(S3W%0_htR>!%6s-$#Le|n8T#oDdX-M2v&c)$%|Us~E8j^rM;jArGuUNrfR}fb1Q*P0ODn3~D=2VWB~`W; zI|WwDKWxvO-?ZCylDJ6P64W4IF|KFG;u2JjjduFNQDtQ&$Ns)fSzG1W<0W{3cx;X| z%ivccnVfaIGAkxEP<*iSXE`Qso;rDGom*DC3Y+f}`o8K$>YCYWr$q!s-^h-M`UJ0@ z)S8~~^LfF7Plf)&yuSazmMI%w5%6nld+B=npy=&G9Urw18}(D;7b_M$!oIJY=ko6N zYo2e*Y2A2a@$|cE!#X>1&n@&8H4J#$ z>Zb==M>IB&CIMFvI8~v+w0evq-S{xM17cL;`|^Ljq34Y$zU(kNfIEpHSu^h1+QN4_b$YDmaY#$MPkW2MI}E=MPx$O= zD)OAbO4_~qPRYB9s+RWBnNv#{2j;D;Sf4QRc!=`>^W!0dTLJ_{WiQ%4^qRj8s|*Nw ze6uY2>f!$OkMEqWEbnO9IHN0c@2SP|7Q8*{dH&EP!_KuxZ*RPPX7f{Woo}>Ao?lsU z<1lVE|JpKY^8L<^3p*{xjLg|7*#YK(ZR;!+{MkO->0fo271&b+RJ7WS*P4>R)L# znr#xv1!cH?>`^%bYMl_-y~tJ8=s1U^VQPpD^F+h^q-yn z{pW3C+)Sb3_Zmj5;xBh_F1){PsUgzA-{oP;1=H`Gzp6#uvyGlu5FZrfV^vfn@;`Nh zz!&^4PSeaa2&4(g(kytL;yhe^JEv^-*%DD?8VkF#y>%mt5jM;rk6RUUS-+hX)#kF% zDVTdQeWbw`IXA2%B$93c>%RWK6BAC(E{>#=Bnw;~95(&8?t)HqL$iH9h&_(H6VX(jgw|^{3-@zWUs_HN5@!r;;za)$4Tg6pF^nYM}~ZRA5)lGANTU7WVB;9e6E z&%KxD?35OFhp^{6?D8zJdLjXTy%xlSX(V5m>_?vHf)rdC#gPbM+!Hr9a6P06LEMHr z%_UNo@vW`v$r4xQP0@uHSs`zU;Ev*xH*AR>4EXhys?IfG2!nwXh(n4H&}Wg8zQJ+eha1Bc#&@Fnw;!GI!-%6SLmb&OD5djqADgYuA6}VxL)iE458t`^;kx%@ zzWP%7WawS-N<+yoJZRcQuTjoJ&2vZ{*T1H0*+s$ioyt{Ghh0ihXq)Uq_TT^(uB=Qd zb7nsC^2TL$My6Ph*_zn>1n-Uoabd2_AHFV*ls$}AwhjYjE97{dK@cI|mZ34K41xfv z*^dqR5RcCgo35lwr zm7G)HKQ4b!Ki^nh14J7xVf&Br);oo;#(35F7B@If9yfAYYF@(iyu`9%x6txJ#}NA| zZg!`*Px;O<{a%QFym}+4zx&5-Q{&s_7JT6@_=L=8m1&o;eqd;dANtDI6^)I4*8cvz z2Wy+gPI~h2arND`W9H>#N45K;SGe9^bg$^MPsyU;EBibjb96w=clGSx&%Yb?OT+Bu zVL=-f)N&U6&|ni<4AV>(B4-F^tM7b2YM18|znjwZ=lfPj!#g{Ee)jzw+o-{PKVSCH z-ha%N;n5G@5o0`F1}K}KP7P*w$b(<@C4J~_)?E-$gPF}E@pQGJ=;Wh;=5Ar z7J3P<7YN;ZUdq8!JNmy-e|Xh~lpaqh9leoty{Ii?vhu{XU-l8xZ)Ba)E64fhZQWz? zS(wr{N-RyBe6ei&p3!!Vn^d}MRUGfA3##P-Lp0}ic@R^&?3O0!n0XAQz+t3Hw%%_N z%W>+}$FeJhjrC6cE|6@P4)a$ziY*$b1?$uUP(Z~yGm4|Fs1HkR-9)$ziKqcz{plwXOixp?@R^68!_Y~knxtK=I^XCWVKs|jpzm)pzRdaf-Z5)j7H&~1voNe8{D*1R zLB@nC}aln?_YiQ+99tWm#5Z+2W`dpYQmyvi>=qlbE$) z&WeJQzh@gU%wIt1@qvQVF1Li80S6ZMkHiE{_aKRriMmbs*&i*CVx_X zaOuH4s(R9kI?5z;g*?xyVcno4njlm&Q-Hdp_T9KEJxGVb{p*?mib;KZ&u#DpvgG zF+-pEe7!Gecf$6B69@jaE7?<)qh0b7#xhl^R~GKcPLtH~b9%Bg8T zH0bzMKI4M2dVeRAnOe8((!$TaWn446+txhFx%1q(<8 zJgHxqxntO!7rq^g%Y))q>pqZ(^eId7siw2G6yE-b7UVPHV!Fj7V6cK$tF{n-flF~l zDT`1=>sqUQ%f=;aIj>BPzZuYP{61)-%hxe}{0cJDZZSiu65-j5r7^fmx4VK6b`XE~A#1Ut)qU5d&)t!cz+C^+mov%n3uR4@o`0Y7 z^fSEqgN#0?&PC@`LhMp`U;9sk*Zi{lE3!7{wm=;xnmoA8b$ATb+Hn-oc)-bp zasq|&e0~(L9G505qn*IDGjaQcgNWs?$Oi#-v&&BDo-gACeD*_U{mQWeIN~#R!WWdX z7}l;sh=|#MnvtT1C`XwPvDP$o1x;)+YuwKAi%TeCwdNtr3C)cB!57_VV(%SxUl;n0 z#$OmpON>^91qDK9Af!5jex?FVobSl+mU}+pB+5S%KAD`y*bs)*Bgs!VSB3KLIsVq47tcze*E6O=;3FM73xz7U0NaZgBYimgh$?Bwny zt#qj^n!0U_K%LlvIp^ zG#nG3+sRxZcCGxi!@k<@y^sR~O=8Cy*8HG({z>d{hnQ2szUFS)JLuRf;-q5h$?D^K z7Btyyaa{&tj=6P`8(2E;rfVaMld|C?JGHpU^klGtElJ*J&-<_|UUjzt`)c(8@=yCu zqRz%`O$>kd$FH%5z{AlCUQAq&bf|&b5X}5^;S~3@Go?jguz26uuXabq*JorQhf;(m z2Qr+lY#GdIDv#CWtNpy@>h8H{XNz9cH>~F{y1$HJ)r#{QTEUqtSv5;i?yAZkGR3G- zV}av@C&^>gY1o{>lj}6cnu{Hs@hK|aY&o`@5nPzE-#hl4y(4RiEN$-5&Bbdb<{zqQ zPpfEAPgS4Rj31}Aal8cbd5`CRy?5-OK-P=wxbcVN6S+1r!EBq_A=}x7#V6Gze)Dgg zc64}eVM2YQ=4RghaBSlj?{4*dobhSPfc=-QY$Jll~?_DFKQf4e3to1Ug+Lni#oqnlGT~35bO2bVKsm5YK)|nMYvSf=ojV}0) zTu(1X+w#;wm1CmpGsd}9+q)m)g=Yjx97=t^&3Dmf)wbVXJV)y~aA@hLw%rZ~igEz= zc~enL9Lw-;6;}l$6bD5sV1S;JC;&yJgWbkd2{P_9w%PR?oy^UQQdKlyjTLoC3t?yPx;|=^d|I&ayo(qcP%Imue>&9mlsdK5=_vZ~C=C@)`fzP+=Hiu?# zZ<_wvBWQ@If9A1k5P8Y@{sjX59(1tmb(3?1cj4$&p|!~=WJ<02(xw2(y;6Qdfe7ag zOYYdkS6!Cbh1EC5mN@mVatLfzscmA$z}i*$V;}o|6O0mX-wd^lcfWTyiZF7fq@OD6 zg(_^;%rj17D{92^j_);nlsIDiz~<{e7H?w||HgX%BXx<_yB{vi%lWlm)zS1_4uUf7 zFHKHCm;>v_Z|2*cVpLr}5&voB*IxuTb7XaOPtMN9pEIBQRbG3`DNy{u^urzM z4$%y5)y?mjZGpz-1j<0u;8w>8NU9hVRUnL)jI2#Tj${bdb&(*VM1j|FGCUquR6?FGzLE$=G945w@xhM`{)_Op20%@ditkqunGg-tP1+qr8# z%hn$MV)it-TWw*cnS@A7WVI-2)FtCy8%)l=H&z+hts@v#h)<|9OMvZoGy zene6Y zE4yJ&K(u!-dwP0wUPeMOp6sx>UEuR^G=4bk_Z#EOzCMcYs_QB`Sy|%G5Nuy?u*&Dw zN&E+nyuZ_to7l9!POiFUr=0M4{O*v=B_DCIb(om9w|)2f$-0Ss`y?N|_p2#p3-2^J zSF@RasDIE)--^P!W3O-u#zoZKth6%@Cf80}u1WdDpcje`MRA{L)h!aQ;HQCHyiYsSi(=EtbF>M}{vYx@YbZ9_!P(dvP_^GRXzQ{J_6X%TVT2hBg-HE={N z>wE3%&IpbF(lL z_n7}5ufAdBJWF}ZX>aoHGDUooSL0Q|Dg2$W>V-hQ`$6;HIt(kDME6ZNayao@REHae z3`^%;wTBlRETlT`sQ#1d0$Q8lYX?N0>zEcS3d=urcj{Hv_TL}QPdYSl&QeMAdhSx`&$`^N!}sgTG`DvX1(hS? z3j0MlHesagiid3*yp1U#M=EB0hz0e{)Vl1RBkVIEhw*u^SNlj(@;T!-@l>C-Gru~s z{#7yL`OH76hOsVaH;<5wt`47b{f&eeNlXq9^B;yIENXcEtJ%Z~6yN-GLMtP43U8r)|Q~XhYho|?J@pfrv z119iKU00Y=M$QbL#GMdYo?)9Ra6XY9s$yR)&`ZN@Zv6HWrV_CCRNwX9_bnsHi7nlf z+;*cNX=nDTgUp|Hotm?vW=a0H{oAp|KqpXhR|%I9Mvi+w^f&M02L7T<1km^4!>3!JL8%U(Ke zUx~l(M?zKh!1bo;@x%dfxU!oV#@K{P+xKPz)kX>7fCVU2#^8UKR7WrrlvnnCru z{bp9*K66-^do z?qaSVgxL}tnMzezoF816bWU1%qnOcuQ`kV(qS!(C4C5!o*D89+mbgp(eD!(eM>V`l7sOe%+YW|9V){R(l;| zguUYG*>bJ@0M12;^t**0zhmq3=$8%8N~X(PR$(HKrliD0rU4HtH?O^_xZ11NM-8u6 z2pRywkn%Bef&I*nN=0?e!inm zCN(_Vr5fqPo;c)QT1U%l7S3IK^=`al-#)WK-%pmCY1$L)zdmAo}REdS-MmeVu;nl!clxZUKb)E4Hj z%&hnc2XlVl%y(7JyLTW84@>p__O86pE^pj#H}x0N+fwZNF7V1Y(Ck0W>!jx4V9oe| zMShFE&ls`*J9}*ST}P+Ce5(9cgUIQ(s7?#F);OsiE-^6n?B+AtvX*9 zv8r?Xn&~WqSIVQ(Es=Ul+lOZ6(BlK=UvB5wVSk$J;(K1WLhF;ftC#3)V*}$6E151vK_@bhoEx}?9%g6kjl_hT;ooW}H zF)n3f@s!9=PVnYg+FI@k?m<`6k)+ep^Y)8Rp9;hRh>jg!r0lLdf10sHd@TC*`D0(T z+N8OBy=QdwfVPH;oc`4^&{x;ze;d9dcb;DUjX?VOmwlDfWOKO(hCF*|+%X7$k^HU@ z3vHpjjEcxmZ1Lv9Av{Hcvd(KA3z4$KrVWn76q&bCuG|=aPu7eZZxqMrf~P75JzO7` z5H*3z3vAv~S^NwVx{uQSb%YkCKQ^i9}cmppKwsoAN374HsT zAZv{Anv!|{C%Ng!QT7CmO|3)ld(LAnp1yx`W^nr{FMGcr{X6%*+nX~bF|j`V@YUi4 zpPo#K^4lk`j-T?IY4gU=7T1-cV`G*N+JC=pS-^xp{?~=Qpw_ zLo#_?vLc~h=$<1Vc;&n(d=#oKupPiS^JhlW=j6_#(ZVzFUpgw?2G8fN&AM<_5cN*v zkAK>j2Fb=qr+zs))B5mC1rV?G^FzNIPQ&}Bj2AYdh$_(>{#+y=JxXYTRx3Des$Za z7gr~A#)%IHh|^Bpd?0hXo^ZeV#iG5kkd_RNIX*ay9=@pF`L)b1UdzmLk4|o4JH(9M zBJ&M+{9cJ+u#mm=VP>8wAciA2r6?<`HC$dUP^axFE{`4?C%m_4gKU>8URZxGGz%Vw zSQ1|P__!aN%a|oogPM;&Q2HwgsVjVi*M1*st1YIrKiJ@h8(n@6>}=D{nt4uWBioc2 zb$se~cC7vrpD3f5+xINt2Wgd<>fQm(rip&<$E@c4^m{`3?uOKqqPU3m<_^`C;g=R= zCuBT5Ut{mQWN<+1!KBZ^x7w)^oiNAfNgV%?3%-3^z!%KtJm zG2(ifsW>{8E9sXLm)4N#zB6psv1VY;m2myJCSB>}XwMEQif_qN`i)&AJmi%~%Gc!& z<-6wuC~IBAdHtph#S*l$-KQO@OepjF)^JI>YH&(=YrFnZ?GDG9=#*NI`GovxPWC4< zosnES?W*xn@`1}-ru?@Pa~sq?AG?OP3+9Yf`HM!L+pjNcGuiKM-qzlHH0olsy?f^9 z6E`O51BI(>XTM+h(KlIFei9GbJGz=N!}K^s^?NfGp2`1nSFvACL-_mkKmOs~C(czr z&saKq*BsO4;n!x`^qxpUe(|O<#^iVDtExCvF_)NbZd_&3nxaDPm`r^fY75nMvWJbE zRr)c70?pC%V)(}HNW0`aht%aCO{!6>|FA7@r0(*_Me7@9c}J=2oE>M4zy9#zY`nNM z$h&oJLkwOkRHvO#S7Gmb=9+x8W_PlcZ-e)Svuo>yk3&2J0JYzG}(p|`)j_=V9`KUZ7pcx+VV4*Qdg z6ss}@qZseCGOqPB5_rw&(iUA=Ig8-IH+6jO4oH>cNhERU=ddXDdtrkDN-t;~V_1P% zX|-otbtU18yi^%8n>R|?t{n`^iqt)6Hb z&BOfWM@bpA%iSvil-G~q0^7KvrP{Opj%Q!Ae#l)gO$Q^u{cA><*Y2_Ji9_3io?Q8u z6ZPu0OV;{xg;Vvx3rE*_-H%m?5|$ollJu(EBYPSEEDCXjD1-^iK`6Cdx4?|ej82!$v&T-0u=}a~#)`eM zUQyHbCeBU0v%xARtl>e<;n}l>3a#)1{tTR31I6_Xq|*4P?Z#ix&q{`iF#W2555~Gj zFTNGfAPcBHqjbDbIDEy(_)Yu`a;pspdU0O&8mb}GvO~lm_iJ8t<=E5)Q)TWdtq zj1zBNjP1n6ZU17x-g)A3$!M9)j2W;S+45=@IqE{=^ zW^>ug<1&(DjRm3~bPZ>PRk6m$ovU`;gQaA;AXp)~@5wG$vtJ0_ zWmR7HO1*IGyFH`n<%68SMB;<3!`C;(ycWQ1pFsHY`&dxQFQ#9sJ&x zHPz)!=?&e{4YjPXd--5Ec5BaQXS5QLLkN=#)_DxgFmeAUY_;g&?+8!V^1%&lvMXoh_&!#3f|rcYNOqrIkz76OC;3Z zuo$*f#;Q!a0BiUhjvarQdFISUOkMHoy?C3FjXh82lz{!L#D-%1YDSNePlNA4+jC?! zYooA*>%Bp)GIgV#+xP_s+F2L4!tb4;R|SFA zHF0vx6L>2_yoqL;3a)qz&t}=%8Ao|}t?6%Wm)ve&sEjtsBUar&izMGAtPaLP?&=8d zRV9>w@E7oV`c#Ao70Ox)5B6R(27-C1 zfG`X`1OV`Z(y&2x3&{YKCjfAP4FR196^S4dU~mL`KI#m-*!J>uV zm!MFHek28%USR_$0Dd2yreGl>uo)Bzn58KoX1}6Q@QYG303>p0h@@Bs7)a0<5Q*ji zxVBON5}wvXMBx=G(}j2-5g9F@Kn(~Fca#Js$Y7$l1T<6zIY=N1TzXn8I$CRR7NJ@Z zu_i2E=akUXg1>s)U^y`^9e>g`Ot zLInTGs#V5+3Pfqg(ya-gg^W!%kvH^(wE6}L>E6_>!q*le5eh71HJT^n>NZ*~#`XFUl!!UcPJ@yE$W8n~c z*fW2GYcU+|E}m4L`v5z*I5SaxUl??89znqY0CT+rIHDO(!wdw^1DMYjG7-ECV6oVN z`3&HX0mgZJ9JS!BC_gS>z5sX!!n1f3z7k-*D<4B;8vqu&*i&^qNBLdsS%?P#1RmY^ z5dceE>?uC8X*>n*?S;SHE58t8obIwpfV;~srSVkR8h~+o9{vRCsztDrhEJjV5(g$~ zL*FBq=fM08;9q;;ogwTJx!O}Yi33>X=}YOP8DJ+@X9^a;6OFyAGnFR+U?*1>3cmqh z2UjVD{~BOBS0@SO$eK0gSuyDf`|ASm3>r zX^sY1UkR|()q{f1Q+Zq|*oKQ?E>`-}0JgL8S%L6wbiJJbJ6P)-$U`tK*CK%J zU7e_UYbluK?Fqn+);xp2`DCtMlzq1X+>Ivzc6OCg`2O%?eBE^B0?hH^Q@*4JxZ5{& z(|D?`&jGfz6;pn44PZy6y#>^VwF6ABc~qY70G8O>GmuR=0`LJ>2a4uU1l!wDcs0Nh zR|hJ81%;>ce+e+*%BS%ELij#3-o}=)HAN=^VBD2U!6O0Yc=IS()BuZJ?I?UXm4~3< z9RN%1-I$1L)+g3|yNTk(YeOZw1x8UYsBOQ^bj1Q^;lB|9O8 zxf(AXUnA{Y20j41Z(n!lo6x%g4Y2|8;fXYsw>^LSeMRrD-S42E_>kv{q{N>VfYz3C9 z_3R|N@YT2oCpzd|w0J~rSEN})qUlv=lJLxxgOQ?64rVbywFIV7C~&MvE9JOhWR?jp zD23jW#B%d7hFJsF!%dhXSIa1Pg~7jwU`;xcP|Cqblbj%Mtp-@tT1*POi=id742TT0 zqAtcA(oM)Pq0=2w7=bO*5}nve3>diLmh<6R{5I*i7BiC~A*SgR6*P6_{@r8|icHY= z|Ec6~1Olm4A&1`{RFmDC8t&u@sZ=1~;3l;kKsSLw6*i$!9dBpA~JZt+fr8GD5-!xocf7?I7O zav-9BR5NB~nDKgCK`4X@H-%K8P-qlt1*t%SLnwoCS$9u}IM!LtVz`!Jg32}6kj}_g zo|bin2UsUCg{q~Jy0E9%VlWu0hs1DNH698OpXR!Qd}_9Ib&cp0(h`z{n$UoHB1S}Z z!N?3_I#n|VD7wKL*KT1=3=>0(!%nLNeeGBX-s%QB(J6W*0u7w))IpaAi*uR27NbdNmjh+=$vpC<5(;zR_wyeIvl> zfhA894%sn6D>8X%bAbw&85FFA?!lCM$I{XCltJML5Lbaw9isPh-(!>jEsPA*b@bA29r>TMdV=5NCv3-bIhX?8>Yn|_Vu)MSYB!H z%h+%eUJpJiB!S>!tw%0+-!qFv0Y(&3iqqnhijn?aLTqjEgdiRkpTfh+D}r1(0?X;d z9%yl3MuXv6q#gwZ2I>X6n}9t2JqF!Sju~$-d*T)|Zb9_W0}}8kgq{c(aU-GYhdN{Pg$k$|DzyTr%l^vpq!;FO66GAw)1j>k zN)eEYVSmL|*swglJI;Day2x#oYi;% z8L^u2fE2FAUXlb%K#=$==&Tv9pud3TgQn1+Gl8Fm#v4dzAE+ro-wCDy&jcHQ3xYYo zIv6xJunM#id>h8Nf-yQw46>6!j(|>=vNIM5EdrjU)`8!QAffbXC`FK9&ef3Qfg*}^ zmL@GY$3LBv#(+otCuV@kTbLobnHkby@+3P6U19dOjNR!n+wHjzc3=>FCU>FHLife(+|B13Tgg3qZ?ac+bghwZ_lL3#U zo-k_y^*}>~c0n>8XrbY0NTNU+;l?mQ2dsq-7$X&gLF)$L776XZ4gM}u3p#Z-f$$&- zbiZbbOWY*Vz>x!{hC`?z(9sFsM$n+c%?*YvH=!Z|9UdMEh0qNhZs^DnMYw5TxPN^> z$O56o>jOp?@IC72#8#Myb(kUtTrq;snP41wM&fHxZw<}?b2(ZV@xbkeX`vsD$YC^? zJVXp=ofw!N`hE@eQj41)Jm`ep7y>?AM~WCGH{68iftZkoa6>&1I029X>D(}|1{eX< z#4sUA2@DLtoIm%qg2F$5+JBV_nqJdFj0aw7$eLbYZY&P z)>*ntaunI2zzzj^G60kaK%pK)dJyPYEN9)a{_T?sGc{NaZi-~I3&;+Ro2J7cbvI=~ z)QdJ#XD10p>=bp0EF%0YNQC-vHw?Vr^Z8C_uMc2Y`;hF)eY&&b>>ZMX46pa@D9P*r z(Fqj^k_5eX3e6r}5l_3Gnmd3viWVb0a=@Ce%K}7bh#cWc4?3d4dJQ8mYKYEy{5P5Lv!we;c$g%Rp;v5zdZjibOIVtUkO328sZ~LCJS8)q8?$TE{yo2 zsXz#-fUXhTOk=$eXFXp=S|TEIAf%!h?><9_C0ZF7`O@t^ZfHZIr)!jdYT^?YrK)zGAdkP#4iz7oA+bYUIj1M^den*SGn7-6CO zp+`pWB;wAxt}B)~hL_sEpvQZI^l);78RFb^e>a%B-I9(sI$r)|Sw|RjCQ_qt6B0ND zU?LMty+wGC!?Z$Zcexk@I9hnZfZ@B#GuI3=ml)Xnip8?6$NYDi9-P(wyS=RD!@ERX zk-1MS+g2+y@bs~baTe>)-Z5$5X;b0mMhNk>fLR7Aa5oVq6vjf+>2$;EJ@MNj-DSe` zz(8g-)obqDR%o8Mxy=*`vn~^g2l%$d+Q%;1)ew(^wha*bc0x}B-4TZRx(GMaBZ@SH z21lJ6kc9??JP&GAP%Q{@Ayybo6f3}s8+^G7Sh-BG0wX74g;p18#~#oz!9x~wGgxjH zJfB1Ok5l@AT1AkqVUUE@13Dzim&}C76FBJJ6lT&4758kO@W5i-Ok}4S^w7Pzc@mz` zd-rVSPEvt&;a#31B0Nb?s32;*YGVA@cV*Gzqhey>-<9?6FN3MXq|8~Vi)Zm?ez0)i zteM$-%?Hb7Ey4z5e6V2FfLV*Pmdsr=_k#h87p7_kq%KNdGI!wz1HuOm2(iKg2M^Gs z&YYh*XV&7Lxg>qoYeY)?&5yfTQ;S2!<1BFWo6|*Gx_@ZTBwgN zg%40<9;nHP2t1If2%r$D>o=rx#s2X{`E)s1Qek0|Y5lvrN|Oo&rs#UWCnWrec`MMBymHVi{E{ zg;1zede~Gd82->EmM4j+Z6$rLQ0bX0DJ*<@Mc?NbnJfj1$u#EB_bh>fugdreIHvEr zKo)ba^a!O^Ti*;7Sn02ZZxA8j(4-XFfW8Wjo^%9{915AN^dSqdZsndTLEraC3wly& zL3uFI*}cK+LN|zER2s@dqbPZxddymXMD%9(4~jiIln}L{O)L%wP^ngeO6YsDQE!9; zPV{|5GzbV=bVN@&(qB*dD@a2+=++myH=}!PukzdU`tI`Z4;IEQbTZQEq|&;P^gWZ_ zdh}x~EUPqCmK7SU{86OQsf*4J=LT(qwhH!g*b8AtTTfzRV^!6L4aLRz`7{dY8*Sb8 zL9&7{Jw;xpb2+F4t&7+7L%LS&#_TEoiuRr!`%=Vv(MR_xRX{+u{edLnPfKwck4=Q# z8!epc-XJ&R4FE1_3@Q$Y9{R7CEU;#ef07g}>O`UfRKt>qsaA#VNm^)Sg&-@e|Ne(4*Y>~ zik@^iou9?k018M^^o>^k!IYTQfvow(n4D6VSWGbr`K=yAr<<&~l}c-V_#dBZ8_?Es z|4;fLhs%%jaJol;KU!WlJ&-uj?i zCP3Vi4)+^29C&Rw)WJe8+mmiBPwNM;T`aC#Nw*K^`Ov1M&N3j`BRvA()|x)8Lx?nvQ>^0a9B@a;#gBt*y13A9YDEgXVgFn0~tibW}}?|SD! zaIURq9=izF<9eo!fO~Y<=xucT0zzj)?R=e0K2ysmVdz+fnZbHO$IfSKIXb3}1^lt# z%0Xu>0cVDe3-?SdFQ1_m070f+pk?Iqv;aX05YQ0-v!Fz;(psRWBlLteSKw&m=X3Q; zr~`6R2d;;5dcKiwu*t)9xSl~#g)2~C8*v@SfTNsxRvuo+(BpY5{ZbAPVCq>~9I|BF z>eyP)FFGi0|6SJ{Dun|Qp@Sf(3j$GA`uxvANNm`xWNpPd9_$<~L&wlEi|{;-frBIk zPJsn&ZukV?4>&Af6d;)h-JC4YHLhoCSvnRR&MA3}ybKx_3fy+{N^|_boP%WsqJU*! zfbeWkG8@#`ex8~ESPvwM6(kA$IVqC#8)VdNMI z16R+}gI|;|O42;@I0Y;u63q%t+sMsBPSjnLfmlF!ir9Ixe1Q(nz%y`l7)2R513G|1 zFgXj(00Cv5)&J7ni|``cdV?9+MN9*7Ru0fdJ5@(-`Z6P@5Z5C*G-dE-9mB{friwwv z9;TpnsFh-jRS1l^L8W}e9Eiq82NXnCR11Bci}X(OiO%#v)nrw|>o!E|tVd{2Xd%)P z7z--xWh9z&1GAWAq!_g_4XV)Nh3x!U{gK-AVbnRa_f3xj&DV4Fgn@vDVym~+3t-O` zjLT=_+ru$44IvByy{*ogNuTQ|&SQasP+MYy_K<-&Ivx-~JNPol?*j)`gVM@BuL$3rkG>*1Ls`lz!HbQA&KY(asG4oC zEy#2<*uc&QVm#}?h3tg&=xLHgtdedl)0z_lWxJ5UH+xBj+q^^3Fo>|DspKb^0f~JF12CbV7&dY+{3D^fw&>+FnVFq3S z*TB$29!Q~jZ^(smqf)3ePrp?7)*5?pQOqcw?4;-GaRb-Tb3k9kfdl`yEAo8g^>1F$ zkcYhe%`2in>&1G7K@2r^)FRM1*TEjS9y$!5LnBB?)d^>i1?r)4qV|Vc5Jd^(LM@6q zL+=Ltk{;2f`Q-q80$M6^HLgCF@(pBfXzR$o!3&@W6%>F7Z(Jb_`7bb|N1o0p=H=(| zCB;;`gA_E@_dWiVmcZ?db#cp(xlw2M2^lBNsZ* z7z%!`;~DvS8~s8j=&m_H1kON$I)l4l;8@6E;0graxIzl-kc)OyG&-TZ=L*!I1kj_d zQ0W_20|$ZuG)Qptxqc$VIzV(xh#DyqN?O^ZSmZ-_5EC_85Cp^m1t1|IA7Huq3=xom zWFP_F54u4zBOMTwbr?Db1Py{WTx==oI|ZNs8$H!Ez5xMt4P%YQ#)zYU@&B_!PCJIy zMhjN|FU~?9l>2|thjxt{9mJpojM6l+3hL`}Kgi8>FZH)E;CT#?m+o&+%ZIx>+>q<~ z9ttBsX(;xvfzBK+q5}$~WTZsgfahZdrje;n755qz7!Z?U`4C~ixQ03rWT9>sqAWqh zB{)h)`E(4!g7F4U0Yr>cO{j0BI!Gu?xdz}_1sub4m!3KxEYPv?fngZVQ3piZy;mLJ z2MCYSQ9hJ^UdlhBSa4Yg!04wBAkZDH@{u?oF7Ta?<i;1gu<@4a z1t1G8JPL+bMVvhQf9TA}M!EovS#^f=_8*UV^q41tOmE-&|6dupi!ngKTo-8B^bQXb z&=ycLrTc#v3G&$a2n)>?aMTXzs1dXD6X;sHX}$g0KbH+w#tk529+DEd3@CvbTqs@B z8vlQvbNftzAp5`8*mNUN2$h4|(Op1y-$z}o9SIKUtU|)L0BZQJ{g~6^p#lHqBUIP) zpI!8Iq~$pfHA85Ys6%>lAC_Qb7a&U@_k=#mNaPbn6uiP6sFhj3%9{kiGqp4Gusmd{ zH+Jx|ffJDy{?7w7E~=gD&?7_IC@6q}6UrHYDx!@Tp&`T&9lF3{8}zR!^HG-zDC=2^ z!80g&n8x5h`x{r7J3w&-!qOdo?<@4qU?cj-WsF5kz#T0dR1Ez%#|RGk~*>hUSQk(SaU0VTTY7J%BpI6)}q7k%rp2kZ6Sf zo6LcSA!~=#E7s#dCi+RPSFDH9^?ZYn)hpv0$^T1=9m7CBBmOfx)Br)mTWW_W+g@To zK7qzH9Q2M%hG_{yZf=lEE^Lvxxv|A;YKOc2a7;Avtb4A)r$DsEW*u)mkqE?-h0 zE)*Av3dIGId^^AZ-sp((Y{ID>R7feRjN79qN=a`hs+**3iLgjqA}n>tcQiUdHUCha z(bmW`3i5DNHjf8v_EyH2SV|4{@RV&=ATeMDbckWhLfRJsAt7|G$SMK@Xp`2cfo~uT zJaAr^`+%JXcYyhrN$rwfDL3+}2653B8ABpJ}V-CgMvS{B;{x++1@Gy6WQ32u~buqe^KvyV&)j zO%)M4np)@aS*s9M%Jc~04FTgxA=#N?<7Y6}aLWAG|2zwjN z2SYJh(8K1x$x}3#lJLaIC<*TtlMt*#p{(;+uUw~t5FyI#>N2)gvr)cQk2P2lc5A<3 zB8Wo={iep~)0XSYd^ZL>V6{eCZ);Nwquaa%*86P!rTTIx2~eol=`rkxhXj(F-$q@z zW~;hXwpL}+kov&L@SbkIXn|Ba)jD;FVl(z?rSf&qNozGIcL-Dx<^T0cT_3q^SEt<_D%x*SZwlI|-xyfpR~%T(6$jV?Z5(|5wji5d zF<|RpGq~Yv>tyq}1@yMtY`XtJ=xan|qh{+R|ei zzoT0zvjuOG+k!VLY{4Z;Td+-S3*Mly1+UlHg4g=kg4Y;8`Tx$JRc5u6^xfM1!C-f{ z1U(*DrYVJ1+T>rtm7tL&)L;>|4#f~ev3E!Kuj}Nl*r4J;XdId+0*$0*dj2-`bN}^i z^Og23l|o`J;FN2y5~H91y)OOe;Pawd20D*gQsl(wYLSXYcJMs5NxX3 zz~TWL`)%sErPt;@rTsSd-r93}_Z|Ei&8C4H2bBye4#gjA8(c4O8`il8S#hUgU9o#0 z7DEoj?IpRCV9=7RHX1etlxj-bJswoi;jzw-cG=l&M~^N2ils+F>bt=(`=vbn+ zbtv(%wJ-4%5maKZwJY(n1(x{R0yY9A*lv^r*!)WZZGI)~Y<>sSH~sbYYN&UkJ^uTw z)@~K;D}wfV{@Oi`KS`$OaVZ=1y~n4vbuCtub+*a3cC@hv+wX1nMBtMF`?$@TGJo1| zZ44+el(Z}Hh3vR>9VKbsByWk6B=ycVJtR)>v2}#RJJ^WQP~5KAuLP5BBjmo(P!b5K z2a?oxL+THQ?C61MH`SU~4283!TdTqeDpi*TZuB9AQ-UdrJ_{`NBTlyVHUqedW4pK` zDVlZuwoq}pQeE`6&KtC49X6=9wzDZ846rF4=4|pu{B5#bem1t-uvJs$TkgBbr;ID{ zDGe;qZwe~bZ|qR4E9r>Q(%I%lvDVhb<_+D3F18y0HKyOtxfpP(x{g#MsKEB5ZctNF zk{sIWyD@N+rZi}8`#l{o%DO%jvZLqb{>4+Q){f$|ktUC5?+<$be;d#g{7J58Q{$+4 zZitfu4fVJ;`=qeP{=G{=Y8wKfHmk2Sx47Sy9y_}2?DA;m$2#u8C@9rzY6sZ|l%U5T zdk)KkzgzYs|69Qyc_<&{M{glFdTFC(6V0uz5AoZ0(pkiP6L^90_X5r(`p!n{Wrapg9FKh15o)Z6BEu8lMk|Bz={3o6rWY`4j$M4Emy^)T(Q zoEeHcY%mme+<>J_1WqyDfaU8}xN%8?*1@tQp}0ed9>AT?8+}RwH~E%urM}q28Ok(U z{2pUA|3_suZl~N9@Q}h5xI<}cw^hBNLzxyMO7EVZ)a96WqD;_6k`ZK2ql@}O9AV;O z7J$BL2f4Q2BQ0jZ4~dIeak99+_q=IwZ-*VRXd-`?5Kr;ZVq)JizpeTQb=!T*#o&0@ z_uWq)$I_EM*SE~S+_2S9E-S(-*fP9?UCUvQ?zjGLV;$)355kAnor-!Db-TYk-ZBKN z{o7pJC9CjEgbzE*@K#T(oqt(BYv-ci`@5{`y#9~=Zd=#&{%%Ec)^u6>M>#0|wzXZ? zSbMd#+81s9bFTU_d``4gUZj3dT_oF%_sQkDb+`RtEu<1;ZmFW)|5;JgUGl$diqA~~ z(yj^oFFR0<#wv^CVsrn!I(Ul{pK_M@to;+=;5;*VnI8P50r@vu=n>`LDaO-hcvbX2 zJ03li!8ca^atQq=1M`1kI(ql!|AHX?r>p$$4Zs^GK}f4=vvz9p@{FzAr*wajYs_6q zca0gdC~47{u47h?>Dp=3>QSA#&RjLKYu9_M_uvBs*(oT{%Jof1NEk6{Vq)Up*zN&3%}}Hc9haEczZ-t2kHTZ2p_|TM8^z| ziOvYp24yIe%an@rI}@kiiZBq<*DrYnk5ws`$(6)ChAA{!#;2w(i?QOnw8QZgwakjIIxl1Kt71^Un92Dx>3jjf#okS9V4Hx{iu5#*D%jL;J-~E-x=%8K0RtIi6{UqI>Wqdi2py zEu-qmNA>C1XH>Vnd(#6)f_4QeG~>?hGiEH0?T+fkcAtSd^QkkI$M|-eo)EEk=O-;Yv{c2XG&Pbs4u1sC2*I5%INPZC$ zCQOKkn24_nj*N}%zGCFq7=9UhtfFGo2()O#Xh>=FDEcP(gw=_0^9F`H!Uqbv{@3_Q z+iINxtd^tZ@vCC-b;F4f!((E4tY9nj`n*+!&VyI=>EA!RAFTd;j1#8B@WaKy25WdY z_ug|y!?}J@&5Yeg17|=`j~=kJ`|+jP{rhL&526t86=zOh7*OQHuU0v(hO0r)fw)E_ z<6j60YEU|Yf;w^`9R5R)8bV|>pl67pND9(a2EE$|Vh{rt3@97!YI7(Xh)YM}*FXu4 zU`3`;^mPpKuy245)gZDEDuaf<0~X>?Ne&eX5|BkqM5OqWg&H#OAuCu5{$wy-hR3fQ zFknm&zG$vi%U9zsV@6_Z1`5D z4(CdE;wjI;rxEvplDnX z7yyg}CIYj8g}@4+1b7744;%$P0L}o-fPNWhfdRlsU?MOZSO}~DN`U>qQQ!mM3~(7} z2K3882TTNJ0}Fu_Knd^&upc-Id;pvQE(6Vgeg(<|1^^?0iNI`NA+Q1{0UiPN14n@m zfHS~lpc&BL2YO%tFcO#uOa>MM8-b62W?F3CK;RlBmkKNgb_3r5J?~d? z6M#bCb>KWOXD!+XIDpV~N^S}8D)1}dzh24B03HT9J)q?70?L8I!1qAM4N7htFdHxd z%Yi3>i-6XqGUD1eO4Yfd(L8qmqjPW&)dlV?g^& zN-iE)3+x6y0hFamZWxdZO#2UT2WT?gbop?v0dZwYZWo}~tmGB|{{qIAE4gAoxkbrY zf&Zke{|%al{$|}8z4Gtg`royy=QfP5zlkX1pYEo~hr4(?#{LfIS0Lv>B{%RPj5FZ# zhm~B~PRy}KFxMXa`{n%Idi{Sf|02lc?;;m8>)mwQ;EvjbaSk*9a~{K-1)_H=xsyPT zJxcBiU@q3ezgy1#h5Tw9xTe+V6dH|Itx&5po(-Q?t5B%bYOT%_f#20>^qzp0d`gW{ zqf=?f;AA4DO0Cpt@TV5JAV#H7Y1JyNww+)50JT=@tEW^PT;w(yji1iX(3uMe4CMUV z1*#1JhW3H&a1Isc7wF&7pW}1}ov%UX=Wp=$)B5}4pd@t%+J$L-HGaN<27|A`VDOju zdYb@$-!84j-#g`x{aw702Kf30dj&P{2j66dwVIm}{==YGalXDh{#(rrDgSZ6vqx*6 z*0x8pm>4$+$N**n?Sauif4~ZS1>6TD<}69i&dTJoA~N{&%uM_wHlKOLnexo(nf$!M zoQ#4jOU?}`OY^b{%xy{W<|SDfW0v4NX&MRPJ6H`*z*z^KZTzanPrWB+X zus9=&Gfii4m`w$F%S~~XOmk}>F=w8I#T!}tV8UP^0*C~nSo{bUKi!nF6uja=9}m9M z^9ww#DGtRZ7+C_65^^y2Ofyo(vT<&LaWhQQ&H1^OoP0BbKhJz`p&7K}%>^c^pI9$X zAOi)EKQ2yk5=Cdqy!j@vc9fKyoYF>y*5VwgmWF<4FwTEtbr< z=_tceV40GI`_w%JOif{}{FB}FM|soZ?_|kYIrG_c^Fo{;07q&=ia7&q^Y**j*;+4; zM=U?ZGEb75r*dvrN<_s9^VuD7NmHjvlD;E;3Y(dpRls^1qY6jjAcNld;~>~bV+0S) z$0x>*?41E|F6o`2_fE^o$tvK@d3lyRJ?oth0zSQDEbwIg4^EOLK^%cV<{`V?^d1yxSAY=NIPYW-k}j@p8%mk$MvUB3DFcenI+t zGY>njpfHz+-SXun(VH_VZn6a{NXkq;Y3dE3apUyNysTglPqoUJ#rMwVvoc5b&V(l~ zed%c9G6-@OQAmm8<1KR+_RbWOhG!#0so zr7mFO@>ohbo0y(cn4Y(sjWf^96FpPX^D-8&*xbCVY&Io*Ih$CRV}_NzoW&N-FT^}c zfle^vD2hCmlu=+IcdBKH6cKOEkUV-elnujyJR?{bZb%4a;W+?_jeqNJo;b6z^_ zR>ZwXhGlUs%0($lvv6id4qvdq%v0TnH*#iKGTDrr{9JQJ*1Rm_nx2}J;^yx@g2a?X zS~4d++cYmbJ%0h;rw=cBOy*@-1*T5>>2w77SJOy ze#X3|ww?QrojiL*U^2M^PgfePPRfZVrglN?J9O-X^O?H_cMIXW_vqQHcb~rf`VSa5 zC^RhGI5;9QYRJ%G!$*v~ebneN(J`@Ojh~P>anj@|QWP=;57@Ji6<#-FqtbKK{g$`<{CGnP>O^u(%CQTgUuZ@=^IKmYaK`yYIG@}rMWRekd5XP*^b>UTeJG)ZF55x&$2Wux8EuQXPs*HkEGPvTeshJ0IO$ z@%X-{_dkE&rNeU<=dxTZ>QfU^Q{rNi6WI8~acuaAbn1tLdKI_+5gE4#ps>fpsPKjz z0fN#EbPprQ08iSj(vd9EkW2Z=5RJDXo@Bh!sR98&ASJ*MZ@ijkI)FYGq-6)yVmP8& zx1YZ_XFL7rLjxzjqI+ZIi>o!EuU*;_ ze4;#)do{R@Ke%why+`W5i#@(>)#qn!`{nzyi>Dp_yy0K#KU;gp!`baBpIMZ-qG_)4 z*Z0jONq5VFPG_q#GDiD1Uo~h;-{W&`zlY13{C#ZN7kT&2fBcj06{E&~uAJmtZ}@c4 zVg0`5XATd^e)y%aU%r3ro0z88pSzg-bwuIa)d{BzUw(V%=uiIfobhy@k?gx^Mbo}| zuS0s(iNg&qcklVmp*wc&IC{!|-y5&(eofv_Yg3tCI_>+z55Ir9e~*W& z4!-=%SO4lb`p}(g3@?Y>e)k)%KA(NGl3)AUZ?7CW@rdt*R}_zY`eMO|@n2j%u=LZ% z+V}YeKMD9YKhP)R;=0>2w~tx4*znBkg)4kc`F;PGpxf5>1*U&-w`NuRHvgJWpU`et zP$%o=dP|)(XXf0-59gbU?j4%l`I353&XO*lyUq>#ta$c{Gu+9EXXjh0k2E#ekC(+A zf3@QmWe3xKdg9A3S8w}d?>ldOJ$!mybyDs8W1q~Q`TA35)rX@e4Si|CnSq9{CwI{w zxHeHSG;M`4_HBDw^^EHI&)Cay1}{IJHEz?P^bc=aJMZ<1Pc6NNURW@F$5P*uit#?j zj&zXs2=Aksas2k9@AmU~$UmmDjcj(@e&kF#-7 z&_aLVgWJ{f?)H%d2)oUjvtF2c{WD=vdcvvf4$Cg+E3SNM_$qa+a_U=$6eH66%zwJE zLt538@mY!AEX^4+ap5N~d^`Kg)AM|)V`^^ydRWQ}uRr_l?qlCsPrWq$XW_81Yuy`f zl)QEH1LL+sDNjA|axc};s-xS~Uwzbn=69(l=AZ5vwqo9)*CwXFBk!_c&h~+p0mF{_ zyu7!}_w6p#s@bJ>d1zuho+ANLjpRDaiqilO}npXz^_ufQ)c zDtZr&>OXkQpo-q*!E=Jr@nYph`d*!@dz|LWgL`#;v)!WxyLwuHs#8UWIYH9`9yOSB z|5ARg9phW<=gJI?){AYdvpmh;MUCcU3(4~ zJbXmNz+S-}{5y8*Jt%VI?NOn9Li&ac88v!n_^>h2_M%PL)8ZYP)<F`W( z7l%FHt4gi|&>83ogaAE&-hlELzGI-3-|!6ZHgk|-jH zB9bT~i6W9HB8eh`C?bd=f+!-0B7!I)hyr~Mizv|Nu!sVE4vQ$z=dg$ZeGZE#(C4s- z0(}mPDA4Dyhyr~Mizv|Nu!sVE4vQ#^gBiLVUPK`YS&$VZASD)H1(p#Qz$n`rppX+?p3g1bBKDYt|13iIRz<3}Cr~x_xb-)qiT@80T+&*v{fRA6p_j}-8 z2Y8?vZ~$?@^X~j-;NJwefU(HG<_JEMgewP>fEutN?I++eKxOO!?Tf%`@E?Zz1Ym{V z2YET5JwSOV?``nAUcvVY;ir5QcR#QWcmVL!`wgVY5vH<;H}Sohr#CNe9z^HiQx3Wk zgsDwsKsm4#*bY1hJPbSn>;iTJRG$jqao|bdDc~7kKkyvz0&oy`33wTJ1t6L~k^%ME zQKY{P90z;>4NwWZ1-t|N6L=5suJZ>7KM&cTg!?g21$+v84txoG4cy#k-y-fi;2dxP zXoj4>hx;Qya{LMSt3C_DJFefN+U6w9<4it+r#XptdkpXY*x;Tx7QU3(*X@G4N&0k; z*&lx#i^m`28M?cEzR-e!`k?*86xLy!)@$Ec)8J_Q{AwJQhtviI*;GuVucmo zq?|+@J#ja?ME42GEA=Xq=wk4~h^j~F2fWgVK9iU9)ve0(@c*l{`$ovQ`G6-s@uW5q z-Oj&J-Y0$k`??&vUC!+Ts4ic)-AcSX^5|nv9X)O)pUKC#>*|T~xJnt?0owO`RNNQw zZSDIxLGs7qPoHMS6KQH_ll8hCt3+8>`+h2z<;QFeF0QycFEA;w})#+8l256Gjhk+E~8 zcGvI8IjB12+Tx}Hx%RA)JUMUB zsVYa}1!OR9U{&lXraT$LrZ|wJu~Q|J)v1u{SWXPYQxD=Fzfly08-tHlKv>l=AumsG zRVq$6VqQW`Q8(POg9}2KqSmL}KPCwu@;%D-?>e*HH zBmS<+>XkLxO24#w7~95dPrapc#Y{Q-;@EA;Y&yn5GFnn0B191C6(bJeS13|grnuHE z?ff8=s}PzLksMQ84U0khW0>+BV~{@Mgi;)emf5D=^oEhU=NrfUg=`LZf(zR|*Rdf-HHvYsEb?WO0-!fJ8&)gnCa6T3v z|MM=U1S6k=j6odidA!8Ib*b8OD5(hJkYlpl7<9)oaw`4Pn1!9>2Ug1M!Ugv2*vVBU zo`uY)WAdwhUkv$<-DbbcDNbDG!=IdVzKpS-A7kun(!Ko!+#S1{$vL!FeobTEd{A%y ziiM?!O@oZ4f8Xj4n|{sEy-J*-_*5agPFD6M^T#C8x1eGjub|;7gfI$eoJ2+%$xp@; zrq|zoUqK*uH}Q-OsAGx)FRH)0pLI<`0t|KJ?t&cZ$QtxeC1YhgQ={?XdF068Q-se2 z%HhejpNU~?^pjkN(@ge*?#ja-lZGpSEV$m$UW}Yn2jPayI>$O8M!1fcVb>6&d+!`$kCjD6S(l+> zakdLj{#sdld@N-kAY54%8OeLXNE?f|rknHKGB4;+XGb#C`5IM?zp>6oD0oDF z5f){+jygNiz)AblIh5Y&L0Q627b7Egx5l)2$~;DniYnt@m&U*@FNbGG{SI$V8|5kj zRZ?;pQ(i;MqH|dp?gC?FVU@6c#q`*G&}u}2{yZ#b0$ANDV3FsKfnVaFcGP>QbR#<6 zwHagK#82N=u%z9k;YP!TpQ?7L&#f+%UHU=uQT-3x!mZmh4p1vxHCj}e_O{qflU&46f#5QVC5OvvK6r`&0E=X3rel`ly zR->b#X@2d#9ZnbFO=1=J2SpEe7yTBBK7*p=*HE;oUbfr$IQuwrQ7)-1x?7E@ojc%L zc!gN+VLVgSM(-Q{3!7yBS^U{mulP6OW5j9Cb|HtZ64os}i1c|DsYieBfhY{y8?X@h zUSHs3I&k(q2*FlD6UwgA{nlknTSGcJBu$0ReV)CK#j7FOh*^A;$}@>-?~15cu^!3m zLef}tEz?#(|8D$|8FHbSeteXL^Rlao+9a+Ni0E( zX5mJ*TU2{LQI%EoKZ3~D35!L?z>J-}EC*>03#i2+S6 zCd23P@k5c%vH4o*;8L8_^t->oo3G6Q5iLAL4BzO%HsnSxxOiec-V^n`>*crj>s^1M zp4P2y?=bE93Uy~^+%A#RyosjjT0ImINk(00{JP9 z(hv-ZL3?QR4T;g(-)Yb{P7uaI$2K5qctQ=5klzyXLdNO_R^~{Gffb|wVt7M1&o-H^ zToFv&0|LVF%`e^cao@95t|GSkqN*WQTggrdHT^&1wN)4{H~h2Jj;Uz}3ar<_*JQ3? z>>5h)pL>m|ujv}c3&|S$J2dQ~`42O54k})77PU1N(MQW#_!I9gt~!p*0UFx?T)hF$ zu%m9n^at5akYIlV-%Zwj_0)T-D?sVRy=&!B*-3V^>nH5ksWf)toAd0AfNzl=oqH53 ziH9xRBfFd1SAXu)lJMJ)6YGwn;>_x@6jICa7Pt8m8Pf(F^2EL=J_?vOSOJ6s&ilZ7Mx@L7Pb;ye4s)m#4uF@ z^Et8sMaHpsaEx z+Xh>8(x~3+f6WIgWSf!S2hGZqj|oB*HjvO_PKX0ebrsVK!YkZw2x8UpLy)#|6y#ci z36z;P*f^ZH!&J_5%7MbKuHk)mos`uGU1G?c=FYhQhn3lE54fEh$*Y|PkfSv)vSiT-rZpB1 zg<@o|a3M4e0T*B0$PmEVeJ=t`E4UD#y&wWu=*0kIt0*8EYZ~*pV86yrTu%}f37;rY z2nRu($4*GN#(acoA?<`SNVt0H6P9$XBcA!vKo$VN2xM8h3xSOo(CI=4AuXgyCUARd zE$86)T{}<&N85ZV4UXDzpa@T<+7@dShzyM(RQt`f8et0?Amrkq{EEFm{>U6lbSg@C~l4R32s+S4(3M09#HGOYWYl2GY%4oI)vFdG(8-0^FqQW8OLe zMJ3D-Tq9gDdoFH9p_XgU4FFFe|3{iYf`HLy5x%ktSUD|1xxw2_5^{Y=q|#TCu(ApV zDIhlJ)(#2~AfYfg=srB*iQN}Uf#o~z|E}N8hwxB>=6RduL#LiQN#+BlK6dQbQ6nl& z=_r`An!1JQ#36GkIjM?@4?kbMZY*O_lbUE`$-oeqAKr*b@8;@paoeV7u)iP^$z-L% zKbf6PMeO(0O5qTjjJu}MeHdnzO5!AxB{SJ~S1=hx)1yZZxZM$tUGsIJ<#mpAYY-e9 z25hCv{!@IJi*wzE)Hj)v^*cs;P$thstMQM^Qg1R*$`4O^3x2A(ytvznS}Fo@_@bd4C5 z^*wilT)+IqZ>d5N+)V~7S1W(e$s%@!g8CMcel#g9clbJcX8dOfm6 z3qp(_G~geBq<=erTXF062$edlazQvuLu87&fGL@1(FRj8U<&hZ2EY`?L7mOU`d?s* z7Jrvf+2SuWkR_y&)l8PqYJCZxGYHn3$kM`;Exr{@LA@%PK+#qRY2=2HMxy=|V(_vH zOfce3!Ey0e4`JMQzt$;sl1WyH!!4IelY|AQfd+;kd_wGCqR~sy7+%p({T_tC&rZ>< z`DW`J;+_OxK0+QbBTF6aR=B(77XzF67pn(e>2&i{HBD}w| zNUWkTT6F4U0nv>CD8nmTYryw25N1(hA9lC0S|s9$AsN{nndB%=xa>{fVQuCV)!(CX z6}p$Z3CT$U?<4dP&f5juDIr5>J|W=!UaD}dn=q}qMJF6o*e@uJCMc^x!j6UFfKIG- zZY73p^AYd%Y`)5Z=EWeOv_FRhe+ztFF?6T6jPUKb`j5f(2BvvY1&wTVaTpR2t%{jUoEeA_&6q05 z^%aUl4<^F>++OLBO>dQI9(tw@P1*R$x%2)H~ zU2#Oq?Jp%yWU?@4aKq+<7=;*&EwsL!5?TVgqs@CNMP_%w)>M#JD=wE>FeU#EI2c?i zDxw_9{NSE)h{wrdkW;};=Ha~J19t3GO&D=)U~s6}VJ@-pVGuJ+m}raN9cEgo70}l8 zTCAMqq&P>QrL}DHsZ%w0p-{_)hi@+uJuDo>iF-}*DD<^PF(%~0>(^QMFUO97?gEJo z^>Xsa38Vc4N`C|SFlj5`Ak}&D0x3b+g~O1Kq2e*&h2f*sK&|1zFT$=@abOqGGjcf#X+yswbQ)`Z}d>P3Ll;3booZ zc#}Vu_=?6NG@%nPj2>>(KDAkBy0ct(25S1GfAeP4rj`QObpJ^Jl@)4)i-A3QboYlB z;(hMq$q$nmON8#(!Nfi3HRi-_C+QjQ?;CP0k3Af`+G zf#0&-u5NP+%u2V3D4o_qR+@2}|6-C}-FYPe+O~ z1e4nzq>!5+q(t%vJS4QtWWx0W!auM33nhYM;$8||>_Guqk`bWwSqu!BPJtMz2hDOT zt%|5A3WPa8mTYq~MkqGa0{ZO)vT@>My~-5uLlv4}uB`e1)Tx&1m%Niarhd~2O9z$4j<#WU<2pCGnn1wvO9#@+1lI+lS8P#um9G! zaOd`k504!?@gef@=rraKPC==jI(gG}+dcnO)d#8m8a&Iw>4b7}8S78wF?KsS*Tq(o z(joy0P&CR%_Cp-tjpt$a0^lbpKZGkO8ZN{DV-ROECg33ihRm2DCnj|bq^ZJbQ&lI_ z!yC~f1h&vfmav&DXnL4G^Oo#~F@kHa8H1@L#Q_jNmB>#BuJ16~A@Rd_tSl1_R?|9; zHR@_7tah&VIAt2N05a21@fCJNtwP5#ISG6z0PlmMLz`Zy5ok@C6s0;t?pn7d zw`;&WDh^wec~+rmUb0ljA>tTI?n=9;cjRJRT6lenb@4U15dP}b>a_5>7VDf_2gGd9 zzA(v}*TJCNU4343mC`r`Q^GTLsWe2r7f9BfCs(gGA{+LzZr=3ht$!g>ZT*%j1q0K8l?tn(h*s* zP6xg}%8V){+-4chB!$~Ujzb0EPL!vK^;jvF;-8dP;J2lWeIid2)0^Z>r0=7s5W`ay z;ICzDHn~2`xk!O}XqjvyxoReV!X18F!NmN(D2n|249q!B8Kd{r3+#Sng(q8 zPwhXiEcekP+)kCI)55)7bq;hgmZ7Q=(|4%Sd?^20s$``c?n#wVqX8egibJ}Lbyp{g z`4iP?1|Nir)KdQE)s><=e^&Eic^xzeqaK+WqZrMg1~OC&~GKG0dF1bw;g5Et4P8F^xvXgjaQG zT9sU;dmS$1#J<&)>$E;H2HA_@ez=H5=L31-ejQ3*p|4S@5q?yEkm8*mA)WF!>CY+T zaFsqxsq%9<`}$O9DL%zVioeIF%Fm$1H)MT~AMQ&&=Wt#VV_#C(N9L6Kisd+?d@EHd zq)+fg{g9sNTcuK?ow$NqqcN~F4MwFLa@gq(zi!}hTohBhXE>))tC;#LLz+^F@L2=%^Y_PO_G5m2)IM?zOt|I_ z$N7uno~`glJm$kiw>z0bKOo=BoD?4%fH3F_1ElbG0ceLW6SRRv_(e1mCI%wikGYNp zA|3fO?Z6lOrnign)%(d@55qMe+)OU`CIw0ElW-~hGF(3>wS@MSS{>4h-0rdVQa-K& zTqRQs=pfbO{tiU}f#9d>Sm_^t_7!(TxuE;LBl2Nhbm}CzlRF_F>T{rzR4)g)pfh)t z^VZp}WL? zNDt1>AAIp)iDcl4J5u+yv{enZX7J?G(;H`)hI+Y=O4*3Pt&?lovNMC67N%CCWO$x} zaVYVjzOXu;D>sI{ag(jw=ZZ^7q=cmIW(M@&nFv2(JHK>x()pTC2 zR-#Q>6s2LmFee+mFkA~dY_a;*c!)#CLf>g8qB8i>8k__*oia;F2^1k{JB zVu((1WNZLk&8qpy0-~~!68?wSu@sf;i}vvZy;$lum;y}E_@`56!*gIKz5>YgZ4Uj z5+znJ;O=sYHITyYI4810_{=Gj!xke&8v&}4hg#|$s*(fUDMK;ps|}6RYqg?S6plKK zV(dX64>@aUWLH~STAG~A%+X9ge4r{pWFlwDazR!Qv7@C$aL*Sp6F7)j-8nIT$q-?i za7fVJtfVxtXRcEFF*|71d2NZ2CMFXvGIA-Xz{o@QdK%e;G9aOr<|dk;;v^2F&O|TB z@ewqcUmO~ZtC7i_?5g0D*SN4=Tz6hab1_{p+NkarIL%EM_a5U>H=ZyG5vW8OS2r4g zYNZqutVQk;nyD@TqFjOtJ&Wv+Eh!>V;M8Z5fe)SNY{K{fV`&7s#}bAi6@q@Ju9xcs z2*ssju0|(D%vFb+`p?ybzL(@9Cvi9^H*?4wG-uqVwJcAB+r2@kH>KSiyt%bErhAQj zB%rm_V39<$+^r%SabBT!wBdO+KtwhH|`)Hto96F`^ zHy9SqgI^rV7RPnWdyE}dOA~6ZQM+nceT%BG7Ts`_bePzua;H*Gs~fW5h!|QD$cPTD zspxeQ137fY2hCI$PTIgPwVdK16y5_-gCAVoVCrdXgGmR41FNVD-F2p;( zcanEJ{OA(uhu;|&q)L4v4|cdT>SojiYlT;?i#OE>Nu-5DO$0p$*^}732*lAQcCsi0 zhuCi@oVYfl%Rovh9(B3mXher&cs9F-282apP-NPopjqAG!t`|tF1eWHS4go1GX%8K zM1m+C$oB6W_o@OWpb_;A4S#o)5OtY3uA?!vv?{m_^bbufrITrVpjj07t!%SGha+0O z1>@%f;kp9#m=L7Lv1ga20P$#*x>)#cP8a61G$-99NX}mncJ8SfP53<= zelIgot>Q+DFJ7S;aI}10iDyi8phKpDyM^$$lFJb>W}X?jJ{##d_z_Kt-#H-6D#LShhMb^ zJsp76v2$m_ZE)ar?5uFt6%}Q@80y)#FYDWPEIbUaYkKMi|5vq} zGgZ#@2Jku$0|aMy;I;VK>{e?Ai8v?Mv)S?aSOYa7g$X-zG|MJ?r9xCHUB@m-AU?uB(HvOR%*}c1(9Jb=@swZ%leJ^^N6U&arP> zIb_H6!{2o1?FZK8De0SHQU52-d(toR*t$bB+NWM(;++@ji!h_p9BD0Sj&t>CzZ6|qTNigherE5H z1q;=)_a*ikVM#eTwtvKi?l0u~W@yJMyHo#k9Csu ze(M42r`BJr%~rw64+^_|WT;8}&EJtV^bHlsy!(LUr{9s%?*Z3tmviZ*Qrx}U=y%`P zsAD;zv=KYn=!lwr6B!S+Mz0Adz5Nq%F3X+A`6SWa&(>q=P+IJMIade}-4?h+`wnR1 z7ML>@@pCQ9+&l)qDCaIdFXdbFiX3O^ebQHjy4lyfhLat|V;u+U-JS@KCsHco5a_nJ zX{Ws`@hCzWV%?6)xkUh#zwdRae0qaRX}^6W=i=U$(qcb$r=iSLI*rm@uhP$?bP7KY zKh?j|&3o19wzPmVly*OR7ioW7Ur)uOJf0!M_vYWv?)^&QTZy`Sjo)!j`>w5=Rn?Mz zJytPl!+k%>ISW91_QH)~-Pk&J{jOe?bB6&+8~m$OcTc};sh4w`uSjX3%~GG?5g9Ln ziXO+oqHMWxX~&Fw-4?XnSxu7IJ`>W zMkAj@fkk7If}5J2W8tTZ=U(!0mYf_qsn=sv8U@!KxObj{OP{UaWHS|<6S#N2g1b0f z!TkV?PL*IzQE=_G3T}i>!3}}msYW`&0SHe)crW}%5cdXf0(cWR3yc8&RlpJ82cTZB z;93BMkAkD`gy!MI=0f~&+u74;^rT0H*>f+=sADL-q4nIAoxH!>5BOwGor=war?xdqGn^=FiPLqzxj%VKl5 zIse|mESz5&o}ZJR8=jt*S(ue$2_HH*Jk0GMJS03fJ!27$=*@3U_8ccF9!_e?K_`Sq zgbfWF9G+pp(eJIVyvQ^eZWWs;g zJ=__47rY3ei3)B9;7Osi%Hto6`Q-6?@(-B`T>-2DJ^^-4fery)1daespflp%g!?db zJ<%s3yclSrcwi6G-T-z0hk@s#72Gl4AMktY4juCL27W_4>5kvGy)b{SN7k|V%X2c4 za;3)8@V#(o28TTdx#|>6J{D2If&?gTj`g0O z&-dYR9%OP-;?z`A!qnKYlM~|mL#Hk?(Q1yVDQ*>T+V@~%L=@|eqqxO7nKQ92ljy}{ zoSIGtozu*1y=(=t$;S0ANJy8CK?hG>;wceH;z2e~?}hz&U$PY1w9JLpn9tM2Ed}Nr z>VN`^h0mrl&%;=E9G>o0Yfxr4n}2tIS4;anj7i$xjRxib2>|WyW&qy%yYue6l;0Zx zsaW5U_cuVP&?!48j5sqn0zYbrVnbR_)bF5}ffIwrVoCGfjcDDmfr`aA`QD73VHkFW zc{mSWEplm_CkxWEJ@XHz_-C3jAeAf(KT|&Tw>XmCl%AV~)7!hJ=b5Er8J_mjA6#DOJ?2UjX_@}^?A^s!yDK8EzPcO`F+w8rG zv`|Z%4yHV0y!)B_q(|RCK93%K6Mk{7lm;K+?%i&%xyjb4g{crc4p89$Ao;R1LpWZt(Dsv>? z+lcEnm_8+$=XrNXKY6-WAUVz}uq+wdE>E^(BJu>LcmxVAC3JVL<|H)vxL1#cu{7!x3na#KhC>`?=_e0>)2h6}x{0uA< zkrAdTv9s8y!kir3k&!uu@uM&gNj76p$2KV>&{Z=$-OocJkV23h*1nNEu3VXgXYowP zqjx3`2^VIIUU#-BSUVsL2x}6q!!T#_BDF}CJ!=q;rGhr}ZQ&_&&qrG@#f*K|0z755 zMM3De*CW|t$!?2FSb`Rgqh+uyPTZZh1>F@9H|cG$vH2J);`x_EpCtEVG>9gdx zb1^;5W+V*kjUgm8{*LtQLQj=2CJXcOP`-N@LJo9aOrobzJnl=%Tkd8iJ$}#%ctZr* z)EZ9q_)svUj>cja1JMuSmt^H<6^!H;6cps+d#=|l!i^KE7&D25BqAgu?Gpmm! zAA9K0ILxaLJ*0cCzd>MeF7C_eBPAC0DVSd{dTQ*{B$M=3#YA@#CB&sNuMsLWS?qlb z&%YXocnlD4E)i8rHiE>diK(WjKsua8KDO_2+lJNc=sxbXIeumEe$%NotI}>{O?jr zSHysGj(O>gm&|~5n;E4O1)5A>!f`L$g)|dWpJ?l$P_;0noWFemR>GY0=xROiH z$ewU`enBRBnvsh~V{&jS&0lp3ZB_H397LCvBXLvTw)E!};LaKM>eV)zq+NPeCQHY4 zPuP-(yAijxFqvu6(G4^6^KY3hUDb4=o`FVG&? z--x++yd791u9{HgQcPivcigQ@YSkdErJ?aTh1uD;1-Nd>qh9#*40`oJD9)vtelu|o^uCmGV)%=L0p0r;l?z@%WTL zG!*ae6(8Ug-_9$ZKHVcj`8&e(@aZhZO7UI1;)A{7X*PN0kULuBgI8FseDKO#G{m1? zXM6bLW82nv&(|BNU7n9pDZigre$N9x#nUJ7|4(~o9~;GShVj`u8wdijB9KtWM9cRX z47RZgC^6>DnX?VXxPi7%hz?^P*l_;9cYvW(u`0KP2DP-MDphC$2t`UDN=xi2e;CCr zmO>LCriFx71ck&Qq%sYEK!AwWeV*NS)=Qy)C~0Yxk$(5g%)YxbH#_?=@9y2`?F?}? zW0(7|Cx4hHKgE-u>dC)Z{Z+d^sO!u)>&dd<-4C*EI!RBd+%&%hLOfaqcf|&wZrhdcV-dyM4C5wsGHJ!1i@J(_XhN<7`iD&ov z5NBE1-YpCEx)0OdTNccnfPD4=y{_8_u&(Z(T-WUbh_er9d$$k3UiY_uRn~bN`@1&b z+015)m7ejNpCEk+{2F;*`kupZ=tM9bpx|eRZ9Td@)*^n1?YoPvZeh5?P9y<+Rd}3gFpE z0%!9?8W-kTg=NL_B4xN$3C;Uz=>pHG_>K$3e7aI5WAVyzp4aVYMNIKp7r_YH%EMri zmlro97gzJS5%@w&BPH`fbLQVo(e5;IxI^R=a!g0)4a~5M;Y}oNAM7~2GpcG`q#{;c zU4zePd4o(XS6LUSsHs%d4XY!V7C4f?#Wa$ri@+ZcwI4>Q`dG|%?kN38DN+unPYpaB z30QN+J8n3NZz$4a6fW6+Hrr@qw+tH)!SMS=noz!VP91YmJqgYXy22 zjkTt(!S(SjcD>saH=9w<{?ZxtCvT@P?8TgKAif)W`XmHHFiNlp6{qh*c zQ0p!GNWdLAXUA-aRIQtshm#_`(ar(s9NyS{_q<)~0yFGSv<+tljW%LJPTPxLFqfmk zWxW%PThn-6!J!e2a0C<$*h5e}Fq(a@>SdoVakAnxoS2pqeSKNPnZ(?CI=l5!e2;W@ zZghAY%3bfo$T9JeGB$bK8S6499S;y|qu3kH)U^G_j~{Q9<(C$REX4Y|bE)H~!$U0# z7pXXBEydKmbq$=`w7wjU=Jj~D(720}WW2swE>(=x)WxfLzOm!g@j9g=Ix}7oTV-c5 z;%3I9F~w7MoLx1?>ArRnU69=_P(ueFuXoNeJBel4X^QVVL~BtH8vUlW}9 zpt7KLfQQiu0S2Au)lKI0A;}GrpKk}_Cc!b7X$QRfc|+iGORDkTl#>{PgiwL9dGm`G zN<}6?d4GNKkl!3F9QDL?p4Rdn9AvG>~CEI#s0zq#)XDVOVkZj@o?NgYl}nH!;B1Ha*N$(zk}VR!WR zz2%=ny0|oqtMqaOFPp-vGnkM?Pr{myS7l~}xl4NUoEcY{7od{@5709a@9nTo4DE`^`T9rvD6mPvY%eezP9y-44B-+iCj;esc=8Njt6Ats~2r zciI#8+9b*MVP3i??zOpDd?{?V1D30KQS!9?FHt{xyU;Sw2;Pu-{O*jiEJfOec5P^z z|HOWTla)8uI49$`;N_+EzE@4}OwC>yA z$bBvT^tGC+f|g(WX?>{i zF9jTI&~PaDvFv(46r8r6jU$C^gRtSOgP}~b)i=k;-d@Oj1Etu%K_wu%-2d?co7UMsUDZ zBY3$rNsTJP$oxXXmA-0Zk-AWOrH>i`U3taWsxthYYLd~Z0?Eg|J0f+?@Y%z$BzmRi z@+&>B7XGSGSv{AJ_6!`=&uSl$qMF0LvBk+N!kbq14Q9^7zrv31)44rmV8DOUYBV12 zx7^548Ofb$g1@t0t?@*l-uSYqhK0@^GctQF@9i<3-Co#p`MI9U2QX8ynuQZ~7$@(K z@P5weamnTw%pr53HEC>;8m@+^mhdF?SV$eaZ~!gS=^J;pDsN_=&cCMgo#a0`sL^=h z`K3mdn%LdBBFrV{I-jpHraxS7O#a{_qs3R$95&jP7OL0IJO_WCCw+dG^Q`oo->`ot zcTBx%=ICTZ7CCu!H$C29Jvyn+5QZ*YAxlIi+|B<=coB<=c{B<&N`LcfnU zxV|*WbbWV{cKv{o);>|a4ejIAY40-;=6Qa`W1G;Y=M67Em~8&>75sYWJ`R7&!+W_k z&a)Z%k{Ryf>V9rjvsM_E8Z@r23MK{ZLYhSFg!f4G?oMwHl4ffysxq>E5LSit;RmJ} z#hVJ%f%2dG@!Of}Ls_;`C13$~67Zf@TXa02tn~iM+6Hvq{ieD_24x@Fn=`oPZ1?Hp z8;*zjtAwnvYj26ya)kmYDG?Sx$r7OwN@79+N;V43P_jkX1|>U$Jy5bwXn~S8p#w?|3&)}4 zl+Xnw-NHpExhCLOJQf)s41tnVVKkJa3pr4dD-=LUiLd}lmI#$l;@lhi)T|_BF8aIA re95QGT^Y*UyjYnhHYl@rqcRU5|Al0~`7wTrv>ET<&VBUy_jLaOU$fT^ literal 0 HcmV?d00001 diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/02_designing_the_button/sketch.json b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/02_designing_the_button/sketch.json new file mode 100644 index 0000000..abdab11 --- /dev/null +++ b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/02_designing_the_button/sketch.json @@ -0,0 +1,6 @@ +{ + "cpu": { + "fqbn": "arduino:mbed_nano:nanorp2040connect", + "port": "" + } +} \ No newline at end of file diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/03_designing_a_menu/03_designing_a_menu.ino b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/03_creating_a_menu/03_creating_a_menu.ino similarity index 91% rename from examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/03_designing_a_menu/03_designing_a_menu.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/03_creating_a_menu/03_creating_a_menu.ino index 6f5d7e2..e5ab044 100644 --- a/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/03_designing_a_menu/03_designing_a_menu.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/03_creating_a_menu/03_creating_a_menu.ino @@ -1,53 +1,48 @@ -#include - -#define MARGIN_LEFT 0 -#define MARGIN_TOP 0 - -// Arduino Colors -#define COLOR_TEAL 0x00878F -#define COLOR_LIGHT_TEAL 0x62AEB2 -#define COLOR_ORANGE 0xE47128 -#define COLOR_YELLOW 0xE5AD24 -#define COLOR_WHITE 0xFFFFFF - -static const char * btnm_map[] = {"OPTION 1", "OPTION 2", "\n", - "OPTION 3", "OPTION 4", "\0" - }; - -void customMenu() { - Braccio.lvgl_lock(); - - static lv_style_t style_bg; - lv_style_init(&style_bg); - lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_LIGHT_TEAL)); - - static lv_style_t style_btn; - lv_style_init(&style_btn); - lv_style_set_bg_color(&style_btn, lv_color_hex(COLOR_WHITE)); - lv_style_set_border_color(&style_btn, lv_color_hex(COLOR_YELLOW)); - lv_style_set_border_width(&style_btn, 2); - lv_style_set_text_color(&style_btn, lv_color_hex(COLOR_TEAL)); - - - lv_obj_t * btnm1 = lv_btnmatrix_create(lv_scr_act()); - lv_btnmatrix_set_map(btnm1, btnm_map); - lv_obj_align(btnm1, LV_ALIGN_CENTER, MARGIN_LEFT, MARGIN_TOP); - - lv_obj_add_style(btnm1, &style_bg, 0); - lv_obj_add_style(btnm1, &style_btn, LV_PART_ITEMS); - - Braccio.lvgl_unlock(); -} - -void setup() { - // put your setup code here, to run once: - if (!Braccio.begin(customMenu)) { - if (Serial) Serial.println("Braccio.begin() failed."); - for(;;) { } - } -} - -void loop() { - // put your main code here, to run repeatedly: - -} +#include + +#define MARGIN_LEFT 0 +#define MARGIN_TOP 0 + +// Arduino Colors +#define COLOR_TEAL 0x00878F +#define COLOR_LIGHT_TEAL 0x62AEB2 +#define COLOR_ORANGE 0xE47128 +#define COLOR_YELLOW 0xE5AD24 +#define COLOR_WHITE 0xFFFFFF + +static const char * btnm_map[] = {"OPTION 1", "OPTION 2", "\n", + "OPTION 3", "OPTION 4", "\0" + }; + +void customMenu() { + Braccio.lvgl_lock(); + static lv_style_t style_bg; + lv_style_init(&style_bg); + lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_LIGHT_TEAL)); + + static lv_style_t style_btn; + lv_style_init(&style_btn); + lv_style_set_bg_color(&style_btn, lv_color_hex(COLOR_WHITE)); + lv_style_set_border_color(&style_btn, lv_color_hex(COLOR_YELLOW)); + lv_style_set_border_width(&style_btn, 2); + lv_style_set_text_color(&style_btn, lv_color_hex(COLOR_TEAL)); + + + lv_obj_t * btnm1 = lv_btnmatrix_create(lv_scr_act()); + lv_btnmatrix_set_map(btnm1, btnm_map); + lv_obj_align(btnm1, LV_ALIGN_CENTER, MARGIN_LEFT, MARGIN_TOP); + + lv_obj_add_style(btnm1, &style_bg, 0); + lv_obj_add_style(btnm1, &style_btn, LV_PART_ITEMS); + Braccio.lvgl_unlock(); +} + +void setup() { + // put your setup code here, to run once: + Braccio.begin(customMenu); +} + +void loop() { + // put your main code here, to run repeatedly: + +} diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/04_adding_an_extra_button/04_adding_an_extra_button.ino b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/04_testing_it_out/04_testing_it_out.ino similarity index 87% rename from examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/04_adding_an_extra_button/04_adding_an_extra_button.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/04_testing_it_out/04_testing_it_out.ino index 9f45754..12c0601 100644 --- a/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/04_adding_an_extra_button/04_adding_an_extra_button.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/04_testing_it_out/04_testing_it_out.ino @@ -1,53 +1,48 @@ -#include - -#define MARGIN_LEFT 0 -#define MARGIN_TOP 0 - -// Arduino Colors -#define COLOR_TEAL 0x00878F -#define COLOR_LIGHT_TEAL 0x62AEB2 -#define COLOR_ORANGE 0xE47128 -#define COLOR_YELLOW 0xE5AD24 - -static const char * btnm_map[] = {"OPTION 1", "OPTION 2", "OPTION 3", "\n", - "OPTION 4", "OPTION 5", "\0" - }; - -void customMenu() { - Braccio.lvgl_lock(); - - static lv_style_t style_bg; - lv_style_init(&style_bg); - lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_LIGHT_TEAL)); - - static lv_style_t style_btn; - lv_style_init(&style_btn); - lv_style_set_bg_color(&style_btn, lv_color_hex(0xFFFFFF)); - lv_style_set_border_color(&style_btn, lv_color_hex(COLOR_YELLOW)); - lv_style_set_border_width(&style_btn, 2); - lv_style_set_text_color(&style_btn, lv_color_hex(COLOR_TEAL)); - - - lv_obj_t * btnm1 = lv_btnmatrix_create(lv_scr_act()); - lv_btnmatrix_set_map(btnm1, btnm_map); - lv_btnmatrix_set_btn_width(btnm1, 3, 2); // Make "Option 4" twice as wide as "Option 5" - lv_obj_align(btnm1, LV_ALIGN_CENTER, MARGIN_LEFT, MARGIN_TOP); - - lv_obj_add_style(btnm1, &style_bg, 0); - lv_obj_add_style(btnm1, &style_btn, LV_PART_ITEMS); - - Braccio.lvgl_unlock(); -} - -void setup() { - // put your setup code here, to run once: - if (!Braccio.begin(customMenu)) { - if (Serial) Serial.println("Braccio.begin() failed."); - for(;;) { } - } -} - -void loop() { - // put your main code here, to run repeatedly: - -} +#include + +#define MARGIN_LEFT 0 +#define MARGIN_TOP 0 + +// Arduino Colors +#define COLOR_TEAL 0x00878F +#define COLOR_LIGHT_TEAL 0x62AEB2 +#define COLOR_ORANGE 0xE47128 +#define COLOR_YELLOW 0xE5AD24 + +static const char * btnm_map[] = {"OPTION 1", "OPTION 2", "OPTION 3", "\n", + "OPTION 4", "OPTION 5", "\0" + }; + +void customMenu() { + Braccio.lvgl_lock(); + static lv_style_t style_bg; + lv_style_init(&style_bg); + lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_LIGHT_TEAL)); + + static lv_style_t style_btn; + lv_style_init(&style_btn); + lv_style_set_bg_color(&style_btn, lv_color_hex(0xFFFFFF)); + lv_style_set_border_color(&style_btn, lv_color_hex(COLOR_YELLOW)); + lv_style_set_border_width(&style_btn, 2); + lv_style_set_text_color(&style_btn, lv_color_hex(COLOR_TEAL)); + + + lv_obj_t * btnm1 = lv_btnmatrix_create(lv_scr_act()); + lv_btnmatrix_set_map(btnm1, btnm_map); + lv_btnmatrix_set_btn_width(btnm1, 3, 2); // Make "Option 4" twice as wide as "Option 5" + lv_obj_align(btnm1, LV_ALIGN_CENTER, MARGIN_LEFT, MARGIN_TOP); + + lv_obj_add_style(btnm1, &style_bg, 0); + lv_obj_add_style(btnm1, &style_btn, LV_PART_ITEMS); + Braccio.lvgl_unlock(); +} + +void setup() { + // put your setup code here, to run once: + Braccio.begin(customMenu); +} + +void loop() { + // put your main code here, to run repeatedly: + +} diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/05_display_challenge/05_display_challenge.ino b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/05_display_challenge/05_display_challenge.ino index d29e555..9209311 100644 --- a/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/05_display_challenge/05_display_challenge.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/01-programming-the-braccio-display/05_display_challenge/05_display_challenge.ino @@ -15,7 +15,6 @@ static const char * btnm_map[] = {"BTN 1", "\n", void customMenu() { Braccio.lvgl_lock(); - static lv_style_t style_bg; lv_style_init(&style_bg); lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_BG)); @@ -35,16 +34,12 @@ void customMenu() { lv_obj_add_style(btnm1, &style_bg, 0); lv_obj_add_style(btnm1, &style_btn, LV_PART_ITEMS); - Braccio.lvgl_unlock(); } void setup() { // put your setup code here, to run once: - if (!Braccio.begin(customMenu)) { - if (Serial) Serial.println("Braccio.begin() failed."); - for(;;) { } - } + Braccio.begin(customMenu); } void loop() { diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/01_playing_with_the_Joystick/01_playing_with_the_Joystick.ino b/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/01_playing_with_the_Joystick/01_playing_with_the_Joystick.ino index 6911840..70fd320 100644 --- a/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/01_playing_with_the_Joystick/01_playing_with_the_Joystick.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/01_playing_with_the_Joystick/01_playing_with_the_Joystick.ino @@ -14,7 +14,7 @@ String checkJoystick(int input){ void setup() { Serial.begin(115200); - while (!Serial) {} + while(!Serial){} Braccio.begin(); Serial.println("Press any button or move the joystick."); } @@ -22,7 +22,7 @@ void setup() { void loop() { int joystickPos = Braccio.getKey(); message = checkJoystick(joystickPos); - if (message != "") { + if(message != ""){ Serial.println(message); message = ""; } diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/02_handling_events_in_the_menu/02_handling_events_in_the_menu.ino b/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/02_handling_events_in_the_menu/02_handling_events_in_the_menu.ino index 7e200d3..45c392b 100644 --- a/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/02_handling_events_in_the_menu/02_handling_events_in_the_menu.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/02_handling_events_in_the_menu/02_handling_events_in_the_menu.ino @@ -15,9 +15,8 @@ static const char * btnm_map[] = {"Option 1", "Option 2", "\n", "Option 5", "Option 6", "\0" }; -static void eventHandler(lv_event_t * e){ +static void eventHandler(lv_event_t * e) { Braccio.lvgl_lock(); - lv_event_code_t code = lv_event_get_code(e); lv_obj_t * obj = lv_event_get_target(e); if (code == LV_EVENT_PRESSED) { @@ -27,13 +26,11 @@ static void eventHandler(lv_event_t * e){ LV_LOG_USER("%s was selected\n", txt); Serial.println(String(txt) + " was selected."); } - Braccio.lvgl_unlock(); } -void customMenu(){ +void customMenu() { Braccio.lvgl_lock(); - static lv_style_t style_bg; lv_style_init(&style_bg); lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_WHITE)); @@ -63,17 +60,13 @@ void customMenu(){ lv_btnmatrix_set_one_checked(btnm1, true); lv_obj_add_event_cb(btnm1, eventHandler, LV_EVENT_ALL, NULL); - Braccio.lvgl_unlock(); - + Braccio.connectJoystickTo(btnm1); } void setup() { - if (!Braccio.begin(customMenu)) { - if (Serial) Serial.println("Braccio.begin() failed."); - for(;;) { } - } + Braccio.begin(customMenu); } void loop() { diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/03_navigate_challenge_I/03_navigate_challenge_I.ino b/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/03_navigate_challenge_I/03_navigate_challenge_I.ino index 9891585..a531642 100644 --- a/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/03_navigate_challenge_I/03_navigate_challenge_I.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/03_navigate_challenge_I/03_navigate_challenge_I.ino @@ -17,7 +17,6 @@ static const char * btnm_map[] = {"Option 1", "Option 2", "\n", static void eventHandler(lv_event_t * e) { Braccio.lvgl_lock(); - lv_event_code_t code = lv_event_get_code(e); lv_obj_t * obj = lv_event_get_target(e); if (code == LV_EVENT_PRESSING) { @@ -27,13 +26,11 @@ static void eventHandler(lv_event_t * e) { LV_LOG_USER("%s is pressed\n", txt); Serial.println(String(txt) + " is pressed."); } - Braccio.lvgl_unlock(); } void customMenu() { Braccio.lvgl_lock(); - static lv_style_t style_bg; lv_style_init(&style_bg); lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_LIGHT_TEAL)); @@ -63,17 +60,13 @@ void customMenu() { lv_btnmatrix_set_one_checked(btnm1, true); lv_obj_add_event_cb(btnm1, eventHandler, LV_EVENT_ALL, NULL); + Braccio.lvgl_unlock(); Braccio.connectJoystickTo(btnm1); - - Braccio.lvgl_unlock(); } void setup() { - if (!Braccio.begin(customMenu)) { - if (Serial) Serial.println("Braccio.begin() failed."); - for(;;) { } - } + Braccio.begin(customMenu); } void loop() { diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/04_navigate_challenge_II/04_navigate_challenge_II.ino b/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/04_navigate_challenge_II/04_navigate_challenge_II.ino index 10ad8f5..63358b2 100644 --- a/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/04_navigate_challenge_II/04_navigate_challenge_II.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/02-navigatting-the-display-menu/04_navigate_challenge_II/04_navigate_challenge_II.ino @@ -17,7 +17,6 @@ static const char * btnm_map[] = {"Option 1", "Option 2", "\n", static void eventHandler(lv_event_t * e) { Braccio.lvgl_lock(); - lv_event_code_t code = lv_event_get_code(e); lv_obj_t * obj = lv_event_get_target(e); if (code == LV_EVENT_RELEASED) { @@ -27,13 +26,11 @@ static void eventHandler(lv_event_t * e) { LV_LOG_USER("%s was released\n", txt); Serial.println(String(txt) + " was released."); } - Braccio.lvgl_unlock(); } void customMenu() { Braccio.lvgl_lock(); - static lv_style_t style_bg; lv_style_init(&style_bg); lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_LIGHT_TEAL)); @@ -63,17 +60,13 @@ void customMenu() { lv_btnmatrix_set_one_checked(btnm1, true); lv_obj_add_event_cb(btnm1, eventHandler, LV_EVENT_ALL, NULL); - Braccio.lvgl_unlock(); Braccio.connectJoystickTo(btnm1); } void setup() { - if (!Braccio.begin(customMenu)) { - if (Serial) Serial.println("Braccio.begin() failed."); - for(;;) { } - } + Braccio.begin(customMenu); } void loop() { diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/01_playing_with_the_motors/01_playing_with_the_motors.ino b/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/01_playing_with_the_motors/01_playing_with_the_motors.ino index 07c8a1f..6b7399f 100644 --- a/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/01_playing_with_the_motors/01_playing_with_the_motors.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/01_playing_with_the_motors/01_playing_with_the_motors.ino @@ -1,28 +1,24 @@ #include -int motorID = 0; +int motorID= 0; void setup() { - if (!Braccio.begin()) { - if (Serial) Serial.println("Braccio.begin() failed."); - for(;;) { } - } + Braccio.begin(); delay(500); - + Serial.begin(115200); - while (!Serial) {} + while(!Serial){} } void loop() { Serial.println("To start, send any key to the serial port:"); - while ((Serial.available() <= 0)) {}; + while((Serial.available() <= 0)){}; Serial.read(); // Clear the serial buffer - Serial.read(); // It is necessary to clean '\n' - - for (motorID = 1; motorID <= 6; motorID++) { + + for(motorID = 1; motorID <=6; motorID++){ Serial.println("\nMoving the motor " + String(motorID)); Serial.println("Current angle 0.0 (zero)"); - + Braccio.move(motorID).to(0.0f); delay(2000); // delay between movements diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/02_selecting_each_motor/02_selecting_each_motor.ino b/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/02_selecting_the_motor_with_the_enter_button/02_selecting_the_motor_with_the_enter_button.ino similarity index 71% rename from examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/02_selecting_each_motor/02_selecting_each_motor.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/02_selecting_the_motor_with_the_enter_button/02_selecting_the_motor_with_the_enter_button.ino index 83dac2f..c3f2270 100644 --- a/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/02_selecting_each_motor/02_selecting_each_motor.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/02_selecting_the_motor_with_the_enter_button/02_selecting_the_motor_with_the_enter_button.ino @@ -7,63 +7,60 @@ boolean movement = false; float initialAngle = 0.0; void setup() { - if (!Braccio.begin()) { - if (Serial) Serial.println("Braccio.begin() failed."); - for(;;) { } - } + Braccio.begin(); delay(500); // Waits for the Braccio initialization // Sets the initial angle for the motors - for (int i = 1; i <= 6; i++) { + for(int i = 1; i <= 6; i++){ Braccio.move(i).to(0.0f); delay(1000); // Necessary to set the motor ID correctly } - + Serial.begin(115200); - + Serial.println("Press the Enter Button to select the motor 1."); } void loop() { // Check if the control key pressed is the Enter Button - if (Braccio.getKey() == BUTTON_ENTER) { - - if (motorID <= 6) { - + if(Braccio.getKey() == BUTTON_ENTER){ + + if(motorID <= 6){ + motorID++; // Increment the ID - - if (motorID > 6) { + + if(motorID > 6){ motorID = 1; // Restart the ID to motor 1 } } - + movement = true; // Flag allows the motor to move - - while (Braccio.getKey() == BUTTON_ENTER); // Avoids more than one increment + + while(Braccio.getKey() == BUTTON_ENTER); // Avoids more than one increment Serial.println("Motor " + String(motorID) + " selected."); } - if (movement) { - - for (float angle = 0.0; angle <= 315.0; angle += 45.0) { + if(movement){ + + for (float angle = 0.0; angle <= 315.0; angle+=45.0){ Braccio.move(motorID).to(angle); - + Serial.println("Motor " + String(motorID) + " - current angle: " + String(angle)); delay(250); } delay(500); - - for (float angle = 315.0; angle >= 0.0; angle -= 45.0) { + + for (float angle = 315.0; angle >= 0.0; angle-=45.0){ Braccio.move(motorID).to(angle); - + Serial.println("Motor " + String(motorID) + " - current angle: " + String(angle)); delay(250); } - + movement = false; - + Serial.println("\n\nPress the Enter Button to select the next motor.\n\n"); } } diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/03_servo_motors_using_the_joystick/03_servo_motors_using_the_joystick.ino b/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/03_moving_the_motors_with_the_joystick/03_moving_the_motors_with_the_joystick.ino similarity index 93% rename from examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/03_servo_motors_using_the_joystick/03_servo_motors_using_the_joystick.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/03_moving_the_motors_with_the_joystick/03_moving_the_motors_with_the_joystick.ino index a9b350a..10b5be0 100644 --- a/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/03_servo_motors_using_the_joystick/03_servo_motors_using_the_joystick.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/03_moving_the_motors_with_the_joystick/03_moving_the_motors_with_the_joystick.ino @@ -12,10 +12,7 @@ float initialAngle = SmartServoClass::MAX_ANGLE / 2.0f; // 315 degrees / 2 = 157 float currentAngle = initialAngle; void setup() { - if (!Braccio.begin()) { - if (Serial) Serial.println("Braccio.begin() failed."); - for(;;) { } - } + Braccio.begin(); // Initialize Braccio delay(500); // Waits for the Braccio initialization diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/04_servo_motors_challenge/04_servo_motors_challenge.ino b/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/04_servo_motors_challenge/04_servo_motors_challenge.ino index c8407f5..04503c1 100644 --- a/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/04_servo_motors_challenge/04_servo_motors_challenge.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/03-playing-with-the-motors/04_servo_motors_challenge/04_servo_motors_challenge.ino @@ -12,10 +12,7 @@ float initialAngle = SmartServoClass::MAX_ANGLE / 2.0f; float currentAngle = initialAngle; void setup() { - if (!Braccio.begin()) { - if (Serial) Serial.println("Braccio.begin() failed."); - for(;;) { } - } + Braccio.begin(); delay(500); // Waits for the Braccio initialization // Sets the initial angle for the motors diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/01_designing_a_gauge_interface/01_designing_a_gauge_interface.ino b/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/01_playing_with_a_joint_angle_gauge/01_playing_with_a_joint_angle_gauge.ino similarity index 94% rename from examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/01_designing_a_gauge_interface/01_designing_a_gauge_interface.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/01_playing_with_a_joint_angle_gauge/01_playing_with_a_joint_angle_gauge.ino index 6e6101b..9bdc746 100644 --- a/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/01_designing_a_gauge_interface/01_designing_a_gauge_interface.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/01_playing_with_a_joint_angle_gauge/01_playing_with_a_joint_angle_gauge.ino @@ -22,18 +22,16 @@ lv_meter_indicator_t * indic; static void eventHandlerMeter(lv_event_t * e) { - Braccio.lvgl_lock(); - /* Set the meter value */ + Braccio.lvgl_lock(); lv_meter_set_indicator_end_value(meter, indic, (int32_t)angles[motorID - 1]); - Braccio.lvgl_unlock(); } -void meterScreen(void) { +void meterScreen(void) +{ Braccio.lvgl_lock(); - meter = lv_meter_create(lv_scr_act()); lv_obj_center(meter); @@ -57,17 +55,14 @@ void meterScreen(void) { indic = lv_meter_add_arc(meter, scale, 10, lv_color_hex(COLOR_LIGHT_TEAL), 0); lv_obj_add_event_cb(meter, eventHandlerMeter, LV_EVENT_KEY, NULL); - Braccio.lvgl_unlock(); Braccio.connectJoystickTo(meter); } void setup() { - if (!Braccio.begin(meterScreen)) { - if (Serial) Serial.println("Braccio.begin() failed."); - for(;;) { } - } + Braccio.begin(meterScreen); + delay(500); // Waits for the Braccio initialization // Sets the initial angle for the motors diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/02_completing_the_screen_ui/02_completing_the_screen_ui.ino b/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/02_selecting_the_motor_in_the_LCD_menu/02_selecting_the_motor_in_the_LCD_menu.ino similarity index 95% rename from examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/02_completing_the_screen_ui/02_completing_the_screen_ui.ino rename to examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/02_selecting_the_motor_in_the_LCD_menu/02_selecting_the_motor_in_the_LCD_menu.ino index 2223e02..a682875 100644 --- a/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/02_completing_the_screen_ui/02_completing_the_screen_ui.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/02_selecting_the_motor_in_the_LCD_menu/02_selecting_the_motor_in_the_LCD_menu.ino @@ -33,8 +33,6 @@ lv_meter_indicator_t * indic; // Indication of selected motor angle // Event Handlers static void eventHandlerMeter(lv_event_t * e) { - Braccio.lvgl_lock(); - uint32_t pressed_key = Braccio.getKey(); if (pressed_key == BUTTON_ENTER) { @@ -45,13 +43,9 @@ static void eventHandlerMeter(lv_event_t * e) { else { lv_meter_set_indicator_end_value(meter, indic, (int32_t)angles[motorID - 1]); } - - Braccio.lvgl_unlock(); } static void eventHandlerMenu(lv_event_t * e) { - Braccio.lvgl_lock(); - lv_obj_t * obj = lv_event_get_target(e); uint32_t id = lv_btnmatrix_get_selected_btn(obj); @@ -59,14 +53,12 @@ static void eventHandlerMenu(lv_event_t * e) { currentAngle = angles[motorID - 1]; meterScreen(); // Load meter screen lv_obj_del(btnm); // Delete the object - - Braccio.lvgl_unlock(); } // Screens functions -void meterScreen(void) { +void meterScreen(void) +{ Braccio.lvgl_lock(); - meter = lv_meter_create(lv_scr_act()); lv_obj_center(meter); @@ -92,7 +84,6 @@ void meterScreen(void) { lv_obj_add_event_cb(meter, eventHandlerMeter, LV_EVENT_KEY, NULL); lv_meter_set_indicator_end_value(meter, indic, (int32_t)angles[motorID - 1]); - Braccio.lvgl_unlock(); Braccio.connectJoystickTo(meter); @@ -100,7 +91,6 @@ void meterScreen(void) { void motorMenu() { Braccio.lvgl_lock(); - static lv_style_t style_bg; lv_style_init(&style_bg); lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_WHITE)); @@ -129,17 +119,14 @@ void motorMenu() { lv_btnmatrix_set_one_checked(btnm, true); lv_obj_add_event_cb(btnm, eventHandlerMenu, LV_EVENT_PRESSED, NULL); - Braccio.lvgl_unlock(); Braccio.connectJoystickTo(btnm); } void setup() { - if (!Braccio.begin(motorMenu)) { - if (Serial) Serial.println("Braccio.begin() failed."); - for(;;) { } - } + Braccio.begin(motorMenu); + delay(5000); // Waits for the Braccio initialization // Sets the initial angle for the motors diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/03_learnings_challenge_I/03_learnings_challenge_I.ino b/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/03_learnings_challenge_I/03_learnings_challenge_I.ino index f36e9cc..c09064b 100644 --- a/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/03_learnings_challenge_I/03_learnings_challenge_I.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/03_learnings_challenge_I/03_learnings_challenge_I.ino @@ -17,7 +17,7 @@ // Variables int motorID = 0; // Selected motor ID -float initialAngle = SmartServoClass::MAX_ANGLE / 2.0f; +float initialAngle = 0.0; float currentAngle = initialAngle; // Selected motor current angle float angles[6]; // All motors current angles @@ -33,8 +33,6 @@ lv_meter_indicator_t * indic; // Indication of selected motor angle // Event Handlers static void eventHandlerMeter(lv_event_t * e) { - Braccio.lvgl_lock(); - uint32_t pressed_key = Braccio.getKey(); if (pressed_key == BUTTON_ENTER) { @@ -45,13 +43,9 @@ static void eventHandlerMeter(lv_event_t * e) { else { lv_meter_set_indicator_end_value(meter, indic, (int32_t)angles[motorID - 1]); } - - Braccio.lvgl_unlock(); } static void eventHandlerMenu(lv_event_t * e) { - Braccio.lvgl_lock(); - lv_obj_t * obj = lv_event_get_target(e); uint32_t id = lv_btnmatrix_get_selected_btn(obj); @@ -59,14 +53,12 @@ static void eventHandlerMenu(lv_event_t * e) { currentAngle = angles[motorID - 1]; meterScreen(); lv_obj_del(btnm); - - Braccio.lvgl_unlock(); } // Screens functions -void meterScreen(void) { +void meterScreen(void) +{ Braccio.lvgl_lock(); - meter = lv_meter_create(lv_scr_act()); lv_obj_center(meter); @@ -92,7 +84,6 @@ void meterScreen(void) { lv_obj_add_event_cb(meter, eventHandlerMeter, LV_EVENT_KEY, NULL); lv_meter_set_indicator_end_value(meter, indic, (int32_t)angles[motorID - 1]); - Braccio.lvgl_unlock(); Braccio.connectJoystickTo(meter); @@ -100,7 +91,6 @@ void meterScreen(void) { void motorMenu() { Braccio.lvgl_lock(); - static lv_style_t style_bg; lv_style_init(&style_bg); lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_WHITE)); @@ -129,17 +119,14 @@ void motorMenu() { lv_btnmatrix_set_one_checked(btnm, true); lv_obj_add_event_cb(btnm, eventHandlerMenu, LV_EVENT_PRESSED, NULL); - Braccio.lvgl_unlock(); Braccio.connectJoystickTo(btnm); } void setup() { - if (!Braccio.begin(motorMenu)) { - if (Serial) Serial.println("Braccio.begin() failed."); - for(;;) { } - } + Braccio.begin(motorMenu); + delay(500); // Waits for the Braccio initialization // Sets the initial angle for the motors diff --git a/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/04_learnings_challenge_II/04_learnings_challenge_II.ino b/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/04_learnings_challenge_II/04_learnings_challenge_II.ino index 3b22970..ade5d8c 100644 --- a/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/04_learnings_challenge_II/04_learnings_challenge_II.ino +++ b/examples/Platform_Tutorials/lessons/Basic_codes/04-integration-of-previous-learnings/04_learnings_challenge_II/04_learnings_challenge_II.ino @@ -17,7 +17,7 @@ // Variables int motorID = 0; // Selected motor ID -float initialAngle = SmartServoClass::MAX_ANGLE / 2.0f; +float initialAngle = 0.0; float currentAngle = initialAngle; // Selected motor current angle float angles[6]; // All motors current angles @@ -33,8 +33,6 @@ lv_meter_indicator_t * indic; // Indication of selected motor angle // Event Handlers static void eventHandlerMeter(lv_event_t * e) { - Braccio.lvgl_lock(); - uint32_t pressed_key = Braccio.getKey(); if (pressed_key == BUTTON_ENTER) { @@ -45,13 +43,9 @@ static void eventHandlerMeter(lv_event_t * e) { else { lv_meter_set_indicator_end_value(meter, indic, (int32_t)angles[motorID - 1]); } - - Braccio.lvgl_unlock(); } static void eventHandlerMenu(lv_event_t * e) { - Braccio.lvgl_lock(); - lv_obj_t * obj = lv_event_get_target(e); uint32_t id = lv_btnmatrix_get_selected_btn(obj); @@ -59,14 +53,12 @@ static void eventHandlerMenu(lv_event_t * e) { currentAngle = angles[motorID - 1]; meterScreen(); lv_obj_del(btnm); - - Braccio.lvgl_unlock(); } // Screens functions -void meterScreen(void) { +void meterScreen(void) +{ Braccio.lvgl_lock(); - meter = lv_meter_create(lv_scr_act()); lv_obj_center(meter); @@ -92,7 +84,6 @@ void meterScreen(void) { lv_obj_add_event_cb(meter, eventHandlerMeter, LV_EVENT_KEY, NULL); lv_meter_set_indicator_end_value(meter, indic, (int32_t)angles[motorID - 1]); - Braccio.lvgl_unlock(); Braccio.connectJoystickTo(meter); @@ -100,7 +91,6 @@ void meterScreen(void) { void motorMenu() { Braccio.lvgl_lock(); - static lv_style_t style_bg; lv_style_init(&style_bg); lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_WHITE)); @@ -129,17 +119,14 @@ void motorMenu() { lv_btnmatrix_set_one_checked(btnm, true); lv_obj_add_event_cb(btnm, eventHandlerMenu, LV_EVENT_PRESSED, NULL); - Braccio.lvgl_unlock(); Braccio.connectJoystickTo(btnm); } void setup() { - if (!Braccio.begin(motorMenu)) { - if (Serial) Serial.println("Braccio.begin() failed."); - for(;;) { } - } + Braccio.begin(motorMenu); + delay(500); // Waits for the Braccio initialization // Sets the initial angle for the motors From 3c3cc21134ea84bc92e04dbc2687625bd03ec8d4 Mon Sep 17 00:00:00 2001 From: Esquirio Date: Wed, 31 Aug 2022 13:54:18 +0200 Subject: [PATCH 29/41] fix: removing the speed function from the codes --- .../Braccio_moving_range_angles.ino | 2 - .../01_aligning_braccio.ino | 53 +++++++++------ .../02_waving_with_Braccio.ino | 64 ++++++++++++------- .../03_moving_challenge.ino | 56 ++++++++++------ 4 files changed, 112 insertions(+), 63 deletions(-) diff --git a/examples/Platform_Tutorials/lessons/03-important-programming-concepts/Braccio_moving_range_angles/Braccio_moving_range_angles.ino b/examples/Platform_Tutorials/lessons/03-important-programming-concepts/Braccio_moving_range_angles/Braccio_moving_range_angles.ino index 5d22936..7206a1b 100644 --- a/examples/Platform_Tutorials/lessons/03-important-programming-concepts/Braccio_moving_range_angles/Braccio_moving_range_angles.ino +++ b/examples/Platform_Tutorials/lessons/03-important-programming-concepts/Braccio_moving_range_angles/Braccio_moving_range_angles.ino @@ -38,10 +38,8 @@ float angles[6]; void setup() { if (Braccio.begin()) { - /* Configure Braccio speed. */ /* Warning: keep a safe distance from the robot and watch out for the robot's movement. It could be speedy and hit someone. */ - Braccio.speed(speed_grade_t(1000)/*SLOW*/); /* Move to home position. */ Braccio.moveTo(HOME_POS[0], HOME_POS[1], HOME_POS[2], HOME_POS[3], HOME_POS[4], HOME_POS[5]); delay(TIME_DELAY); diff --git a/examples/Platform_Tutorials/projects/p01-moving-braccio/01_aligning_braccio/01_aligning_braccio.ino b/examples/Platform_Tutorials/projects/p01-moving-braccio/01_aligning_braccio/01_aligning_braccio.ino index b06b096..dee140c 100644 --- a/examples/Platform_Tutorials/projects/p01-moving-braccio/01_aligning_braccio/01_aligning_braccio.ino +++ b/examples/Platform_Tutorials/projects/p01-moving-braccio/01_aligning_braccio/01_aligning_braccio.ino @@ -1,6 +1,19 @@ +/************************************************************************************** + * INCLUDE + **************************************************************************************/ + #include -// Variables +/************************************************************************************** + * DEFINES + **************************************************************************************/ + +#define TIME_DELAY 1000 + +/************************************************************************************** + * GLOBAL VARIABLES + **************************************************************************************/ + // Braccio ++ joints auto gripper = Braccio.get(1); auto wristRoll = Braccio.get(2); @@ -9,28 +22,28 @@ auto elbow = Braccio.get(4); auto shoulder = Braccio.get(5); auto base = Braccio.get(6); -float initialGripper = 160.0; float initialBase = 90.0; -float initialAngle = 150.0; +float initialAngle = 157.5; + float angles[6]; +/************************************************************************************** + * SETUP/LOOP + **************************************************************************************/ + void setup() { - Braccio.begin(); - delay(500); // Waits for the Braccio initialization - - // Send motors initial angle - gripper.move().to(initialGripper); - delay(100); - wristRoll.move().to(initialAngle); - delay(100); - wristPitch.move().to(initialAngle); - delay(100); - elbow.move().to(initialAngle); - delay(100); - shoulder.move().to(initialAngle); - delay(100); - base.move().to(initialBase); - delay(100); + if (Braccio.begin()){ + /* Warning: keep a safe distance from the robot and watch out for the robot's + movement. It could be speedy and hit someone. */ + + /* Move to home position. */ + gripper.move().to(initialAngle); delay(TIME_DELAY); + wristRoll.move().to(initialAngle); delay(TIME_DELAY); + wristPitch.move().to(initialAngle); delay(TIME_DELAY); + elbow.move().to(initialAngle); delay(TIME_DELAY); + shoulder.move().to(initialAngle); delay(TIME_DELAY); + base.move().to(initialBase); delay(TIME_DELAY); + } Serial.begin(115200); while(!Serial){} @@ -53,5 +66,5 @@ void loop() { Serial.println("*****************************************\n\n\n\n\n"); Serial.println("\n\n\n\n"); - delay(1000); + delay(TIME_DELAY); } diff --git a/examples/Platform_Tutorials/projects/p01-moving-braccio/02_waving_with_Braccio/02_waving_with_Braccio.ino b/examples/Platform_Tutorials/projects/p01-moving-braccio/02_waving_with_Braccio/02_waving_with_Braccio.ino index f837495..de1a0fd 100644 --- a/examples/Platform_Tutorials/projects/p01-moving-braccio/02_waving_with_Braccio/02_waving_with_Braccio.ino +++ b/examples/Platform_Tutorials/projects/p01-moving-braccio/02_waving_with_Braccio/02_waving_with_Braccio.ino @@ -1,7 +1,27 @@ +/************************************************************************************** + * INCLUDE + **************************************************************************************/ + #include +/************************************************************************************** + * DEFINES + **************************************************************************************/ + #define BUTTON_ENTER 6 +#define TIME_DELAY 1000 + +/************************************************************************************** + * CONSTANTS + **************************************************************************************/ + +float const HOME_POS[6] = {157.5, 157.5, 157.5, 157.5, 157.5, 90.0}; +float const WAVE_POS[6] = {180.0, 260.0, 157.5, 157.5, 157.5, 180.0}; +/************************************************************************************** + * GLOBAL VARIABLES + **************************************************************************************/ + // Braccio ++ joints auto gripper = Braccio.get(1); auto wristRoll = Braccio.get(2); @@ -10,24 +30,27 @@ auto elbow = Braccio.get(4); auto shoulder = Braccio.get(5); auto base = Braccio.get(6); -/* Variables */ -// initialAngles[6] = {gripper, wristRoll, wristPitch, elbow, shoulder, base} -float homePos[6] = {160.0, 150.0, 220.0, 220.0, 100.0, 180.0}; -float wavePos[6] = {180.0, 250.0, 145.0, 150.0, 150.0, 90.0}; - bool movement = false; // Flag to initialize joints' movements +/************************************************************************************** + * SETUP/LOOP + **************************************************************************************/ + void setup() { - Braccio.begin(); - delay(500); // Waits for the Braccio initialization + if (Braccio.begin()){ + /* Warning: + Keep a safe distance from the robot until you make sure the code is properly + working. Be mindful of the robot’s movement prior to that, as it could be + speedy and accidentally hit someone. + */ - // Set motors initial angle - // Should move all the motors at once - Braccio.moveTo(homePos[0], homePos[1], homePos[2], homePos[3], homePos[4], homePos[5]); - delay(500); + /* Move to home position. */ + Braccio.moveTo(HOME_POS[0], HOME_POS[1], HOME_POS[2], HOME_POS[3], HOME_POS[4], HOME_POS[5]); + delay(TIME_DELAY); + } } -// Waving whit Wrist pitch +// Waving with Wrist pitch void loop() { int pressedKey = Braccio.getKey(); @@ -35,16 +58,13 @@ void loop() { movement = true; // Trigger joints' movements if (movement) { - Braccio.moveTo(wavePos[0], wavePos[1], wavePos[2], wavePos[3], wavePos[4], wavePos[5]); - delay(1000); - - for (int i = 1; i <= 10; i++) { - wristPitch.move().to(100.0f); - delay(300); - wristPitch.move().to(190.0f); - delay(600); - wristPitch.move().to(145.0f); - delay(300); + Braccio.moveTo(WAVE_POS[0], WAVE_POS[1], WAVE_POS[2], WAVE_POS[3], WAVE_POS[4], WAVE_POS[5]); + delay(TIME_DELAY/10); + + for (int i = 1; i <= 5; i++) { + wristPitch.move().to(120.0f); delay(TIME_DELAY/2); + wristPitch.move().to(200.0f); delay(TIME_DELAY); + wristPitch.move().to(WAVE_POS[3]); } movement = false; // Stop joints' movements diff --git a/examples/Platform_Tutorials/projects/p01-moving-braccio/03_moving_challenge/03_moving_challenge.ino b/examples/Platform_Tutorials/projects/p01-moving-braccio/03_moving_challenge/03_moving_challenge.ino index 138d7d7..cee77a0 100644 --- a/examples/Platform_Tutorials/projects/p01-moving-braccio/03_moving_challenge/03_moving_challenge.ino +++ b/examples/Platform_Tutorials/projects/p01-moving-braccio/03_moving_challenge/03_moving_challenge.ino @@ -1,6 +1,26 @@ +/************************************************************************************** + * INCLUDE + **************************************************************************************/ + #include +/************************************************************************************** + * DEFINES + **************************************************************************************/ + #define BUTTON_ENTER 6 +#define TIME_DELAY 1000 + +/************************************************************************************** + * CONSTANTS + **************************************************************************************/ + +static float const HOME_POS[6] = {157.5, 157.5, 157.5, 157.5, 157.5, 90.0}; +static float const AGREE_POS[6] = {160.0, 160.0, 210.0, 240.0, 100.0, 180.0}; + +/************************************************************************************** + * GLOBAL VARIABLES + **************************************************************************************/ // Braccio ++ joints auto gripper = Braccio.get(1); @@ -10,20 +30,21 @@ auto elbow = Braccio.get(4); auto shoulder = Braccio.get(5); auto base = Braccio.get(6); -/* Variables */ -// initialAngles[6] = {gripper, wristRoll, wristPitch, elbow, shoulder, base} -float homePos[6] = {160.0, 150.0, 220.0, 220.0, 100.0, 180.0}; - bool movement = false; // Flag to initialize joints' movements +/************************************************************************************** + * SETUP/LOOP + **************************************************************************************/ + void setup() { - Braccio.begin(); - delay(500); // Waits for the Braccio initialization + if (Braccio.begin()){ + /* Warning: keep a safe distance from the robot and watch out for the robot's + movement. It could be speedy and hit someone. */ - // Set motors initial angle - // Should move all the motors at once - Braccio.moveTo(homePos[0], homePos[1], homePos[2], homePos[3], homePos[4], homePos[5]); - delay(500); + /* Move to home position. */ + Braccio.moveTo(HOME_POS[0], HOME_POS[1], HOME_POS[2], HOME_POS[3], HOME_POS[4], HOME_POS[5]); + delay(500); + } } void loop() { @@ -33,18 +54,15 @@ void loop() { movement = true; // Trigger joints' movements if (movement) { - Braccio.moveTo(160.0, 150.0, 220.0, 220.0, 100.0, 270.0); - delay(1000); + Braccio.moveTo(AGREE_POS[0], AGREE_POS[1], AGREE_POS[2], AGREE_POS[3], AGREE_POS[4], AGREE_POS[5]); + delay(TIME_DELAY/10); for (int i = 1; i <= 10; i++) { - wristPitch.move().to(190.0f); - delay(200); - wristPitch.move().to(250.0f); - delay(400); - wristPitch.move().to(220.0f); - delay(200); + wristPitch.move().to(190.0f); delay(TIME_DELAY/2); + wristPitch.move().to(240.0f); delay(TIME_DELAY); + wristPitch.move().to(AGREE_POS[3]); } - movement = false; // Stop joints' moviments + movement = false; // Stop joints' movements } } From aaa8653b02518b09b85e32005ba7ff7b09514640 Mon Sep 17 00:00:00 2001 From: Esquirio Date: Wed, 31 Aug 2022 13:58:56 +0200 Subject: [PATCH 30/41] fix: fixing waving_with_braccio code --- .../02_waving_with_Braccio/02_waving_with_Braccio.ino | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/examples/Platform_Tutorials/projects/p01-moving-braccio/02_waving_with_Braccio/02_waving_with_Braccio.ino b/examples/Platform_Tutorials/projects/p01-moving-braccio/02_waving_with_Braccio/02_waving_with_Braccio.ino index de1a0fd..f969acb 100644 --- a/examples/Platform_Tutorials/projects/p01-moving-braccio/02_waving_with_Braccio/02_waving_with_Braccio.ino +++ b/examples/Platform_Tutorials/projects/p01-moving-braccio/02_waving_with_Braccio/02_waving_with_Braccio.ino @@ -59,11 +59,11 @@ void loop() { if (movement) { Braccio.moveTo(WAVE_POS[0], WAVE_POS[1], WAVE_POS[2], WAVE_POS[3], WAVE_POS[4], WAVE_POS[5]); - delay(TIME_DELAY/10); + delay(TIME_DELAY); for (int i = 1; i <= 5; i++) { - wristPitch.move().to(120.0f); delay(TIME_DELAY/2); - wristPitch.move().to(200.0f); delay(TIME_DELAY); + wristPitch.move().to(120.0f); delay(TIME_DELAY); + wristPitch.move().to(200.0f); delay(2*TIME_DELAY); wristPitch.move().to(WAVE_POS[3]); } From f0a9db51c304c929fe7176ee8291f1567a5c2f9a Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Tue, 6 Sep 2022 06:46:54 +0200 Subject: [PATCH 31/41] Allow retrieval of captured angles in CSV format via Serial command. --- .../Braccio_Record_and_Replay/AppState.cpp | 35 +++++++++++++++++++ examples/Braccio_Record_and_Replay/AppState.h | 1 + 2 files changed, 36 insertions(+) diff --git a/examples/Braccio_Record_and_Replay/AppState.cpp b/examples/Braccio_Record_and_Replay/AppState.cpp index bc8c875..d25cac7 100644 --- a/examples/Braccio_Record_and_Replay/AppState.cpp +++ b/examples/Braccio_Record_and_Replay/AppState.cpp @@ -137,6 +137,41 @@ State * IdleState::handle_OnZeroPosition() return new ZeroState(); } +State * IdleState::handle_OnTimerTick() +{ + /* If data has been recorded and a serial command is + * sent to the device then all recorded positions are + * sent to the PC. + */ + if (!sample_cnt) + return this; + + if (!Serial) + return this; + + if (!Serial.available()) + return this; + + if (Serial.read() == 'r') + { + for (int i = 0; i < sample_cnt; i += 6) + { + char msg[64] = {0}; + snprintf(msg, sizeof(msg), "%d;%0.2f;%0.2f;%0.2f;%0.2f;%0.2f;%0.2f;", + i / 6, + sample_buf[i + 0], + sample_buf[i + 1], + sample_buf[i + 2], + sample_buf[i + 3], + sample_buf[i + 4], + sample_buf[i + 5]); + Serial.println(msg); + } + } + + return this; +} + /************************************************************************************** * RecordState **************************************************************************************/ diff --git a/examples/Braccio_Record_and_Replay/AppState.h b/examples/Braccio_Record_and_Replay/AppState.h index 09fd28b..0888f26 100644 --- a/examples/Braccio_Record_and_Replay/AppState.h +++ b/examples/Braccio_Record_and_Replay/AppState.h @@ -70,6 +70,7 @@ class IdleState : public State virtual State * handle_OnRecord () override; virtual State * handle_OnReplay () override; virtual State * handle_OnZeroPosition() override; + virtual State * handle_OnTimerTick () override; }; class RecordState : public State From c5c4ee9e283139b430e053d82339fa9eef46921a Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Tue, 6 Sep 2022 06:54:01 +0200 Subject: [PATCH 32/41] Adding README with instructions how to obtain recorded angle values. --- examples/Braccio_Record_and_Replay/README.md | 10 ++++++++++ 1 file changed, 10 insertions(+) create mode 100644 examples/Braccio_Record_and_Replay/README.md diff --git a/examples/Braccio_Record_and_Replay/README.md b/examples/Braccio_Record_and_Replay/README.md new file mode 100644 index 0000000..3643f97 --- /dev/null +++ b/examples/Braccio_Record_and_Replay/README.md @@ -0,0 +1,10 @@ +`Braccio_Record_and_Replay` +=========================== +For debug purposes all recorded angles can be received via serial command. The approach to do this is: +* Start `minicom`. +```bash +minicom -D /dev/ttyACM0 -C angle_log.csv +``` +* Press `Record` and record some angles. +* Retrieve the recorded angles by sending `r` (Press `r`). You'll see the output on your console which will automagically be stored in the CSV file. +* Close `minicom` with `Ctrl + A`, `Ctrl + Q`. From acf3a7f7a83ed5306905400835707142d50779db Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Tue, 6 Sep 2022 06:59:44 +0200 Subject: [PATCH 33/41] Add video of how to capture CSV angles. --- examples/Braccio_Record_and_Replay/README.md | 4 +++- .../retrieve-angles.mp4 | Bin 0 -> 465794 bytes 2 files changed, 3 insertions(+), 1 deletion(-) create mode 100644 examples/Braccio_Record_and_Replay/retrieve-angles.mp4 diff --git a/examples/Braccio_Record_and_Replay/README.md b/examples/Braccio_Record_and_Replay/README.md index 3643f97..6674031 100644 --- a/examples/Braccio_Record_and_Replay/README.md +++ b/examples/Braccio_Record_and_Replay/README.md @@ -7,4 +7,6 @@ minicom -D /dev/ttyACM0 -C angle_log.csv ``` * Press `Record` and record some angles. * Retrieve the recorded angles by sending `r` (Press `r`). You'll see the output on your console which will automagically be stored in the CSV file. -* Close `minicom` with `Ctrl + A`, `Ctrl + Q`. +* Close `minicom` with `Ctrl + A, Q`. + +![](retrieve-angles.mp4) diff --git a/examples/Braccio_Record_and_Replay/retrieve-angles.mp4 b/examples/Braccio_Record_and_Replay/retrieve-angles.mp4 new file mode 100644 index 0000000000000000000000000000000000000000..21807891559583b6e06fcf4a970c05bcbfe7ce10 GIT binary patch literal 465794 zcma&Mb980R*DV|;9ox2Tqhs5)Pi)&($4STR*tTukNypBY=ZEjTcf9}HG0v{NYOYzU z)~Z?ijD5~1ARr(@GiMKgrIWoa5D*B^Klks8+0fOP$rixM1Ox;GW#(vV3IwrhU~6LN z{LLwc0RQ?b-Vic4ua1C8Q%Xws$loWMX3@bY$jY;vi%+ycWEDik=~xMc)I`3SCZ@*U4iS5RhmEP3Ga)l0BMTifBhx=@3uk8lHv@y4 zn;X5WrHQG%jiDXAy`wq9KeNzVINREMbL;`mmiBf|+=Rx4Mux_GOoWc6X5X!esgaGn zu{9qPHzPMAp`o3jjfaydAEP@9_xD9;YszP0X-MegV)Sh>5dxe%{@v<3n(#5vGJX&F zZU}8H-AzsO|B3f)o9a6n+L?c|*$Is;9PMol_5U^0+0oR-#?tAV!RgLvV(k1K$JoL4 zyK7={vP(%iz?=-X!xFtyV+w+DQC{|)|Al(nhHcWgdpHpc&$`nHyK z-(5l{V^cd*V;5&WR>ptQbTs^DNgYj{EWU?38uJ-Dni1L>eXrxUJcQpJK4unLMnZ>w zlILTjW&bt-{{;Hi-O!zno$DKLayA9^DaCQgGaza1N8ZSQ3I5KRYJhj;nvs-^+Da~h{NJ9P+LSLzWl^n z@}

hXbdN7Hkaa@8YHqg}3puwuR7YPvS!{I*p0t{Y$2z16|CGYF}_EP^KpTf z?`8mOr?Lhc8!1C>syIDEg8PRikeDA2IWo>2T&x*DybiZR3EmEt;ios}%ab8;LLg#V zollRNK8Wi>U4&{%jY29=_#!1_R+9rPWT=;uK33d&^>jzN!oD`#)+}Uh$SH%>k8Tl` zNeLm8m?;-6Y&1&LM|izXhXNVfWV^tA`1h%^(=U zMjjJ1y5rE_4U;O0zb``Z;`pkZTxf1CLQRt6HtgqQE<&yQ%A28VvwCAzcinik@1MY6 zr4UL;Whed^YAJhr1vj~J$nnl3Y&M*uz{~(xKMP}uuk6fvh_c;;93l|W9)GlM$G#Z^ z;wYRWRLhX@@!xJaOVDE3a&@;dX#{vl^o&SSH`5P^&OaALt;Ey2$5K2@+1C{6&=s+% zF~R>j`V^=}Gp*;3o0+*`$i>)yA<;L55iKqen>*lpCQN9llIL?fNUaT|@B9^=XuMG* zeuso@NVfu@Ze4P3Q)gz+T@B|H#t~fo<~XOc{!Ma@Zd4W;1RW*gKW-FtMbmqcj%v2U z()4EvO>2%`@*^nsOYvS}`B;E#hU1vw?GPmbqC-e9ZC;d9A20waI3@U66SAcuq!e9| zLZ_h6ZNaK;`P@~BAt&4Z!z`#p2+BpkCN{auV8}@ZAKbwg|8{iM<>lO2Ouns2^I;uq z*m!5B%mkqvrDV%m$TSG#+M-Jxa5F)4mUyU;_mU7+BCK{69gSXR7821~M#9MQ2gspC z8pA32g@4yNU9%))kRiuA+(8SOqlD27=8|CfcE%_ zSaURSvx)v+2UZzK#oK$OjbraAs@}mhhss9QczI1b^yNQ;PDQiK&IvYz$RbR!JY&Q2 zbyD+_%g`5uk5^xNlbgU6R~<8$T};^rM>ATyd^_1p_dUuR$N3-lAnnr&kM%D?O!b*qADqwjg))6 zAYA{HL=?%uRXHR@@xnAagp`yg6>@Vdfy28hJKyb*=6&?Z&XVODHw=FzcN7^}8oB)f zmdLqvU!T<>+>KUCMrbi}D8N%2Ok6N^lmz+vOr|OYu-QMBel83rXSwVv-R!FguitOp zs~_{Hv@V##7p6!zi|m^3K{IL>XIij@a|@f~*B3IW=HGYIB#zn6e5TT*{IyfX=}SXU z+RV_Vsp6bcc>ZPbCw-Cs105F06C<1%LOr+U$dAyRz9;n6bVN(EXDsgO1?luhz<3JR z+1VW7XmGQR9e)%E#>#4}n$9&KTZC3-tb0dh*E1MNNvneH7kHp}>54^jW>Pq;lTfmL zinOp-^68*T34%*D?z)^S5$K(#^BL!km`Dc+0{TW@u*m4)Ab2iFsTFxxhwPx!Sw1cBuQ^iQogQ|Ugqg?Jbr5KU!(hdbT0Ynu!zRW~5tz$tu=+m5WbLwVySnx6QJ6pKPtOQ)aDI}9>5~%ytY1-1eze^)BZ7P|)IPbi0Z=K4_ z=v;mGpNg>e#gR^UiL4DE#Yp&LHt59!WPToJDW1$iu-UwIv(&=@R5_dj1|5nu92|9p z-{MapS-pb<(vB~TijmF3bOf>HW&AmXI2YIi8hKCz)3z<^C!ocnh(bmZRg<-}4@>zD z7zAID?X_GEBk-#{;{%cpmPXFc)iAEM7g$u#q^JQHdi(GO=!Lg}CY6snCVwBo(rs47 z*Fa2kCNs(f$SY4mFCr}Q^(l5uP3;rWkNvypCO*&!mqW8Fr0x~k<{d&|SM{N_(E)9R zI=4UDLf=Am561u*)^}D;hN>DkZdGdRL~aB7|3+wk7r z>;~=C8I}RprTCkaX2plh)!a%@!y`C!f1;>hMXw<5F7}-CjQq)?K?;SH5U)v9s9A0p z<*o8Al2o&Cwq0HH39+D)z$T#`3L&ImoMK^{BUl=g7dvGfY@SA5Oy_wOJv06beXxO` zyZ9Q)<+jb*!}wOI*%#-jy1Qy^{kK2v9(&i(;TLMae!dq1UK+#d!4{%%eWGcmQDA6n>e)_G{N6^T))b{Xdoy>zQ9;eyU2f(e+-{gh)rS=YD-kL(oNuS zGRy#4HEI`}(e0_Z2a5uzV`d5{jIiknx!3|RLkPt4>yI&F5zjLQxJ^+=3J7IeGNpHVf8lyY$ zh*+yCG2LkGN$T~xuMD37U{4F4P8%1H+BVf`9pa7RIqe(k!gL zBn{+hEc2L9)v-nxULZ>B0Q|V@qHA?L?=2mH10+Pk-5KS6bYi8Wmv*!`TO%RmI-o6$ zOlqoz*jXjESB4|988k)@YwWh__qgCDQ;yD5pz6!oDW56^#^cbEu_;`{)4?j ze&B?9jqe?den-Hogy zSY1oH@e#yNnc z31%}Ds%+Lyo>U^G^!U3?Z~a2ypgGMVe+3sfnptL>p~ZZprWUd^ud4W|#$oNW)u*xj z!NIB}k@ZY9J0gc1gIc7INbV?ZPB{7d z&}8*v7v<{G4X>o46Io~6#8x(FcpTDL1RS9d>qx8zpMh1EIj>dq+UuA$5v!YmnjN3C z!lOfA9p$eyc#4^jE?sWOy2Y@d|KO!qgv%>1K3(-_N9vi0;e?S&;V(Yy^yRi0as=>m zuhVj8R6C?3!`~B5hS(CsT@fz_LBjZCOJk(&ccpjyrcq3rJSg>8Peb7kezMAmKoF*R z99W`Ovji-ReP)YCbx3<`)99D7MN!N7zsQ4`U0hMKEQ+Qg4jR-Yetc9MVHiIjGDf_w zXu28s)a}`bn-LV(#xhDGv};i^vyT)*jhR8uzgs(yibT!$?ax&@-DvG8B&ay+a}tp3 z4)P$sjy*?7V+aH-D@B9qgLP^ftA3o5TU`*pd@*)RDzz+ctv0R?3?7FNXLf5>Tv+ArWM?HA+9e*H1fI>2uRi1MgVW1=dPclB2A&c z^RIN5+VmO^$AUi8}BLxOg6>>?~`87j*`(>++~<8N1szL?kfuCREYM z6t~pRg=J?_>vDk=@4$$F?o1`sfP~@BfBw-MuI+lK@uM(Nk>1>u5qHJ}S0cwI{8>iY z%p$HkQN3EDEw$@@Y9Gq+@K&Y$bq4x*9zYYo1NV_E0s zP+z=dH5`|+hKsihVsEoBgEhNUNH(k)66ww5-a}Q&A%>Jot*O4 zYqeOKY}^fHYf8r}pfB`FvKGfH$@!Fbq}&auO@K{q-R1cD$7kL>8`v8`6W0^gcQ0PS z&RL`0r-Q-c^*IV=mz3dslVvn9HDY?E1MtBH%HitPl%SVZ&r-aUHoX!rAETj(sK*LbB=G9)hE;|}9C~axNijyT z$$UnsZI*X(Bsp$mmsElHs2)*nqDkRQ?@^O6$PCGH^S#(iZV+8z#ZI&4WqUHOo`qR%dvwvq7m%zna6@MzTMs1-8D-bO)H+nsT%F$yob?Je zhh?Ur*gW1DFR(sHK#XaKDOC*yQ2EqNj5mgnPMhXId|Hgx-RGehb%qDTOL5i~&G^`Y zhV}Q`OejM!AF{ect$*nMP-!J4tuy5l1lP|+r3_8Ts*T>TKk(EBCVEjtjY z9G@$TWugGew^4fsJ?3y#O)vfR^;I&&rHfeXgkH~|Zn<|=V#pQyLDp3v>_RG-@VA5L z<-qTPLT5{UaPt~AkZ`pUYd~9c8dG7@&I$`UEG07QXx*J~34t_YdT;6{Lj?A?$iyt|fs|6A5&}2G+Vc&s zak1@HE(A{L%vv17@PMQ<&^p6EWD(hB^F=|{Y4u3P%l9|-(}+2{vhii^Pg}URYPECI z5hNTZ$CAUdal)Rt^R4X72zF@!`IvuFz`t^aU4O2K3+CrnT{PSWhn_c*Buwf1B6NIy z0y;n}G$%nq5VFaL^qfrebg&^~^+Y4{+$wG_?c7m1O&zD}VfPyW@-{2+7qCjM2gPBy7ae9e8GnDtvUF3zC4SyQyc32>U;B$%Hh)YI zosc{A(4K6v-!Pz&LJHT~81BvfiLnnAfx$ykwP~VjLQNi{3PP+d6y=xw3CDF9^=FMP zNPKMlP&$Jv^+rUzE!^XIYFk5B)*BCsTLHZ9GOt4XlEcl6_KRx=$~R>PEM7>3f>}Mn z`ZtCKBKd3Nm{MQhd2!g7!nq#qIx~=TpqF}c&ydKgxOiwUY`#xfQx#^hqhSg%{LKw0 zhBOr7gC?LBycn-3nIlY$Iw%dneFA~hiX@vZByncW zw7;MbvF-gKKtCLW#JY!1|AcdG;Uj`=Tn?L`H%7c(f_ti-oVSzv>lx~I{MMgW|JoMH zNQ(Z->9Me36&5G>28#MpL*h&v3z3=QEf!94cBoQo$Tw6oy9s_hRA> z4|xkU`l=s~7=c<&Ti)vPopLVwZG1~s=w;b+k!~#Zc!`LDh@>cIQG@Gr58>L zv^q5+glER2%Szei;53@Sf+fQ?C^u70n3&H!givupR#zYqCSHv zao<{h8exTN)duCN?F?0z#gAdbks zokuW-^~=T$wPQAQ62`{$;>k^QBPaEKtn=LbD=+E-4`dCPC<5=JYM}n86&Kkx+yJ=X z^m>w$U^0qxX2^fzEZ~mEC#2>!orO)IR&m8(a%b56D#TB3`n6ii5L(rE`;j)@tRkr? z=!5mPV)bZke;{oD9B4bshjS&jm#{f|@L}PXpfTd)WuH`}q4KQP+}&@DmW?q#*fNAi zhqh@epT;7M&SVwYY>07dq5U^#1a@KWdwpb&=%`?zLjV1Z8bTO3%{IH!`tOp{5#8x6 zLtn1^*<~1{vXnZ!A0HTy)R&Oa(*8_8%B!PJ2ywA7l5>r<;Un6RxI3^d0$*0@!g>bI z+QZ&)_(~MPgRci)6`na%aNl)dCPYk#On{0W4plhYUZj_1*Iolc>4sgEdHF`4br`Bn z=k1^Bekl@eq&5n_H+`k*TmE?2$av6pN zw_&Ee{Q#ngq+y2ow;!mNAXy@7*X2T)Mt^z&z&M_x+i1PE%gUX}=tw(=hHbrmZ`W>o z{RP0G`zrC;yPZE!)Qh2#ptYuHzBD%C6k@uCc-Utz0aVgLj}Z+dpW8xXE||&f=CN6e zhCga+TI4;&4-4qKwy7)Ss)pJ)fd5ceN#uiYRk`(KPb6y;ZyRV+5B(LN<4RFPkVIJV zGs6V2xXmL~=IbaOuK^kcF(qhrQz#o#OA$g96>pOEJalOp=6_Wk2SE_%_K%X+2y7@Cg2aSz+CH8a zY^KMQ*ov+Gx{^9Zrz|&sN|L>;qf|3Ne#V<1+!ZT#v!&hGjqT~t(~v!5giq^zzCIyt zZ`Ox0Wjgk+sVnbBK`>hvmw38;kN;D{H_Cxf#Hw!CH@w5O`{KT#+-NLtJt8;sY&={E zc)hhG1K&`55EpqundS^P3rLG^3V|9G8o4`hs$vNEjQkef^{nq7u zb>TsFQf6kE={b{332}ECzBxhF9;fO6Y7G?+b-lN)p}^DEB~OYe_yBA>Dg1 zKuf7F=AxS(|5mD5+KAHV)X2HI?LkG=<8f+0Ybf&i8~F{ z^r0H+DX3`KxS|_8=n|H-hn?-U&#PH>y*Spx?BDbI%t?jih#dr*<}St}9Vp?4kpSQ^ z+-C9-_VRUX!mR#9uDe_t*INtcK)KZC{~h+Mx8ItI7Bb5NT>Bzqm^qWCcEfuF!=wf4 zt#GkR9zas}QjP%GU=2?dJRU|p!tT;d8{Jd+dqv5Zi@mf-+tesc&kNNGm<74?ZJGelB- zDp891g%pkVrym`W?<=nIV)DS)no=h|M1u>m^9GBqVL%KFPQQH0-0lc@Qa65OtXBcW zIq=9KG6-h;IaaAU;@^EOup!_vAsDg|qDX4H0*PrXC^yStMbiYOe>&8~J7^z9CeDSBVepT{86PBM5et~!g8bbierL+I z%YLgh&;gX(R-vvBb2F|LBPm)En;^jpru?YSC+7J1nA?2@oiJZOh*kw^^_w65`AX3Q z|6rtqpga@bSkj9OL|+J4uQ|{fu^2Xy3a!~8zY+gKP$)hp9&%Z850GPURx!YC9bl-( z!i_qHDYCRtI+o6jiO`AV0xVR$iENYi2e2?>tz+2ZUF`)sK0k zt{0|GQ|UKVqb;ZN$g(T{Qro={;ilNlI`=@MlFU2QB7Qx$Uk7zGpjb@AVb+U@QUXhow^6QJYw%1+%@v)X`JnL=246;8y#g zi};zKT)l`tsyrYQEY_d0Y4pU8$pl;2=1(pHV3M=qX_)%K!vZZys5}vPw@jzDUP@fS z(qzi;v(%@M`NpAu5rv8+`OF+x37b;2u!yZP$Pn< z%rxRu$^Z)@k+SvCJozcNy1TLdjbK;N` z{96$YgOG=a;=}apvP0Q^aHk@?&0mTBv7nYJ0Tg= z?vxhW4Rl&+soR?SaPJ1%g;#i+-Zw^IhiUBtcfqCYO0Rz2bmQ3806vifXe5~|*9ZL2 zzrY_9>&M%60e1si1S-*_Cm#`z72Yn7x6cRA;vfE|89JDXdnR5#mLHE_%Bnfn&UJ`x z{TysrP5OzsHc+44GlfL=*a!nNUnJi7c6W{N-8r8pKqY0}VT@vNglp4L!PSZ-CmmN< zr07kwg|6Lacvgyf3v?x)7VM2Mmu(9krj+^?+jlLR+jI3vFA%4!$m!+Y$hiSgVRSCA zL*+IVk|rxxz{+35G$#2tB=0k#eXSa|)TsHJp@EG9wwW@~sYrWoJxL<0KwuX(0NBSd z($U|!rIVcvV-PgSKt#TqM>k6oY#1uM(*QG_q}js0JMq6pGE52`?YFsoLyCA}SZZ5J zf(RV)Z{j9;VTog`z^sUmd2CgkzL>rplaNz}A)HAzdDuDzKtf=CNGFT_NZP^HItbp9Go12o1`; zpqdnu5nCx`O+@Xvu0DS=JKgWk-;<^0T93}#k8Y!XB$%jmd-+~3Ga=GDBlhq(5jKpp z7SipaAcUcwQR|$|A3xFm;fN|-m>XA>H!WhVoIkrAKv(@d1=%M314>PSu$7xKC{x7W zV$Z=6w^%SpO?fxDN>yK(yg_Ti7SN7NPOIt_(z+=Z0oej?@*_C`XC3irH;NY=>CV#M^s+jTCt`afccgVD?bP*EqVEOqgy=K z)x>-t(hANRCd;WqXx*Jm>E45^SGN@!;yC-C+VeZV$q!bT{m6zS{!yFw6Rbya zME0SGii>kO;+U=T&)~ZC^-CkHb<#k6U8$#1nuCfj6W>ILPIT$M$Iduj@Lr_*Ua4h> zfKm)fX=gY0=+w!CMJh^8vr-x#?ah|5jhD0A`vlDePj{nbS7~ml46f92bYX#HO;&&LmLfM1pz#dE1?M_J+PJ>C^N{a8GeKFve~bay{;x0<+#mZ)?MZyDq#0o3bGx z&$gK!)-cATOX@Noa2Rg}qy?`!_n&SGc2P#xivG=_E%>iUM(4XTAn9C3gwx4ez#Asa@z!D&G~en{#cAM$`>cSC>khcs%^h|3 z$*eri<9-$bON*BT>x^I+gOCNJ#)$lWCT^iW1%xGs!sM;6wNuQx2In|IL(g2xF-ba= z2kiA1hzuqE-Pmn@JK@z&sACoqW2>q0t=-AVYi@gyo&c*OQ=)Y*7uRH#s4pXS{_xxV zFd&7ae1LO7?9`NF_)|G0@L@NZ1acvk(}{n)+0xKa|1yiC!B6^Ix1ifGvQH4VtE={4 z3?;vULixO;7^2O4ZQ%$y4ibDf@N@LJt&mg6ZWjsjvpJ+#KG=0;Wl7_%hXv+vsZp}7 zu>%Z>eFW*`RBo-KI!VR)Zpmt^rq9hAd$Yg}cwUL3XwDbhpa|}nz^=WMF93V`xN-X^ zjuS?oik0?qvGFQ*0k=S<>xPs?zxijm>VR8TklQF^wg3q)+Q+b-1SkP&if9mWP+C$v zT5Hm^8as=tA9taVm#-=SNNCR)B$pdS_zLXekujuMKRkL=R50tPL03|6{9~qocu0Sd z;Nr(|C=xKX45THca0gmxWX6}~#Pa*8-?j)_UaHry&x2+d&`3#yT)^BR*+>ue^Fh{R zGGlpiZ=$|1vDAPD9j2T0I$!XkQ6;=^0b9lN-AG1Jsx&aH#={gO$5~w28%KFbE1QuJ zs`9BUG%PzJm{IrYPsg7Hz}c|m_R8t_7o%rXZI7t|L_edJT&GQiw#krnfK@8D@#s&f zb5M#!f893lXs4vJDgHSIDN%aM1gb0E0XLfmxAy+JWoHW#pyEigMsC0>yy7gS3^srM zK@Y>gHO>Be-Y>oD$n3?pV7d^f0UG4$4J*iEBCJmR2rbckJ=74;Cg;{U!U($2`Rc$@ zZ3jXD{N-+S{O%?afF%m03*u|x%0d`fkcVex)7bp zCx^`}{>W%o+|d=0Aif)hKxt^rQ-BBPD=+#o&)JAB6q1SHEWBF|V#w$Sl|Kp!7fy-8 zGSyATuT-OCpD6&+hT*6UmYRZ&i1p2vV0@fYdUSs#g0)12o`QYfi=MHEs^VQtRyfQN zw#ke{1L>fM{FK&>_$>z41l|3D5)x_Lax2B?X^;h?@u;QEUF*+J zo;kUC^dW^KXP6l^Z~&xcdO|p_?|}3)t*9p4&KvwvTPzF@h76*!N7bZ@-4tA5oYPNF zkdGxGsNvOU(jSViYsLh{Vsj&TRJf78fWhiybYf66l5EK~@ z^>h}Y$}|-KQX94hIwYLx)Nu_y7bd;auxfUifj2@>xV8Q2fd~B~g|VX+PS;cUjy-D) z4s{CxGDGGooOSa<6QDNTOE&0%s2ncWDlCd_H%6f9InxP#Eh)(s(GegZP>@7WZ|ECp zpgPb}B!E$1);IM3{DB4)>FF|@(U@T%uf@lH`972^D)fsKvj&J~U;!i2f6$;98HO-l z+`rtDB(>JHFF`ba$K>iJ*QhV#jV9&j@z)99&WM&M8j)J0+dPi)ztciKe+NPq$`KZ} z|1b2Nl1=YFC~%J9PjRdPhwme#|4I{d?%$~KPx1eQ>nZe&mI?i`V3qL$d8eBRatt0Y zu*h2|B7GXviTy;3X-iiW)#GmZ>=XVa3PfHKgdSLds5ySjFVFLL;V&e%IEI|0#ijxA z*p2#g*K5<%&03w6SRD;~O9I_G?;2z7jDUrcf}4qt>-x~;57?chXxVrfR%6x2A&FdS z+Ci{wp?VX}*{v_FsWAbF@MC8uJmYFwn4G+r){vVJtM8xTmeABx!Gixu81|oaLl?>k z6-A=W1xDI^B`y7r2Qud0#TEVB{y&QQ??ROP-)IjI5U{z>uS!-K{iWKK&KMYiw;8C& z{prXoJ4p$c@zhgvl)A@G_VmM05?c!(C)85azcb6B%Jg_*vNiMJ%cZho9lzH0v{{C3 z8y$?!a^)qr!;G_?%v3bFnnq?>p7G;9X_a z;HYZfuiFoqE!Tc>GQd~-Oi>!RBf)m%$HuuDik&)qK&pu0lm`dBopm{+do zTwAJ}b`fX=)!B;L5tyCtnIe%J{8xiA|8H5)gmT72(dhhulI+-${^J3r_;!46(bJ!~ z|K)yfQiGmjLz7LKnHgrd|A(bfA=ZG3=~(0h85v#Y2iH4tmXa5Ay8-TUQRDd>p-p4wmv!h~7c) zQ+IK{3&gr+_69Xlz16tyM5Up(KcU%f26tHszW~o^d{k1?5YL`)3;mg^&7hX{GIF~T zTz1u!3YsTR4sE#94q6lNYHKe_lzB+z;%4caPC?FuBYXDe#x^@V<7*L5h~z+8LiZ=E zpq1GIN#ylht^m%w0=KXb4l!5bYpZ&osYK;#QDOX>%WWI81kSAs_T*;0GYTuNKEs0P zZ&}IWwR58wyhCA;a$BZ4>>o&^Xo3lrfq6^F>%Rnl9|_1fY-9da5e_DDNBJFfUEuc% ze*F)0fktOX7m&6k^mZANqEkpppEi5+Gq^J*aqY_I93#_p!*OuDYCMK4*!osbghZ)Jiq<8^rEv;86Hi8|Is-m z;9F)qpVU_)EuYn*gc{CzM0c#aU^LY)|PePwxU14{2h(>O0) ziEPaa-HKcPe`bb}_$N)FT%~{N_#YTZ=-=PJxeot3O=RF)r~idgwh3jrv&yK~GgV`3 z_>=;ZZKU%6Lh9ISq(kwu4)>o?!@j=NtFAf1`7wluN#Sa!_Z75BpBrRme0b1Sfz8hu61aC~1VV~e881R&7p--o^m-*o zQ779<0C7lj#>`K#ViTZ9H) zXmUvab|!M^#Muy-bSHj%U0^k2RLN!SI_oG4VJkeS#c-9%jI#^T$1d;C&+ z|C=?;@wh@bZ0Eg;9Lt~dBv~%?CP{2wCpL%K$=;9Htx0e*ah6fwum>DTX}d>*E`LCS zLXnxQD%uxQnMbl##?aP-Y7hJOa{;<%c@xaVBYj7>TJih@{*iX?1Z5j_6-`r2#)TX+ zD@pV1wz1Bb_8DWJ%GKP>hQyKRam5ip_C&CLp-833G9bWih{(}45adA2V|s%kjZR># z0uH3mD|WGWx2vA4(xL;l3Nw?dgcZrl3!x6)%y+sdNkw{ij_*ruie*4uQ51SBZtHi+ zVW(4yz2~3htqt&2KqN?7z)t~sqRvy71tD^@1RnD~-|5{ZdV7U;s zwy3HFv;%bM5ff(nvqpY-VC&;W}p>%#86yGCX)G=!XfGZ_auRd>H!v zbpqL&_2-|ZN~-CwY)}ge7!txnFQbd$h+RpB%~z(xh>EntO(z9F!M@KXRCywX0^~uIWGtAK{*xn4@PX zIri5Cfa~a-Lh4?@G+l*WW6R#BSO+p_Apx#gF;g>tA_mqjHZj*gQK;K#Ce_`mrG-Aa z|L$Mt1EMgM-X5yM>92-BNw`*Ws96cl4@-pFa5XxOW6>oFNq;75Z;OSMY#9@huSL+$ z_m>=`U7PX99PNb@7sPa+jUT+TkMlKk1amXS6u+y9K5Xq-Ev^txcq>c5Q=$rMI$);# z(t@J$4M36ztqPb$rf;#BzGdoQQ5qf(h3r7SawBJuXgj~7Zx1^~?qjiua83@BY~$gJ zgmV5>78p43psc@0R?RS^FxnAv18@TnJXoq zGs{6G%ZJ{uV^7QTt_6a)+}Oq}jqzMVSv`?=&?hUDPBh2?{d2Jsx*5HX4WW%bVLbTv z>z;@>7?@0ET%0cBO?rbwj-ok;ECrbUvTWY1A!stp$2C+i6^1FYH5-T|L6X&x+% zRrk=cQ!c4ufa@?`KfTeR)UPTTI_jW>g@i~w3UwpY1e&*sqHILZC_AN%tJb3W8Oh3P zkw3INmxS1Am{~-Q6x?y|l@~#uk!c5rP|L&lL53ZCgi~49@ML~%wcK`dIAjxL2g;mt z!?`#3LM4}gF9rXa(cqJ^&tx#c7`5}JBhu0>(2(DkeagE)tiN7$6X{D6oGMnT=UXJZNX0{4V?mSL z*s86h$-&}A!-_{HYCfqO{K`dIj05{c-ojl-98nf{I7bl*kn7x2z2JFO?gT-6QOHE| zl#GYu1fb!lcxTDHsa$5#dab2*G5v}sjgMDkl-pXPN)L_NPf+6@ERAMDK78jxICCjD zdm7D^yCj_}5f8ajm}chwY6L9lKRT19wauNAj4m_(6kP?`PnRwNQ!pXExfW4K#e z+xY#?NHIb-JGkt1+}b-cv9w9J9a1Cu`?n}!tTW#`4?UkSkETNnI!2*~}D!S8aCD!@)_WmN5H8H^j-#!m`6g1n1 zEDVq32Hm`S9&^}Cu95||`u!BhI(u0>sf;@CfjO#EaZOZY>`i2-GGKpD^t*kN_54;C zM`h7q+q21)!|y}sF{%d5apVM5#O*}`_z@m0@Zz_1i$(?p_0w4g6)TdXHepKwZSNQ5 zUogng@naJpF<1>vUXNL_)B^c)6dNcDBIx&ZfNG_zz=LX|P>n||Hp_DkC<^t{Yj%#B z&?6hB`qGgy88qr)nY}}*m2{sjH?{riFa6;2+`pi4PPm zi&*&g%=4MVQtteCl8@SobAZ|5(Z>je`*r7U?1iScP|Qx>Y)rhY)8w?SO?qJkQ;kyb9EcjdD1E{X-1((X1A_Ux!y;8d?LHu*!SY)!9O1qei2^S%LRY_$Y4GxO)T zhX*pgS9B59BA?&|`H}X*RFm_-x=$EudSqU=lq4ZjR&1Wi>4^bwX1aVif`z>C0#HYh zoN{zH!AW;3t6mr#y+L5BF3bteJJ1U%{+{5nk?;(f&}GmcuSqhePH~p;IrQ&tKiAvP z>{SKPHzqMx+!syGyhsj+h)L@5sPNB$Dory^X8odTHfs$ayVlguHMesYw7~huPX|O2 zVExvzCF^uv0ryDZW2KW{l$(;Id3kSeeayms1uKCfPo+^VJ`bKmBoX%9ri~Ck@`jdU zaPj#NuddR!trGJunLX$%DW$GBgYkAD9?YI{W@vMxJGVz0#G^EBGf=FmH2Jc-kbi7- z3n%l|@mqnCcQqK9z<=I>^?n{G(;vHW3zF@=?x(z-e<2&rsnto1lo~cG>s7kzswvvU z4cS5mA9bgGRV{9kuT;5L<{D@@5Ng$>F2WT8@+}YnwO>!Z4v>8Qm^ zt){;WCBWs!3q%)RLK&?UzZQ^x~>$g zL$_^4gN~E3A4=AqHnKmh+^o2xl^h!M)qRYHx9A!4gdihb2Y-BRi3t!@ok9wB!7gBr z@iiyXcj#7evevocD)zq4O{EhEQrR2MVjz|yb))~S zHrW@@=h7<>MF&~7!`7n`F|Kb-ApNmOjy?*X@rIH>aPTO9!xD;V#fe5$mgZ1MXaJSf zAm89z0D2bp^>qKr0@VEkJ8TwLoI4uilDY(+RTd%f@#z%*iNw|PN@)@rc6x9;>ixba*|h*-TAg6ol4?XjN4hSKvlc0?dK6oOV5SD`lp9Hlfv z@{eDE;}JGM*!zU4EC725_Eu^A{mLgd^{mEp%9@Q%jQ(P(I&Hr(F2Z`-+chC}r}?B| z?SA}eU@fvVX2NlMOtlr0C;y91eqNd=x1}hcJnr)Pg?5V!h%dI!8a*WnwzDx=5tOE^ z;O%D6EbfzSPj4anz6Q}c&k>QEX+=qt>p!-E%bctU&aNdIR3)C?R1Tz{v= zF8b_B2|f~`=GkkhveC)G>3mau|F5N_oEnYSWr4#aJ$<~FH=O$akCnF!$} z3GObz-QC>@5(pODEx5Z|aF-AWZoyrGYl6Ew_ahX={8k7Ii`)wV0I)dDE=ty;D~Xxe&hkd10184|lk9K4T1l z^6z-IN5UI$>T@V{8@^AOLn7v77M|4+d^u2YI)DpRZdMJKSCAV7oK5TDuY#%k@G=bx z+a?GK1kzQmGnMoVbYpXsV&@HYpQ#78NY@K90~T=X9Pw<U*J%(gj-wrq&eV5v;cGZatI+ zD0m%(4S{Oh*P-SL0h{2ti$VmCL!{--t(6V*V|t_>)K4d7u6!)8!HM8bG>+L zyFxn1?xb@v1*#K+RlKj(wbcQ|*0tF)a;55%+I|->NUy z-IRth-9Db+qsz*dfZdfD$~Ej^dWlWvRm+;Lk~ga*suglp=i_@AE`mBJ6my18m!frs z+G(1O3+X10GU4EU17{AQ)wq6k$+UcVZ2f69||t2iv-r1w$$G0I8%{ zS*B@wFkoP9w=kG|#cXaIMt4CQ)h#(v9-FK@tx~IgDrn4l!$5d-ve~2017IGP=g(A#1gIj4v$bejLNK8xcqnk}C z1FBbgo7hN1+hopS zT;4IZihFWFkE!7?;Vn{SFjyeY8RO~tEtiUPxlT>PTToo1F1`}Q5I%x-PTsF&WVB$P z{h5x<%bGsH<^h-cG;Wh?j!(X8=Ga5H%5(VikuL1vt*>sa9a%QoS|svAB5;^tIQB7KQ*P&IT63^r0lQGjMY}i4{3k;Ei~+3Pf`j-M*`2-~~~# z5tE5m@b^#7wG7pnNxDcla-s}Rr}{FrCVdct^d*tQy|-nG?q7*X*@D@PT`Iibdnn$M zIOuPMI718$N_-lAGFunQ6aF&p6N5GWt8lj9Lq4HUvhChQXmhD?hG8;^NauvWd9v5R zZyGtcr3*lbEwlnB6I=h%Eg~ZEy7x+Fq z0#4icBhd9myOpuWHrKS^kGJb#xCgsaC7qp>;$^4$DWOCHLgJ*N+R6~KdaAI?rRu4| zFsL~_oxc7)AaGtsFc}HZ!W>_b{RgR;J-$kSaHlt@cQ^dlB?pnDn+^EHVr#g7e2C+R z0X?sBpq#?)(l4O{p#HT&vm6<9$#O_UQ&YJXrrSqrqld7VM{hM5ve z6L1G^VJh<&nIvaElR+c@=Q0wkZw@62IX))G#Ou|l<%r+5x?0xj)tUq7vG8$=i7ODL z2)+0b6niQ#`pT2ExW4CDP@E33)~+H`fYha%D%cLbF_40Hh4uc3*YMR zEC%8VFcgw%5$_V_(ChMa^WkMNVhoRg|IFMkV`%haV=p1zeyb@3;7M44jX;7)&s=fqk4S)s~w8a z4rHgaBCv}zt<7H$06T_czs~C{1bcrz65+Q1CEu8-46Zk~YuTJe$0J-7iqrV+qlYO3 zDO3@qHgfq9ks|sgsKXP8t&EP)WKgeIdm6f-!5IHjuvh)n<#D`}MY5Vs`K_^i%kE@7 z8d(24K~8`pZou>{=WR>xFaaM?nM+%jDX3Mh#bs>gLsrm@W~}bX1*P=Jry(8WE*)mY z(AYe`M)JDR`lW%{Wta6ZKawQ^zU7oVLl9a5bsJIbf#D|)D0w#5J0@uFV7#PgFFH`u zP#Gyl!w-DN>z6=$b!zJ9KZx`0<=h&u{O&fwP&~^`mM#qWj13?mt1+sjdYWgyzz)-& zzuS;!Q}DKOY*hcA4|YG?*IBu-coACMf3&iuX7q0PwPf{Jz=&D_RG6f4g|SF}jM=S5 zDrB)~$DQ_j*y=C9?^b8mV+FHS-nd4G7A>o^Wh8S+dmxxsJOt%MwIur~ zaY~5Je7+7?d0+i$*y&u*a9yZ1HfRK1g^%!uvX1e59$_VvAsJFN%7@Jq&kyqqxU9xK zeSIkFS4&9ewT#+rm#W&#%0$HeK zoT2RNA?Fd__5qKa*f539V6_%y8_7;RDgI72pw86p;Wuj&aXQk`P8^_9IyXbU!ZG$}7TtAmZ;w5(> znGjIl2zDrcMRGHeZ#~(j*jYuMLUyltT@SS$3~UVaomi4dHlIeWtZqAo6-T214jNe} zZ7L3zlI;SDVUF7PPCAb^UoOBMM~PX3cYyLvKvF7j2BOl|e9SFMFHWMnf(_mY8QX`M zuPKA@9{!$yscE`TUC0<>*+i-99JE8wMhzs<$&I|+uj_PLb`E+RlI{z=6nu+nGzdh? zKBWF z$Ga5T?+iz?PY4u1uTb#OUt!MNyJN`5)`caC0ym+`1>4Nj6ES41T)yXMAs8Bc6V&Nh zT_-};S7{WDl`%A`nBh5b{4A7hbSb=4wt`!Uj>RLp=4l{tgGI8l!x^6Ij`DWBas z$s{M?^%I;9SASPrmFE;LeSz~5EGOe=LQ)sW;IUM#w8p&{hR4-5^|5s~=f_tRY_gVe zM3lT-r}ttLAh#QnZr!+2G?YLmc=iXe(Icp2hcm6^CL*aLw{A}7s$?B+Vri-KEZSIt0UnoloB8$z_KfZ8rRdswW7L_CYYZO?FA%b7{Cr%%{6drH+ruK+!oQM-aGi;= zXE2b(=&p}})V;BurBCH>tn(@uj5~ooLh9FFrTgWd@pOgbuQI@xThva>mzCuN~ z#IOsav6Ybw{ni|*t)fdgNybm8EfkaVI#Tl(cPYS@kCW{aL4t4D+6nZLd&0%tYl_x$ z^>C_F`T`DJu_IFI^k8T8fv#fnc}TO$+J&2S6JD-2yDAa?H6zd@*|(1IKLl^Jh0iO19adM6heHT%a@AMrt)+CmkFZNX|So>F6P-ZX)=|KG2wURljPJBp8 z@nD)NS(1T0(U@Mp?-7+wxwviekNN1N1>cSCP(vpk7%Nsw0&#+IPPpp)yG_#wtMkKB zu#ctvEM%-I%8qF@@pxzK33|B->_TX(BRZ?aN*mx$QnPB3dm2N|Sh9 zOhMe8wvzKU`AtDN&X^C?^*NGTxcWf<$=j$2_hr7(}1?F&8Sw;BgqRfln zt~ac+-Q&Y=?!5au!VoZzG1d~xeh8a3($8wh;>Gr3Lq1)yV}Jd@6UklA9Li2+UiaoM zAb`FA7{%s)eG(pey`B z(Bgjx9>|G`n21NnHg>Qt2MO)$uFU#yyM|*xg4E5MD$fkU_Tc82Ul6|2s#SaY)N%sq zaA3geOCOIX<<^s)YvlW>#d6UX73{+3J@KRYz<{00=8Av0ntZTZLOuajR)8T2yr)a- zmY%jmPT&GQarhohwO~*m=@tRZy0!vC-=mOWX{DV|45#e+2nc4MfY5RcH0pIR`onBk16(Q6;bxB zfnS^kxa)~NAxVg?QGx-b&4!U3#)MQ(MJB^nQewi&yWoj6i0;>oyOySJB`z;oB!%;w zmOjLx^cfb#N4_gvsa~)Hq8%Keuio2#l+uU(NCecUf?(fdn-#wn(u=D+Y!)9eSu|_O zw#Wb-#_Dtlj=ExlFiDXX){jIAhR@QAJjWueI3v;(h71mR1rA==$K$iAW1n~&XG2fp zMHb|!+I0o@UiH|x(YO*c^06{^j+%bWGHYV#Y6!(_;c3cb_s|chP1V5v)Q& zd>SO+q;Zvf-g9O}{!mlMX6#iMw}k%S#s!bv1BaZEth&m&lNHFL z1(Ac!XygD0{SaZPgY&4WN@B6b#$e9-ttVTb>i(Oy*}F&txpmb~wZ}E!C26tpTtNH} z-8`=BnIX2OOP^oCmUEIs&!cs|`cyMz36vr^!KPDVqP8M~7|#n02gv~mewK-NqmRzd z9O_4vs}soZWS0yoNa`De_MIBT7Dsz0O~8ddxh4)b&FATIDiG>~xAUGkX^;?#=xq;u ze_#|zF}W0sd0nT;S!uO62CC%&#IAQHc3e*3VK$CDSI7Hi-%Jn@_L~#Yw6b8n0ROZ= z+}DZhPjAG^?>cjv+Z1pDgJD>h|;C?pwyX1B}O@2Zd3H=%MT`EKr$K z@io-w0uOH2(qX^pr%SFvC3gF6EtvjZ>-PIwWC!> zXc7|C1$D|+Rlz;oNoNu3$2{0Ms97%m0JhX}?gX-RIK3efoZm4<=U)%grul7Jo@B}m zpC%!~^6BXZ)3^9Iw_dL7%ShnmDCGF&43VbZ37Q??xoY4+S)arWF0{CK)lv`^Cz{H9 z1D@N5_qZ+Sb49SQ;~}|b#B;_pK65>gB^n`>7EM-D{PWc}a7a*kXYmh~GINSEo(C#a zxD}~mu|Bo~<*FJpbW{sC13Tl2o;y|*40Nwi>U0a?ybIWJ%NrPj_yucPEcL41OY*cb zPb{~gPA&}lN-6%>zW)Zt+>O*%c7K<65nb`LX6l9iW6(FdG#mESRyMQ}WI zKt61wv;hpqXzYunnI$RO}NUK6kI)#LSb zg)_|03KCqnE(N5ELnb&&U{VSv+4T0c!Z+I5L7(Zz$FQci*0>*b?aMZFcDyHAQhC_Y zEgnR;a3FZ-HEy)2gx-BDn|Az`JT3UKG(9<5-L(%#u5iyD*qjK(y2Fqs7AZ%b4{Ja-5E_SJx>03dps0Bmgx!T*H zCr-UgoHKFQBsZW%7;?=IaNMp@_3@=O2MBgBq{r;wu9m+q@A;3^*>6wiO5P422HQr=<|{5?(DmW&*%#tK>XN^c4>O^QNcdO;XBf|Io7WqE)L%vwtpOh3KuqO z-?i>uRn>glq2t@}0;XL^ER2U-l$4!K(fEcBXF$V}5{Cl4&3k1{&e=VxTD5QWXfWUd z{8?ATq(vjKN5m7r4M=psti93pOsG*eroqB`JPgnqRF zWZWeez*MU%TMV>#?e(_B4oaTa$xy3%3ROU0L+`fz2gu#(W2wcBW$e|G1p2H_O=-Bo ztUVT{x?6x*0~JB~O0VxIE@r(OlR=5a&`fv#a=EF7Pd;0Uivm45G07Q$NIpqUtw}$+ z5ZpVa2*SMiuk*V$@4~bkYYv8>mYeNN>jca8L2OM*cLa#Nq$F4=oLG^WOjHk+Gt?%w ztEhv%AA%R#ZSSQ)XES|~D)oO2?nP7vWiEv!7+?XOI zYTmks@<{gWBLEUD^5iN{0&jOFH}OS&F!fy42dcNFZS`8hfHzap+P+GU^Oa)5O; zV7lDIZg8_A!{==k^#k6P6y88orNcT%O+Mx}G~T9@GVz{7rGyIwHT+b>k|D->U<;Z@ z)I=0oeKAM?ZKw@rWo0ZSRcgt0c1Y&zvTq7Yk8`L z(Ncwwa~w^eEeC!l)zYpb5cYw>HF)(HtfQaOHzgF)PzSs6qTpnQ7M}r zU$f*%L8}KuQT6pCPB}Y>QLa!w;i_xS;7nNsfyiw7Juj)w@HU;rySM7dVeB(S%Q1)B zoTu{LJ<;4pJ~Gl1^9&Pdsg?0f$y_7Vby0z~lV;wJcfJb~A0yyL$3_}-SZEUs&c`4p zmpbp4pvpqStgLW&=;DTBQK8mapox7w!m6de|#Fws*w;* z8CFju=X?Egef-LsR4mL6O%sV8hEW$dpd`?#461ZeI~;E_sz*{j<=o@wyiWqU zRk{I|K2XAHwVukbtGlJXJn8h--{_~JC>m-X_H*x&qL^ZK!&Gq0V8RPdc8kKH-fzOF zfC`{`W-^VyjWGA=wbglnUE<)E+&%QDoLx81GKoTtsn;c2@`Rg4i*nk+e>}R1|736c zK^=yjZ6T`L=-afM09EkR99m{=E64_Xss39(6QBn>Wv&QTKLu~ZGP(RIgduh<;%~Fu zLs7=kv(mT*l-~OD_N-D?1zWGF5~ZpidzBOUU9BDI zm|`I1%2BW${cv*SUmwNMk`2*1V;ByzgF|PCc%9fOMv@k;<5AuBlU7S2!L`C}K>8#hX^d1hE0RDjKG ztP&3&k(^aK8vE#%b8g?;7Oq`h_PXh{rQbI>{?kuyQksj-*emc*7ZJ^Pzzxm8lf>qb z3YFaPMUXMLi$7=owF7~`G!v8Vj10PK#65#LhQy6ZzZ`kqDwPB58c>8o@Uy1F;zz>A z_LrZS0seU|>fi-{zJop5ODn|ruU7tlxdPBSKnc|IrTr+AcHM4w!_2@OxY%hm-1w4l z3+$B?gVeod1^Utb?wR)36 zT@1t>Pwy^qlZchzj7^W_@2^Hx-1ok~c)$P(PblDacbFh-Zz6W7N7&_IavMGM7K%CeCk&T-nwiqDzNwnvHvBNJjZ9j8V7{oCX5 zFdm_;v~%qwAC}729_x&S0y(AAmCUJC%y+ShZ+IS6R%I)E2q7YLE~24T;2TcQCI_Uv z$vQs{e>c3q&-Ny`MSoR&C_y>F80JoI2*mW{WQ1c+mtKCczx(CGQib*Oow3KMgzY!Q z4BlHQ3qfK!{=oMWAQ?IllUhu?R`vV^F5$98==bV!F&LFVB#(DRMoz*n5>1KV@1SnU}WdQTaVJgZhW=!oUt0Nc_ttTOIRWjy)7AI zon~ieZ0)uw_$NZ1y2CxiwIHXM~}%6HA2KMVh8x{-O7{mq#9=Arl1M^o2^Yn zMv^A%bL^fR=%-zGccQ*jpep#C%U1hsOTs`kZ7lc*vlBkQQ2{X-u$yrJ6^G9?FTf}s z!HwRvM-j&_WC?(Gdqx1mf7Q4=w;KPmRS?j(?Puko^pje%UOWi$q9QDnupga}O^ZK- zjOWHcD4~`xTK4!m`?%}~oUXJ2WWuyBMkMl#tD!w>`=3J&Y2RTrs1?~<^L3Z2DZCCQ zvrL>OQ%EuDLZYt+o-9X3l#dk@pm)bR0Wvb~;lv_ucSO$m=t=V_HHn=Bxyg(=6gk(~ zzH!vZ+RdXkhN3YBMg*ral>4lL4p#N!niQ`=FoU?56(v~{t45T}{EfP!Dyyd57#{i} z<8NW8KC_GVT#xvl1wfhk|7I8>rL{PzGe@MsW!xIts1pm#SI(I_Un%P$)0nr%3uSRzA^z?l9o| zb9%_?1QU%M&QLopsBsbA0z{RJhs8Ex7+-HpTC0VX(8CF6n6bpI87H>3*RAAw+J$hv z>_<6cS(_3gnH>Jmz<^%G43eP1J_QmcKAi}w2rXQo>s?s70NlNN66TlXdSWMXIPLow68z$1DBYy>b_~;wkK?NblAJ;{~83! z$H}_C3TC3DhaAk8)cLf>i>Lo#H*?RkV%B1MzkFmP8@~o_#}c{*PjH-Z199wzBe-_NRJ;YoA|zKnkA? z0Z`5eP;CT=0RijFPr z&mI-G5O4r3 z{1}pIgvwY;2y5#L35vc3(r`B=m+hvLEAcaYC>|?ndXNHL!)V31fGBP|0p@lcq@I5T zwOsJl%Pu zqN(;CjoQBQYek-aZwKYYsDe&ydFDk-moJw*h^$kx7Pc^cmSNA})&C>l`z9LCD?yXG z`DFn#uPYQ9QeKLd_{4i7l~CsoD|FY37Ft{aFAThI2QcuQxBW}Az#REdvrSuj>>Ho&I1d{ zU%ZA6 zX=EM5ep&$1k`w)`+wd@ZF7*vwe_}pp7Nf$7bVB>ekAYXuQ6(=_!g)$>NN=TkN|4@} zLVGAC8-sabDSsDBRFHt!w>Haw|59U?KsV76bs}4Ot*V(DUluGgK#`|e8FGYkkuH=z(6UvmA#Z;KDd!7fwfVrIX|V2;zQ54 zpjs3-r(G&~(D)r9tG#dKA8Iu06>W|x0A8)$egK#V8D{zMXTYU)jMY za_1Pprfr^aU7v=aWk4ED&j)oh%oSPFendNfnJ~mAlKZK{kq}}>3vnTpltR<`J zg=Ms80LuW`{fxT)hwPpq{=Y*mfb5<_u8_YwqzFK?LG==J0ia0GcTc?89Nj_IJjo0^ z7Eg!+Cd#pru$(aCN70!9(LNhHwg|UvZGFJmqi+KcDLBMyK{{j6LhgL&VgrhcO31|z z@t2RJ-^`I|vZM||cpxYF zS$uP9;sY#OZF{J@O8sDS(kj|wyxS*gkEQ($`~9g0K6!}52P>9WXM(ZQ?w$KU>iySK z8SlUy9)nf0AfOS@SAuK|7bMdcMB=>nuNkxiGajo&$%FIdix4z3BaoQn%kSJtk0LhG zXU-P4DphZ{qvgH4-= z+vw7O0cG7kU(7&w4G=BB>jT0&0LbZy6Fr8rWw&c^9KX;x*8p^Yke|c6z`qOmIYa)> zKo3y${`~C3v)KY2n!bYAw{L+=Xnz^b81TM(t^WUFU@BbZI zto#WrKq;VUL3!G2wD+UFM7)N&qvzd{cO8aRcw+v%H)t6+v%n?z+11_g%T(j_;Hh7d zUI1M-I0-|^M)FfHXz3h)`nSRWBfzoJUlO@PLpRL!-1Cr9`(D$!hgcmWAsllMobURL>Hl|`* z2+1?flupxjbB-5FSkXc`kziYN-1OJRSa8B7Laj072z&~eOgxd0ryDxW= zA4t#Vmz;o60b;`Z9nPia1|Tb% zEz>)<6%)@Xi$3u=yCW|55p%7en}jw!Z58_Zxe55D!G-dfk6AYdt9>o1!`@&l1@c1W zT{3I=HO5Q1knpQE?3}$Tj3cwK;w&R32+QBURn=Z@lk|i=CV*gGn2M&r;At*B%c>|` zsZ>yARbS%?Yks?f-BdG0ejy|8IQQu?o4#uc^5EUx_i?+BKqNUMnn$CvDK zps5Yh-A@u`qs}?6w~|-dM0}z_1+X)SFtl5abK%tZLKLrC!Sz^x+LInp%vQTlInLw| zIgo!FI13R#o>;%5EgjUa6hm+yU#u0x3_t@&^*Pr1pHh9+!M~q504n?wZGlqSudCp$ zv)>Y>-_W|U&49=cJ;v6 ze+|*KV}21l$ohe7#ogeO2ahKZ$#nZC$g(XT(V%?%jQ*Qa+}3Z~ruCOwi3;23-tlZ@ z%;Rc3^o>C18<=4&T)ly-(_S4AAHg*bOGM1=WGxjrjn~`Fr?Y)t7-KgCFoyj*;?uR; zWb#^gz5YUkZ2%B40N*tLT>HPHijA2HeW8GP0w@5!KLaR#+oghlR>1QPfKMAgeHC{4 zJ@C!zXiH>sMmh_f<~P9!$~M-e!kK|{5#6iY=aMKcwdpxO6xd;rUh%Sds zd}S|-_zB{_!VUncs&D=cF09*suJ8XP>~Q}O!p7?JYb0PuKyU0nVF%ELrNLGLfWx1z z0*4Vm1YkG7LH{Rq|DO*;%Kq}r;EzN+G~+iBlA~KY$Jpkm_~1A$eUwc&?B9!-HX77R z=2cAPzQ}*jV7w@!Q8|CBDIS!v$uqbaV!=R;;t0LPO>bQm3C~fDENA!%(i}qJhuq3| zlu1DvFZEnHjIl=-Bb%-+GZj#_-HPKXQD~{WJ&Go3a;~GRf)w%hAP;X0AV)xMmtH#PD znBfTQ1DMFu!vL0$J&%@e+cj1p2tRLp&>S_o+&wwf$`P||VosIJF>VCHq7c)4*5j+4 z7|t5*IXR%chc4$_?wXw|+x7lNWt(JgG@-R8vU*@m!yR{poOILCP;ghqAH)r$%$~4u zzil1p#s{!UKz;{!+6KU>DnBUr&~F_e0w~Y858z4%5fl1a;1>b-gUj$wvKsx|OKmBu@m(l+tu`d6Et{{7dYz6`+$^GV>wtgi!k7YJVpQ{$q zIrOiFU!`h%%YW3xVB)41ntTM2w@Av=s!LLhLU;4+zwan^u3gC6liy#)p)ffQ8}T5 zFM~L|y=DJsTHH%T``}V$5Rqn;;^@Qj)03CiB5d1cPIe|-Lr%mF53VIy^}Ek~0V_=vb(I$T%zOzjRfm0-v|&@ObuIMZfX8{aXC z{-oUvyeKg$dzCKVy<{-zo=KX{ok1C^DB2h|`mxJ`ID~)sNlx~==4I{~6f~n34uGr8(xdylFhH{km=^mt=&RU17HW==A-xdIep&2)9fiN- zWe#G0ai26P#N9ypfE|Xc4o% zriib~20P-r;R)N+rA}vR@MU_;@_Re>4{eI6CmBgm>Af4Cl1K%zMd+%^xHQxR!e>6- zk?}gfte-Qv&~h-{Z#0Ve7>U9KjTJV{vOns(h&lPFlbRFvwatX3;o(Uo!hzAyiJkp@0;59*~9^M{CqI{m+pS%Zs@;`h3(V-wy6;`0Nv^SI47V1Hd1h! zsSxOuBeEr?<}ekx_pn98$qb{EE-#}YR|9?kK+&I1sr_w+-%pVJM0)MUl_wn)n`J8p_j|Twxl(PNth!gQqeT-N!)mk^Nw3SO4 zX4-}aS;v3;wEBnsVB}2#!@@x@Dhf|WNn52Yx!2X=*ESL2iNp{-nHFGmH_`Ut1d%wF zOdZioELY7lf~bdMCK0M^TS!?P7jQ76n`QwvpEpLv%K}+Tz@b_TqHj|sVzz^zU31m% z``+zz@`eZa_|{EqKIumsc?f#+7;ayWAj_QenLGNvv2BR#a_s#C-WV~=+mdEY{#Yf$ zARuBM;`9bl2{=FM6iK8>AT7>ljfKv}iJyiXqTudD^(5uTx?<@4vZAif0l2 zN*HYa9!);C|7W@Y4Dpvk%gggvudx!pv6OnFsA39_x%%VbfMd-Fk|$bejjq(L-Gip9K<3G zm&F{T#~GFT^**Vz+gS^LGoR=G;Aifd;Zza@^4SZr!@SvlNleKp$13R%ZF2$POP z;6Bt|0*$WW%eM{aeXbO!LpHY^Mn3d8H1sOlsTj$N1@dqzULn+=>5TJy%N0Hj{ z3clKzft26Yw0etYbNj&6$1+XXAb-w}V{wU^>nwlbq;<-?!>?^iw+R-oQ#5$xdL+-@ zr23->5q(#bF$itBSU4Qly0b3mX$#0rJHUfP<{n2lQoqz-W!?pr*~uY~{RBr>2*oZf zgRX>i@S+R98}+(A!U=(O)ckG#cGLMQg{JVQnR#-p-V zwEqmLTa*GF`bA(cMF0Wd|Mr3sQBO!dZ4-LK#|qgm9e!dUz~>nP>R_zH-n z#QY|I4N-=%NNg{9Bf7YvMyHT4tROx7=%3CLQM#%Lep$XhB)gp0k3b1yiKMvMy~F?7)+rY!K|!#I=;r5p*=HCj&y2zm_}*%t z$Bv%2^>wiWT1mreC`=DepBMSe0seW`;;+<7BI^56m}>jH>Vq`YO9z2xI|pcS=YP@S z-oFLA{>PDlI27TRZyv47FIJmSen&m4h%YNLZCHr+b^cIviCaEtxu%VqEFD?bk-NEm ztdsj-D7|O-Q4X5DlNb`WurrQkSi?8|5=EB#a}m8hkeMTo_svQYSP0L0PLDvgYT0-O;BARZ&`TiEt zwdaNU@;EJ%DdV3TM|dt4&8B)OQ7#$%ob|PYlfH=Y_4(K7RDV}d!!s)1w)D_*qsn99 z!EkbGfB^N%l~hjY$Po=qJ-<|m9!#)SroN7lUR$go?xLPdVlwI_Ukd0pnK?l91%}V} zC~vxM2TJxHZyU`FhtCLmD26&6k3%wxx*$P^IX9eVGjytH-CuvdsBAMH(i#6Q#D*Uz zPh)JH-aRoIUmxBbbFqL_qTLFWO_sC*@=CT@)vnjaRH5QWJ0!mf!axPiz7d8wWQtl{jP6OM_Vs(Ap6rA;Zps>_u?*F(> z;waR1fNM^b{Pg7bIvpJbi8=AgX+QU))3>B~`O9EAbd3XvV%E}u+$c~VgJ~d=Jzusv z$k=A3LfIFa02Kz<1mW+aSh1;_dHruYh+Z@hOYO8TU0_lGT>y~$AAtw}!Jh+>H#QQZ zus**>j0AKi`xA?R=&xr!`Hkhv)D|tSz_b>dW(mA>YykY?uMffKgk8Mt^J?UjFVvrh zK7d*O&jAY8p8y4@z9Jg+N#U9jaW`~szJV3#b&n)|e1%&;!#Yyftw4)}Ch-LBTE@#n zKux}Yb-dhwegZ24G8dl zWsLt0!Tuv#e0G5U+>Fm#SMHAk zUs&bSwEhBkj>8=*LQN$A7NU7UMJ`%36|?=jzzf^Js(=wOe%%3l0`jP&fk=L#fOi8Z z&xzYVSJ3{e^*>yv>tC)@xqt^&GZ;q(nV55-F!1}n8Si|8(`yW~XzLZx?RluEAf#+Q z{ZYs(`QzoXkJl`0%q4S0sUc732ZWn?SAwH4j9K@ZrKP4dwuae>Nk^OQ$Awj!pP(In z=z;JZ7PSMZ%rWAYlCQojl+OULB*4?uzfSCg{MfI5a{vw?p#E}K65*CGFU^p6fMx(= z&)(`UHT;aT@&0%#5P?_wC9}z6qrba+eKwCjPU^4U{mI_`J=%XdDZnoK{o#l^K?ORP zd31}9MDT;p%RDv$zoz+L561pEO*^1BV48nJHW2+E$Yw*t2Wo_Q$Z=&AU>Tz3ubdIS ztEFMx>03?v?WuvLo|ywgy+4n`AjnVO_51u5mhR6P{_h83rhjdD1*94`3Dbf4;sg(| z0??rq?83o(I?;Drai`2|_(b7+L+ZwrTE|BNj6Ogz{M##Aqhb&vUxC&G?8TQ+Z<0j% zn2cA`XHK#|2>a;7g?J2ubSS(mih&5QD8N?zmCXpv>6*PP7v%Y5_ZcnzEhRv)!t;j= zgQMZ!b^ryibYO`;Z~-D$@9b_pL3&Wad+@1VL_QgcTg;V8+NGPN@5uJDI{60Ju}Z|U zd=1C`OUzP-dI0iS|G+ZW>}MacG6Pe3Nb#G`KyUFs&uJ!gPeO9lMSB8U@)NFLG~X(k z?+grqOvX$LTA7s4>b^=knqLlj5_VT&f4@(-lPLLD4Cz7!P8(Su3PfBujo5C zH~ldbZ`(WM+#JuL1LJLMpQ6y1YzdVQLH6vgp7_Z};((%&zKzjJgAYstE7pVhF-<}# zIfpH#%jr*A)p6Ir>pC+P~ejB-Lo1((hwQ&6f1;FUa z0Py!SE(33-FFJ&k8QQafwT%utPU2Q|9MWx0Q;GZyEBTF~-*U8B?=fnkaeyAR58R8u zg)I5iIxbPbJAm}x@CnGKo~tu>UK5{u77=e$D#-TLSTKivsMs|3Ja3zfh2`-T?~RJvimHq-`)} zo`WP%EkElhpL-dFx&m4Se%abEYMg;uz6`1eRPFNXn8@}MPmmm@S{BSsC>4By8@4Q7 zT51Dl73a=-UeVXDO#;4$#z1t?TI6736+g%>TSC}Eu`yI+c(lbq^`E;2IxUcgky@vi zdE`=%C{h`}bC}iqa@e|A^ae3-SOh(#$J`tHsVQ%?luBc5dQ8A*RIgDQDxd%9b~#z& z)iT=6>f*;ZN@TWXdH2SO0mAtP_ExR>Ir~o$HQo~8TQka|2gPR4A;*l4-aNw}(7qRP zYlO%gOX+U3zv!Pi8z63g8~KI70xp(+oidvOC@(pKn9pCQ%phWb_Gc9Sr`iMod(z`C z6n+-r05L><{{kxhp#6;eM@wa=Xp9~W1g5X=h`F*xm{D`XClN;M zzjd^r2sZu*(dzhUitVYR^6Lbx#a?bdfK#*qpj8Ax38o45D)2Hay6v-nY_WM-=u!Tu?sM@d`gqSV!t^*cWyd zYVq}eS!(L%!!78+Q~PPdu|^)Wk`wq*b}8}XFx8V2PHZE!FpGNdq!!G$fn5~Uy}`lO zOEAOAmjr}>LS?26Kx_}n4&9G-a()2?XLAl|`=O%J4q)wB4aeAY>r(dKRNWMon8p7u zKf?Sc7yUmgLHz&wI{xpD;QvFK^4GopsRZfX{BP^{KW-=bpHK(HFIR+6dMycQaHOQI zKJg&(U(W;l4M6{cs{fyG_y3$7{J*3B19$)LvrGRI?to~UZSg(6;qB?(^1=~7Lf@W& zUt%vL01e>Lw0W!8Nn>AGGsvO^8$k7bb?tRfO|a*bpW?F~nUu>0&_V1c?`pet&$V?T zn)M!aWXEAz&h4jV9(;$N&=P=o2!g!J+Z#9N9E6(5~y&B$=Ox9wM% zS*Cs-j9j!TE}=hZ^h#8j_<(=D{D22J`jE ztYUOYtA78PG0`B%{tZtVdOOwv2Mh<#ao5dbOQEs2^?0ucF&eB`S zX_8?h@$+zq_I zX`_kU|@tl`FpL51F|)?M{gF-~Gwp96pYOv!**Y)%_v)Y9^_EFO_jL0!mMm78t`*f99@;9P&KzGsmiBfq71_VePUgzL`v&aU6WK#`WS5Ya4Sj-;v`g`JG1*2>4IFk=5-6oJ0~__EWP?!0a^9C@(x<&xu`~RPSCZ=wz*8qX+LVc2`BK zkHvm^-EGH6n|EOm%442V}0^9QWKJ*vLhc@!!r< z{g3nhf1?vkng4Blx&4l&7RYG(A1N&$d}%+tn^Np*0Ks?UKC3GSr^=jqZTwx}yT0Gs z{-z&669E83`%S_F0r-sC3F~&m$obTnWr_@^hQ%;HDKpASTf0>>>^J6Rv32_7g1Wzv z-X1!eb4qFa6x_hX+S#_fZvahWDTJuqk6ZK~3!hxiB2NMXqlU6SBqLx+%#?oCR|HYu zm6BursG9i7a);^ewN-O){%)PSDNi&VyP2XA;T)a*!sFS&DDpA4O&Hqr9bAg`5axA* zN@Zoq$t2cw90VjwcAGicpU*Dnu86}Aih^aD~qXb4R1QbIUXW-2GWm|Td z#c@--VfBL==u(CBabYw_3c)Y%QRfkwft|wk(0;EkHY@a}8qh8hCu}hUAX2VPW|f(I z%+s#}w=ZtFGklfbBwl>Y>5)%Q7NKq%y%s1V)g`yLrySr`=|vYo4nKiBffjL0Iifj2 zzjXLaKw{k0+9JbqKK95D@Xd_0>kgXShAL7cpPMRi|F%M^&cdE)jAD>GSNVq1`%3G8qd4l zAW-3}{@L~K1z{QMrDWe-l+EqJ_6=)aP(T2RH z9KAx%l6|KpK(VMUVPwzP{}p^vTtw)l5P~d^e5NR;Fd{td=P?hCyG}@t`NliUgp_;- z0v87me^^HgIxEeYl4j7hH`lX|cy}@i=Z{FR4V#Z+cFiGcQRdV|&Tl+T`ThrelF#O! zGcu^$B!faJ&tUyiah1Y9>^ZUunc0p$r+HP7r%~ZBoXf--m;CFrQB)JKf?OIMSh%zRq&pfo!_ zVf%h(X0mqwgUEaoNa%Kue7Sf%cI!YoKRZy?tpKb35)yO3im+=>VWyasUOJV?4BRaq$&q+#$Yr!$R@rm;B@Ux?1+S@Z6OawY{Zk?vMQkag+-xk` zK@fNVuO${Pty2vf4n-A)n#sK0d>;3W=J^nSqGA@B|3UFDOI zNutxcYoyb`e`%_Fl6!tu;B8p`S@*E`mx`)kqnv8Nd3#;b4H$V5Sf+Y4^=LKcIAwzR;{Oyj1eUI+^nxw4 zcBR4$k=qhNpX?Mlxo#C*DLt_}I$9lDnkA0w*p{-A#(QECR2TV3Ic0dF|MiOG#Ff%^ zS1nx&5hBwYaC|Z*fxG}wou#m%H*SbfQRd*B`bd|zTycfM%mqiC?qEeSvodhW!6{Ub zBD2g3OgT3Uo+)@wVJ82|e+%$0#n^~ltwxn^>`;b{%d}2WU<%?5Fxh6%h&8jk#0f2@ zE*Y~pfAz~&0jg>L=XkJlqz!!D@NHg1SSPw#Y2KUQvp%{Fbm=-PpY3>{h#~;tOBI^X zav7RZ&&AHdGfv87@k;O^0XBp`AcXt!FMx~K_~1!|h-S;?-@s>m1h|Dx{&`r^M(ong zXyEpsdA6Pp0u6}bfm9TQrm+nE=t$hnX)J8%=UISy1+9A0|5ImZ^< z_n^IQ=6s+L>`Mz_v<+KH7DAgyze5ZHtJUfx z-@)MRB)+by{+Wvk;^dhCzC3+6qRe0dS4(0J$jL((5jAYqN9eeAVkD@A=49z;`VGcq z1JB`4?*ksI9-rB$5ko&cfMBzTAqQX&+djsYzTrGuSe478=C@!;!+BG-IfG6*COobw zun6GX>B7El93d1@+-#1Jww03f)Pu~s$N6}c-YRHZ(UR(T{c@!fa>|);F7l6HgJDQg zozqU?1WO(Vta(3p;}{T%!E*0Tfc33!8f24PttpIjDHv_S;{27Q601-sEm9J)hEIm7 zQq1J=-ymtH?#CQJ8knhWk`9%O7e}L}%Lc(ssVSpll@9hE6C)dnf(x*_r@>ACiHuCm zj7b70F<4^|5-XZ50j}!xJ?Ke^L$e)3s>XC&vEoh{^n3kc@@Ezq}lDvMzE3 zgVuGaLLk7X6CC|8RMU9WiwB=jorm$gkYoKz$Feh8LHSnuo`Rl@^2F$6P41ia@*|WZ zuZZ?Ft)(|L#DAbwewy3-m*3ybv>c{n2Cf-q9nVlsc#OndavAa_Hh~7OG^ad#{+{!Q z%$5qA&2O_G$9oJC;1+X>m58a^Jm4ii_}e0`Qw^`V@Yu{C;#~P^O;_~M-{h;WV{+Pu zO_2|R)Amvi7o=6_dvjTMh#jpDQ@HQbPhq|PiwP5REW}^ljh#y2-3)8}Y%RXRQx<7< z3Rk#``XTWD)ANJ#ia4gs3kqjW4WD=N!MGVqD04#J?gTJ2h=srX{)W_k%`W1V4x!+; zpsj>JShZ7BHTq=UvpO74B7%#g^VO)Xe|&0eg0fu|wB{7cC1cEtDLytzFk3;sFaJ?5 zY~C)|u`F%D%Dm(f^|1m%M-`X_O2MAvtVl-Q?}iRHgHT{i9unEnz=I%b{FI1V(D#^p z@;CKVF3Wb2O6tv$=A1r@hd`hwrJMqo1MnFp1+O?fw9vgcH_dBq&mIHR4u@U6SWk+A zIq@gJscLCks`ih^S5r*w2Sxhz3BJkNRjMxDz^b!8+&8T;;~&rfE3?4~ss=PB>) zjx?&l);#w2%l;^~d97|(1=FH4Mz7;yzy%79LG`>OZYpM;!gvv$n_t*p^d8Oje~}uU zUk)WDexF1Z0SGTt#geiU)4K|!!EV1_ASGal8&9?jh>6Py?8&CPTQXX)p_3a%HnKi7 zeoKW6=P#4-44+v`8Cuow&!mHOI29L>@%R3!+e$1Xla~x&vE*EdZNAGI4K8)s+Qhu_ z@P}Q)5A6%SWu}>Y7;#C9ebmmlIAnFzn|~8T^(HA3gX?_@I6V$E4mW6Fbl0}NGwO0F z1T%_%m}C8d83NBAxrAI=kv6vYaabIkTc;w>qVS&X7Wbs!J5L-Rh=zT5G?=r0$^y|= zMkUDjI#;b*L>08udeTCE@WgXgdxq;MTjtNU7LkuZusotegt$yk(DB>)UoKMJXC{34TQjKYolc`W%FX2ZX{TLPAWjc_|wq(3q}OuqtXj-@HL8 z^EoTla#_SIFe&c{W0v$h9nBeMVh`RFp=g>WUlmt|ji6uPYFyyD4mFvUr8 zlj6@Kc$B!vaFGwLs^f{nR!OR%a3Goe*t1(ziLMhmH&D?8X+8+pZ8Z4vYEV%McM)@+ zoxF+^MV-2oE;+bnGc5$(aZWu6I2tWwxV=vBrGBGNZaHB)Jei+%QtJHB2KsC6bM7)k zlc?qZ?X=MN!5{i#XvSLNBiM2QyvYOQ4F-o8qPQ(Mz;t|SN_vIUp5H*NH(wab@FuiV zca2x?K;;L`t~lW7`a9(Pv5fGnJqp??uK46LKTf`EnC@5tws^pd0N*fUUX)eB`U%ojO>i=r15ELE!!$>7Vi)=m!al3q;M%ZgB&K;!it<$(* z_&!UVTPA3nN#gjIG;Ku-X7v&qvrR@Y@-xAg*wW#e0gpjn*b0Tx!~@tO+joa68-6vQ zo&Bn>Rzq;_khpIMz~p*w9D$0X$Yrxc>QBjmJo6(CTq02MwLhuHB85OBkthh5&j1qk zmJs{+0k4qZ-0iNL&bNseQWL6Ax-$elx~&BJu8fS~539+s-=!$mkSbJrU>b{IJA8{l zHrdN9vt9kG5GHFtm_4^+jq|zOi?obxdqTv3r^3Hb(`V4+xmN@;`R*ZO)vZIgiID{w zXeAL`Mbhjvpo(A{@^r`bO!R?>&>i<&eXfyY0meVyuE|(30bxtHIW}OY`-f-P%XY0O z`YZ#PMs3?aR(G8)`4VK&D1o?W695Xd>Ag1knN%5Ri6CP^?rE$ux3Wte7;6i8i31Dp0k%>L}JOocrt|dxCYUkxPi}K*b zxeR9~U+rd>sKjo)Xe8nWD4#y=5JVP%AMUT3kAHyFk~naEYOMG+=uLr~rcv_`#QuD^ z^}Q3uqsmp=F=$=(JPI+!x~c0ISXdtvH+aI_!LtkRW(>A5AX(qS{tg^J`nEz|Yil_r ztBfuZnVdy;RWkZ6&U`>2xSoS&)d;lqp%GNQ;QN;QEQJJ}Gi+1E?f&$gUJMdD0F5cg-)i!z>nK>O8cF2-vO%}ruW5)t^0!;udg4vfdE#xlVI)JJXTV`)>aE@><*g<+0 z|06cWP@As&b3IHOt81d@mC+{y!-@9LFqhc2LdnqX5opS?{dkWS#-lf1%uOD**DyB z`2)n3-PLZ>s#&xDGJy7+Y2n>u>^g-$J-R>Hqc^1Nol1^~;AkwLX*C1eGdQt#sg zZPG<&zGD)kS%1zY=>na5+6-Q@J-})gs>Auoj3{|mkj{$}R9u^?=>Y&hgn&B2l+|92 zL^PQ0wa%KV{@5m3(Dg4i*Z-+#*V>8<%h&<26zMnaxG)NJc9RuSb^Ta~Tf>(hP(G`lOXyt13j|5OWh5{L8>ogx zjPV{16@q3t*W;zV@WJpy!>GFYqV$Q-108A0U*=)|EEHFhwX=>zdE%xJwOs=Qy+%Xf z8zMtID56-jhBZ*QX`X{1GsX|D?9VOLKQotaKKoTTBcN?XTXNgUWIsRVD8JN2o{k25 z25go|m~^7xv|NB}ERLk-ZMWghp@_))lLWrK>hw3(>Q61yge|3t%B=iiH3guaB!l_n zwh3zUQD#Edj3B;^^OFVph=HUcQ#Oi0$5fE=6tE8 zET?QX6Z>(0LAcA@Sn8T?+qJ~F$w@Yz=gXkxvTrRqI5ny{f}XN&fkk|f5<0sC@45>l zA-tg~PDbp`a?qs&#igN3`z$<8Gp*P3)ex3j23m&{)E`*JmIXmIuq6G-7OvSIhagiV z-HlAEjElMmRt83%moUSJB396cLV~JOO!#_5f{c9cr50DeawSkAG@s<-Q?-)6H?OtY z{47!k{rw4LETMNhu>}8G!Igyvn-XOTuKpE3YMM&LxeWJ5%&#$JiPZz<`svpniO5wO zQ%j64Oq$^3a2=DLpevv8f4^xauh_j-h31gVq-}rJTFTS&)mp3c0dj?}KhCd@XTzFq ztd1@_XVTT91<55zh2{7qd{%V7OzRE5$i`czqvbOeowoQJ{&`MKTpFPMo%rbK^^xn0 zpkY0%9eb}v9*JH=H!GdWmubbmvawDXERjFHvHTstuObpFzlFViPq*Rj6S^ZZ5MD@w zINrTX0^y;>XM~%98ac()6V99i z`JmQ5`53$_h^{z;Ndd-5vCyRp>`1F-6Xt3$_%DwNB>~{rRVg(r+XuA25gC*)J(20uLOr{6>lH&yhtk{wj*E-}Up! z+Pj*vQM6m%=AqQJ1PQZ|u1gO0l@D)K=%?hWK0j#rx1RyIgab|Z1+eXdlo$l9i`s$< z__syadF9*jpV;rGAEzS&G-(upXSZ2)3;wftGfC?tF**~=u@%?1g&5UG-AMe$2nrxf zBorVh^UCHsO&xpFUT85Q8l=<<^~a>0ub}YbTFC@c!XM~4wXZDL1Y#k;AK_Kq{yO4V z1o@nK$*X|(W_tVL=zXNHVc^4yAC>LQHO=f#y*jgVNz>WbdrjUXYgsJdmG62XP>i0e z?X_!)`$-fFt5ABqY1j!l&OoresIMIcZ~P{o=Mne?;6AQWv^<6GudsChy++}kzK%Auf$fhR z&BC*ycUo)ZB$S`%xf~mH4In*49>-GD+Lch#cfRk_IcUOJ6@)IW;}{)je}gkL{L52< zpA$$`(~UP<1tDn~FwSzJJSp0bKYqQTayIq1e2d}SZez)9fP@3)?&YGE;#Mg}Vf}5V z>s=N6^PKaNO|jfQ=GHFRE0<{EZ7Fmy2j_UL@sy^Fu^83RURsU1U&}Xk3;IktP={h9 znHHXYHH#8%)q$54QgN4ew{^w}436HwC2Y;-z1d4EY7hqtMbx?Aw88woj|^t7m8xc^76LwV zA)?ha>{-$~f}t=4gM*27K%0C;nDh4;)zYG{@8~GV=!h42ed`nc*4#|q8d~8OnD1L@ zM*Akji%;EY$IFtI*FqWswez6|ToefmZKF{gV+%=xfB%B?@S%NX{t9e|`)8)9AGp(9 zk2)cQdBVyf3dO4LR^!aiyb&8(-aeROv-9qRV-5Zj+@X~B<%0*%M-|;G7Qf{5<@mI7 z8j(OEvk=s}0Q@WagLMfS9f&ZvEp(6iHZpHqgBS3p5^z{$gfB;Nh!zn5 z;R|GJ316x5Mlq(^9ADbt^v|%wtT-=ljNVpPjV73@tQ}H265Cf@n?b%iIzX)WQ^$@f zq@11uopIk=%YgAZDEpeGYH(!cw)O%7#j!R{^mCC_kZH@*kK@vDRN$Bix{CA+DU$ct zA;$iGW7tzXf!*Xzwems)=Uc3hD1(tZs~9ey8u>${MO$fo1`H zP$4)j7^K2d4}#R~0$7Cdju9d}hf-`CvVXKD_f#^A6Yu#0jIX*s=z|;`W^WzSY;U9BmtA;{JoQPC?BOey)=qIqTW6cQO{-qgj(kP`paH0 zIt$*nLC#bhzhIYNSluVn?doc`9od1he9;s`z%9P^@9R}Tt#7mPk13f_0rlWXgVelgB2Sh`Sy6*?<+)Mv`i_FBIg#WFE+jH6J|D0b@rzQr!{?4WuZcA z0B^XRbPKNIx%oR2&ooFymI3faX`IS(e#&otI) z@KL@>d5UcBSvi3R7KUps7i^tZo7>OYnT}-$@-!$D+-B`<4U}v9^wMERPiU5~GmS4a z5>KTVkf|A!kcSU+H|>NAyLEg*ZyXURsD+ zSkuyTlSxfDNA{HI`bW0h+EP2ZI(GCL4=2eZ(Y0DP^#>x_@d= zrVHprWj4soyBzYpnqYG6=W>voG`2r`DHITNp(>EWFAE17XKpL|Yk`hRYp;Mu!7XSB zuKN6!()Ck^8O#A(tk&aU(dJyR{);lV)EfnKFN~lHs&|()#JlY^4z$O;&~oc(8i_MJ z{Ur=!xo7k_0Oj2i<0B;yBBWT*EA$`(k2(b2A;#L z@gIptine>N&#_W2IK~4bz@&z2(CBdI8$>@(YifkcWujeES?#MM0hOPp{U)dn`J$W9 zS=vNuRRdZDAt7fN8c3coSDgkd%yacUZf^+uRl%6`7=*2D(|0ln1P~hR*VN~)yvzdlPg`dsji{}h zDEvLULk|6rvt~tI7psZTD8$u9QX@7Nuy}oF&0oeZC`dtjf$aN|!)K^7z7cMx(zRhd zrY$@SPNyABg_erfOML(HC6hd$t8j?dP=`dX+m$R$6N_)D7K`>ZVE6#jV9$`tHs{|z zrj~vzap1)N@(108(h0V3_%p{B=OOB?fjMn3*G^H=V2i|{b_N3POgKM+`4tW2(Is7e z5bA4z(0;4j3i~k(MNl*sFsF+OYh%rCnx2-dwawQT^Usax+M2Cqg0pq4j>iDOHYkaZ zEL#W4hWLHaAVqap*g*cxFa!*I>lIT%*lY8Vvc{{Q6OfwKO&rn}JFs0dP3*$5j+xSD zc@V?xMG@P*K<_t-M882>_$sh_=oo9>GCVJ5jP{L9zg&!ub+a0rYiDQ~>P~areE=Zd zYSkvttN$4!-`MAVehD@E#DS%|Of$goqQbsj0V59!<^dy<2-K5y2OC2RJMg;X&oRGT zUt)FL-?&Du+9>R#2eR+Vz+ZSu{w1XbEQ!wZADDCBrgMQJL3R{XZ5^AzqZ@ab^U2jP z?rG6l5FrN(vNb2(IS7Wr(|mh4cN!O8Vi53_e8*jyd&UY|$Oz7XY*48(x?O|Eg4``o zdT_pbK8N8zoxaUk&?*=hE$BpYrz$l|QUKL8i%^N-6kTM5ck(J@DN=9nfYN0%uegc4 zog@^56pa&CXTWmTc%Z~kX#Y0|ukB{6t_TZ3?^#kL_cxp?Iu9dMIy`(@;uHKrAk|er zP^7+bCl$vJf!l3X44**tkmX2%pb~?QVc(=tyfyHT3N8V2rMF zVkMca^}4+C(T(j6$vnhQ`x{`JC+<7DJ*4FaN?mNZdtWSC;Fhk0ck;bO1Kd^B#`l9Y zk0pvXR|>I8i1}hhnk^eCs{B3zEE{B)M|ID|dDST>B2wl;p$c3Qqe(U5-?BB&pPRJ5 z?B5JZYB8cfm#MGBAG!FEEvZPid_n+7*TKB@n(;YWU59g zgbrOBaoDL%UtJ5EusD1rHou2V3Y#F*=VxpxcGe$KACj&QaG^6{55uBCq4}ML)3y+q zRE}J)HkAtkME&JhopjshwIe>+iXG^!0eA_&NFtHrJbl`g$b-{`KL@oulnM)y`g5gI zdCQ-OVJZR{TF>O+CkBTTmeoPx0ft2vRq3`13*_FTjIl)kemx2?x=L54gL%6VY@CU@ z&w9|nN?R$_jZCngQA-p5xD}bmY6&@MTtca}PMq{S>ErY_CZ5Y9r~Dl0-rcE@`L>e7 zs9yJWfeuwURQQX|wOt~89=-&`xYi6Wzk*-x2iHosM@1yOSfUdoA5q3jsZzgFxNsblj_C6Yz7a?vQo;N<-JUWtLw&Ji|$Me1z|Ng^YzrIBd=eWFg!U!BH#^_=0Y}qLBqU&Q&xK{ zs+7rM1#cVzEwbA%byJ&zh+ir0JW~Lpwb#XBdAgJw&5;~L4dgboD87!AszzY%KDuta z^0ElG57q~l%0Iz;U@GkEnuDQW8^q}hq|gtw1AA2$-#lvIn=vCp*r@)!e&{cb^9Zb`cF z1`!=TWP^`UPDb;`6|S_UH1qfaFM<^wZ^DGX)1fnEo?b9YpTA^2xpjUOQ+_nIwegYyqv#*Ez*}tfI#~mk5;hGAWT+(^9>Utf)+gGs~A?9 z-SPHGuio|%e}2BbFezC`VI=9G*9c>l7w|oqU7e~|$u|ny{;_p$g(X0}HVb`S&uBcd z4+anQE!2sbXa-p`Dh)1Sd}1wx40Oh3p_E>}{PybrAH>j0C9c-w96G;wvW0ZUVWrgG z(t@%BMKf+b#aM1*3kk1c3RC_AfjuQ3>?71B@Nnh2>3r^ZY=-4s^{lpvO)C`VWwNAd z02oG6)SwY1v8%*t!KZNLG<8-PU#?H^uMDWDbsYR+L0rkxj#bKh=R4h)z$QW2#fla~IsI@%=V($9q($G-tjv1)e zPSd7nc=5W278VFXF@lFAG|&$^~ykPb~TmJA2{;eN@2 zmkC|e-tE4Fzf!RIn)NE0Kzb-@zv3HMX1B$`+*-@1bDiqNdyzSb(;fmb?8pMZhvXn@ z-O7m@T3+k73o^Sr;kJwO&AupfuF?YJLBSo|VaSHviYNK9s6hil=;5&G8el1tht)a3jLc>nl;pF5ZSeG+AGY@mQ&o6Wt-Pwf9VIq3Vn07gsx z#@82>cA9KIl&m-sr4^nD?ZfW}@9!rV3Tb0Vnah~Lut&$xPg~^8bFKtIQ9VOrM48~P zG84|ciF#CG0N~j;)~MK}Nc$EXLLV%oU!8+4WGNbKCq_LFgC_lvqdfpO6hk-vQlK;K zZd576oO{Bf`tNu*5q+mK++okBX}vlv9I?|2Nh0U(u5KP~4(082{$;6Mr`0947k4X4a)EDl{1ytYr4^njpmYsu56vf*VaPz zvL;mZHa2!U&jB_%vR~IfmUi^8)Ye729tN+h4b^ncpgE_KQqYsr69G=UmeeU&yJ1exLpzc;dB+EWfnC}s&%oBAtc3NVO4Y$?Vv|dWeAmN~a_6K8n=2vP zr=W@~WX$&NuB5fDqr*L+yNz%JvpQK&2F8X9Y*cypjp{3=V2Lsq6Q?N3t`{PTH$QUt zJSEJsId9wV$KTch-u{R0H$T?CU@3MhRb^Hk0u*PyF5w>2A4G!)*416h+1V`K7(9 zq*gilyM)o|Rs^z*B-zzuG>hpN6)mnvyY#{}Zj=2x1XAhR=xJ@o<1)TCH=>3A`e0te zRvrzbbSk$?k0xSk7yO|N?uCw5+QLOouv@Uf+AK(q=`i;q3}_;|wwZc}1A*lBXvg9K za^b>AaI~XQzsPM%f97&l(#K32tYTp4#K+F#s3$rZwsdnq8>0Ab%(I+g+pb9X6uH;y zs0*8^(w`Yk4*+~`brfZoU75_x3b4$#)acR?$k)0ML@PypDhP5)FS zM@EjVC4Y{$_g@%;qTL!Cs4dl@)wjEqM%_gBFnXgWAxiS!*Cj|5mh&js+9}KMgEVwI z2hAa!W~6`-@ld0$PEOzTcwGgN;0Ng*Pa>$z&~1tJF1VR*sg2Ox*v*aJgaOMaf94Y& zINbt>>*VnS1nd$#^5@xBaCgoH|d2i>2mh+95Nr*;xrMVPXWPOmDyi z6yGqbW|xKM)wwX==7ap`TbS)~?u}u2A86j@XDjaM=#mg&JO9W%Nw(!4ytg{6C`V_D zopV=~*pkPuRP?SO3U{*dW%oJUYjqQR2vP69vew4!WJjwG@?)2zi+CxS zeNpOfe%s&D$*1Xex<Vzf4}N|w-bNuNU%GeS@Y)Q@!&T&}-zC`lTq z<@effM>1Usu=p|!5`-xC&?sz#m>iEu=C4w#xy!O2_)yCnG8v0H*WxtMUQP?mZcL*A zPVx(^Go|nOkO!`M_l9%;P#odz;?hx6AX~kA(o@#p!bph~rOn5Q`f6=zoO*wyutowa z1NjncP=)JO;Lxn)aF6{d!1InB9mo69yfkm+6IK~p4{{L}mlIk+c#qsmIINrSvIm}) z`zn)kCG(${~Ckx?6!J4=K3Pw@ACT<2_Vs z#`A~|PbU1=MTVFo-W3tQfc@vywZa)ilYTgX6yJ|#c)CewAq@G|aWZwZB&ou=;@EkxEl%oNJ@up@aXLG-HCY%>m9Rg>~k(3+AV@pP%ZRh5gmF zXBLCF@GxAl6OvLsDc+*s-9TyA&Bm_!YbAVHU~XAR zqY3Nrb4X*~V{U*0J{n755}T4UPA^?BmQ|ZqR~ha;J2fsM=RogVGgTt93l53Qj+cwY z6NJ`m5eD8qjG{i!ZqUcHs6%k%*TmV{qPt@b%_-h2yRZXUG96}x?Hey6wIFYu*uC?o z1a1cw++;WzwglPCKSru%g-s3Xo>U-17TJ;z14TBf7UVK(8;xAjEgSJN-F(ofw`8n> zIKC%&GvP#|{g4U`N>4g5K_w;m{-rsF$`yyG7hc%bn-q$I^8sD03q}O$Qx6MGX?zyC zuwKV2m@Gr|6`aQ!pQt$P5)G=f9e{S0wx!@98PM=;#3=U1EyC?c-*a0SKWH0ZOep_v z0=M?tr}yw!^nwnY^pY8F)&Vk4#%SRN(Q?M~dL?vl8%paVO)1L^P_6S z^N&(sn6qN?LMe20r;14~36M#yPJgObDfZ!g@5(!GiEWCn`wJT?OZgmck)x|tI9KjY zglFcXW1rl#<8S;}vO9Co&ucC+3d(LfR%f;Zo+|Fsw#jg4>TWs6H`2PCQ#9e(Us1r6 zlIpmZPK3oD>k|w*r-k0+GL7X_p@qNC;yW-7Y-kJ-uR$`0yaWc>ZcKr+dOpylgqz+P zqS37XUIFYX01?xtQ4{;9i`tj0jmK_q);hgq?VOPWq+>=JZFKFEX4fBiNSV#o+^z46 zLRr3#in8qo#kjFsHEKq4Q#g_ziUkc`WKHQsmggbz7-5&AYF0&lTGXV;jP;UOF<`HR z^4QrX$HB39EiH@8x%@`H8Y9?F+aZ+%{C>K~BcK;u_rMX7S&(e+FfAztsY78;>d|~j z;&_r>C8~Ku9+Ga%?e%aqA_~=$(pScaq?#IAKv9iu{@h#_H;?b4<3!NyOEY zO(0Ie3Sx2zYb;?fu$6ZVvdNPy7Mxo@VHo>7Tt2@&yJWk+7>gBUBW6LC7a*ti{XFn& z!rT&!wKIfE;FaD%$H?`a8tPoIn$cd!d^~Sac*#dL1M(`z%al7uanh@_$?h{e(X&K3 zY2EfkxK?*ePmfm&K0B1;s&i6jgjE??x9`qC^1U7bJv$W7lSZTE|jI~OgUxY>{!#hoA9^?dKO)5R3HMRHV^!2L)}Uo?|#b5I`OGJ z=}he%5zBkv1-ROFbthI%{^ydGW5fS2hEL#ftbk78!F!uQ^s6*e91%Kk2pMAP> z%PDrMOH;<(yGIo7kt2tN*KngRz1)33jWY-X?yP07vAUnjwG%bb9hVm zIy1emSxp*zbd z3abtz92xg3=Sd%Jgn<24AT<O_Me4ud{b1}jfJjoMy8}he=Qx*o6AKNZjpPt@vURk zU#>}A7|!&;2DLEU{hj|(e1`~pFi&6X?6`xr_STQVftG+x`QHQiVBiaA5FTsI=XT&z&7tRwS4|3oyJ0Ew`lppw%jzR zH=Mt7xHVjHp#8Ln|T!KIv$@*e9LHS6MoG0*t$+l?I$# zSkqtzYXpj|cnUPZ(R+Dzg8?5E!v()SN~t@g@JI=Dh<$F1`i!%bkIX(w zgl_(*QnxoTw`Jw3%To%_K5@sKI;c0o$J$LF$?{VZ4GtFxr`3_sKKRbM{Gnw(R`%3g zP6!AdeSMy|hewC3QDgo?emb(`T4*H|bv-Fs)K{0jgBL(nofz#1GORDkgb)a~o{CWE zKrj@DCKVD*7?@S*XYi8Ihr)+`4#pJQ$*wXIPtmwlqKLk8}QpDsHKC$ z2Q+-6)$oxhAAzaX?e_Wa(cCF$3vaUf2m?y>QS|yeF|2dAm%4oAL&_wvQ)5X;XKi%6 zAXx{G3vg)KC0Mp?`tDEw3rlD$5C7^D7Eaewe`i|P`zA$LH0fEQ)VZFWb?DLadhsy= z0bdiKny#nb6krP1d1ABA??AIE@tjgABHXQp6(Jl=_)q2&ddIjj9}!#)n?gkm`iSA& zx}gJZ7*dHG@}EVF6D0>A*1~XG@1MaOknvlbl|)K}oU$zUf7uB(GHi?s!LeyQCX@GX zNA*+@=7h2vNZB(P>}FU7MG~zd_=*rO(l-|FQPH>ni2D0AfU+|hj3bMKc-U+T@-JOb z2-Dgw=TaS46A!_hnBg+qYwKvd>R%*U%m0Ys1}{X_wbX8r zzNPZ=c)i}&A3V#%%(^?#;9CSF9;@QudcGZw>Q}r&C^IFa_NoHfBul)ZJ5~+psh|SmmoAM)+&&KO zbrr)R!hkOH^Ljq!ajO@aJ7VLdY3Z)z`s?7}NVIE5=k2eP0T12ILlmN<7Iq@_G~gt;j(igSvAk#&D~8i!^x< z6(Xt{PJsDa>YwbI?!Lg>P=d0wB+f{=FVfV{hV{|buW+b#CFP}^jocDslLtFXM-3V@ z&(ovX{VWqe;HEPHj-#fs9hJ>Up*}56>@#IO=ylB)iN+K%+wiBt;ds8P;*0TS0PEy7 zOvLxDFbyXaHo3%JmB|!n67J9Sd;r`gSqmdJ0ZW7O!0H)j+4pA36%yV;uN3FA6Z)4W zv4sifgK`js9+sD5_N>=d&5^WbpsOqQ9=R;-Rh|pdvcs0}E1x=_cgjUkn6V=gQ zdfXf7eY*R@r1e*g`Z3 z(3;{6L1a#Er?m(4pwOW{>msZUYq1sSktx>uF0yE_xI6zBVec58*|zk1$F^-d9otFA zNyoNrvtx9uj&0lN*tTukdDCn4Ui;bmIp@6Bl@GaUjETFdMvb~NGkGN+*H54jmaBfO8UEa|&bxz}x79h+PMJ%@kptKy8eHju*1o}02zm!x=lQ+sU zAOb{2fX!1BxvrlrEe1l66_skNjGGHo$cg(u5`AW9iBK2Jk<>vYqmNLayAxt@(^BHa zv&k$w`g5=f!)vn-QN@z!-~x2B|*RS$%}1SIdxuO)%l^7aMCB@UzcW6z_HCC z={BnMzK3RS?=FWH%a}z~uf31Lb=Dhvd~f|F><0YY+$ycDtu0>Kadw)9bMu-bGG_Tn zlIR;u2W37GzMdRk&&J}S5P76;G7;D~8B<3+H0W~(-x>|dAUDA7gjmWE z&@Zz)AjM@S9&TnjVx<=!*DWTvdz=nKuDyV2727!~0l-Vu0j#zsPLXb;e*At8nn^BF z9x!F1{lxKfVOh-TfI=o;>}kL{i)(>ly~iHBYL4E15X*R~2doH>?$~qc7MK}I@|YJa ziBst(^zgi~CQTrgY1M*>*9eLn>xcl{_kq^5v$_Z#&F5N1p(M>_F~2tr=!Z^Peb|2> zTsz@Bey;PyxZiAZ1137q2G$uf&#kvYlLL)2b*tAqt7a6gKOt_?w3!j}dkI|z#kl17 z!pciONRVB2dWVzYriBi|Cth|Zf8rtF7Bs$1!@7{?UgOB(TB&^Fj(wjdQoXPXXG^!C zdVh))NbKW74(|}y3Y|O281NpUuR%E$@W|P!oi-e+mGPkj56xQ1sVt7Yb>TI5@Bvke zZBqk-Xrlaf*!2QDrb>I^&f*Z&>-z_&# zbW@h%)Msa$la1*3q||$1lx_oJH@^NF_KSP7E-90wBWD}oZNJMbjGlpRa-%Il$uMv7 z)dGfyMRdj&xg=t6>43ZF6mK8KIaQes69kpY{nb9wf;6+m>h#^r>(x%3a=z%HE}Es@ zXiO~Dc=1lM^pTYgUsgeCVY>)`ZSZ|=KiU3vl>R2vRubB}!XYlY{V0zjDT&I_%{?>t zmPgD5|5~*2hIgD>7o54}XER{thx`i^ECF@Ib^#0`Nx+ zj^qU}R9!gP_z41qhbZ>;+=7M;_tZPUH;L3r5EKC_TaM7+XPH>?8swTy4w+vw!K9rt zOBGBF)b2c;A1@C6kdlh?fX5fQo^qpKN%+Z=#y-Sc>slmd{ZfxkJWLNBo#f3qdihQ7 zITryjN1gY%3WD#0IG4Tr3W~E8UtZZ`v=8;`2Z-5XUwyfs#!R3IVu`Z=0oixeXz!t45Q5ByDVh6xckGuF|)v zdMt*W4lyTNdLYjwpg%RL8Mlx?BI==GR;VZrdi6ug9V^sC4;%EbItklfjuyFSi>IlGDk>) z41Z48@Z#htQTyO9NzVFUR3e)-jrvKKi1bd} zwCZaoc0i?)*51U7Y23MyzKZER90OeyEw*N;$n`S$s5g7en$4et0n^_zci*|vCrDlC zVImvs6+gxkPNW-2Q;Z@)WzU z`FyI=ZqzNQRX91~f-7(Sw8n%v&c6?OuH`D;*&xuM9v#!ZW<}q^t^=V#} zXG=#+%}GUKTzulilEL%}up_o^H#lpEB4JIB68hZ;af+{m!th4E7q-3}UeJ+#dmR;+ z80NtOx4bvM)4d23=3}ef`|>{fp+`lW61I2^?vPF67##=Jo59`=Wqp7a;aO&rFMD|` z_JBze?X%@}Nc`!S|=(--D;k!^-9o%@7SRKDF|wmgZI1kW$ge#oh3+-SypI=PcWP7^1` zi{Lv1CPp_NULp729vtc+&EGHTyLzD-OlPCBPL|h`Nqh+6FI!<@kog*U;pYNxf;9%4 zwD*09Digfp`!jsy7#5l)-0)YILIwKUmy!{sF*s~;(viWx>aO?<+1j=B4Y)wSvoM!- zq4Y*#GQSv}oRZ!>@R3K|ypZYjd~8_ua=!hj~(OL-_-ye&sB!*M>bAr$oH)cBpH`>h1 zoi+LJ>A}0HID}uERY#_-B^hMEX$&n`6qZ8THOz9oM3vp0rf9h8C=IPYya952;g!mK z@}zeB0$!Ir4icOf1!ZC9gPN$hA!xQH$8tN*;ft|N-PrK4nnr;qro4j85^>tFc+m%r&ZSl^H}SZ6D^`8sWrd61~44ndQO^hAUY8$ zfZmEZWV{OSfq3|+{N3c*)*v3L57O*z$?17oH+Ohgi9Lv9#%{Ai;iL9-OcWaM-ah5?j1Q6=e68Y$xX67#qceBhl;BvMg*EygCqe$X$NCydPFZ?h!K$DH|aL{ z@BE=;Nh2O)7X6`0bZl@YZk6(WSf*~`si#eZ%o&M3P}C!PZA!0+&S6_1c%{OFq1cC% zG*rFqaA9-Scxl84PZGf-Y7^t^{v8^plj!S^*)N3RM|P=4K+EFN4eLH8;WqX{Jq)<@ zxlyXnmc>0~MvSEPJ=)4^MSx~q$&j;MYmVRmIb*Mi)3pX2H%0DHP9}(H$sx6 zl=Y3Tp55Z$LatO<7zZ{F5PUDY-sU14`ZHgLEQSEi6E7bcD{rm=sh?>4IoC-JPDPIB z^OD2eo3xPgeCu>^dCWyyK)s9SrF&SupLEYa{E);Jk_vKilmUYGJg>EaFL?_KilNg| zRq=5F;`jG}6o&(kyiSObhSP{VMSg{B~He=Xq$Sy+>Hn zdBtN>gHRI|0E_^uf)@gUw$s-v3{>A27Zy}abvY2DU6BSlsL{AHTmW1p=W`1H1;gH6 zV`f(ger96u_!rFv@DiZK-xy+(1fT)9331ZUzvy2yoKF(X|KHC7cNkH6FvKj{Rd8GR z;8J$|Fq9!vOQTCPfo}TLCnpmS>yvATQ3*gcpHgIqUO4xYB5RqLd2TGUv;awX_iWwS z*EF$DxD*rU)DQCKtzgGIlu4OTnVJ0?Sns-^+Q_zQ}c9?a)n51HO513`@8BN31! zG(a5?c0h2pv%^^0)4AoLzU6Cs1q7^nG@-@UiEJY^kYfbrr-&U2oy_8v8c5l1p0`ly z%CERNk(1d9F9cUmo7r5VW3c|r;Ppb)dE|7hnW74wJ9dw*UyA%3-O#*2Ph5I7=XH2( zM4ioB%2`x@HUA`F-qS;+oJ?J*JQCO5KN~YSI1d!IN&J^j*|I*FK)-dA1!Vy$9^q~a zzcm=qevke$+~D^)%JRt|72W{s-+f@WFMimkmRq*b4eg}Y#Pd1-xVN@o1vFWl8HhyL z!`exrs_**yNI>z=1Ap`Jg#Sg^{vAWh&rv{&zxa4Q0Dz;lQn*L}(2#Hp>+?$&zQk&k zMd57gD5a3`X+4lw>*>xo+5XJRiDF3_OnGvFXKrpuPKlHe$Gjs`jjZA4p09Vp&E-%v zKZ%F^JEI)J44kIi-&?LdNW#7s9R{jOVRuhusaJWsXdVOY{mjSWxMZaNe7E@P`({>{R4L zJ=(J`^&I2P_T}PpfSy&}O!&8(tMUf4F;DgLD0sX2r_dfWdQE6QWOIahQ8ENSP zvZLi~fDr4HkJ#10ccV>LO7~eL zl-G);ih#K0D*i}Ks(I(XdDE-CSD5gr)?hxKq(p-~QPGg#pPlr|@W2r26S;*epPoxF zJe&OEn7=4#e+w_u`T(fH;c9xiA0swdQ2iN){2MQwaU}dnz5AzH>Hc=yZ+(qVs}3GQ z@Rj19L0tLIg`oEr^iKx>K%9*kNMahM)qt753!M%^x93BBkTL<`wMi+G)f>UM_xM${ z&6v{kTs{a=BFDZ%5E0|9CxSQ75I)tF?r_0S*79cMXnxv{W(Nn_)H0jie2WE)j|p`% z(OK(e-WGjalXBSCOhAN^_if2pq#nx+mM$lp=0S)5JG7p48va`eC^xBk0{hs8Ymkgo zC=y3nK;6gEFSj4zb>L?c%VHaFfJQ;V#US`!dgAdRV$h$ZFD25`gc)yimEKM8eRnAs zX`l{az8(%O88Ub_N%Dsil^!+=1=0IN;T4zVZJ zSf&p>7DFaYzMn#EIuv>|2=Lgqaa zsNOa|>y5KvssTJ?6MABx!*OTsDH3}*2LObVZ<65Wss2iX9pBGmvH!yB(SLxf81SPl zqAceh{uu>;Z~7emjr{$*5;w50U|S?3teE&9dod_P~Buh zx|#1xn?pf42Y}h?9{i%p%~UHh;FwF!-X&L+bT*_Waj!tuj)19n3 z_$d{L28GB*Ob$f>khMmM zJ(d}^k1#yoq%ftkFKv6MjvW6|cYAFX;LtUQn&dFOAz6f;z^_RxkF zkva+;iAd{%eXpQq)7jt=5=XTga%&}wMWt<8HSyeVFLSQFF#;GbkV&6qc=agvtQ7DK z*!E8_cnCf}?I&3NFKRD{2fHqj9bsEsqUXCCS9LXJ|p;B1mwRW_?b$-0lo_V z6LI+||M0o+|D^%)PYmHl6z--K*StbO0cLgvZ&Mx&-f31di}g{-I#^fJ9f7xOE=TD} zptQi!cRNTsYV>M~k9zChgT(B#be&S1=#nAWYLD3T)Hy-AlaN~x4o&3)_YwzCyO(^f zG4WM;>J?<}<}T^UTQ=1%nnFZJrCT_DdFrUlKkmbyA{I*ZL`Xp&14h*)ho zdbEIe(QFuidWh~OT-B(cJ3|Gp(P52`jmf=K@+Sa*Dt|@oZ#k9!OVob-6}A79vI^1P zO3w;NLgdafSclff6x%*+@HxJ_gMUts`B}UH82T?D09_H}3s2W8~IaKEdUG)enfLPxJ3a>Oa$q z|I_-Z;rmCNL3UvK#{V#2j zPgemV{lmij_s8wM#<+wR!$Nu$N$-SjlaZz(DGt>>s+k6Fvx&G!Q**(Nni1+Ltxk@@hii$u@7yD}&QJL0*}R}sfwqOF4t{ayxV zml~gs7^VkXLKk}6XfvqUq5ph0W@#YGmSSE-9*VGyo~3@~(+uVH1DIx7DZz%jMBsmd`&mp8_}zKAAyJ>KjzF-F@`W1oYZ9nKx-;P|f6ATe4o%|zh}B(M zf?;!OrcE`iYp{Sf2HN>ppCsQL(@Nfa-nGCkFfD3MTb&r+THz$y!BmnbBZ>W4NH zjVMCE4nheh=$q7QXN?#T|5 zqVLk5GXS`L{_?v9|CgSaz^8TbA8_#hOx*wXrW8l*aF^(-pPlG)>AkQLjtBwJ*pk8h z;k3+sc?4%*??ouP=J%HP`Nc#H&Aj1R&tv16CKTw3$^{M%){0xB9D{|!lt43Se$5!Y zt<8JT!>Z(Y2?+X)r&t<-+lNVd3_IYt5FK{p!y&iQE$KsL)0f}Le^j#U^9@LUi!>Eh zvstTmK{EdeFch3FZmz2g8W_Y}nV3|DNTk)@qci$utidn82c2BbKp?!k% z+z7rMGGCBh(cZx$JT>7MDmcQxQ zWZE6;>&FZGJm&ry(5(`&fZvB3mUEj2x#trr#O=|>Lw6?hk3OkU4;DitQ#;Xc?}7ym zT-ZlqDyz)sEG$3@)3Sr^m0unC=6iKU-F}^X=cnt=Io-fDfserDlr97Bjlm*s)_KbF zODIx}wWqm^^6O*CyU`6*uVI)7DO3-3P-NRgA(%K@v3hCq>8}^a%>oWk@M zmv|Z*FJ9&Tn9*y2DBfA_u!PVdUp|xauUdTjdzF7S5edJ=Hvb)~|J6hg0cJM*ZWoY* z7&Rv`>`&>4lryzXdSjvf*?8nWE3u+LYU{s)^mmt)cdY^7NlB5ggGn!TTHpu;E=U9D z5=WiM)J}@(iN}&guY!t&=&n@RLjV?z5WlRqZa%@klO}YxqyV=}<%EaSdkr&|@S5p~ z2-)S9Z1{}SgT43-WlH959r4NX0CED?#rsio<8J>L-;Qn8*mT!;6f*P z3)!BUobotZD!%@FyvBC@ktn#*CFywh+l-)KA1>O{#EwgDOr)dDjiPRu0;oG{TG_JL zYEnZdmN3+CJUa$t#sIut5R>7EGWB9f^|w=IA-TO3HcBy==p<={PC0Rctg&J;o~-Xs z7E;Bu*vp5xw%fYmjlG%|8#d$M_}{lrA_>>y19`%I{{+bEcftK!OiTX}pw8L?^B7A4`pTA4D)q*XEiv>_jOJb7k>Ng)2jc!tTZ$NKTVjWKKn4Q8GKju zz3Jf~%3nxP)RrZ>tzS*uj@c0lf@1L-{b0fQQdagMyfJ)|8I{lY&M5uD?G61Y*a^xL z3q=66q@qzFV*sdb% z_JMBar&Kg2eg4AkG%Qy=?Z6_|hzeJkS?9dCv8{W0)q)cac#9C5iNF>8Ejks<8Bl1M zp0R***=mekq0bTT+nR+SfTq-H=x8WTWLXaP*xsdxS2wNYVAXhoYb1@YJHu`aRaM7^ zk1md2=dw*-HA@Q!I*&&K=mohKp69S&vr1PCrJ3 zp$_cr*p-DO>)Sz`7g_iI0Yoh6c}rI=o!?cUewtSFnc5SS$9xwqdB$pXpFBj%HNnL# z>(}(~=YO|6+tjyCKz=bn!)0n;SI|0DjeN6j+zI+}7+DOs)}1^13M^B=V#J`o!zHCh z;Nmma1y^8il`O;xrr===6B=9rE*NKSHh{h2wX&lfrPg_i^3iQCva@cwYKRJ~d)qXn zuM4!S-VD5=E?~OlM85PL1(an&My7w#x=V~^n=!t6hsts$XA!WE7y_~1^;Mpow14;Z zZiRYRvr-edwxPBpx?J2(+X6f{g};EvQ=b{4!q(+!)u@hI|!F zsTa^onjlCl*HePLr-KUHK01CDxI-!Ll%Pv|5ZL;QD+v+b;0H#$#&`AFsZj7j*8Oc= z*^h^0HntxPW$%3?u>7ZwMLBJ70~G-Mk)j~WHj|JOJuKsFh+v2JNmk}5JbY4%O^SF;|yl5wQd?09*6TCa6 z+~lRcJLvBzRHB4+D^LPt;`XgaooNStZ*$mR?CJ2MGPT4no_y_9AV12kpPJx3gtgOb zy5{W6hhhU%dw;2Qo5AE|SkZ>5O*(<{$bq(0kdGqnXyS=!q>tK@Uq#KoW!};Ioiy~1 z4B8t0h+P{lG5m3BzstHPJziqL#+WY`CypTVo%k#*Ed=~tGaz#L%;BQDH^&hvH+9jLbq0b5eM(PuXXOz0kPE&BnI5NR<3nc)yZ2QVD#yvmKpoD zugSI7u0P_gY^nU>F+n^YV%Q$b(TkdT*W&#peaR14){Z4cv+N8$F)`XZ>AnQ^--~|@ zd25(e^6=fpOn6^bsNa!L3Ecsr&^6)2w6~`+x|I2ec0sQrp$0 zx?DOoB%W2IzQ&jWb-AJkTL~ZKQM`hx5%WsHs~WEhGB8uK2qFQHYK-vbl=1ndqEE;t z=AdYhpSUE?el_DHtm&J->yMUUW_7F@9#&~DsrG+T>>dm5&8;CKUrkUU;ngDor1la^>I2|~?{Ef6I$cf} z%l0bx+y+4ZwtNk#8(9-t;Am;Pw_+D2uP-=&9%Ig6(PLn~1TOW##6H&hKv*)P_BH$0 zf(!h($<2>Mlioe9Aa#$TH$xWrI&rElb+?vp3N_!4Zl9#Rec2o6wO@uV*Eh~vSMZ@ zpXSbyF}PjL=#03 zpS4u)Jo=h~pJ0sX2gFAYib_%H>z8rm5Z?G1-KCtoR`q9|glV`A# z0ST6hu+XDw7Mew%pgBssMPhY^j=+i}^DRE9_8d)F^!y-nSEoYW`J&q!J_KU8xS4VP zr(BboPHSOcQ*)ngG!I-C9-F1>m|M~mtJf^aB*QS7@)0TfxD36t)2#*~%;LC)1vHs+ z!J>k-L2l$-#hq&WA3ed#tZ0Nw?+itRQE*?+CP=DDQT8KbuXFO&*EGGkVEK5gUwAT9 zqFvIzXH1;yw5+VfS)$+@URdi>F;y}x$YW6@8uF^P<===(ffsD-kP9-2aLJG$h zMIl5j|0M6*U|PK>Es)vRIJ-zV83*?|*IFE8j#fT&bmJ2-#bI;o8I`7PNKJ$V zMscdOpL%dR4Rp>b=EHa$fT7G(AmgDuBSNB(9DHR&Xo)qe$^5hc&`04hcIo|a^>uhg z)Lqz%C7PPb(5T$NTV!Z3bKhS^+?xwdqyEK`Pd=ysws2rnVg}I!Y!cS8f;Hq zvp0b>tH&5m_lXP3(}8-}XYuDK)2$vHHkq+Q*Ka%-n0gH(?;}wcyzRCE5pc31n+s3) zKrL>sGo+u7-Ux}DOqYCKQ4Iaf`Ny-KaMG%*`0no%a^mzm{qHIcf3W9e?1Wp(8R4!qJ!x50VIIy3j zVMtbrQF!^?yCmJ?E&72%*s>v-tIZT;rI8+!5wWzceB2}|C+RaV%GF1I&T)b2n$%v03vY<*}$fewdfZ; zZYC?`v=9Q+MjF)M{6uP^8se%nQ6!7y<|lqOJHs?|I^!59&fhKDVm?kCG?C z8upx<5cQez#05VAuw3=f)68&ei37UR%iMiLOB>}o*Zv*#|!6zBSWqmDuIy?aPX*;t+Qd~ld^7?iM(^`wUK~56t0>~em>mX zSiF*dZD`$;IdTKezz(aj!XYOR+ z8-P3+V$$rVwDf=8UVt6fCehw1AGS5P`37D2qezplzW%jb(^_!AxG#de57+(t{Zvr_ zgztn5Quz#$9lGwGm(A}7B5YL>0V8QA$OfSS_qvEJ{qoNC zP68=^(;q)WBe8v|Jr@$?n^1n*rL5#i;Vs6c_#N{iPq1bekYhw&BDRJLp%P`}AKuiH z_kczMBE1FDUcBVaK8>^N3R5vyp{8YoWGUpO#c@hAwq2Tq5VTTT$n)!TJfT}af^A@L%DjMi0W7uNl(i5W?z$N+%|5_o?^sh>smhbSOc zlq@a{jLyyyz`$>xpS!o0o~&r7-?c+l4LL?eS(<^n#^C5>9vpTX2`z)WJ)5uugmz2W zgb<%msijuUn7^l>gef%F)N*UTV13*L6Mt(=8gQahAyBN~vgdi25-%N-+FS1Ka&qiB z$oM9YLR4W&>rncdVXQnAN|c)wM2%wD#8_T^3Yx-kOlCGU&$;AJ49aa*p4HEYt>@;J z?!i=*Q$)F!z4v&S4IGV_Lv`s3?+u~lu=pM{aFzEn-IQjUhORPVSMjKNW)(X< zUNy9|q@c5;3vs4c)ZjFji-UeL@TefS8C(34RYJzh0T9mRo@j#|j}W#X=RTUt3z1XT z0t(47SS|1*EC=ZXG3*2#VuJAR5Ag#d(<5m8tK9NKNd2WIFUEqqNbdGAl&QaJ&5q8T z10$WJIwR6NR?3i$$s&83oucL~bRC)D9}STS4p9@plpU=%M4Qlz#Z})8g}$HJll{zT zkPcu9ZIuaaybSGg-v78Wpdpr0tMNN3S{GR8$}kE3xktO%eu`a$GeL;)LPuAH4;eVt z-r(!ft_5;SXtelMfrYwhD9Qu_T^Qu(?i=B$SdO_nXyCLb!^S!()`EL z!A=OneA!X=&U&v&P^dXfUJw<8?2ZDy+%EvD$+T|-nU6K%Uy`r{EbT3q8NSd>07In> z=5Tr0$tsv(XVy2zHekY`eIBZ1$IT-kFccyL+zjFZ6p< zw5})lU#BWwQtdvJz58%o+XnU7vCxBM+{J14P(T_6(nNKwlZs5D5>E<<;bc_|VXQ`ph zHgyme&*JapeSSa~o)+X2cPgvfX&g02n0%UHxCF^ReRPZeUBALu`jH2ApthjlCY_j; zcfXulxv(h>M*KBhu)D*@j!odOr>WUJ=h8m}2W!TKK6BLzJu3%68g3j2=^9GY`>x-- zvLOm|HPblviLIR%H+9m^P>B0T`B`oKM$U)2E4Vb>7@W}30rZ#1_PdLtTq)(C419PkheEEWL(~d;g*L`6HNb-$HSAWBgylNuY-#yX!hy~a$ z{bxdz5^q$1+$bjT4@tf$BqLtq6-|KgUyaX2yjgl8W^&DRk0IyL^$6FMK7w6~h3&{S zdOKD)HO7{=IKu?r^H6}yKG1wlpoRIK#Rm@l&pM5-F=4IV5g_ahX|OteEMdVIg=1hQigu(Ae0lA`*b z8F?)&>!b*9)a|H@dL*j$55eyGx9a?kvvnC>c}!=8FP%~N?=1G9F%q?0NKz_j+kJJe zd;CrFN^3_vQ%&p(mhpg2v7iV>3y%ZaQi)g-7k-#&Hyhh8#WQG6u8W5B=bin1oj6;VA26Rt@Sf)`|a~FdWAVId2*i7Xl9A+QHi-A&gX8DshfJ zh%`L&?YMvYY~bC85Od&>99!F`(aCdrf(%1{SB%0nN1H!UPF&i`{|0)peihH|4OQpE zV*JD+x2K;^@dojJF47w$y7ch#X)|wf)40><8_)!Q24F$d$Xch_ySe3RJ)U|T5DpSo zG@@?GiXi%(!_}C1!ybjw1Ic6j=j%w=+Eq9iLcmf=bzI1hnY_C-Uw~XMO%03}Gk=m^ ztX>l38~Xj=mCAI2&n18bK}n6k&)9aqUkMHes@0nAn^pT-93kW2UIzAv$+{nIz%^mH z&Ik79`?h5Od!0H3C&orOVVfW?dJP`Mi)Ue52`(h!_AY0GJ*9 z+-1u^J?X1!*<%5`_Qgg#Fm1x^(a3lN>@t?UX5eP;mN=u4=* zXlXB(NZC0a7~pX-!&y*Vdd}C&?n|0cl(xABX-f8@J|wFU2XVxR6>~Uz)0lf&#o9I# zMCF3(dy=E2<;QEeJr}jbB#6M|F+N1vA<$7^c>NziDW|pf7Rc4RO#N8n$(|dH+DA|C zI`1$LA_cM}B&(*9V3_xCGWKhBa&Zd%9B)qxePxB;_sRk7We*ptV+B#P0P9Wo2f=p$ zA_&ERB{dW~a3~zVL#H8+{79~N#ipHX*`-dDjzZ2z-pp_#@ENEVY7WnMsV`O}uux4o z=kBVTX!?cbKA&FQ6rPAI6MkaEHsWzbYj6hny}m|H;$#z~m5ds4su@{2$(Oe zYufKwDa3?c)&l`9E6tb4?-=AtD0EzOHv{ccB$JJB%kvi&VuXDFEYNd|7{>`;YwX2{ zRFZG;5fs|=6#NG%q>Zz81gAOnz3m6f`W#yQX>xflxQuZ~V?$`J$pE9E9SuiEM2{~u zb}lg-)E-9?4p)qskCG%~13?}l0N+XOqY2&qauPXQvbW&8XyD~nYl+zoWFoz}BQ+oYU zPu2O>lPMn|e`}n+gVRU&EY<_;Wb~pd)%f$<_)RpUm$SX<6^dnZ0KCRE=>H}3!0Me`) z1YaFcS&)<|3|}1qfM0ei>znq^aRMMo5~I4YG1-sGdddwE;<$30Fo_6`&KO?Uma0B5 z9b>v|^hSjtS43*L4oq3a^qqPVtqvQ$&A1g6c^~-{M=9J>Y^Cf^l`oEZ`v4t~Vn-sLhu~+V5Wk+Xo}0@7RT2TP`9> zQJRY14qV|VT^MO3yT<-jayO6D2c}^0{3Vj60`AsDa?75YLLgZ?rO@##;xP{G!{XxibQx!B zx{8W#|67Z4J5C4HT;u&0ASEjl5RaI?n404Ojaa@fTGS*LJKYm-%1Ca_`OyyI1=A7M zAF6Y&`TAtF2ntTSE$ajBY9{cTwI^*I&v&uO6To80S+6sxIPfBv_;w<#ClX}7z_-b+ zFWYJ9Nu-nj2=yn1)$;*cSeRL*>t5oBVFa?w;RNqT-I^rxxkF*E-AVG@^!l9|<2h?+ zkAoPu++T2u-}4_=&+>i7F+P~x3+D+Xqun#d`f`5;5`|DCL*&8%10R*J?&7}V4W5mK zAR>uw$lI`Q?TV*6VQ)o`FII(G(3Rm?*1ZU9Vp(iX1kd6!*&a>7kyx$6_e4ic;y_N_Yb`<7I2XrXbv(Bo zx8qw)8{%3E$cb02I?c^=qlDSLg!_votP*cws?+abqJiUuWRNrg;$a(_iYYZc`68ff zkkl0g^nV}e;1BN?0K4Ej61PWx)CQ*6s z$(ZV#L#~!D&>-mDp0&?H8`-F#ZBsJa_MxZ6QPKjysRgc&pe&#H5@r#qOg76FPxq}o zyx@KqE+!U&5aQQ>iQCp2!SQM{nZa_3an^u8Di!?2UD$M|Eas*_HZF)MsQOQkxJB}&=M+wpLvemjg0K^@ zb)PaPIxazyS5&t9?kJ}R4+JmAaMVByJa%yVdpx(rxJghNMrU0m2OsFy4xG<1r$AfZ{Por*H-i$~>DWIV}z|6P~SAt3_{908L_6Qvi-;|Mn@x~Sf>pKya zD7ax1ls>i&Z#FuyxWV)=->{1bQm{BZooew~IC@^cMl%A!8}L)-Bj;oO044LC#4n;& zaC-|FJfyy_j6$N7!!S_il1AG%c78MaHw|C+mbm2$0BDX5>?Sg3IsrPVwG;Ycw>O^O z9fN8a;KExRbXDO#NvBF46k-xzUV^#43$4=k?6WO*lslm!slJYD5xY#77PIrTB z1UY?jpkPYwdk_#ps6mQ!&{Td$Txa?vkzR4v*iYfRk@g|vsnGFbGq-SEP%5i0T+>yN zhhnxLzpqZKSexKO`EBPz95ju)@#T?H%h1X`Y10b*%)CU8W0RQ8Ln93GnjOEMl z_!XNV#>1?iFb;#3qNkEJ6(+U&a#6%{_S<3=FO5eZuayBJP-<-nXo?->IyFp`*L`-S z#TdkbPTcTT>$(SUnq+Tv_X0lf|vLPkakLt|m8r z7A?XdfaH9*xBO1M#aB*6hfkIS$o_LSdH{DCv~_u~uIF*e=ORg6*}*&onEDHgfOBvH z&ly>ONI`y5$8staQHZN!jqZ5Sjod@aW~uTome^so;uFDmJ4d(?#P9`v@e{A=Wc*@A z{%`%hko$OZ=`{p`oR~=1q}zOiSuVTnD9BzG@}gsxG9RPI_sSxWRM+2X>`V5{Uz6R< z)dfbHZMy|uq~eZ%#r7_P9~OY%=rDkkfA&(SsLhg_E$&B<-nFYnV_xeA!B+|>xOsS= z!zf}@f9k1vX*E3oI=5{otz3Dp($$6$$W-K(97VW~7!`BWUM7<&vbW+mpNbKgcKnie ziS5I;uC+auru9Ofa;YDJsdcX993-Y^cL_CO?CF>OSQ27bA!7imHFG53!7T$qLWTX+ zZ}xC9CG67GHC1XZM-#O;xb@hwbfQ`FP>EG}>TF;MU}4Z?@X!RN)&_u8X?+}wKI1sv z+2Q~eO2mL1XJXFYO*?TvN|LJz9t(!r{$eJf+I)2`v0Uz6G{wXTIlUMqERtjsN$KbW!w9-AR(IPq%=}if3z+vc6z5A- zb0D72DW!{bFSqJ9#*^>-*j87igL8ZpZZ*#qQ{rgVym+zB_{eHB@Jv7#LZ>ExA8zfq z2I@{chlnX125ViLLJat&zW#}GO9gZ%)ZTK^nqk{EaOtggXnQX^)FdfQQY&#=2~+lw zbT;p1?>~+>f7oQlchZSBm8FtuEyZY-0HzF<(6tsEcRH!O6}AaqVJ>) zJgX-nQxHfhiqD;wc>*^BUFsc7YhS>azh%y>6uMAdQlkS8*84CMkF0oh+ek<8Sj~Cc zy(p9eAD;0{_Q{pbfMk$L^fo%yge%YI5@~FfLKoeVwRQEEYA^U`#XHH_VnHO~#&~f+ z_jI;8N-{#@8@BVn#aypPgT3xtHTvpx%0L&@>GYD&%SE#v-o(rc<)u38KU_xYQL-EL z>}>Jpv2NnHxFTo6&EI4UZO1^Q>|d=}3N_}Pm$V27d8A5>d_>--8Lo+1nq@PK%tHo% zCt>QoU0hWn}vsqvUy_xEX!X zOc)O-g%`xGr8RjuYl^k;$;^!)vuraxp=@-P;O!s*6*)Acyv!N0;SN(DlGL%vN z9S37eQ~$Ak(`pdV$!hufU?5r*`|1ncw!5eoTLyKjO-XwJvj>t&6hs`-J7x#?(aO9n zzO3mIFf0w{qML)?rUz#ZdAGdq6K0RAoQQlP=Gv)g1fO;zeradVAZH%hpsjqCA=~1C zMNPkT{5b9aC-?D}qhTi&((2<)vT#cGGMQoVi*%2c4&~A_9O`fN819V&gb>Jww~zh75yv81dNSRyrz)g~w)>!CEAu(gVI%*9uSQ zVJbzF2=~LXx*R`JJW`qiYhxtKx>=tjuaV(<3~6dW)s*y)DCFcOX#mW(oyJ7q3##V3 zHw>LTR$iNPdJZB_RTa9$!iIT<6I_m>o`sdBUrw_+U(I7`ALBD&jvK{VW~l~j&%kIV z83Go|yYLcP;Q3@p@EM!!X;Gl9^)B`%K*r$8Mx}>WoLh)j+wI}SoN-;?6*K4ps+B!a z!J5}aTFH#miQ9qBSPA|=?%pyuu4Gvk6_dqeNfubl%*;#{Gc(y@X0*s+W?9S@Gcz+- z%*@QU?eU)3o;~lqcoFxU8}~%?kB;hE1zGu3W>&BKs^5MevFMhm(+FnVKFDg@Y<&%{ z&e+rka#cDlQMiafP1@?HRS4Q+NxPhl^yV}(+O0+4?IGYcQK}189f_sL$0;w6u`Z~| z{p973>c*wwud`LDkN04$A+Y2z$VXGq3x$gq0bIO!1@DM7>_*H5;CnxEpu5rP5b`*ucP z`fj4H)oz8|UMI9STuq!k1{YeZgI&Y+&ZTKx@S+uc%b2@5gdknvfVDpfz`kul+~=j*V}D0 zM(D{3LPMt;!o;bk6u@qNEhhcWX60s~m!9GGL|SZiK^lG6hSY1$%BD{!2X5jrAZr@? z*_d+zC+9%bJZ0|DPjaa90ulea;dP*@H8`SFuia}N&jJfCX(Sqsz~^YaYvqxC_a_!y zDU(6;RVPC3n5J2|FF@R6mNuJf6(T5Aa{IZB2y$+pUgP{ff5=Y#X5J^75D**Z74ry3 ze9J5}MGilb2YE=s_fGr96I0o46)B=80e`l~_u(EDD$biB;+rhKyf6)q$#ZS4Hrgq4 z!d{LWxe=e?ke)PC0ztV;&I6Y!zJP8yAG++6@#AxRt{H0lo7^Bh0!T6@XmSHbC~$Ga z1%}!qfxu6D(U8_5v3$9-@!#RI)!YGhbKQcrdmtZDe^S*BrUwP{Hz%4@(SXF1)yxvb z7v4f@GiKj7Q67DXMcnE(2@q&T;5a@8m1gON1e-oBveC9ZrygC@Qu@+Tm+m9`96m$bc8;^R3V7U1E@KrVHBrw zI}oS(mKjTW)8_M=yEV_9Nw*tX`%0L$u|P;@P^rl28;Lw0($yo2IXZfuI{kpP09^fN zakV$Guq)4ntOq(S>q*O|SjQ8SwdH zSU{khe%#hn!4;I6Eo5jK{7T!oWY!jC?uokEQw@pgrB$LZ7LNK

EomaJIz^a+r{FTZ`uf{4?fK}{#4oSqD*PC0g@S(e-FJja9=q0Apy!y_W_^~YRAfS(2lbu7#SmGK`2)qCU1Y*UX9sqdt*bCTNsJ`T~C~cG)^ZZF$5RQiZoa_}n4k_CQnUu0Q zTIQ>i5|ucoFeu-$TpA9H)$~TE!QEc}DHH$wg74L|bdrUtDv-GLH)ENtM&SZ0kBY-> zq4S46vX?5ppvy`F!x&c<-dUCzhIZemjR7CAlJgOFcs(9h`F1s0$itFmdaXFp_~%%I z;c*}p#mxL!_Rrn$nkBdlnLOlFO2Z9YPmisu?~xDWBe7Cg_Koxe&h@M1+KB9bL}2v! zOLLAf%TNy!DbBz$w?n|-)=3qqt)ut*v20z)ZwXRY^cnmqa(Wr&KrV(6>b`5J9ZV$% zGP3pr;a3@bQ(bmhA~`pR>gQ0P8&{CZdeyDVz>1Gn}MJ?0vg zidMYAQjTcYI7PQbV1U=wrGV3Ogny{puQ%YC<4l1-ah6N5LJy3AK48C&_ckR0;o7dy zfWo8v2(f`RVsFJ-fq=rO6{x@mAXB{D9U_7dyuFD=nAD8`?Fj*==K)9(NVdQ(3cFFg zB(8q83sK!^-Ttcw4AUXS8krKqth(ib#6I@e+Huh8NDz-pu!EvwJjsnQk4r~D%@6#^ z#Y|FOKtSB*mUS6h0g&C$C(okeSGn#DQq4}YX@SZPGD0j1?ItoP&OJ2hB$C=o?M-n$ z43lsL83q!ZY%$g9ta=cIw*v(6PMN39k2ifM&fZcSn5iYFTf^A%6$090Z@{fov%Prf zf|}t1apP6)XHg3WU`Ye4-^ogS00TSIWbb-S%GRM*?m@3vjfK_ozFz}f#on;<^_R>J zWLjzIurF_d43I*HoO}N2jSam9^Su&+q`e8FEGGgOIKTcPo>u?0j>?ZeLqbjN5Xo39y#$)xNLc1CU!&e*5DEv#8*DpHdI;aU_nIy8~G2gln zp)*znqz2je$=>)n)RpFbT!$;jVkD)JwP^}PR?&1zpv=l|y6y;9jeC;3Ja>{G``EZ) z7rvxWQ0S9XPI?tJAxH79nwk?KSPfEM7P0DHO>kxtCeON$&BQwfGf`WAqBG96hS)Hv zSQIlzomZNb8C-b9t3xZbE0PsmqC|l{vEO`&DTn zX@ArNHpfJt)|l#M!ga&zlRr_3YK-rvOEsc_|&9<(%p*%20;A;C*UrhFnnvrg<=I<5ac4i*OTNLiqgFts7AMNocfI-PzHZ`gAj87a|btsCs3m% z(&kqlbV|RMCtsQ=QbfZZ$EeKFmcCXers}Epabs;o;MIqmh0&+@1*SOW+Z(ZdH^y&3 z4gt<1iC_4jhhdy83j`f#<#R>)b<&O+wDCKw((oiqm@|zm&9y%2$6tQ08$oiHZ#1Jq zSek5l5$CpkvWhIkGT$stTMTY+%oFM4nuP_e0`L?Ph{DPur6&EopYVJS82 zc)18LX99_hb!a&)9MsFG>6=eOKO<;oJEm3*6rP;@R3VhTi2?mQ?s9ehO|9bBiqEVR z>E!4J>B?3MzS7$H$Ie&YqCfJ;(fKprez;SAsVQ*&aQ_70m-oOKR6-d*&no=c!Vjk% zK{1iQ$esHmg}-WIS_A3;65410bpVR~>!aHa`1Z`7!uT(p1rc|Kt!Kz}ty+vCsEXsH`p%eowPJa5*K6*}SdBr)@vvVH z8a%=#Z*Q7WAX@^&9aIUP$nmI$6NDIc_s~Vx6H?wF1>TgK4qeBWJb_?;e zJu$WHpbUc5*N>pPZA|t7gIV&`?{hws=GI$capn{;r|B-XAy?YM;Bb4Lu;vrNq6|Mv z-DA68Bu9Gc>Me$0fiz9-sxA=u3O;E@%30gwr9A-6;rX*u4ya4wQW0b;ne!Aym#)b{ z2(RwD5EXM5PvnIB4n2-J9Nadrax_actL(}7_V>dg+!3nvxXf2+cp$1IV$xm;$G6_s z1%9}sIgxrr3gd70DO13pyjbq{34;a3LU%ktk6|g=hEsp>%argl;=}%g(x+#y z^R$Aef}NrFLvb)W#3qnrsNQctm|zx+%%wxtufJfALL@qBs`5-et41tlXuju(Nfro< z9hFCMc>0n{zIV;^AwUV^SU+YtKy5pjHj`-3X|)dYhIXpFTwJiq^%FHY))z?`Pg1!F z3>W$wVbW$ew6yZShzO~YK~RvVtyfo2`@&* zRh{szh=N3%##R*1{oqzIGt~3UGSelvoIky{#CQ3FoN$kWpr=DgA?pph5hNY(qE(Ei zaLSSm(g7TiztlVMfqVz4fu2y0Vj*6CV~_DhHy2ep>x^ zAuF)C?b_zYBFthd(tBWZ5>Cb5BtaW{bW|7QM2A&7^^^efk1P!u!(&8UT zd{uB?@*hh$yZyuz@Wz+rf)1l7i*FGvIlW*6;|9U~mS&esWLLRdHuG+ILDJ*(I4@>T zrC5Ph7h(U$*1?}4_k$`1XmkTrD$o#H>oVW_$GpKs*8m}p%)09zTZi?3=BENS6x-iR z0U5FY4)p&>H^*(e>`A&VsLqyzaq|KcN=+>kE-#eJYiypO?%!|`oQOW-`V4nb{`y% zr(!dRdd6`t)5$h*(cDpk1s-Ww+;i58(rz96+Wm%Zc+IUK$)#$=^1~cYOZ2-8Ov4Jg z0_{`=ta{6Q3c8WHXOHiiv8j}MxXx4;Uedh< zRo+MtG!lzsc;?cZJ4tc#5{?-NlM>F$sk9FxC8>W3vJA5Dblg z_i-0~jMiL&(Dc|iMa-Wg)YG6dux2A&Nw7%|p+9CZ2D3HeADd1gsViH+52|ZzKG4;LaUKmj~LLi*-D`=Lr%i|a& zQ>430EED=kqpC_Z61Ap4_*KQ(XPO$1;P;B5)^aX)uW_Z~r$u4>^w-5|7miu@-*2Bt zi;Tr5c$%gaY3T`>rxD&K1o9NGb&}7x=F^4)7sGm#uo#2j`3*Qxlf6m8txK-h$=S_Q zJy))#|L{X`{fE1`Yty3D@sk}@?kdX!A({<*YZ)z;0s?un^8w1t@%Nnl7U;c+%k2q1 z(GctmOWvL4d)H{so9@Tv9^D_!LD?I))N?we3|^R>1D-|!&Zq_`JqUNLI)MA-hb;yE z5hwz($bV${|0q_H5>_Pe1_A;Dge$;Pf9CbG2F@F{lYkk3a|h%{Xmi2fvvMg!z;&TU zvltn(Ob`TxQ?fVJ5h5$DY<_XJ)>_=M4<1_sThoF5fb`u^WVZ|3y?w{uvd~S1ZpGm0zQ95+O1lL`+uLI}RB?Fr`t?88eJx@u^ z7ZZMJ%#r#dga&Pq8pL8Dz{c1EDSm1|7?p|JDgaK9M26ChGj0}xYEJw#ULE3I6_*I7 z+P;tt`r5E>uuL{Kz%!7u?{{rs3JFp`h~R~s*X}*6I;4es;*ssi^uiQ0i+wksWN^bs zxe;L~8T4rc)<8>3>ZF@Pr||gGmdNBI=m zvfJA>cogfUmt48v$x;T8q) z3@{3bHJh2%Z`aZKMPt3FV&7u3ix@*zbPcl#cEy6y!^sg4Q;MI;A|BGG(k&CVf3wKe zFTKSf8jd5L58g5Sx!$NzfaNCmJFURB$v5jA_yDOtR00TyW(`n_2tX|WNTNqm{w`<^ zghcmEa!zGb${+SDKKP^iuZqI$fOk+m#45AKydysNG+^3|V4QS`6IsCzYrv?1$M`)6PDACzVPXiW zdxNi3Il2pKkf}L6s~)EVAT*;FWX;Bnuv@QKa%ZhuIZwm@1^YkJJj$edjeGZDPJEWD1W0$*f?Ch zwuGKGvEWQ1g7=cQ|sNKJB z9Np{4W=lRLW7XcftCq+5BEE!BXaRqwB3ube1R|0BG(m`A4QBsS0zlO&uu0Z9{RF^a z6wr^WIjd zT~dF)g@vA!(&o3}nNZXZp(L!r>D#M3U!ZdW_tAfs_c5gZs$D-&Q?dbx;0WK()t1zz zk4Uoe#c?vV`Y1b`Z(2$~5V_$w9OywTNOZjUEJNQuP)F+oZ2EylSTHNN2jEr~zkBSm z=p+`LH((%F%3I@2s`YoztT}`=DHt^|<{NoYPqS zd)aOLn^r|8BiPTcCH<1vtuBEGbn4Jp)BQ*EN-+{iX;_v!E;l860l1Rona|_-_D-D1 zzGloCz9b-psgNg1qb9h>ew|IF!EBo4L7&^p3DZMdZ?A4s`5P5P4(A+`xZwO7Z8p>I zd|}>V5b>FvAmeEoeTj!2^U%i0BF4w{3b0{BWw#>sVvhGyd8DdRwj>B;nq{@hb6VBg zVWO~NcYO(Xe?!3cDX)nP{?eduesZ{Ki8O^?yd9W2{GPiIWhiA~muP*}*gyCof9K3N zsNcE8II$*Aa>NqD5J+X!)X(@JMx>zb2z!&y$jB*Kzs|1ZGu=9}c=wdI^L9aRCY~Td z^d^a1%_qZ(d<#AhX58)%-FEB4zByFp88wW|c1X%z@ z|Nr3Z01%4(#@PWPWd6f80nR6WBkcfA$Q?2Q0`UXZvA)6w{4V#CzC-dg=m)0m6)z1m zN-!WUE8?Qp@XL9WGk=t7e(j1B{m`?!_s!_+O(EJMIHAkI)su#T?l$S39z89Z8CPOa zl&}V&;S?qu>>1e~L;Z2a{}%<$*I$SQ!ut_*VgXKMe*5p+jWFEfB8-?)>ck!nK%Xfu6UKLmMn|*xmaW52~Wjy+{d#9)eC%vXs zSawB+TWW<@4(q_X9>Ob)NxpfK5qKq!zzC1%eD=y3J27|S;gqGxaZ>CJ7~W6nE}Wm| zM}G_){fMeOa1RK+m)MZw$MDfA0K)(W>db&b5d$&E5Lg^|CNXcuIV6s#P4lFs~1}{;M0kFGchxw7p%k01o&as<#J) zyctdEW}=xub}4E2fvhD9cRj@d&fhbOthunnj5tJm18Z01+Rrsc`{mcXR%Mvbi2oH z|D0V0&3~4X{yZl5eRdF!U#@@(&g#PCySMQ5PvE$z$5%+)PL6=hCj{vUk@O?in=p1 zc^o@Ub)nsFI^f5eE1^)Pn31`<=eYt;uK@-D*bx4-kN-H|e=>{!?EP*S-K(sD$Ve1@ z@Xr8E;{RzN{~8D==(ZCgh|9A#;lbOYA1i?WZ{$J0_lt9Xz#?Lo5eujU=;ycX2f|4Qum11A2fm(wa6J8b#DC}!$@7#g`Ju|h)9#6aE->$mW_r#Q z13|eqVlI%Q29+RUO2omrPqxdI95N{gip$w6Wzh8SmZxdF496)x^M^M5fAClVmgN^Pe_u0zzW!qT`p-H2 zMdJ03bNU+s|D~_L`2#>dOaJE}4=@wJ|1JLy%KUfK{F3PZZ_B6t?}+)YfcM{xBN$|AaUI4u3a=KW#MjzvJz1@czT} z{|D;+g7=Tr0W|x&<@<>+0K9+U?yoib!=3q`V)Oo6koVtWs{ru+#f}P4qW=nb|J_af z3*Nu1_b*5FFI8#(saXHys{YSG-hYdw1Hk()AM|fjlW*GL9_G)fCO4ANL%lr(^qABG-OuMLYFn|KxP0P9Jno z00>SVaLt>Di(Bqz3Nb6<GNk!!{K`-l9DfB56N&|&(8yeTJmnAGGeCJM z-?}4qeg2eLI6I}+g1?Fg&iwfM#um9BR|sgOOXwoh&;6obPtR1N4j&%eBFjTfbF2#Tti zSINa!1ofgT`Uq<|{(bf7ZRrJwW5c1*u1DUNC)ORaLVR%{s4q<G%V4MUx3u*)~kcK|CyCsWD4srxT)czyhl1!uYfX)&H%^f;} zfQ;>BhLnDzJsvPQuO_MYslw=IMX~_zY^kQW#%e@z@_JZCeh1s{f!_F0J3=N&-|N74 zz%H6w&~gp6sIzkEUnaXA;fAB}9UiphGsKv6WSsRlio8hfD&*G_dgQ7NT5DD!@FRnU zpTq7$VzJtGUn4#^XOV4=8m(;QkI#PSxyUvRnm@NGl;vf=^F8RfAwUx&0bHGO85dq)8DYH2&$)e&dUv!wj_78w13!GHY+0jk@gmDnD_!jN@2zW{0mTquvVf z31}#pW1Sxq5yVU75ME#J)gRkl?|NRJ`@C+8Udw1Vk=`TkMR4tcOL!D`FzN*0KDNw` zdfJvkZMCZ`#-vU`#CZ9Ma@X@k5RwRvfnlP}?Yx2I1rCPw8Nzq=$${qdq+p z-K8Ki%@x&!>B^RrN)gM~AAlZ&yM+0}f{^>38$l8ajlyAl*7F)1^Sq}!RHL@{Jg@ui z3C&%MF>45<5u0^Jvtj{8|K>vf`Du)jWWNnVQHHV*Z}niC$m=WGxc!sqhMWgDW)T*@ zKgsMH%`p5;Z`DlA^aq|cihk{SrocwQW~M8u7b7-UmxQ6E06oQ)4S@N*Y3HZQ_#ka-j>@V$x$a$*1eR)mU=yxl`b9%qzlNaC&&L0J#kW%2_ueykpFY|MB&Hp}~kgg@!h_3SP(XkWqWTevX9IHndw;RSgJ9Ybznt^HpI! zFXmQ8(lL3Nv`IQt8*$WAPkeo$w!G0~T`Xgc7U)EZXHxD{w{HUP`~F@ZzJj^)kbpz5 zoyIIbimaWzH|FxFy-FklCvLDVs|am_CxO>APoyzc4n;IRD}3&wAjfOnHjCiu?KxGN zUn(Vv;Im%0!f=c~z20lb+1c&sr9^zBh9y;v{f^8V?XdpwGt%>Si;k1Kwqb_t2?MC4 zjouSrXw5-^=rCMsX__tUS}-+6aA=EhhvE^}P&2IW9HrMxv3A6rVQTLhA>>eZNIzXR zW~TDD$j`i)d}Aeu&9GVYKwX)r4p zHN}md!QRsWvLRdC(FdX}?qP=_ftF?9Ft!X5lW?Z#n89A3Svm;0OSpcozCM+8j~-5z zKXW>3SU%yN=8TUOIKCv9e{tG{;*8QzJ2T z_L{bxo-%wo$byUCuG0pO(|n)&7M()A@Pm!}<}5z#^h^vkxXuy0mEG-_h#Z(2?D5*w z)PS5VhBbD45^I!*-l04C#F<~CCib0&;5@lKo9Fr1LVWEY2{L>n`@{B@vUuSHR4cgN z;$DhGf$S#!CDmwLb&4i>?q{%I8cc{#;>Hm);Sf%7&rz_#M42^xSa)5FOfQrk@JlO$ z@e=9K{UvN_kOdYz(-!^k=99OSGfxA&V2LN77vn<$hcBZbSk%ZxfQw*T0e|d(%m7}B zLgCey#`&Bd-=7Ck70Ch~$V5f<5Qyq({}~*)cCNo?^h`&$T~*a0tH ztxJixn3K=qbYkQi4lZ)BzFg@j~tuy0r zmojc5HT_~FQ2wu1XGoL~+|nZoa418L;2u(fxna-ft*iKy71<@>_`}!y{AJ@qH^Hzi zx68|#2ZSHuKi}m~MabqOkXPQic~L^`!X>!QuinW#ABoSw2$lkW9mHw!gjWpIyo-kC zcom{JD^gf{gZG$!`sK}J3}czub1wY{v&-a^Yra)yUIl8C%0-`({Nd{EzLR=9zS*YqP~LoHX6 z(?qy@G`x3wmm^0KWvKx-;?F>_p$nk?{hF!BW(Y{ZK}os64aBwk4o4{(LgI2y>--jx zH78eQ6#^Jtqnk(0!l-9zsZc?S*)lI_InLPLPLAM}na+@E&Up`eRjPx6G6Ujzxp$I(a`CVJxqwhUtK>ZYAvb!Je zuS;`O9y8A^Y2y!J8%%~0KfP;~T+ysOR>oDgDlcnD+%EvbP}+~V6-e`H#GajY z*x=F#+fT4WW`$g|D^tA^0k1Eu6yJ+lhK!p&Eq`vvRutqW%opuCQfc(?Fe9T#G;C2y zrxNO;WJfWebRK?|q%2q@P~vQL2^&+YEimB22bsi0wK(u_bBGv(RBF#;Qs3|XP+bn> zKb?qq4_@u+a$_taiSHZ1Wei>S#Xw;Net-(7()s93hhku_1+|k5nr?h zUV&^=clXU5zsMTiD|o`q$)X^`^-zXMJkZnN*z0#~f>yk5c~V_FPBglS5W)81w>vW7 zDncogJ{Wyrx%uvCQd87I?Zo^tgLv#L2?r2G)y3UA|C5E zPN?&3MhT0=-s%_cY^I%6U+rw+g!R%_8DFfAc1aeM=?X*gOYTWmPHN+ z$U;ccmkr?FD%Yo1$k?QBT*4HX$lgk8VEd6?`=$AqN_x`He6eL~Lmgy!T07o8|5QxQ z?qZ7o{laLMTnq*91XOmA~esTLHOW zJHje(&LS6n{(wQ5QGYyRr?Z!^%Av3xH59JF^}ZeB+;N=OXX#l^=v$J_LcEuy&Dz^F z6*dK1FxTbN?ri>x;*qOJ4W(rkX~lp^WLeSI{JO8jY2E}0;5EG9fEMOXp>ak~@1&_?CmT}3<#f3FQ z@7ZbNJ6D8}O^D&*jQ-DQ0 za2V{^8wURrp2AZdEC@T6(mC0(n^TmzvcDyo9*O6NUWYp7|L;ig2D69h2*6S zL)QuX5J;VF01n3B^7f+!vZ#wsYvM;EKH!zip!G!MowqZgk+^rS720b@k+d}|fw_fY z-A`|k*(YEz7sw**lL=v&MP$E$IBJU`cM|(6hDQ;vof=lwgG$D! z8K0b6uGMame~bPs?n3}OZr2^&wGWT0;X~R(zUc1u{rbj^wviQej4aw_Eid2Ql1IUL zD5L^8N{bj0UqkIE99ll7VsZDg;xV*bnD{BL)r`Uya*si6Hcjef8%upHZW}9M_0S=X zaBep7hJ*6*Bq2~YV%x0!m(P|oY}fO7i`QCZmE(yCpN7==g5qd)8hH&xV0OrpGHaiE zSBdk!p`fG+%=o*kJ)5`#P3U}(SS95)u&Ew78&$(-*==GIkRr|^A_{xyZHV^~udGx& z_8`BL=0Ns{Z%E!c#0R50J|v9sWZZht_X*i8)!(e3?$<|b;dWztG>TT;<_y#C?3k0R zEG$RRonLK^zGktT+YlyDZc!w%_#{&~H8kf$dCai&0TE2Rls^Dg!BnnPZ-yROR#*SH z1Kv`^5BIpxk7=l@ z<%4qmo3fVpYg3igFxrR=zBIq1hQi!92b8(qxb*;|!7#y{_gw-e=N!ZkX0rOsOyz5d zLwD$<$I_WdRZ&V$KCcR|Yt<#s3mFRG@?NZ&19@ZYdKu3=n6@V ze@t1R+_ph4a6%3iKPB4TrS^QVeaHEPwxeq`4mF8a=#j4)7fOPoE4&fA!e)ha{0?LnC~aN}qa3WAe2&8`n(=l7 zbn3+|m5^rd(CxJwfIQ%QvkjQRCNA3a`El zb>Iv>!|0>8!FZ6+ji(B<=-X!T@5fL*y-sd+7ao*i4Z@r{mbN5M#MGD!v>h_!k3D!w z1D_=34f()}UcB_k#BFHrE$~k+B}JiWvR2q*DU(HuOYk(lx{rQxeQmg?2qS-9d*s~1 zCQ0?@%fAREmK$17uXI>$wV#S>d7J&2n-CL3st^VkoKacBxs;}!Q5XCxQhczKLy4=z z=}S+yohq?7Ba&CZUfJ_#-~iz6($~x_WcbU7d^CW5 z?TpO&P+od63dvIhcn7R+n7^@EBIrB}Kzqr&IJueB=MT}z<(6S|c(Jikiyc6{3#7eu z?>Y0Gxn0EOl|leJ$7y%i!f@U^Lj+==< zI+<7Sd>W7+9MoNIz>0yES{ZR=5DBvR>dwhun7y8}!G+QG+6ux+DU4=e>j>*%i0Ja+ z+JP*G6WfCM^jse@A3-(Q^jZ#6OWIa;P<{;KLZd-^O7co`zL0|b6*Gq?^-O*7^F1j{ zn~Au~sPO~u%OSm}Y<&^FYu%2Jo0U&cwWeP&jzAMcKt20rsk=mAqB^XDVvs<*)=d%> zv;4<$qcyKWMCaQWYFiND!0~g%u<6J-nm&X8yGfVKuJEU78H!m!Psp%%<;EbbWrCCD z&kxuK@siC`_V<;*g-TdH{V}F`>(}c($$KgU>{OeQQ_r5+3N7|;jnp-ROd`QU34%jo z)^Iqu>y*K6${OoM@o>nEfN*Sy5J0B6#V_&0E5oW^znz;$h??&Ac!fct4wO&uSO|*k zm=iHx)5mnASr-+bmt?iMWxU=6qFw_bx+S>vPa6QKWWV*!#4<#odtu4gX9>ecX45~B z9z=u7^4D6gk_5f0Z{Z<70mI1oq=4!-8EEgbUsMy^iV;Pw0D2oPCBO&OA_p-JU+}oJ zCA>FXp17%dU&;M0ELrRVUhe_|ooRgOu>DrHFva7r zPmcmGcoI&bGO4Nq7o|Ev3K6zT2dvt)?7^^0aNP8~Ht_E;!ymKmr+dJ^QGHOpodUuU zQYEv9p0SK^R*QTsA5Tb_JT;J=r_9`Eama(Bemun2tfnusGf>q1Y7FUmD+DTCe`j7~ zJ1J()o6msW?)9Wm!+|$9aRysoKMdxAqe4GNt5ph>M4-6L#u-k>Ylw>OsB3z4AXLDx zvaTUIOc~L$Jjoj^a3J*5J`X0Kkka|EdK6KWEr&)l?#YltMFcG^yqqsl7ym)Kk)T^< zBKoH5S>(>XxaX6^)~;g^`&)QLXA(A=SPpd@bb8{xC@kwD1mM%TVc~>Sl+> zn=FU5H>=AaHk=ppeh&0gu8XKl_VDo-qp{%1ZT10bSI$oA4owk_s>iCBiH91Sv+Wg) zm_u08y~v0MUJ~x|?!JbY$!x_mB5a--w&MxC zebgq7u}GERgxQ-i=(ohya(m}OsB;)Y@LGlC*seA{n%qHoKT2m1j4!2TD{*AnH}_ru zcf5mhSQO6*dG0ze7%Y_z2vY+A*AghTIcBlBr^%^lTKAZ*WCgs_!G|l!3^f+*aJ4D_ z4MV13)p;xVD6<;)GftQdflx)HZBM7hkS;gZdoUVd7X{!mXII$$9Q(z+eaZ^C)3mgd z+w8I)=Eh@#&$7rYhOeHeN@q@#;7P&Ldqec>2jk_JO*JQeOksH}^-@?F&BzI)NuY}h z9rPmRXf5$lmzGvWx390SvoSVmkLcwy8eH!(C-T}u99B3kT)^zSV>+PP1h^KhhGRXI zS+Zt>Ok>LF1Ua;!G79b_LmF#2Z1wK>RH&bf zGyzlS30vGLGK3zNr!rT6I!BUGi(Ao?5|H}-JUbc^Pzrn`mPuv$t?5PhS`I7X!E7;1 zKh(}y|}k0hG*^V7ZIaUg;dOKv+u~pLlrT_-=<=P^j6hRyYZiH z$@}MhssmF~>Urdcs-;U1yM6hq(%H40k|`9z!C$~@lHo0TM0dnIm=I(-#c6P-qb zCp_)TaQ{@@K~UFmNe)#|C2X1wHFX6nFE+oE_fjkPC63QAV$8DmJwZmhe9VoZf`lhKfBfl$HVoNZyakBge2#waB`PLvyu3MPKQuUdXF95=wRSC7+!)7EY4=tdIF*0m2sfYx zJCE0H@ae;Z1vs#?UVoMtHK?}+A@zLD68Tgy;>)OWi4k)wFmmzevp<-PLQQFpv7wHp z!L)?xfeh$13geJFsAIlzyQOcjjo@R~VX=A&FO0Cled4*iFXr*KeikJ+ImU&!E<@~< z)O>VN6APOMi!J@dQNNeQ9f~t=o9LNU&6=&>mkb9O!+E2iyxbg$Qh+pNgC^a8xBr&=7O4D%`X$u3_LO_-b z2MoCz9Dv_wI`DRIjLvUqq4zdLD0}e>v-ES=4U~m;3i7Xv&mrkG<2UFk%t#Fg^bNF_ z?=MC)1#b9^DsQBGgz3PIO4HwI4tp_sMG#X^U^Bg-9_*C3Q|wR6_}VWqedt>1I?(FBJIzte;Ak@SNhLJEp&`FBU2DOt02* zew(C6Qk7UwfGbQR$-q76GUnm?CFazVQ477F6=+;xdBYsJvA4%_)$NVZj)@{LuX({q zKotE)I%Sm+YQT*{@4$l=hW!hY-20H&K8M3s(`Zk9!K1@Qhtkl2D7Z@=V(~J13QUO2 zI(VBVh;;IN25eMMe<+Eka_!}gw_>n+zsJa}h!LuBk0#RCj{`lMvVUV0oZjJ=q(Y$aQ}RXLB3w0Gd$A*#lRBoOJ!1kM(c%!qf9IhJlnqEk_S0%6!^;}%l6xUBU2M2Y! zK^fULsq;11YLf4=`(+EenA-Zn&Jly5-3rFjeVIA+Dhgn1@+uTGef^XkJ5LF$hTJ*5 z5fr`OIfXf2_>ky{=7jRUGy+-uR&w7lM1 zk*qGKE>i`#gH@>stEAnTCcO{G&U?Cl@4<8^3x`yuC$y&rn%|#LsjW}&T*d?1@dACz z-W>_h5Ee)H1m>pX`kawio~^Yjzd?#f<7S+nCuvje67E4~bneYN9x`SVIf6m;-5YsQ ztKN|5yI0@z_A3Y#kxV*XIi3EiKc2{HEFbXrk7=b2lwu1TNG|<7K3Ae2*nYODO?dhYNtXl>^s(^-3#tz5 z`%QB1HCgo6o4s=c-I(J2Ni_uerUYxwpTHY5re;{+(i@*xG}gAOHK7QDl5*Cp?%W#l zF&lT8=%O+>|*IYoxw$S*e9-UOg($s{w!d+zPlerV5JRc84s}p)!plT zf@BCN1nPPGLckpCgmDdzi<8GIs#YgEC9BKJbelo~&BKM!Z3o=uiKEo#M z14yfHeNP$^yLrEOo~ZjGr<-Q~A_UJTYYz<%xR|1%5}F8I-#pCkF9u>>S}x*}*2FUY z(3Jf|PKlzc78h5%gRtqFLx831oV2Wtj#l|&8=T1op0~N|b-$<(U(1S}QA7F!8EcPn z7~y&UKCo#Z>rfLgNG}{O-Llu^lcUqSAA12GQJ!6`9MxmdzUx+`u}t_KQ`f?*-7F|j z#&@7=OQiYqalO;^9}OD|gJxwC^!V*VWer;9_HK@{1SK$E&9s`R*zk_9RpPY!Labt; zjXW(nPYs=aUY$N3fe#|3&}`^(oOI-Dxt@4#UxCoit`hI!<&Yb4WLFAb>pE7w?`Ars zrV_NlT)?VXDfQ2|^1dq-IGwSu-7a4QztiRPB6ugoqPeJZD{Rsj555&>nCdL!p-QDU z1nFX7;I6ya8IEM`P)OX$fnCo`=g$n zySN`H>ok58da(pwxiChy-j^BQwq}Y6W8NJ0x%3S0l-{@3ZG%ToyK1l50ob@iM^t@r zh&hKGHDgW7x@mknH6-@Ad}=%;o)m2iOk@4LbhTp2YaM2=u{kHnR&Xx7 zvu;>g=&ZbiA^)X)!eRWGJkyb+g5AlQ`k z03=^NsVney#EFtAWOweYc6An?T{bh7aw`r06p-gyfLWlxU}GHV{!TR%BOUn@f+M-; zE#ti1jx00l&KKJb&CZ%V0_tf6BUJg^qKs%cTanwq%TSP2-@UV(_YGMOf4Ab0DgVO0H0- z(>F;nxbC6#{Yi$;*Qo=c+@x#4R~GT{g^w)E`$N#%@V+!|%Kk!?T;CPVgto$|z<0$? ziLuHcGUr8jSWqON<3>#(lxApo-$`JRx;< z%LG?qm5RJ7g*)=PE-HTk#zz4-%MRh?_51EjO8OS^iqIOICtgw?&ZrL?bmV6OF@Y)<&lHEV_Bb|A z;lk{Wuk1-ElDyF1uRu%+Xu8(HCRh01q&xuUx3bYOWTJLscd)CM( zwALXE4;@~aIF=9RgblqGeD?9);pvOnAfxID0ki5x+OZ^5mzI>*T3QSOEypQm-j@j9@Xu(whdf*Z5#oqd-(m|Ue5*caa`$vm9&!wzbt#MjPkXJDd zXXQP^m&KlURt8&t{XSA%#ie{!3k6O31XtiRuDRiTzw`Ae*g@qa#9MEmyMv{=lxUn_ z1JwF1YUkv;z8`%!OmZmK6#mIK4i%%pbD2o`@KOJJ9@qKsmf)gx#`_<_6uz{Bp1VSu zV&CRrJ4ka+!Cy|2bv06u%oydeu0t`#f%Wv+4G+o6m^z%BSDHKz(wMM)A0l(K*f_xp zHayhYZ`>XD9C9un>09zdD`i)k5bv}0Fb5cZZd+~pW#WKKpP=#K?2HQJ+nSA$MPR3B z;#sj28qZGv!wJO~_Y2SqLm;<4`6ZpR9?;v<}z1?_zI0A+t`D894x6Xw(INX{nE<~J$ zJ%f>Ko%fVX$qHj3M(ch*)jEbMaA_kWTB+TOnMl#YIX68?&4n(Y+NY-~!yJe6lKROM z?Djn3EZf2tU+8BR4L`!QYFbH=($K`35JTimu}qF9jO4(aKL`V(G_an$Dlr~C7yO9oMLxYyxOXliFv%ZL@# z=p6MWc%r zjDewzhTSfL`Jf4pR8ImDvm;?0c?f++`97{AdMCn2a^_PhyAzKHeo!_3ioOxKXFuBi zwbRIFEWdD>ec4qxyuR1e7V1YGJ9)w@lMjXrmp5;k{i!?066(i8zO>=6Fwu#1{mTAR zqtm#xAm`Ebv}MbmR>NF;zl2v$?UlTdVUeI80tZTxsYj95(=S1g1m94dEOBN0fUhkS zBeipoh0S)PbV3YU4|iv^h$gDDkjpGYhra9stEEQED%hGt;)NB3Tj&}D8pcP%oon=F zviZz09)-7;x?mTMLD9wsy@fMi?W(_!fytV$HM-JxJjHMo-3jWEm;*^H*U~yAcEh>% zZFnl9=&k+zTHEr{sDaqeZRMCr0ZHt~1*@0+I#QPa5|u(DGnsJYD!Cs${GviI4EU9Z z3M6*yWCj@8#4C6^T3JaHs-6l;TD2gDB7oG>?c{jN%WJKi*M?@)D!lae_skWkl~9wY zKzSzZpEWlH;4x5XjVGiG*YGp?8Ub2kps_GphrETXx?z!rlzUJ|bp?7?6T;7q+>*6u z?%$V6R61QrD6%*Ym73c+4x>oBRnF%W)x{3qU#S`PljSx5c=b+kS(jb+#0E-CXSuVh zo@&T6Ry34)HMDLOzxvbV5ibEavp*vk!B24Oyq6zl!YxmLx5R>cHxxEPd{}}lA$$g3 zlIGs)ETrP2oaMVa#{^Z6_Idr`>ej+3dR8yQ5iN+eXQj zvw@G(ZDO{u&O5)<9q&miS*cNnOm)4%N0P#gqoV*@B9mJU`0;Fw6hZQn=!QkrSp(p} z?o3Md#)*}qVKsqf#|4MHGVLP_#UJFj3I?!!Rl9k z!`uSj0%#ghf)?x*pxk`#H9-HZ6uBRUz}>)X?Bjh&087b8OStX(bS89rW&Q zhG38sB+jCNjE1{JI90V7JKy&O^m1S(g?gw3a z=o(awdc6_PCfOklW8X0?+ZKn z?w5uYMUoAC7=>P>{QC6OC&?6}VI7Knwm#wBte{Rs+L*>w9Kzh%u zEv>i~V=*^{_2C6?m7@rn44G(-JwJ<_zCNhJrA&&BQD0}UEBC7u;?i=a20v$j%Sj)o zl2ObXPJACcFW{oh(X| z5ZbiEV3w4qjx0dZZj9zIPdO1w_JR~(Ugy(jWZWKX^~MP^NK8+n$`g}Q7C|ev>f4x_ zBfx!onhA2v_rM4%W7k|*u=%#o;9`wiDbB8$3j*FH$x`N#tcxxv7Xx1K*_d?FzH}`P ziyKm3$fL~N`efw1?>{+du!S^`;Sb_SL>;m=ha@(YZh^Ku4@4#{>L6wF6zb?4;` zz@Fk5wzvx$3fq~<@F2G{W|Oa7qkYT$Ut2gNWdX>`_A7s;?UmeMblNK%e zRc`bGW8#l=C2q|@&GZ|Mw$3NU$v`{9o(qmmaZLLICOcj^fWu$j*a2C(` z^goDn^#G=;942;^B1@ZnO=^>U-?k^onFe)HhFAwAwZCHvyLq3*aCm&Y`jjki%l)>p zzWWe|s@rP8Ig8%ON+6?r^~4AM8Z}(gh`if`F^E-Uw`LF>J73{00Gi+xc8IgIcW&Q` z>vdjSWbHp>o=T_l3_WT2zU=(2=G$_^)d}#SPXt57SCE(QC_sRnN=ByQ>HM*p{DejE zx%??k#zz%ts8>) zi$dgFRijNKM#i%J8-1kB?Bd8}Vg9#m;X6jU!a3vjZuwK*OWyvwUq5EMqa`?zN(~saehNRpX`p_ zSPhR4 zU(k16g(~dIq_a!@^7R?Xg$xk{y7ox2$eZXW+9`jX9%pA4%u-BEQq&_3D^sn{D;%}Q z6$ZgxbrZilxzjoHO~i!jnV>>bT@I^Zgs1*6ZxeEmJ30hN)EW{nF@XWduO#t+f@-Md z>WJD*`fHPr^x#1biI34$9!)Bqj}uGWzjgwqs$xfY;f1+@%3!U$`{8v5Rn5X0!J;_|{> z`fZK4KWV2Rv38ygO`_xnhjB+0frxygrL1`hn~3Z+e`)FIdhI4gY^usZfs9?*#*bdL z^gPorNJr(jRBayLS09=~1343dh52T0tKygqUpW>>ah->XKygP7k-PZwc1ba(H49`+ zwm#hSjxK1~Hu+}y{O>Q0adj#ipn>QUGg;m!UsHIw6+OU3*}P<&4J(hTY2n{+9^;in z6TdS4s>Wof;50)$SIpv0cBc!w>2qW~X8e@0r-WLtKarGF&r6JuaTh7$3)zc5U_3!qoPnh2P>f> z4)aHhGfs+?;j3D$Qa(3#B=mhk*FOgsO-L~Z=%8eO5q_Llm!z$v@RY>RfVu?lFHuYrTUgaj&-uQ8x{Dn4{VZqPOd{x zbEL@{A0^?5ctR#%c!X}4yiJ=mk%l@ksv7f4NZZ1wOxTRL;$3W&HvLRtEvz*lA3;WJ zfrvy1gA}4Ll)ki^5zbO39ar+9M;LIX5(ZGoalLlugq8@5iK2LpSKN~oo-TwHg0FeO z(@#Vn-(JeE6l92+uFjG<(>@q_xxN{xn|(aB!TTP@&7Yepr;j6xuy~M+*DT&zom7#= zxTA(U$vKOHk{CR()ihl=tf1V=kgg%4_zo$R*)Jrqpv#_1$vOs7kjIIF*}BqqcdONv zoE{*+OWz($>~NJ-;FeZ|l`FlfhfuXV`D~rK>*XMa_sN3W8|5}hyuA^*P_{jwd6;*0 zx?Mt2U(Z$}dzL3hJIRki_l&`fk2vums5C`71oa|9_ua^Emhvadf)&)8CzqndUWoCL zE=8!i!H4Ee3>uCOEX-tbWO%(9E#_i9io65!_&_~@uju0H47ACgBo0ME%PK{9jdJqC z*9|Avb&p_p3j)1{(pQ}Q$}rP$on{_uT$AI-=6X+yXoYk3 zMV_$Ny;gW4BdApy67vCxs1B;+$Sc1nIQKOl-F{(LTqE%R+NrPo4sef2b)AmdJFLVD zK|sd}@SyRwpTsx#E+)qn(kejVjKdI#SCNPr{-rAOfsqT?KidHmX?BNk*(D*zvDI+L zQU9W9aYRA-Ogo||?5mrOxEq#CFT&z3C#Z#ImJbMM=bWbHoJT%{L9a8AntBo0;d8<) zOisMYKG^-p>ZLNDbihUtAcFAN#bB;cTOo!3M2NRb(}^Zb69LkDl)P0OVqk|uVikhH zNn;mTkVmAwEWPO3!QiZVhHP1fmnx@q69UcGy@+MeI#y^8Q6m^&ru9JiSAk@GU*-Ps zT47T@d22X7o+MvDW#4cJbrJYx{u%0C@ja#VE69W?ObsIbhnM@lyP?iUp|24Lz$*LE4O4G#2?0gD(;GNB)vh{<4g=z~)`2RmHLt|}0*1!JzBh|+Qb@yoUtD7skGSnP zno-5ZEbLywd7AMI)X4?^UfXuhtYYPf$&S;^HKk^ux!9^$L7RaQ+V%L`E9`X8A+a&+cBX*~K&`k^UV{bya0K>F_{Za3TT;fyDrb@~5{0FWM9I`*UM^@VNtYt# z3wCaH$E-3w@Ip9CzRbirA|WGyB}quNvr!E!ssnUMtb+nP;FoZo_5+sI-}JD*C|49z zu;I8vyK8Ojv{dc}JwrqV)-CoYY30tU!rZP_*0f30 zoaLmv9!zs|c=Do7_1gIIX)xK^9Oit4wqYp&hS|fD&c31JQkx6*+A38Dv3>kQGbgiN zemgvTTQrL$mb3>G0-Ty&Gh4TH6t|tR#=*!WQD`^Jkx+!L?OUo)q#u*IjPnSTv5z_7 ztS8HNH*xVUE&Zn3OuPMD&dfdl09_vl8cxq!N?a3PBqF__urx7FSUoeB*v+~w@IO9o z4&a~;+S$eQ&qn(c$z|CJmz&1HDjTlgB;DMkKKZ%{tf#JQ>*$}Md(>49r+$?IPl&7j ztYp$cWWSMwT*8XC3d~M`t7@QZkSV=xeXF?l@l2NYvYN1y#PdDtz128_2<0gJOrDq0 z5GDI_)bc}Q(c$KyW67-oz2r{Joq@C}YdvDvq6@@uLL-GBg6Q!+>J~@;*^@+AIr``YK^THBtJs4c^`*M2uwfM zs%H)X=6wpCrjWt88cUb2=MB+$hfaf$&!R^B&KGW8BGhJxXjO-LfZSzEw>C@{SlS1* z^u_OFT#1t5X(yvdKr#`6DvyeT{pq9?Svb-Uo|o!b`Z}-+CBc~e$=NX63RBn?&gcQtK2b-;HK%y|rD6kvVs_eZ z*`r3M>0Bh_rcv|7CUXp;b&AiIFewOGk4w8mQB?*2BB=dI!hS_chf6!&xTR^?vk>_qv(A=7|U0HId@c6x3yW4XJw9k>=aKQ zKiXMoJ9)kD0fLY}_e7{RBEE1BvVe51q@76Gaz~X}sD@Gg4CnqsS_AZIOgXf z)TaywD-Et5&4>Eu2sVu$q!@EjyEw?Evu=dDFDLQUUaVw!-MVsm{nc$E5ox^4@2iIc zkND=984YMySY#wi-3w`*R{GE`6T`6YgDC;s#@Z-5{Yw(;($iOF6iz2e#5L%-jtYdB z8hDVpGbv%f`Xe-^nJW?@(h*_cs+sdet_xh*yl{IIp$j%5RJ#;)!4(O)&E{rCykinh z@j&b(uAp)cD#kjk8%PVO5I~P~F$>g(;CoUFK5|)@*`BTMHd|c{vq2+`BWD*QaU2pp zZ}bT&I&^OolhO`@*EhL)7SmlMt{M-vwbL6Vz6&921xjv zEw+4*0bE1k7x^$_c8MJ#PM4>eK_o3h?W9!m;#3rEvQO9W&SpoGV81+KTnQA|v1oeHXc@>6_p-n*1Au49N*uf; zEe3mRQZ%|mDTlr6016r!mrF;XKL;mtv}LTjB641H=wGNm;T5Od*vUVHL0}LSxD+X1 zS!*PZt*>p}-v|{1BiMok%qQLz+LVe_d)v2sGc;*pv(uJw@$6>&_zqymi-_pv*hE>) z7TQT|?u(K~9uK6b48*piE~Vvne}UL(ku{mEHa(@a& zc)l@!xeBu>r&w38-Af@a&G(jcZ3Xi@r>mZ_Ja`sr zEj3syKlLAsi#m)H?(vaYA=2Dzc1aw)vwjUjDhjHP=*W5a&GWG!!ugC%WLw|R_i%CC z8`|G;bFL&r#p}f+AH|8a=968FW6o*8EOoIgbiHYy65G+R7mft`IftZvT#Q(@vqy{+ zit^#Iz@YO^*QTlU40lWkswNFTvp?l5lGtI!X#%y(wR{ zetuNG&c=K9`vgFcqD0DG=A3-A^_Q1tvxmiJKhT? zjx4g(pfje|AIhMTxYeT9RJ8@PDwrfLzv3h8!-@zA3VxvcDk+{|Iz0MNPBmbX}WBkdBKSk zxZ-Xx-a<75r1XLU3AS4|jd%3g_meE0MjPe>A-yt|kgXV(XaYdblS}=TH>Xse_n2;k z8t0sQZ{Z269d$D>m+9t?=De|FFr$rn8J*j)KGriHdw91O8O6yI52*^UBEmfhe0-wb z?6MN?OJo0zpZnw|J-w#h014Aeg^Lt8HT+)p-H1ypt;KN2J4BdMDF$1>3KNf^guw-= zLaV05SrBa*Nr{a|bis9G__JsXtl&?^AXG(Z-x{neF&!(;E-5#d!c_n7xjvWq$E znhhl19NNsF+F$K>@9i8k_R%O+ffi|=iH}mwo)#}UFwhl%0=3G;?A!V6$i2tN2jyEk zMx{s|`x>7?#}2JJb$GZgS+eQLd^#VKyzL>|-=c`^sjA_Io^U;+yKN4^-J{CPP6#`R z_OT+c)g8np+E1Pz6E|9(8J4QtN@pAy+36VEczq4@B}teh6Fbzw62nk=l~`#z^uNC@ z*(1bpytA->`+94>4wmAMxd~??K&!5qvE_{>=%qIpakXRA)ASPq&g=aJVfP3O03V=g z{vzBtb86)6654hy@qJnWUe@!5y7p+-h~u1 zCYM3H+I{&>sa;3^ux#4)jd#(jay;)5FK+(UeT&ImEaP;AFLr*ktNq48_cOP&l3&Lg8#HoX9Ypz`VTl1vv~Kc>SR zWoZd@&>Sd`qI3#=LKd2RJZ$_clb;m1;cd?<8AYq?qn=7Yql;?+mM#y*tWtt!GdtG& z6y2`$Wti+YX)rWdOt}?=dBf}mR|dYN4y?dbpZf>g4foh@YbST#6@Dax<4q%ZCk&ge7}Ax z?q9qcf4O%9_edPe{N zf=_6Xk5kR>|N4!yE!U3y>m6_P^80*(TR}T@Ma40REa16aiV{m}P)P@dw<#~M<$Nia z%!5%%+p2IkA9q<2J!^R7HM%j^)nSo5AIOjdP#bt5I-Z740O$jjckEvee*9yTHvkX^ zH;~#)e>;m2%8`c9GU)n+2d6i+FdYo&x4M;R!rB3sVSz7(kwQ91<55SbI|T;^f+k+D z{+KP+J4fPryt;wl-dwL&Vb9{0N;j~~+?`?W=dPC~092?&(=ll*U(7&&m3;Nx!h*UI zo#>s_w3Ov(czKAi^I0_HAoHw24o}sI(!eUVZTP+n724ib=KJ`v(X#7!TZrn5J~f-a z;ZE%nvK7BV+S-UWbeV&B$5q(AW?Dv8F=(wsF+lfhkolKP-`AHDJkssK;1@)LU}@$! zs*bY`c050>EKlhOl4OhPD+4_fh0*l= z#Ze5f))s425Cn4v?yj-fI~hv|6?d_CT3lkL?EaE|%Bk-s`O9>#YU-NOGY}|;W#rJe zFO4RzG4cdNgzBjS6rmHmDd=V$BlPDYeC*j7onn_xJaR62CC_L>EHp03RaW->9=txp zU-8Z=uJpWx^4<_3GIv2Md`_-j z@h6Od)wCiMNpO(Bz?E=*TyIID^yb}EO}~=i073gTXASfZxdZk(w>U^O{E+rJAQpZI z4i}6lm_QVH^AaRPkCK%AS6wKWFL2y89-|u#pN^V3!LaBz5vA;o%&=HzXCWsJgOITVhJr9Ulcx{UrotD6>fDcOwK9J;4t zW^~jp+b{r6w0xW+8LP~(NE%BQFx>C6R3<7u@gbGPn}m8TV;$IR^5~#=Lt$jj&15*D9b$QR6-gF_21wA0`ZWEQsUu3w?TtQY9N+v+yk?fy zR;w`j19tt>@aAC3>wOKoJxgPR7gh_^TfnLQpBwsEC}8Tk0qZ5~k$pFJ;ey{xA7YXW zD+!sQF*sMN7;!eEW|;R;Q6?1_chs;qU$Dl!$h^&{uegtOslQAP>`5tWUz_Ezw(*`aWU|;DmW*SPO1$pm=o5>CuuQ^tO_R}!~3JHbigb$-V@~$HU0=I`m zZ<%96-}+n;yBCEnF2l~s2;qN3{+wX2ndCJ=5(3XTWjMDjM*XTq*t*&qx^MdGCV>Jw z8hGMx=N*mv*2;*4+OiC*{xXs{>OQw{%LsFc+Fg=Sy^9+7a)!Y<;!Q+-q;w-5o=WjDt zu6Aj-x#-7D69m=GRNnye$Iv@WvQcM|U5+8NK04bWp0sVJYOARkkc_zFz-{TvfBl*! zDJ@v?I7{vX@_LXSec4WMZ+A?=Ol-y^$V^E?E_;J*UOw%!%NOUWjtj4??me$V6z+az zholL#_2`z&a=L!C2Im~dpXMzsw*q%82aI4C{Zpc|wV)t{VNJWjMQ6PmYr5TCr3ZBz zLs5!#@PUlDSve7R@_Xyk$`%P%)z>+u8jv7~j`wnAXU1^K_1PR`8maurrh^Ums@gJD zTK*t^yO>n$sF~;!44sS%4_}@1>e!6Y{?jkhMhsub1=@Z9)<0Ng_&NzvHVCM&Q=90E zCZh;GR|hfhlIjE)s)~(on!~W$H;~pARAQA7LR*O=Z!z&Ri`&;gUncfmZ^StD5+c;P z_ZuA1Q_^GIL^$EXj|eX}12qA$fkW-1>LgD1JPcZtX6I~M1#(?kwsva^%``V=y+4+; z@tOz?a<0o{Pn>QXr7N>#e>ozi(^N0irbE0SPTzPCq|{F}};XIX}t4T;_oTFZJ;qQ!5swPkpZy?ipF+ z@v@GW>YYVCoYwZ42IYzB;YgJ?dnbHO>gaRJpD21n_}WRcQU*`ai9pZ7_vHYnD_T{> zEfTozGR1T~#^?yLYi@;X15Jkby(NNs@1O)jBTORUb^lbwLqb5)p+g)T2PYGLP(!zN zi!FH~>`q%KB~)JAU7wYYuSt3snVH-RrQZQNAic6$JvlWwMl|B70|+9bx;0)PIo73) zR+N{w+c0m_)(F=M@bkRVsLxn3*H0bf+8Z*2LTKW8gsip7( zl$Co|jfK_aJ5CNUV>+_xdNY%8tFQxChjOBz%*L9#bYy$wah0%1&Vgt}KaOW{bzn^JCXZKzW#$98SmL&0BQ?Oj7 zwPMlltpX4dF76ad=GT8qSovZ%jG7(^fYgm$yt4R&!3PT%@dM-3(XDuRQ-hbT5wJ)E zWHZ4WJxv*pP<>Ny4#sZ2spt5Cb`Y@`^C{Jy6=yXw;e;~M@cW1yMYr2+Acc6-e4t#R zyBLpYu3TJsZk-2xEt+_bDPhtvxsHce5CS|xFS}J7@9BwBdY6+F9<)?`$*zv1MpE1{ zEq`*XGiZ|K;`YLxKg*mhSxnL{oLOkq?Nij|_Qezyk}soYP=5Hf+Rjq-=f@WAoT&cq5(#f~?^C}s9ues?lQpmnOR#KzGwjg3b496g00f;h> zP`HmB5_BP}Hzpt35QXL?E|?}B?z#8pDezE#{8sf?nXilL&6I|V2K~Fia~@<_05j*< zC($~h+%?Gp*meyNo`CoA?w)5M&NHW@x+s*dOw?;G0v{hjibMOkL#){OOPhm+uIs3{-UQIvi z{QSHqkn&29FozS7beEB91Qf5U51+Ya;{8HoZYNBKF_H0{(rjqT?y${#^|U{?jUGk!s-$-;m}EKPcX1x0=V?NBu!RRIYE*gCB_ z*`dqaf#jsY82}CGW=c=6$SBH4hn4^g#j=&?VWn0oX;5ZTW$mUF zNUyO3c%4?tRAraBgUx})c0VWZ`mJ9nug%gW@Z9SOoerf$tu$8d)nhc*hh zah;xLyEZ*Ac~YzNfuR&6Xxx1}K?2Gm!Ez&qQf=YX=;rS%{N z>{`+;4qBZVHwkDsQ4;y=1Mv?q#c5bVwYgl{aXmy!@yKSy$;K|_(A>QlnZMO|p4 zzilp)jE8&F#}8Cu>EzoNpL}BLux2LrYj`(K-h-T+Y;c1{iPMvI(b_ze^LU!kBdY_Q z(5M@?WkZiC`^1;Yp74&0dV=1X4g&Q=px*S!WDuDqO4XMoO;a5oL3?6^x^ieuT)>N9 zhY&H0Lhmx0be8*Bt|DNg+kw11cEh)9Ce9e+rK~1VGKJ3THBBerK(cfy!9VtsfNiJQ zzOY?Ak_&KU@qLv>O0LrmR*=>5kAw6XYAHErT9@%+V)Qfp+50ZA*8IwKCttF z3S=&f^D|~|Xdd_gXq2B4es9&0NR|C9FR5@elP|_a5z`r zcAod}6QG0-q1@amG^!viaIV=qT2!`bPDc39U?_0CkfscTQlO>ZLY|h7Z`f~3wonGz zh<|qR?@u+MEJfLxWAkZZU57zFPM$CIx;K}Os*1KZtK(4Hn5<%gq*DlN=jn}RO3C2j zV0BRkXoA|%Z6oP`id=VaZ?udA_+kTn7CJkBK;7(65Sj(*DJyG%T^tO_>FVQ&Cq)(O zN_FVwx?k&SO2cdsz!0wr7NQp%?sj0iV@0|bz~ELs1ir))I5s(moT4i!)hjAs=FifY z@|`Z==krp>6fBT18ZDx;eBfrJn>@Ut6O#{behy;MP{o;EWRMyp8-Cea4{A$#Ncei% z1N>wQV4~<=xJvLakN03U*SMb!>{XWGax&fZR+qLwT%$87hHVH)wywmE@50Y+eUG>q zs5pJ=KGC?_i;{vjV2?6g8^HSQkIlFT3$Z|}tL;Vbpd_Rs+$zH`68VQSyR)LmCRy}Z zm`k?o6HC$Nj+7F!zqpC!>@7rUdhXkv=ITwjFI1s^|1J;+51nbgYQW{7|wqIn)YkVI^3AJ zhdZ@4=Oji*srR?K4wZ0!>HX?rW^$tOH3n zxUix$I#W4P_=eQ33OU87G@HI#=;rMuE4-jIi77Zu8_&LY?){-2A;X_cgjNosw>|82 zMifeTpzyd-YL-_z)^VtpNz&uUQ6j8TB|z@DBTD2oxlfIO-+8ifF`}aM>ZnZRMc&Pp z#J4Fj?bXlp=O;J7uOEmg{OJM$RscQsk+QJm|M*1b=PzFZ}hp|;(!y2-CWG7Ke6O#)q*9E3x2 z;>-36Z;_8=adSTuRz5CN;QP1=i9bC+7=h|<^7X%Uzw(6E|KZ@{Z1awfvp-~63jS{W zb*=<|a>*~Ldtd{Q@SqqN9(0Eqaw6dIL3vGO0u8;Z!Kpd$3EbCu#G})RF>ln3+B^uT zZfSkOB5bL;A|;_;K0tbXkRCuzob>*TXy`*h%#m5^%=#F>G#E@K(oX%0%k?Sak z<`MP*2@C*?k@U!?=r{_aIQq2@t>*&|jXwkSmzFp3<6>{#DgX#iwLgXThZ6DX$FUE= zAnL!Xb@P2#KLiYD|FkMZ@T6`0f<5y2u(R-|F#VENQf|?X1p-_@!B4r@zw%=RO7lUw z*BX56e#uT825en&1=IDOo}6{1`(qTqMnA4Z<u(1i)cyN6`WyX& z#{Z1|D}1Cs2>Ew({6BCqsQ-@hCwd0$->tvUKQ!q6pkm;!;QmR)=9fqn%5TE`I?SFn zJH+?vpWlO>Ve_weAC$NI)B0CxHvYi*2jhMX@$c6kid!G=;txXomlXhj`}e!}53uP2 z{SP+%8}$DGl|J(O2bKO6{r@_TKFaei9{tzI{H~rqIPl-m@jk}#qs)Jo|L@cP5DxnH z#s9(5zl#4q%2K{Rvii|Df7ds=7X9hR1PKfv^{cKvDEgZ}f3Jg&DF0u^ppS|6F9!Wn z{{C!M|2==dEBoIt=VKcG&76N^wc}$PKlu5(Q+-(fiJvonWZ*CM{0l$-4SzoP`MVqa zJum-rKl=YVgZ}6C@yD|9pJw+z^ZSq5|L>Xn_m%&_&%b)df0Up6e^kd`{pT-!{;I1F ze*W%2f3Jg&DF1KoLI1l9`au7SLI1_i-~IFd;hpD${eLau{w@3e>OX(w_xJq!dnNZb z?XX|H#{d5e`X6qC!l?gX(8nDh5O-S{Su5r~;zVnlLaW<3YoV9!2%NdGRhhu$ zJJ##99*J3cjLA*Vi9n7%u}-=b%&CT0`vQ{1wU|O!o2^LXi@%s)+tv=`BL6c5NaMF9 zmuA&W(QT{_tDPMTgM38$UT>hxA!IC*Of8Jq$gGeHf+cVn^x$Xr8I<}yfO0LEUD6cG zhlateLJpw`ov1!Q8KZ?4hDOXa(@)0tV=@SMItNg5pHe`VDfOq+{|^8uK-Rwp$hGFH zOoB-}nAX2d3>%;7wCi=%xtzI~TQxBu9>q~1CNqG!A~qnp>^WDJYAX1%vm_xuXy<5p&pQ{hiBg zc1OEcNE4#ub48YJ8wUD;S4ZM$M6}J3Rc#TA1C=Qk5VH<=-GGP3MQ@T^WZ`+rnG5X9 zxqQBoxDbn~DRtF-qy~SZj8|NO?^M-qtxo!Vef>sfU1~5nc9h%`63P@25C_)*$vELX zCZf#o&$M4+g5ABvk^5GXKfgHh!6E~8lH(MJI*nGuq&5_M1crX5on?CbaegVk2R0FzXDY+CC|cVR`=JEdPCtt*?S zci3kjtUr|T??!ni-RqKiju{9Ql$4}0PBC-$<=&E028lGN6i-96GEw}Azd+S+Z^3t1 zK}@HLS*!ou6rORprNozwRD|8*dE6mE{*H$?(B_4xXYDzgFpWZde&VufDmzs~t&2s_ zwX$o0_CByLh@L*3Ru(+fkAIzs_5Yv6JHRk*D00Gr8~fBx^vU?NUz;bT+TTYUHo%-0 z$mNPHoYYt19sDyRDAQ3TXHH$=Ef2pg?T}zrkAP%12Z$ zbFIPQN_}ksH0M0#C_e09X|shBO(phV;_$;Mr6GDJd{a}K!0u8R@Sb7wxs7qM5=c2gZ)_WWV>XeTUsYJGMh?yf&Dx zP7Zf6FI)h=w^3iW+GSl0s8)cldOj!Df=QAx2!t$9Rk3%!o=yiFg>(g;%h}c@fbO|# z=GSTF3%NXivSk#OUS^0TX9V$%ljzeGO-`rDZu&d@?7gcTG`ELqyY~?U`zAs5oF)Xx zEi0e*0puVJ2+6&Cksh9vP9I3(^2+;FJY%%gil6bK|2|R;h+sIz(Iqzzmfg5^bh0PJ zVRGK7+{GhPE{?^{{-e*_>&mMq<7rdCUB~nZq!Fw%WQ!O7)*LX}Stg}0o-Ceid<}c3 z2EPkjr0310n}svp+r%v!d;sp(c@okhsIm|SsUC*~lL1IH+&WLvLg2wX+YPB?Y8?yT zjgJ}XCT6bJ8tbWHoZzx@}9!oz0s+xJ0=r2G|_dPD0z3FMnSrbPU+`@ zo;!c$JgW1;{-C*0qq@`w)Ryo#SG8AEha_h=Mzp4G571qb)g4L$!=uv(&z)E>#b<@GF>Qul+p7U>}1=oHV4aWfq zbBpc}hbHl6v7wi*O;HOn7SNPm(8OD99s|IoahP>Bd?)HF2|AS*SV}I3>+8FhEWC=U zX-PB@y^R2PzoFB7aaQl848e_(Jo0{Y*}a6E;7{L;^1RA1zqw@hEYf9?Z>Y1Ql*lto z(?4`O@3+P33?oL}Bd!nzbWu= zTH>&6;73-=E1))WCs5xtzU%EX=W5Ia8n@y7a=?A1JIC|md69|=?;iacfEVk#?$F9ZrWw^-l7Luu@7uPDCZ9K~m*zpuKu| zJgNV^x3?1CS`Qq=c$(j$))%gL7tc$La4zuvdI%ZB)&t~@k77Y-Kg&qc*j}vS{)Mk| z=cDG>-c>;|?R#p|CQ3(^+xg9sCji?{BdsAMLGY~(z+E+!tO{x7M@Ls0HATn0pHgnP zZtkkO%V=th>#P%g^_&wPRn_m%%81!`4=@Ia@IW)Po=NzhE^wSEF3QBX)+~ zj?JrIsUKj0K1Ki5Jy%DMit@9(D{?mpfcGZqhAzJE(yTwAn*WYC|f7yHQhEe?k-EPjx;4GxD)MnR*N zYHvOhcK7Z+5fI$;3^0V_*c(+>6Tcg^@`EHXB^0LZ@rKEEEvi5Xr%NMdb!(>#ia?09 zpAnCSvRPU28JY0ImF|B$qO)Jmmw$$GzX3%;;iI2867pULT&v6J?RqILEErTGoU{Wf zlB!DcC(ZmLj${8!bb?K(ea$wAw2f|Ws)I9vpFSJfbNj+Yx^w6qe z_gAL^)AgYPBQK>l1QoHPXyRHBBSx(5!nWD1|DT73*KD*z7t0CGla5P;I)d&reok+% z(~Q%_O#%eTGm`>Qz-n2zl~=bpa(RB64W*|;c%%`O76m!rZU#W1abT5ghfm*kEWcOEK@ zQ(ks4aV!1Ows(VPva?AN6%wAdtnPDnIM|y-1IOjk#3f%CQrzUQcz}?}PPdt8L3SDf&p7%b`LeQ!dRv zr}H0Pdp@%XXC*P({A3-?mUnMFn&{GY(w!i#`iT>huktRjz}(4+5;H?|>yyb-Fe~zF zu_kS{8fesc#_rDC+Dc8Z8)xkX)f^@90Hw2ign|kA5NonBWb~!=#u;O7(IXN3p+eX4 zBpP4rASlQ6A(fe#-HVe8Iq?(POp+wF#oyG4W>8VQen{b1qYmmO5{*|w-)1=dXn^$i z9^UG76iqr948q{t8YoMCuhe1p3)4TQ?UUJYOc5`o7jB`7FHE!9KAuh=JN^9x?>)^0 zj#QkK3se$cSWy9shW~v_O_Ir`h=ReX@Rn}_ zhx5=}Tz#3?p|o9w0zWFLy#*hrYLA#mH_}#jPFvpI{yV?XGwF8{5-d)r!7HP134!Yg z{a|;&2Iq(RP7Y!ueVHyh-@xX$Xjz>MA%CmF=b9ap`KD4F?#>d?M@e9byGTyyk=p*V&SJI2 zy)P*(e^PO_v~UX0kmB{5n&kDb7H?7w0nS;lfnyj^LOu9bS>vs~M#KH9QtxR%$e zQ~QA;ha_*+`qTkV;T7^xqk2Rs0rJMGyoxHnK-8N;O32~gI%MlGuhOeBQdK8Wl3r(O zr#Bai0&k6ke*Yg;f&I}MLq1Bm?Z3Dq&QYk#QToQF31)F`V|fGHx0nebhjwuFegLhj z8hAswWs_2yi)dS)0El)CIj9HgxNZ`QMqE7{e4*o8q(dkr=olp9UENp>L5>NhRpvkpzON=so)xDL`3EK!rV3bQHtMVD zs*>9dP1e;U37h!qT`ML>jK$MIJ0~W{orMQii8_DhHDU$pa^a;BX>0I2f4Wu+HQ6aG z4qqWXPB5LYfvmaW&QpsCtP5Of-Qz+e@uj5{Hh$K6T6In;{SYX{ zaq`n`3mcBXRyF^ON3(Yc06R(L_({ifOGOM`TutT7qc&4iamsw2y8MXP)o}qn&gkDZ zO?ZAtk(edr*#MNoPGC6f9>OL;e43#S5mYn~_g;fQ^vb%4NYaU*#tUn#?c*A9ekeOT zr=yc&bKqM1pLE0Y;NAUHD(>PKD?OCcmn*w^=R(s;GkuhOkUg&MK0c9PHQL~~zq=fh zGCEE$#2N+yKt7-;*73M>$e-F>yZWXpUe?~a@}QH$RTwGb;8P}okd4t35!@tB4Lab^ zu0nMAHy24J)Plh>f#m{P*LZ4?R{n81VB12PbEvAq4>2Id`gInu9^dYfnoU7zD z!3g*?qRJGO_kewn%NUiUn^lzL{t+0*wsX+AgFm{Umz@aLewrN2`uRk z&jl~(;f9=sKk34PJQGG?p_c>tu%9;sBUt45yTq=$_onO>UY8feFzZcXys1j&1V!LS z(@lQOT&_Wi1OtxbX(&Q8jR>`So{isDuky&akKGC5g+^ef>v2s-+^YT`?GjFhpfve* za=S%4QQTSoUbgIa9AYD89DmySV>c`iUK|v;~wxbg$jW{*nJ zcdSRCHlNzN2mid@=$6l&L&mkd(bN$(!G@cK3hbTCr{g`8|F5mN_I^X4n-(|;R8#R_ zSHW7fJO+`nPi%e;pgkA%dg>wfX`KoR((9$YjFLvtvPJzkLH5XT$ilt3qhwx8Qnu$o zglQw}2(e(-dDuJ)jw~BL*8iG4g6jAvQC6ZN8o1U8FmInLe4L;g;I(P=@SDUH(WfwP zCs$AWrS&95CSb#sMpUrjKoKCVYO}A!@K0SEHHW$?b+^hA&(_ED zvYbX~A0TYx9$A+?4RMH8Ef7vyS)u>9p-g=0x^@ARQ9ZB0Pr1Kw(xm{(D)@ezGu*NI z^N3ST0vi*_kjP@Bem6E0$&DSGTV~m@#H-X>$COb0PafN8^Ol(g>7XTpP zYJ@8}WY>P#Rc`2lto|-i|EM%*c%bglKo3S&Lqk4z9V@Ro5C(t(PtU3`DBat%!3uPI z8?N_5{!L{|4!T~X0G(Ivb=_J_`a0;O@Ct>*<@~h)&&Ly0BMg4Y z3wDt{UjmNnLy+oOtsW@JlRv+ByenxYCt$R)p5M8;s4d#BOsD1&#GuI+QdLUfk zaW+izWeJNOIat@Z_2vs^IousoKn@!_I$RKbUx4kNfd$jP;~35QE&NEzPvglYIC_5F zg;X78rB>)or>wqJV17tL@;OaL4l(XSI^yV@?E#QYN*gTDxRDC%F+0wDvQ)1h8s5P0&C4E z|2yGI1dW{=pY^DVR-9>KT)14b7#dxGNw$s?(V&m6v4b(5er)^h7D|m@8m~W~$2cw_ zmx*_Su&P4=@W%^q?d3CxM(c*%i;u^8j!aOISdVZ=w_?9n0B2K$jz3oBGckA zP556w4EwQ$Yly-mojSe=3#J|q+lJMt?5XORubYy#wfDP+t3+^0_y-%hoxKT0J)Se) z045qZVyupoA-Hg7R+&Z8F9{?of)Ja1-G%czvbyCFM$HvCskEJSCmtF z+*|$axgQq+Q-$9CccG!DMAEW>c^ZekcjA4_zc{rn+fidpyt}FK#2`1NkEazPq}&>% z|9k5?@Tu1{asg+M)>>MiuyB8cH2k6Jejq8@P~p{$f2sqXZ{M+)~PD9S$s4r>L%wDW6xy-ib?G9#m=EU|j*R%GidE~(H{ z;8j82oY>sInr;BnkGPOBh-P8H^58dr_~DJ$oa|D;%i+AXga~Vg1EI!dr!&7~wBkf% z4n&^0d*pc9yA>OM307#^=~T%0d~-^X`vm$)t^^F%i-s_<2_~;3{#)f))yprUzx*yH zO0{{{h|!C?k2GmGQ@B+-RdH=jn7p8)w3K+wiC9Hoa`;r!m4UaJ1l@Cr`6UfQ!O1#} zYSl5D$V46&X>n}{hj!$h{@ygsQA;fxRGoppY0ta%!hpbJUIyB@AqGAfV;&U1E|vih znY~kXXfi#0lV7fz%O_6VqyGEUnlyj>#UrRn%!V8>UF;UXkMXBwB#FPrsCzEyKThv2 z=W7auITMiX31b|8VUUXtUpxp)3oDnvGf2)VStA1Ck(fdpt~=q$lu7lj{-PA-tuceA z{u}*UvH#mTPkl96T{u3{gHMkSeV)MXtP^4pc$lhbnd4|QAD$5;SR2eyQOl)>7G*q;lG)iveWVfjs z^8E{*1{p+#?jcUdav^swetqNskUyq!j5$w}`<1++L~*~41(;)WL9*;dcHnqHRTF>; zdiyN8{6+e__anJJy$Mh|+~$2vSk2jw#{t)rax8499pc;88u$Rb5h^XH}$$ivWa}Z(TD@^1)Tl~33LeN8xAuQyd;?He)NxW9g z!u)MFcb$?y&HZAJPdC?8nWvI$9IIahK8vQ)8@n7u6;Ez0rbyHW(1NRE3o&y0u_b$R+z7$JcxmY{3MN54u>~X0rub zVE0aIIa*-SWrxqQEeE|5tdCv$RGcu)kNtQYIZ!DKaa$m9pPc3t8A#lWXJ=gXxOE}< zbqWzYMZ3@v+0ufYhY7pTsRIW9FaVcR8wW6V*bJO>6V^ML>A+de*y_95e!rxtYgv<- z!O9y5y8bD1I-j_T;I1)KCbFgCPXm-Rjh74G9CzGzm5|!RFjNLD^>Q(do8U%~2p0UH zd=i1mq(!}Y#(y=i?64zndF1m@?AGF04-QkR%BfwXVW(FNE)%^E6fA`h2@`H>(B@De zcF>y0YgMn+!rvN1SMARaXP0Xb7)(=*&E_O_ZbEAwI&8b@)ALelzaC z!h{UMr{w}R+#@DI)uO2&@<`N~2+pULFPI*fzuEGo1``xcEH1!lMWAKfz{GRr<1mf> zx-FSdZVf>)2z*Uo9CJZq>&79lZ$;K~|N|`skMA-W&beCT{N0HW{Q{9L0b{ zE}brZ09?tDxbk7A{1Tm*grU*u7ecrc_UqFqY=Q%sW0BoD=P*>WbCqx(aOdQOc z^YXoVSzss%I91pJuCL^}{j$yk1?{}Nt(u0--6jTppoVN$p| zc%20MIQIP9Vs{F^>q^_+F$1klyn=u_;sIf{F~T-JBO{WknN<3;TV`N+b*G?7TG9@p zK*sUQx|^d>dUDpsL3w2cf*+)T&*2=W#5pBq#rr9q1mxG;&vj z34jo;K4TDklS>eVjRipF1HhMTrJQg%v!S5Qx*4xhSTV0B)VIFL$!R3?n*y}qKKVQU z0w`#NXVL?VP4VcJk*&!2fXyR~O7g|aUk|Kov)ApPG{xg1PqsoMi5Eixg2NQ%;wa52 zdwXm}yi}{YFJGIG4XPT81_qC_KuauESSd%KWiY+a?0{muw$+TXvHzs>I?Ylz!1M5Q z`0Rr}g5oEo{F!vu@pddOKryI5>LZY@+!;B7&$0Yw;qdGi_7|uzXg(UerENRW|kGPwR^EDz{ zb7Clj3krub`PzjFr;klSOvh>_|2#IZ0(I0!^sx5{q>5pLR&paJ?K|R{cvKDb8s+L+ z`V=lxQn6hOszx_;Kf}9urXjJ1uW$P&WxQQAR3Ges;SsD18o0z1LL?%WOYxwE7R|g; z&h1(U^X+BU#IY|jstL+KXrrKC(BuI}LT^))9$?aFk;YY_Ko*vV*d~FLbE?+H+ywWb zZaoldP6tuBoT_Lcpq64edULLzm5j^+5mfM>;Jrhik4yUjeXaUIIGZsf zRGtO>t@?PCx$?#pGu9HQN&Ulm)(thVRF}t76YW-G$xWc2qJ1E+<}@Z`&*6S)(~O{Eqsw5`*3SY0gt;2AO>!i;&yjL@1rm?fFu#U+gB zxF}<2S*zvCImjcJIS9J_J2_Io3u1zCI$Vv|Gj1OSKSiE{X(O1K1M745(1=iw+{q=* z(A$!XLE4)7C~~|Z<4&rr_55iQ`s!d{Me6#hNA^cp-j?M5uiS2|L&(hVd#LCkg-Xsr zVh6cAJbqXE*G7PWo2{8$f@d(lHBEt6p{C=xuED>UQBHYpnvB!FD>t^TqR@-Ff@l3c zFmm=on-k@8BO0dbSd=rql&Vq0PauV z7LpCM(l#S#StG3J82|YnM`6D(lxd@)7w+z6lomJC0C%uRd_JXE|0p!_YD?5qoQ|QC zvqoZayK$=c7PAJ+)e3Df`o{mjU!2(rs$z+5%;m~WCJeXySC2bTBnz-9r-~0Zf*#bN zAoJw^aKI59Ph})y_6Cbfd9>S`$^MPJjh;$Cx!w9s*9cXqdJTdJZYR*MWs!QHfj7bn zouNzyeAfAGd^<0nAf0r4Y8%R4e@TDKLYuu0eOzK z7|)t7e(B*04W{|GG>Q3gAYU!92`2pT27yjT_-2Ard>lV!b>m9Ay%TtzuGLl0vk3AN zlz#l7`vqq=bl`S*#An$(gm+S20jn+x+E2LS$N?aTe%JNjlEs;gUQzyM>Xye$J5CeKNXl3PyxnW&5h`{4=1Efi- zyLqUZS;{4eDLOCh4B0m98NY+NzTSA&=yS{Jc~X}vd+0f{z{dWf1J~BA#byGZxt|M4 zYfw#g*_w#8+=R1v$Apk#^te`)!D0J+&_Gl$-b-rZqF!makoYzmH|43bXDTS$o_jLnMDG-&=u&s3l_St7p-vTuEspzk8&PCD({N~t>`0m-2wO2~ zqvQe@JFXLgrtBi2BZ(&B@XEc>=!~SHGzA;AzJvcLZq+Xr@p*77V`d~l4#qt0ncyTi zmZU0kaL+lT_ILQC`?43MY67aMjI=CgYvfQ+0B_GQR)SqF4I*eP=9_6ZD zRm3hze`7jJ9RCRq@{hOG<&y#clBMXwdi!o0Ka&IjDmVJajk37g7kcwH6yih+v1=9{ zr`pqJkQosnz$tgzCSoJ{l}G(n#}ks-%_6vC-@wTghY#q_<6CE!+Wly3pE)-(h(U~y z0V>Du-;Jr)zbN6~_>1{duz>IyB>DrDH|P4a(D_}4IG!DS2THT+{xHw4*lq_ygr;E# zQ$(KYS>8NuO^{EWbSjCJ;|F!-FgbfS9PfR5GPZDHR7?lxR^Uy`a^mRUY)PFBk zy~1#KZWeZBM=hWH+NP?y3wvSTo8kS*(W?-UONFD9L>J1M%p13jUK}6+DgsA&99~Wc z<_uvXzP2*9a^nJYm9z))gR{g&CxOrG#8I6i!0q9PAzqMlkzsAnBVWRvSL<@ z_2FiXFHxgi3l(k$GPSPb)$*-SQ_qu~|1Z@67A@%tF`7r83`t;y07fDd-)>t%yMuiCWx5In&MAf8E@gz|ad2 z`NW5R@~e7};(@a}|;{GRt`k*%F`qv31~W$4$4B@K*f*$c9FgaKC!Qjq0zgW;KFiny}-pX{Tm0Ki~Bjgu!cy&!zYD{J%Q7?__q#k$US z^@3EYD4;np;ua@3Y57<~(ufd!I7r zay7?A9T~&tCvL&`_PR^MymBc0G&%`O>E4F*zwj4Ck&ZOM=;$5XYaULo8dSUdjPDmV6hxGmRSQ4V~>ncI(+CgKQ23A555DxbDy73=jDt? zKD_Cd2x4Z1!k%Iw;1Ki|Kbg)L1iWU@{+wj<(QMOeMO_)*$2KxI4}oTw3d8z}$27>} zVvc?6T;#p7apU(LDn~drQbeis8zo}^B=3wjFq{%D^XH=KgZE&p+rHgr) zzca#RW?SaFPzWU%8$Y`YF^uXol4lVX&Vyle+2qn9*7s9e_<)*z_dwV!9jZX5>s+kbHoCq!(iT;fC2A( zb?U2e@{WJ(Q2-P}bY#h=Gb%#jFS0@$0nKh2>Q;jy7aAP17eD9MMk$QNfi$damWYLE zL&3o6SI(681G~_Gi_u{D%{`S|S6jUgvskLH=CS^WYoj$WM^i<>&-dq}U@~6t*;1NU zTR1%%@b(#)L~0@T$YeM1u|g$Gsx$xi3uJ0K<)GXJfP*VF+X7|usB$0$8kWpj{fz6W2JHvUA_Db zYQ6{ac#`zpwvsw?baJpI+XYcDW8(?%jX92J7eq7z>NeEXB|9k$uJ6)rjLSeF;e!Gf` zQQ4;-4w2#iDR~~(Wi@d@YORpYUy19h!8oODdSC#9=y=q^TOT9v!PC~U`KN?BOGMj2 z)a|HRt?~*ETOTACkh^;WjdYJUajL_!PXE8jMvy(9COb6AvgwI!JE_kM1$935kn|iw zS)h?(TlO_=@(TiQ-ohCh#)4@D}paA; zr`BcN&;yI0DRIClb}cVwiRBpO4hM@iPPQ`5zSMS|AL|GH{`ux*7Tsu>7ISJgr?b+C zGROJiO)d^Ma#NZ}(V+d=cWb5T#e(yp@TnncC>=r(;<0#3Uh}Gfs#6P9{asrDucK+M z1(fj61iJ}XA7f0|DM}%cs@*r13U3dO9a6)|PUwRp#P28#F8bJ-F)A6y?+gvPc6u&d zWDu-c8vjMDKtW&_Q0ox^?)vSrlRgl=o?{w88eqS*Jw@Q1uWbH9NuTv@-@4;{SAl;+ zuBWz6Ab5qXl~en2ZXx8s{U@5D&EdL^G^)4Ou}fCgZg5mWcCs*ZAbpqHZO)c5Ib%P6 zn1xYxeW$wZxa2XqA57nZB@b3Fgzt~U~w9* zL^Ly@LTjZ+8wOfRVj?MdgZ7UE+kZm zi6^lK4*2$ei&OHP%4PIpq7c%xLl~k&s?nW%#$r8`!Ac2q-;u`}7RaDbM7oz7Ze;Jj zLz@wHL+KMOLxub1CSW6_oWL?2#{rUT8tp7U68M5rE;eI8MRPiqofkb|O0sP>p`f{N zpge(^f0pQGKktblH*F{)jF4%`@}aIcKI+XE(eZF6E|T#~NkQI-0E&35#e5*f-XAjD z>+*Fn`@aESq^63*(=bHb^tObl!$at=A3&sfe2Q}d!PJUkEGMybOHZ|cZip%YZPeG~ zx`Mi$YsFP5*-?t z;3DgS_K=NoFTL%}>MC^ac1r*$7IrwQ5R>{#UplBw{P^1L23ak-D~Y|#4{!Rj66hyh zY^=+C7fyR6OwJU(<^EH$KgZ1z7hU!!u0=F+Y&ydfJyag-yCU`ki%ofjMAZL99Jk-; zM8|3k->5$fovdUg%}aN4uGjU8bcG5c6oeH2oQez?zna}f8(bj>{1gR*1XLI#O~l%i zKvr7mN)ormE7Y5!vZqMIn+OiAC{a)TVqUb30;b5TurWvMVYUE@0I4Hc#IREkVE>_l&pZ8A9CU=Ri*|z^Dvbh(M;sNt>-@r^<$ht@aHk z%y6k^%LjEc_YH+#e#pvNI}*RUA>lb1b6F8-O) z!mA3Ec)DMn>LXI7a)`yZ_8cqJ;M!rKlse;kXYWxriXNbGd+ZU9YY1tw3C+^pZe40Lxe z=pvgLqK0kUV!(l7`8F>y2DdRwNP*JP0rb+*C=$AA+K;Y;UjmMW?KHNj3FY8&P=79?sCtP>4tZ3WNQq}o zuu<%?0&OaT-sm9;#yEoy|8Au&m}2AmYLrXpLW+NF_0X<>QGp455?v_Z$St@i>KShV zaQ?Yj|Fmt~`5qW|m)Ns?GLahcZ&&<78sxQCn+UzaJ?R`w-tZBTZLA=2bjtKVZ0=XU zzMUam{+{ghct0EhSdjZ4UP^B`{uGc?666pL{%?};=3Fn(=kkYYBQ_}hHv$@h&5@WD z7Pl|MzNw|7Jsyu8i*gv1I+*NK&Fu!SKZIAsePb3x;PGaxQD4~&Q20f zxNlv|Q4Y{m&b*>56q0fzudNlDKgmCb#EyIkQ!3t#ARH z3$xS-&<1fefV>{Z$lLpA=R`aW9|=B{g~Ij=wX;zc=<)rahC)q>9R2qjbQ40k<@#62 zc{|+_X}zbnselV}mQb`)jCFn#L10pB>=I&V_u%gWR6{&C+H^h8m2p}M?${yt0*}HL z3inxmm3>cKfV5$Z_VSRk2CRPMm=$-{weo=4DrjdeeKh;j7=Jvj%uj8{q=Q8)&MBto zBGT68F2)}OoXjw{o<`k&)5K>3U)M&<-&D?39(1SV%4G;A!9IX+4|0BBbIY;+?nRV! z=am-{tl?b3HT;zLRp)a=WA&(j`N!b5>y3*z zF82Zu!sTBa!9L2=*UNG7L{`w9rRC%bSCL70Ihu&@dtM6+^o82X@rmd+zzq2Xq(*O$ zNje7Ir+tr0lr*rr>6S}vU)X|9;5)v4+d_Ly_pOO{gKDYs1O7BQ9X7}LM_xt6{^;C3 zUWO%ihRPsD`H2Vl6+!OHZC!!qg#_}T(emOX;Sa5zu*V;#EDXfXd$PVpRtP-mZ{JVJ zIlPVdXpfxcMe<)-!aHffaT=T=QJ&QFT&3#BRLE+OKzm*~`P%1*5&iICMEy$7Nv%IOa7GEaE57!-?Ijo0_)_mdhT5ax+ARPAl(* z%O(^8(E4r$4WqV1;^y9Cfz>r(#j38M^o+M@by$(zwXrh%=Lg6m;csC0<1u4=ICejY zePYOyX4P>cGJUQ5!!kyp+EX@|MY9dm!8hD1Tr+agV|Q9S(&-YOlqclKi3jN3;#GW& zMHsR~z(#Hu=~kAVW1(R?Zh5+*lfmAOZE0b|Yz{72GRCcHJv)C_% z+p%vv%EGEc)Zv65zzmMD2xNH~M6>kv3tc)W`RPq|jQ1&M@L3k0jal_13Gl7r&yjx6 zFQA=hx>N%DeiGc8L_mhv^}-bMwckZ2WRMCMN($C1rK=G%qZXdgMb?O_;RnLMf@No0tCaqnmugpT~9GP8YOzF>>oR+z|lT`b3t@1giY|;iY z%zk_e{ELymKk~d)_92~*6%~X}9&|5S=OY5u*bQ;E?iQ!4nB?1=hDIJYqE&}syjnom zTgXEkg+w$IKGGU~)p(^fAZIzDydx3?sB#N2kv(jCXq0)NmA=}nhtz|XS4&mxRl`$u z)q}aH4cF3Tqg4$AEF%NKs{1p3{~8jIxD-#j0^Wr;Aw4F5tQzhzQSV}F3nuEEsUY`VtO)p+L}gnPV=!;1 zWR7lXX=cfPNYwFzldpcqma^B+$B%;{yD(dtHB^)qiiuaS3@Mli}{D^^p_7t?oQ@p%F?nDbOyb#}F_LBc^E z2EqifQUQGGeKahvsFQmK;wW$i z0#TpN%oh{yQUz1?6%AcBLN8vR=75cJ;bI_EFjM;qqGY9-6RKR~czq)-71CfSiZ%Hf z^V5`xW2_e3rkIov-^gW~LV|KtN1Kh#V7?lo~pccL1rg6(>=enreWwP-ZLN>t`+$fsw^FR=ZgLWbQgAgG1~j$ z37VQ%+@jz+qLR#?90pVD#fC=m1`tw8%EG({GIQo&JEJ6b3OtU=0*LAC0VYPu8T!~=uL`_=~1Q$f# zyf4fOkLM3#q#8$nWs)d}S=7EAiLBN&?&tV`YN#qU+(AQi$skN7HeT35qFp&2Kv{qh zLV7n4bPZjE2ayCp2gO(T=%%no13c*hO+`+ou|}CG_2O_EP1%kwPP&;WvDee2s1SNu zo=2SN;n>tDyX|_MetlNc)U;&@ax9UF-M@}EykF;as>DXhx~IDQyer_J*J>!E*5OK` z>nyh@y_>SrUjJPQTI4+TktleieT;GYz%mr;gJzkn-et7n2ufe|k z{JhkcqZ8YEE;AzA&@?U#d4to;wiNh^EOeJ9Md7gOZOGLc@6oDnbyT2HsvVIBHvhgi&88+H(dn*lytsv2eaARz|P5hT@edH zuLsP?!yTW`^ZQ;lJn=nKZ_zj=M$(MCL>aBJ7w~SbMwP<}N&0~(0E|F$zrV1ibUE(X zK{5V8O#m`)?m5sIFQ40Qrr2ZG?MC8%$U?K}4y@A3s3MTPP82iZ5Qk*d(%my4Y~&su zDMv=Q#46)SPyMXW&{KghZQ=v@=^}D<#_VR~t;QT#&}6mMX5E?YSp4UF@P(h@n;> z$Ny!6N8V3DOuz}4b)jSKy`rq{ORb+)s*9Qr_hbI}qFK{Z2<9VxBnz&bW%m4{(mF6Q z+@ZwtSip^4_KY-g?2^nR&NX~bi927ozyl4r(_kpVW-QhN64e9-bIMTbDMs$Bt%y!- z+>l_PgHISIY4Z|^G8P_48ilOvc1rl{%@Y=Dk;gsP5rR^<|9Md!Jdgo8cNoeSbJ}!D9}0O*zY7ug7M`vyY;G~ zyq^Ocr>>=WgUQ^SwF&f0BKA|s*JGJHH2ptbMrU9C#yEU14>=bC7dx=9;g5 z3g&qJzX1Pg`2&pVx_JPP={83|e_DBb!NdIAbu@yqix9$%-iD6^aVb?~9hiX6N}F8& z$?Q(L#TybEE@=Xiye_j>hMDGJquDTY5dVm`NPkOSXUai9&WLpCCdKiXosikV9gV)u zLv5%Gk_oAF?WqCLv|*2{keawt&QJ(Bp(-hDYw<+n^#;T()UBvt2o^RvQ@5hjf(o{H zJz@kB$^Wr&?g%f1VB_yp43vfL=wC*?mSW^y#2ynFB5f0ZmxJaehO3EtO|NpiTO=Gi zMeDykM6Q$)``FF0eCTy$rX=iEJLWH+z3IFSL||>dR?F)w?2f zBOy>w?AwG}`T1BMx{En+>pP0EQs-lgPOlFMN5`ao&7b_ysF{dsX8I4) zJK_|c*4n?{sWfzmVI=qQwMZ7oW)t4k|NYf@q7ZUjm45BGkQgERwJAPBJ#R719xZYqhmQcFk+xtsqEjV+HlPx16pMjJ>sI_6ChED zSWE!(fV|HwjB#A1@FpKb11@g&)v-rO7{{^w&BasBFHm5I{o&@xH&+v29nsujRfrAn zR&B*dsW%3ucoZ9#@K1 zvoul(&KiBa{p9_7PVTSKE+DifcVsOTK*AX=2CM$O9FmiWnid2v((D>a@XBKB^*`-O zc1)ZyX^l`ue}~4BoBS(&-+!fGwK{jBG21CUKznZyRAipAsgG`(w-nf?LC`hCf<3@j zrX=@yyzhV5O~RV2V052i*0?Rj$~7RZH7lKs3PVRj;3PUc20YhJKz+=3v-}i`fY`OY ztiMH%nw-;XA~+AeNJj*0RO$%`rmq0k>L$vMHa(G>M!pxKdzY?O*t(+Z@zg5;lXa5S zlln7(5USyb84Q&=*Aq>s2C+>tm3Po(qNz6p!VGj}f;^|Y<+RVPAG3g^MeT@D8$rP3ui8if|C*j$2_AwFLGmlyi4n)_}r?~^YjPw_Wd5+ZDK<(kJ~aXWT_dTBB+agT~Xi| zcSv7Mdr)fKqWnxL$HA-Wbr+8%LgQW46+6G~HNbIe5wRpdn9XcOO-`0)47JQX60_C8 zP+s1ae?N!QY%>Mz>`19@E$CD&O$aE!FxPQ-Bt&&rMFuS@1U2V<_j)4wMm`95@f&i= z9VPXZNn7#h?^k6KhCZ=bIZZBqu#yuiE95X&Po!`Z`8qvp8f<^ww3B%OyMKXx z0cn9kQGn)1E5MzD{A4G+(WN6=Lb%dkGLGPHh30&PkEcV2we;uAxgb4hgP5burALYdEPj(M-?(NFC!nCZnHC@Qj2@oNIdgpa z1ERg@D`{@NJ(7Q`ddAwrT0A(vw4u~b-VL?E6fS+&|G-spyknirfRqE!*&cA8oO6*V zgu6j8YOf~phrk2~K(CAK?;s6g#-DtYEu`TFPe}=7;Xln`>KKHJ54FG!^Bd^Ye^49T z@WHq}I&z(6C=DJq0;J01`xgSc{I)s56_sTj#!so}$N&ui6b+a%LF<;W+k~tjrGh9# z9%x||uGjhi`hjCYzf*ja-hj1h zYNbzgo`Pi4?Y`v<9^CM*ae+TF=UQ{3AXqY)dF0zL_hy(;(!^3i9!7+|c|o&5Z#~Jve4?(*MW;&9$wpW5@OjZK7cP@fg+vx_6f6IomfS zNU_vg>&eqE(|Ve&Ub{tQBF2cqTOkZkkA8#9L=+3iJ!F|@JS!EOF=!n6AMj>KllmT(_rvZ4;93_N zilZ^B%9PW6J*L`ph%Php>(%rry7XRX7eju&giz5k%YSovsOZ=?C?>B@r)G%vb)=nZ-5R!>&*{}@ zGv{d?+)c0=g3Z6&1NNQubuQ6fvTe;mi9Id4NYI+gNz01TcK%O?o^yR$DPZL+>}D%9 zFR#cjgkQf9;LUqR%Yq^dHFviiIgb{uI-g3*cyHsP1uyKn z4%D-YB&^0==SIvHh3StJh^BwJuW(KWlV(^A{d(!{kT%@jV{aLQE_|k5$)ikO8x<7c zlm?oVFeofBCfJ%?QT65u;X()LR|9{4Cx+H>nnQ~f=o{3ni3IwL;UTM5doGE-;kIxh zHRm_;_Ik}yG`n8ht}snw0B5Br!q zTn9`FdXPth?e!9JaaL6oo!3x8_7BdH4tSo6ZE8wqW+woTB@Nu_mbp6*JTmlA$F}#C zJ-66aJX|3o><_Zs$WBmrzTu{@`gO0lfrTWks>|u}3SaTdCmMu_p>++?rtgr7x5p(` zLOCN^!k^}E4(DQ9@&h3@*xXICOwE_Quj2&~Q={+UonbdztgD(R8l;HcUuQ~Q&0mK9H=~0LzXNs0EG2+K%$d)eP}`&Z+DhuvV^ z^?^bCN6$h-!zS?np5(!|(F0&%zBWu|Rxq(zK>Cyhj_+iE_z1cev5fe+p%ianAl50( zn7N`c>iMA1E|p#I^b(v>I=RzIWUDv=VVnz(xeJL18XpX!J5?u=qaj>kqg$6~)fzMJ ziby@hq|&E~MpC%UZi3yvnbEADGDFpt+6;yeiY@!qU_CegQV0saJ`Na^%Uo&rdr!|O zi83?NS?ALKSz@1;4`=BXR%~}$?ml=73Tr2;Z?pbc$fY38lAXFIgM3694il{F`8T8& z!nsiUxZ+WrGD|d8dNPY5oEq~!Uy-T$B8Q$|3jxDw*{CwFe&&sn!D&B0f|?L>$Koc> zxM_Ui8xMS`_od(|pcs%jBhcS6-~vS26L*p0M6~TsyA5Q}zMDBhKvV$j&8X<{cyCc% zbT+a(|8Kr_4WTd2HwUigr%76C(oQ3fhe0w|MMLduAbRR@k5?oRN#o9o^>hb_#l;O1 zXBhlaoifR6oV$&A7cM_ydyilu)Im_pxdM85Mejxfr;D|7r1F=i|L~j}pvf!6j$JNU z=XN4N?Au7z9A1Hrz3ZCPXVInD$|b*pcxvae1e(f~d3vw@gRi0ts^f*&R#3cusn9WX zpmt2PM-@EnZHJga7Ht!gSR93Co?1tKc0(R}p|7p*Oq1u?{ z;u;lv_k6c>=^uHBAtkRAM<)3yGnLMKQ?2ly7ei4RI?1u0+kG^T==EjgVbi+z5Q)jn zQZYury^32oRF!UP;8??YIFj=G=rr$kD*4;sT~48@p3J!aWeP4cO`fwGO7I6hUub+{ z>%wj%{|K#ceJWP+duOEtW@!5czQI(`ohmi1um@rPuEK2f0K%tI-6-t-Y!d-e9_G$T ziQy;y&%%i{Ic>Y*GR_#)oF9tb`YK=jb1Y=$t>lm-_6(j;f!50;vJ#ofU-|#e{8~GO zsspGa^Mj($ihj8cGH6*+L8lCi+{r%{ZLs*FhGzWv6?`}aAvF(nr?~V~gs;y(UNecs zjxvOwksqQv&~E-^hbwPdjFJCIr5Z+^lxHsKI7@*amZ#73HW`SOv8cnP0v=0sVVFNUlbsVmU8gxKqEhu| zo%2R#YMr-$+@ygZ=2ARXD!Z(GHzQ3J(eT(}j-%Qp&bpRZ#L+H>oW{XG2k!alr^k+{ z>#-FN1=`9bhq-xCH!qD=<`If7Y&X5jc{-Qin$u2UL)XFE7HsDX>Hsp`gHQN9xrhVN zDo375a{0RiKC-%5;k9;7;f_ec`6%vo4XPSAs-RbvJ+n(iJliLbNAFcHU2rfDCT^T$ zc4wm*Kro-f=EL4KjNgiBOp#xvVg?{{&7} zkq_~#Jclk~In_*yl?TZTa6K(&mBY?fC}HUEz8Ki0c-Tr|YZtZbz^$ z@DyqiAMqSSnXs6h`emfr^!ePWvG8AElDUlphBap{#M6ml404ZvM~~GxwM&>PRqq7#Mwfpl5Xq z$QsI5%}JeR&*pY1N?~bRo&lsc+%5fwmF5*!O}Af8#y+`-G&PAMrSTS6WtL5Y-QvJx zP@%r>8cRDGTo>t#AB|DAFyBlT!tb5gTWygrrA%OgGaq1xbZtz~nFuR3dwN<%z7u&+ zr9$hO8i&v4x~;f9 zKZopoRNELXxY4p(?&>q~AYT@#nwY);0U7wn7M*Dh68WiTg5cc;SGNtn9qo7dZR~>5 z5QjG6T10LXOPoT^s0W0#1+`M^hzMY&-J2;HWEsbYAigaBVhkazY?LY^IPfh7#Cku2Ngv^+jHK^uKRh7!=d#29i{N70}aO-bwxCl_5DTb76IP8 zAKmOPtCe$9utUFdmmOQTXkD_prFV#(8W}#{GuWlB)VyXTzA&GC?SZ4PFN*svs9$gJ zVs!m}tOLI9W>-OVQ!!5kS3U=FeB{zCHR^62K26>|`I`cDhD19J5o+zI9N~6`(C{BR zs|B>j%*v^P_MEN3(%T|0=t577xW13pJ!|90gqA|#xPZ}KY#--QXGC*p&n|RER=0NhddJEGhT?IT##EQQKllZaTSHg8uwKXjH78oSyPIxOgza4nYL$!R<_qVg)yoo#{`6-+8Xzl5KB zG#Ty~R2;|>X7NobdN0rqNnegct^~!y{qO~}Im`lydHZZ=a?DvseRl?!%vfzo#YC)# zR+KypOY@xRPjR67I>?qZ*^}+7knkz;I9? zpId3Yl(6<3dOZpu_sC>8nCU_#OsX^g_zHu*9r0;(f3Bu<2O+({dHmq55c>A@d>m!f zo~!e)j0S~XpziL-*Qb51qrQ8A7e(p{4#e%4-)kV(N1t=n+{QWkUQ1o0Rbd##&DR(C zh-EB|sl_VpkPhP&OLzCV!}Q|X)xa2YU~uFweF;qp`I{>ofgFk#JeGOJ|0U96q&JaW zz5EplLls$YWjMAUqKEdCRYZWbnz^Vf|$4$T4v;up^;O2u+qiEG&Z=TZ~S6XfAL+^F5tzd^)n|D>=ADc=MQI zExMG1cO($RE3e6yjW5GS-G>bRLl2>NT7f-VoVi6E8pf=`Ui9&eYB*aMe-_vs31LU4+Dg9#QZzfDa&c)) zW7N%}ooEs%XaP%i5#4C}+m53L4luSii(l((Su6xdoH{|%{`nW64u1`Gzq-b1Nu}xP zA{Sh6oyb~7xv=N(3#l~~sev5NHbf}AuLL&9P{q9BGAq!TP23X7qkbvpY#`*-4D`B9 z$3^Hu>C>AKFw+kSc`UL~&R)D__Azv~aaX}$Q<3^x0d3t>9%sdoKk`!=f?C4p5$&J! zYR$u)CqKwd6==3%IO(vEr}-EYen%WwMN(9;V{9jjKJ5rf#M(iVYhamapilD{nSuSl z)UofIi@mPR2RrP&iF`pR7Z|UgEq0@O-Rskz-mgusj*sI7JvIju{GLw4)nBKG3-moA z*#?}Ok!S;RFzm3-)*}+*a-MLB=p#dGc<@|e1%r`tV9H$sxg&hMORQZoxgM{u02^hg>r?n;+F z8kIi3r+iyTkv0!u~rI>n^fn8R84tKcF8)o5{&9snfmL zEC8&9dg7=;O9;ABg;ZG7a7R=fHrmQkTin96pQJOOd3DIr;alLkbIZLebw=33Uw!o? zv2Bk0Ik81@Dj<_>YoE-Z5QZvNPTBM@Zl*>#Mjucz-+z#orBYgcrAFOq{9v04q67`d z^RpO|Ruet4VN*u4FI_{8>vb4ya3?#L!eAaZ7O<~&|7tz%3YpB~>5$i^!DX_Tm08z5 zgAS`Z9KPMIHw<d{O!trm>ijoZb%9cfxCeOIuOfUbfj>7*Or}3*yRl@P)MOw?)%xof5#GTL zSpL4B?UWF89unIByt zDYDVs1QbGM^5dx8A5fS;-l1<`ePzJ`?WMnW-VNO0@N? zQ$+8~qDF2=@zx5tFj+;CCOxj*xSyLGvHwiqBTPWkTTF2&lpm z#n155B&is2?pv=jA-pLv(XQ;4!KVcb^u#EtybETAGVuRW+UMsrSDbEi#pFx$SyNvm zT&l+|43?_d+RS4m4eL+}?M`TqW@f~QkOx8)PTIn}Er(!=6bDz6b4D8Xoq$C0=>z&d z=~~ZbGR4^zP5;N=mxTcEGx`E%$5qK&N-3Kyo*hbc1z*jes}%jO=;+4sB4DpxPT{Gw zl!Hk|W(UNm8G5@ia1!a3cU!I!OmD$Q=R&cb(`|)=c13z9We*91ZQI$iZU_@_YvSgHSU{!9{e1$GEc>aUEu`2wm9K@VeG zb*$KQBWGsavyXm2tMl=Ka%fPwO_BI0+$p@OrmFWln93;qL47Q!uUXPlwBc3cyhj{m z3|&ncuGJvO938M&(b|Ufy7q$am!61uU`6gXID?O<0G1km;Mps7VVsS$*vAJr0;B(z zrCYUmBo_jx)Co2{=^RogC9jzOSU}{?jt)S1L+3NATC@8zZl?8k5h41G-4{e48jYNP z3Q7mfi)92Vs3j#jx^TMZ@__`-IdK7?5FtTk$jl0tv5XrU%&U#bVJXBZ5)0t80*Y?j zHQR$?qY0MdI-o<}-}~w<`F=0>a{CRca%kfk}Z0e7Tm}x zS41sp2Tv!pKo%|ddPz+ug|XtDworaL_0IAi%%Eoi>%$I=h@H;ed?bUQ^cH#SYwInD zAwC#zUNI}hiv8!?UKB!My{|{_U;00BVnV%WBvoBEW9Du%u~N};c1XkzS218ean$J= zWSz$eVR!=Aw-QzRMwR9`pd!CY^M!2--;t#9JPQSTtiaZjuu#VKFpPE)@WN2BE}JY0 zyX#u>|D6>yW0wtWfSl?-o>eOIw&T(!yOf2FM!Cn$W5zDVAPz=1Ft?sX{L#%`TH>e$ z8m_uml>cCG!p*3Q4jrb{fN8IGRavvkvH$Kw0fj(hwpt!^Si-QAa-Kkj<__@c82!4C zczN&HOQC5DyN~2W0@sJ9JgNK;Q?Tvl3f8;9f3z~f4SISk#R#wo9^ml%-a}?`!1NxE zGOv^YcsD-_m^uxjoKXAz4peGAW<0p_G$jIn%)z0;+r|`jTh*UqBCdw0bXa9+<)Ig~ z-)xFOi8X~*OnrYPJ{#H+zcKpMKz!r6RrSWjoELs^2w`%sj$RUrtP9l~*@A4=u50;r zgKBUF)jBud9c3n`&DjthS$;9LK`|$nX9!a(e$*U4@RmqM{F$#~%E;DZFg}UZE5n|1 z_S!g;EHS#C=3lxD1ns%#O43)!z)4}wjFXtU)9=aM*ncb9J5HTkW6b@QYA8;t~3;K=xO`g722n1~s>hc!pC_aWNkGEr% zu$tKCmiKK-QTG*$T%t-Kh@Ko$6)V^ubnxxsMEy;`IKz~*@7GtSKAX{b8W}p@k*L^F z)GP^D!HFEC=))hWy0!=aco;@?tlF+EtJr$4HGlJz20LO5Z*v+qBYPir4iSEVV_+u_ zod{4+6(kpD)+9_Uo^0AhJ^GzVU_wIqxLw4!*W0Q~b7=;hQm|0NQm-q2AV1K8xy*&3 z1!o$?fb(>_CG$w0N;C%w>a)#D(U{!6Q6{cxFmBdul}9IisO%4u3WgHeHy)Ti5gU^Z zSHb_&=3rlCxu>MmZ{>pwbnV~J)uqGcq=kY?KQ7>}*-*6}Dq*>mMEZopjTI>H_Z~33 z`TK2sb+FxgizKA37K0Z!k-kZ^pi;eEOoLicKyQ@Rm% z?aliPY#UG8(!{k8c>ay8YZlk+ZBtmkgRhgc<^@V7O6JHSX(7(5r^OQpX;$G&Vsr3?~JfKG4@YQ!+Xv8dx~Zzxy}w) z8bq>%r5zO{{*c@cd~sM7?&S8|t>Q`9nmV6zf9r!AeZk5MYMnyTl7mR)Jij*n+tFoO z=1C{1qZB#52U1W3o5X)96FxkN(^Pyp+6@6V7TrQ&l!d4bZ9;I>Gh>LFB#qfp0>l1% zZX*Vr~G<&@~aspMaqAe-Lgq^Zxfe znidn-16K!%MoeOOWMF#flk;X+7CBE#^<2eqf`RVwnF{LtSDpR7<4QX`;kqmlX*yRQ zKCu8wx5*hP8n(rj*Af=276>+~=k~lQ6UnZkL*yE2c^^qW=oG%!SzbYQX%oC;)OMTT zt#M9hSzCydtR*}i+6j{~q7Zsp#tbVobQ)>*4T8sZUxryLo00)`H3q;4^lNdv?Q=n@ zdypjV6Y*IP7=BOcAk(yS^#QBLOO3+HS(d27L7_YJztgz@CQ*s<%pRx4J z9GsN6)4*?WBHA4FuQy_C4ALhsHK2A`YW~dtdr)-0DZaO|bh80~_9}zWoENGDph7`= zb#8P(x_w4gWHS_R-oeL9#Kz6L->=P27(GtE*z)zC9VYCy4|qw$ACifUji!w1{=*u$ zk-X_;U#y8V|E+(b00CThL3>s}O7Zel`vCxj-*B@(Y0{2Xrd>Wq+mwI5pv9;7nhc>h4ePbgv-V z^HsZp0MNz^Xc@itHUO5LotQ2M?1T!aG%)hROZK{8g%`MubKR?gD>3@FSECDB^-PI# zk>T`>I5rqwCX@iz%h9GR<&Lmha+%vuLzG*8nqiw(oCt4thsV%{ucF}&lP%6P1Xf?P zAmAaDv7gxii=aug1j0GVJM{z`losD+f;`Wy2IuNw@pBX?E;*1TkggWzwOhOb2^+5u{>(L#7D7diG5zuSq*;|zpfGPm=lf@>3Y)Z zQv3c{dA+(@8f1uCGXkWNQA`el2-wqYN%N4gQF)zk@w`bl{59_jJmD2<(jLiDVY`FkR!4X@3^Pf#qde$?+PL!rm=9N39gm7d2!~ctJ&Y@neYe+N?)_59vAkdohMbI{+-|{J6 zf!sx*gMIj{*PqILLLJ(WQSAY{9wZ;i+JI+r)=_7+(XBcSf{nE9mY@wEhaxNYD+LR6 zmWp(mCC+8g;hF9{O$F7w1`Bmb4XE-JzL{*Z$>I35VOd-edYD?%d&wd!HQKQEAMUWf z)e_K?sYBO3*T-B51J(#?M0y9=gxp}S$*ZX^-JZac0g%xWkU$w-&hvuJ%fE#Pdps-< zZ6};wKnPe?ypa{jgO=mgXN((v?rQ4rB%AW`FCZHlD6F9gO58G>`BV)et`&%D_?FkU zaAh~IBGkANVlkgJ>GRIY-;)bYzF~Fi8T9dp*RvJ?rA#G?OO>9GmX< z{CEszqA}fQwxYjeJo8;|@C4th;po<`gZV_LO(phX{1VTgkZIzj7o66VZP@Hj%xsC^ zd0U8Lb+c`l^jnFo%iu~On#!kCzxq)lKJ@2*HZBw8DwAAlRv$oV$Qr8T1`ewedLF%K z8f~UnlQonja8IN>YC!8th4zg@_$2Q6G>oz@F$Tist--l%a$`_9j_7ZKNg?*CIjnK@ zmwVd7I^{bsm{hDza_$M^lFi80OUU(&-hgU|E5Egc?8B^oe;n$HR9P*D5tuW-Whh_jo{kYSVi=5aRY&x6bpHvq}1MbKD z@i&gJG!Pbl{eUL$_EEO^MWj3rQYey|`x^(W=Xfu%m3iQ^ZMbF0bdds_H z5C1ub#D3>rOl*MGV>z>f7@tBJ;?3j!vc1rl{$F0_Dk;gsP5rLy<|9MV!Jdgo8Zg$E zSb9zcOL!de>~}3Sw!~W&`}aDaGdG1usw6k(t;3 zv5p{&1I|Ujh8_`nJd}MiH1^FUh!qy1h8IL>u@2kXqZo)-mQhC=&-f>`XdWCdnRh8n?+$u z#|VT$`bjIvXh(DcfXg5;LFrTvF>-{K<7@7?o9lcMessQu1oQHY=PX2m;__#_i)4Hs z+!K78uiLIOH&sJ+iB+Bfx3M2QeUK2!1Y(EHP~)T6_7FJOYsh0O-blQJ-+bMZAzWV+ z*y603-VOHDpPc3`;~lYHhr=3x&astrI}@5)ry0<^(bW;2+*NuwW7*)9VY&2!+Zj;& zmoM1{je}=ab7#;MaUU|&K|SfMQrt!RZacGEV<9u}nT;k5tUNbIa6?2|8o)4aHAz5L zgeyC4mC$+(?|*j23quRA_G$et2SEGNGtn$lALJhbbjS;i1IT(dV2&@xs~-?rxgq?~ z-RMEE?B}j?;e~=YJ7UC=ckP-V8D`^gx8lJBu!DP*qaf$SFt5M76fA(n^~f#XWW)zi z+k((uq9|7Z59g*djHjmh?_6-Y8OV9lE)4>-_rpQY`oK`K^`P?d_^QEaxb8c2Fa)J6 z+Ljkg9J3zF^djQM^{M7?y*4r7BDtb2p=HrushbdMa%C)UC-QKBFF*%jV}Tvi0^)>U z10bxJz1=HhWM6;MVqy$~QJnpf-u!#y`dM%ltpmlYUV8KT1UX?K=M6LJKhB)OXZ&|x zWZRlcN_1zn67VxL3$z2`512cRVVnEQCQDADGOji{={D#86v{-HAXz z&qt!kDl$gz)&N# z7vT`nJC7DDk|-25=?m2qJA_8U%6GU`g$gX$jrrmi?mX=bXeZPgWO_vb*m9EO zw=9N|&Yc*+k-2y>s%=uBuVOC+*WP8|-UI?U@p@USG$fMDEoO4*+<})wfjFuK48u89?riU_@6<;s!${OJhXh$C9?oIHg_m zVBl&^!El2ea;hj*Cp@;9`_h7ryWnwwl~o2q4X)R}IJ&KWoqHe-f9NA1qwa_<=aNi? zbZ2-OjAwwv{lJm(TcTZEsQ^vNP~hYW&s_H&(1fx`h@&vaZhDiGP7mVpN>|fy$k=#G zGHN_`zo0wBT9k+X{xwu^hQSL=1;dY$H^dy*G6b3}mrSgI6z-U{N9U-8^XOF^y3+x< zRjBtU?;-UK*%a+z*W*o=TB}H@8K5NFdd6K*;0w`HNThrhXjP*8Oe{)U_-*wUL1jYY zUDXu3zwR}_aa&QbBtV#o>_tsZmTNq;OxTG1O5mt3Z#`3=!|ApehH|TlRJRuNDXyl3 z6kr%@xVyR{I;*0i0`eIDjsl05EjKKWaw+LIz)<{n26Tb6WcBX=M1Md*DX-0wXr3B% z*1Y5lDbU|UbWBdUFJaoUfWPbzj$`XuJt&p>ga~i^Ilb0N&Rzix{Y1^siIvEOVSgIm-HrsT& zxrSf|{SUt}TmJoaF@{76!Pf9&X*S>aJc1lJL^M`pdNF&8 z`GeOL`J<#Nb6_xCWoMW?>VX&s7JOCKU}JAJD&qzHS`~c*Ee`QP$&+Z1M3VAnIaMID z&^F}yn&DJ0#Lz1iGK0~!ySAdEb0vks72DD*n(!ZaZyIl8(lPBpwWWfSMZdxJb2fdu zg$&5B;#W)}3nygMaZv)5B>C7EIqiZoQvOzh0TQB}fB#9#h(7n+$8Tqpm8)tDzN+&Q zxAl`{m<>RKqW<#D!OtSD+V||jaS^tP+yBA^tK4a6i9%2tEpEy_-ao9xXN&%W8TN9N z>|7_k&mfXwnIo}Vn0UD&Hy!wz*bJT5)Plm}qO5Voz9;a~krobY+uckYdV*-Em&>O> zKxHNuc`Gw>99u5{Yj`7(goO;or;)YKi+z$3FLf+%W!ap%!=5U-&cDkzpU^n!AJ>sCU1%STJ~si3t3 zu%ZPTmTjw%bZ!r!%FH456RUq$2xHB=2L0zd%vX=FxM)<0#GQXKV<+=qt+6;l5FFqZ zA#9HLLIn*oZIaJUo7y!waYyLsV!xr?&EG(L9C5%0%P$fU2o0d84~7S?tHgx--wwnRdo8tw77EFx3ethNVPBWWpHhF6u}d* zNpS9sHToU0;muhQWW0?tNdqkalsZs?29>2|g3wfecJw4z1zODKIF=2mBDOC_322*2 zLpUy?pt}iMk3Rq|WXRlkf!Be6mGcWEa}R1ViCgaVyn^}#55{+1p44hlsx#=3sL!eV z2AQEJP6$m8ni3_^jM0ZJHm`G5B3$yLT6g&p+&_~T=!MU&7i`bfYxDPGFsVS-+lIMW z4nX3bt89hVc1aA`-nuk1&e7Y9Vh38Ac?AI1-}bOSO~w3)!q$3!a-UXYNN3k)*|1ywJpaWicRU`W~0*H=w)u=d2i4QJVJ zn?~kF+*T~)Dj^21K@%=+Q&W1)b(4|CJ*98FXbmuGG|LHaXPo4EEC&*abV)e1WD9A` zDsQj6I>6B85R~#Yz?*jV1{i5SY29lEXWZZ+`jDC)#jJ(c?_=~O$_orep_#27Yz`*E zMGogDp%Patp>6wHg|WE?W_qvrny+(al~Lw8TOzTrU)l59O9fV-t_?|t;xu@pL4u8h z@nmoa+opbXI9X~D_!sPd<K7AOath)fe=+EzwO@(fRnnM<|m(BSuq-%nfEmdac5|k^agNS6l#~A zqrMp`+(;}GUi&#e9l1r__Z1zE#p$8pBf8>xI`~J`Qss=)7cVR`RpjYSzZ3R+UIh%P z#-l?CVE=Cri=sl!SS4-J-A_qaYO>5=Exrk`UZ0&qP>7P?!KffP~MSdW+)NGPW1eMrz%n}6*;tcA@2c$pR~ z#Ihmd?6Sd0GHETOZgq=3Uj@DDX3JotF^`bigM{lqOf%~R@UBt|xM-ATy6=V`s?@%k zrt(yV40E&!WcYhF)>gIOx+YT=kD244*Be!of{z2b^AOm1_YFFpLt*cgKJ?z=_5vRb z#%@Yr0`!URp*MNJUZGCZ|M2EH3Aku5=1VmcIkg=gEu9K0u7=h}iLPDneCkzFnsh4e zddhvsoh0(N@^lj=cI3CgLXm!_DD{KBke)o~zgHKYNyi(#T;o&Myry0~lb3O?Bc;de zPj>7CVMpo7mmo`!Prc~CdUQ7k;VwKIfBxUSzzmYSSm!q7o_As(lS{M5MDv<&Sncp_ z_9>;TBSg3GkQCLT|0c4h9$u^epyoBhD!Ac$QU0}@upN^vxcV`kEAgEfDlZ{+ zWCx@?Y1JEeKaCrjuD?XNwO-MxQ-ikUyFIITrA(RwVe4&^lKcI%(GPTAKOJ77kE~Jd4;BKub+?03#or+r zrQU4bC^a!&cw7UX+d`fT1`>v>Q^mP@Ldw5O>HiQQJc{VVe+o(q?63wo-y+xojO*_k z{Kxe3$lWPIIClX6W#oyNKbgOzZvbY6P{9-COT`8rXIzET^!w~U6yKB;LTeDLtTO_qJ_ekYx9o%&3Iqy9e^Sq-|=)8Y-UF+ueTl%G7?qG4V*?1YZY zeCg!Wm>%+ibGlS6#EWqR919&V9xDHu?A{CKz_@28`NaZlMKokxrLM?9%SiS+Y~^;D z2aC(Yn>h_L{aQ(%zM!{2tbPEiI*Q%fqI_+?!l6Cz>nf46_h;gjrTQ2M35ym#`XE)V zPN9>+84XnRnUMxJv3=aOw?y!v?F0ifvPQz4Z&X|gNh|+ODu#)Ol_#64z94I8n1l-~ z0vR!U`Bi6x8lqo>6pf|NgO~FnMFQ3i;O&at6WXtPN4iyGDpI@jMj2X42~chF13pHA zVo;j<%h1WvnDsOYfZm(~u>79Pi-hh`G>J2-}xts5I) zjV#};kIO?vp05{gXB@ugoDbktfHfaZuV?$itMuceyk3#ZA>bFBwi$8^9ER^tP#>Q; z*%7un(wqTM#*cdf+BijG3**$o+(k;#8bd81af@=^&B!$RL!e}yP53rYIwC!szkHMy zHEk#W-7lLgl*xcn_!aJBf6b0Z-sFGEGiXamVQu4T)??Ebj`)NBXy$L+OYG>k>Sjt&d#86E+xrh$McHOll;Pr{Be=`d)l_o^FvA0UaEtTXn!S+Ar&j(N!FFky zg{#?%dG<{1>d^v@KJqi!2)mq}vdZGfwZ@63g4=cF_ju6r6iixSl>?#@|e5b;)WT5ZNO3mv}kyydWeL^!P%hlJ!QcO-`+_9L$u zw^7CWJ9*E^Q{H0_Ra__D$I{_d(8>NRD5tN+K;QR)!fHmfzm=yseaZrF(L6(ArIi!p zoZt7}UkJ~?C_!cn-3u#OQC)l7PW6jEU`=tD+&@MC0=3QKSL6@~4*I?*@7s_61Q_Ur zMR_W{+GOVrXM&h&15zx@+VE)HT{`;LFTP#3+{}8Af^Pqif$W6HhLm5G^iF1YmA9_M0@?po?_Cx z)nA%g?Dt;qEanm;oyL}c8IvtKFxb{#MJ9RV`#QgyAJ3=*avMo@GT$*CF5g5fLBH<& zGn8LAVN{Hdcy*V1dgjw_kFY$Bnj~CfVL*7|c%++n^Y-y3c$cmOOXbHeVa*H3k~bcd z>o0D{uF8Kh&}vz1|870AoB=LpC6nr=Wi?!f+D=$v9eG}1dicjiN`Bt8BDPV5w_o73 z5x8aP``&P1v{>M%`JsE~!~0biF-&^k1tybhLHRn8>d2|PGxj2Tr@gvUs_nX?+Tpv_ z<~7Yw_vbg?`u$Tl7}S~!wigMTix)`6!nf~ld})5m&p;+^81Qrza`iytuXnZMy#17n zXi?><2>0gb?`X zsZ68go`zKlKvKhRzm;s660U$DP=){QkvB%930Ye=&p6l#_fS8uR5gA3 z$o&X&YOe8Tp9;)$_!@A$>WgqZUj#GjFZnXfPUe7%Z7Dj+;k#{}Kn#*w;lPtBr<0IJ zL9M8dDh_Zx9c*&T@6&yXkbX7#8CJZ2JAnZ+(jXHf&CRz{0w zUE1S&QXTK7a*uN(D541V;=??&lgb4c7^hOo66lG|t6x$JCu9{GDkrpG2CpG`%&@2E<-b52KVw@S?XQ^10_e-pZ8C}q6-V}Nb zr5^VyPfH|c~D!1*S`*wJBrwBOc-o?|<0himn-1cwyk!GzO9gv37b7Wm283k&c< z6*;IyIFXBLJJc+8dgf9YBjS3jDPwdf?@7!cY-*!R9wVFHt4slOHfFW2$jIK=n~`Lo zqe6t?=FB?+VmZ%DwiYEyC8oda2o{)ZDOb5m!r^Xt2k|th@{*KI|DDh(i7mec?(l}- z3IYOf?u8G0PXLP&w@ldMR$93(KVC5iQ8Kl5NgU?hXpkSXgg|Ee)GgU<(|!7z^Y!&8 zf!;ygOeU(XUVfEl67j94ZCCw34S|kUsFRTQ%IC_w`m;DnVMe0 z=2J0A_1*FJ$;IzFP={FFK8N z#MVo7&WSvHS};Wgv`2w&ZV13mx%04_nE9z_)_-vEAX zMA!fT0{{RJB2_Zhp5x9$^h=oaVLLKnk$|#Oj3x=HNaS(B0000I0iHcXp8x;@00093 z00RI3V88$X04M>TKSXB$tGBKo000930VxAUTGgZlJY#!Dw*GY-T$)VLizvP+G4KEY zJHA1hBs5G!e*go0kE)t9V?m*%gB->)PP#lIu;;G{JPo{t(`kmWqzoR@5|a<@7qtd8 zEi%ky$3en1KY?8;(9vC4%nU$v-mb1$mDkb5z_0#`XvSy`zT9@;M($W?zi)t9nm0Uz z`KQ)Jp6Cisyx@mQfrO6pJ*N^RFv=aUXpD%$aOlTkepQ9Pkx2^ASBr=s|w{TH3&?WzT$&O;L6q8Q_#uqu-D zj>N5n`M-nfJpK)0GN3>l3j@a~_#i+@&5=j8eE5%noI)e`CKYYjJbC5c*WwGZ?di@+ zTwpA$9Les+?34~rx;B?QnMnP$zlbK>P44RywuH`m(e~$DJNgMX&Yv984UxqWX40b@3D6TwQWvK|D8qq&jU^`2 zxaZ9#{$UY#87B)A+tM?_S_(%Lk`1Em6z7Ss4@+@*uWS*53nB%b$vs6= zdLqL-4xw-~M*8YdBD`TXUHI-JkpE%QUm<2D>HbvSE~M19a!#gncngiPN@OPXd*mh7 zuKOGH>L!n3g%~RPh{bonlB|Cp{!Q`t!&Iv zN1hL7fkAO03d36CmK&}cUdOH%q4=@@#Q|XT_-g~BeKOqYWA}{v?d#D1aIkCXPB2%; z;7gWcK${JR$i4LnN(M~O}947({Bt#Ct2|^3FFFlmb6FMVZLIgCtUDzDqx4% zf=&4}g~$8`Wk1f8Z!qI|gGryuA=MH$33NaOITz61Fj(WJ3BiodE_fNSrjr8Kfyxs} zltS7x&ueKgu695X({T6JRX8Cq0S%hU3^)u1%y7`~lp(*NiFrqHwX*lEIqw~byE9x+ zYN$fOR{Qn7NcS%8Y&Sw4)&uAUYWC%U@2D$& z^628DAl2oQVuTQANZv8P5<}wPF8XzH1|WhsEn(nIxkQL2efJ4UtkY5ZvD@x&!_B~+ zZP!K$2g0KFD^E)!mt)cAu3&}~$0W_8uq=Rp75j&sw!^ksBOR9316<(-w1uT7M!lwD z;{mz7!V0|~!8xa-oGwNQOGqUpLL&!Uf`;D>sN>>dk3%QaF5oR(h@Yvq?quo1j3C|E zF8#0gug)v`>+`>()re%qY){jX9k8M>U4FyNWB%g5v-X=%D5l~@d(W~+U(CQGY9Ec} z7g%=`iEZTG_y6vxiK zu9g`ZxvJ1c|NMu@P{_fyDES!neBKy0KoSgli5;N|X$p6YITCRm9OJX;zV|IwEc2Xo zW8^kBp3K%vqs-uYOS!mQVboC>Ov}|nH$nI3JQ34p9PKxS4t)WAT?Bc0DuU1dJYILe zBD4(@D{=C=CEI`DV)pDVf+Ish*hLI57vn7(NEVs6$=-tBF35Xj2`3e~q8`>(W%l#C zF-z{T))#`2FUh7(q1^=Fd;aPeMxFf8Dzn&!RqbiYXv=ppwFcRqo`UVtBD@(`ifp&y zNG~~&&*Hwdj9hljh2W3JGF#Eba!@DkKZ1Vq4ZEs5k1-P^`g*T)C=|$*52pphT&Qs+ z*O-Y*y)%S6&DKyDFH?ZPWWl$1gRZn@WB`_Wh`ap1=JgnVQI-MyZ`>N>Nf%(_yC#v z6=(lV1lPnnbvh%qS1}v)nZ`30mWdTlOr=V-tblb!>^<|19o5$%6%uh8b8Hl%`416H zzANGBf-^@n#X7kBUbsiUM#uKbK~6)W@@+uesP7S$MR*- zrYs+ok|dnOkN0G{`teuWIC}!is1yK0z{g zN_lTP`)2f3k575dcNjO~i?RI&Ab*$u1`ZYl*;ZuzUgGY_8y(>wA1OA^p>tKVQm2|m z5opz%HEchf3zzf=vx`0nB?b({LwR*n^{8f3Tx zXugvh&k0;7zr>#L+<1_~7d&2WsZ$j8Y@~UqP@<(Kc6F2q@@dI&wQrB1O^*r42w#ux zSoo${vNrGoLOn&LF4`_DaKfdIq*$Z0x65UVPQ*!5nXOPsMD1zc%md)NbShqzh7Nz@ zVa>h?(X5nsO{B3W%C)!4B!6Cnf!!+t$%LRqq7TLz2Jwz~=9Y}iNcbbVlxF9o?Ds3i z41jXc>1ds+_@`(t#({6@fV&>Yi*WV1Ol!fS$<>fPbiNjUg6ul=ibwc+REv-}Z~Y*4 z-y30$=y8xHhFA$g-AfTMEXYCvYbdH3rCDfvlC1_bb#dl~#@%a=U=rk-8c(bp8u}8p z01_iPFy%rdM~c*IZ*Dvv6baW+u4d(c#z^(o3_zM*WZ35mEyeNf+y(ouOat*0;~J=7^`zLE(^|%`|Fe>P6Q76NxE!v~>Th z{g-ofRr*E9FsaUr4W$DW4#6N^#(_;$$Xb83>|s+>G$zoEt578VnX$Soi>}c{v~SlE zx&Sunz06n>r1a=!B+*Q%r3>tQtVP$+u{aL>ZY^HI_hh?>#Kx+rZ2Gh=9egU{0lIIy zZLsFq=ehC0?{!HDI>fE@Z0eB@@OX-T6!#$7Y$sKRGHP&~*T#iW*@fga6D|{igdlRb z%0?ile3$!qG8IitzY);0KHgt*Sd#6)a|ih6Yyj$MW?*&v#$TfU_L?!xHhS-y!Fv=! zfvQnOW2(4LGE-cKRPQQ9DkeP}w;)>dpOCe+ky12HPxaM9OTSkJcFy15>m~+-c~I&K zr{kuj?$vgo;rG3A2C zI)fgZ1in$E<%CS^KS7uHO4=-a@?d>Wup@unh;Q@ZK69uV`#D`c3!lEY(0Kp|gNMpBH$G=fPB= z*P-IpDLgcp1C`liEpIR5zX|7&Wn$e}UoaR?s|tWl!wFy}t>5~*825@jSOzK<3HC9^ zoD+g;#t^_+_F(w(&BknisA`3ZND9!WiO+4+xIisryRZ~-3FiJ@k9~YPb}oF`-BKEv+2 z4B2}Bg}>nD^pIgtv(RcPsB}j@57S?E;gL&{ujcEw+@rbnIKPL!X5-hatuMYrWGzfU$vspc^DObqv}imA1k{E~-j% zLLS(mq28$a=02bud>WqUo3R$w@Abk=k&gxoTb|KLWI#OewCV(zA7$ouTNrdivHApjmCqz4{j_0J;QNC~bD_+Zk$%56#bc!Ms(nM0 z;aokT&B+5O)nsFO=?a16wIYMyZ)xnY5-XNo5siQn{(x|4wb2**Z0_{h!EohSn|X8~Q@hUN%w%r`e^ zYv$2Hu3B(EPIX_GdH2IL$(xdw#d-5TJMpkUunLD zRXwv-NiH!e5C+uqKc9m9VB-!{WcC4^dXfKiqQT){WY3ZV(fx>bxZTXNH)W zF%$J5^%ohw5%zFwL65!1MW`b7Z5QQEKnk>o^rz_1rUR{5tBwFrQMnAVSs^h{R|7~d z`b1A%%`7`7YI4db?}aaW2w_*2ylt{9y58gzlsXtovhfN0*lnel>$KGr*)1_ZAiuH$ zH&^?QG?b-uzqX22^|?0Rfrs|R)zOq)Hyqzgc044IiS728821G%5MmI56wLx69Srok z3z+M)kYfr#d|5m>Qo8O-On8_UN^jAXfrb&r1Fs*?00FXSXd ziu=)D05JLK#s<)V+km@Wd{_PfE-w@4V}maO$j3p2{(I?FYybU7#$lFR3oK*^{|IGd zkY$MtfRA_K@`jPbvs)FURMVh~y*PF)5s*uET#JJbe?8&O>BJdWJ5qQ%Pk)jrX08H{ zshi&Jpy?4yQzSnE8luJYU2Pxj4!XZEMzAEIY$c1{9NCFtOj9N+#OGI%AsuwL#Xrv- zg844|^Nw)yS@CD*n;FK%Ka|~U4N<7Mcl#BGz1VE?x zdAA5$adQy{x)nW2Rp>ax5AKeub%bA_oZ{69{40CsM9|%O9pG!bQY`O20EI~@j~|PZ zG0L4~4u288_ns|ZN>UG)c`qvF#C|CRS|qTN@**v123F%Rk>544q@sV|3RJm+D0|l=Zuq`SBE3oe&)bv_S##^<UhsGkSVW%6sC)Tr4g$6W@*+6Y7#RIqY;44 zm5g>;9MkG@I-T3kXpGI$w4&)E$6jBTYLVonv{iRJ zAt`$`>>qt+ozQ%q<*c*xQ$*{GyzDuTLRk*yzKokTk{E?K9957>SWf7FS4x3G$j z9yE9BGhu{bBo-^97290H0C)#Bb3`zUcQeTVK{u2Nd9D*p-=DRD6`3*gq~$*eJZz z0&thM;4IYz8NxLWQ|9I#RTMdOHt1|q)eivrS0}kfNfY6quKvV*Oiv(;fwwkv!yI`G zc$q#U_fq?EfwnFTSx}w@BKCm_!TOX08b*pGu;->%M(J~Y>vnp`-Q`UjIeA4zt;i)* z&)?%v$^99g2F>2L2@BSuk!<#yC<8BCh=Y3=J3sfRD{73-M18EJl{%U4N|aYv1v;lm zNDnl=zyL^r2jhagSjZ3<2a6^{1ViuYAt~mToV?posKr6!ecMA1VTmtPD1~ZYGfG;Z ze9x=pN!T#@$YIF9!h2QQ^+P5LJ6MdDNZpmsIx;iCs5<&3)S=#Bh~3{Vy0OW!#Byoi z$PNg{!=XbyV0S}VgY!3WQ4;`kp+7O3cXtYY_(#(@u1-;nl~v{4l~f!)H3^wne$zos zy=T<+Rh+1L_=El0h?#AwFxKY{pP~p9_IA}5v8yb!-w?&I#<_RyCV+mv%T+SoRJ9U%~lZ4&bg0ef0WM(ss0W=e6 zA?YP+VJ3E;bZLB;HL+l` z$dD%Q5T?zyP3hG05Dy6Hob6Vw?=HEfbty5QUyBp!MhQ<0Zp64y)6m#qf1x79t^sk2 zA_pl+l7xGLMjIIr#z;X0kb?J2%Esj?aIS+kb+_Xu|A=cr~;I6{(@&!J|8v}_#!XOf0T$-P+lHE-RtRA!xE zt~n?a68mv4QvGGAkJ)(PktMn{0bZZ!1Mb4LEZhWEw>M`L3F4xa&$=-J`_6bjxRi+a z9#|%rzxy3%5?83^6eR~OuvZP2R@M{Kht19(JGrsM7RK6^mZga!MZa$#!n7OhEX6VX1toaVmA_By|sU*F2J)t0%SLV_13B04uU4h3`12jGgw zPRpoOb!X@N#hD`eWx=dyb{r}{ZMMQ@Aa6EH>$1OtS?b`DsPZ4z{T{fLWUfmGY6FG- zQ97BEO=qNns!Q{}<;La>D7ply{;UWX{IM`F5V%I!L)C>_(YivEG}3kLBUgqy-;8gL zkAA=`w9R+nwLnP5AY&3nbsz1yA#|NN>0UO3I|Ps7Zb(RKBa-7`w-*B?7cCGDM~yh0 zPkidHt~+Gbnigz|Ry1!GAPv?NM)BC_qqK*@Cy_puE~N_%(h<8YlnPzr6w+|BtLDxO z3lz{o$M)BnT@lsZ&W(kd@D+a?g*4f1(L}kDT4ObGsXFV-MTt~*-Z&mo zH%DT)x@B-Obi_aydhx~ZN2Yl=4IO&%8F<4Ev_`q`UT|SL6&&cZUDQ$ES?+QF9eo;0 zz?4D(&du+cV@?Ovqw>_0uPD7OKEuZz_`|&T6ef9!cKP9c;j+6Ww`xeSM@to0d*uH9 zLdnpFY!m%joY>4~QRFc=E}lG$Iw=dhZdg9mwz@SdFRIF2tBxTu*$iUEfI?7ISIW+3 z!P;#RC)zDvU&x;Tc%tCSs~_qNk>oCd*(>#r*CkfcobeQGV1lx$yGuLS_Sz#Z_ifeMBqj%(nKDu^nY~Oj=kj zI9(|*No0H+lAIUzIcG0oHXKh$itv$~4{PRT0@vWM$rQ(-x5bBt9gqTnMQ7{zsL_$n zny3u%12R@p*yMFCfhz3aF1o7F$YGD9XrcbectEpX>D6`JU;k}zcpLF_`PpS!VWeq= zZkKFj<(f{4=7Sw0%VDMN*ZN+36AFELI_x} zvq%PFQOpg9{gVtoavqbQR{2ZVKh;!32JB))r3G1l3LHSxFL@ucj22e#s%uTE;Q~$T zMfkKptklR&=~`ZzKuHQMMYkWpaR`BJfwk?FRQohfQ){(vzMR&M%`pU?e7o~Izw^7( z(k5On(C8l6^UPFD9t`e~aDUP_TPc?F7&^qnFVV8=$Q(&iAT2XPyij`Rik9O_)2R)L zm4zSX!>K}`j1*3`90!KS+w%~*V*?{C-3!#V?}^1xG4%k6_!)h|tb2F&$v>!g3~qK! zjFSp?C0n4?#~1}-yVie%b)v%s{L>Svc%X`~WV2LtK;i|Ze*~ke$#&qtE<+PmpJY_G zGGZU+j0%=KUPjHC$=x-~dhP=5XpxA%WGh+%Z=e9?%Kl>J8pTjo7?jxy@Br{L120Mb+J zI!iHPEq<}V;+GP)aXKru785uQjcduT?sD{d|H*8=%fb|@j@-$BW*|FFC}`pf+9eXn z!Gelf;%Bl-Z^TB?Q_d!MT-S~6wO42<#C*%5RG=4v=PUcwIGCf@;%Z1MQr<$YDJmv+UJ8aKiW zt2)lhf6AJ`VC7H!HCKH|8FpS7y+evJcZbJtfDz#pmBwJS4UPlCxjF*%v{1Zp79^4X z`q1nBXvhEmd|`{Dz3u?rcmA!KCZ%TIQ8Seb)UrI0#sB`rg};lWqpI6&lUX~O$e#Jh z`P?GSPjX?oE%HD#&-dMH$;vI#NpvhUyte@-gNP-I#H@;Z-&Y8ER8DW49-N}~@LGsIlIB!$SP?w+U z`Z=9hfH%@004oOQmSi^j?5an}kuy`~WoP+kcu(;8T7AXmgGIPfmc*+&B<%2PIV6h2 z(8S_e_2rjCfDzxKIY+bi zx+wz#<8p2jz5fLk11dB?HiU(;ZXCk{4|V>LKXsQeUQaf%1Rw|I9J0BBv$y0^z-rU| zb))mV)K$6gx~P@3wc*KJR1S2MtDf0W+Bk7^?YvsobyPvL14HdVN2_ps2_R}_)x6`- zse#x&K7%XA7TzHz{e|q8;KH*ZnHeiHbM0u(%9G}_+BqRH_}Z)5fXJ0Rf+~N0s6uQin=`h3iURz+5a z3=Q*df&L_hlVMH(=d?S-vN-Yv^kT6JAigc{qL^*~XOc>x1WaPo?LOKuRQs9vSf)fz z96v##f$Uzw;-h)A20UhsCcruE+k{uav}NtIW<@E7Udj^K>_2?=7{76rDEJCJv?L%#f1qd6>zV|TrmC&>)&k#!dwV8vCAiF9-l{9 zQGZ`N)}_5w$l(o#`|v7iQtar*OTm-ohkvHzLr*??*L=*v$GYxf#_8iYLwnhS2bj7e zm}0R@3=PHqVhbA7L+n$OI!9lcyf}C-fPm~_E!Nt>yK3>4Mkl%vrvqqNK}#qdUJ!@39wCd+I{4sYK-9`CqqqlowYI|GbKM8m5oF zq~4x*p&!6EJd6MTOaS@^t_nM>3Gu#SH`!*|vmBq3;gex^|L73=f}2zWwB|z5aYD7( zoj=Pru^lhn+#vRLpMRsH{Y%J;(PnK=GAUrHGtH3fYc39q51^Tl<-SuJtsIOeUUzk6 z74d1ve+-VnCwCFHHsJhnrvCf10VA&u|Ns1dl0}3S94gYIU<3%m zzB!oX>-So6B}f682YJw%*X(dvcJ*6&lh)VYBsT%ODk zl=~A)67?%yz5`0%{Mp$)ikG8Ov^AHCi{E>-a%T2E>q~nRRJr0cTA|?gQkniq2KwchD;(if%+t|(8IeqSziiv zq(|JqVe8=Ze>(39PeDLh>wl+;f-M@XOwO3b>~{`?f%F(gTH&Bw0kYJw@s{ZPPnzl_+QqD`Kqe-!j5&SY^B|w-?jTNqj7k zgS^5k;(iz9IqC!ls9oHH)4hL5{+_bZf~MI8^p`JDxL2ngwdVeij~N@uV&Z74*f?lg zqPOzhy^%J|QY6Nb&HJ$5P$yx^DM3yeLRMReoxu2OI}3r!I` z(}r9uF{};%f@N_d;2WMi=T%6nrrF*+hVUJd{Swrg|Qu6$EjbVrL3Y>7y)VFsQOkcJ0encqAoc!+;YNy#X3VBU;q57Mt3Gf zSYwXT*gjkQs?9olCzrW*on|Jq#V?~`Bs{&Icf%&zub;|;yCND`ad3p()KVTpAOD9A z_^f6e6-{!BI_KQBDJqT)H2E>eFv9#<{d&3`nmDm0Dj+X-)>8Wqq@H;p>20F%a;a$G zp<&eX!{;pAp=9YD7dc!Ve#n#<1FYFmbLBR+pY)QwX*Ap!+)(Ijk#n9`nQjNx9z`aeJ}5TK#AM?J1u}yK^*97bk4jGo z^{^bo3eJ)JVjbJ5L8?J-gt%e6UY4$o^0fdLh}#Y3hV*|A9fO_!7V?E=q{&zMb+!qdq-*L#gN@nf}N7^$i{vqI(^i|HW)`FHwn$d^OhS4BR-W66HV7_ z1gOv{uivB!AyP0T8K|Q~bC+XC48jiN;23p$KN z_ikdJ5;Itvex!vVx;O!-0gB~WaZvNYX}C^0rz#%NiF+>H>+S;jlE*1T;PT>kzLPC0 z4!r?G%2~J5We9V;S?3(kSSqJ=nR7TE5YU59dUTH<^7Gfx=)F&c9%x^_AwdFv`<)w? zoj>`y>YSP-&9dFB6eZ|c>-m1D7lt7Cl6?swg{Uo-lg@G&8#RuUYIdN z&2}6h(aa$bPv3Ax!pfER{+i5jMeFa4T57U&sn)?a&=G_fNbW*`_>3XBy~u$L^Q!+Z z7x6sEs9TfqkwH%EI5#GP$WxCcb#n2>c*{aM5>`F*h^(=HS*A^EG&FhPk3H|shWSW< zp@m=0TgCqug>Wa2qSngGR7^dHD+iKu;X@{W8j0#TLDcupTEz(C(?`a!DQb1`vv~ex zMs|wJm0x@aT(^$av7F`K7TNXXqV#n%QYn;mbvvgmcN#n)(j1Wr7^oeZiZjOr_<=H| zX+qleRnio>d z&xfqT-p)BZ0Ild^DusXM#@S&a1ElCW|L<>b@=3WYyIotUdnasPC%gX94QVg0(jBa? zY$x=5dwOJcR5*)5bQ!+|sDq~943}UVtbWw2^5PKI{63#O2a97r?_&}VCq(dBVn>l( z&-3>QmF8d0PR;-P%5oXsVPlU1AB^f!vvnnDW~$E@b?IH-cZ6lsSvOC5-Ob1A4}Xq1 zgws}*dH~fYE^gzSrSl$ca;GeAPeoVZ>1zYiq2YfhYpikIP#eQcdjQXYq(jGg<^bMczsl4S#q@9OrZ?F zeyd+ED8qYbcdL~b95ewl-%~u`p94OjOp=Ws#q|Nq8<>@qN3^l#qNz^b-V_hR<>DC` zEEn*Uvd3MOnkWRNobtohGq4VV-D=S(r{I`6z;A!tZ1Tu&YQK@5Z*P;MviWI^1=<>S z^myOUf8YWTo)4uB;UH7Q+-#wq=;bu%_zHh#Mwrk4jG+~4I=2*34lVH|p_QE~zw_o0 zU6M2DL$WIZx2%V!!r`XRS=f`!_;1RiC6?ByX!=PpV6II^T@5l}dUvVpJ7ub0>drL% z784VSH6#)i$gT*w(c z00|ghnk)n`4QDXqg-DtTW#76Z&fpC7LCX&A$YWOm7_VO!=|rS9W}BTs(q2B8!k)2M z`xa%Y$Q|E?)Bpduvm^VyivRzmOv|KesCyG%f7)a?IV#OSJ@N>zwl`X+2mf!utR3dV zh=8x2C|0Jf{h!}v{hgCh<=`=&cc0q_Esv}Ys?7fW=60k9T|;<4lFa-&Cm5{g&&x8W zK&qA{KP?TPSq{dxxUD9gbw{DW^70aeswkZQj1jk{=m^QJ;S~;eQD|w!y595_S<#3rzfew za8|DKaK3IRzn`iUU;Ynk|NRtL=w$UzWU3lAKkCRblTytT142q(fpB51?4Q&Z7C?jq z`9*bTKh3EB|3aVK=T<$8H@dWMY!SPpczjOF|Hs1_gWGm96ipK7^K}7sy>&_H!9alR zS6=M;+Ys8WSgmaKas1+y1d6Bg@vvjG$*9lPs%r5_{Sc{Ccn;uneC9zhmy1Z@T1|PgJfnJcRZvZ3JN4MD}s#25)rXIYxvr++L+M_L;Chf zn?J;yy`alHDju4nMug)Vkm@gA**C_wTL={^1xlKpYxrSwlJuFrStLgFAHKwtglWgC zD`96bDAeMW6)`~CZq!`x)UED#^>i&eca0VzeRg`&`)toWB4bufAQAd#9P1mbj(js5 zBX9;yg>$+yu%c>&Bc>0AX`EBN{}7WdPC^6`NvFCx)H&j zW*f>9ZG}NzF*ZMk*H?$J5I(Kk(0E2Uim*v#+}E8uWP`b4bEYiPsgqCt`tB@dL^oR% z{Z?`OjAVB*f%as9+I(iS#+`E?7?Z{*DHTFtH+Cq`KFoENN)U#1N|(mp`Xb4$DJ>%A za&PxXp*ayK^-28jinD`&7%I`xS@t-1MUJwf)^TJNqv2CS4Ii7QlCE`Le+-Vo;O4#AU+Fq6z z?&R<%aZ{GDlbo;oM0$#DDm3R8G-j=B(75Wjw*X1`@NT>zj^5Y9mUUKlytG%k-bLN2 zT9Hs)CZG zLWrG_{gVC-YMplA??r=6;oPxjkn4N~8&On56a{7@>-+&D(bya1zUjDRqS{Rav!opf zLA?`?XW%UpbHz9AO0g+u$d!R$*$Q(79mMXcO)L$DX$a8%z#ud;jMLnLv%EQd03^Cm z*pd60`>uA(PXk-r`hW;goavS=cQXJcSta%4rgA~L z{RCc>&%SB#ansZtOvbXo%K(~U%-C$EGSPka_Pjip^EhSfKp3W5mj5JP_Nz84p z`7<9B(!2Z31c@bt;a;cb>h{8a3{N#*@T>4}i@d6X1cNm`9c-53_OLzt*&W@hU0LI| zGPW(gVw1NLO9*^F4mOyBSknl#B96qH{tftQ#h$hA)f&+xBTsVmuh9rpbj9@AXsZfA zbrZ94uCB42m^WD5#L6u1oZhc~09in$zkB|vmRitfpU2pMEj;{_8$KpomD1!cWLYB} zjfX?PI|F;ZSab>pb8>x^`5%(IaVAUtTejUt*@AhoC8b zmgObXjGj@3J7fANITSWZ3p<=rb(n*cxvF8>B7fyjweo}qOjQatwS4Lj^Ljr3!*a!a zJsViyO6-U*fM@3Oz=H~tB3bm*dj#N;puY+~jo^qcj46VICD~49bt+UcL@~#w_5pvxnK>#e#|Yn@y=q8!evVb4I-g(;V4Ctw-Bo zVA5O;n2E?Z4M?N6%JVhBN17*7vzgwurU-4s?|(CDe=69RA#QsSi95_+pL1udVE z9+-a7n(5ahO>y@ECJO7~0sEg3z7Oc!@PeIMd>$(kE;f=kYJ9Nv#nGgeL3-H9nw#ET zU&n`BF%obhoeI1tyYS8%C%w#?YodVL-8&XRSxp+LRfRJMpJ=h<)XFf&NxtIyMy@OY zCw^+K?brbp4(&?nTcpr?_x`^-c_IA&LboHHYo=G+0kdlhkkAsj=r_o#0BP``r_+aK zWew&(C~o(`BbKlvF6>|Oj>G*2KpJ6)8FlTMq*DfvjUFLfrs z?<5tjkRe+i*$apka$L}$94U~11<@I{m3>RNIW>xr!x7-cPZTd=lJWY_k7Sv%{5{No z{&n&G=%dD^8;eBmZ4H&Up*3c`@?WOpc!*3i47)Gm5-oxPKuDz0Gds~fB&YwL z0yLoSJ2e8pKW!8OvNIxYopR?F*Qc>;&p3{?`fGRe>du4Z9bT41s!!&yrI@Gb{uJOl zu3xR+xoXel$~XyoCNp1jBA+$k&YBWLnO5RYiXulH;_8f|^?nfVXf*Yxp|NJabxpN; z%fP(r({e5hV^}}{f~K9NLI~BfJOc~=@sq-!M7T&!j_}u%;BZV*%TR`h543H6zI}qs zMw$g<9m{rn%m$6)Ri*I_I54W!(yl>>N4Q^l8S)|$R39c^+XFFW4W8v@!p?i%LB$&g zlGx_TC;$G~UCjyuLwNBU{DA*Ph;X7kKjN2H%&JW8+Hg@O=5xBu6~n7APpT3Z0$FKs@s0=l^3 zel_$$N?h@oN5_4oXWWn#^s0Olj~l`A#TsA6<*1@j+0sk_D?ByGE7@OIg+k%dSTajV zacSKX$a*sgYonJaX$=p%UF#txY!5;A`QZ|6s_kz=(ePNV`N3ihX9>nDTPkanpLLQr zL2OCm3m}n4e5RJKr>_NNbTMueO;}j6EP5|F0)25>aF1V5~hQ2+n{KtY~DMHMV(0#X0~0{{R600GfzrBbf<_q*ryRh$X}uEYxN zD87|MePlFPPP`lRM+!XufPxqoAKT&KKKN?V9smFuQ30M|M0Wym000930L;oVmDw-; z)LoHtUQvQla)l{r%1+qJ_Q2~M>A@wx+$Ys_2~l1+dCq*RoYeu4ResH1uG_a9a`yI> z_IL(1kY7PD58)Ed!TzfUM+!Cw_mYtn2CYyNKJYti>DK?gj1yL0-$K?S5zs=rOEdb_ znG|riAY+$ov{s{BCfH@qvN6h>H8pSH0k-Vb)$y=BhYn~>5Em@bLX?Ah~xB1>Zpn5aVU|y~|WGWNoUl?E71>iQ18}jX7I}y#@ zGQ!^|?+u~2=>9oP92vJ&{SxjmNzrzeVIn%XDQj}xYsS6UBJA8u2}VBQN%Qi`FDkuU zCezvoObScO6;CWb3}+**pm{QvF$H~;t!A-B*L zr$D{7sZTr2uv-``C71nHGou582*|IG+jzaJ>Lwj|7jj(V)0peD(@tm5%O#NjqyhX~ zdPEJdpjRFqQ7i+?wM+!V)2d9E3V#*R>bnS zB?euX*2lu9s3pTDnu=(fMYEcvm3`d~N$t+TZ08QgF0t!d1w}KoM6O;pJPa~_zu7P043E!GnC(;nGeBatkegpO2B>j9I?-cTT&h^l~vZTI-E;7bzip4+hRBu*rKuIBAqPjw2filR{^luSL zOaQ|TP$4ht6Yu!l_f6G+r8{IEvk$n#r3)1Qo8@GI{0<#Y)fk;L1kS2gUS$G zHB zfhQ^oN#`lbH{37HQ+Jv>r#+5L>V<>_^4`jJikp2)=RNe(pG-LG7N#z$eV$=+JA02&^dxz}X7%DG zMbU<}b6ew(`8=8A?i7~Jmmuwh+fISGX&Nz*+*1V4S0=1b-*jE5o`+-Pew?4M|I_Wj zzC7k5@fy4*y>>=NuwQHgJ$q=*FFEJuDEBTrF~r|GZlFTRVCRi8n~kznp^*_{o!#*W z^si>cox76pkuS~URwKF1+eXC*d}E4UKGE%0!DuK1d+d+CSbc+`YHHsDdvC$a_QKL| z{McGC(Dq{_6_KkIT`kK|Vw8dbo> zcp>f$zrVqn8;=mRoqij``~`$-TRPaepK`2LrDn349ORpk>tjEx8)F$!%d}D=Fl|** zYyht9HSm#RX?$()|IvMVK`V5)V(=e#LosE2#mRDE zkIhK9YN}UdVURTUZ}`m-S-2ZQDBe!KE3j>e;zS5-j6-ez!Nc7fDbE=Pj3$I&bKyFN zl*@0Z2s5vfKKj@AX6Jd%Lg1(woT9d8i@&K=8Q@QBU^{Aqvn(FG{zB@eCvEv!knB> z+#j8!cH`T`#3JoS!O9AXIawaqTVZ4^f=5vdl`75TSjdZyj<*CXOse$r9e75U8V=Pi zvntm?ga8zZ7NAy*^0&c~T#?PR5Md$QY#`92{Q$AzC^gC5xkO;{o zcXh8u->wwAez@w1VKVM#ziq~ltikkLwNC;kIMSm4(;ZHv$_QTR>H-a?*CSZa*!%~& z9aVKJ@9@qCdIPU+>y?It3Wl)#ibH*(~-!Vm;+KXp%xxJ5r z3X0bKfr#f~>4i!LXNZ20n?HHZ6w+TmM{gU=Xf~^)Tokxw=RH2kpU&`@$nC#1_tIb57ziouba8zm-IhYQ6mKRB9s$fR0c2Le zTOxln2XB|NF1P&vhv{3cKO+1XALYyXfQg0;!D4t3)j0rx0@Dgouf2T~I}j zeUG`{?r{Ota^X4@hP}#cXAYSun zWX(nq!OZFgNj4l-QdVm!W>;lpuGv#l02pH~eg&^e5D6o+9um7>E41LNvRDH@8{o!% z7Zc&&9~b_n?U&@1@LaavD>VjBZttjTrN7cqU=E_kBpifT79H>mSi&0u2d45$+! z-2KI+8K#>&31Si3AJGhNEH~gW2aJ9R?%v4IuMpkb5|_m*I0Zh0M0G7hw{dJUK8bY*-MDeWctrJZ0ENXOZztkRcOXAn4ID0s^Me9R1Baa9(wvnZ&`$ z4DYKZL*Qv*oqbt$;WM-De&#CW%-gSK1onRA4PnwVIXa(#(Rg;iXH16X82jIp822DA z^gonxZ`ws_7tYpx8bQ?$okE9tI`nT7zyU7+x)_9oH?!_MI5HR)EpblB?3e z&h6UU?+OzAgo>pn`6oVq|My#^bLZMJumT`-YL)HuyLnI4bP9*_4Er5f#_um{WNSxP z$cS~ZSH|M_u@MJ;*4EYjxoy_p%d?reKCdJ^y z3iV<_(3CX)9qORvv3!5tzbz)twQ)64_`iJM;80QU_yi$lE%mU?nbh5}#P>&xgQpo0 z)yKy(F|7tcj|X@E;^xmq&3%}63aQBF>V8~vAUjxS@zJs8*!HulYK6U!xQHOU@nDg$ z3n#tvX%chNo!_mRha^Z?J1vDXj$M9TnlD4TR;#qE`b3KrrQru|!d>bD`U~XI#PNHK z4{bBa(j8*L@gh`w+J-9>ISkJXxClEj9mkImUe%Yq5^ri$ptZO~JR-tI#5CE2IoBB- zRI9#++JYco4r>+T=>@;zn4A=HD|>#tX^vkDG$$A-Q10Tjh4Vm6l#>mDi;-8VgArJJ zibu;Af}-NUzb|xr1JFF3r>KxYdShn!f($HnRW$Pq-)9O2k$F4FIbA1JTx+@KbzXU# z_$i?8?_L?ATilNn%eg#iVZHBm&KK)Qd2L$eKFaM4N9GK87Z_%Rv8%UeVP zDjoDYsY+l<>QT9ayg{-aE@}&rYK8UunLU6VBtM1FouFdwy*Nn@X*>t)*gI5tV&ms# zl478RsS%G<4STXFdU?0}R)2Qkfss-}GkGP7N{&H8u^%3tKr~0b0{HtjG{Pzf66n$A z#@8-N7&1HY8$W{Zh=nB_LOs}}hQ}#?)TRr+qCqn&L(cGjPn|qQ`Xo@bA__W4q;JHK zeg7<~xZVeTIFl>B;wtwWX&PA`?F;Lz{p~_E8#LV-teDzkcaxvIDc)A5m4WI?934BI zyFO&NGm*tfYz2d*nC7=qRlW<3U^^Fo_nOORlf{?2Dp1_kVj1k7W^J|SC!GO2UhN#p zsdZCqXf=X!Di;j^y5dM6lX&?uUeCqM?-SUT73y&e;Nqy3P_;Z%)b7#d>G2Git zO*xESm@p-XfdC~VzRy*Z2mgD5z)bCLx637WMS!7SlVG7;faE=b; z4P2=wIaluCx|+TM=i&33+1s~hle_{+tCSRG`{xuPeo--VRKB~tj4<9@O74(G-gjRe z>_!$#XSnEx`7ShW&=A(H?OQ+mu+-TVBylavvB79YD5ZX<1VesUD*1)qq{-pJ9nIl| zx>%dl8tMiaiZvt=6XQFA49tY2<9EySmFV5a6wtwj{VTsL@&YZNJNf_bG!dJS$*->a z3ig<@v1hQ-rBI%p5_))}yAwYKz$6zO!(-@Q*TSqz;E9+q-z0rkh!P+-Z{UD3wlins zlWG3+w@FwzH!>!ys4mxD(n%P<)B}EiYgujz`9z>pWJ_ncW{b7MA+R|AK884u z0-OVOCI{mQO8&N9ju2V9@nagK%HMOcCPt^7=<=U@ zVXB&P_`<1vcKIM?sPSxvdSM&(kuA&NE0MaCWp33RyiJqNf`6L)$&yu5%D1sNiHJ1} z^>$vHLtOmj_M2{24e5GlrVdCQ!LC@og^N|5S8+lu)tqyN1sEotPd$dxz%BH ze?bbyd+V*=?rzl$gw0Pit5>}^^4%-=Ci|-tBaT`E-g$Nl@3;s6D(J?;0e=b!mkDp& zQ{`+WIph7%eu2*b!p-WncC&l6ZB4DO0mF{mG}1PxgsoTFujSJdj7lBhvn_f!4ea?W z#?+hKbPo-f*b;x)L570=_>Ge4#{sMp=RG6d?>n5shFS02_u?C46 zAXEB1LUePw^m!yf-7@?#?n-QJC(=Pis0jBEHvJ{v2$Uu0WL}x6=8>zg$ncl{;K$0Z zv+Rk621sL(l8T!*4i;L9G8pepDc8*%c)3+nvK>s(xJ^$-WN3Yl0?DcZC$IWuZJ2|l zx*9k(ZtE5Y%f161p=gVL87p_RW*J3sI0vf>tZ7Up9_PjkRIDsLL;Ph{Hib=68Z^WM zYp6A09ZW>jU&coENmjU%Me}VSQ~GpXpOEE`2n2A1=7zD^cE1>FC1fSzAPm9k|MSM{HCH9Q|J;p}ng|PMcV?Y`&z9cLAsZ>E zXI$7L_IXfD5ZDO!?sbo#nz@NX+e*MFp)9FntgAUe7PDGa!k-jqsXl|oUPvGg1R7zg zzU4zE7-Bc~!(@JHfvY@!Cv`IXy=hEfZI*Tm+9FDI;MfnJ3>WEEjciq@`HEFGa}JDJ z2-zXhVQHF4eSJs5unGNH`fi1hOXKDZ0tI$`F@kbV@HNa69 zgfik(Ns^q3M2iIg1`k};-5X?kK1>7tcW$G5O`O36@^r?*5A@)7_~w)p(V*x~;B*Fj z744@a-<dj*Iz5p_*{W&12Ed zHk6(bNtN*B0>1d0Gw+HB7}8ukZ^11)_`Js`^K3Io=qy%wSV7dk_T!4CTsr@oF1%_Z zXykP6e=D#fm;N12z7j4gtzOKno8(r-U#iYThVTL(mfNpK<&eCTLm;zl-xfB zuf&nO$y$xGnk{vsaKK#I&%a(k+) zwn6NY(=Uqc6_KRb7)&YzDfkUazb84JU^W|WzGx82T{B1$*aCO1+=_a$Bb`yn5FNOM zj=M;1m~BVd=m=d$wvSk+=D(wn zYeCae(cTs3W-fdSo3WI?nmVREh-l-rK}h=Tm38~&RlGKCHV}AZ@bNb|O?@MiwRLQB zyodnS7HWTN+<{OevC|X*azk0yZ|B;W|DqtT4iONSkP*|Lcj?lP8NHcoP@gbt%G4cB zH;!c-%O)euHP^~Cv0wcDeg&_C&~KHcvhsH_V+gBW-ct zt+lfh8T|0x2tFV*I=9{9NSrp)p?7E|T2EvjPUI2!(he6eF1P+F2+A;SEkG!w` zyZ4=Hpq@WoSlTd;U*5q5=ptJ$R!ZJbtXf9u(=DB+uc!S+xLCQ5aNQ1(bbo&zr+Ltj zzXJ!-ast@xJ+~)!U97_sDYrPt5IOl~BDl(c+ZYr77P?-~{xa={;ywJ%Lk{5#Jv%zq zGO4oNp6sVlHnloesW8CB3tuo76yO9XmGa}YQ@(LN=~2O^U))tSok*SD4H0oKr#tpq z|E;TYMI4;^0M_>|9Sm*Il%dH8voC3C|w0>5gV3~$quM6gFaR*q=^4{z(#wyws}tTqj@Q8RtLQ!UWklO zj(1v$85GI!^aj)7;TdD4Jxg;8y*bOfqo0#^Tlv6ak7*J>3aPOJFX!ns)5+GnwJqZ52A?i&Lzo-XIn~pkKxSa8rwYsft@n+wSG8T_Atc(KallwK_Kn zwpglmh5?OfOdIs20~03&pCLV&O|R))|46Ntwt{%ljXWYwEU{4;izX9tCHzC#uj#NZ z_fR#R_Dw=GoM49*oI|R(ikfuTqOVDvJIrgzvb#G zC`#Bh{)_xuasztG5b(H?^Y~GLKhlAj;rfuYRbu^6WT19Ie$uThC zFCJH&)N$p!AX6LMlBYZgtryFH9u;nQGVICbPmmsVT0CWn{*wrUdysPGm*TeEw?y1Q z@Oz=?fp+9ei?qAj>0z8DxGEJ(6lSF;Hwq=z5?I+ap?SBiv)qtKO@zZd`nx_3i$Z+c z9Ob`nGPp)qr}pL~HBgvi9~$tt|M8dhz5_q*Z`DSOj+z?&9hFOzRSzZ(BoV;x>~= zHloqaZNO~&IJ3EWmpnhMCH7f-IDu8pVYcN+Szm_{)yF$&=pvHN4}~U?d=AVED-Rg% z-P4Bi40Fhdlyr_H`vYCQb#GaKyCPzYif1_EZ$nHSQL{6G2J%g&h3tqgdse)YNei4P z@Wv{uAfE`G0oureKb1!}Kl*$5{SGi#ug7mDU0D#f-teqV?@+R7&PFv7PdKKU3Tu1*l)iNAR(O*QC)kNdbpsTLVx5qFI04=Td zUpUpJp8CjC(Pu@@P2M3g$1FcCk+WKR>zANR#mXe0dc_^S8ec-Z$N5)-r*^@)TeA!$ zN6rR~v3Tj|vEbe3>BDP2Tz=au{>?ed&mYzD%fho+`sBpPnVf6+1OCH943KVz0n3y( zot~l5{jO&QPFx)=br!jnsitG?*Q-?~(+7-=Y|2BxcDK-#j6fQoI4uD%T(UCbc zF)@_cDXFTCw{ec_mXDm{{5Vdxr5pYPQ?3EY(S%ogyQ><6^q=-!esl@GA*`#{_Wpnt z_kenr52b<5>`0a_PCO#aUG1e#pYhbK68ZIli}Jt}Q9VIlOPCZtkgzi}{NN2%E0COu z+TgctqOzg?@p%6%Y)R)Q?I%%iq`H_Zr`%Z3vcjJ=GV%yD-8NS*Hhw8*UtnBrUsVnw z1RCUTk?rLVbSH?J=#Vi@-MWKRPiWc1r=g=ZxN3(F0*}6X_52kcw%;Y8 zTTiQK-cHNxOiByr0pl=Y_US+OoRw^lEAdOjXY`&EH#yGDz?F55#q;GZgd_>;b8PTd zgYc6b8U%p__tLrHNs%YzQ!V~jZKnLodL&YhiN@re2>BA5e=i=5#44Ut@+5>8c%Rri zDdW|gOE?^OTE1i|N2I)wvu0MbO)cT4%=T}~L>M@kOLF-^B>bV|SXx__E$;c29#`A5 zQ4JTiVL*Sn6C$)Kikh)YY(M2Y68wGZi9G`DLN~J0x`1iR z@sQ;T_3(cc9SfJmlOyw#h-FND)lsv)0z^x{+hL`nAD>{++ElnVQ->eyIJ(b9Uzut6 zm|$9aI~k=7%mbqgynYnm9xKW&bg8ibP!;#AGple29OU#VlJGaF-(4(UV{;`1TG;O3 zfG)@Qp|3tvSg@(3v|%BJpb51)O7%fF!K)32Y>~0(Fjv&}zBmi{&|ZqF%TC2coBc~9 zMOUt{n*W0Yk9Bz(WCQ=C@ol3`G%g@%??v$v2)UowyZ--{E)1IFvco*C0Xz1C!UUvt zlbzvnW{SY3Mkum#PxblFj*x*;-8;(e4|$erg&KBQF(r_h{W&xwr{&9Uu4t9NDp3W6 z1T(I`*BW7%>jO*Z;fSC#Z@lTgpz6^4YM+oag~7+j+AalF<%CH|Y0U9b+gFjm!ss&> z&?E~8s*~2uWzD?4(f+oKuiUY>spoXRW&VG+!;go*vC|~0R-XxgWHDPf7x^64{`>8x zg+*U18|Y{2ZJ+yK>i5voIJ$Xp8UDH>Bi<(oz{KJf4B~$kGI)~@nUY2dfO?R2n(_I^ zX#HT!`H20wUMT+Bic1{@;2!g9^%BMnV>`D~)&fT;cZW{_{>o#ch!*v+0E@p`3Jmj| zg&wX?U^pQJAfa{XorZXrTF<%$9a`=cp0^WJ9GgoenIHrBFS)xwL7v&vm|=F^=!15# z(R-{NTi32^$GU~vdvzxV_I+10VZ%1md(m*kvQR(+%rv+=_{`yR+}rqG_`Ka-m~38P z?NT>nZ=#0?nsBp5{|~s22t}Cmb!24!73+%RF_61&A9fx`MkRniF8jn>@Y8keI70&B z8w1$Rr^!A?`5~yow~u1h*kl_62BQd5_sTk30|V*9O87$QL46nk4yH#v)8})DCRF&_ zpMB#Fg!uj#ePf zav`N9%DWq^9N6dASLTIMIExHmLSu7mSB@^w6#yPvx)skVqyX62y>Hpvd*oMx2+bV3 z=7OT-ITkDzXRaSu%ZcyC6L!$hEN}6qyNW*66n?n~R;**#n($t?@*EOc>4+-^Lb>WN^0A#_nvV`Kc5EBq;WVcPmpTO zhE;slTEZl!#dxsOHPGU0g{^gt^dg|e;km={oJ8$F3Anw=^l@C#%*#PB7myc-cDTK^ zU$->Y9a4g4+#I7@2!T=T6NC?xgOvP&QwESPyy(yp$IB=9=B2y)*d4!X6`k`U)@oE% z0+wYn2gLmGBuN`4QVsG;uD*$A;I;hXlJ}AVqD$xW!p#9jyqM@JPdC6%GE<9rK45#P zol@VNPzIrzOp+aFT;ZtB&wN^H3XmY=7s?#ZL6C29#+KGqJmo6@d?%LPVP;K7YNCU4 zE_EQQq`n19N^9elfs9o}>-Pi`gEQV9fAeVc(Y?2z`FRNlY5H7l>hScps9Fw=9Z^Nk zE=GteMO%(|RBgzH6^r1yo3$RjYJY;T(Lt95H9tNu@Z&O}VLvkXDQ~6ZVz?MDuSmlr z?FwtiYVNekpVD_^fD_mk2M3`5SaTG2xLB+lU-%4pAj)zgE@o;O<} zWEM2M0sWdv*c3V}i>tp}>*)GprM~@NVjMHDgLGq117c{*ppz_Druq6}8hl5_L(rx62Kv&7Zb!&?rtx)cIh>$MX3z1|hwc-$$ z$ZE$+Zd{VD9SYZJOSh$4be^@$lKtJx!E>D&aYIY-k(4bDG_|Wmt3wjIst&YavrpSkPC*@run7~g(ki%`pf@&Sb3iII{by4XR zIv!uIPvH|r>3(q!1-(6d$jAfbd;JFpC#j-)y|8d?GtUh%mN1u>ja{CBsWPM%ud5@r zj}T7ncqVsj%<$fuB2(Ku4>|Xmx4@J6V~X>-$xU(!xznozbBxzdTCC-zQl9MnQrk>> zD^M0A=RWDGtWgJUI{xjTh56ZyhMxnX#Vo34&(=!5TouaULv6Z4H`LrjB!A5zw9b)* zlTlAzrD52s8)c&j$1_xFbeDRE@$JbS^OFqiHC=}HRR zF;1c~G5t$-pFb2H39Dl+h*HdY!lf^tl^Cj^TT^`+_DbBwgW2LVf7mJDk6{qEw@JD{ zTey;d#EqYEkCmu4->yYsDz}Ccs00&f@C=PeXxHxW5m(x#GsJ0(#o^2$>`o1HM)S*Q z9&7J7!aPxzY;afJDtzeS%cxk+tZ5C=e6od8rnA*-t)UaHi7JN1(6ySEz42}7RT1kM z9C+4IWOxEhz0INI_~dB}Ql;tE=~u)?b1c$H%uUG&1=o}@yI z1=p%!kucTk(-ho*+&68uOBLS?IE=YhjSwaW(6~sM0HLB9n{(DMP=Yp=*;opFI!~!= zRMRJ9zfO8R$JdJ30-A0fY^l6tEn%K#gs?v9%&F9OkY`1z{#NeCE^(CFB-!KkUUm<# zY$8+*a8aCz08LCIChR;o65tAjCEFK)w=QA|4Cr!3MfqZa%2?)H&fGnEI1_g(nH z%YBko?`?SgQd8|-H$;l%cDn63_6nQ!`Ol1@l|Cl$O@*mU3P^M*vZy+{c0AMCGv*mG zR0h%RGn0n1nVw33mS#RuP4Qs0UXwajO1o_8-X(&PmQ8E$S_8n&glpPUk-Oqt@jvYK zMTL(q(MvSTs)s7ApF14*JH3f))N`mhl5XRqD17l!%v`{rkl+Rb)W91x#)Hn-U>Z>kirY!c^*v4{_3S6Zs%;&j(u`{{W^%4i5^C%p-f zqrpuQt$~B29Sx*9b?3|BjFqv?7WOCnINbqn*=M>OuZOYEsjD|(2sZ%d=$0C879!Z} z0F`Ncw`(6eN;6I5d*V+Q*n4a(lq>9=;STq+TuaW>QB zRF(Rr?RAMd;Pw=Ai1~z~>c)~vSk`o373Vd}aw>1Hb#n(Auro#NHSh%>#Gss~-ID^{ zil5`=?k2vj*#irZd-CCAN=zN@c01zdj@>dSVZ7O@xQW6i8_NaO4%@MPf#w7>W$GQjfwScJsZ zP}VYr%1+nqp`vWd{`896tG6>Y!-^7%KjeiA=0VA|T4fvc8G)iw5W>Yg_;lt@o)X4P zZ@qnmdM@Yy}sGZZ025i6&i262!85r;gG6JOS=Om#QQBmzDs&vm$mGhR0`A2(tJZ zYBwD}|9h7f{|#YOO3rp&Np7nmR;qAYla0ieTH+A@h!!SoczzUN#pf2*R)4gVW$42` zyu?Zy0XyrF@Xc2IT|0}&4F*q*IjjI$aD_p!#0cB2Wev>?nF~i8mE6479pMni0A@9X2bP*989mt z8e~*|2K6044|$*dCWzWrjvG>Lc^fXIsm~pjJrKk?juP3 z+O~pw)r7>ewdDyu>HH~3nS)KOd16~&c!z6BC{m<|GDkSArEey+zXl2Vzfp<{j}on( zK}G+;)DF3g;kaC8iM-e2wm(we;iq~Z04VK+ErMMc{NxrXav@4(6@T2+U=BNaXJ4aM>AuYq*9l)v4+y~^_-FTH;VFhAh4_NONHw9F3ol> z)IOd%BF9`$_(-~zk4&4o_T^%JPCUUGwb~f~NOagsyM1pKb?^Xj9c~%+XbX`2%oj>`lvwAU$s24vP29)#R%8p)3Ut<_qlZNW4YiZ$Gvv$WSAlqqe3h?D+A z9uv|iA-)UXe|Vv-tV-l z;qL5^;$Ov7gPJ({M7^Eom1XJ6Ji+23hhS2JIpK#Flsc6}E%^wJst4=_dlOqTi;oM; zJRybQgypK6wx!lsd`{PJ!%kzFYH`NJ5%(4~jQJR^Isd!eu=xfmtj|TOB};OZ05UtF z0(qvIgUkoOUAcc~I0s;g0EfPVlQ+EdVstww$WF7e+D zsb3Np*NOAz*`Iy(DvsW&?Z(V)6Y7$>3IA3M94f(DFP8WuC}&WUu{x#QBVI z%(ekGm`=tc0d30^8lCZzC6ebl zktLiqeHd?N6%2L*13Q~!Hr7UH=?Eq=B)n2|XM93s4>q^zoKv^3k*6%q@-Ky(97 zsSGBx*#X$S0WK^(&wB3mumeJNSs4mR1tOS4jaMl7^wCa1 zTqG!UbIqi(N$LCNSxJ@i?S9Kfpr>Ug9F;;-MGl@tZls811PNc#w`wv9>;z>PuCS}4 z65WPS5%8N04ekfKqLW|!kT`4f#SIpURD=c382W1iH>xEwwpGw;b}+vW#oDa&T`BFN z;B|@P8A^D51iVzF0f_-)7(lZSidgJBP;dkySf;NM_B42DE!DvfzTf|@DoSPN7?PYx zxNox@Weda|y*)a0o;%LXI`{am`(+Ct-l_ZsdWcgYZi&6b(LS&El&dN>LV?WJM80r8 z#7U4YJu#5#c)4)YNl~ed>pkoI2bOx1;N!jHz$V7nqY~Cp8%q zpSc)m)LGmM!#m&v9TTUEF$vL5%6h(qX29dA55Rj`Oql-_FFRw?DAw;0@$(Dik2|kF z8E#zM1?iw>qA6(}1F*a@)aT&+yDaJF!Yu0i5Sy^ZSK7DnmjsOg&!k%$(9j4I1OUid zWrT;%lpS;A9Vi)#!Y&^exrbW3ooVKQX*ax`JQuZtD&Q?!qZ6);cHS~nNrk!~YCTyyoY&z6rM;*ESJ7E!6vv~g)R^EYjwmr>ql#M z5ZX3Ha_I%=o@@W9q`y#;ME&O;O%LYsb2TwBwYpw&_A$;QY|Y|_PCnx8m2WWpAKrJ+ zIp)O|N&QOlWR^31!gwr&EDFQrc{EKzQdbnt2*VToJ@?$O*%k{CT?2V&C2e#|n&zM5 zB>0)(;F5;i9fr0tuIEUzyIP8D?t0HU_D*I{kct@ho94$Eo^zI4px-aB8n8wh*`*!1 zdrsJZ_O`OX#5+Y6Dj{4uu_oPPh~2!kNw2X2E3tVqOGl7Y8Z@kLVR~O0CQ;FB8P=C1 z+7a~wet&X5PHGh>9l3vJIRAjXT~~g!wQy7o9a$Mx7>{(?aHbQxU<8W4^E&9Z{(sT{!U)e%A`*$(}jt>=L(6PyX0 z6NkJNAauFNVJ9<(F21@-*MkdwWrGDSs#A14ujG4gfjPpAr>4SCj?jIzqwN zay>g#sLzwrB1GzQ2q+_q+`W+6+D&}MxV(%^Q!xc$dQH6$zgEU{cvrR^$#|k|D&_Ur z%jd=DjMS04a7MVpZU{?kY&#bk^$cI@hEogK?;l^mbVR|Ws9o1sZ&atOn}Cjg{#edg z@EuTCt@ypL_POF_a44Ori^7cAuLTq6MmnJtI65D?Tn7L1UqQ)o^J;tI)f(~2(q=@< zgt-v)jFK!%<{Qqd$0a<`>nyB{S{l&Ouc zB9Jp+{jsbAAvq9n4;tkGu$*aF({l!rSQ&`zz1Np|tBKQ%ZJ^=b%=@#H*RbPG2aYJ4 z6+6j}P9@kVbt_Z2mD!sH922IG;GM*B;AT19-XxqG-eg{RUBBJG6Fzm1y(<{gA8LL%IkDvuLVHTYeS@1Fv$W z%y{UX_>gDzNE?|KU%}flarL4JzKDSy;XBSj+l6)B7A&L)GEzLrQrui)ICyaz+#SF3Y zIPDsg1>?#Ag}Po)T-4SpNE2lRI?;NDDh_6U67K~#~BNs-%27S>csf)G)J_-;npb0p7 zHvaRZufeqz^T7GROpM9>`aBw?q^P7qct(#F5_8i6Z>8-GHqq`Vne*#bBgznnhu*=L zT`i`^VnxWXp+<&q<-QB0_31tY52cU)&uh3wkhxaNC@f6dK1R*tT0}?M+`L84NV_c% z3L+u;lc6|Qzi&Q~9Dx5ynp0V1Fxzq`e;a3Fv{9?;0I*@Ty8mS@@srD%*#{X_E}%Sx z*TWYygw2Bt?oi%%(Kl>Y)*QXg;dWsFul%I~*<$OMN8B5|K)6LLwXzPRC!WQc`w2iP z)_XLl4XpBncqjQ$YnTg{^(3rTtTC+-bCzC+)zY_-&Uzo?c^Dl-WfF$Q0R)q8k>-MB zG`K?-Q_E%(VTz*^>7{=0WeuL8B7EI#)s=LzC0fexc9({SQ*I!X;F`!IrN-AA#6^u> zB7}iMZNcHhJ{-WJx@Tx(OLv_x7qPu^o4=X%VVf+yK}Z*^d^|^mz-;DXO3rI+B(_DS z&@wKK{s9aO)lP&%s}Qax{Be68W2Z}Ig#<49t^5!i?eB(c_LV2M(2l?2o~vwG#uzPP zGfk%eBv^n&%#I|3${TUdeV!y>M2H`dpLdHz)<81;9vRN$7e$c4_4}~7L*m7|VvkBt zJu(?efS$D`UoC=}P>C(=smrRbuO0rdeN5+y&@FE}ubAqHaHGNYlmjn^$M?J$@c#nY zHEz=W`gQeS)LcWz&H)O|;=L0cFmatw@5qxR-+|j9ccWPPMT%`}@%w)#jnoX=Ju4}g z(T(fGLvsH6_W_!hM6r^!o2GBJGK;IhDAtc0m!q?@hq$@STa&|3QyV=cXvH9~@%994 zS)eEemQ&y2KTk3&R?Vxs+(Nd{1tQw&dly&zv?7XsXgU~eT<1PwDYH_{plR30Fe`7| zZB^j*!ZyhRpG>SJczvtS8pX9%hEFjyWzS7SF>q#CMa9DIdX?J)6TWnv{EMg0Z>ee< z|6!~q18gb()Rm>*F@wRTnV*9^m61O&*=FwF24!azzVJl2>+`E^EGg0v{X7h^ETkcA zOHYMTvpE0hU51bw;3pcofU}JoQPw*#$n%UxA^`c5`!7OFdSe=!6q$L%V@ei*`(pAM zO(dW50PLDIg2~4RJL@FW8H%r>O4mZlhGYr#DEm=FV*WG>c`CYKK>3>q`i0VH75i4= zo;4QgD1_xsy|e?;)(6j>BoVUtnVIpWmFE9ZKsykpntV}fJI{{q(175)WE za|dv58A4XepBda}MWvDOI$#19B8DW6r<<0ZDN3ek8jLyz6x!u7xF7G*VLT+LQ(Rz{ z(lX6o5@A0ok3B|+9hf>3YNx#2cWyWl^d82b5tQo0AgN+-}C?28fVeD?_=L0 zQE92AZ5+yugV-rZWwTQ)T|Grp4kS zNZZC9CC4>!rfKf@MJkAh18KPO@1+!k&Qr;_09HHkuI4O9t!7usTr@V3G+(^6l44Ur z?DE~WuI-J)+;SVKo-!q03nYjOd6!!eWuDun%-$Ajgdz>Q1 zO1Gm#JriBq89;{g?3?+kb<~7OVrtUyb{8*5(}*DSWw-=P;LG#Z%zdS%K-_sclKVpQ z*DIt%;*81J&^pjvvKG1gnYj~6@T1o7NkA%>_m}``R89IJkcr@3bwV-V9nefc`7OUf z7-70JGd$WP(pkP>J`O@$gHxocAH|I6Sksbe@(K}-`fL|f#|PL9#qrQ!_k*$RF%^N@h?n0#(T_ zC2t!3_cjK9k9>s8?gudPSrWQzfZ?VqVA3t?vE7BN`N}e~MFwuQWY{}?2q1%X#?W!DnqbCd4B&0h*>_J|1~b@%w2%nOn$g1JvM$fA7z;=qEvQc@ElO8sxqO+ppqzI8T}})I{cxrN*bld-QPLRt>mZki6Jtd0FeTU2gBU4mb=* z%>(z-UK<=HEDn$({^Qab0zR^R#9sQRm047}ksnb7Uzm7+Qo3s6xBt0S>|eEg^*shC zw+=g(S&1csX&ubuuL0fM@V*;@EYshP|C`zm5vzHlFN6hb0000ML7s+16)Z;p35yg5 zdH?_e00093SHS=P01*M6r9@`{3p2TZ00093013DN000;Po~J}t00#r;U;wGgf!F{5 z0{{R60Q7+X02LTPnyfTTe*geI`uD%jQse~m>tK6XQ31Yqla6`YAvH^D$|k!=s(!q! zeY3yIKLU(wG2e@F@^#z52L~+B#{gW7{ZJ%!aR6A_mP(?Pwq^ck>88op;qF;6)u}lW z8Zt0~luXxq2wXN89PPPXEvHDFIVA?!kdlXpb3?NubCbkRLf?;mvde_OhMO1&Oh>ud z3ynxFrW`Bz0bX;LjUGRe@UsoZ!5TlqOo#AQ7!O&34A5kj+-?18pGND(CFNy$gU!Z3CE{Z+zr+OliNZR-zlf`+8gtIi^gV5uk9YQ}b`9Hbg)xH9rEe_`)?H0x)O zYH+rg3|I_$DPl984m7(0v6eO%EjV%?*0Y~aQa(@UhQD4jqcxfj>$bUv#pvBuY_hX$ zXMsy|S+QVQ2VQ!R+?rxnjTp9SuS=0@3cET3J@O~o%3aR;6U%BZuxAltJoDPbeoSCp zs~)L;ch?A7E7-G0eXMcM%0Zl`Hm*HgSc`c+i_zZ=&UpP0(}aWekA>4?nv)g5VHJs* z$I0}{VP2r}OBgM(U!QN`e)qN*edN3-KM*eQ3xujDW1I_c$C zL=FHZV3Ge_rt3r6KT+SGc2X#Wuk_i6bXJaSH%y3**74ZW<(JbtpZL>z2*~g@O|4K= zo$Yg~CtUAz&q&2-E30<2waUtxYNrdH4uD)QFPmrmS#sBeJu&=8jrPe4=&?NP)s{Q* zS1oI9Ni9jo)SI$H@-XO8=HazmkA12H@M3aYhC~1oH`=4J{~9~jH3`{n9~3{~hy($Y z8J-in%sld44h0PCn1a#JvVv-sAYx3f^_*8>kCaDhOq<0qA3QU2qQ6<(j{A?LB+iij8z@$N6P;I=@&{y(>%yq_tb&j|NH$ zA1tT8??5bhW}J?Ekk=dGvU9x2yW0a=X`jh3Ld3DewgFhxd!0RW!xG4%Z!_%>>p$|I zxyId6)dpB2KX~s(q`t!DHjqe4U{A)83A~ zF{RJ866jp-&vN3Ewmm&#nFJ}UL_@^UrNn81DwP`R6sz#|ETd;bFS@c)ofqr!IxiSz zWIzc%jtXH2*xUPy5XNi=kp#m)SC})$k~ct6FZj=yBXwJrwRlJJgckD~0OlEB*@EVK z(4s{?6h!_>;b%M*DSr|Xrp4e~SWOiw0YG?fzqr#`35j58PN0@d<7`HOy3!!-PKrJ- zbDTQwhx=m8%!@g_mLWfZoBTN~!&WbT={blnv{wI6ZxQz>WKNp*AMJ2n_L}3bH8ywg z)xURauT_|^b8d1#;gMF3e3PtT$^5pXb#e9ewm)E>boO(07qh$%d!!LusOwu$6b_AjJ!H33%6qy*8iTc5!SA=T}_>^5P>`xJ7x<+ zkhzwL`)o{8ko8*PkUAw)RsLH{!Xn`DLWu++Ct@&3(p7?ayDdyd%$Y5|qGGZsLn3>p z^S?p|h_zHx_<=e^RD6c#o&%j5v<#kP9rgF(iwD<_66h}~q-PB}4N4Dlteb?_nNmVQ zT(cId7ty~bJy_I37Ps^$G>XHl0s)nDWgdaNzG(jbbqsPXpzsqEPy4rWd?%Y03S_O~O*&9t5GMBR*=X1W*VE%_7Hl&Uj#Vb^i&OXl(?15YyF=TxPBbfK(Ce4(_&{vbt?PR}ej>bm%hS4cse64njA z18HLUP?^>*U9q0ZRG2f6IN?9=2@X?6ku)(=r>VkIfXI4{o+EJ zS70d5G3)qw_I{jYBD2iKJ)bl!_M^#@hg2J*OmI)BS`|8>v0NyFDp>QEFj+h1R5n4_ z*VC&vDgBvuQs`Wg8h?O!BZ(Pu-wp;!*@mw}R9jmBkhD2d+gl~@P}2^7`Mx)5AN**p z3sc5&9rvE+aH!iB?jeoEa!<>}l)@>N6iOHq-w|rHH5E$bJuA?Eg`N%+9y9=J4Tf}0 z`^4=A$SuTnh=V>c6j1*)MecV1o@7cTuBB z|7ib@sH(RA@{FTW5I5+=1%wM~RnE-*?)()U0gy9TClY_{O5d}2;R(|nz0}I5GU@{s z#bnXZhDM2NEW0T>2C)+H$cGlKhkCE&ML-~TzasQ)CvGNspT3;@55_bC8<=fCod&W; z0F8_F5)k|O{P$IN{97RUFf4vMcqofQIs*c=SqXS~=+NH{IxDI;SjOXr^bN>}X~GGR ze|Iat$`%Rz%h|1^QwKLI$iu#FT}K_3r`wgzX@G1dlIcYrj%nENS)J#t=z?KA$OKh( z^9Y{87o)(y(^enhrRKvxbS6YvaY4B{cuy^Ohk|}8`SgmtcXC;%No}+;LRC|ow}*qLBFvfYWq>T_ z>+bNMVH*gp!$UD`SN<|NN-L8FbF-^G=m(ObzMEvZvGUpEDq>}t(H2>{kj;vFOp&k? zMb%-Lm|UR3D%cbgl3YxdvmI(JPNW3T$Cy|4=U*)H)z8;-xim*~i?mrqAtjiy{xZ~z zk5X3>Y4DvS5U8bVPH{ad?60;L#B z8-0OBx*h>n-sl|%-SzOlS`l|@p-4Hc2V9|P^Oq@Y{5OzWY(P#$0$7aP4xYJnzK{QL z=UxQ0x%K$sfP`6-GCmmTm=~URaPXTI|OQ6*9Xwdl;kMv64`kHL4|y z)*=SaP@}FCgllYFC-e>XHw61r7(D{GFk?8fQ}JdN>vqxpghMp zjQeLU4vz+~duhLnTVZXRdc-0UdOcTF8+IHY9GD5w;r8!(gQ?yq>a38;1>i$K#1mz7 zP&;Q3DG{;=Hj;-bDXnk(EY@%UpZp>@+Hkr7xla1S5nTx|v0C&?f*xrQ+++Il1%Lpv z{?`r-U|LrK0fvl3*xhx!Gbnav1k<-gMXqJ15x8wr*7)5Fg5(4l&)_Q6n(|=Lhc&k1 z?#J~tBGJcRKIhkO2*yZA^=lLHK`N%gXxJalx-6iZG6h$aFhRlI z%*Ml@y3ZgdYFD@49g{2I$EPfXn?^1qQ8x0dSZh?CG_y4!=W2r{nh=ce^>ZE)9pgmy zm5rUmMG9tTr&U8VUDV*JQ$Ur5Rz0-xIri9ad@>Lo+o++9C6`X7%wwjxnO-wliG!f> zpG$*p8-ep!V!Wfa7Ax8kOW1i{i=PGMxo+zG6?shkc>?B7C}8HNjWq=A&eJUoKg2|- zMEjAIyivD;(G0@(!>};D9OdUk%puGzAzVRem`8!&iXr8wKp6Toj=)Z_p4y=`m~9o@ znOa`-Niz9b#n^t$iNm13C|_?Uxrcgz^GhZkmfO>DAvZ&QAZ%S(6LVj=pN2R2=pTEUVg?9(jmgixl2U8j%ByGwH0v!a+sVs zr`r-B@;}$w;;OQV{JyzvIs+jrlS0RWHgojT^-j2G1|5N7~?uwUo6qT^BE% z1(B7VfX0k|X@)=6zss58mFBjlT_RuX)dZza8*+DFpuEizYgamq!f%K$^LZooM@WnX z!bIvkWsC_r2S`!`{reK3vQ7-6#s;H}A%ZU?s>tQ^4tB6o|I4hmFU|=W4)*zWwmG8g zQW$|G!93?|$~1;2#RK4jSgI1;JLbi<2WO^971Ih4(GsA6j3Xt16T4#<{9=A<4ns$E zypuhi?n!n+>k&f9c5;=6qBz2vJL1QdNXU46feIN5!yHHX1Y7v8{WRE2vE|iq_I;B* zY;~x$#Nt9>NK%pcWB%muySN3CcP1wzVN{HQD{CV;>WK}FIc=yB?vQYiWR~+jyBZ3T zv}#Efj?8ALQZ$1o^MyJBk-KB@F0sM51Fx`murzFZXEHka^Fn0_wK=n4l@$^IBvbmz^?TJ?VFs{i1dfMkeLUn=NOCS-S%lPJ?0kg zB|V785Q`eV)1gc?PFeDLjJy;&}mQWPL;#UQAxaaq?wMvoxwuC zoHvMv0gI7O&Id2?`l^CqYJ)_}=okGpx9(tjIdpX^t%UD#^&}Y2Ch4p9V19YL)&@PC zQF8hai);R|mY3F?8|w@$)-p0hEY<_~NkK2lJZ|N%*BhH6tk*&?rXwHQDk(r_+%LG= zfdg8#zCACG zkj`$5$=f4_0}=iL`louvdUv|`voi^GrF5!#nH!?b`v!r+)F6NfmusbBJ%7)81O0c} zm!8ldKzWYf|5f9`t$!+|!}L1s)==#?Anla4wFY4sei{Y;z*Xw~rDgTFj+mHi%)`#n zPp^iQx> zu7!MqmcNjvjfHOexdd)tsqJ}SNh-Zk|e^H#|HZiIa= z!j26T73UUfB@8h0000O0iNkZM*s$&V5k9F%fY_3Xd<9jn` z`XLukg(_J;arm=8_w>f|S*zr8bQ@*}wlVr+{?>((9fOdqD(Vr)5;db>Ww%?L zLYg3Of^6m~1&Vi(GBUq%c@0*N;T8-Ci7pQw4qIGHgSC9p!a#MaTHxm+w;#c9fkT-N zr|>57TtDW(_5jpvSQsZLY4S+76b8V--2r5hMY>IUt4f+Cb3E@o4mU##&-88|L2B5c z;E=;B0u2;=^D&@i&Ksx+^tSzZ6HsU@N~vYdCTDx zJ9wdj3btExky*8usePEEs-?eOGr8Z~nJ%T;Cc4+HwM}>NTC#_3GzSWkN+t(RK9xsu z*B`3HYgxWTWcz=+emsNkC@6QA)8c~@(2VtptPOpT+;2Kuro<`CIW@==sq0v5!AppP zxk%~nZcFG}?}%#owi&7h?%v#sHY7{%y_aF~uJ+se1Y)=jx%33jKR~8eB-qUg6DVa@ z&jpId5_XX7n&c$`*zJLwM|-OpFqGJ9*%qvVn#6(}_~riFmmwVlSyVZuI<-CsC`pFJ zc0R+}J7r_+LbX~XiuAky2;1&^=|-}a817Qgnr)xG7gWQOj|>Rxm?uf3QVy{SmzS*M zlUcwsH?S{i5l3-szHEbvw57H!_t*v%v)(dpQWlTOom^$3Lbrj$X_%^%;;gtU6C@bYM^$&yEw^3$@q8>2)|DfJW&>@3qU#Rb_c<}Y zZQ~<5``>Z7tU|+#>NJ>KSS760!33e*PTLjuHPZqIH7o%byPiTF8o*b#b-H9J%2o$x z>yO-2;?fUz^L{(fw{jLwF&Cv-z z(^nsOh$)^SPs3u3vPqq&(b@s_<(@_M**b4MU=q0xozjV;jJMv=QHfuBFjl-iv1MR4 zF5IO8S@;Cc#4vrXiYN?I>M0T>&YQ_4jP82jP&Mnxo>tNpb>A^8JuY4W^vUi}(X$2b zrs*=opw|h&CsxQDY>0R{fJM z(Onhr?E-wXrdm8UKo68HR~xjRL?;Bz_`=&pI|)9wjQ^0o!o*7+x~NmD;)pk3C;4j8 z?g}Y$?qH@`kF}L^$0wx^W`t;{g1@0G!@z8-w-?Wy*G=*6#bOHTqnpu8Y+R{BOFir) z>QzR&s?(q#o4KWue8%-A1yd(h@#Ch=;O?%FIFzf@x`G}aGT>-HUn zl+aJ;`(B;@VtVs0Vmam*JD6lD z<6%^p0Pt0G>bt~abQzZxf!6>%4ko)^e0y>P1T>beWEIkYqB|NScpL_0WUE^|Io*e= z=Lt&U2ehC0*DCB(Maz!UoF8}sok6hSV*-k{2miKB?$%ZCzmL)dZ)iADYxVG^K3R%XR2P0J>&zpbIgG0Us9hs*B_O^BYa`r-kWz)bbKX*tO>ww4cc5>HX z^2*XY>mAbPA~*i9#&$2d<4MQfLQH!X`-R!+MhhE(?L~A;y`IIQ3km?P%80#7A8@KA zfCQig=a&!poG9_12ZiU#!WJn$qKDQy+EYinGyM*-g9q+qKBMnv&u?k~yPn`K&Z?{)1puO~K8}R@mIrrO)ykK+6 zWs#13%E)n%yGA|&Q0gS)?~ov!e(sN-HL%n=3=TZXfQ{|VL@mFHlx1j6u&nRmseVV< zf}?6;u7iZh(a|b)x|MRmVhzizZHu@tm-y`))NpewIB_gloM(2%V3HUXeYnZk8R`sv z=m9%>lQ30KVj(BEpf@b|!q@Aqjv{2I z>@`G#M`3g`plUbLuYkw^v~sw5Ab%3*QYXT&3@4D{EAz|=cFZ#M0d}e;d@0O zhASk~OFGJxiRwUCN(_m8e2HY$TYZV1c|0DrFdjQVw6!`1-+W>Ne67W}PH+dx!{ES# zi2>7%Uj?239j!TqTTrBLz2%`S(zt&eZQh2u4Ym`bcn~HVhH*@2J{!Np*|$UhCj2`$Yk>+ zy?J2q^b>A~| ztP%!~dkdS8Ie`W>(z9?xkEOq!KW`v2(9$o_` zD&k-lt@cnyX{)7gkeEVNXM*sx9~;u0(JTtC}!pzYhrwA_}y8TJ`lg_6oD_Swygx|0*IOBR@T}}%Qw3=r9C61&t)?& zSYPdu2Aj6tDtUEd-<>{ha^VwUT{GqgjH^-@X)_);$6?~5?$vO|Be7@#Rgf0QBysAI z_c0|zDC@-H_EZM1I&8N#Y9Y-QlT#x&V6|TKj6kyi?iOhY3k6)O34$_5jn8=O09->; z8ejZGb@@g23+812)%Wj!0QAEFX1^?_D-Z|6LbH|`Bj>emWJjLq zX;Qxi#?xniD}szI8ZWkgk@kRz;T|6Ee|~?U>OLtIs4nb@k8N#km~q`fi}9*pH8!gz z!!`amvWpY-%4iujttrl=i^xC-s~2|LbpWH;{I$VX@vc!KycBznKPHRq84 znKs||ETNOxEv?+Wt-Q`#M#xH}dBAoCoJdJsh^wT!rbnx(vQu8dfyR;mIY-i;U-*adwUE}B9lC+F(3E(bQ&H9tyl>QsT7V!b=*&&s#4^f@K z4Ly?^ppxtuH=Gav6Sm)A6W6j}H_m=;w06qC-045iF_R8Wqzni8G{);m)#HWA1SBrI zAB@#GjYO*w_m;l*AUB349!@Q+Rdl7X&YRBYkXrc6f17!Pb7V2oLWmCY<*+}|^+j&z zR?w+EqrNARzB^qfac@6l)8no$-st39jp5SJk#mD>lmTGOt5nx=ra-P@P9xq`t2%Ot zC0>?H&IC?mvNf**Uj&^|1$u?Sy_pvOX=H?}8HkaxqC z=p((|QFt0ZsBvI&yHB0l@5%!}g4qPXf$0x#$vV4+U?caC$bgNVNn%qo6bYH5Xny#DR&vYNF#n z-b?npv2&P#E1Z5xkGp{Vq8U4=Umy&+Hryzqz7X1T~6papYk9}l^q|3w@%?S_co1HE>asej!(ME}rN3&B~de359R?fIbPlgd=DpJm#M?C0mA_@N+J1076l+j!F9S;dfK1AWBL);c-qI91E9BZY+pg{SYu{(?iIs`crtd z;!`!_70}{wKxdJwW11#nu+Aw{+)F}MI?*V7xFM|ozdNz;8z9izObWgi@V;d$zP~g( zs2$jBnU6reO~orQ5vnXB4!Qf~he$nV0%u()t7^*#iAUAL{FDyOo1s7?`e(!EH=L1! zPAo(|YwQ`+LXN6>QNK*>;Q_+l;ei-ykeQ+BTgoblADOYZ`_QwCm0ysX>CuVUEv`6O z!|af_#u!*f?2l0pD*z^%DO5IpT4s%5NvUM3`Jf@z7%jAbHv-L`AV&n86u>PWxNfIn zO4VwbrCz$NclZTRo*9$@jMvR@+yPMwrUH!KP;a5S>t|VJeUlOeMmMPUQv>X61u4l* zY7#1Wh(8i&@1&8)$QKxq2B3^T#%%d=C`Md>wK=B72l(|J09W zi=ck89JIt{&r{{?b;;1kMq6~8ApGC;lUvtk{(aiCdZ0eVwsc|9FGwsE~}mlVT7~W zsxb-f2GuyDnMxhi+$~N6 zI;fayCNiu`fE&78>#ww(!bSaxkgbU;QlP2UclrQKuw$_oE(YG4!XRqdEO_O5;CH1S zG841Mr^)k_#x`DrDxtwa=ey8O;v$l}y~MMH0Io-N9BHRsz!D~6+svqRq01iWT57XO z?!l-?NF8J=^eWU#%^BCHNG2ldZ%F|$2KUn)=%}P}V0gbO|9GJ0HI8^2;A1@WZ}2Xl z6_?vk+|8}L*=_GBxgAeym`WGK;>pRs9PpiNihq{9`_(znGhNPQ(WLO8q7FTropA%7 zl><3V-g)bo6Nr5<0(ePhEb!?`o?(A+ObT=RU3>$n7K^aM$Gx%O!~WR`a4|Ft!oIa; zC7>IhBi~$s(TvFHcHge)4m!c;oAxQa_N2C324@Rl@>!KsGksYC_H6 zdz|OPH8hn2QABeE?FgeFXgiv8ux(Z`m(o{SiHN`+8oQJ+L-}UHXc~%U-mjF1&2_Wn z$7IAJ*@m;SYK$&e$-rRmwPsp#~>>{5beroCE*EZlQMb zMVjo$2wVD=8St~fRe^P)2KFyS$+!TtXm_?%==vPUWszI89WBkTUNaIc)gAJS$X0DuCZ;YW3EhN{3Cez+j&&bDSm)Zlq=%j9cpCY&Tgl_ zWQ;!Qrt|g}r}<4Djx)XqT0u*y^)ScHMLqG5o?1F!E$<2HX`PGlm_{m&WA)GQfU}kL zyr6DHFt>fgAiRT;u~T#dQd)EimIK3(Fu!CRf@xLt7CVz=qWy0p7B}IQ$Kmspbe1qb z2W2wL`x|y4=|?5IPw9@QZUaM-+UuaV)fXt_C6kQaNH^XZmY`q}cPB}7E#NOR<} zFojQrxtOGSaaVTKlnE1eBLRV3P4JrH9i7&PUslyJaFo~8y^=--cgQn~QJ2rllcy*1 zY&=I^VU*WJOFH%i7rCz4HdvQTv(nzqk0$fRhH_zBSj{&Bo}nsu_{9XRjRtv= z=12yD5|S7>!;m(I+Lq3bYbsVi3Et;a*`+o;0_J7_5(rwrVg25ca&A45e-Dwpwfx{@ z=L6<~0)jLN2$)=Rw4UY-1RA5ue&vT#<6rsy@OL*w&^taW=Dw+8$fk*ANZ)u9rEs&K zHw#CB`fRNWWtrT9mGRpY++ACS2>*A8JPuo5>P7xZ0Csg?H6k)6Ol|Q|kZl&20+ybz z;71viAkvOm=+YHzyjlkp?q@G`UTG+_#b7||M<|OF)vq+?^Ib*mpNu^#+OFz_RpyFs zF6FuPHfa8MSgp{mtmE7Jq0>Z1I60bAw*DKrT%{81MvdelWZo@GmJ`|4qRg$Vp{w*+ z^jdW06LCc+Pew2fJ#2S1fF3E51b__|s#%}CX?j6F+%KtS4!5zgfgOS$WX#@h4U86D zqW_h?M0|sQ6Cp$Xw@-!Ic23kM{dpvpvi`%{LUkbvIzmnA@59plCOkEsRY0xYygso3 zud*z;Kczi5W%-bRpAP$uYLX4y{Jn+Hs=%E5(M_c~*UQLu7%AXSFk(4-ze+B$tx6-mNL) zcVy%7ZSZQ?a~YUtLgHo3{#OERVN5#tEW=>bd{-|Pc#{GzXhvG}-}i&j9RMBzvCQK7 z4^EinrL<%RaCAli!`U5hr}_OLUl za?Q+vwm?0wse<)LeI*1v9N>N{NR{|BzJ$BUyQLl#-bwDt!Qj*6)HvB3Pn(&bq+3M3 zuRpn33l~c%ujmSfzx=JCw|9yL2JdHRxM#mI{93<^fklb-<`fL7tx5a;Q&kV|>7HL8 zt5U-Wm*2>&qG|`T$+J32%@NVpH3q^ofKYL@`xTI@hyUAV8?^$tcP0}u}b-4c8O*)$n^2a{JGih`&;bk(7Aw;$@5pP-3L!vm9O0tI~U~LbfXaSc=Te@R5_{ zpv=`~e9n3CQ#kYi{D89|KFjGJjFd_{pW zzu<|UE+W(@R%5p}kf8m%JF->> z_Y3J4S-^DNJFbmz+*!daIFhz$w!O?m4QYIAKdHzltVikjG*2{fnuS6i3#Thu-~CFu z>J?IAAgv=bU)T<#>V&j6NqTsdKJPh@=k7cRa&_XDw^fk!;zdWR1tCl+<20SZZN>YG zJ$x4|bj;&Wl3>2v#f#lFf7q$!vRvV|<^PW@ba?grK*9 znmBWpx&f9=LeFPNvE#;R5vkHoJEc;yB`{F!`^rd+sfX@ zTm-SvK%4BhkW1a(90B#IMw8$O*I+334#lQ)D|@z!II-s4>?6P1yL006%pgZaGnbyd zFY4@Ra%Lg#AD%!^!PP(xNC*$1!0`)pSC0t_-N$+|L~_~$wLcpy? zr6r1GJX+O^*YRfMLcoKT#^R#S zbZ^qIrZi^V=hVrMzkE=72=WC%7d^7ZT4e3YbY}M!vqRp4MICEb((|C7FO-(30v$`Zh=Rrij zaIp46!7~GaXDJG8QOmr5g7=zH<$YLc^5N;&xFK))1~ZpvU%odx@*75S4LitJ+XK5K zeyD8-eF$OSfWj&XH*5uJpi$_A+&;=CiaYzQP9c<`*(JC)WmZN5VMk~ zw!wP*k@8e0({~wIyg~N2Kxh3Pylrhp^{4Du>9io}QUkr07*hy0LA(TfA4k?YsjOzw zbeq(FP%5kAMSPpR_W=?RyPToEs7ABIf~Kh`-Ud znU`-bIsGQ-DLR;qgK`gA1?~9m;%A4#hZB?tM1liDBhTq_M;s`RVIPecu39s>lnOv( z*>G63ZW5?BX^gs!j!`mgzd}E*$lLBbsf21~dqP|Qp^=$`^kdOzol4rmSS)|D8a))H z9$f(Lf=AJsXlk-i9zdukaBXKp0=&6N@fL^G0HDSK=J^|~sDlzMnHUx%>tCkjlhiWd zv!Ra39e*Ba^_~;VzeUUxfVI&0XW3!6Vmr;Ox}Svgd~*Q}&~bGx(+pjG>OunbSJI6m z06B4R3>eYT7RB0Wq)E@o+6uG^xlM5BOZ%;J_xVpa4W+cpQX5Ms@Ri(QoA9tg&cdoD zNE@YcgHy|%F1&#>Kj7nOqU|-`iG(cKLqG#bG(uFrs|pufl=BnwGei$Snoo;1Pnh7l1%%aLshv)seGS7Mo{|T*^|px!(P#Q`=1{Tu;0{ zS#8ZhH~n;@ScVH4@E<+a*nxq6N+Fc3AcMx>(d{QO6O24eu9ec3t{lpN3Y=hDM9@l2 z{Cby5r1B}K2e zjdJlD7ni88==LZhPAeA1fZFU09o2_%Xt0HC|LYa-CxnFrV&{Fl!(PZNGhJ|IaBobu zhu<*|eYpo0JG0TCpAJm!%=~76gCS|R&TS6x39Ic09cJph`>C@5b_2GiMji_6D7B9emrdlI6`-vuJN7fdY-9Kq(q|nXapI<$hmY%4eD$ zFyf0FJxitA@oj06wz6BevENsx|FALY2lO#8YIjv&FmT-q2AvXa9xuKBSCNI1d{pwi z0U7*76+<*CY;%%(tFficpAMsI-4&&>789Jui?d>(LSZgbhqKVWr8$S|LBz0m|MlP- zRI)4*0s5u9CUcT9+%^Gu8iFJl**7rkRpuE`9VV?KyRsUVBW&=L*u%ot@_fQZdyOjf zI+(E6>IN8+#iX&RQwnX}VO&gfen__GIG?AL34UHTfAttOrPChqEHe{<4)&U)z6KJj ztx~d68zj;1-p=XnbQaC9p0MQvo^&>r-S$QjGJw@P>p))XIcdEQ?LJR-e(6P^GCMp- z57MI?Znq;PHnutmxXAER2KtY)ZlU1lP*7uRVfq=1i{a!kBO{dSWRHAk4=f=fWxEWM zRlQi3Cfp%J{QP;h(@p8Nen-CQP0pyH`LY{4HK%^o+2X71T zTb0)+vB`NR6I>bIY+t$o6XN0#E!D@HXxrK{-IEn8yrRF&+Jmj z&NvuaAW!t@7r)jThCv{&Z_-TsCZJi6J80(&rT@dIxIQMPSB3RbjM~;am=F4t9Q_=NCh2zy3vRxn#eUW{OVoK1d)LX_!QLuLC_3K zYs+l8)R!<>2Z=N3;x}@|ytNjJ5V8 z82KkwC(8SetI9&qiFT{VJfjipfi?;qmTuvU$zpk>U9&Qhsu3giTyZ>=&)r}oLq+UE zwR^ZbQw*(gnSKdhDAYbdR3>NUSZ(ia`rZGQym=kj{Q_g)#G7h;Y~yG1TApSw^#E;z8zx$^%3SoROBzRRO_CSroMS z#aRdze=|FF7pNuAerWOgR^}D65-K6J?jnPeuBLyV?UGJd{p8eim|E(lXkd<;MSH9x z4V76O!T3t5%jt7Y+ypV_tvD9p=h1LX)$EoRJ8WrvC~q6L&!jWwE7!Q}wikbaselk{ z-ZF5@&mWow4%e~fFVR0Je5ZH5+J{awlD1qR9m(|ruW?(SL#8Lc-wV%WS-{Nxut=Oh$^Rl%>YvTzym%VyOlG5Fj29 z0000TL7xsq6)k@N679124fKzzzyJhmZbA!qL%;w7rvLx|7y+LxM4tc$WaVeE^8f$? z0009300RK|fB*mhDFL4^MSlPW*AS_$QCxd_fMn#}TutOyV+uoo7Y$fBr>?W2SV%$u z4;cUe54u5{G&D?0|Aznwz(Tv|={oPv^Fn6hU#Ns4#oP z9AcY*@Sql0e``Wq&+A}h1}? z==2e~^vUtec=L~P!36H?Pg8ah-!5$dvCyuAFgytW0j@WBdZtNf#*^{p$n|L}UWvk4 zTfRY#&<|cS!(6^T)-tUvcab1ckkF|Asm=aJtwLC+I?ti59C@!TYRdjKiU&FRh^>CTIcz2F1Y>1*>ye8` zE_1Z%4W`b(02;23nowY>Ly$mA)~p5gJwko({txOw?Xw&J0|jkLKRa_i%qq82iU0Lp zpXc71ua-hEYp2Y|dZe)FCofM0!V1wi_UkH@rsot6Q>L@>0Qfy~XPQjyM58{lyLp{! z1AX3YIZZShGxeAwsn}27i*auZ^NKfIDS24;?*ZhNOq9<-_MJMe0g!rlh zDmY?m8geds6FN0rnRZ%9O74~vK8psDq|@ahH|KPu-3Q8!aF^(}d*Rco8Vt(ui@axg z*2x;JF0y2l&YQ|>iI!08aNAO&1QK1*D%DvRATxD%QRCx(AA1prJ3i?w1 zEFiZbP)5ImUBZ2+upbep4@c>ZjTQwl=~mHPk7YX5kh32G)MIzSo{i$_ax59Ut(ifl;N& zQq)LVlC|5iV5-5^uoFr{r=tAo^1P3N_JQJ(h;u;i6K1cgBH`We8 zx)cWegglz}28^NH7MW#eR4+;JT&yiXCR8e7Z$8@8B3!$IaP`NCF-aqv7TVj#XB0s+ zBIC4rmw_|a1&*zU4g#kWy|{qOA(bkH`yudpsm#E>=5NoX!EsE#Ux`Z2>Gvqilh-;! zBr36AwUlqCxs9`EYB%qXshNyA);+9;E2(L+&{wvg7%yxne(+F7bVYk+?qbUB=68ZT zg-r!$KY_gX3c4-eNt*-?)+E>{Yxsk|^8`N)xzJ*7Cspex8B^QiXd_*NaotrK9>}_J zhE47->qq2CHiew$pdI;a0%Ln4r!K~S@oPxnA3uhY2C%d;=Gxzw0DF@|^U!h48p!B; zeWO-U&Y;&#E-@w0|4kHGJe4kdjaBBNnwS&2K+%ldHVoTC{zAjH+ z_p*5N^v6BtI7rc&d-?a=aT7rt)#(B9&gPHqMxiaDkBrd1GEp% zkKvR!49d(oELCPBV<4PhL_1Y;1$OUxXAG8C%d8?`3rZpRiAz>?Qf|pZ+j_{aAW|e- z)v#*Btq!kDMNT5+&T!NtD(#Xkr}2D$a}skx_l~0+iWwWTJN5)cZWZITO%QQkiB`lK z=QC1vFibhexZ_Q(kF{EZ$hXBD@vCnQpnh?n@WZv>ZWtn&-}4A6`nWoSx(*SQHuS}L z)^rgXvU?H@`?DH*7xK z==z7Q;O|}~G-VD)b)`^a86u@wCbt340m}R854{VWbCCbE2cmsNPh1-X?^P^8@1jO! zABt^5m{=16A(MwV1vR{pwnkX(vC|wgbI8X!O)0ct`GWRn+_J@vZdhK;aK_Qgr+CrYY*bbF!O z@{HRBL{&NwbRRMd|58fPBIqUUfH|M?)7iHh+KQ66unNq`S8O3&nM2=lAUa*(@K8o( z*$ABr8Y+ZX9XTVJMLPw75R4M8;$rdYEFt)`WqLy=5c9{M4e${DXMb$ruX5CxSg@+e zX>VI((C@`C&qYJ8)@jF&Vj*QX+7t%*Z7~+1&3?Ws3MtE3l5}Hoq=hi-TA5~ybtJN) z&UpcEXo=A=UBG6J)Mra6Z`Ubs_q@U^JUNd)2?PoWFB-l_M@a;bHE{$N?y|W0mZh9Nn1S$3;cC5Q} zPzisT<^Uz0o-8o^uRpMbflFW5Y@2;T)}`Z9lQv3n41{;PAkE_Hr0eH zWweucUu1Lov>I$)Em~Xc z#(A2qx2r;^OCgO5j!Q>;{JumnJ34)z!&XFx9Hq&26z$*g}+N zoraE*QVTcYTHM_ZK_=~l$mQrW>|U1_P)wl|nhg$K5djo#HeV}ZcwnAad6nk1o}p#m zAxLVN79Gd#YobvGNRXoz7vyJlo!*I}C-<%F~yl)3wmsTWCsC4ox?{G3C4!OrvXL!^Bal928_ zIdpw?q#Vv@C6hahNnTWtQw;g( zXP^$E9x6bJ!>u=RI+j;2RX$&V! z9w3e#N_noaH_rj2~H^A*=?K&J?Cw0cDY#1Cn@H=_@*K4j8P<83tZ`Bf8PO6r+<2Vd&$q}!oGx=Zm zl}BxsI0PlQHNDP7a2(Qxwh(;CNT4H7#FK7$3(=t%dFAL6()0iS{8D8}?3rm% z{OAWbu>)Q?KW-zK$dOj90?GQ`9sDmo$~4&^-KZgWh5yauwGOanOnPxb+#HmvKbI|- zN?1CO;RMSuEe~*#%e0(jp9)Gk z$OcvQh7!f%&aua5wf2vLm=RWpK(ARA@|ePEBbx@e=W7&TuDKwzRhLGn?z^>vW+!SA z%0^#$cxq-II*(F9c(Z3DbpNC-f4x2~dZh<-0000cL7!4Z6)pc1X9iB~7+q*$)W+0) ztYi2-!}0)wJ?@pR0wSG^3n>5q02KkBaYcUs2sYzcFaQ7p006?L7#9-&001HZpL0k5 z00vJG>4jsQD*NSo;1K86AEUtGU^3^q87`@c7ytkkXF;2IG)zzbW z@qAOQmr8yM^6l=+Eq=L#-5*w3_01;cy2EJS7qquQhJrMqPV-$+TRqxFVbYih<1S>e zrE{q;)WMst#&4em;y;3zT`3Y5tcIVu{ZJrKWt{R%P|@*5R}0_+;U~e`1IwOoFcrs1 z{sUy^9j%>yI|b$vQ}eEzzuV^~E9(CWttOk5wFOp;NzOmCyyQ&TX(|({1j#XWsD`Jb z9D`Ndd_PQ6AZs;+!N4p$<n zDsRK*(_AF%{@p8i2v$J`8fbG`anl?F*Zn;P8D4JI0`O4;g#@502r zX!WL6VY0{RV`iF|!7}m_oFZwmrR-h$g^teQ3jdW(fJzm|7xSBDJaV++@sz!L`=7`e zV^=GW66#aQ$b6n0>461uUjYfyQFo1lLGv>YO5;;1TGKZMSGUh$O*pzmh@DGTC7aZ` zXFUP+P$BiG5eQ{<@%9T_&ni<)^K?+0t2Bq~q&b~j0sU}}uGMzK7k%k9c5|)!C89H? ztkef|QGVb(lDT9qspLrbXMznOTdZR{qZlLz=_$a2EaX1GM7JJW0L%G(G)0V@zE&gy z*<2EKUQ?y(DW6u+*wcVlSXtCS;0X&NXar_lz+$0_r6ktiU}ke~7J$IO)C=fe8#DU6 zHa=GmKDnJxDn}3=0yTydi8%~v9hQrc>^@}3ZwqP9sGm!e2qgWwQ-pUe56oNQ02fJh z2Jn_kx(_kIs}N*8g?7mANRI6d4Q{im5!4v&$RPL_?q1Ia`uf39-7u=?yMEGRi~6zF zK~t&HJMC`*!1I3BknU4bMbTH`ym``Ug)RT%J<^Nw8*>5muAH~lF(iK7q>I0G)a8#G zhQ)e3=6Y4c+X)ILu{r;;a4@9#bNVX3r~Bvp*M2G^0r*FocYl5_@*{O6StE;CA{twZ z;_r_fsz~3y;A(qz!}*ecVrC78BtUu1nXj9P^~25-)fw%^37i0L>I$&X;^x9vU-29kh_uhEnt6Wb3LRS#I=d3+Cd!0|MqA4Y1#7?*m1NtGaotjNb2D3rP#Kk z<}`z7Q&VZaIBu8?Bdln5+g2w(Wg;0@Qa=5$ zB@|)eL1D4HJcENd28GpQ-ouznc341n68&y?l>j}v)dSyLqdC5%z6JkZpxSuJqv28%(iiS!LOp; z5Dr2emfALm6LkI%M1(+NWM@F28mGZ+P-7eiD&Kszo{`=6wIrH}To>#W=k;>sV|5vw zThI*5HlZ~>X#=S&@m32fYx88%&6q>6a`56TUK$tqt9n~M@Wh^x>ND;wV8 zW95;1+gx#n)%>R!&G~8^-a(005dUk<>_ZUB4B$HQ*}UVpw(4hZC>g<}P|~@=il`(+ zW#xRBJ13vRJyQp!68**qf_V?Gl_r>1mJ8p}u7sSFXb^c^-u5!Tz|>drXkWI&)a?EK zYvAo&VM8q9K{04t6Zn#Vn*e8fZ@Vuj{n-^lVj5Tnpdm#DI$PD>qC+ofoM_t`U)}V@ zL}Lghb2C%X5m!{rHpTjo2ovlIu0I%DEUR4!Iz)ISh6jZRQume^CUj|UxSjhZU`Je+ zTk!a-VExHzL0efKrTKVvO%mKio=9RYwGdGUhOYD2Dlf1JgfmD0|XvWx%$J2)_ zO>F?3HG^KR9?pXiA8^f<5IJ$;M>h>8s`pix&{OP-N7K7Y@f6aa8U8+>`B776g@DW# z00L9fFR3TB`c2Kj6Nw5D)hd9GAO$_o49lX3`dD$;c2)oKfo4wkVWx42p(UF)gSiA+BYz4iD?!P0rizL!rm^C zbq=1=VSqh(kf(BfB)RFx$sxntsk9J6cU3{5D;6ZVXVLIe*Pm8v7x|S-gFbj{WsI4e zAKbz<1`mc?*#9-#%i*oj4_g7vEo;ZMN?Tx^m3{Pmv{c8Mgh@ype zuQBsh6D}gmU-lfoi;jS{#Aoyk?6G#cFY|c>U!T=EBlMIb6m%dqiGFL_my(`hl)mB8 zdbyps?>^HpW6y>V=%E74PBL1WSE>}f5O|-j#NZqp5qk$pt4}^l4G%+u$55_-Z*xcv zIithMuAgaDV#{jw*9Z){4ZQ;8b@ziZ>$(RrBCfbU^5LiWl;ve6ieUB6iCo;5e9^ol zq9Tr`(7vNoOuN5Kq~b|(?3NZAvW$57J`{+MhhecQ7!Wtm=c#_BoFnCxJ83GDl0vv; zFU2`AX|`K>q~xLHZJeTw>>|v)6ci}bT2Z9$5{{Dm(N-1vm1c}e3(?IppZCVHPjJh` z-USA-1DnU>?@lS^OWpY0;C-4x;J2&p`002C^)yqS8_X6OjuhCW+fgi#YMlllr@H>M zyVAL=#UZGogy(O)j)tU)OY<-Zf2RjM7%@PP%cVw&7Os9uL^FJnYEg<5SbuOeyOmNA zGdJQhr@t4_o9J|r&o-*M!Z_Ix6OJ|x43j;S-K-``tm{jOCqm|~P~v+M0f;S_uI(%v z0HWBLUpY{E4vU|1)dgUecW^X)GI6&-2-HrxQxXa*G(IyziTrqdi}W`f6X@pDr?FRA zhl;iaj-?%q6fHf%^tb}P{&~(v54$#s@qYi5s?VB*W-#2i*n0CQuMi50f<}<58b>v* zJ8El2PUp?H%?Zxbs8+N*f<@2cPN>vUR8wL3&zcR)x4L^b^*i=_ zWVp-&S46jLb^x2w$W`6>HEh5^e|m8jpo5F@v^Apx614cE-5+Xj zpQ!Y#?mklGnXw-ZC|Gpj^d0lLTfW~vdl>{y1VvSIGq4%SHRl&@31uiF44sp4*L3aB zql_RNz|L8>B>C%W9;3X(HHly054;X(<8#(G#f&dQ%*UYvlopwFTH7rqh$YPaFX7^aHYs75;~o+5e-QLP5576pnZK66A@4%NKzS90z{c)oI&Q~vfw^S{MuaL zNlw)l_p>#yJ;N&KIPcWf%Qazk!7l1epRLz)@$&N-4-_#>BlV>`0C&+EbSvU!?wz<& z!dox7kcU1I?_`T_H_hG4zw%2z{_X!R^iIC(A4j0ae~0)!)%mn&Q#oym@K+*-asLbI zdKbVu07rSy@OeHSD9Dp`wT#FXoUp!BIpUNx+r-~p)w2O|hvYXno8d}su%>3=mC5lg zSt@&A*Zw3Q?k*QFGPZQ(dn#)L?EE~ty2a0t2XGub0ZA2;CT`si2-D*UP-DG8*YIXM zqcO}8aBYjztA|J`C{E>wr@_3~JuXMdBcClGH#a$Eplp^a`G@&qwd0Mo#6`V*-(N&e z+-tIH)$!UNix`laKnBvcGrV++U+s`@j6L4jQ#*&_;0GD!X}sTbxr)97~~GKtu@C|Gvq{XBXG%&nuR zPRRCAGmO6u{LzcX>k+!&fmS&eXhjX-Mb+S`V~e{&N~2LMD1}K@sEPrhr-?GU%wRtq zxl(hbDKKe?n*Dd?f9#h%*Iet6(89yL)2R6$y?w~LUZy>bUOuS#)Fx;Mr-3mMY;Uy? z3&m=9Ho(_hf8DvRpY8G+jr2~HtlhCcVNV2l&Fm+AX}N5}!sS-Cr=>{LHUJjOrGtY3 zm!bPuJOLz1AR?p!f*STNDCFT`Uo!CJ;_Jt86AQWiP(oipTf+w{i-D_Ek{oTch8H=X zYG%urN-ZE1LZKZMxdH?AO6M#B=Yiro%hLgLQkBfQb=yX#+bPSpkWe!8x&|EW!5vRe z*z)~y!AJZF_~i#-Dc3meyx#h{16S0sAX9G^#Pp06#zoXfk;%qff+?wN0uuuI5<6?G zpOou(a1)8!cAg64VdxEVX}G7x@ryUF^zXRZKw;!`QU)-a*issCwI`{ueD<^9qJVLP zbWqO=XHokl!vY$YhI+!XM7k3KOagtG=H}akM3w{hSfa!M~xcv6@*Wu z<12q{MT$uGGDlE03f?Vfa3C2ySA*~RgBBsNCs%o$==@=t48#{0$|;{$R$V(Hq6 z@H_(@GdU{Zsvru9Z<#IwJDW5x&pjzbcTxmPUx=HfcJ(vwqVs?&T?KU4^r61w{;B1- zl-_ufE))D`lNksMb0GG`c%*nMj5oYiCjtY$`rEwl7c@PJ{9(o?w15E`Bkk z`^3r9dtM?lu1G?FV1M7ScP=K27UnjQaM~cgCr^+sF#He?%y#g=$sDZn_!8IS9UT95 zrnW0li~lY7tqS6U5~ecJGY%aqeG*63PDs_uj%R(r6cTTEY?>ycWzc@9W2{QA8tkdl z1fai{o6WWHL*@aMSH5VcF&>7T<6~hrTECJ<(LRRh*tpL*p+v|n8!O5Qm@zEuxNe0n z3rg%VGy3~z?>7aPfoOcZ7=@YUQP`ROLmhyWM_CL=9E1wS_K}h zxIkEq*TbN)(bGBJGIZJSmW#WtR}?_{PSg(hT9G7+cQ=&B!m1_=gikbaOYdf?N@Td) z@3(|2i%1l0fkmX^1@jcL_PG&4Yfi$90^4PGz~K;idY8d;Oa@ybtKTeMN#zYDH*08) z_>5IZ&Mkr1*w>r4otr98T}y?;for2c~l zDQh?rW9ye*^JOoqNs)kIsDF&b@ffNq_JXWA)~5h**@YIax(HLSrDrdYFu*Wz2jO^t z400EnuSA)p0nvB5i2N*Qn0wh=x zs4NqGJh*|((0+l(kxIIfP|Oq$pKEB0M}lyn%KvXyf1i`CNzSM9gyhOC zK75gYe7j8bKze0NtyqsE_)2@8*ZBB*9WOMy5b+)5Y?bj?1ON?v871yo_rAHzV4yzQ zlB>Y%*`Q+X)wk?;_(lj0Zn}F6(}S@nh6v&x9sZ%YHeJlI!e-=viU{;AQw6u)R*!{6 z1ZQV;@qm8hatb#F=3TNexxzChuYwMBu9`AA$kS|wPhG31c?Uq|L%wIVfuj6Rktdpx zD5RHdp`zsWTsd)3%eaXYM0qt;hU2A+k=w5CZ_i1nq&oV@NZ~I=Sg9*6yE^Bdv8TJjJ8+@fid~bM zJ2=0ztD*flze;U85lr_E#>TYDkU#_)1M*zxA)y);y1cpa?l1G)B{vMSZZo)1+dMBc zXnPh;smB)zz1DVMpVdu!O2=%ZdonDvCU&}6^_>_XW-?w3gpQwPrD5r1eE!}V)&DH% zhe?J1_?TaFSgnz$k%{ZuyArgY>ka;Gs@6FdJ4{`efRo94N0i7)I9@=&L~gHr3a>1~ zpLo=-rW(%#Z%3$E5Qo`wYHqE>Mos`3;QRfkFyu9V_{AjSiCD*f+9sp2D!h{>qNcdoVJYI_ zZFksbyDbn9P98~Xe@u*#&4Z@n959jBf#%^sl&U+w_U#{+nlyx&BAiL&fl0~uYVAarG*11J(zZnkZ47yx<!Pt16ESnaSbyPJ2P6wNPEV;9;^|)7Nsdrg9n=v2Z@Fqk3^w$^BqbW0aH10k z7f*df8WYwff~sD-tPo%kBQD-~=>v+d20v#Qmt!bY^7cstJopSOJYm@uA4bVOlYm9X z7E);3E2{|+y0EYm66#V%RExuc!Om+Q9*~9xapLGPiEQG%YccX931ot^obZ9y0000u zL7$dI6)pb&F*gEl*DrgD&wD}c=1tTK9yr|nUPLzX1fpX;YKp>GQE|G+9aH5F(l z{(k|L0000Q0iU%;{}uV!#iiYCXHr2t0A5?e0;m803P=C|02l$Ew?+RHX9iB~7ytlB zb-V#}vWro`0Yd-)6A?k1yfjQt|KvbWE#NF==~P7Txw6!9ULl84+W7iBW^AMVo*~s{ zyo8B7OinB@7yXm&qZ^e+SbYi6crzV{L(O{pB&RfR@E|oRwinO`C28b_fRZH!%H&5s ziK%2B9;erbOD=H=YJ+m3>xJjQ_d)4O*OQ92_Vq(s5VU?G3O{+&FH|j_2X(=J68Lsp z*`G-V#dLi3-x1zv(@YZ``$+X-8xo3aAe*%|)0m%bFnZ{o+u6A|0gWyn%-hY7e0=({ zIZPa)R9>kBQ-|)=P$J)=hK`qHas3&&^a@kY`8adW=%>>fi!U69*)2^Fb!Gkm9)I+O8Gw0#?zw^Afe`~W8sX9k~Gg^)~m z2ECUFskNdzK-Qep47=*D_>9)RXIF*n&l2*~A>%bmIWs#yHqwO+Ui++Ubtez?u`(Ws zGng7ql^-P1G&R#A-7vFjxQ=$#J9IyF!}CNN7?&J(6=z13pJoG0b!N3&E&d}oPUgxv zz=%O{PO_=O0THN3UtFw($pjGl>l)4tHhj@D)`8Lr4-XN5{g3jB%JkxXiYYBb}*DiYT}CbOJAmAgY~G*cfpmV=mX zBW3H4Il>!-EZH69HF_Sdkl)p&SG>K5u>M!G0b-DaUBt{yO_+weYu)1dKW+nqv%Hcoq+P9hJY!#10^hCJeMd&~dL6<{LB+Sf$uZ6i)&yex zny+?BQnOffLNa@-S7lcbj3T9YaIxkr!42u@vW#UK=h~uF!{$@RBwQnNbR>|*$#0C) zTcOv9&m#HkgkQA|2fjJ?!CtdnT~->wy%CS@!{>S;~8e zQUVg_QSjtPnSQMyvW3X{;|zuB_uxDdXKmctOBBgxnS z8YdBlPa}vlkqn=y1S{$3EFaCy1PP838blQSq;N;@qdn}#hLZ#?)-8CukL)GP7?*y- zQd^`|!Kl6Gl{LgC(myrzCxkBQK;9S%AMTbAJoyHVP%m(8kDGZOnm_n+67jT3Y3I;h zI}EPqa42NoLN7t`&l09Rma*f9Pf%MlYG}&)DC>#j{tLFrpd7}=$C=|ESZgbR$M%Q} zJnF>8mzPt2#I~WJ#5JuyR_BgmfDGV$bEDB&H_DhJMo4j5gG$mH|^? zO))5Oql%$K4@lOf^y(^T$YI%*D;?oEu!OAw|BmmQ;23D_`+Vx%xu5S0=d-{D6fb=f zG!Mc-a=rbDNqb}PU}-HS>7%#$T*!jD${F&cxWztNkQtWgy;6ncI1~~~>yfl*yFIUU zMHo-Py0?#HA9sI_8}HD~i~Wl%Iu%}+?+W!B9b;}@e~!v7{55zq(o%R&ki&F)nkyJv zB}5>jM4J!HR8FQW@)jx3P4FR|=7hq(kj0PnB$ab{Yt6W^uV~7@cz?G!CzcWe(P_kr z+t^-481q)H(C%V~nzQmdCz_#fv_bY543S;Oa5k2%aCtR~WY?4>LnO>TE(X1TejgCh zYxl%%JC!kvgZ&w(qXwHkQ)FCqYC#1_HqnUyj?N}MA(oLjW_epZ#cjcyd4jZUkVV>8Hb0YWUot2q3q*+lC18!spU{bQ) zH@fNA`dh+C-LBD}u*M}<;spQKon4phfR$shMo_@5s)h*-DF`-W$Iklggi^uVkHv}6 z`6t$Crxa+#}o;)0>MmRc+ z%gLNX9Hdci`X^!bog|Ws&N>!q>!Jbbv4_%s0IzvDm>f>iImN&AdP7c71|$N&vc2kS z7Yguzh1c03IkP&XlvOitTQBwt<#VTdL2o{$AM^D(EQ~~rVf1O7(}{$JV_;z`2Ri)P z|C2;H$Vy)AERGCjKd#>76iS(z(Kbp`*o_+d1Ad31~h! z3W|B6MhtSNDOg00Mmt9x%r1c^=f#)ga`+XQd`6Jh_v=*)Ugw8*eQ!gY(&7P4_k4jx00aLjmVam`Ur;R7 z6Kxe$E+$#m6;RU25|};}V}PJPzlSOgO^RQ<;e;r=I`B1%7sA2)`v2ToqVI5pdi;q;J2c(K)_=VI4&O^S4C~)F^HnK+3Hf7x z4Ku<}?M|AGbnZa4}Cn0S4tajeGC;P+{L1N^A^9N zT;HQkkGIQQuVRI*?Op~k80u~)wD-Q><2{YMQ#g`kM0fi#P>QU$opO&pW9SFnA`D=v zEjnmY<6n%6StWSHUlBO7d)?Hq!;(MDe9Q-D4qGHmD+ZdPgJu>!@W$=$SpY}%_Re@V zBO%ClVC+)xZt^QH4-Rd&Y8}6f3-AtbW^GU7kM)b*tjEZLAsUXSLm#FL3^1y8L`Br!&xjZ_m$!JOXV+iLpVmb6mhYKD za^3VV0v*X9Ubi1GMe6ZRNW?<5Su=~axVTenx7yG|Mi{x<9Iv2coD8Aei;I`qzIfD~ zWGz9xtcQ}<46B6?2Xykbx|~X~uC*U;rl3T&YkW|4_`yf?Ve(Rd-{;8;4g7w3tt_QD3vnN8E1OUpl zpSM}sZPo$DA*SEl8a~F~79Rj(ma%H9M}8rmHL!F=GAWCVI~vcRs$axxQ_%Q=ZnxgP zRVP!vSiDqq?4Lfc@*guF8!CjE8o*O75uJjD%Kx4-tRI~A3mI)tV2Sm@2ma~O;$7EJ zbA3OR(To)mk{nQDX#Xm1!`1@snqE(pGC37Yhm*2l!AYllfR7EZavX>o>bV>KPG;-* zH4we(iz@|DzM;R{C6B}`!fh_naN?4r`?9%=Z@kqtR3TO}?eKLVXhzXyN5zjC(B_jW z?lCu6!j(%{E#yk700&>co@KFy90_%iJ@7aeW;aK(Ln2#LcH(B{XHiUbacg#^`3(zd zP}&m@K;sbZuT~R9n`V72xF~xW_vER)sF4w84@T~ocR9`@Dqc@Fd-F4hNx__N2FSud zbBGgD^i|4{$Mqq^+pJ|(MKefSPg%{Ytw7iA({?|vjYZ9uEUo7|C*W-m)ZQ}rmUH4_ zvT=BSp-r!WO{_~aHU9*(o7q@k6#ISw0$PinlYScfi5g;VIl_RmK4#{ydH1PGV4pqe zo+CAdq6sew&xkI&pJU{5RWnk|Xew5(LOV<`jOX=~2Qw|GR>2X;4RzBsrHyn~cU8jh zWZACy>DrfG<##lSKk<&l_o=j|C|$+}R1-XBMB4*0-fBI7O%~`j6C_4n!0RNr)QWwa zqg&New+@GmJOO3s9hD$tBNzgJ59gmwi8_A7jh41UoJ`}a`}oeCA|>!hBnkd=huSQz=82bMNxXTxzF)g!s|!rp_sdrqBGX2F2<^~m zS;!`TZsUE)_oq8_7k>eE&0`G`b$^yfPAurzc#9lwPjy6&!Rhi3CGOuLX72_fgE*L( z$f<8d*!O;4!Ua)>Zu?}H5UD43R#tny9q&c!U}`NBO&JL{w7%2{371{^S)z=zpgRpdx~WP*^Y zjfk%n2qQZ=$neU`;D9^f80{4sX^O)>dG7F( z6E0V<2pPYKvf7{QaEn9zeAW#kp?ri9>A$o?Wdk>glFt`j^>i})-^{Rl%?!g7SYu5R zI@CfP`KVn~t)}f9wuxyNH(gp>ZLjkbd2a~_&y4LR{ z^%(TC-$F6Ng_^zK?0b5FiXkp%>u#}`HrR~D?r1=b2{K?42*f7}HW)6u+?*p6-&x|( zkQw>uf_1i(232uUYAbSBmvSH2$;jweGk5*9`2p8M-e-z$NY^g+ki?wHZe{0Kxqnia znkF&f`{{Nq<1hL}$t*@ej&X|7v2j-6_&Bho5b)fRb@=Fxm9ZU0u!8pDE(lP3WCJOm zqzNXMS1Wa8(WnQ4$Py%QgdsC$$;ryCv)g%7l!Wm&e^n4>*-e#~N?w-af|2WLYI1L4=S-(o z0Eld4&(D$)f1$@vPJ>gJWNf_ybS6vJHhjmnjfs)!ntb_TB^3Kr%>uP3iGSL@l6H?vKZ!buV6V&0BJ5G%wMtrE9G zG$qtD6-xlNooXz2>pBM-o;3Y$VsKi0&THpvRS{(x zuxFu;mING<^}|0%9`>vLq;@lBa!d}6uE-$t|Jqr5OWz$q*a+qe zfes?UCsS^bU9j09oloLp{(TVXpEXJZ+>VOYmfc2VVY) zDlxDrjhwkAJ&savmqpMQ%TI$DGk^B-X9|igK*<*JJdEIeR3omfZtd4LeB%|g403Z;cq~ zv3sa9du|& z#Lowy)i^xjXrtsE_#|MmSiNTHyUy4>roBEFW#528h&UmbU$2LyWIV1!k3kNq4`=G@qGbsFBN@=`Q~sOqmF2@okge(WB+tMjx8XIT>e zwij1>IFioMi;|_PNB|Mse%rn7bqdiC&M=LdWaR^rVV!s*LYwRMSzs2Q`-YWnnJC?p z+g^A93kqQ@w=47e;nS42)VjX=8Cyd#ks(cfT?uiyMAcMq!4r6>diBvDLws!8)?Tmo za!aFA&D)z2gY$Aaff{oYv+?p6f^dc;>$F6{hoqmb@_}nqOpFB1om;n1ime7HElhSU z=n&Y00&EM8Zg?k1W6(wfW+`%yLd9kFG|ZL`Q~TUXYW6xyse#Bx0ubfk{=i%;yyq7- zi@7>S=u);S@<5F!u`XlMhqjc!ERg^XhYE`MWt<~ZvUj2ift*SuY11IbU+}pW4;<^c zJ8idkrM>RSYREVOLhYU*jUbssy&Bh7hUV7f%h6^=O>6U@W|VCKcqVHm3|>KbiP$|> z_%t2;Irk>`8jYJBwJ36tvRK_^unZ4};g;Jjww1>Q%$bsgesrXSgY&m@+zH?H@aW{W z>3tqrwV44^%kct^{S2;{o;BCVWx%)ttg=H~5z@r>a+4r5HSoO&M|%#ZBU1!P2L?%h zG&dd(;!J&4gh=0dqU#!=J=I-uQ!f=v1>#|MEv))1YrK`sp+KgvxTMQxr@%J&#x_#O zNnJ&UhM@6pqD!AIZb= zb;HbRxvLB`N2ou{%SFE96mjr;r)06omV5TLh4NKysltJTGy|`i{_2m#?!i{OUPy@F zx0@9gk<#b~cIAS+squOgfq{k-k&bFz9Yq)F3|hrvnJ8|LZcAKio-lia6Cw}hM8(+^ z2*uX@W1Mb>MFE(X`YOq{NZX{_V%!B{Z9$2#uFUs>`nUTHtuGM|YlFGCMs~tDUx(D` zWl#)TU>K@|(5%ZZoc_7=f#>hn)Rbh`BPQrdyV$lR<10QD@JKcUhp>7iZzeIP+#C*6 zt6`0{5kju09mz4+Pi0Bw{586^be}1qf7R4I3wJVbP&9wNXko{(lkI?hxk=(gz>#9T zHP&pUCrwW;M0~Yz>cOJ6B;pCBOXL`cn27gTv)?Z;(Ql*qiRGWf`<_RtKIBGJY&Fgu zS=G0qXr|!SG6H8;M^A5d`I)4F7$ntQzDlc}vXAX8|3-ZD&Yh^|$<&yh0!cq>?^q8q z(KBG3CIZjZ0WV9@bu|IvS2lWCCn#|c=Hh-@woc5ii9*2f*FBAsUudZuPj-Z$CqXM! zV|+L%3nu)F7{D3qJya3rgAhQ7zW4|e{!zkH?+tpzGZq>}DR~NBh>K zZpn1@Yu`SM-PmC($O11Xn-3wNY_sq;Qhwgj%V%5J52lXflF#`b${x&Y^zh&WL}`3BcTeu7fBF-cJW*P%nwPfGt zore+de#qR^SI1aQQA5=s-sB$w#kZ|U@3#`aVj$|X(H~7qhQxZGJMeQqVNBZp zik?pqJ}eaEz_K}QoJPj^2t5Z~UWPo6wX9{Jnb{I-cLR(l@>u$!y3 zGo*2Fzy87U+|#Ak?Pnilh?Ulo;P2QDuL^u_QAu%M$3nXwsPpodHypHks_ni{?BL7M zx9*0jHG1kR7})}ffLI*6;m7TdM1Qz+q%ex7EafjPeB0RP--muguxo)G-VD2AZAmZd zrlnf0S!+Mj+G^^eLK`2YvF~zJ1;&o_U=nSkXcel;){1%k3g#M;*yypa9NQB^1l+kZ zM<~Br58ml3b(TVLjf8?K-EVdG4Tk-`NAQnD>Jvi}ZJUZGHG9EBLRlF6fHA9u@k(FI zvfKKa4i8h(r}Oec>61g$nD}s9%8@Ya^UhS!lZBp4qK*EAdT!yuk8Lomn?lyUbb1y;!&KPrPy;ZV_&p0un7YiIZ&t-U^)Nr#a!XrgT+ zdJN%?NqD9k;;5O{EqLEvMSAG5F3kPL5&}*@%8V;na2YyEt9wwMh0dhl5G0z>nRCIj zU9u4Rw_C$YRBph{wduiHI7YR;SR%)52uijDB5y%He|3tBBrQQ$H0sHins4B5uvb%E zF19ta-H!Q928dE5=a*7*gj)(XKNTGUWXsMUZkf1}SN3dKMg(=tki(RS!l>Q%k28^= zWU&T*bexE-%&>N3Mrx<{CG8WFd8MvrO!S2GcL(gWi1%3?lLqsHOCp2q05^%A8H6KN zncbkhuJKx>Zw?~9y4rMuTF02gRToa((uAD;%wxIbSNvZ!*X`A?$xK{>xkZF{k2wMo z4OdQHp-v`D9-Td?C%G%y9TK!}#?hvX3uQN54_W#*obYM7Qly7o69S#PDQKc3`(;m+ zxEqnWsksY%WaA7x)T68n_{AqTo+!gW%6?UJDNl8x3n2nyzy-)Z@SbSS8R-`^fAyhL z8bEA5<5k9rwJ^xt)TF#QCheV;DB&=$<$o0xdSEXR()f5BxT|V=Y|N$E^v~KlGHL z9_6kYQ6X_^?%T{~K-V(R*oW1DwCnn-scXBbe&0_&oI9f(23DgF#y4!GL@ZDnrYm$v zUep3$9_EL--I%h8fx}I%nUz!|E6UJ`CC~<2Uk9J3Z3dI~mJ1X-O0@P;#ni>pu~5L8 z`Fa|PsUd{@R!eA4#aT?r>dr2g*0%fXG$e``fsNqW<)&{n==03rI#uHsWL|Y$0H>8T>(krnm5K2i&I`_YdIj6`;?_Ih*C5?#5C~vwnyhwBMwA>p zlu|-)N10#m`(@ZV(oR51Ha%=y!ztN|+EYJeH`-EwxjGMAd2U5Q$?$fTqK+yM0BXY= z-*xvW6UEQ>MvC)@SjfUAx|p+jYU3)@Q}cI~koQ+T8-|g^Q;J*P&v$%2{w(}IiwOvx z+GiXhkivOFzWFxP>M->0b0mf`glM3%n$`_JeHe+wK?M2)C>clY@F?1_LL;*=|H^E~ zq5sK23Y5hy`~jdIWSXaeB+VIp!*1U00OEg>#LWLZT! zh>)vVi`Dp^I75+hDR*2x2FH%JJ0Ex>L$L7F8x->B;{;#8JkiUdzw0fpE6h6}BBbAz z!#fpG@!UX~F7Q7V5DBvO-z;VHUKKxq2VgWWble=jnU=40fa(Vxx>n;ZU3&^lCH2dD zl--Y43&WueXIJ~do$L`O+{-G;#Xzz0gFbH2iO(UUSd6y90cd_-re88eV2~rA@?r;# zx@!x8L_it}!n6xmk%zL(n($#JCCMAu%W5$Q4 z4eb4J^IMm>O(9w57kt8}tO7_VLDr{^FM>^H+(spJrj6RQy3qAV3qI!EPampIWlP(` z4~m+xs(VVA-%c>OeubIQc~ttrv~wREygL#d3~ewiKQ;p#_?7|p<7v-F7(apYLy^~g zhAiy92wATGhKk#)5TiNJ?Ckn?7flr-G`uK-=<)5kQ5dqFmR=f>#nZI zL$6_o^Kj^3Ah5~cBctusN7Pz`hZI<&2w;uKca2|Bgc2pZk&PirSDIz`i3KZm1=8`7 zsUZN>EbWQF#9=Rku`nZ*?P#$3<&1rfvoLjsQbCZXChObRUkWf;!-O_=R;<;rj^fnA zGJ_?!8tS$)u^{*eD1`- zL*VTs%G~59dDiOh#iWc2u)SIFo$6Ey^Yx>uAe}PnrH=y|2ThgU>Q1)sE`{RG0RR0d zdxtr=2W$c}gyiL35lbI0r8;g1jlzhHN4+I0j>UQVi%3u6o4{Yozm@r8#W{r|5+Dqg zZ)y7^E^{@G*e9;17%sjKpwbWvA_fMT@>5ugY_TI+*H7bQRtVN5V(bRe;3I<+MNb8bf6i|-pe+5*`TZxeB?tgSC51z& zu!bu4vj77q%kX~+0F4IFMafw;rJH`AMNa%_W`9q4KVY8G0Hjh= z-I}Ht&>wL>^K=&e|Kfi3hMVwjwD{jB(I-mEpH}g={GgbafkzTkNDr~?kLJQO)fHr$ z|EL1R{<9+L-QgXZ(72?(G#Jrf6o6?m*r1m=zpaO{bOMHUnPIB zp#Bw`?0?4UFZRE?@)?rsUp#-aXVd)~{hR$y)Up4U{SV70`=>|q|H*Fu-#o~l&ddKs z|Fntzm$UN!%bxQ$`{&-W|C7Dpzj;2{oBkWc{A;J!A9j#OOuw@Ks0Wn$Z~i|9vwvy+ zAKg6to9T}hKKWn%jS_yMpVI$h+WHUmf5z`~T>m^l{}1*o?*Hcb9BtnJMnA{(pXc8H zX8&9B|C)pU`>N6ZH_zX)XBqxC`pN#EDfZ|5zmI>entvw2|HA*)OjhB)dH(3&Q}*J2 zqkr1`WdCOZ{D=CFX8w`=Pp;g5X(s1yo}+*B5dMw+_Z5$T_SY5vClcPLhzLmv?&|3; zbTrKT-H(y&4#TXO55TvB9*vUpKRJA~3Au(?X_W#OyBi+s^P6L*=H)JEVuY5tz8s-#`o_PWTpt%;*?$JUYh>;2 zhz94B-c})Q1$JGD@w{lI?2SY^DHnpyCM7lt(UGQ z`bE{#)3SYXV`oX17|0BTXE3r9_qEtN4pRqQQ?dJ(Cx}?1NyGL=`kbBi80J#Q4wh}x zaQR!f`pZteSI*2fHpcpFSa6*{Erk_q2#lh)VL7O$XNUK59qZk3QjO6_E3;$<-aaWk zJr$^AAqK9U3K$qDfTl>Bdy@vPOonaH?tKNq@gd^9octI0DntiC34d+!Y+Q`5EsGjb z9VLc#s=%!5ZO;@vxQrJR!fxp0Z9(r-?U%PN;NYb1F+n&zxvbVu^370z6ABO+G~B@B zhc@%r@122O*Y%7mf~c=DfG#HCm#{YqDO#onrn;N+nBSy|9Xto$xJdg=dP(cAbr8ZK z4JKb>MQy0I?K~K~fieSF9Ji8X-Kq)K1tXvj-cRfO#DN#!7EYTXxnWv}sR-nr(mRU^zX6 zUBfNvz595BXC#PIJkQKai*i(#x*xF^%iePBxEw@=bol;e$Nr}MUAiP8@C#~MAaQ*# z@EEm1oDWu0Myf;{7mG;=I4Ja)c4$gzKI(pckxT~b$qHzqSwjp_Kps0hFV2zSe3Z>^ z$0Gh83|c&xE^j%P;CK0vwo2UYiQvJETMb+s#}BJh7xh2khB4m>Mc~N6QZirw5u~3 zGR^*ST@fkV#=0mvTd#vB6myU37?4QR-Fh6iJLNjHuhcjW`su*?STV?$F=^(oV3wPf z-;I#z7N=k;_sjkW{3dUZ=}s2dT}E_SR|tW9q+to%4=h}QYH(}P7xD22a&i&a<}GQ| z`!-9=4`QN&WjK0*IU@ZGHpHt^ZZQrdbDLUJWAbZ*WRCAi$}<~SWU(M9SRyj(QNzBQY1+)XE5?$IBV`j%o@GnCH95h*qte6sHN$Fy)r~zZWG%yMgAzp- zSH$*ovg9*~Rk6ObE%K$dqsyv)JIRPggVE-MP%&H=-^1g$xd)axWM6tU9^c3j<(;`w z?0`ghRP1Tf_MwP#@R`S3CG;&Y?Y*zjqn}gzd3Yx{(xzEE-eTo#HyE){ck0hVCZFU; zjlXPb(=}h9ne1!&_KQAD$Hg$7HxlAQ|6#=o#XmW-Oh``QLS})6)erHf=N+7EAda0I zc~6STZisN)O|g8>aQ1*YV>+V95c&*X4Bdcv`$xIU=1&bhrW9JXe3*^1byzBEo$~ zgB&HpPI3QKd1Sno45Ihyqa|_yhG>!Z#o!^&Stjtv0<@!*bgkOZ^9pYlK1V9W(&2~QR03kGd$*{EO zpX%DowqhOCb|8`<=19-zoD~uaS@VhK)x65k3&%TB8Md*re`oubDHH`%$T#2hEjt;ba0j%Q z&FiGqDCOwIW;-rfJY)Hw?_nsu*g%LyK~xd1gMnD4lKs(=dT3qKTdlA10fb&T?=Ud- zm&BFA(CXNbtyVWz2vD|n7M>f3;f5-K0h4SPzx8rlXxIxwJ4!UIKYHN%(nz*D->LgS z^DP}L!#Ixy5$=Iwc{P)uhbmZCIYE^OC2tHaH`i`4(nI^2uJU%#zij76SaSFne58*G zkkMyu5>nSHG*f0193^Av!raw!$!#z{#+THAlISF2uL52_q73$=*+;HB;O(I%ogSYO z+1Y~p(mAv^5eyeKz^u0xgU7h2IDhyb^0jrV*Fl~w562gMp{^PmcV8Ue6-z^fGY?*Mdgxmw^3ivrKk*Y?-fUu@J0-wcR=LjWCsV&WiFzc>#J7y9g(i4i(z6l%z5pHJM z7*h<3A=dv)gr+5czx1)xEOQpQ?(7HVh~2#+>i!`mFYYual|Aq5BvK;L1Eoa_8Het^ zzhH%?Aeqlu3w?5dH%~safTLOdsPCb zjb+sJv1Pkl4tT`PW4~~6S9z6f zK5y5Z$anbrlon-}TXmgz{e!{WNAzE8q=OfX=Wo+_4aACQmWSlj7hY|5Vyi8$iFlYr zh-(YWTxAeU^Bnjdd}Zr{InU*i zpdAwBHWio5KIr|TfRip~xY5qVmA5xkeCJxuv3Hu2!rG(Q$3ks(BnXeHk+{SvPRmi# z7ndyNS59O}Cv~mev91Nmgo$nOO03a5g?MM)1Ik-lw^`5etFq$lIUh(ERn5Kxtbncx z!a5Iis3L*)vJJP~|B#H`X$}4Hd}`Y<-}^f(B}w@p59fygRo(MbQjKv`tafspO%cS> znT4T-+fL}Q;#~m3nJKfkKU^8_6EV-%xosLWj$Y(Ywu0bTxvSYTd$q$69_$A!VQ66& z-Ok(6G-uoIk~&b-etMA&TZUgFkfEwHx*5551JrFDu3ZFd`3hR4qPB3u;+uTG`)zJe zf~`X^dHJ5G`8+SI)6zW~yO3Ru3_WeOv!CA)cMW96>Ye%)TLi7QJF@VlVu4wNATiyLwZwi@0w*NSH^fQ)?z#gBB@jb#0Z!DT$HLcI7E z@h!~|4%)ltcU!Nc4R@G$?T#}S>qC^A5qaD3hk<%Mpn6h48n>t|=Y>-z8=3?b>cywpH4`9b!ucb?fHpH zj~}9hDZh&uoGBCK-APVDBd>&8RBn%+`GU{|5rRe@upgiAikc$~xHOcipBj$JVu4hP zB$Xi|H+8>ZX+5WfT)oKI`OWkq@NbJF8usQ``RJ9EL`>1a+PRk`BWX-+Lo_^!<*P#c z%K&ze-{FG>u1m8{izN`fR--|Sb=079c3i=R7)gB+QQ0Nu3#A*}!pcMf$9oRz8>}LW z7Fr`w1~RRkJJTDgSVY`k4>)r*Uu4(5kz>;C(>LB&kZ8Z%T6h7KYH^dYd7XBd?O=87 zRI0aN*sd1p63t370?MN=560a&OA?#U)33OQ*bsXsd`XUhxiR*#JYQ=Rr`}uvJ>3f3|wN`5J)xJM)huP8l~9L+dx5&n5FW4fre@={QZsC z-m}@Zl*HF(gdLnTD}KtTpbj?yo_}-`tR^o)cakveX&XwpGUD9?#eUlaT<|?Oe@6)N zc4m7XFy$qDX^~RNjh-;YZ3-Lw{vjASP#Lv}?Jb2Yr&?>4i{5n}Iq69NgBizXP}SJ= zN^k570F;C6b1nFHzbZV)4T->1JGRZ8F1XSGjj#@GM0E|Gi&qyLXb z9)RflJ;@gU!0MsA6jmd^{X;k+W<>XAZSU|`9Qw}ybDxYLAjD%(@Tw*32LeXPXtt4j_aDc>06p!gM``#3$C-$bth698pMuH?y zG^BVkUd(_HO#y91dv^l=!C#8CA0xqi6i_n|f4Tq-_1P-UKk@Va0N7rUzF^8LYQmb` zpMQbNKZ~(GgXVq4#``QJTT>uT>bmQJ{PyP`iT-EdXGFcvz=>OJ>20;V|0c%)l9lmQLmNHX2O-kb5j!6iorc0xmVb#`*9tt z;!st~0;nby2BW*h+6I0%iNZPufnCK{_ZVQi)>krPKb5OrgygY7_FkHj{^L1`|CdkZ z=SHy4PNI+RZi33{Yo2z~oqYk@r~yR#{jH6L|JlLyk2c^B|1S7nPM3eH>8}C<{`8jr zu>k_9{S>5(pNr(*cOK;wUqveW?K{E{At#L)`!Ow3yy_u>^Z{BdaJ{$-CJ-a7q~s8c z5UXcH?k+vEZWClJC-D|9SOn^_jhyI^ogNQ$g{1uAyZ0`3ccZI+r`mnxH=W)MjY<9{b`V zRYb%J{%V(*Ry`IL<787g<`%c(7hc{_JHYV!hgCyjz`PplYx0l-Q;rt{nNZ7+9o<(Xl{n}dKX6Z%WvV`6hlIJ2rg5@12c@~^q&)ZY9$@w*6 z_ejYlz@ZP{}Q=vI=@8T zYr?}nL`~QXbXUHZl_f**Ko((kf_^I>qOWKrCiMgP42D{NM)}soswLdX27h9jG#aE- z$CR~jwX7svAwyzlXzhjj0L$`P#fwrrllb*oES~_Nr;#a3A2hpo%I7(0^^?9+C^Fv) zhPwOm4X%WrL8kQJnXy_@35GnmEEH@QB>u;^sI;|Om@Vb*#-r<6SB+>mI2LGQz!p(0?GsC6HK@9VK+FJr&NxI!jV&;K)Y1K!2H9uwRAL_V z(r8p1(+Q`SCB{bN*;%k`W2?`X8fKjK<@9kBeFO5$xI6_WLCq;>A{(7D9{$0SZ|-Bz z<)m3=K^q|Hm$j>rH4_4z3z}b0NmmPe`4!2>@Pv3QP87a#{_{mkRNXXg*!)L$sRT%x zp%;ez#CsF4sN8@bI}LUK`)lu@6Uw+2lB=G4LnK##Tb@(*Idzs|+iW{{9X5#x`8}h7 ziZ1^P9ppUkM|u`=Kab=nx|2u6@Vcijs2g#Lso@R4<7omYEEC4wEMV=pD`-Yd38jMM1rHGptJ#{Vb}s zwNmYPt#kD9T051lM@p(#F_%Zh{pSVYklx;KQ&A4d@{WY);WQdtBLDPe{xM+?!9DQ) zu!)w8QP8ABJZkRVO)Gwxe4z8vxjxxe#F0VH>}r5bO<2zO1=$vm-JOJa4DWjah}Y40 zYppv(KfPOCx0S({L4qR+W6qWm_KGB1t5GmhnMSMil@c;?`-w zv+;pRgzwckE_s1%n$@hYIAMo*O{#bmk@>gv4<%f0d$&Sy3iX9JC9cVwq{Dv37ddOS zhc$F>lqg9e<)9x!=B)P=k9K*djd1p|=aw-7FZtwX^{?Y0?S7Fw-VZb4B|hsOqKV{T z*j8Gg&)29NGhLtyGoT05a)q4@bnu-J;hZ_42!mpX);m;-dH(O}koQ8b51*-qM6Fip z6F}my5`|*o+s9Pv(=VgWcO-?%YK;mJD_Qn2-z^eZd`s4C=Yh274me$X=aajWzk>m# znaJP~GeI8aHCjmL%dyt`8eCJl;vo5<>}3!6VTceox+zW9SR26cQAjN;3r~=a7yPV} z&SL!b=Duc6NLI_$KHE^!I`$^cLZ*F6CMphT%{R{L+$wL-Ih~Sdf7F{4ibu@|UxMg( zHp!soQcUppRo>H}^H~YAG(GW={7cKC_StER@_craaWVvq@Fi#j}2ES{|IWJJkN3-B!If~egs zVwCsbYLE@ZAV@#XtT!@lx|V$}6=hkNSj8$b#5xMs#L}lnFrexwvyswiOGinxjl4vn z7sMU;J5s;CFi&qMMuG=BLH!(=zUi{u#m+2uT2HxO<@=ff$uv~Sk=yp8$R8B?z=S>c zNMACs{u?M^9!m8`s#|k(zS$DHr6;Gmw<)fspf?b>xLffahTD3)lX*H=*{rAsO^`PXPFT z(4UpK$DI4_1iyQV9|r0`-Zd-4@y|*E3Y8D#XIy(tTQ(BhH}3RG6I~!8P%-PjTxYiJ z)x>LwZoJ!6FQ9hK8joJ9d4JT}3qP2njXlwhGlp?0H>0g??1zjTK|}FudZ(q1e^6a> z3*3hl@1Ye&X^6`@liBj409hq9+oY(xt(fWYOL$JEz12hzG>j3bwpM-m477p9NgWk} z^IVB$>yb69bRGlStV!G;H-Hp&5QhMpZXL}-em8%!L%<7-S1cZGj?46f>nbgw)f^&* z9p9qaDJcz3vY2qdbhtq!`x2fxS|eT(?R-PdYVnn*V*Jamz8|}37)0RF6g^mzt;j}~ zD0V?HIym==CUEzn!vk-lBMe7|Wbk$BKxHQwQruhi;TiBME3Ri3_kG_E>G0L)Jq4^J zEgNLlor%cwsrv9&11;9PJDF|NUP4V4*_zyeVV(J$;Jw*i3Kzf36it;9m#jw|bwoQ? zUBucaEIF#uJyJ(>x{rz`?GWfO2^cj;_EAHtU+&6@qbEtrZSxIcawXCQwMGGW4?M(5 z(DM0l9`L3%L^le_gf7-b1Eci0g~0Eg=UpX}+F|we%(U&Oz%=JZ`dNMrfx(G-{{}Mi z!|9i0@nY5d-VRRCs_J>13&A^-89PtMwg{IW6WM(P{f)P3$#P!$zCKrP?A7*?anU4L ziST0k)apo49&@9JmN$RqW2N zM=*yZPm=AZiz)I>Z;9FAhwe`?Hgy>W-?IGDxyWdE0yyPi6P-2sk^p8*6)Q zqNJB(&oD%Y$SUtyk5Sa#MsU{5<;lw?aE_4leZ$2%P$0p`R4n;%A zq`NviCXg!$tdVe4V{Fiflj9{$(R8kI4plQM^4mK1cr_DsLZKPachxs)rJa(?(hn9! z4Spa#a^1&XJvk#KK$^=YOp|LQ2$Nt&U9Yi7sH%v=W z=>#YE-0oE(l{I-J zLXgUF*9~0feuRTJU>FH_g%FM>9F$Ds?}XoL$(`o{zxjIX#5K~tY>Zp|?&weU+y?)a z*bv?FEoO3IRSnfFd#i$R8pArO2cBe~m`st-7pyGey39q-3Q7dp?3<=n5EIg#Wf++e z@id4#`g4hp9k6XBll5)NlycN_ic6^kQWfUvN|C>;i%HzAT?gYhh~@6=X84s>WSB!g zHCA|c%^c?;)vVFRHh$|Cj3}AE;YTlZA|44#jmhk=ao@ebY#arH=sxv`QkrJXMkt zcJ%#JuXrnh*z3;$^9fJmHoe>9&2Sic)B3Z(&0nVsBx>*oTtby-3tb=Yrd^n%KoNk4 z%49?~s3SztvI_>n?fUHb$}ruQhn)#GSmHAWA!?Td$DnEIc~7HMwCTXgVJ9QL;*8EK z%bGR1&BxQPIdRyu-brC`LEu05dut=ArrkY<_7)$?5^OvRVeE;mgyvQnn-^w=a7&og zzP3sC2ilin9)pB~N3mM#r%;|eRsykhE11uzirhB4_qBAg`Q79T4i-T% z=_M(-Qt=m3P?UNmsTg5!xBtv7J7v7T5x`%RMmv9xLT z*Gpj3!b++9Jy@_=LP_`O3Z6gy^4wev9HY>M36xO8K7LU8<%>ax2WFTpxj~ZqJQOZB zDM`?E2BwcsiO5{Y)0+oKS9=fr9gj#J(c{4_6~eNd(9Yhn`cGhk9oFw{Xrh_v@JOV& z)us|B94wBd`eM^>B>@^|eAUi(81^HL()gU>6iq^D-iZKw{QE=@V6FF1#|%FdZ)3CP z%qGF)TGV0$o>B&?a;P?1J*sqBf6u&GL1I)jOL}@4yDP<8N8`g(cfHnVRp~Du_5}kO ztO)OKkiMr+rnlw1Ez;g0&yGFHNlUL!xEZ4OiouZOhv>n8 zcQMD|s|JzX`+Nveb^WlPR}Hcy%M5$;x22L#Qxd!E*N^`M?dId@-=!Up>%vJ`RGvhWafuU!Gfy+^#rImIMziQpGv=6Yk<%x-R`!F<5b- zI2R=*v2}loxANK#JPd;dN>32zhZAf#5Bs|0LxcmusG?#Re~Y2i;rUkCCEc?OC!{@Z zPK$7fi2L%sOGq|I?nw|cqM<53#P7Bq=s*E4D3E5~l4l4?fG+f66*HZMyN{X@a#cVhQ9`oLQ5)Y zR?-Hq@5?HUL)gmBC|WZi#VR?O5i^qrHSVdM?aPATbX1k8r+O?om^ljyBzMj6 zLg+@a!DZva9~kqZ`Oq$-=Q20j^Tihcul*4cUiQnMg)fO}LaLSumd1=*TXa;-!8S4k zX1JB5EqYm0X5F>HP9p^QVVN?@`6n4%{2Nn<^h8SQ*1Hb#T>@}?lKQzOr-;36ciULG zYx{lG=p@_C1MS*Z#GRu7wD!4W%0&W8`L%}R#G_n!UfteMYkoYgC9|jO*Or#?b?PF3 z7<6k3T2YCP$!|im+6LJ~l7zw|DXOltgVCs@I`-(z-^C3PV9YfT?3avH(`L;yYm>sWRwV z^n<`+H-YRipgat9z|~8PSm)f6u7*X}CMGg_O-rkWLJqYRM>00ojqiN4>a~qv_{d;o zP%mLCxGsJ_qZM2tyy2GPj4 z_wm0L3{%SqJ4^npoiw@COP_pfU6w@tas6BMEA(D-gJSYa8$Qgf3eI~kjsq({ ziIX4p@c@elg(7ha;xm2fZb5bkSvhk9iL)dlCC|eGcX_8jRHFG-q?`s%lZKUknnp>< z$9vd~H9;2cm9M@YS$~mjJ^3k#V2C**YN_>2h#5@JgvqW_aTp2=b8D%A8VKGH&l z9lY)A`|quN%Ayp$u9az-cP&8~-X|L_IefVGu z)L$JnL$5>gb<9{o`8|eK&T5MYCusJ;W&TIdA-K8UY)@Phl_M?5W!fw)AF;hTx5X`BD=2hJBuimk(M04^cWbIcDd0V8(|WUioBs3|)X3tMkTLnr^*}I< zvQVYYB+PNAv4-RAnV58J82+%k|3hk}Ohv`)EH;KilkW$id<`k-v zE#I^@;<(Ok7wz>fSs0UtzSZ2T(1#WrH67b#qA)f%WFUA&xfMheuGCQ4wKzB}PDA3Z za!^EnPcS`_Q+?FU8jwG)l>L;*$I|dj?m07gl>01S<7Rnvm%U$z($@1@d(YvR1z~n| zG&9#c>HaGM-$v`$zBPT+UOk^bLG{2EA68bvwW7VRuSD}0uYs#c%}=s3l@dg=a;mK+ zNsiK?x?xI#W{WreJP87h2c zp9mZ{lnc9Ovws}C)}g$83rX<^@tI}-XoH#$;q(j2DihmgAGDbHk^b%KbsiPpg$+7^ z904g-uXwyL}r8 zxhyZHn0(-tR}PwxH6=>$v2ln69nPC2)nmntM2haLsAQH(km&|{xA*GcB|9$rEIBfD z>JP()STcb)4Z7dn^m7b-jg3G6o!=dHN%<&06iG{N;$GYRP&+zk3@WQz1;Ek;YQbJU+ z_En8*e{9W88J|yNGBB=lfV$v z8p=t#C#gr1D&JS+hC1GE(aa~K&m8(^X!2Na!@&El&xj$B38UfkX;(qG8p8p3w|iwq zM=NI=QE=fx-ilL{_Pa~}woqw!cA@25DF#~3PwVP;?d?W;>|S5%p0mWCW*}`VK4Uq? zOI6BUbw32LFuXZ69d)x{5=9zBc~bJXuOTd!vti$`g@1g!%u8>~>uIwJ+QfQ9LB3uJ zsZ749*}s?!`YH8cX)$Jib&#(!ziG#!i?&MDEm4p62T8tIv}XONG78fA64vQ48mU3u z!v8F3B1iB;F9LwkDbi1|d~xfUDw-h|ypz~blu=j7f{B6%`eFPw6d2NjeHzhJ0%e|2 zo*K?t{+!64vQYQSWNod;-O*;wjhZi}W$zb{ns*98+FDG!c1Xys<43@&Fefbb_cH;x zeW59trW$|1z*E8vC#14p00_%Xu{OncWSFB^k#l7ZsLU(zXSQ(l_XM@P-#k+&>u~h+ z_3Vnrm9&zAw>s`x61_pEbU)S5CZM?bsi5S>LIx+(cNrfPmQD4~`bovNStPxa)>EWb6rZxN21m~r!VBJ(w-XM^i#baCNR-#lzd|pU znjA29)RKSj8!$P?wN<8Dl6-gak_qf1VsZ(RC|V6U3UB5)-b&8!ufQcn2!3gRb6ELy z(P=H47B=lOnEkaOKo&7YpXd1pT4g%uK1J8dy5Qph&Y1MG z`{^5>2x%aa!o&Tk(aV=wT`7FC#9y?VFEHx&5OWrMNnU_%a;@*NXNC2l*K_6PWd9!k zK0v|0lL_c~^bSq~1-zKui6uUt#s zPmcoi=J0!w@oX_d8>+n3!;PJymiwYin~jUx?g(XQXa)rz>I6Ib@_enDGaiE9-kwP zjWM}%ff=^w-UUxW4}JGwi?iCOmWmo4TY#Xw&pWT<0Qp_qPk@5DF{5qiFrYlalY42c z*X##=qK@ZU2u-IBwt4&v4>Tn)jF&N1iMkn!t3UtO8>;|%Y=6rf8J~;uXF&8Kaz|5x zB8QzH^Dd(^7L%#^MegA=PW|qk0f-~RArf?IH`QJ`5Li$Bf%b}gte65wl|8ZXQU=R{ z&c8VoIL4Ph81h2{n+BEkZ$VM53N2575n%sU9(%=#eUuA_-8I zF-W&9$+PzNk{5%lySHp_A^pMTe8_U)w7wIRIG0<$;d}~--3rAqoXmw+mJFpSO2b{L zF*n{%xk-g8lod`z_lk&0Mc+GP?}$;t%=nfc|Ns2{w0gJY;Ow-1f-X%lxrdwwPElF$ zdXil~)DAH#s=Ra>0<3H55J{|yfS>LA=2XIk*a_m5A)ku;;M?~}D-3MJGbF}ZAoQTF z$&534px`&?brYQcCOvw&tXU{NBx_QA_vgR!1{9j`iZiVdV#i^@lKl1G96F>=&!4O1 zD_yk94MDwU!f+ws34V5FiL>b%e(NS9QTzJgN1vG_CMZBQDi^HiH(BF;83rI5n`S<~ z3|tCx3T*RQKkJBv1p1e@u;hLoNHaRU(NAejY~3JQx{cFfQIQ7_usPE3pEzkkhc&>3 zqKEa}Q$L3|X8Itp#xOgX3xE+oT%F*7+jN#=@-B~In;MErdU7t0i1|1d{1-oKl?*x2 z1|h_&v(h=EGkJfvoEMO8{WQA*pTx&PvMsv}Hezh#FLeC<3#|mC2hiOd#qVkz z3}G+)44KfIrJtrJ*V>=Z{6ERl&U0dG1f~GO-HlBIO$07yF!79h{UGKaynq3+AF;=e@0@ua)gj&u1lBP2#db`OC)4qW|b(L-Ofq?SPrIRU?sPT|MbfaQ$qo zm|xIc*8UKFv*1jzR5+c)Y63uCRS8OS(iho@8;5b@V@>U|T2Xq{N8!r?5;AewRQn4k z+3d1>;M*4!+ZYcbC#EPz42hNWE@X#8^#j;MXSE6J(ub+=a$e;i$>WBk^ggJhFS-9K z8mY!IxEK7MKhpvKMCx*rx3y7Rg)+sF=hJ3t`|T7HD^cjNHM*#v0fYC=Pz0MA{S!z0Faj`g(ju>>|LvyiYAuRs%MmcZ!X~aNmbwA zil}8979}#@9yzTN&fgKm_lbM1u7J1cDLIQy5f_bvTZQ%{8==+{q`qz(x-A77{wghl zZ%i|_%o1etC}5UtuP)Bx`ITSVLX!mM>L5;&#~cO z^~trGDs*EFxP`wlqPF$cjc3+LLB4}LW!Hz5)F;i5d~A;4@Xc-uk(WGTfw!R_?rJN_ zMaZuE?WNil?JkNiEED#(mX-0uX)z}UXl}zSi_jC@f@6Zl)J>E;ILN|8@ zq2H^Od*Kv*xX>MF-U47sPXLhhNDzN~hPUk9jp998bQUCcJj9)HN6=0w+(YzVg#Jg? z8h0R5*E4+iqgw>GoSYb!Gh`c0frgiTord#_j_jG4XJH;$4+*FaL~GMSa7fppjU5v} z)esLBPgZ~7{HwG%3O0D}1cTTm6SRG$O#i=W+1fIk$PVR$cB>0RoPG9x=&a#Lb%Qz! zkGNQ${6`01pNlZQmM+R74dkmkQ*jhZ)r1DwdnLqjpKBLQ9(>EjgH{3z&IX+F)zXOQG zYluvh%rh!I8V{jz+B28n@ZFT<*+^a%Gwho zRF@T5LDY(E8cJU8nEsWl5eD$@j1Q#nSZAvL*|r-FRq4u;&5v9 z5wS-}!DY2&2$y1a^cvlZ{i;w;%Q%0K^|d*Rjq^xe_kg$ehgpGC`FB_Tw;EII!nLR}ZAPwDKR9ajN?ZM-=$6@Hj z?er#{FIwE?nL3`7_Yjdm59l&9PEnhuL1+U5z?0aGvI!+5alu`AlY_>J53*hzAIuRI ztXGcvv!R#~+vj+TRnHLi9#r&-iPLeobqs1=WJ(9(c<>3~dnf1lmpIjzLYJE|B?!XR zMA8R*vob13Kw@UXn2Q(~Lz!_558lrh=X3+xOFGmpwxjhU6n^_kM+bt-w8js`53c!& zUk~ov4QQ{!_Z7I!7Zny>M;ljVAGv9-w0oQXQrac@1}2!9gPX~8Ng`$OoZ#h~>!Ej8 zAv2es7yjkk+Zlc>n&S zb;miCKL!qnhdb{|Pr!OG?gE>jr3BigJ)!H9_ybvzxwWM7A9OI*BYj6#o7FEvE>beJ zR3&?JV%#wQC#k5HK6%PtVYRQ^@JRc`^EvEi<9d9YpDBWeyS;c#x;&zbBgKA6IkUlox$irvE z5AnRhu`3eH>uPHb>5}2|oY_22qpcj2giC>abTk}@!aIG$SM)hD#9y&gvF zWHg(wdacpRejBc-sYdEnE^I7UVqfFP0RPRZK4Q+rLQcf1427%nWC{u^ktZ3(2Jcog zkB)R{Ftm*oq!H?#{{gvV@%zLlv!Yz$C3vv^zl=Rg{6&c_qSdUvv;%0VXQo@FScN(G zlcvzL%2-fREH#&lD%so9F*E1vSKP+Sj)F1+61F}50YSr6#HD$}bC*c2WZ%?pNQwek?xA%QhXzJwDbmU`#t^9wDO%B>YwMRjA{3D_}t=Ogfg@^90?LD%-HX zgg~6!`s$YlCv9Zwnp`n|&tHJL+JWs}08Egxk;q(6(pjc}SFBhOEzi2_{NBLrmX&4s zl!O9s`PRR!)thOquZfPc+sh1fV+o6<5BUyfzmH}Nq&|RE9S)E&X&YW{NCxT)Leq2{ zZ86Bf_&iABo=8;u&2{ttNXdt}$dDVe+L|eR*7a7$f#&36w0s!NN>|l+-Ym5ui20DE zo<`|etM3+I#FYP0l8>E$O#C>kmjAcF4b+VhL+PnX8ji@ zgILOtMGneJl1ky9dz4_Dy}fAAAbl%mr1XQ|CKbZf;oziVb|8^rhr0(-^URtJQg>v? zB*gnAh&we>K}ouD*X;lU_Yg|FX}zr#hzR3tr?6}qBc>9hP=mo{&*;)+o!I}V1S29n z_Orz)FofWX&&Kth)cZ#Gd#)vO!FVw-iFr8kNqBra(tYo)ZhAntMlzT;%TNev7d&uy z76LkOlaX1A7-JoEHd%F!~ z1$<(nib?Y7>~rcQ)2klrAkARz&;herV}lh`M)#`z-bJYMZzbOsKZdiLCdzU((-dW$ zxY3?OW0FfIx0d9HJf3%f2Pe~3&lM62^Rakw><}xJc|d&=0y&utcDQCUMFUg=LHgLf zU7AFb06QY+L2#F1Pl8gtB!jcCHB!9e?SMR5*4)rJfuze4arZ-jDSEC(eT8|HT(G1@ za?}M1t>s36@!Xv#Vux>Pz-#Vw<8$Sgdx=bK=y8mu37?WESLhX5FzIVx=FfY1knBU( zaG1k%Iz&PjA#ytuir0R-kxt<+$XDaLd?K%wP{8#&Br{ z>Z)HVQPue}zSrG5^`S7>&oae=c0atJ83yu$4-VIEcK<+Ft7XW|*DA*kpn3p6rQk*$ zeQDj@@_CGv2HdBma@m;r@X)YW=FU$2DkI@5Qjm zp&9znMA}+KPl89(psW!LIwqKZyL!d{W7JradKuVO{8Ut!x0jL`T6@8wfxA+7koa3u z)$=h{&4rq0oOyM;|8AEQRdAD^+B4h)bebX;F1j1%beAxitWcD0PWBY)F)nLZq z4u<;5VUHN2yS1{nUlW{>nN*HYcl>tqY`TZplA}by7?aTPhmBA*Jm;SeOT~l(SA}7s+CII-LlLzp6-l>0`V%rAuo9KN!mHhL#~F z<<*vEsKfsbp@eB9zWlQi)Sj+Lq|awyptnKWl59dD^yMEb=6eVZiB8({*%yiLmT#|C|Ual?vNcT)>C{{+UWT`@U(2M$-=_I%A&CI({1b3`9>&6~>Yo9lM6ojUx>2zn%|MXXS%Q^3JbxRz^dBwrk*d$^AzRR{QoB;a_ z3Nhb@*=eIsH5TqN&R7qIg07zg)ireg^WXa~M=n~R{O5zkkw=I|num!Xu`x_l_i%lor)34@+}T zO&$=-GRKJ?EoB@{Q)GREtuh*NY>LVqGe)qg8!`qNo-H0dNji{uB04xa0zcs5P%sM` z3kx&;1#)Jih#pv6^QeDSeQbs)?MPo$+sq&DRnYP26%6Fd>qD0H?P%Ny?p zW<=zn9uh}#4uR0$+1n@}4%KYt6CTIisMt+Ikmb-@gh(PCWwNl zRf@y`X&ye{oZM|x_NOz((cQ(#K)YcquU;cE?On;S>6yi(G{ug}YekCwge{`UC4zVN z#R5>IIicYiCr;_wza3ABXC4ZK(IvfZt^-If^@l!e21Wk%m%^2c{R6=IYR;O}pePeU{{WNd_w# zyHVvDbYWVpQ|@*d2cc?E$TCfg6LkS3@H>-zaQyqmCh&GHcJ%;u{}B|^I;<D{ybPKhhZc{@M-7eO5FL|7Lu7A-#%gfidc|H~80G{0NMnr#F zUf?EEjqp* zv+^LE3y4dLgY&DutRzVPD6@})=}Bpn`U}6iuo&rh2ONQ$Gv79K;6{d}S73Q$P&v{% zcza#&*H-*lO)k>JANx2~$KB2dcn?XAs|kocSLJ z`|1vA*shUh_m4c`Aam66C^TB(&imzDXUWn`9^LEL7Wnj&*^WKV3X~pDCDC=o6!%Gx zZPaxjeG^}~2UOvb3ygS3V~*aX+78wu{oMVzD%auM)nd$0ti!)z{0tKv%%CA)aGnZJ zo=8ds>~(7cx6ZDO)ks5bp((sKl~bzzS6L#VuYP{j9l~*yws=zcKOCgqR%nU6)ignn z#Iz+Q6&A7bGw)#Ua_xdZ9PE3%;1}DBh*-HIcuIt5qqJTzfVDy5B9ck z_BfbJL|5o=f+?6By9Uc3Ymn@Ujsy%BxX=IAOuFzz030IFJqXW7X%InG|-g~F2DQOaj=HX_hnZ`TtOenB}Y5VZ3lV9qdgp# z%FWn@)5a|+D$ft6Z=)&ONlTK1(!`f;j(Cd+a)@wW|C$HA>NTRQdKUBxty!>OY=olMvD zHdEnGI-$^OR8&5SJ7NaNdA<16?@t&QMvxU&ciNHy$1u?9nuy%SN&mso{Ukaviy#SA zad5@{=f+v!in~JsC5!YpDTl82G_c)(PQ|X}ZoSGhh`eUE zu7c-fSK?b2=t7h7HCNXUb0}#lc9?I?i@H^IOF?P9w5}c<+9SRw&8nBO0frI^=fv)(+O@O{PMY8e9eLSX&J_Oa60r zI&^6=^RGTcmuFS0z#cfFNb2%{bI}6OV1)+00OhH!C<~s>0vw#2czTr#~A%!gYtp-U$xPQ=?d=n5GiXlBv-W_O> z#H~2IwbuLm(nSNJeCV0`-Ib(2F#rCO9u``Ay_PM%g5`}F2z?@KfHn>&K}`B~^&8nZ zdCzHk6e#nR)@9yw5fR|@4(F$4f5BWYDk(1h7_OD+!Onp5eibXu)i@QZMsYAf zUO~icpYUo#9*?9LY3|0=rLbGT>lREYvy8uA$=NB2d0>Q)Aq4zPgp$%Nw&B%LiFBh5$iZ z=?2g0wxFk08-(g_x(#e9Epspb{qZ`)TlyokF$QXDC%@>-`I#!n3Mth|*Tz0zq&fb< zBAN@Y8wUOAVON8iPamnFK4unIQ4YPXuJT6qCrkyS`s?k5Y)Q6l*2VMCX)ZM4-apf3 z?wU1uvYxyHr0yWVZ3Jp(K5ghddlltM9oV}D7TT~9FwIRTZy5O*C+mrvPGrV89_v$D zS|mK|D7lRI^QRz`hx3*#Jv>M0QM()`VJwqhwXF zi7bo2jUf%>Dfao_&Ztb*$ulV}91bNszmqm`WONzm2f})Pt4!iPlao=pTu$Au2!%r= zw{BP$f`pvk2@0Aa@^!ZjOT6$0%4KFPL4@9wVi5FJj(LYZJ^3BNd-fYj}oKf+p#vWf8bYH&0iD59mZo~G=f!GHMH zoA3S>S=&E_&4t%kZO&YxYQEqR^WeUfGG%I|$Wc6dQ57qgRK24ZoGjy2rhI_ScM;d9 z;}$IN057PVZ(73LzKKP004nu!N{J^Tx08qS-8=i=8TI~!pWxZ;`Pi#$K=wLT0LRETvq7{yVU8QQBF_g_K#6;+kuh=9zhX2-C`$r9v$06R3Jhb8ax04)(^hQi?wv>`bkp-lcsJ z5flQcPylAFCd$~$ajMH8?YnS_u2{I;Z@3mAWuQ9fGZ*FzsMe=q$bRIYDR>FjAwRaK zmJTr11dCuEd$pn+uxZ%1?(C@oyFD%kghjHa{&qX+PU+e>WYTwO#gI)4HZ)X{d}YUS zWwd8r_9vQc%oJ{zd9PSiTDfMCxoC~;JP~q~XFst=2m&Aj0?LgU`4@`Dl!y6%44poz zr!kXf$5C2`Cz`M!+GM8H$I4o|8}9&}lzL3}BAY+L`TR!m!s^11o<3?UKB;YIxZdEL z$`SES8bp4&w%tEmh{JpP$9PwW*>{jA1g)@E!k`Ft$>tv}4=G%WuXI&ji21y(4(mx4 z!nLNA)>)0@JY62!`wHYfg~Kfifbvbn_MQ8Rcy@L(AUqSUkPK^^Pg$rj8>*2FV0l=0 z^&1U+21COk@C#m`8Vma;R{cYpw($t%8@6Y*fgB4&-4xFukh;uKr^(kRr(aa_+5BBOnGijTC@K+eRfW#K?GDFr8COU* z-CgXPQiXJEm$SE=aM9=C)6ZN_GvdTeDSLUvB-k!(dfQis0u22jaT}gHHr#;Z_r51w z>}9TBgimR6csHkpb#`~ zE}|YTEa@~p6cp^#PK-vMQ)vH>)PGm}bX^Y+z<%kGgbD#N_-Bl}2PC%4Fx0oiiAxyI zdQ6FlfI~yN5}dPTutsRU@C(BIPJ*FkEN1g#4Z1y#Ptxg2hRsqn$fYNNPV+%Te+1oQ zCX;fXj_2TDe@$nhlBN$Ehs{b(hkjVE$dp%cj^FlNN&)hu+Zj=7Btg65>Rw(U;v48tf4v6KfU=KDN-%^a_l*dn^&8n*m znufwdh*Ahz(&?05+~xE-FZ#7kp>+Y7>OhW9VGe2|M{+Kucpt9qRAHi^k*@<<1$sw@ zZUY;$fmVCT#HD|sFK6;`cm{09FoWSNS;?@y$PLbXV!cc7wyb_`PvSZg9letTTnzz` z2((1_HQ^aCN<&4(%lvmf(q>jv%Nu``>89ovGj)L<-tBrdTjr7^Mu^w@%$^0V4bg01 z_(JSA;&i^0fkIH`IvRMO#8hq3fSNp>THz0oWVOyORkxQb)4emHXO8xEy2uO5Hn~#(QyyhV$kxuf~ zDaY8b(&080dD9BPMtGr%XD^ztlccqrVT|V5f6y6P*e9!_)r))BFi`x#uzVsrkdTP! z_&xYvMvtaXd+AYF$IXOma?qZwT5QdJ1)YX33Id%4Q^$$&>df9g-r0SvZ5$Sw321Ii#Pjf} z9Uf*f4|voyQu1_2+Zy^-ME%-%jxN(S^7t)G+@Yjou)%;0+Sr`rYcruj)W5nZhO$6p zUTvd#dLQTmxIaMTr$rg5m!k4X* z8qQ;>8fB9P5&J+Tw$aF`RMm3^Bp7w!9C~TTey5r~n5l@xGe$xAW)JM*omG~F2DfXPOda*zhO7hdS9z5aFBQx)12%tgU){eH#ulM^~N6)hM+IrBZG zOVlblJbfA6&D(O7;-QDXCdutdUeb-O=IyNkUgVS&*|;<6Z3bp&I8dkmUK>i)Cz-rp zkn*?x{HLZBmNdZfZ(KU{*{$`I+z$nfs-Kh;`t|tg#NT##Xp(;Su7HIrB{ynA7!szl z|8*rNc#8+3yMe)k-zQ%4XM(?}Oj5or(dKnUZ>+tn+o4Jm760G)8rN=6_a6={P(3V; z-MT{}z1Srkum3JZfl-C&VNsM^7EJ)msC!HWLZB@)LkiYlN`a{`Fs?|y`VFPX{Bm*F zUv21ZnEQ-Zssq<$ztmz&{F3|3cFl|i0(x44sRscIp;%tqOL?u*dYMUCSp%;fNW7p( zy0Wr+2Rc{z^c2pbYnV8McteFw=#&z zKn=>H*u}$Ye(R(A+IUHD4hjpX2S__ySt@ReQH8oDD5naXqky%YRBNg0da0)&a8uWU znN2)1!9D*4l?djgLKw7Kb(8R3vmSKh4CwJu-9eGp<}>W`)G>FK&_0v@<;eJ^l1nuX z--gXCJn!{8iKbtZ6|g7(0DYT<)>Ddv{vL{Pl!8KkmH|t^_wNO1|B{P+m8W9(fB*O{ zKPn4s*?G`=0aZp*=E(oz-PbGrBzKEZImpexecdJFD5w0%1w*ssUs_K#GqOmN0mR>` zLt^Nf4(F1n&6oL3n5xJ|govyjm(IA%L^XfG11f&b{-AODOv`49Ob4scey>vZK|K}_ z>og6`vO8;ZBnXE`r>%eS#VggoTFJEYT}@|6CV66|m==0mBdxi|$#{kSaH66;%^I&v zMK9L*VOvoCXDa$T8gnXH)romL*lM(lEs`Bkn&3)+&qn}|Oa84Oi>}0$_YU>?9_HYE zu+d`-QwW6P0dCA}Vy**6yhX}L()*C$ngbMqK#vIVTgEDxX9!yK zGU*O@wBA(>Cy(>&YDzI9jwRNGn+7ud9G}c&W{u0=BzL~FiG1yvp>p8q-$NTunf4Ah zGIeWOrcEnI3HQRc+8jzzZvI4L`OJl=w34*mDoR=>u)0fcPr;x40BYRq9~qC4@mj(q z<)lJQP)F3=`eypcAaOt@jXq&LW0DOt-;jC@Qt~r%(x0PqW7w^_Mg^o+bm{exy6u(90;eMqv8Ux9-4*Gv= z)~l<|Eo|*_jl8OQyv8*XYP&IN)gIQnD!7$IDi};&9Ifb1Z5IOVb@dOpT_@ruljt^> ziAKptBkzB*a`H=13=01%0eAWJrEX{^g*W3Sx6vh)B!PvAKAW4kbvDmbaR&WvMTar7 zl_j5rq;s<)Z>WxH{`L*6;HikmDhI9*|0o)UAKYfIrTPG6J1yO5Lbn<_|F)|;F%!vh z2@|{gHPLlE9b5xBFmKlDx)Z$(zv!(DHk(dM3G}iq^xx5m;r*YKJbz$K-PjV zDj9IPvUG2mOr7~9pRc-4H;+mIUGWc;|Ns9NkqL-s z<(6QN0Uae8*I*|ZGNMmUVw#Q6_;#c;%XTb-5To~OHXP@|LVJoeHksWrgG`B}z0VF( z4b4jb(#0PeWa57sI~2Ajwi$#8=TsYQ?7)bRSJd;r5V*_?6FV^Jpny*D@8t#p`|>6q zw|&m*7uN9`DA2rk{%Hm`wpJ3o?hbPGpQ0glE#PG3&Dam3YxfcPO`5jj9ugSjJ;4t) z!$>P&ZCo+lS23zch7$480r2ob!@o6RP5lWd{!;0?cC$#E9=4Y8<$@^{shCQf1v7zL zP_n>dEi3E#Irs(wUx;!D$3G+^-01W+57}Z7Py(hVq-h#y!|S;lLY^UK?>+{m>riyd)!q0^P4w@ck@H@f3Xo;gHvq`M|n#WW)EC8X-Rw(YP8Egf> zSn2IEKadO>;ADEARm9iUo;Z`x-|k9LqepQ&YAWXtwycb=2~Er*FyE}Mz^mWYpJAUa z1zgbJ02jl>ZfUrHG==5FCA?gM9GEPRezQzj21ZM=4l2!i6^vIz(7;Ap7{bUngt|MI zN$NB0I+Q|i`hK+|F715(`;RT5%2O15xn}*WvSQ4|>Y@8pgh{@36~fZ@no8g}DD+N+ zv14rPGzy)}tq+{2O(tB_77a$qtK>HAFJZ_EfqYozpE!eWfq5p051?zRdL%`g81+Dz zS}YnnN&k5+RkdES56q8oo`|OPcdwGSrGVhTM@whay|EPYZ@bwi=oBv3{2~aVR2Ri0 z?eE=vq@HT<4geIjhvOLwnx~>&jsjB2W(sMMKwQS69ys;H@$Aq0{wBZ{!|Q*J3*G5( zgnHBE;Xr~(12|vPRH6k=w}=fo=G15Kc}k6rNJY^D=OgjEYSyjTvVt6Q-i|BCVoWb> z+-iU!`mPKA+W|(6(CiI?sig^4o87N_`ho_?U^nZk8Jz7 z$g(7;KXR9Ep1e6r&LzE#d&aIqiV%sg{qC~i>Btx_ZV=ndOwyia6aHiOtpinF=KXWYgq$*VmO8X`$WkpZa6B|MT-MEM3aiXJRfZr#75AI(O$nzKGL!N9KkoADzm4 z02xUlLF%cAyKUY5eH1?icR6xKZDtjHPQqFhIk-T)?eohk@|dc~Mt@y^ig=|(Khi(l zVQ^^&2X&h??dcI;N`UuZT4ie{0--o@yiUdle3tMkR{Bn#@ukrqv?vu+ZsH_uLHSq@ z=h;;cs!adrIj^l4mkPA1A-lE-X;79wnt>a)?vn_#-)-IF7C{tybYROGqysa)<(tyP z*s0B*@{Q{aXLO?xh!2>OUlaWo4Orh)`WhF_gyzm^&7>&90Zr|Xac8ZvioWZK^U7!j|(UaDO==b*Vu;qq;WEV6p?;6TD`fHd`UC%V7{ zuOAA^rX1j3vmASQBg;<|pB~&d9P>$E3BD~jGS0LfKTCj1*X=2+17?mFooSeGA3@F& z&AyoEpaj^|Sd;O5@ZK6s+Jym!Nr|w2Hk{#+@XvdG2ls1gbuQ`ha?nY#7k0r9J}WIa z*1LUvxJtfASV0v+>SkVJvY^sY21~841-u=hiTQ5gt(wP9qz@=KR=Jm=RvJVrO|L?@ z=8?*Ybjg(j=YAW+GBXzal?B#_Wo5^*W=9$u@?~Loc~0 zic^fI=v06osUznH;}xTW{N{kWH8`@)loaHjWUSbnOGeTuM6_gP3kA*G$D__sh2{X? zx)|)hbN;X_L}E4Lz+7#adfX=tJe|Aagg?G9b+a{zA0&oLd|FY0JbR_rcdNOm5IPwd zy!%wFNn5(wK8jy9yEdKkZaz7HZgG4Ipz}28Da^DBrM}a_;aj`g~@uN0B8dJbV3Gojo+Eh134N^S^QfjcQ zfXU)k8p@BLntORKkoP`eTd3FRhM_6uz2j0xk|E^X&jR;R;zrEw3{1=??Mh-o;bP@O zIAhISI)5^0)FHqJANoo864*r(>S|KF?KD9A4dl1{k8n&bo%IQg659o`$=vfKk2Xrv z2JBcDE1uxUSMvW(Wq2XCiuI6aT0*KqBH5Tm^0AEAW-F&8Ic+*ZsMk`K^y}@htMJ3p zX`+2mou854&|uCcSPmu7&#>jId6KVq{xLJ2c+0;Dszo8Z0A4n@;w%+a+)T9a(&hLO z7{#xKv&_IDax}$ho~?CWV?%!g}pe@ zG1H~LWao8KNv&|y=8Otk;@#|nB;-(^Y2@6%VH`N$iUw4ZcHiN%;g!AU=& z;0GFE+uB*H)ng&6;Ucr8Sk(;Uuq^M3>WHKlisRMa| zG9bX%T_gW{P{sMo|4%z?H-%(ZO*eoZ#+U+>fPyL3D=fPCtq22uiyv>9Q^=FXQgLIL z=lpf$@=WMMlqLacUS%Gll@B=rs%2qo1crgQMBhsuOZAWLOhAnfoT`57yoK7QrQ+fj zqbyN=G^YnNru=pUVghJ%_I7@p_`McL)Jt4UfY$c9#JM`0Ngff`u*o-B|Q~(C=fj>T`Dq^15)E6B& zYxMqmGq@Z`z;vaM9~AM~w~TpS14m~6)tM8^g3DLx9qT}idNiGnCpxQ&Bz`LAu(Qxy z67eW+WuN3RQ8$m`mb@f-#XE?yCc!aS$}@&}WySX2$3;J=-Wmf7CwlfdKf0Dnm&|Fj z_d%9S5A#~ZU3^s@FPr`uUu=z zjzek0YJZUr6fkZ41Dd|Z?MxEP&b)6-U1QcEqST-+>AGK2!z8E&3e1NR=c1C>k|Sw& z?-TYmM4s|KOsdZ;7t^t52e{R+f2+ph_$t(K(O0LK^?i&;V!`DF}6QxnAT&d^?MnK`?Vi(|E8vv6U2&4O}%V)J(>jP>E~o`Rw^rR zpU2?KFTZQC%nCjE(9PQ*B`z8@lsz=*7m z=TtKoo+CX6)p^ieSfOC{WVIf_8cAt~nxbo&w%x|u|8~J%;oie4U@tsB=fiG>7MeC_ zS`n#&-0$KJD#D0Qgve02>ihYBIvz5Jy2>zs``LKScE_Fri~c=LG+L*lA))27pWuCY~)tue-eZ-FYVrOWM0NM%Fw|$4L{We zuXo6D`|;f!kpHvI)=hr*CN*zcM#(@ZqOagQ+Cy5jkE$PkmeCq&Dw#GcCeAVH#F_Xw zdPnn&p$X(9>!1I@E3vxvFYFQ&c8n33tF@0CA4`P7U zP%%MuCQ2#BMw-zq3MNMgfP3!!QRp^8tS&om?|))bHb4N&_BWCTZX{wLuZ#yR6}lV9i>N0t(UgeoZOq^QF3T)pzkFa3qwewC=c?1e2Uem zdwFAIxgR+?xKK{PGh=2GHn)D&q#^3N(Pmm_fy4l6Gpsjj1TN_}z+T``2%PjxGTMFS zO?LcKVtp zq-?=*@bZ_QEBk*gattv7+dz{C1ZaKR%h)LaVA`S2QfQ^gZ`F&CD`=0H(7 zmD}sZ`nTY;q7@nh@aFj_g$m)LG& zYj}w;N1=ZWXzSDVtV1EE0S1~??-G^F8^<9>)IzopYdpTvGLTRe)Qg~a0h_St|Jn%R zZZ$nsyUATH@l_)U(X))~S@h{wuJkg4Z@t`6!>h|?RG6qbgs-9wr-!Ns|OnI)}dc$p53f=-% z!+__UiBVD+s3q^eiRpiBkRP=#S%WmlOo{ZwcTAQ`Y5JH=M}sn&ycnpv#3^J(3Furk zdq#W?lC~ zLRF-i@FLwf(iPM$3dK=+m2vu@x9}OehSpEPUS{~GGscJ7N_Uem(k{L{t5VW zj^{n=PWp%@`oNz3$O?Rw{kY0~&htPxTbyYFpZX%0n%y-sW^n(mv^ICqO13ZcQ1LIo zVN~hlCllW}BKfv9Y2+&6M%Bo!TV|UGdB#te;HUaV4usoIniP{1vGx5AxGzlccu0*Q z+~-VnFR&*DSiZ1V>u?_=(-9PYxoB z!08sf>K_ZwguZlmK|wmXrRLpr2NWuD zC(y`8+dJvd(I$nlCmO(Q7K)BG`Tqn}PYx*MHvNvZ%q`hZ7Br1T;F4Bew+bZ{z)=ZQdX0Vl^k?n`sxJ zuS_KKi!&<(;hy8V34v=%h8feS$a)pRB)QBysbiM(QBJ=jxf{nj@jYd&!9AvcbCs&M z;zF5C6MppQJBq%y8ohSO+@IsxciP}m^wucpP4?)*6&S)&6DBDZ8E!%FEogLwWGGH8 z=5f}<5R?#ZxydQ_FGM4NR5(8qP1hH+etndxadl)k>zd^wpi=!;#*#x%-F=OYu6Jw$ z7^Mv-GCDugU_;Y#VRzHZEC*|Q)y~8q^OTR8OzVn5_$)U2&|%{%+VftfM$zK{`_Ahr z1HLN!J7H`2+s6&R!bU;dGJOJsWXY}Ht%=f(jLuimP)rwVX!PzAfyA<=3{WzRhvx`d3iE*rYmcn6t;DFKD%+cu>y|hNmD91wb36j1okn6o zV?byKy}=Hs!L5FP4GZsdpopXkN+}w>aVxN|j!^7Fbx-I($cuMm$HlEG+5cL<%R(!6 ze+=jF6g%FzDRm%@%pVzcPLO$+Vu=OiCVn0>;9hSPg0oDTgoc+tedWib3|f?Wb%z-oU9m(|?(U(%FX89!)# zfxuGxVRBEz<0)!~%2lt#-QRdVFu_39s9rf{JchiPEe`?D_(NZ3v`cem+|NhF(){B*@^-?O`y1>Z9|NiHs!qqbDOUlA!z|&AaDXIDT&nU9k z|I{s!;Pe`)idr6)=B)KI;*lium31PvdFIbWvjr=A{`!rs!bxV*t*RZh+pRTGT<$?rja2do`p*9 zm3oFYA&{l2EbDEg&C)~S%g%Dizj>h3egHq_f??UhFhp?Q&~LP@lFpW_&;T!Z@9sNN z30n!@z*uj|#hVCoB!rm!fQ1`JTj?5|1g^vn=9Lv|AR9R(B zV%K^&jtdx)Pq_`ki}K7H?&OMsF<^3U&Jv2xx3Z)`T3)V-F97o;-KN2uryvouyhQ8- zBrulEZx+rrdT%V4RUN92+|e#@Xg&DJO=i8>KH!yR%O^{_V27U-mY5;#)F#F=ljW`x zOd|gDvMRG)iu_KXCh2QlA?`%oW0NMq+BWL8J#E{zZQHhO+s3qe+O}=mwrx*$-+R_t z?-TnE)Q5_SjLN*uJP%ge6iK4Cy%5=az4nN`EZ2*H44(3Q6`e+bVSOjgPEv@uXW8mM zxAlX-k3I1#W$se|o{T{bU%1Y@J9~&7i90cnoR%}HdX%fw8{V%PsWW|)4F~>|+YlMF z>i|J5?^Y@bm=*VT=%*M zY>Pg$|HV`1=2!(!{u@tSMvL>(4rcY7#$jW|)%s#G21>`mfhcvu$pH;Zhze%<88%c3 zZK$phR^K!lin@T<_(;aaV7ot zQ);0PMaZTT$V8v6a47k{a7j{H!R5G3(xDz7wuu!#@;KiyCL=MIrZfLMP288G7W>lp zsj}yy9+v;KIn|+GCKA79xZjyHHro?AiWxI)c~8&&?PuPQ-@StOMKn+6Ff@Y_)xYcZ zv=)dd3#8~gG}VF2b7(Nha!uyvQK^XN^@lSK9xAJyUu{J0!H5BE1-LFBl6(fDM8NIrub5M73L#_+=1esM7LSaVSQpCZ+EKwS%dHr+ zQzq5aYM{TH=+7Q90Khj#ku;kjEwKa7m|9Rp2q7EVNnXc0EEj_m zuPjf}xkb!a!fB$3kC|~Strv<+{td0q`*Ycm2@e3PVOhW;KR9^ze#A67)qg9bD4T+4 z*@?~tDiLe|L85)=)zg0KGpHDLv0PUfCk*IK#eKXzrWySeroPThK{VRyQg5EjOG<}g zvd=A) z7Co_1B+WAPw)jcYK>8)P3y4`cf!4SpJzZbU{Y-}#bE3+he+fccFS?*Gv85w+2DOc_ z;(u)+7Dcn)9C}@|S@A!L7dwU?ZAu{knRk~p=6D(86FWD+4yoABrWj|m*<@{PPJAsH z_?^nwhe?u8)#2D7g~(U3!nf(#BM1%>lE1`OzCx_PTmQ?N-E>ro;P#(qlz*WQHT;GD zX;AD7t=0rS!AAX}1$$|^W16tH`Tjbt`1xk^{WF_Ln0NL^Coct8yiSE6epfGj0)BUC zLeioh`V?{upmtH51x}f0>=I}GMEpDbrxSjSVmQZGCAEUTR)szv%yf`_^@1^h&vm}6 zf{h$O((qSmpmO*VVuYn5bDugmWQj z4X|^4_%~II-FHMQU&k^mE#0qSr}Ks=7&B(_Q)z5a@YmzEfBT1Eb!X`!2Y-{%9CdcNMIlQLJ$?DIV4WVvD9d>5M!kVf z?8xTH!YN}I4!*xUhvH`d7d>X_eBs(!`15`>Mv+S|0J{W`Gs?(pL0BIBw9r_vDq!|D zB|q-8N!~R9dcMXvSdF2xfa+@#wOf}`^Ykrt=$tw-AC(bjj2D0FKHDAXoGM?50M`zI zT{yJK%KUB|QF-Sp5f#0B+kGFOuXmot*B-r|W!&(I5Rladq zW7W+%8dq41qa2fbFW62-@(cMmEAlm64}HOv+g-yomfi8e?IxNAcub$AW#9)NUNYR5 z#<2O7?4H{i(-oS8T~S914M0twI+hPOMS~cuqnK~D4#&Zv-rr`lGkG*WhVjaI$#oex z*z^P`WX2We$Mv0oqYzWG8$xFxJnZ+Sj{>FjMY+|*F{0vborqSn2f&2YQ>zCQ!;Vp3 zhgqW8!jt8?0DHiMZ!5aym^a``0i{Zx02{xu8taLgZy)W&GVHI}rn`LE1mTI+y{GkE$DuJ` z9TVy6o`2N`K!MTkR+Lg0h-Puhw01frdo}e(_%axLzMU0Q)Kza+!*!-hc8#~=c)`{? z>g*7rP4s_6{z;k~#CN=-a3?=wqul(RCc>^fbVA-T`taB>af>Ia{jn~n#aG=*J=sTo z*B>9DxL$_57isvce;c7mePEz_rSJX}_-w(n+-VIJQlp>q7G4O}anNZ_>YnaK(!|cl z@OTIXFEJ8sBZW(r8sv_K&dsiMvOC`S%BsPY(mZYh87HY|N$mTAZkeeDv5B3AMg~fw zim#SRTl`&XfN)blP_INY0PsYQSf{~xjeP(V7jvs)@+gc+Yvh)pKovTr(j=~Fa&;=| zlVCdh_Iv2GzNkire1Vgn5O$(D!@#=~qkp3NPga)Rx6b5_EH-u&n>;iEH0erUoWxS3 zUm>DPC8+2__>?a7g~JR17O+ZIGL%Gq+Kb<#Htj9~SFaRDS9Fatg7bd-npd!obob=z zfx@X43{)IxGPmRw=(S|3vtC!37Ek?(0Qm{BOti)>wkFi`5yIMOTCzPcN zAO(7@=0EHAM4)M{9lN6H3jf9u;CbLAdOHUeMAZSd%tvon+GO55 z9~5bKxM>WWKj=9ya6Z)#$XzO5szJP}-Q1ygD!i_o8nEbSlwF`ToxAAHPhgpG;0g8j zptA^jw|J$&6ueT>-Kp>(t@DZZa=<1~eew^M0i>G_+w)NpLF<`K9X#sB=bi_Z4$E)b zg*>kPH&ffi=5DtjsFx_}7?z$d<^T@#(w|w8@yiDOAue2N9>D-)U*TpoaYlQ$V#5*0 zVNyXzO}6dn6IAmPv|xI!?pkc;jpm}A^`faXt)$TTN?Fx>HzaY~1fNX1aTNyU3W#RF z*eCPaTtU0(sgb#_thdCAGA}8lzX6sGcs)fXCP$af+MPDyE|3Wu81}XG0OR?0Pf6ax zD!MPFkCEC6y)hlUb9X6FL_f#|77ZYC3BFOa%^>EqM+fg~vvhrU7q{K%?pU_x^IzqFD2hmsLN^cKTuFl#j1T=t(R znRA#LHL9w8f7XRtnMSV85;pBEiRHl;?0Uc}1d!=Q0uuuiJcC0&wOP*}yImrv0z+M8 zl)60>TQ5G3B`V$nf;BT0K~Z-cHpm}Jhv-gj_xDQuQ;dQndyNVJQj%ckC`;S4mWYaV z5#(g~S>zb|PCy~y$hrR2RaIs(c(p+0)6YghikK`i0+Z4aiiw|+P@IxanVhrx^n<66 zyX1;E4(?DE2P{D75$+x<&;qaC`!pvGtcne7eu$>v52%HC=5FxQ(<-u8+%OE5BW(=kFbCY-{=vUC-iu0^x6#K68g z7e&Sagc^af&eeV?7kKePttAm{Lswe76S&-hMp^tUsC?-1rU|&n;7&ien)Mj-=dV|y zQnU%Rx~x6VS_Zz`-O&gUS)snP$yowPnDe-ipnx^Ezv{ZPM^%?WMRmg;Ub1{Z_0c2I zgx}osyatgHskJ9wlf1t6`BT|#!al>KZWVHjiu z@|EO1WrZ%}F~d>NzQFei-EK+7uyyxZQ1QK?l!J4Mv?^(`9XY~~0u!t>M{`n}&LS7z z@}DoDVA(elYk^|y(*wb!e~~YrYTpU}$yG+n2+l7`Qr-|R0LSJgd>{92w4%3VR!WGAj;jNlFotqIULK(%Y!|I>w%mCP}03C!r+pSF{=P zbGgD)W4jo;bTNwR*EP9bP>P=_8!)~z0!C51iF+I^iF)@1Po2hIDq7)-Hdir3Z zJvQ3L91l_fQ$7tQPSpvYs4KyGcqaV*@KgO7(OeS5f zoydh{Tu{A{Fy0Sw$OZ))A<3L7+_>djPMHZ4xiQpyxWLUXjZa15RBl02d>xuCxE$zw z+EhWZs)9;2{Ad_x>OJ9S4`i333^g6}4Pmp79l?avymn^2neMFr0G6THGp68&opx%_ z>*c(CsKkelc2sGx^OPToa@J}cr004J0i~AVz5z$LJl4}~>c;~oe*6hTJ|TW&`N1DAO=!f5 zlNm#-@$k7p{vqLC&FX=Lm8p244{e+0XkSY%^2`4 z58{b{%lo0jmIH<+Ep}@0jEFsJJr|1hu(&`eE-@fuZ9878*9IX+F&?{<9PXKb6fBC3 z{3^~B-OXs}0VF>QzB*X@=mD3+yt+m6a1JN+O~_upGo7+Z9!2wSuJ_WqC^y!h@@?xn z8*p;|@9-Xvb0cXRDoA_`oY$v<1ga#AjfH3g{3Gbp2uikVjljnQ+{%+uTg-=Ng@NIj zN-=4xkC1@_4DKoZl#|3JXzqgCu6t+ z+Ll|0kIrCB!!Cx`r#qUxf%mkU`6ySSutn)BRfW-Ay35KD;PY+XztREJ(LMWI6-eE= z(KcqJ+gwmo+mZU@4@gQAJ?%Ah9c3meRRmmuDcASfP|90zY=TW7stAQ4EQt_QaEP)D zl+|vR&5BLt*dWPn4`VWJSX?gS*MxlA z6~j8ivw?`ps*pS2`9rL87xu?>R}E}^?zpe&DfqA$i;xt1Om<$G$o;~O5>1CT_+4?0 zp=ckh<`Opgx1>;wx^KIhvG1oFTL(2gz!VaJ4cU(&p=G90_3NexE1$a7Ll{sQG|xQ@ z4G_k2A?CyQcn&~reD>W9q}P!2^g}Mo{N}2_RJKK(9 ztOf^%HsL|YS6RgZiBTOu<`nz2bJwp^?FDiA2ekp%yn#h^kMDN5xCCQ-ut?2P;~x4R zg~|qAn^7b=161uGxRA*xm}kfa&Q7F%jx%sAg*wrtq8h4x)YD?9v?;+*#?+>tE~f7Jd&ul$#dHi2+@M4+L6T# zBU{4LrL%{}HhE88g?c-%pTo&!2aR16WX%GQM?(KJSH30lknwo^W;Eewyee&bq0eL? z-mpqL6iJFB`L(hGB7`V1KVRWZT+&&WjH`-_NX#dPp=k%*CZ0BHpqPqwEyk4khHzEi zQt;5Gz(gry@vS`DF=Be?$obO|@zQR`3@zp zJMiKjk!pFndE(_qlc$P+EnUA&v4=uY2{YF!>KSNZL^@o_HP}b7oL&JDLx3PTOPUK^ zSV)SUyN+$M>9uYD_~r}rGcnfi75m;0IKX+ZW71Qf?8w1Kh%tPT3a!qHdx*KeKjnw& zxf0nx5oExEo>s~W>lDBO%u_OS7>UryYkez*e4(RUi@@E!FjYb&ZqDwr`8c+U3m)4{ zM9xSi(!o6mjJY_jS-hGr%H%VD#- z<6k9998-^0Y7{sZyT$O?f$9G$XD$eA^v;M#Pb98Bo~ifq*|S;pq;lZ8*N)STnrazy~@QOLY zpC!VXw;iS`-x5g`FK?R}K+w(R+}87#7E#RyPpOKgs{L1m#y7y>00-P?1F^fJ+ z0Te_|?M5tX)$F}AUz=tl>|+1@ediLoAGXUq@!)PO$Wn&sCVm`g@UFtwjQ5CmLt(1aYhK*dCg=FsZp^FmIsrHIZin!iv(vT1zcLRJM z@IHv#NJcRxTn;3%Il6$za2V2F@)Xx}y5|)>nR~K}<}i|7ybm%_R6txO00WzzZyrvR z1nO@W_U(wLSOO|u$m+q~Lw&Q0DAs^w1R^$f;5IXv25L8bDHalstFK^+gKNYQ`wa}b z4OC8_!e-zs0%_e{ACAAlGf|OQu`19pjzpbWa=(UeitAIa7*QE`KQTZ^-&x*9@@bex zf5o0JTMfW=%Y>HPhBE{pov`(E<^GzNF#LA|q!SU_$m`up{&2HS4~M)uYnf>4u(afy zvfk;%O3QiTOS%JOpctEivw+?2Jyk*}Xi8FCeqXG9VzguF{13H&zlGB2jFKnGnb{w# zdh^*F<1++YffuaWFaQz{jljsW`s}>6vA8IIg*_n{Bmm*<{*l--_u8ha3m=>;J!&qR>H*Z^!P6_=Jetj0Ys_tGm6t=To~M;ROlC6uXI8G z7$A&VF1lA_O6Jo7zgRMkJD(HCaO81x@TWmNV8x4E-*vZ$6xuVsfD^OtCXFxv)N-EGS_Xc|iJyAQ-h1QHoVc%k0+csJn!0 z00Te%?8l694Kc;Zxz1gIg)f1~#7oyJ@?ugw!Fc~a`DVpwp(-f_Yyp5*!mVng5-tzs z!zS+h3ouct1QXVfzhjXz{aVWFDhs{kv znBl8Nt-~~72u`>(QLXudRfE+qzlx(m{EA9DjG>pbLyO+KheE}aoNCrRYM4J{$ZY2L ztqUo;!0?#b%4($9r}+uaao-jkb@hIs$;4HpR*5;Qy^(}6mK-TLE`$|kw36Ex11u~1 zssH4d6H{;Sr0>RNWeGL7Ww>lvX>wdsWN>{)<{efNP!#a51WTwpxBde<**vOED z+^Zojr<5Q1#T$M;{mExe?Gm?9~|O_nfQ>0Rf0@h*AJ_XL;bO6yFVKSdy*j#Tq- z^xDLx(dK@ji=ZC*^vU4rz^{!KEJD)3?swx<+||6Q&reC_(|V6M26i|(hYX}&)yv~g zh^W@~2Ti#P>bT`blXX7T;ohA;L#?-7`Fky|apvbTL0P37Py`cX=(1pFHrj9(Ix#nE zjM>q|dCg@!*nIz+Dcy=JJg<~zYBvn|d2%~W1p~Y|4l?-HzO+q& zU1m$=;8>-II+|GJ1|e*zXLNB=5^7|^ib z@F6mIy|z0Q>UOGs4b<#T46a@faQNad@@SH-^e$Fgo+|)v?~AStdL=e+SS)q*({5?Y zPTUFE=m6PpFvgYRm=@VvJ`P^Qv4Hi5SDSrdr@jMZ96E>l`pW@gYpBE$0*G1LoD@gnYqiwHcNY%2D4-twr#mf7#Sayq|1) z@VlSlg#IId`HkqZ@q!XIn!%u*wMQZe=ITw#&7>%5d+C#@!q;V0bOc)o;|59D43j9W z(JNmfO~wkjUgru6XP6WYgS*KtaKU}ZXg2u#`{|;}j*?`nmYliFO+xusf>Dls&Iw2j zx$HNShw7f~?bO@pU`Q?_!7)wp)mVt5>KH16vjBJdIt+jDZV(k+;k%*RBS<(hFdrj5 zc$9;%HMT1`W?c!WExkSssoLlxxWdTj_IVe_U?cjDOav1ZPb{J4>?>o&!l|ho?Jm=X?YTf(+YpSsGH4bf1n}29!VbG0tzw=+w z0dbt(zI+_Vf>EI!(fru}0P73inrJ(iH|2&NkP}-x@b5Q_%VjEki7ugZ3|&#*fPstC z&K5ttQ8WYa@Nhl^n+nDYQHlZYyr^UWf=|1FM6kzjAndF!GCQ3#bW2p8L$N$<4xESV z&zr)$1#;ujAnYT$bhpPxcM;XLxctfSQmw764Mgu3Z7JvQapBwx=FYY@sHQ>Q-!W>v zh=~x6?etP`iN5w%FzJpGHe$o1LtAV64CvKSC>FN-(e}O8!!9cYp`Nljy`it(8}AN$UL5h*8yH&lu3a*G26fR{e6D@t>?$@P1km-Q}vB zVSI-!N#|`{7YVCug+7mcS;-7XXUss8Le&Z&69CwLH8bcb!jw#o5c4ZOJ~WDe$quh2 zih0}zewT-(J_W~H%;%MX3KWX30YRv`tcmoW)8ROq0=zWFW|Y?;H-+wr+5@l%%dR|%a0CKV_4o~H4Jr?M$&C{acNH!6WBgBE72DuqT>v)MZj z9dP3Ee<$NISKJM=c@-nMJ%k8d!}t=(&NSmfhd8$f9s8*I&|95SfF8RJ!8Ru2GdskV zYO;NS$ZMQg9*$`>qVWsDuoG^s%y$>BkbsRKzWvo8s&MQnmOkp5yl~F`PLz}r{mWHF zu`v?R)UMLT%HFu;>M)okX#?{b?jN*htF&HSB6YLMPtY%w#CtY{cmvIT!Ry^K!_$xR z0dy`33b+p6sm(WxFp;D&Q0Y9yfj3vrP{okjYjDYPH9kKgru4I=owgH0x=7G~h77pf zX%;VCdht~@hnTK?G#@RW9|Ztk3CdzUM{aPXOl5X(KT*`N;QzYe-AY4QH&W$L!I+ei zseRsUM+RW=)CLnzIs4w|;g--9Z-8N3Vg!WcRo9WIgW|@6s!k=yD~Dw6>HmP%FltY$ zyBZ1*R}-$?h+5S-{Dt00DYAz7dlWWI$71*QbfZZ~G!NGpoHX|!u}hm6=Gf7~MbZcI zMI%DE8mHfZh1s_w?%vd^1xz_?x|FkJh6CHoypaEbq(D#OA#jy#rlUUNA7g*iXT_`^dMSBPu4q->U-Zx|EqUy;Tp$Re}UsI@NB%jjNZXX*7u^aL)lb zlOQ_A?zP>S53OR5*W+b~3}xvr)rcPY*%>C3DenB+Fw^C&!V&^7cCMp~-D24@zPN{q zy!fDGFhul9TT(0c+;1#Iay{Y1XU}`^nLNOf)j00YkLb?@Qu!Sa640EL!jzlM?C)LT zOldI&x&Az&JG8${${n>`}-saLJ)vtA!Vil!9r(20+(gc(lpuUfvnF zLUX|#($9>LBR~w1T~dS1pXFIPYx-2Z89IR<|IQ~EuSf@}k!x{?>OFi6%kkCl+W#)E z>6zDZsiGJX!VrryvRk=189Dt1u>4kNKzp!mQ;g2jj?ho9XQ4b6{1|LFlt=C87dh~I zzj(jmw~HS!wSXCYiiQxzDbL5z-g0hC;7|gZJ!FOST`yea#2H$@_MWRyB6aWUIBgCc@;~>8Vo>TN9+kvS-QeWT^(FjTWPxPrl8rb`sT7wfK?Icu2XGu$2+@ zY$DZAmEzO`$*auOU>Z#3D4(*ZYK3UHS>1g#evGVo9c0g>g&D65+Kq4NlM;fXp0b}| zYD??nzn_UZMh*dzVa^Ew@y)SH^k&nsNFT@Sn)yIR=#He4N!~-bdtSP?rSO!3MF)kTSPoqGoafnoJHd;8xXD3`Os zOKBS16k}%y{;SJf3G+slxqx!?fv%2C%|ozKQjDHyNp6ddX`v*E)Bad00Q_G!BWCK; zc&)u3(JWp=jn*H8yijkmR7OvImvXF-0pfv$=RUCJ`qn#KkeksriucG~fApEs!OjEv zAL<)M@#K$l#f1mjcO4kFec&`1*<7LYkjbA&r9DpAATtF;({%30RiC)&8lb!)1$_?q z1x3=6wA525^WjGi4Sr*24{D2HBvAHpYea%?mj^gq&;{8dSN#5%$~M$P(=SaYz4P4+ zX#(kHv;C)T&JyedlP939%ZC}}2<#AKTHsP^7{`&xcXHaTrR15P#{WJQ zch*XKK`8Ipt(0Ep{k1_Eo`2GO&f+~n=d;BeW%6iEV3C+0BEx%OS1b_6V{1nq#mXH2 z6Ls_0HN%!BYj+U35D2$F$v4_#5M8Fwu*ojuWQBCZW_=$HR@$(`3ovvR3d^DMi_Lf9 zSMc6s#r=uQHT1OQwfIf@bFZC0hjY`m-#eqLDA%4J6Ci;Z9#2T;U$5`_pA!#2^C<N1`}v>DD9i2MdKU zvCTws3)X-$mBK&0!;H17b;U9`?JwV>@2{{H40~hggr5NdTH7>y&F=+H`{W6N#hV^* z07)utxz+++JWPDPgictqJlqeR_%k?^9hyW+Z;fk zj5rSiopN>}Z=<1WAiO8}QSI4ajlp{t1PaoQhZ@wty-QCU6F;xY$jejaJzbDQv#(cZ z`=%oH72bZonTlfN@1qR#V11iWRg5^1S{Aju7UTG{QC2x$`c84vOiH>@UuoyZ*Do?J z;qXdI<=a^%XZfZ0x`^uHupEyjKhm2+M9!_m{{}mre@9M-Xj6r47NehNQDXYfpSe@+ z093PGV|FCCF)Z~3{tO(?KHhWDRV}OhHWCk3rljG+W8y{)kWe=QSmpiXu0@>)A0`ZX4y^0@Q!$&K@N_dw|+_g!S&;|c6kZd zxg)VnRTmrP+T(ZA(nz+FWduY&t9qgVoJ#uEv!H@|I9Qv~94sM-8WdMPMC5X*1VllX z+o}OF<83WQ@8ue*oT(gV4VXz@kQ9ALbHm+{85OQ@OPGnK?&iu;;a(81a?WN`xEwO_ zmvChq=u64i;0iF$L(nLwT$EtlvEjjv%f1 zq8)(p!#hhe>2X{e>Yti4k9>Yw&JEQvO`6gaHn_RGR4^t`drN#LcV9mCL4SGMt$ z$B*p@KhP5jntu$_V-Ppn18X&(^U5l(!uXCW`;4nQVlaxS2P65X>cUMqb{wL}6n7!t zey;9aA-+w!(~wGJ0oEIN2=4x}gw1J_CY#o%rsu6wIhuT;(S&JdOk*^S<>$Mcrc;MJ zrjze&B8bA%&4%A3Y!K&kZXQn|3n(mgKd?|S^BY= z&;+xqIXflxx{15wEc$0}s_ix!8*w10A($2=<|bk4VlY(ivZp{QX`qrL$m!H*)NU<6 zs%&c1$lY|V4K18~39l{;JiQ#;niD=uK@7V!H@iLbgzb7bn=x+hC6L7p-J6oXnxvIydFoOkn5oq!$u); zE!90SCvp<{tTGbBWZtVAJ~A?P0iMF8zH#~2zG*0uUg8j@M!{zhY$VJPt3aM+Xs=Lk zKOEUfV%?P1Q32IFJjILq#y*&-nBHoIC*{jxMdTn0hmp0gH@yPHSW`?zl+2|go;`8t zG3cs(;_E`L8I(zf9&AT(dDZAVyhuro7_DMj;}_YsnTApHe$R4KWU zuuP>DfQuXzPabN^-7ciT_gkIs=UbUhpoq@NscSe{{6C$9~RT6F5|MBpDL z0`jkxKJ^R7Yu;R4UQ1#yzRgMv#nr1gF0-;;Z&J#>y_#Z(Gk1oqnlsHDs|5`kwSi|i z5gJj^@h|wnGx5Dk(xZ|OlG%`B)cqqXRhI;H?lN2WMRE}4{R56)-6Lv7sPLL@_a?A% zs(q=~SS{N*V?eb+E@}5bu>9-rPtXjlO*E*_immNiQbuYL^UyA}9QsdfqosE&nQ&xU zgp1yfP)NZ1|3E z!jiZp6=t6$pj)G}9qSl{{q5Z6yl<#~>oLf`NE^>}W zBS+WK0A*?aifHDJQZra~PlDs7qQ~7()E_kbn2+$o5wb&xY+&Ybk z{rN-GUI`gvz-JA}dDc(%sj$(^*Xug9)V}$r^O4W>w8!)XXreV42PGyzl2nOkR0cuh z-UxKACjt*^66Gu}fhmg#eq#iF6>roU0v}ITkk&~2NaUW^)&O2kBGE<-x_AL$Up{wR zs$W58NNhF@bk*UU{LXo(+`v7` zi$lEE?^gFbBcxx_WPFQ=1A@YhNa-Cb68BE@Dn%UwMULl1tQ@Mb_NF>%{)`=A_eJ#X zQjyib_sK2aGhKMv`!0a6$DY7T8dqUtylvL?--4u18rzZ~oe_k!&zqk%V^5tcK}gj< zk7fNfboF)H5V8=octH0Xtu@HAK*@GsH4_FX{g`>^HF&Tb9OGC=#=KIq z%nFQ%6Rj@3+U@50E6QmFwi`+G-3gJ%yV;@kZ@kN3MjlA^rmHwXdjRV``bcck1fIzF z5T?rvIiX>nINIa-b$w?j+Bg^B&60Lv$^S{H^zVD{-SyperOIuUe@GG~$+K%~>f3Uz zm**O3n_yDZc@C;&aCZssSYeFY$wg((X<1RaIuhTs-)Gdlh zhA83(NbZY?bWT*=pemM0?wL7><9IhTHK!dZxw#1PFLi79F}|K`Z;}6V1>zU~pDPez zEcPdsT1bm9h!HAfbkei7O*I+B zEfzdqHCZVbGT-#o8LXgmG;lbi{(PoT$hLp)=CUr*3dxk;1I=6(#Q#WvPQLH)|B(WY zmZkrX6hOWuK~?+@De!E;(XQTXh}SMhQ)@&-lbk_9N0s_R<2G*x+4<&qF>opuL1Wsb z4RONCgtvI3X#bWuR(baQ>(k@&^^Rh&JO9^~PKIf7P2x7#*a;a?jE3>>#l|#e;TK3c zp1kwX=Rs{L1K1smhl_l#)($@v2RV)hsY24Gt!k}BIcWB8*EFdg+81ypYbDylC?}wR z)CE35lR-w^uiF^jf1Ut*`l3$-ixz%#)CKec2B!d8?6StO5GMvwI(ibvHz2CC82_Cw zur~;+{^A)Uz{8Mf@lG$P$#-jIbVDrH>CB<~|2zSO$p3f(f*7C&$jX}Zk`Dpd!Rnl2 ze2@GZkV4SU)dB!OI%sd7!Zwtb84JY{o`wB?IRTBZ?*DNDBW?dbCjicm@PC{@?XG=q zHTY_M>y$vu4BBS$Ft+LLz5EQgwL=BXVp)<<;p%lje&?SLZUOZQ{RJaOO8D&{lne11 z&`GdP`u4)S3!H?`_~QR`oDpE>Fbg>)K*Kq0(RCYb4hMAoX(N+?Y$~nRibl)$7v%nT zuGx_aMvL&PrTb|DTCgX+2C4O9WudbI%5Ir-Ec~(3&0zA1l=*MdTo(M(2GV!Dg_CEo z5k)8YNTEMH9P#W)QkYnAr`21%M~C|WAwuvUQJdV==q}_gIdez3#=h8QjIQXnWcrY$ zJ&KES=7FEpN&K;2(3a8P2uPeRpy`Girtpq73k&^0!Ee}DDp#xA>X#Z~9M8P2d-|30 zb*cMjaZl+3k+C*%>0miBSGDI1pd1Z%=s()TLi=4|xW01RT-9Sy^rQoAp~d`S?J{03 zp4{-^!?Pi!MfIH*RC}>w`VKOA<>h#pz9`bmf^+(kSWT6CzOl2~rJVD~sNblZWBz!BGMP zwX^!oRtgA1GWP z*KQIF=)5Z>v?*8?F^W6MFs>);#bd0Ne;e<4cJS{w<7+$&loC!f+X~MJ501n5fucRm7H+Zbu-p=+Pt@dID^{qKiu zy&;PpErFl7%Odq$rLql2FxdnmSg2X3nJ>WDua)AbaexI7P!$W*6TsJVZZjvuB!uTe zhW|!HG}oV*7KfS+R(N05G)cnZF@j&+9mki*ojLDhwb}cm+U`|}x!rz6uStTbUF8O^ z^g4={so?s*;Z_nKf_!oiZJy0mUN^D^C5y5!2XE#Ce+W6B9t(?7KNkbB&S6{@9l4&4 zVu5&NeAW%XU^M~kpmMR%76d0K3}_t2s}NCU-Pwc zf5yt1-mMXzP?1M5@xn=MN6SQ^-n|W06ov9g>ig-*1-%%}Tf*G9m>8Fl&~?u-O1m#| zazPrX%}SsEZn+jyYJ@p=0H7JpXgNdo8IF?7bjrOTngLBH`m-(yu_kZQaAo0nfQf?-GbBzgju_2_ncc zft38hFZ$sV|) zqm2W!R`n2);$Rs7HS+*K_PIxonZgLyW^b5_4*tBn%7~2zjv$0%^S7+(CTY}43XldS z>$#=oa9TlXaxskk94Gtnq*Or4Ko^euAD}t)&*6}hN0G$PcKkKr&+?GpLcyJIA@dPq zirOQ&=r;9ZDPFvqjQnqMiN{qB&c1JkzUPu3;=j8lHXLCgd(3!&2sK*XreIoExZJH5 zND0GEFi5O_WRB^EOa=0w2Iv;18bSC|c@}0oY-AbFK}!4^E`BGdajOtY3DWzaR`Lgy z_kQJ+-Gsff`FNw~Y;?-#M;amyjqR&3EwDN_lK+2ZAXVw@3ZaY-6a6#UCsVISo?R%smRM93nd;k4@+(Cr0--5IPkg2 ze#MQWev^<{72?j4!qk(COBHM{gWxaR88%Yikw?ALs)myik|E*n1+Kt5A~qF2J4h^I zK*H~5Vn)uczEEGV7bZAx0%~;VVR1F^)mJtg5bVTWEFtxz=mUK)WK( zHVQUW07tJA|Dl-bPRbRsIJ8!{Z8*0iG`m`+iTHeqWLLt4US;~T^C@w!IWSKcXlpKH zECO<@9oeBKllMj7OGgmner z3zgxUK7UM{^xcJwNpQjpI_yx_8ihQU=ALOncf#~Onm_1Gbi7^is0AhhL_=KMYI7mG zhZJw0l-?-y*~+5c_#PlC@YecrM2$)Hwb3nYa#uo1f3!ZDFa)9XhvwpCTMyTb`$(An zKho~0J+p4>8g^`_VkZ^bb}F`Qn-$x(ZQHhO+cqo7_0__?o_GKI3G%ZKP-p1+5UR{+)NjUO85?-zo#Ia<)>gX*v^kg$K;VL52h*uf7DX50RQ23x@{B zvDjA{ry^+DJY30Pm(IxSd}~pylBAcOG8hyYoE11lAtzdod!_D(S+H8}!w>T;D&#@v z0A;nKIQ_?mFb61Zb*|a@5SVXW9;`}h|0MKMRD+O8UjWHtto~6DJ2C-y$DyV_WKfut zS4&jJs+4GG+|44;9w(jIBCd?5S)q@_|CbLjip8OQuy3VQZ_Mv}!8itKqjAhBW}R%1 zoOl#?bWMhf>@+4_^rxZd%jHyA#|}!)^C^&BJc1-|Q7H;39NFk>8LF&v30F57r34xG z%h|Z3u3z*#G~@Z_DKnb|PD@&wu+6Y5(;hg8#_=*N0G`rtq5lQmo#Fa4K5QF$E#tr|`79 zqQt7efNP=y9ani`a=oG4UtgQ@+YH+fV63s>H7!`Ptq@`LKQ=gAGH8CnLWB$Lqjgiz zax;2`2;kXn^249h!%%+?GjE@h(^dV=)ak=G+W`BaedD^2?F`k8-q5`BHF)wP=(}tq zf_U_{;6FYDXWV{T-}m~q0KcJr$>O;AChlCyoV%2>iIGow_@APNF*@ zYZk!)TSdchy|QmCCK%@^Q;kB0{fWn=eSV6qNI=E1WkjDst8FkMc9M~C8>GlP5+L7yEWif{%txu3&yg`2S4^|l?Bc|v2vdrsR?)kO8$3N5d7XYx?6 zgH{{-k@aoms6Kr%g5&Ion}HsXWg#_@k9C)y@IdMeQ;F&lK2YrX&0QFbA9co^hNKmmU5Zoms+(GIZf<}RZXjjqXa@l=k}wylsw zXxeM`>-)RjT)l@m`)kN?QkGRDt+W`7%38GXjzAFDQN!F+V6>3-q2(=<^i%j<4}=#zyJ(yF-EG?(qmk z-G@&;&-Rx@riN0Gz=Yw1;uFnOVoiu2uIY~E>+gZ>YJv_4PaUx(5pCkYxu6@1#EmX? zi@k12cG;NFg<~sV=oh0h38{-|ltK8*eH*h7Fy=KPbErve6`?Ko%3B^XrD$V}6IUyd z7-CuvM?fwJ%5zJxJZ=OQWyT=cL+bZPojvB^E_+{=7x^-`&gQ>g#^WeEj+Xb+G3VM; zc=t<-SS@RDn!oA0=-u}-eCTeR^HuS zBVzg7OJD-m!@~|~o^vifsjRK`@Nvy;>j14q>(P4cE9&CGh@Ri*CR)~69>I! zVqQR$1=fU(F|$9_R~0TD+L)lU(^JW;@;3v4S9Wt3=)knuj#$}k%2;=4!Ia8=pzuN_ z67wyE@FS~>uDH)3{ zB5(+OlQ&VVa)GTrF-8Bymi|*$Mn&Qz1r<_0MVig_^O;_@+))gbaNURh+aT1W_bJbEtv;+Xo#<(EZc?w^eZ8PCBRB~a`Nc?b-0n) z&#V?uLEx6poTBlkz{+5xRH709cv(7S!0>It3&6Ua9Vn^WIo$XoIBIyKMBHbicWD=Y zlAn>jy{T#yfpM^izU0K8{+@rDU;5Hy>U|0l3S?~1oZRhubL+?cc2%>8RESm&^zkFS zDWt#D%)JhD(6!o>w54b~xT-Hb?d$|*J9kFj(sq=M>flbVZx6`$_|$uoFHJ#@&GB?H zXO%JbF!5#ii;ld+DGmciocK_UrK8HJI~E)rk<;SNSpQBv*!4KV#mJmAL)#fr@&zr| zpXsutXB_-bF!`Uik0z4<*mag-lUX=Epi#CY&K4nFxD`WI{w7?YKxWim148ljA8eFC z(Mc>a0a1buy4>aALObYcD=9-AK*3NvA!2;A0Zx*C7GpFjCR1t*1Smm71ML8ArL?>+ zpA7neliSbW`;W;d9dPGrwoq#y@rgk9TK+O5WW84(tf=-#j-R>hjeulBTD&wCH8sle zqdiO9Frs`l!V%<#`ep)vPB(8z)Ox5;?PfS)4@0ioiAM4MgFKdM$EkjY^R@&~pp*<% zwNHhWsCy3g)Nqu36ObHnrHv8gEoe{kf#99~Y#%7Z2U11XqKLkIu%{@Wf(cnu(ZziZ zPB0JfX3pc$`E>1TUkz{JDjPhCAE$cs{VB#JgFs2PRHo(hHqUgQF0S~A8zq2AQ2s2x zcR65}^Gr7Sf{ES}pf{T+xb+}LETpl@q+$=`xCkV}Ah`i1QNi8cI3II!$$upgU?`Q0 z0@BZj36GqS8yBh(dbXjv$O!xOE@%~Q%&>9%Hv+A3@&)NYbN+LdM!6BBw|IbSGs`PA zOz#v{9CbBg=iEEMW0!`iFdf>fGa9*+I@LNzYW!qSrO3d#`;u-IL>a<^1Ds=F(=gGc zjRc2GZs(#-t78BM2DnmZI!_60(PQ$yQ|l$x-eYC$*FQP~o``npL7fTLy5v{D*k7H& z^3UG?bOy{Q)7ic{;sgB_g@ctkTgiK1;5kKdZ|H2s!5Y^D8ju5MrN5Mc#Au z51q&riy0BLTVzze8Dv!ivuJn6qI@Y+Z8x8nz%{{VZ&6vS3f%9^zV8K)%er*!IMk4G zg&r1&$jV4AY`-nS*p#ElRMUKIWa^N}GVI29AeF5-A>KcDHS(H04yjH{4Soc@-(6y-4P&W*%2oc z!g|q>)CV4YbNOX+>cr-lN2<)WlO0m<)P!Sl6-NdZcBC&mv32hf7BshV;kuOX z_XZk+VNHZ~e(Ij#P0(++4G_Nup6{lb)Os#_TY#%?^rSL^vV z!FOv|xoGg==%YAecSBvyt-Vuf)fX~sy&WYvoo(M=2(`_3!g{$C^Db_b=myHY1zS)H z)N()Op*LDlgdsI14ly(U9k*Q@#qLZ(>>*V~t2skt?YXHnmWV!6`SNJ~J_38~6&hUa z`OVCMN>JLfKkm_tRDv;vhRYACOyhUu;a3ViQQ=w7_tB^o{cl)3IjE0!Wt;4aCw}JX zJLhR$nriY}%54ky(4a~1VEi`E4%@J5jdnPZ`;8%?k zPrb=Y^V3^Di98S%SO(dvsCzazg-B(yIV2)a1vRZ^N!$r)#G!=i%K8Gx>BVK&LOhTnjK0I zqn1kINIWsyaC@S5?yC6|oJWVM-;3ar&7TQ~l7Y(* z9tBQvs1>E7;Xlw6LI{aY!n7^uxTRpw#~$~VIPdAq{O@ZjIAojCU=Cr-xQAG@u$I>= zt9nH@y`IP3)*qCgbkVuKhdXFzHsN7BL<}wr3BF!D9EbFnxr*8zlp$(?_JE~~W7jH8 zGfCFGbRBt5K#BGExuB?20a7Os-q+KO$%QA&>p}2Iia*I6-StzXE9GDZbb60ZZL9lg zxz;^NTC-}u#Fiq91J{gpYjS`n9}|KJvwhCTU_nc1%1ditV5 z4V7Rw7ihas#(Cw!h{EFVXG18QHR(vSJ ze*CP>TrSyg>!$MlU?>?L(6+hgAB|f1$W-=Qa)K{D z^xNEg>E1R=XmIn1o&wK0>CsPoEezYY2>s*XHoBf%CYvAooVH&936_eJPl>~=>#X(g zWcMwK=n=x#{yYiq3>D@X1lx(yD=Tvv+wiBiR{%w~EKG%cxlL*DqH=_fXp5e^3{=yU z*|l8M*hbN0qbxt*trJ~)2C=4p4z9^+QnoPR!_l}fwib<24g*%NwP05@pqPGHTJ|Z= zysmWo`V1N=5O$yznfhG&o;>fhdi*dW!0vqOVi66&P=>QW@!ONF2+ORH(U_-7K>k*7 z51wQOCbDIuY7c}fHNSFg4Hx$NrSl$^c5r?C^jcXd3yS6t!*nDHr4@&2{DRT3RD7R3~1kp#cqtxgWi`jyCEUnn&3T`%m}`S zn3BG$rt^o|{n_xzC9u`Yf@4!9G zC{AxQAKUfFx&f?!J3d8qKag;mhQ@bkY9q<(u&_#Py(Eyeu$Vd?o1Ymbfd37W1jPcY#ZL4Xr&{3FJE@rfFNe;88dfa$ni-aqUN}6vHc%h2^Ckuj0CcRmW!Paa7;O~w1 z4Ug+(V>SrmdQ&@x?nm#cLQ2_WPJ`K5xC!h^Gga1ZR?T@`dXwhafEiI}Q3e(iQQvsK zCBxpt8FdG~PD$MTD}(e47RdtU_*uu5!}X3mpc+UMT9B>#CK#hs9AGFZV?XWY;2z}; z{V7RkQB8HIuu-*hwq3LK1&8?JJDplldKXMFt{*c2O`qn<;i{R0R#tn>>9eaWH}D#_ zar`hbABQB8_sn3_Q!%^>w1 z7;^Z(q1{x;=lbwJ7`PG(W>`UnyOBq9AYQiNKt=9DLJ z%*kl&A62W|#Jz`fp)aty^J?9++*xtKp42)ufloM=_fqx*pf6aODqwR6BE}(H;lFL* z2=aDj5km!-{G{Rx2cw$G+ddnbI4o?3-eY)0|Bj@tlVItmswXp8;ffRaOCCI-@UspE z={MeW#Nb_Br`P&#hach7Iz2e7!+>k&6{K*o7lzJ*!eH`yuvr>`_2eti{z@w1W35pU$DwY zu-5n%@9m*w(k0ce8B%4A?{S632^E@BbxErsBZtu<+XP^ttbMQ^eHPhzNA+El^wP|t z^qzRQ@ZjXlO*!cH3}nv4mWfeN{es*5F$kjLdzB(uC(i}N`o1J=ib-+NscPbW@>U1R zhUJAWd|SfCWHo>I@*$zrcyO}qB5j@~YAmkWk52 zZ+Z0nlC9>r%hJ3DJYbe(j^0b@qVQC63~8Y1r&XC?9rH9C{INSM$X&`s%5_id_QcKI zmO?x$gFZq<1-h+9`*P$qFvyupvbKv)wL^gTebqYTV`8E`Fd}n5I+qV!)L$oVVTWQ4 z;?>c{)?@Hgs0%8_RMqWHk~9sHBr-(khfunaVCiWV0@<%tK+yWmU9JdBRv!h=CfY0FCFZjVxB=U5iVO zI(@0(9HK*|DWuTY7C`MZ^iHMhu%K3sY1|GoZa6^qck$UhwqaYrpXLl>j{0B!A|BQ{ z{zW{bW9$8`+Kw9f+DL5&EGkJsAHa~2?X+;`O#OMBU1m~<%GH~$t@a5hMw}-cnWI2- zL&YY+ms8;0-mcfU`xEvP2e#>xIZzzz~ zX|}L1G)U!BRXB{7JJMS7h^_#hQ=1ACv+*F95DQO>R4m$H=1fess|r6d;1x`~Q({%d zI#@x#dz=SOiS+E(LSz+1a6kDU@-SJU|8L~MPV~RXLtqc$|BwgOjQ=7JoeTdU57|cl z5Ax8N2lOB0!Rr5z2b+-pA`bza|3e<=2@YG-HhnKiAR}%A>`RUCU~G4*7h5N>FR%zw zqcXm3*v0}^Rnhzue(4RoH-$7?5GeBjXbZuXRD{JaWwMNx!~0_n8_Va3*vTlSzbmLsGq^9tlP7+ zw2pha{HBF@Er+vNoH9cNP3RZhWbZFsdT=WY5+6O~m~H@fd5!7@#AXN__u*>40_r@Q zK9$(8gnhRwPFS=ZFvPImDQOnc+s|y#MJ9C0Xj}U;*Hd_&O{lNO7gN2Q3|$^xV67u} zt?xQ|wRm*hIwDdc_Jny%9crir0y=l+TU+}0GDkITNpvVaC%mMc$z)hLb`~SJ;0$v?)#|dW=XF^aVK(G)Cf>xg zp}7Gd>@v15Mn&#*Uq94AK>!XGXPf(VE8O&JWgrXv5eM!e~$vE?cGK@9oIhu1rMU(R}f3Z`%HDATu9` zQjqq{UN1BaKMa;{1(mtzd?6!Cn#47|mGI_-_l7+BYZJ?>{M6Bqy~Ab)(UeF5EsuNc zRd_SF*=Oh*3o~N1d|m*m36Rj3eW`IXCVt$7{buA;Ha@5y zo%M$kDYhEMZZas!!rtZZHB0TjHIh&y5-ZSlOt7Go1){f?uTS03#LYN6NJqpLw-k_< zO8Dq%@kov&43+k@EM;Nh!H{qb`=UYg0i#YV1BK%nH4hiXC?ZMZBnOJGMmwZO^J!vT z7fHUr5Np8}mg^uj=D_0VhBNs+PwNCW$?t5WK~csC$$a7O2fwC9Ji`(8O0-Ea4do>5 z4YKVre?jHK7rR#na=a71EfvMt;|qA;Nv#&#h-v!U3)Kqw0e(Ao0rnYER22}PWfh1= z$3P_cg9Gb{k)ikS0OKzF zbA>|0jPo&_G7)p5F1l^c)L&sDDMG~pe-Ae9cUHM(Imz}s(xr1l4?v}cHQ;x=A|rCFe6g!HptP$A*oT|HEw1hvrO zdGA@ic4w5@XpSdmYLR)PyX`QhN&0VyCly&`3eVOsiHPIJ&zNx`%7=YK7hYrhAT0hX zJq<-s-0uT~S#GHZRB%x4-+7aGur&xW+=)*M>NMwk?{wBK1s4 zq53B-PU^Rxso@UsyLcfWi>NcSX7Of+J+hcf9aji~gnDS;PO`Y)TQeAp4>~`J6MXEE z_4=H*%+V5hsj84(uO_;d2OpQVg7w8$73B16g2yg$j#?z{{pU-mgYEGnVljQb^;;|u zj`OkDwqs+7`|oVYi)T8C_U5*Cfmq!;)+BUxL~S=j3fg2XJQuK)=8FQ?e==L*zd-b4 zs+?ul=KrZWp-&4L9X~-AmEr4wh3|R7)DBDb+}>d{aAtDsF--B2${0DM?r>xch0@}*1t z{`EBj+Lp|{Od`e=b-e#!*SUNzr;8VbegELUo3T1;xEO~BME&NFJp*vAcDd3ww^5nK zCKedu!Ep52tYW(U!mK1~N^|PVi~6JQoKZhUFeA zWm3eUu?J-8%A1-v&Z^Kd!Dt6sR@9WVF?hJN($5(38&|Rc{g=B**8?)XQMbvI7IN1B4j9ll)Jv0X?|| zlE;?a$`P%$b?j~YfD0^4%@Un(cXjDDJQct(D?h)+F}iO4`*~VV0eaV{)tnbMWk1wg zkpwTPj(DAj)MuG@U^NpG;;4QG*3w61oqZ-ECar||z!a;MJRU!*Vk2tWr2mHVnzH3M z?;oshBHvyLS_>Dlc(p4X)5szEM-Rvr0_U_G_rTHizqgm&Co9G0yH5kLM-eY<6cYT@ zu^$a)hJQH2@#^~-uJ$obC+yDH-zkH7&Ayh8C01|HL$1Cbm^O&p1VE{Lsiy2;bV?N? z@cN&6L0*z0AZJ|YMSLit-`0ooKHbF>_Gk9_HZ_a$QPT^LRn$Za8_ghmu9!;=!A?|E zokeiZ=q!_0hRK>rBfK@QBcsIQ?joW>zmx#8@HFu7oA5K+8WGw9^JFYvqfnAmp*O;z zhMj?lKK4m!(iTf{e(RM~HPPhBD+nuA@t7DuUsRM=?nM6n6<*&}2`U!9sQz*f?FHI< zbHB5wu%|s6y!)vJdHx|383c67WTMQ-x6Mm2$PPdiXfps*ZrK9T4=Y{5TjuLzal&>x zu|xmD9rm%EC=`AE4|ibqDf&0=kmK+!s0>W7SFJF%4Ga!i}@c+PjmQm;F~oJL~Vq=y~tt)>c|`8YyaeE+ynd{^q|T1diq znrnRkW`3hvHHKy5$URcS8aDNe3)+N?|EV^E?w9-nl%HoFG&K|zWRzMyh4t7HYW|R+ zGz-}d{z5|HodKk)Q-<@OHJF>y zw}+DyV=pV9=`Jc3|3-GF2Y^3%gCBDuo`s%|+w&gaQnqK#FPVsM$uV@-9MSXr#w+C< z{spw3%rtNwHwgjK5(Tx`RT&R^ewE$+0xf@rx~GQ@b-uYUVfX6v4*;9+$N*n~8cVa_ zEZtJ_!mg$uLGa9HM&PmEZ5xV)U0sVyT@+GQGmWE^PrIPC7fH8#9n?8H>}YUDlDV31 zcN954ALR|&sR@G8BTN+djPg^4mGJvysvu<6$DMDT@0+=cqjCjt>oH4iDATBT%GFg4 z4WmT~WG0~c}N zNMi!+D;dl#y$o_sTX=7Wu+#3!48E;m-}Z4Vp7s$lUkuczUi1-+^Z;wO9i)@!TUNZ^ zUuJcw**)?{?zAKI6Nz{}R{Q}6by|ZDejf&R&q0}}P#$rA_+Es$v#wqWi!YLJ#w~^a z%}e>VMg|zNwn1D!Bg|{imCTQ6^I~gBy!Ijb;_zBD)9Dl>`m6O@>oo4~^RDtm$ zq*8!)X}f`r_!`ZdJQOJOIh@$@j8l(d#aO14a!p@WE{CKL8TXeaxc69TPns@rcWve; zmLr=_6?tpTlryy_DL;SJOrPs2CP5&-WyuL;cxhxW9$T{*=j2IX{()KC#B4dRU^#vH zp)1NK=pDH7SxZLuSY?Dj!%Gp1>(7PYL>Uu|^bhD1$05G*hEp)`wUhKU_`cltP|3c`GIM?yJLk0-x*ot1X$Rv-6dcYO>xV3AzzKGKdmmZiqGOdfC{ohWU?B6Y$ z6EiiM3ya2+2F7~wXd_8<-PFb!xmhkO%Sb0H@MnkEa&a%Ni_%(#P!TXe>1$Xq08|yM z^D}m>#kUzg^ehjodv(OXKFHiR5HiEwgab5TF|%#*Fr`_nvj{ttz2oYEJAIPk#tYrG zw-r3~Go=L*gl1=Wb5T7i5VJC=k2wX$Ufy6-}?GH3+ig#v{1hl;L8Sb^iC7oAO4?0vP2Gnxhg72%Zp`a6R@scy!nsYh$c(Rodt9FE+zy(-uBvg%vH*3o413r`&l>8*H?5$|bHX`0$%=4Nvb~AM65`l#0_3B^hjw)5M?QKK>Dwgr6L!tLuN%2?8LNYev*wLsIxl1hi`G^&z zyy--AO8kAA2J&vu`Rj1_)Q8l(&oD=(x|hc{9a8M*`la6XnUVh+w>(d=Qn3r~a29OP zQNvnWvcPR^(;kf^$8DL=y`w?t#K4gb`&m$=ZBEJ;nZF{__D#`eU!PAfs(M(ib=HTF zOJ0`Y;jTC=&l^tBM|?ASHUVh~nv9TC#6&L71HrRxoqKJQXXe60lYVB3E_nkzWw(Hy zpE@=|>qa71!XocT0$AoN36(yE`50|77cGSAXHaQ4nQ#f>@sDb8b{o1dcs&tyxk+#r zF>)WCMRe6{=5a~Jnb_$c&$Md4@|yWvfDe!$+m4R&8-YA5LA>K_8>Am?49}^gZW<89 zSy!20@NY(*rF;QjEugP@9lr@d_1trN5-o-^_w?Iax-bEL89{H6oek>0jP^P<-isHc zpsMaQ;5JPZaJmK$<-8o7+>t}jVZ!)=3wGCnU5jlL_5*|(Y!{+iMV0U$qBdK^=vF$E42kyUx5vSXWS9h<9)?>Cmo zEU`pr;+LqUCtZ#$u{fS2Dc^JkAr^n=(_U}p&aAy5<2U8qIzp%n52!REEx^<@3BZw9 z2g6a`abhz1%7dv4I(#RADc=IGfGXs{v78X@u!N3mX-k%%AnQOP-1&kNV;9 z4rC#akdI7wun@q9Gle0M5cg=MdpO}%R1BSMfY6fYu?88}%t+2iMKH@6)E6HXZwI}H z_dTFLTrBqp?)FhylXFU9oDc`P_$y^a7(fnb*(oYd%j=+XN4`J#Pt|}C80u|6Hu0_o zSU#cPNXn!(J;6xsn-2q?See7W-wY3bmB_2sj7eV$z+X1wddV^;a!c@Tf8?UF8MNeF z-6jyTH_1d_?1UX!1wfPeH=Yh#8vTkh0#8h@3-j4&?%C`{@bS_*g(aV}SxQmPSo4;A zV3lNt94y!=w?Ch7z5jifdK3m(&3YUuVyzeaj{Z~b%Plp8CW&FxW0Xz1PGUS>x_JVh zJ#fnJwgjIC7ax=uTfU<62a|3>zW!4%df`)3lGO;PMRC~5 zN!utkz`W2P`qL1gw1zK4GHWidxL2k<@>R&=dromC5rVLIzmR-t(Pe1>3BuX&!xks; zM&mV$eUk5Oo7H9R5%eR3+&G^j`7tv8;D7EzsNAHP0-5shmg2d#sb&uf+>JeOWsd z#$+Ozt~uOz|I;h?Cp3Nb6J7Tug#WS+xnw&9TUE@dBZ?hUVw-Zf{wm34;Wg&( zHtgBxB@iq)4tV`pC;Sj&GN6G-$@_O$xjPpqmZRxi%FNeWkL9{mTe7!UGLsQLs0Ah? zp^)i;AkrV@mTWnxPC;Fk4|B@2yE}$1Pc=I;Hu0VFk$hC>A&LkxMAHOmNJ~fOVBcK6 z)Y}N1c$Hwg*wwXn1Hmz z%=Eos6J52U_G}dD8~SRSl>*0e_V{g{PL`Oqq+8&h6tPl>yuRlZMTTz)SD0J~oa6l|; ze8d&_HwFXWJ(J(2XPq!VbQ(|-cVkbP1fX#hSdZGBF};BEav%lXp!y_wk*?{Iz`ffc z?$eeX-q-kIx6JAHDadQ7pkfC+B73c-4i(s7ZZO2l&ZaPMESc;hYG5tR&LDRQ&RN>{ z&_8eH%9peQRNGybq56K@|6w1B))zte2Zc(*7@$~#Kqayxo365esfEw*^4y2wQs6=) zvaFG`-f1xpPWAW!GTAVF(>EKPjdVxlHZSUdjy9dnomCAvlz~{U(2o0C{yrC*>`lIc zevX!RQG_Mw&$|&SuH;@wK_TDNXwm@C8}B{`8o&mXFLh`_>5YXpR*r2{YsKjj4w_KV z%Ng5@$9MWP5&?YovH4G0;&|#bhEBBpmfsug1hG!LI&!d=6Ll$vn~ijZ{PBzr`yg$$ zJDa=aC_-pj;Rpl#c6K~C!K*1B$!`6t(z3WaPR)0}YiAXpOK=V)dV87xyCv2=_HU3) zjXh5C8O$SsLB~1ytz%}2e8{G)sZ+<~JqId4rBJ^os3E#+fkpgCK3d|%z@^g%Sh7dA zv55t{4)wxpxkl?=vF0{m`lJAk6E$wm=-+Vj-R@|#Nit}BA}qC>0+Sn&Ooq&CnXe3F zA!I^*j_nz)=gTQ>BZc8=vO0&I;$J_X8an!RL>qCp=LRY{p{XHPyUacU-t)pg{mPbeiRR&tU=oVhuuh{l`z z`{NeJs9Px@x?Hhf!*UZ30n5ARj0R%m817V8M(IrssaMxZC5X0<4#RYGo9W9ksxiJD=Y1E*s5?gZ{xA3d4(P5+*BCedl`FPybBRpFNb3OKD;#litGy1eNq0vUk zt
^DNh)xxCz=Af*W#fR^m8XE`-&-ix6}0V}n`P`;OdIWjB>jbU{U`;e{J^I{MNGxhdD z0c8)f8Jk~_Qo6+XbLOJAK-gh2Kk7LOADxv~9gWVM!_XIBMk~llk#Af?( zIdi2UEC&ypDvV8tZ~4z%$I%?n*qC3Ws9fvxppHq?F$&`-sE1@;Lh7m4RG4>M)OCfv~Sss?W2dJr*K4t zUD|Ld`rPu;2$z}4Hy0~zj(YnYkQimM^ zz(qT*KaT{|l=Tbraj$b4R6PdeUmLYlJnG4F59s)IERN z+#^kz^+w!9Od_dkM%&5cDFDC+lPGLyon}_W|H!_~<&DBk1|oKivm9+51ZHAc*5h_4 zcWBT`!F7>Znv6iFjp zs#ed)K3Q*K$yoNt<)=yaeaIZaXg$0uda@5+Wr1Y500uT>wb*KDkjrVmfPc{xYY#rg zEh8VT)rVkn^I^@vvjQuBl`}UL+mIxDi$xQ=o1a#ly#J#}G73-bSY|2h&Xz&ZHQ)Cbk8dR~pOg;`3%$^-2dCHFO1aeD1N9&rtChn6Q3c zW10tR*+PbA3*=%35oW#ls~Z4@vIES2fq-xP6S6a+GshvS%t+g3v#N%9*1B3P-7R)F z_)hCGSvdseQ0^@B)z2`<*|VaLi`j)ECIxSQ2+tv3cc^jTE=PRtwy`eeRWbyzT>7)F zQX|`GG5yblSaT5%m=x#sC?;(D1a<2r;XU1yA}Ku56esF45e7-%%U2_REw%=r*Go8e zbrfO*CI?9|5c;Xz#S02L5R5=61cT&67@2Z!##4waCNLV08qro<%{f`;FZIA&y9tas zfXFHSXTw@LeE%D4{{v$7%T_8b2A_B2?LX85O*>|j1bnlM)CmwjUS`jKsRx3(JfxJM z(_@B5V;ge_SbI5GaDIc}Nb85+{hWtKhjsN|N)!&BQEC;StGB%iXA&_+AY1f`sKiF1 zd(zKUL)B%!RwRlEu^8d(SgXXV6B9&MGRe(-H8Ykl6usXqrnPlg*U~O&Evb-5kL|6v zlrMIzn?c9+;~;`xzp{bW3|kayjwP%lvc7M@gOa}k;rP4B&zO#k!pLFaJx!v<1}gxm zfIjW_sNfUw{BTrkMNXh>$L-6HlhSlGkH58HPz=-qNo}p3>J(`dKhx{iwVo&Wg~2bj zAKF^dO7rnHj69XZ+FeV@ASz5@>R+#e&;<4T&Kt)&_DU2q68)Rb`O&^OeIVC-ld}wP z9XMDVK^rCMP|NV!belTU+6-}5ynMT_EZuAR<2kW`51Sz9q?ot!iCIfh|6oE>s)f}& z+HQ=Sy3y8Jn(P`;lX}OV!7=XeidJ_}xN$lxq;OWLOzp)n@O#)BzG4?gnh*J+a(xyv znKn{eXoF-8?GBt2H+{Lfjv@De>!K}XJ~J*fnfzOOpwIuG_V8Qqf7-){@c*MdFw|I! za^^IxHfSRkYUUC z7_N%~q6pVsY8=X=C*<-1op52NWf}*hAY6=2n`Hl5qL*0uAxf@k=naJ3Y5a=Yw^4BN zqa<-~cy{!t^2ZT|JOo*uTk)AtN%uW(N+kzad*LaLK`jIj;m4Bb9+8S6((NMDxxYZE zE9~!*C}tWsX#RuDJ|eVdAR2VX)uGh*9J@yb)DCU#Fu%*fk(wg~{J%~4v-}t}zs}V& zIH55o&+}?!`-$TtMDezCL*J^CKp0E>_q!g0tLg;4>n5-pej7R2=cGA}T@PN(0%x+s zGpb|hQoN-G{0R?%yg&GK(~R1Vx#_iz!Uu1}uu|Ff5FadnA~* z0F{NWc0u#kT-~8QT)~Qt!hGmNZL*2+k`P7GS0BH_F=aB1+H+{}Q|b6X1Rh_3$7}~q z;Ohmk1wGEb6%u@RU$0&?4N!CfYxO%N{!WrLv%3yQ96&011t3kQ0(C~&Sr)fuwBjyWp`bM$?P;NtG7gO+eC%{zn*yaU zt&2X>$~1j?w1!tq;qjLUX5MxfslH3br8hjSW&%Jrn}x`dhhW10Y7e(!P}&*%inlL7 zBwTQ&Ml0s!i9~o?M#zLoVHGb0(^gEMO7igm&T#yBO|+#C0pTT10%P{ChkZ??X)mLe z;Hj}RBKs?5&u8N@D$N|$#b%$vijm}OS|-zUc+?c699L(P=@-zQCH=iJBkG&*Bv$mN zZ~7Kjc?FB%&GRwsRXZAHaLhV$Ivxz~hStEEGYg?e+JQVB^Ba6iW=ue+FdEa2d{aKu zPH@_f8*?7VvUJgACbdQCk7uIt7kOrjScE$w;iZmL)V-t<(vgsA0t`#^e`l*w%1Mgq zaCle7QT(RM868|~!nJ^#hu5N>le0vq?ZQDP)?=V(xF_zxD_ML>W&_?mHdEEI0EzB!9W~7ADuym(W1~TAg4Utm3 zi}G3SiJU0;o6+>hYCestMlofX3l&Pi=&o&1QadoaKZTQ4UT&P_1n~lB*(A?+EP_w> zkGUf)+rz9g8m#0)?IJQ#^9uS$my1m%$?vI-U?Jkni#HkT9~DxQ>8^1nEvk78r4N-~ zz=?k&ejEng={gEC=;k#ZzQL_8MrrR4hJF{a&h;KZnwY)yM67SXvPO`i1upNz`?Ie{ zhA2bPDmak+n6`%tx_;&$YWlU7pI#5q{PpNgJ_z+Q1ZelT=X{GP53n1rdHSL;ec_8k z;5N9YKTM~`2;34jMpY%t6V1m~%8maADhbO;zGnm_^R@dSP#O9MEXeylonM*bTjBS| ztSeJ8tDS|2=^NM!LJLDwd*v)!*dMm12Ri$Hm;%)wh9soxMSD3aqE8W%+v_t>M<6c< zKd^kn<$mwd4#s0_~_R>^#R!c{=d%z`g#QM=zzFyT{ zv64Hgl^Wzr8CS!X`QDnB06gr?JSsdjY3`f7O#o!Y65-KvJETrTvOQc>J~u8!C;` zFO}`3(PAau;=nM;fATr>(yG2lnn9ue79!Z;sFQn?!Rq0yT>~$jx{SId9_@lNUUy!$Tg>Mvyp& zNw{YiKtj2^mgOlpAYmUW?&<*oHi;5UL!%Up57tQhcxMgq9Yn zyI2*QyE{8h^N7~=IWWomOW|!iR`j;_q)+t&SiqY?&%bRTJIw(6Za9677djVi4b0^A z6W^Za#eQ9D7uy8?Ln|#j+yEtHc@uL~6qe%B`x!7zx8JDiG2>01AEke+Wc3eALoQtKokTh~10fZR9zDZbKcbtvBa7 z5lZ^9CG|lDe1$C)PT~}#(lm}cbsz+(^oT0VqfZgAsR|@)Yr>z!tG0embq(SP*Sq3e zLbqOpQzoi*`h@ekjmwtqKWdYaW0MIy#+dxc1KxG0&4mQCE7&1dv%Y|v;}k}85H#>O zjuONIVPE=hE0^huLHno$unZwZa`;i+m4zxh183$|t=JWL4|A* zJwQIThx3Ki3_YQY*k-7GASBr#@p4Z+f&$rH120p;3V9zG=IL=`?73y*-iE*c$rZmC4-FM^v z6o`_qe-sFsT<8h~eL=x3TR|F$n6&im)p|4!oK3bp!+$Ffp8r!Itm=9HPl1SqUP&ii zo5U%lJO#_GmGjO3-02ehT#a&73efpI2Bg3o{p)G#wf0wFk%u2JU3mqQNUK`U1Rh)u zNtgzdK9N%AP;=hB*1>E@-z;X<`Yk)*#v~*CN}fhymbEgB>DugALQRNAmwC)veklq% z>2?}ie+H1$E7E{>?)U0r{%CX>DBFM#Z5S9gm)mRM#sIDp-$P>}Defw&Wt0ABzmQ)- z8ps=Lu6`!11B$^_&n;O)iw|QuA@R-qwL+BB@GQBt=m6`_C1*%V)i>bLa&r$E?G zOg$-+uRyp8-mc}xjxkuODIv3gI#81g8H!(%XkMXE4Z|c-O$%(m`OJ~k`fd`Q+>k+6 zk{VL1P1uv%P!nr^ZrtU0lhs2R*LpvS2s|%^j9Z!NnNxv9?xz(D#AnAMw(frr8vgkK zyq$4(5{L&yqE76}^y%=6`pcafU|cf#>o@aQg5Ac2$K|-@DMb@NKY9v`^%O+xocKJ{ z<})04F^vIzlK3$3TWh8Q*>J&X%W92eIx#F(Vo-L8CX1*$_?~!`f641P`yK-<(G0GI zCzR54@;$X3Q6*JEKwH7%tGxJvCrnLmJkI~8yYW|*h=Kgt2zZJ!0!?@_{BfZ>1P{~) z|Nj5S**$eSi4lA~8r(!!5+qPY?S#ia-ZQHhO+jerlHRqahJ!|LN`ToRcZS>x+ z<1{{+`))Qpkym;TCCQ-SvJRYg8Qh-tuev5L)~qdUB6}89K!M+{-pM%zt|^`R zW~gh?wYr&nJsAYSVH!tMOST;SZKq`8ecypr`Lg?LXfq2M!_s*P!&;TQ0~Jk*KTAF7 zfjl=QEuL@6oUQM0uTDg30;{QCNn$VBS41S@7QYK`oaor)6J0d7~&&& z!_mg8`=~-1o)iKl<&C7Tdr2s6oKjve*d^6Y?9wEOI9=e91lGHMD7Okcb?S3^=jrFe zZR^dzwaD)iZsp0F@dMI4Ox7`AQNQO;w3x_(JV{S_gpCraJ@R_nT2cdX8#Auvpgt{@ zpItGOz0k5So;d1Agh&$c!7MyT$G!mOf5Q4vBrpIiEbr1-Zj{suhbSi{8O z`TLG6m|p$x?KWUfa2$;YsJ{H-Ax1@T5+R~A^cEertA9IFt+TE54ye{Wx$IzeG6tQ@ z4P_+r(8D1)Hosw_c)R_EoK%{F6IOt6mRi}55#Vp9iUoWRVNy6nnCgju0QQ@p_9}}7 zidpm{TBp5%9wq&K@YA`vG!Tl9KDv*FoH5?_-cYo0CTc826UtMdt$53L+0I|6R#tf0 zmSn5)<`f->y{DJ4p~C=PQlMkpl9w@p3gMgg`B7?TMyEJ1QFl)W&_WF^vTw`UBk3|uL`J9NuTu!AE;SreAq(}e;>#xR1ll45Sr`5!L6!a?d5^^7r0+G0lNIs?PG&x3> zX}!J!%xV>z9Zh7|A^!+Vx!`N7#rBk}?gs3Y!0ftpJ4$Jz& zVYK@(tYTNd8Abm&?#nWmz%B4&Vivs;`>m#ix>wqf&KeqTL6C8!LuSQ5YN{j10oc?w zRu#eVDUW5j`7`ipbhZ)P`?hZnJ+0Z9^rDKl-EWy2ydE%d!0_R(2y2vmKU?IJ?3ky){A8u&ak0RY(1 z9UIOI{>`Pkj^Dul#m-B`sh^yP&j;L!Ii1$&sdrmpIg;8jTF6**+ZtN`TZGeUJDnj& zKvwBFSzRL~Yu8~8Ps6y1P7m`u_HclcM!eego)`S70~N&=h19@;v6swwo>ZjJKDPg> z19x|EIJKeQpi6mC_A8DAudHLkG%=P&R}^tFMD%Iq0oZVA1a%V|N|lMHq=WLsM|F=C z2Amhem83NI3?JCf-4>6weswS%BIa^kA&$P}l8ceKK0eFW@o6RuYLK-t5~Xwbr|7`J zyTjnm(7FAV%e*L8<8@E zc+Ef!Q%v94!Q+gm(V~3UghUe?z^dbC9G>hn!V|i=+yK37##hXurzR)?lWPUY+}n6% z$m#pdQTXC)f%9M|S(fN>s<2qIA#lyO{bm#`F%ElUQODhKm?IH&fLAGf6upLiHD<6{ zDJh0`i^%GFNMY$cAVLNt;#yQZU9mF|Xm9QTRpRCI<$> zMO^SLsio1I4y;DN0)MS=a8cTnUyk@pO6vYj%2rb6t*13lM}Il3wyfbo2N8VuR_kTD zv?rSE6KULG4LRUxm!9V#=sV!u2hST_V;!+;>w*kQ31=;o0`|iOhE-vw{O&`LzlG8O zon-<94+9k{G-T;$zA`$}f=v3wc^IOXwik)hC1JW+AE(56Yl4!PeP*Do%vlLIoCPHz z4MmzJJbem>$E5TmKct(&v?=I~kRr|~Upb(3X)N0d{13If|FW}tWMQMh)k4;ZGNK{l zA#h*#|6R7P?)|; zMLt~lgHN-(+`K=*{Ne?lY*It`kaG3p?eG?D&xS(`>e;n7%rAd&e|WjA$X<)q5b@<* zr&pAx;d7|-YJ&ztxG#wEUoM|jf=tnz;KNsS`shGo)gal%xD{^so3jpQFhcHCm9uB#Z3NbQ(PGAj?7ezB z2EU8k6=y7ATW(1b(3;y8(QJb4%|=#Xf5u;6TZ#N~V|z}EvYR}-dSL(a5qV>ysFI}A zxZntXydCQZr7(As%#oe5kvbg2)M_{*g+w`jA?>eX0>w*fVaDCbs-SSED!)3y5|mc& z`CxM`Y9?Q#gE#T63}`Bi^Dkp%E)?Iz-WK-A-_xCUtn+<`=rCntk1h`<^l=ZseTew$ zqh%t+RY6yw-Kp9#OTJ!gYe^B)uzPI#IDzVL_+MkG`wtmYu{lgMO9o>0@|>xdNL`0y zzcKGYu-LSOP;{P^8@n={a2ZY-y7MG4ihQ$IN7EN_^q(Wvq)u6-V#c*bE&{p@g?qHrdl9gIfcPrg5W8ZLn6;2QT}RoCM%%T?D0H&odN16o>cMoh9ECy`c~?1Mq>tKuu54X z@aXp^nP5hk^-nTE4zUL2tiA&F8K+^u-WCA2A_kWTJ$&8EtCKG`B|C>w*G@pLp zcIZhC+ok<{*To?^-QH;wG|T}`tZuotkct+SkoVzJ*7>&0eW6O$O!8yorS!eZQfnCu z-T;{0Y7_CS)X2sZ(C0wZYJ`#CI(2>6Y;aBQ2r;0k9!8AnX&pu6^)f+A_&X`VLomk& z=BwvN_O~6%e}f4$vi}!Mu;7WR`UQ?n4`5ia2h%)4mRRlEweoZ%g4kbnMRHZfByjv1 zOkP`_KdF#Aw`_2NhdToOUa3EDQDT(t{Z}u6?!UbRb+XYQXllT}y#&(#_7a-bHUI4; zK*wy5{o6}0|MDTp0^+1ck{lw0@Bx+xIPbaI%0hf`?5NjP3TqF{>)G;VNbF(O70>(v zCvp!K>2Xhtt8s2c{T2}QWl#5TWd7b-RXZMslNSAFOl%dLqdvEox=7EX_VlHb+#o;W z0}B^{q@SS2m8mC-N_?$y2`wGDTgU?w%?!_Mw~4X9zGU+DI#HM;SznfT`|$+>FT-`i z<1FB^Ouu<471%L$KbXkSx&T8&-v1yw{iO@_;XLhK3_;| zq$?rO@CqAI|0#Wjm)L-Rn0rmXf@fM<_Q3%1!e}+<^BTzZS z9h_Kf=Ho7UVVVlg@e9v6&>PO*4QoKib>92Dj~$k3i_2KE!DB4xvS+%_hTiSsl0QVJNL!)WNzfWO2aK-h+Lg-B(wvP%d^6#eDq@_9$j?PhH}N00mg~5zrP?Q9=yg zOFEX^rf~eO8fVl?Be#)LFqcSnF{k$ebuX0M7HR*TPzlhG6Zg)gYP>WN+U211;XQ;n zTTxJvie`gQa-cj!kcWPR3*sr4qc93u)6WPcV~IFYN7lVGH47B_O3x|dc=l48gsr%9 zlPt;p_&(@uSLM|2u09qAv;E4_n*oef!=<{K#D-$n$0vh3?u@&P$glNtnBPJc9zt;M zTl}G3eftkX3M(x*;H1;UZAa!ZkQK#*Wspi_^r0J6%1)woPuY7c)5-IIwUJq|TVqQ? z0JGE#MMjDL3HlX8`K4Q+>$lZd`{BEpI)R9JjU&+v(U9D44#FMMn*La5AWq_M8IEzk zqJgi`@PWz2|(i*kbDo z_f>+GjRb1M;vBPv?umotA^1jSzzcbQFIu|wOSLw(-+eL)>VtL=Cao`6Ya_?c(hy>Ly>W%c*7{xe)&UznF;rIML+)o5Tjj~C1n1#Fvfj|H~ZjfSY zMsyv38b9e!472n}q6;I+GK%wC-9VX1a+0zaU4lQIoBHi$f>pZ`&G(4ISVF*xMk_u)Lq=mdZtT>@jY@g47u4C zAC51&3@~-g3aOufZ~)Fz-(ru`iXurK&M1c8lS_J-SBRY)C z);a#-uQ1ZZqGE8jA`PTh9sP@YO~Ww#On=?ezz{AuHRh zi7PVmb;jg*(vc}ycuD^F*Wq7z%-R#qL6t#*FMyMiQBfI@K3|8#d|?frMLZ2{VKnOT z$m1Or6HH}&g@=*~M_QG+^*lZKvBs*YPT}h%|Az-p!y`FS%6fR-FMdh28l`<8ZLVDG zu>k+7xtw25_U$aZDb(I>Ayvq<#L&zL*gT<;9*m``d~GZ%7iT`1bd2M$lV^A|m#r)P zvF~g|)sYg_3DVG^l~;)VE(i!^Lval)B@iiU>r=2o?v?EgZ0HF~Y|ZrAHHT6VU{Fgl zWOB1-pmiv%KyiQGlU@`c)qXU>>tq%_7NAA+V~I)Zb4 z>T6;c*tSzkpMPsF7`1a-s ztW*2rmcV4{bvoA#iI8G?4Nn~7+)g!IfS!9?@jf%efD-?JYjI?&C#FWOvN*b+W4F2%jho; z@vBjMvd{_m@?^8lgQ(9Eb~X#ngnw~X&&s=TFcEIzMp3)O`?5RA-v|c=w z{ySTE%|3BhkURso##>TJ6$&aytS1Rd4-_fh=V|&VGE;O~HHT{6;Kf>6sN}|sv`Fgc zxnOz(7X|VB3iGYX*f%i_N(7i6YrCfC0R^?e`Sps~ACW@>hI#(m-V+3RO}t+9O*hr1 z9|97(@p2Yo2Jvv_JT*&ND+`u(XJ|3S4qUtij3vgo4Js3iHO<=LK(MfW}T0ErOY|I zWs+$*^#0MFVf%rQd)dn~cp1R%k{)m^E3!aKGzN;Y?UV5a7db?L{4^w`5GLzBxr9t%?3(Xq21^tctmWy zXzN;MR+m6^6vEVLJs}u?!1qxuMIqFRjFA{kKFEZOlnf=LK2<85&nQh(o2a`ak|Dl0 zFLyF8jzWC%ZW8-1kI9;YCnHaUeJ)b|x^*3lV=GD|ErZ z`&cLN+znsX%o(@+LWj^7N2FnDi6z#dFqf-tF$ALkBq%Qod>L7&MDNYEc0aRWF`b#< z6J~03Sxsi+cf{u?4y4tJ!(?8YXY>^IbPvFFCa_JV(?@~(0?34IuOmPc(1XK?N&z1n zr3<2!Mb+pV2j-7%nlJbjR>6-yp9s@iWptZWeeLjE{EbAH~nH0>=78z=*G6xMpW z>)P8kksy{h*6OT1C!%5YJGa$KR3oio<{#GDCg+`v=Ks_Kzb7KVbsW$x0S}A3uiPrF zqLd@Yn{LV>Ivd$B8^_NdKvL-=JDLutI@nLA!r7efjX85cW}5ZHa>BrNO6n+?0|2x- zF?-0I>nlmxkbb78!k4^CnPY&LU|N=Ucw{ZU;+7x({`~_BYjwi^EXO%%phb82(c`Pd z&sRt{x~+yRuyV3kMHtkocw9wjsV&9#jI2B3gk7djyW3RJovtc6)04cxRq`MpSQQ!x z(0QbBFZlTUG0p<9>aA#(=(;N>G~EeH2>$`ayLPIa^pFxa(g6dqv0WNrOfXlJEH*|d z7t~J<;ZuyU6JAQhM{e&J4GjiMWkpi;}>QT`2l!?SiVOV10~BZs#H8oY5hMqYje zOc?b&oY%n2IDdGc<}0{RE89YqvRLfbMdA{~*B`Wtxq#tROszakS%MQIGa=%DRNA~U zDQHFR3odIrGwE$g_fm_KFnT=4IWJzQ=s1EJO%d8Cu{2xlJ7n`bmh@bQ2nOBSr@v5( z?dM>2!`IS~2(v9`J8s{fGqDE|r{r_6e%m1;SQDk8())OiXuX)98ouXg453}L&LfA> zj7)2$9DG}nm@<~TD7>cof4lCJWoC$1#P(6G(U7X!=+)*$=d?GNNqK5Q6y2sY^*^5k z`Oome*Rf|MDL9+u9%dun0611~$L zbTgQUHgcm2J#%T)`Q3$ybhvj{nL-yjD~7SiB%KyMVI<>iCOo2bi-GnLuPOmt_%iS4 z$gE36pfpKEqVtuBf3CIa+_6Ze2s=K`!mE$rcIIaY<38bCWTit9{=NPr|EAvCm!>US`AyLg0A; zDE86(k|j&OD6Q~*7*xuy{$vcUQ!io2hxM!Cu1$Sao3NQ|I~En!M2UK0|_ zYrH?TkN1V+At*a{oh5AX$QJ$bDfZ|)RLXD*3vrc-DUgFgAM7?>;~-_-4=3d%o=_X{ zT+pr9OQs%_OEu1>MQR#;4b(xua6*l4IAqJlu%5rN4&$PDFeCPg?K1kJ%u!~!FcSmRvNIhd#@Ou3rM25BSYIT>i$ed_8X*P8&cLBMf~~l3bT;f%=VU{ z@P-n{KD!!Rel!3Rxrm9QHU*;&3-RYABhJrxL|QT0hJ9tRF%S74MFUp+zz;Y)F`=ef zR8|A1S(NG<#9kdRx;LHZ#-a#d%e{HuT;+AV44psH(gYASl+O%|(r=pIctwuWBjp^N*0cX|-96z010jjg{&wAc z6baUgBzqYow+;rWFiG~|{^PnA`Iu5?CZO$VEVF7k%Hs8@|8d;|wKG)*kvw$7=0&tg ziK~BITEuF!HJ|SHJh)CpfXyDP=D|1{6^%-rPN4Q7Snk-E1%R`t>3*}&sSR8+Q!K~* z*LB}*GTJYWD&WA5Z^V2Z+?ye=8YlhNb?^8;*WCmvhw~rT9r0h+-M(8nqq@}VZ`Ymh zB`SRx?{I3L5M~05b_U)PjBSFT)Dgs)kr1}(4DGYUk0Y7vNgj{ck%E&i6G^pQNSdg4 zw(-K5^EP28TUIaKvfvNy5Nx*1r|PG(JrSeiKcT#}u}sYB@orF9L|sB|p4HiYzP^Y; zfw8lk>EO0m-z5>duB#}ej^|e*4#8{3DAy^6s}mWnW@4U0g8j`Q9dmMLyu19HbXgt3 z{AOoq{c0m7LYM5?7VyD9^n8?4U?{71>GZ<qxnSLgFJO{4jqVwd%J|ap?O}Mnc$TD2A0PU??Y>4R zXTAC&Fwnaq&yLe}%=<*33BQhGb{8WKh~+$=DSO#2V%Zu?E68MyplE-}MVZ~@;?h)T z2;aj^EbVd!t;#tVfBRUo!BdUOs7(yX?)eb0^bz;2Ppg&XaK;l1thG+UdL+o^{H*sS zxsCheQF!W#UT5ONn~PdlxjiH}$%5bWEJ8om;<_oJ`^Av2sz%7~Sr!L|xdRkVisQm| z?|stmEHntw7B$q{U({b(z8xD(^hOW)lI_fzcqrvT5PCLf`H-&G{N!K(O^nfMpb(L` zr@nAC-fa>RM@^Oj2eBC>59U$tfohdKX)vZAd!N-)muk@lh%28(*-5K`K+}kr9K75_ zi>9p(r}5UIiHA&rW_ki5E=tP1GS@#uH9viA@cwJ@6Rz-x4oK#EIYf?aJW}=N-uB~R zliqHX#I&Cr@#_QDG_I|p$pj9Dv-NHfgv$@Zc-rt7eSpp^5Fq~=XI3HT)IcFY8;J_I zn9@@k{724r0fGF+4LZMt6ihX8;yZ|bY|jNl{1l4ZCZj7x-4X=-TlnW^ns6QpKcf5< zpLW}zgNa`9yTJyXz#C0o#d_T|{wVxW@I|V3v(rv34|u2Q`{5=dzBdIZC{_4jvWXiT zr$Pr%8}x_lobhU1%QVmgyOSZO#N*RTWb5jSjhA$X2z-R1daWjXv5jV+ot!p5r-15t zGMQORhGyYGG@R(HQq}XQNarXb26d;^gH1ans@6uC;m2be+42~QGiiicHY0SbXf6lv zL$L`4;MnCO7SQ_zM%SbnzW8$D*7?J1$~OH*9;IaRL{*l%09lZ>-nOrpR*&%?bnem8 z1;{8LHPE_nv437?#YFHI61vY{0sxb7AB6g(O1)czU3PN*v9AEtmXM&*4{_!7HurSD z1s|y)1-aKa=nyOXuUiZZ4rRLQ{&ks{PhUP62**(sPN|P#X%%A7ZbdjERU2wBZ`S>E?Id2FWB+6APFz@Rp*})u3;9q)&`gBj_O|I(Le@+_` zY>=qvuoI^)8;cyHjFbCH_Mj#V&~b;Rl#_h05vC?0yYe{8-&fe1_lihx|IA%PBGW`t zc0vj)&f>yWuLweV)rneO1mUbN2IR;_NR{XulbdLt>P-tBm~1~wkz6=RJPWV$>5E=F zC+H2*1A3U%I3G&4p-`~9++?Nc7~Xs;vVgVDQ~HY3F1|YJ*jDxuNAeB@BukX)hp@xv zW^9t{1X4gx6;-*MCV+a?3EU)5bF2h0(O_G2(m=;y4_-6Vt{RtSvIh&3UYzyS<`m{c zgJ&2rCjyWlFSg;~&O)@8F`kcb%*@6X(ilk>muu>^)xPZchB*jbx5%&wwB)V3Di9uE zA<0j?8n>OYZ1EF7+V=>k0Dv!glzYV4aoS#d5H3m9svcP;6XC3^K~|jHn@e$vqzjF2 zL}FJf)|}IUfzPOxHq31%-%?Q|JhN~Mup>@=cPoMi4x4#)MP5}Xa`TU!+=HrCo*9Tq z79WYXwssTLe;!uh+XX8=g`i@>T#uyqY(8^4>1hpE=l}TEyODfu;T&J`2@P6l{uQ6h zuFv2@Yg)rGX-M3<0c`q1jV;>vy^}xqpg`D}i-m`cc~(c=cnf*pb3mxkbxK$@yd|gWGW*(gg6Zc+tOjI;967P!?ke+5SNQ9buW>CK)uJi66%J!sD zzOcY(a>w+YAKyZ_JneP}iSyTHJM2HdxI&%jWTqvoWl`peY_vSim{_#=!}&h6E?*
yUw$(!5_$1kl;Z~aAcfS6>w%LaaOJthfqNh{AaoFI{g zjD4FwW!V>Vpag$efC3z6Ia0Y3t0Z{koT#k`5Ryk1SiC$eexLX)q@xb&oh*7-BsNh`An8}%Wye_??C z{o>&;w9C|4!v3HHP8YZbBx#hOR&|n1tmdWTz;oi8aF>r0qH^U|@+9i}db$~n*kpM< zBo1YPxa`5bUPP)5FUD~H4BDaR<5y|j8mB>iHsS3bT;52_vyDl4jqUiD3|f%ub3O(g zqAG&E$&2H_@!2}Y=4zn#B5&jAiyY~^9%N?VKGkM}XhVOA4x7JEat5zu4wa*N@ zE78e7a^ulA$=nH;n>;RGvx1=Ecx7BeY>&n{!H`Y!1gA(fM-3*~HPAuK;Yd~9(x*YE zWzd9M&&_>7@=(2!~Qj6qgovMg6#6aIjB1XQFwMJU~Jb3X$3G;i}rMo{R&RJgN*ln?&u?g39Xo44t}CL z_bmC0YyqVE4ZV$f`%v1^TMt$k`D@p#~D7*U|8c|@$W|J(VIyJ^^$dS z_cWZy_29NxzV9l$tWEsTJlTO|6lwsd*(`?N|rS&I}B-1=JZ@y7~g!`}xUp{6viqZ)`O@b!hVw^^N4ta)- ztj4GbThBctAz_t6V;YMc?Ts63yo=t3=aW$eM1nK04!$D7kAlmp3E5on?E zUWWc>IC)f3SARQ?5Zd`$V=F&lwZv~LSQri^9&OZ52(H@WA6?v@SQbIC+ue^b(MD4$ zHK0>-T*}{ZL(6M1>^z*d=S~+Z(hRbkPv7Yd{aRA{wr6zenXqP?IF<3KVI^~#NbOf0 znDY%PXPb@1pL9xTDT(#x!kuTGMOPYvWj|}Rav%}x7Gs{p<`|a%Ho1YvLF>>$P%NPR zolgSclj32T8oNB32Z!Ox6Jb2vmkLg-v~52=k>3!O9LJSDB%E7#ibvGk=+#Zlal zGQ+6!S)v{|k=_cLB-WHKD+=Ip8d?m9D;0dn&KfFNX&3{|!F-{Aizx~YL8s)9TBZ10 zZN)-^Q`+5VbQ!23&g(h8YR0ygQTAs?)Tcdheb%h>{ipW3KiN4euGkDaB-KD*4_ zXfHa$|5j%p2UrqCL@)H-iQMx^kDbv%nL4ptJ^3TFhqlt5cG zV;+^nAKQWe{=OK(D{=D}9oE;@$KRQfAnWDNLk_rAObDMuky`R8+iyHNTOl0lObxR6 zl8ra`;FVAoLNr4HDaDq*1o$eajDPo-Kqe>%V{NcMCF)qgb$!<8(J%gN<{A9+>D1U) zyrFuHXh(J=Gfq!|k%OcVnJ`DvQ;a6jJSW54?BnN7s$Umk290F6yrf+MmS$PJiPe~^ zur#$_L3ce_eiI+nT?`oC6|vtiWmsBzCbPU}!a_AYz^EYXabUVzqKSy^GRbwQX%`SD zWJ8MWs3p%3B!-nNpQtVH&hjXaPh#XNHBm07c1N~cFB$hJ@*URID?%;6_t!@+JW@E5 z6Zlt(_reMMM~Vjiygd^?w1P7)3pA+B`g*;B5-XoD?W3mqNB7X>Rr4(Bf<<@TEp<#2K8 zQ#|oNuNV`duIPOKreOO%O?HRz@;vB5NN9_~YZN!4Bdv>&6FRB!wUI$y)WmEC$^yq_ zbn@wdEkm^U74cRGe7lFU{Nm?AFYQG6(8J&ouOaq#@uduY)EsHgANy=Q^6HQpeZwDMFjVuGR*Va8e>?Hft-gOd@go0m;wRyr>TP0pWenT0H#Bp9 z-((&2>qH{hjr$%sK2=a#UzJU@4X%{d$NUrou)EtIpwuA0n}KNLv_4^2n%}5*>rxXg zclVDCCL$YNmP<*&&)Zv;I-=AxtYdj4lrux%wUi`}nvB9Ib7{H|4SIS+a=!6D`e(QF z8DXU)*2}kH6ITt~?Z-(MZiAV7{Bhz%T&G6Ma2!9^!97DfVN3lwZUEVEZJ3(otGVW) zMKF%tp&aGVM0_YjKaR_<4?j-a#)!`;`#`Tv_F32Q-Qek89$98Bvm$~+lBRt9#rPlm z?{;f-Y*6%;1QcKyHIh(Txh|wn)c3v}>PObcY9)S1q9991hWpUQy5k&b>r5d;3%PlX zx`}1J3~{>z7#xxX4Jf9M!f1((3Q*=%@9?Y%X*NWc5%?y}lvz@zxKdpH>%>R@j}x!_ zj}wpiA19tK(euAf{8cb7k3e=;TdyW4Lf-?C#X&{&v+kVcv2i5N={}tjx^2C3fM>Su zcTEl^irQ;wL2u5^~cr|KE#DPAx($NmMh%s6t*#wA{v?IIy)cQ)p zm89h?rgaaS_EI{nv)pVxWls;Biavgq;(^I8zM z6JhXgp-DMa`GJMTX;sbS2|T^USfFn%A<|%?uOb=iDo=Q-^RY8enV8P=sz(uDq zkj;mqxdoE}I{&|%c&@#vmdvSqfNC}GC1~@)EH6p+XvQ%_$P0~#i_B(61j7oLvw6t|q`1xyP+Qfr65nR| za|mm|0G8@dGA_&c6^)&XPi^=PI_o#a z^a<)Tr?xhW&_*ON#S0TnNIaBoYo(qyul{WrJT#IF(bh2q0)qA~*_GCuGZDC4{+uam zM5EuQf!sI2O;g6l_2gB-Ik$V&b6?7>6w{QF#M1JFUi%Pt2JsPsBU|0naNBY|7S*4yLZHSb zs&&^b{WFfH)?S<1sIjasu+WomLj2M+_#gpfTNqJPwKJ7$`Q2W4rbC&^7*s-jrs1<}tgs=DyeNucEeoklot)?UL13`3) zHiSX~)Kt1AG3ZiR%kPxb;RwoT_Nu0-tm02YMa5u4qO$c2VQ<-@CiwYhDgLBe&>EYz z%cVQ^K2|QFjEdAD9;zMG8Mnh!9FWBg=|Ldm00FGqZ$Zw~hlCR@ zmT%v7@v*-E;qEbxJ{)M_#xs9p+;C+A3h`wNU(22z;O;GQllxiTZwy|8_!!iSkM>er zJxst#i98HR@L#|&PJ;p8?_&xl0v}5d$iw3IGSBYjIj^#iaY+}tS{HRHd2y`zp)47frEI+>zV221&*N|DnI>cs!Yy z!DwX``p!9j;+XHD?H&(`1-|5li2IIjY02IiF8VNli-rtuf$Ye`HTHs(bBG;3+2I!p zmn?s71}~G<)Y$zV28sXZ@uLCX%O}&pXjzFWDbU_kAVg%{0FYJ-~w`ufx=1*|jmP zL4MNANon$cur+SGneI*6% zT>y*v-Wm>#x@96-&FWa{0KnRn1DW7|?0D=hh=1&Ot?D<-I#q08B8Tx4KD-2!I4?!g zthlNIHR;1IWxn2}RManDWFGIJ(~~BxBkP#_W@HsXpd^hunjPD1Mq#sf_F|bJ(Q?zR zUviwsGS?1-^M-MPiFr_|)3SuX(8c^%TrSQ(@Mf^#!J;#Iptd`~=qSO{&L z*+nd3U$7_cl89!7c~ihuWajpgG;1hmSt8c7RBA4KWd5q6GRp*Kne$jkKA;0^_k#TQs4vyH%ID~_>P~h;gCo@%aEr%wvNM&Hd z-|I2*sE4lkl8H&!D)W3x#V zAgpDzwK5G|S93NWBaXl@KyFX+*VXIdgJ%TJRr)f$W(Uq5jOup_T z&%JzJs%YS}a?i$Q+)p>zgFLv>s~W>Lwc<@A|M^pMUhD3E)BV?u=lri7&yb{4__rOO z&*YO>P`TOv1vmO6x2ILJCFJuna^E3pKwlxS)|(+8G6U|YK;tMm0Ft{sW4?H+N6VRi zIGLrMWM3UhH)3lwg9IuM5DwXx0GyF>F8TgATnz!xbbbo>D1~~;PvCnO@LZp%KWG-W zt-*(4cES%m$g#tTiOHmC%Q;DEYHbgZuY`B>Q_ZOeZoh$tO6BLzX1ZBgUt)mxF1d&# zeDANOid5_{6~?@V#h8=X29p;$h@uafQ_Ke~0GS7l`c!v@FRuqKH*F42#`^T$@ysV@MKcYhvS0UjuG>~>bY z$Y2cdOD2R{$TjqyvGCpjwk7nH9cEkIw(a9k&6jX)11+o8MmOMT7-wGRjc@5AKYw|_ zP{*}fK6L9?cqr?TKiR9|I|%1_$dvUb36Cta@sgxrhufFMH})n~+8@KQq;2qX!`;!M zKJ+d+#Y-tJTevvu9Pq@Dml^C)5R?u)BlyjRF1t&x1v;sN25~9~ z5uDkr!$aEz^=itYpOhcOOQ2r7wjNZk&JSws!as$|l90!PMRmt;c;()V)J31FY=cZj zR^Mu}w%QqIsxJ~gzUsMww{=v#wPr1n8KtFj@LoSZGhQc!HHb#i8LOyyb9O zl8F?6%KSRhDf&dT6~U7miSk?B;z=zg^p6(z3^Qt1LdKfjWA}#K9Et%E3`i$}=Jqn3 ze73x7X+n6uXRh zfO5`wkV)`oCGIeSGh3*Ak9;FP%3hk5{q@ZW@D=YliW;@{Bpddj^@W_ze>5f6dVd)~ zPCIxcbFH;t7h;Gb5^0PuB6B9L2zgF#Rz4s5XmF7|ojgs9dOzeroWAHo>`{W&#c@}N z_Zc3SVp-LEZCy3j-5yme3Tf@}w;r#hPLAWh{+Tf9cb1DICML@y75{vfk{_D%NmeJs zgG|~pBWf85HbZ(dlfqp!nM$l@#-bk67;kvD?yrb8_3)aoN=^IBXp-(LByLBQ;-M7X z9B=}x12am`Fst8n)b-NeyG73ka?3tolN`NC7g1`&&^ZQr+5D`_w=Ll-{om6p5$V^1_QFKVy7p(ipRlx)AFf<$O zr|%~ZE<4oH|Ksc)w*-Nf=m58E_q1)>wr$(CZQJf?+qP}nwvoBXO;-LUZ&9btu5Tv~ z+DU;2>`ZjKK$U2F8<7W#r9bFUAo)?06HZ!4#^CEbs)pSvC5SoaJvP(k6QluZ>~T|v z-wrr`9t@rOkX+IkX3JFZdD8O!7ms&(6XWN`cAG1&?#Mlu0UdDEu=eOaiXYvuMyXQ2H_&j=Ap8p$w{5@d&LG%hJHgaOSuCz|SMP4m19!WS_>o%R*wk z_QFc58s(ibNY3!$}thcxb<{^dyRYgS!gOpJc z>)W7dv9DC>?UyWw52qk*2-e>8{9zSONU!Z>*#uf8!5|%Cs90)N^>hDj8xNE$RtSol z>L;8JkNq_KZj{Cy@MN1Hmyt$Sk)Gu5*oKWYxib{h$4q+%h#GijjmeK5m*KCVyMu0< zk-1*ps(*pVIqViKE?Rf z(Rw@=e=y}olGPZq4!$1s-9R{3>gpCmB;Rf?lDOL0oIE>OB);pTcU3GU(X29=M`ksZ zt5=k%1gmC^05*(NtXt`oJ-TEyrt&eVo#2T9qk#z<3#0jw15L~kA`DzO;}RT~|6NQQ zR}R~?4gMEm+(kDpO0?ggc;5Ia3jy$z8)X}GTrk|IAMqG2jr1A|gL;ag`Z(!80^JPF zn+D2KAJDxW|4rQ1)CAhU@GKHF^r5_iqhw$$`ZxDa3jCn_!I&%JYVu9BMZ-Ni*W5^;`b`}?hzN<{BN)eL>bs1U-|x@k1Q z&Yz(tyGZJ3(c8`)dG;1^h-97F(5ULQ>T)kBogcOoNU}xJ+Z_HzOLfbqH~y~g$Le$v zr2ldp4&4ene^`16%{P7?xVSFyr*X4M2W`@CQ{wlb_(S6npXFGqn>Hm3Xox$+QOy~$ zzAe1cYzOvWPW^8-K2+&{vhiiC?I>@aDhNxdK4f2t?~Ln1YtucoQV^m1Hrw+{nCokV zk2KrIs89&~8@`;1UDxa}yr(KD&n<;ojy_`(uG7@L917WsBj3?h>_b<{WJo;@1`y&U zJ0|sO3O*w9y>gT6h)N8hQMgn58g*j-7JDSk$on@-d*+|f)lnuqGV4Ntzqbozy==f> zOoXdpLbMKFsQ`Zs2rL-N=vuR9e;SF1`{bQH`oK>achhH5RLe-?` zp3>w4RR~Dwnduy;HffzFu;`|1`>do%dN&XAg|C?uNCm@mn zoVDx(Eairz9Q29t7I*LqcvE9IxoffaC-ez$ke2LlmS{SB+Yv8(@%Bvs?v|c2- zEb1mbyxQ2#`HI){73tE={pJ*BGGJhP$=8%ONsp~54A{Zkq+||ZMuLdHHPlomQi-$y zrZdh4f%551Q~i=t;0g$yq7m#9P8l6?`gB63;Jc*rS$D1wW(Q0GXyC4HE0FxIp8M1$ zcBDp#0CZ#Z{ zIu$Cxfe$T~>@XAa-w>9FngkdEGEA4fC>1xdZv>FAU#gTDKj2%R{s$VrP0BxN@Fa3u z3vEo?+n9DLvt_K5A&}Q|HrdbLOquw+SY8uz;+i72&^vqSQ)^}KA$TrP@RSHnhJ29h z0&2EW=n8pb=I{0a+H7_SP=TqdYNx@-W2 z{D|LL;zfa_())j84{u@+3D{5xVP3DJMl7@KNA2egYcZ&5g9hXfYVPI~#>zAa&C4GM zN<1dObeA-e5Hp%~+XI*x7}0=JrWSi;s~SgGuq8VjZ*exn&dEwrR=^%u(hvE`E{!{S zKRZ|qxrA53?tP8{dg!RhxfOj^@pjbaZ~rtU?uEc}s4b8|ixzCF7d%_mqTplTUmF#D zMg7-}Z~c&wrHb!HeP>@-X(Qb7*2Bwb&jPZyHm*}aHstql;PsLWG^K@YB5MpBufRDnfs_HRB}lPm zmLG{pQYjfd4w>-Sqo`_(vgqU5B0ecKj5!5dX2%_=u5| zSyoy&wzXas!w(B%>Y*?qDBpkDQ`OlxKVBmtr3mQ*m8rF5IM%A&iK0foFAuVYHBz%2 zmD+>-y#z?i$u%Of!91jv0C9-D)UwXwbQ{Jly1VYYKrJ#Pb14Y4%O8T- z*=aKHB$l;NArQ}{XKSN_$#8ty|8PoJ`WX4ef5LmLxs_@|oodn3D&w`NU!2Y8m(}ts zo1l=D4c;FQ$u1)0>2f$;{L;Z@jKVqyrus!xA~r|SkHyl_V!~X)^v`e#!-&d`Rpe(B zK|l~O^HmJIQIU-?YNJu!sFLV%_9Kqd&`t3zUB>x1QZ3a_{r-;I(?ew>nU;=~*o`!7 zi4JD#60UDe&-<=kHw`sO4waPY*RDVeoglk*begryq)hS@?&=Hb!t_8b_1*@G#4B!O zvF2%U#2sB%@5oWeiN`{R! zDVcmYBa~yfBD{svc8f3is1d`L!{EOw$U#kb-MqChAcXIR4oIQ*iBX@phTY+@t=K9x zVL8@0$bw3edzO9VmOEkQo+QO$E#@pL9@jak;b?gO{hbXgp4-SG#k_?7ntqne6OJAC zH*FCs{HCC8XAK;!WP`paHA$}RqITLmP+SXn$j$TgO!olje!-_Wyi=pxX)&)<&w|E_ zAN@1$jnDIrEJ%#qX4JPyzyMs*rWnvsxgbnLawTBoo0MAUHJv#qfL~YuUSx+Rl+pxU z%F7`3B{vDaxjp{4n=JTu$w|UwCrabAi*gOk&S*{=e++6ni^k<(_Barot%4wh<}J;+ z40slA*qY695224}Q*!vC{s7vlzN;FYVP~6itcR_Z#+4-3g-c1xy%&3dxd7TXySx>} ztR(Wy#RY0Gk$|O)E=(f?7-;KFljTL2%{%GDt4VZtUWcmxk%P0^y9_lY7-1!;Iy#$O zcV!Gvr}_n0FONRT;Z>{~E*v9qD9sh0T{NavV$rM)3a?>|+^-jk$mwPtl#@*&V{oAY(|N?rZ$Y|GE{gy~hSnspiSY-WR@Gof zEdr3vBD)-mfrtujT2CVz9K?}Njz4muRjn1X)Hdl0&JYWatUrthUHP^zn~(q4@5F9) zF@PRz{%9f&h~~<;si3p>(C;WnE@;t1TR97goQ@<}I5`{{ZBl<30Tt*w9|#@=k3WJn zI;9XZ#(z7=xTBSRh=&Os^}lIv19jMo6E!qHXxFQ-x`ygD)#T^#x*XZiKe2F-&0Lhn z*=7A#EM-hkuB`uhULN-DCG@G44cRI(ucTd4n=#9w+dD9!^TsoOkeueiq`yQTabPe2 zs1Tq>_>13gKpBg8ii{&MTjuQ~K49ACRCJ)c-`j`5z5raS#t!*1DCC+c2FqaaDIU9~unLfuFF%_KqIl;#_Yy=LexFWTx{ z^o*_Oq*=xJbD>dD3-I5p_+m2f3#Z($pR8WM3njagKFVz;+J&RYe8;&&)taPsaDaXs zUolK==33~#Pf{YET`qFB3aMc<826sceRweZ-<;nKKQlgpdY%5G^kKSmpUN-4g}u>_ zlJMD0|DyrhM4uuj(5Df5+l4H@Q*^`=*>v+}+>q(O0U3HF4Xc;7#RlDSF%Ea6jW6xQ zAxJ90_NVXe3W%e+NPZWp-BQ_EN@&FJTS~Ar=%&&hMvw#Xm2|)$SuKV=+okE+8dPX` zW~kh53X3G>Vu-_VVa=~V^o1rHQeShzO|z(p6vTn@3YJDjruIv5i_`jTawa)g51U;F zu}+<)#KB=GxT^!eB>2|oOu*35(hzScLF}Ywd-cg4@v9_9fPkF8s6mJO2zNS+rXmfC zC_Z6Ce?-YDJ3s<)E@#K|9r&1f%yLmuzQPi4OQWh-gEw>CAA>ta8Tn&J)Zu7NBV?^u zUd(h{w=5Nh5D-d79N4k_w6B>PU(?3w%av5u71rpJ%6ynN6h&JG=m82zoFuV+=)FI_ z7=v(L30aJB$eFG1t>f3HaRi@o1cVJ;O37w^&wJ$@reGt{i(r$# zm0BHbHPaUWDsxgf{ZYGeYyRBn16gYYF}6iPMqv z<`M(%2g>o00C9B?n>tM%rnl4bJ&d^%~Z zO4lJ=*sC0UGJn4kv1NV*n8Aq;-73nU^`Rn?z6OvzZ|4HJ^U+bOH)1MIn65MEIRwM- zE1mF=8zirz3Izwz1{*d3~X5W+?HHK`gz;d5qYk zeQPJ-0j}frflQvjy^$qy+xG=$eVb^H31@hSU}oyFMnxA$<+J#sQ+C5cBJFq#&G5eB z^?ukvC7lO~#n7nSwp0Sdd1_okiz(mAC2AC(b4ijhwZ066C;IRv><%%R^wH7Mgi>!# zar9V3lxYV#*6s)Qq#x+fLnAzjjXT)iws`SQD%tSiRv%b4{E9Zmn||J;FZU?sqgi*e zoc#8^T$??7_!7nlxxacHA}dZ6M;nhrrr!82OdC!^v=nkhHc6P)5ikFnF{@4WA}v7* zZ3Dud&_bGicoXyx#1SaO0>D}-K{uzTe9mA3rzqb96aO;SVl$Ams)ZS)| z^I`}P(}Vp|xw+@t6FPcQ+}Ih92AtVID+||7Mys1F0%w_jX%i0}jx8RX++*0)MF^y^ zKwlY9^m^@*v+yVI*U{x7ok4}kM(W*Gy*g1SslFtO+WE`rUm8J7W_CTA$2Ho?5uU;z zRFD{m5;E#!%0eD1+Y{5Tp%_er*g@9| z93;8dMoGp-J`&RW2nEjw5vHMXv81tRF1}r|R>d7NqK+>5u|6U3_&n5V4Z4HT@%!0YDfK!4|W|~=vGrHz9g#=sDZrnZ?w@%;FnZg=M$tBEpv&7H|Wv*7Uj6r4kO14f@L3ygbawWD} zDOD7HIUMQM7abe8fY5SYcufNJesg2ozXA8cB}qgN=cEm+vh!(5E%7}UDmEt=D<{lO znuJ-xC@S?bh@Lp$4Xkn0XSOzzLb-s}yY{c0VwgY&2Qwu2Hd>F1G9gAoe#h2GD#8H& zq|iHUMLFWStc3e6u?)RtfQ-K*22}w#S|4VINFyDD?lSw`j-(b{x`o+VMSA{ha%{~XygRVW!z2si|YCHp90UC!KP3L$&zOZ%y=IS)g=pAUWY}t`vlf< zef*xJvR^xoVGyKm`DDxiCHbk*%jZPvoa zC*dKhZ`ye_6`+aVkcxMcBQL*wHoOTx!`H2cDMHB$V$D7hY`CB{e1j(+cBOpXM^KH# z_SJa;>;9EdB37G-?xRC|^42=~XJU-vpuP=xRNZlWCoS`mNJ^y*+ZgKZF--O_ey%QA zGlxsx>+$e#oZOU@uQ4!qgj7lDM3X%WQ)>Ufx^v`hFYhs)A|5XM ztQyPeVzMSkIc0U0>$;kQPd^&~I?&DfO{X|WhJ94H&VSg4UwR^b&f_8_^e6BKcyJ$| zGn9yDyETt$%w=?#bQ08ZtNc@7N_8Ml%Fd^YXa1rBw<#-t3sWaj9)3BI^+!fuVW=(l ztE1*{&uT0%RvsfffiOZTehv@CjBcJ@SmVb}Kcr7vkDK;quqW-Jnc9Q%R()obxZFy- zZ?=jbNcm4o5>|GtWtp@1zW(iddd$}fC5<6tYvcsf*vj^n#N~khCM9K1zUJ{stEcf5 zOvA{O3v~4h?Nljsso_6HrsPQ7ms9>L@!oU7Pz?Vg(?!CqoS(5gG(MQI$NK^vy%s8= z$q7a0Q!GR2za09)N)ru|LT?X^H_j@HNX=1Fp$=t;m1af_U{6#wov+3I?!mpVeb`>Ady2(uf#4ns0RCKaeTOf~XG=6w@$hYCzER6a= z2LA7Rg<;0EIp|8nH?o))I zJ(w zqzVX4{kbtO6&hCLzM9IB?40kkkDCqdvpMgVxKB|;KMYiXU9ogw*W6-D^0@cmcNuXPET@aNF?=mWn0!QIR`Srk*!TL`EtTi{D-zl5Rq?R7zlwR zCh=3AU86CwmBexfYkVz=qUSF7%C#$09yI;{06p$8Nc5Zdv_~zuMyhL7x4pgGcNwbZ zq$N8UHKxAD*mlKUO{)IHo}N0_oO{@CC<7Ju?C(swH#Mp>lH!A3do^YK_ZsiklY?m2J{>Q$-RgQfeFmz6{^|MNNpkGvbBTK>BPz>4 zG_yai2(~NheWUhlK}FB7PVE)ik~BQGYmrId0Y!mUWjlMJT9$rpOdq_4P$Z_fam8yk zoxC|_Q{MQYuPtClFcOFRL=>;NiR_kH!{{X3?IbMJ*pSakSC_TWGe3MD(-uycFk(|ecYox`hyIL zh9doKCe*)=La1uW~3$2<%QXEsP_p#gT0~S8q?u7^$WTvkOYgR=w3Ar7@5Df z;7L+`su8LCEJc=qkT858A>o4-2`(a3AKC9q#e2w*VXgwo&K z(vFOJ4nYl#;rZn`Kz7ZaU@;c)>j|6U?RNW>DL7RNF(jS#j84U`0GV8g*99-mY8TT< zy8eyP7K~US2?C@zoM3mI1c7-(=Y)CPW$0~ZKk?$ip^5O>!u1LInSTTX^(vfYQ%Ah6 z_HO*|fn2`AOxo@JgvqY@+2VzH3zVRy)o@%dp%l4OdH7-&Fml)JJ1>n<8ae`^9k)X z`_C*Ox`Z;Z8=@baSpIGGhbARFKH}g!=(rDo^ln(m0?byE+O);SN zp=H>-SY(-c3+bYi8DtJ?P>5ciF)n8B)=ar%ym>FCm{McP+1<f2bhMaX8QOBVPX)zG|FjBJuXh`v-u(IA8@a2JNvY7V)M@%Zd`x z+dN?~OS^WZr6EeDQU#^S>fE=w;|Yu5uBG9*mmym%Q+5Q%H*z@cHHGVJ{*mT>AO+5z z@XzJR5*BD@UmjRq4tk>UY6oA=I*i4_J-}a&``@?ByC{cQ0#j!hnp^I96F>G`X%T1D z-CuefYq7Zk(zi|}D41v`+DW=VfB3J;5hK-&Bg%=7C|d9(o2HnX0Nv*<(2?H?Qf0D; zh1tH`HAUkPP0*>9Ta0txAJ37|GJGRe_XdG#b3B#PO-6Kg+9gK1ze1)$n!4MVU~EDp z^^}C0PR(lTFRrtRW*uXo%A~4VVe! zYm~D}ubx3p+{rNO&0}bf;AF43vGbml6sn0a9InrH(#!H?g?=46aoP%5j!Ps??t&bE z^OUQklvzulPo|uVCa~cqf>S*kUz~s^F><*kFEkY#E5h8tPrqxd#*T|cT>t~%>Tr4#G`k53I^dhfR{8C6;f4uz_D1z}b7L1V70f?I%iY6?u?ZNcH^ zceXMWBtvMlmY6_EhdoAwW=~pT)UIqG!Me)qur?Y%)5y=7p+{MPT2Ft|_v zEhkzpWfg|X-?VW)9B$EEMbo7mjMP+laTfqX&=>ewj z!yz_c@&uh_4-i(RZ<9cUbr$tKX=pTKi`Hshg7S?()J7h^uU6jiNOa~^U0|ubIr15= zo$V*cA>jcj;?*j(l>L*ENga^=rE!bHY7fq_iHJTdAh^Gx!8DB6cd#L9RXKz>H2a*@ z8jDfpf^gdxG%IpFOMmgm$X_zRy>8fzKJ7l`oU{C=^IxS+ienOREep7j zSWEGOM0=EAXW$X)6F1LLUCIl977g;+%gC5;OyZ_x6F&=nH+hd&X>KZoo7G%c;mAf` zU&k)>J{9PdmC_Kyubi(_z20T~$pe>$%aU<@O^BddL+`&e{eO7-xnF_Of>|k>)1?$U z=wYhlz+A=iK%qbQ4a(HcM~_9UmAV*&itG_6yi&G zI?h7*nh&R&E)!wRx<7@Nx#s!rn0+epbbT%Au_^_j`j*9_TLtV0&2#485wPM0gdN4s zJOL~DGh@p&ixyORMlTU%uq!AzW)>gxX+bo&6TwJ(Tbjs+_gD`&=rg4KAC5o zU(`Wh<$nc=O{e&>DN`7G;l%A@X1fowNH8tlGVqu~$qsjY^$T3nYOYq>{NG2Y=^wcQ zxh)SM<>e9n6UHp0hR<9Ka^s!=`w;Mxj}e56tAek>;prHpmwY`~Hd0~$+c(RP|H19? zKsgCh^VkG&ta_Yo%)^-)QN6TN+e()cm6Gv03;R%Tp->7Q+%(jQov`Jw>_l~pBS z?nCewgG=Cfc|U|H-K;NhqbREjQop==ytbGro-;qF$}P&BcWt9KDx8|b9Eb$_tqn4a zx1G>=dME%d%~5r$rD#gTVA`3!0Nss`=6z8Bj7wyL&L=U@BK1wJiLUBg!;K!NOY2WR zP=gQR_V9)#6UY`~`G#;H0c-)P)RTSDo!&h&se1Zb2T^HWA&^%SJxNEbbc14InZPsv zvuFt;D_XGb$M%-+VEc<6?w|iAO=~ATLI0aH#m*G14CuGPsjfn}Gn{Im%Z?dRMxY7X zuP&QQO7Hz(g!V#4!}dM;1xvdnr|x#4gSQJF1hUgg8V?59u5}iw$V;ew{tZ47avY(< zD72bCiNEWO0Vi9*4*&zy)Pne3O*M|Gm-y&C5V@Q9)CWCFuWZo|j-}7;Yt9xLtXxzM zX@8Pi9>6n2dOOB$gd{(dj{@00BQt9sIQo`<$!A(X8N=L?Yak0SkI} zqsP)53T$xPaFA?|aBH554sO7l@T;`lo&-(wLSI~X74=o2GG}Bha!qY!TsDy5t{S@4 z{*JZHBXgfj{ze;&m8W=#0%^Q8nb9bgIXxfCa%TQ9cQ!RXCVL9ap%CS$OYVYiAOR^sa^3Y-WXrKV*?${2*Yeyeayx-4?(gX z8scQj9L|QFw##3v$gvLlbF?z+Pq3y!i}Xk}iD0S3~w#)3K|T?^w^7t12((9m+N$% z*UaHZ`nMSJ?-*S|(AY{h1i3A9YWq1sdpdZ|4eX~%fiun*x#)ewhe~xf@KY!-MG4@w z;d*L4fu*-0nnn}|9~d4_&KZYYD(Obb+@k;q&OsO zG23@jzjM2TkN%%G$T0l}$Mk-)12P6KDQ{8OswieSs>R#Ln?p(yPKPGp!TM#S6U8Eo zs&1_LRsO?imp=ZbN0A4-c8V`aHYN?;In((uqhQPb1T}j%*ghc?>HawgA&X_At=IiO z`i$;O_aum52Ixc2CVZ=w$WHT%L6ubViu`KyUEZ)tW^7c~m$0zFkZ@kA|GGz*jsx^6 znEDTEHRgf$m?_=ZlYcqwB>dsX2&?cUJsB?mn1uxRK(J37QQjQRf3Jn<8ZJ%it9GZv zRmOGyS`K-|?v)Ecn%&9l|6Xse2sf`f#BiKod+gL$9KxNPo(?^GlM-7*d!UcDn~4TsNY1 z#*@V^^|v(cT~xtF&LDp_AF+Kcz9TlwPvdBe3~`jm_AdF5%=0ve`Ue|RK?;Re zVtw8OJ?zihDPHUIk{J4K;67Ax>y|we4BbSc^bLRd7x>6Gt%#J{X2TIgy@ea3-h$FUn5>%-%x3hFd6 ziOqSd3L&0=I@zy3+8ChMvc7cbqL3R4uR9FlZU9gU;dzJmdX<2P;2Y+`cC%E~G`nOX z+}y2qaQi9plcw4&F8dE3 zHZbq#<2g5J1W~}}qinB>9#8 zV}n|oK7C537yaYxuSN|AsX6)En${V0v*>OHEy=A;&)#!w=0ojRvkVwMXXsXr z8+3u5e1*W<9vdIzpX$^UI6$b-oUXU7TI_*Xd@js~po)+hy|e+!y!ZY-xf2VK(zN>i zX2-dz(f5TQ5cB-B_PBjm7-?K5$Zd>3c532l(sy1g%lV$!0Y*AF!HHjX6mZ0|sYBMW z?DZpDojdc7abZFA9nIQDKr~^yxsvz~R6Q>3OkaEH#G>(UtqgywfoW_)Y|suXtH^k^ zX9rwu-f4BDjBk%+X}RNGb5j-W5ajfq+%S@5K4Ta} z=Mib%8!8!Vs)TxKTKTZzTn9sY5dBV8=9gxD8ZIPeQyRi2I?!-(sL0hz8-kQ!P8h@g z625lqZFsS6XFKD;c)1XCDZsT9=S4Yx{&`!m)H{f@AZul*pvPIDA`7%^l?Z=)Py-JNA41rqPZpGSoL> zV{A-*ZV_3DLS!qR%2SnwHG*#g6J$y}=A{#P;*G~aw&#x}gLNfpS2px46tEVEK z#J@lCr061um7CI0dDd&=M;W3ykBm#%yL|y$S&p&}PALeKPBuRB^BA)#CsUdi&9VK; z$4?B6(TMxD-NINrs&~!=n>DM7H(zO!n2{7hnd{*v;nW~7Gohu-SKMZV#t~Nh{k;Vx z^)1bc=`ZtxM@}zeV*Vs#$Kv!*+5PK@L@(-4F7B2e-KcF;W@tuNEYdx9qkzMBN0gVk zx@_PoJp$tZJYEQn&x=|i|6${)74!F>tA7t)^~b5{Kf1oatt zf1tzz-FNJg1$TUrq{loreG!?F@cK<`1L$1`n|@X&C*7Ol8kEq1GcqzVloxkN+6{!qi2X>IPuQ zy!wf9?r|LpBRPWuol0H$Q4{}@L2WcZaW)ZOTw|_gXn)kxLl)FF&KX<9%gdYWOqz2T zExO*9yWcgUpF5NZRo^g5N)CYB@Z$Iho6sL9nc&OZro?mOg?gUv1y>dj-g_z`@>bXl zkN)-VA*-AQ7@|YYlDU8QT|+c-y6v}5Ihzmf0rWBOZM4hFYOhC@J4W;?<-KRqYt?Fz zZ))$q31clcQXPoVuyDGb&_4F-Z3@@SGDhoVDvGjI{)Ghqs9KeePx{&uoV1cWnWlP> zn+6S?Spgnu>_g1T5}G7r@4cCOe4O2x5YmNxgMuW&Jz?@`&$_4e6)I(*#?-K^=ErrW z^77gdEF=D$pq78aKD7}{$@>shWdeQM!@^zX#JM%Fo*OZoomP?&Eeeh_j|3N9YneCNfDdf3S=iR~wIy~L#Hh!Jh-KE=Xj_q8?(WwLileYEf~aopyCI%RUszWQ z+0n%@5VmD>okQjicMn)BjQKA3+KR6Zgrd4jhT#OJAwmPJ<%12D4fkaXW%uEZ$!jA4 zUnk%Ng-)(-^Ceo1cB2Fm(OF66M7;Wodf8a}=G={+%L(33Qc}XSAq$FPGI5R@Eb1T0 zk1w{GU(xOyTStf52M4&&56~I=3yofCQ1(<&$AtG&y^ z(U2!orr(}psd)0}-BI1CQQKL-PKemDKitw8&X_Fhh7f1bnq&S=(fCa*Dey!G*}6~d zJWK|E8h+32jQpa62}{&e>_p0#Q>p?{{l{Jaf_F>-7(u4mcmLfbO=KmLWBxVhx67{{ zTp$@SRsW;73YD0}O!g)dByFt|rVL}prM+RA$u(U#uBKBd;M?&Aa(}#Z?cJ=NFa_sVF7HBWKh6DtWBIM0Z(AaatxpT+CIkd9KJzO{MH~ zXu8LT(2nWx1ROrhg1V+))Cbwee&gu6h8w2wFMX~q3GzhG+dww2&=MPHbI_4jR5GZ9 zUuysQ_FtGn+gPcO7DsTJw2wms3o4O2a{=VG-c7XxJCA(d$t`QL%}om61kS*wT$j-j zFN-tUFvS_1@ub6_-g>j*@6AT(m?a1XI`=eRKb2fqg6{@R9Q|2iuTC~CSgc|z&Zf=a zmnQF`OZ^^VJu_opacQiP)E!>6uGsD_(mZ569Bd=D5cN4H-(7p|%Cc#Xwo%t|d*|$Z z#J8f2>mvR@Gj5D)v{#{!C5;2DPDOa3^&Ge=tK16L3;&k4JbN0Zq=k$oz8T0)Tj~>! zgMPrX)(xH0<}*=zFl?+5nD;}{264xFrC}c_X-j6eoLfwN=UHnSM>aQa=@Gq_^Q~~n z=}RGwhO_pZJh-=ZC1M#d=(UnFZ+Icu7x65D6B^_=Q9oj{dnR2QFG5$U%0fUTEy!`n zyb0MWw3qhW8?@vOkeMK~DD{xt@-Q#R$*g1tc#@mm?Qk-VpnOEkl%OsJhH?H8oBf__ zdgXjhJkCtA+pS0d{E_0{G!syncu%TLW2pqs;^>e|`gb;)E^7yXu^>g(?AMfd^h6I> zIkO>AA%&bRE>h1uOy^F}g$F9k5XxU5)SC+htT+NQS?k^>0=Qc)IF``35e`i~1oC@B zw%aP(zapKij#$YH8L=wB+otyoFHK;hSXPAcvBQTbu2NGpS}Qo>g{Ff zXR62FTc`Yt6y+|BXw=2xlKw6{xlK&!?lP}EZG6u8^@a|kmAmcNzTI<)@9-@ zOn>ih-=74X#f+c6NMd4aD2Dx2V%QMFh}E~#K&7ipFOMx!xj#`3655MsF6v=vswv1< z)l>E!X+qbJ*=Vc%wVEM$mh2RjpP-snuW_`nA%hhtEzNfGV==SafE6XNCplR(Z>Snm zRq5)j?Kr;-!~CyU?dMN9(x#qV?XSUkl(viWwUTzPQ_p+sKBK4NQTqu@5Jwp%7DRL8 z_=SEmnuS$lu9TbBTWsgvuHlH8cvot-5Pw6KXVG5Novc5AkwpiBI9KY6VmdK2?Xh2j zRnPW#P3DCEbO=yP8`KOdGc%%h^1&bxDBPNPto%)I2aAtyWRKs&#sM{yX$}$MheNPU z{n;m`g^i7ZWpWEm?71^0>R)zd_IQ54#lA?)Q1L3hqhhIs2cr^ERbfS*;&+&o?l=OJ z_n(wXoP7HkUDQhUnskzPfjLz08vNz1D7lo)Jx|@gGX}>Qduo$t9bB+lbaP^p54}aM zB0s-WmL%!zUAugQdOJwo>Gs&2{?VrGpA>VtDHkOf{g`8=jV7|H@+8$VO2q(mV93me z_7^3)Wypd-Bk761zZY?9AutoQAWH6RTQ5;q1`3W$cRt2-E0L3J7g3hO6V5?xq-Jx< z9XvimWZNM(@F#>Qbajp3)qIo|=j@7-Q)=ElGot0HCb3ICGTJH9xu|qDL*+eE?385r zBjOGw6nn_SpJD5@12_(28$Qbpe|P{6gD;6ho>H;QC7F#>ndk_f4=%^Wl>7#x=2JMclt71+NMOLMj6?S56c zXh=R{5)9<~6TSPD zSD4qk;bVVi1I~4f((uU|R7OmbMa zPy$lIWNlgiN_o#DC2-Ll^f)C$+08EtGBpI37&F4;R9GsIZT&%bb4FAhD8Qx#z{Jux za5`S9!p6pF|LIIoaUvV0qQYQqSO`%TWkM|g(Sz3v;#$qL&)09cNx1d?tDranKk2=5 zz00!n`nv+TyW?0Ti0CnlBCM{JU<6AkbmAOx|j>6%g7!s4&E}3-W^lNfj~I6jOHR5Z;zZX*DgAGrBE3mYN&=*=Dmk16gZNrW^64#N0eAJJ59*k5A#qHjg5uwl~#ivSKU*wKA`<%d*HF z(8iMJQ+`<8{JaIyBu6{?NG|K{Ta1t`ogE;y-Ny&-mOGXMO6qs7%9f#<8|NNI0dT() zW361<@vVc5Oy;vr^fx?Pw;*|Gc>km1jkDC~M4?3~vKcy5G8kYv79S-ig&fx?!^~D` z&fVrZJm7Huv*k<$25h zI*&y18oA-Ru^17m1Ms?e}X)|DEPp-^0b{giVzbZzQCbT6r0D;aO6_*SP4w`F{9FwD&q8VaKa>XPN3f^tn6T{))e+&0`VafLL+52 zzOG8qlWc5^DkzxXoNf+K{qUn;o3X-0*Q;7_A<9RclK0&tn@ zCM3!25g&AtsTHiO_bNTweIM(fGf{|F4)ENtXCMqWQhq$NiYd*G)b1QCsCv44^nSIuXX26{g|uN z*v^Tq8_kA;ra5N$d!haU-cQlL>b3BBwaT6MxF0hln(H!4(8Y{b$oJTJ{;USSe7EL} zI+&KThh4gQJ57A8^sWuXNMFQCcq{oZEhQp%?*oVoek0;0s`=YHpogfH4&J#4`6-S z2|>#~{K5YDz+Z{~*(S-9B}y*+7CrE=w2##H?+4euT_34azdK$mB@j2&H|JmX41^AN zb)RmYoKw>q1dCzwNwcOAdKBfWC74O|23bb+sjFJEH`7hzvr+#{h`kPRS{{V-@xrg( zA~ClZboC~9g?rEz@Ra)EJvQ#g{B6vARNwYsRJtmI=dL=;C{JN)%ZoRQMA60#-U5ay zRnbA%M;vF#aQ}8KeA<{FXKI4>zGe?4upRqFT38bp=uLB@pU3bSC?$WktB#xI(Y#Wq z3#&Z%9*QrstQ5&Eryh90<7&cgp+3H?rs)VuCl(9I@bnY=bt$xn$;?-$)tSF?!u#Df z!)5=XN&dAY$wgz*1m$95Sfslb8((hD)QAWmIxF_=0a(9*8bqVJPho1Ne%~?qOPy{^ zG)07nc|bR%+cxuUqV)oz%O+T5r--8VB*as>qgS=lHCev`FmYWW`g1zYW7X@3U%2B# zA|F(9ESqgPG4qs1a9i_=4pRZgHn5b}bq>Vsm1rdq`6nSh7?37-Dr~TTKlVp6gm*uP zfUu@B*yI{a>4nFTc+tlq%NZ^h&9ag_>BFH%wUr8f|^zgtAxm8}2r| z(wd+kvrX=1yed7=Us*%UQ)d$8LMK7^VJP6K5jD4FJmL(IAwYFb9lg%ua-*FwzuNoxb>*LCM zzfgMLZw9v*%r?g*NKha+saG->ZLK5^2hO?5FujMHhMI|Wfgk906g2j~;=^}YLzfW+ z&pIiF3Xlj`U#wdJ?M@PE+KrJC;8bpvAW?6U73#MZF%-_WkU6sZxvH;88Nkw(h79YZ zTHN2}_~6G=2o_7Uf;EFfV|9aTo1q+A0Caf5wViGFkZ{+oMem~ z@xxizD{z-=q!TOil5-bhJme>_m;m%+JG*`kZSb0w&rq%07X&y@-M_-Wj6CYjRg>Gv z8Z3wo>E{re2MJaS?rd*z$hiC$svylN5l3CS#Dlhr@=JDo5kCKey|)gkD{J~j5ANa}+F z>fdVHd-Xos#7Mm|Oil?8RUFNkn0>_gx|lESKH19_{P+vbO{*}-H`XI-Q>lBMYOG8E zcO+~7k;Fkyeb|WT%T0@T9qg@CsJjFxe1F)XjjpkvD@^)A4 zk)x5(s@iR~=-H9EO)BHvUmS<pB#tZafe4bQ2RsG_>FU1VOlqVLeHTF% z@+5G3m4~U@CxgP8UC)EkOMOUYuTdPzz%k%Br=cg(0tR_TGgF7HVR9^1*s(h%j8s4# zh`;(qru_;bns?52ey`b$5Xq4CkzLHRgpo)!5eHF^5kp=--2_kheY8IXL?z@Iy*0t; zQQxtk(z1mOCH>ne(ymBM?6>O1n`H8AMZV!Y2{QW}36_LN)w?iqceUJDx}EjI{tktw z$tBjVno4M6j&f&5)lKiVV$2et>+;52O4Bl;U+H4QEh%$9Oa>HK1|nRuM6a-(`{&xK zOP^NZu$niPYtJwA9nFdz46a?U)E|5l^=_5gmA-Mxm86I5i>2zKC%+T3Iwu+7=1E7fH_ zg2%@^-XKzE06R;I1zgvsDcBQ-km1kYn%|sYzbA+G>cTyP%7LyBxJqP$3P)M3RF1m` zlbWTL%$FvT`Uau(h8MnO0(@C>0n2q}pV_H9TbLk8>R5rz<(9=ZJ}=*0bpbmE1WliBNhJ>rb51$llXEoZEenPH0$H3zzD8Q;#NgPn zchbCQCQcu+EsMA>L(CpjG@CxNl9W}7pw6 zQQIyys5lra5q7GD1fI%(VS{^D$pI3WaM+XX09iXf&G)L(dH`wdu^5p- zQaQ2mqHKmUmPH3+!&4V%p|3%nxN?t-F-l1{&U(}*X7o|D!on*3&hBksQ{ij+)(RgeEWJ_+X;q z?IWJ09Qh<1k*vA`U7-`4(A>Zj+$&XSvSjyz>S{E8SxsA5|vUK44OyC_Hut$-^~y9-GmN!R)f-EQ|mdVHvp6RZKJZLSr=c4cd*L> zvyxh*T#p}T&pU>Nv(#y5c)A_UYt<^wLq>ACD4{2md<$+LNpg7?D{N$FQyaMra^{5h zhh7+xn-5-gM@Yd2S}4WTJ#uT^UGj}@j#L@pGZHql%nM@;F(+*r)0b897n&Lg_-LQP z<%DmqaoXPtP!YSsga`&>-ZH&dg=ZoTjuvs7P2d;`S&-{Y5pY-hbO5QoI^rMtaF{UW z4W{|H3_m{ka&B(MJmYdqaM{yI?$_hwTmi*bL5Jp_ zLBO%O%VjCRaHM`~ZL{4lJ1bTWf%+6zqUv6Cf4@1sluL3VORji@3Xx_I&0KHINwG61 zc3Wdi3l5e@lHKL?)@hhKes`&zI)`4G;xjMnSx4Z8ngtymxo~ZVV&E7)y#3tqB@FAq zl_ctgIn-ucgf!i!5H^xj0R?-PM;B)~|7r?-W5%jj^^%(6)8*)Z+!*E);nX~l&*^j# zT%R~*qN_1wA)^DcY?h+8Uj^5z8Ob5=JdbO70-3uFb0pwNl^B@-yzogYXCE~enm#Q>>A z!m9t6>*oucJ1dY@#wzUt0PubRti0C{Vv=>n`rL(>vUS5QX{XukZ`oyq%fq8KtRs+r zQ#~InH!LnMxV}&`zK%fGt&5UjG!TB9%)U*=PMMPR4o0sOLO;{zqa-gy()J4u=CcQ;%v$XP9M*Ni6L{E6AehF3qlpUQW||&a z7H%47K3#KQ59rJKeMn5mF`t6g8j#BPn!~Hzdj{rm5;|PE1hGG}hCOYN%cyjeBK_VO zN8t#fJ=EIlGu-W4F~!9MpkhF9hD0#vvj3s5UguA64ut;=vLoTOf6TRdo;xa#cFHQP z3(~lK?1y;fw>g{HGZl~@JyWn;U+)w7*ov1c9mfXvZs|pp<7zd?t<1N2UJYVUy4wrT zA>C#LU`|shs*x;jhuU~M!w@h1 zwN+B*JrE@*Yq^rBG=i0$jn2xjpE8qxCgVfT!sC`G?UheaWSfOGs*{e>;6#f_4bNa@ zmBGm0ggn6;nroqVfwX>+##g?J!4EGuB_V1H@u__+#%xoh>h8t{2R;h=2PoNyA{g|* z?f%8K#t_J1w}NOctZ=Ujp3J*yE&cV(59d)k(W&P4xo zYy=xHeKszu5B(L&lD$~OISA4GjGU*HLh8fP)0&Z=1pjPfjs3^j{3O#jg4$eUxxfl^ zD^JpuLN#`wNZp(HBOC7|_69PbnE|ENVom zK(#`E<@jjCgeH)D?L6PgUFBB09uQ}<+`y|({DceY=;*Z!#`Q1^O~f9n1NrvicWmLIxrkU~<920_Cu zS-4GBy>s4=33b|fFxZlyqWJPOk8@igDX{L|(CU`wNWOrCJlM4Xb6jSjE}3tUw)-gE zBB5o^4ZaEKfE6}jgv(cecX~Q@WH70G9~2yZpq?F}HEDGST?TwENj;=0g9o|mxw{f0 zg_xMiVYYb-18SZ&or{=DpT#vvw!SHz2G!;zl1)O?|2jz0t-ldW(Ai6O{-?4_|E(-B zkPcMq_II^@QSW}I0)YWR5=dWXl@@+FCvIcL-U+D-FQ*w2!lC(uuvuUE-ePb)Yw<97 zJ>DzKOrxqsUX+r@2*c92@aN}O(dIIDb&^&`q$rW=yRuEBSPdF*38Fu3hnJ0a zYbFpFJJqaQe%$LF0?7E=frkEn=xxWuz{ICRD1mFf)a9o3rMcK#dTK^!?_p z(TALcj>6(Fm0pWQg9r6Jn)v17T07U`-8FKrFAzQ~fh@vbu!17QOiM#VTc_v&AoG79 zo5lMFhR>OT?@uZ*Fs1%P7PLwq-c!<}QV}*rjQ20gL^%WU1BO>Yps0VEAbrkHIr_hI zB>qV?6#m1siGHNV=N$yfLHN?UoiY_$?E>WTBRGMq05ANJ;{IJs!JiC&q`2S2JPQYk z0j9WLV&L7@p*n09(%Z1Z@;aU+Q9V1^uVnF?Hn~7Lkm14aVu*iIkA9~<^T7L&EdJ8w za2?cwzh~-)F0;PCVPI?nhTh)+`zZn#dVgE#X0%{>3r1+Z% zVEFu35%zyFdk&w!Q-5ml96tYVT0BRoe*r4H_D^QdQR+`BPzzv``d2OdeggFz8-5d! z1EfF4hToYH|D@jiPW`3Duh{TxS^u&ZKm6ohL}c;)$?Vxl{-l!p<|JN5a@|hvr)rSG z|4yu2`oQJ=-`wPPoEm~!{r~;qe<5xBZBf2JFaB9|{~mCEdUy8!AZ`4YMP>hg!7qsZ zE-C*?8$Yzbw9!!=YsII^0fL3`v&8y46oNOf$8=)?2Y`X~UvdZ9Z@B{^VpXq51~`}P zhj;h@@4C+{m&ZJidAnwBY)w3gR-KT()ruE6o0+ad>t=tu z-6^qoi);UwU3|FkAp*B<<$P>`c+UM!5JF<<1=$2PYx7Pw4)v7bIEUd7EQs(;<)SBg z;ujik_9;)}Og${?Uhb44oQY|Y$-&6@V{3rWq)XeRAJ4LH-Glp*HtC7NR{BdfE9eGn zcsnnTcv#hL%ul?j_2!>WK^b`uIt4S(BBdEXaA_$xKNr8F?a8O5LMmXWX;R;^uRqSG z>n(t3x~4wGM=}Xpq$Os(FNEy5a$bfn!OBko!)g;rV+g$-H|=f9*S~R4M(JLUUjCqC zZ*BE0$M2TXbj8p5n>@;;>dd91%+tpJ>PW2d@5S*~1uR+$mRxE@SPGOyP%r9uF3vP) zmF>Mo#7)v7kDK;QK)*BGs5)eR`YmpgGZ1W zy^_zWSGH`H=DM}C8*>(3vo7Or!Y0yt{k!=(2TIYdghjO@OtAFr$|?M+o2?fr#X;CT zU>enk_}{GN_4VjV#XC@asIptgD<|XFh_A|h5!P|56Ek18ce&qT*N)bNti>0VaTcp- zq7@cc#%E}9`ksRxC?Tb+!>u=dJ19q?M_wab5R)k{LfaMiY^_nn8i zM-A&XH;x~g9?|caWs@wkGij=SbLAJ^493)k7T#C=QXj{cI{sS#K92FI7OtOrxXj^EI#j<87u$JIwmztye zxJs{Q4qZ(`O!CN{SjJ>-s7?@F&7%RJ1L}2ss1deRA^H)Z@mH_LIaI2+2t+joBgJE% zMmdKiVbRGZF+5BigCMW<{2&x9FgY96=4Rq|aIH`_T@n3czB@PBSn1pA*_vh=nTny6 z&@{Ec^;#1S>_(iQtw}XlF$q*_tq&AyCyQk`RpUm)mqx|OduV=5ALxhgziuz1Gom^tOT(;Ppzw*#g3UT@6AdEr_uy z$AB+_cim?h^hnlj3iO*qL=QUVWa z>BmgN=)uQ%!)=Wx-!Fk1?P?*`< zB*JU?^``jZFUV{$71nRi9_Y=-jM(qL&?3Z+w|ME^W9Bp+)+AC-b_I2PLJ4&o$g&r- zG597I=?9grxLWS=%KSd*OIr-AtwAlZ0oq5RVRIW7_1<=8)IjYw)9kBw#9+DK4#z-T zEp&?v;@mm1GD8#%o9SlE4*Zk1k|HIeffGG z@DAfpFW=zRMLUa>J;XI%MQ#%#HxV?6j zyL;>;a;&=4`9)8siP-`=VAYbyu1_wow$mWsaft}MI;uxlHptU*xGQ|p!E#=*Vd8c! z!H788fFZ*$bA?wwj@$f+=(2EvF>2LQEb~*{jzOY&wnL7Uhh7BXv?wQO*qR|cJU8I7 z)yn%=2T^tDB?L|=j&fqw>b93^(o5a$*sDt?r4DTQiGZUr=>`t;Vc$Fy;w3}@?KYnQ z$E&;~{a3HWfIrh?BunN$I%V|X8}z+!9V(+Bf4GJf{jhYS226qn$9_s;J=*-|H0#hT zin9G+!ZNq;m9v5rC|oL-b!=nAhr)DMRC!OC4mX#FFXV;|C-&Pie#&rPvoC4w#i|>>fCR_?Ah6fuimnsCT^wkD8Zl-e2cd*(; z=uCA?1PUt;V3=@m!&3yACy%vk!Q%k1aTP1l#^S`-{xqp5wii#-O~mJYvht>Y4)9iqlqZRsBuXM_VqmN!s8$z9aEEEQ#X)EthCoqyOX}vs*`0i>02uW>n0mBlpy#FeTHNrt&X!*4cVsEa% z@%5`HRz1V9k%P;&o_Q^!ggQ}?cBJXUw?SZdw<5TAmY6ayIgq#1zPl9^>y_I=lmn@>9yO>qnsCajXo`Hts~K$DoQ zs(+pb4;c>+)d==(VcJ{_oWw@qylS75b0vj6v$~~^zriE^@>mF?0d2RBvjZ+$M9l(p zgGJ?CSRgNAGV9X`i!z;Eh$e-`b*9fr6-CX<&yIG4TYP6!Q1Uzpm>Ng02mtndO z2n1G5bHmo=pD{~zu^r6E3K#u6OwItR*5(hX%W;{ zOUj}(s&vlK!=O)>oWpJ97tXBa^y|K~uLWu>er62RovZrYg=hOAK z)1r6VYmda?&6wl+!Ijj5;`$8PS7yWE)}QCQNphTSSuVF9FK|_)*E%?52>g9doN`{1xS0~Tfc%i|a>M;wKNz8V0-Fro@;-X0U@q6)L z3i4g<3c8x63gYn|n`VG|YgNk)8dyPfZIMX=^JGWb4Wqv> zij-=zRX!zJ#~b<}@wEWCO(qINvXt`bOv;XVKBbQ}ePv=*?&`=*<;JGL@kE}v{DH$e zHkXAdLj3ZlU!Nv|DHdU7(JHxARJwfKQp;W|%S> zt>&B!@?tB|zp9STzfjv(EyiPZ;O}`jk9)0I!nwb&ckr5J9sUWCaD{}0SIv+u1%A<8 z;xM^s9@1bb;K}-Wn#4^HN8!`m++{(&VH_uV+kxkb-#QC2?s<`FKp8q_NhRKw3H?3L z8fx7InQ4*z(KC2Z+H*>iMY$o&qqLpz+)U8IJBRZT677tM%g0IlJ;V}CjyHU&n0vjh zENyGG6KYnmDzP#Sq2DE^B69b~`{R|gc8Zs`2KD{oFw8Rn&A4V=LtirRbYSd*j#CNY zNss7YwjfB3+RMBSP z!+%a_o(;BwGAK>*)jrp`8GEg#6kbe`8H+BuwuzEBxk^>c)k@3oF$CUqi|8-J~ zu62h&jE$0{7w572S$p-PH~&KY_;=S{o)MUk+Ts?_FF4@Gn_y|vm)CiRIh%Q3A!i4J zS*f7LXobMs#eg3M@5OpD3QRaV*n!EUEOsIYdvBCcbvE`U8ZIG;LfSpox!4guG2e+0 zYQ=W~IW|x;lI0EETzqd^Frf)xLxK<3UZ&;cfN|ML5F_)ZrVK(ifOr#ZhYI0MeIpTs z3{3{1>G6XM{SmI;!%GN|xB^(pZ`Vcq-ajvO;A zzngP?eK+?w{%t?8*m4hgS~|3xaQ5J|j#H}>?Jh%>;MG3x)9vz$rKM5>keP2^fwSld z(;P%Ogm}S;0}#y%bOo6W@Igc(oq3=STR+fk&`@`FEGcM;P+fs4t~&WZaf}iFdjPJ(1t7DZj@hoB?_d|QUu$Uu&rR6;<^?jpH`C@9nkB2C69-8OE8Xd zS9wroBFma4n0=2(|C?q84d2xtgfALJ7)O02GIbq2nTxB)?_Isp>C9_u}4Bw z?j1%zl(&=zC&yvPRSU*tNiLjI1;HT5#IW6wbDVQ2R%%mt9aB^!0H?|pK?uGYb|baS z+43yoRqX?4$tR8MRApP@RC*3N9~n`Tr9Xbeh6h-nMH2T z)+wt}T-`w2^Z}XohI7eA(0(`n>&FVhWziZqp1bO^^p!8K=ZyC}G7bR>Mvl#vueaKF z&R^U++O}oU9tDp;zvgzPu>Teg=me3-mB=h zu-h~+Qv%aEPE09VR_IV{VI#VjGqN&ybto<#1QEQBc+`)}06kmQ>Q9T%YghGYKugWY z#Aa6npK>17IL9yKv*1?9^fLHdR=h}_kmm=%COHDU!ox(5G!UNH9sK#1qp?G?#NVkU zo9@crm#3ZAvKHkU2ETt1W^W{GRoz+j5FHDzC{?jSdLU?&3lRx5PDNY#*{aGq1*caY zssTIR_=U%}?=W4x(7_`rZBcHfd0l?1{vRKf0T3v(=tl_ZEeiH*8+{5R`S!=rIy+Ue z&Lx4Z$C+{iK($Ak}jX@VCE2Myr~rUTjrdJ0ww84AM;NopjVnnXI$4FJ%r zL*9UP0=r#6@O~V-0Z+*9EF!k^>bEhul{x^(FQBOlaSxKUOtxFfXI6Tx19jR}jY1|f z=dd_&3KA&p(xbF&64XfMI5-g*2sR%-ZJh#Q;_n6!V80D|7I3kv!0#NWx$nOZCBA0v z4y!$hZk_vT$l2eXauWY-y^^=?c&ZD9Wjja9;6;`XjaYCr3Zq=QM9IFaB1V5G-*ZeziIvFTAaB4=gi3l4WfUd8Y4rqpd_`YdiW7*{kKvxn~n;QW>gcAj}=>Sh3?<{4*VMMIsnJ8eb2-g&hO+`DRkDx04OGcd?$t+%?3GCZ(l8N$V3jo_2TPC7#aC zO80kZ@tCi<`<4f*AfN@ekd57@9(8Vbv0o#SY~OXY{p{-4*-rzP*-EaXuHtY)E$EMB_0HYhdjh;4a|LiLM?jW^E%z67URhs>FRcP z@_U5d-Niim_;qWTt0hik(ALuEH!{QDnl-qumhKnD$L6v9oY{6Q z!^tR|7`@)Ck2u&<5Br56CS!h;&SsGz~vrTFwYKPe|{lr~66O{)qr*}_`C`btq z>O;>oDofH;prpE}<6G+I3k@$Bs8Z#PEV0KsKD4J!I7Wff+LW!MKql+l89rQ0Ryj?Q zejyXlcTj`$aix>(#R%^@Zpk8&g=iGhVyogAzchbm$EkYxtqXVDaI#26zUo?fE07|84U zMcbb1r7r%bE%iHeYhLr~1(h!EmFwj@52+({1|D>DVU z_kF;ZWD#+6z?3Jx^V}ivVGK4;bi%e+y?t6rhC+FV*o946?+cfM2jZ94)>+@9`@lG| zCvxP{01;GI-q4)qy(8TWP^dp4ZYFn9zo{<>TvSB36BN)Gu;Rkdam5CA!)&|a|HSMh zwTp^b${`^{qX=_poNUquS{(J6G+*@q^!wsEZdsKyKeS^W|1b4jfPVn6e{^RtK7qh; zI^i53{52-~!-9TxXhm&*vM~R34ahX`8Xz!^f5N5pqelzaLI!|5Ll^DZ@E0$WQBoA#m&BUUGZ3Z&9 zayHV-p$di3oL^F*o||1T1)h(afLSu#^hN%=UnAh?r=6m$DKL;j!CyWgqLjst9m0QM?8iviai z>7GY9|M*J+;Dax47#L}RJw5*>0@%>w^Vd{haQ@ZEm&NyIx0wHrKX3?`HuQg2=9!BAGY9`+RG2@K@UuGqaZWJM z=R>$(Y3ZL{%S#NTKc}VN`9C8Mq!#^78 z`zTO7Le^h&a4R4k2-LqseBd?!yJP=-8-BEz{cJJT3Z;vl^?>(u0 z^ijL?3Fug;6*SYKfvg^blKwEsj`M*b`q2$>GOtE(*vbd_+ksEyh1V-jqSzMBirthU z)6?74wGjtBgr-|8N1C=VAJ@>vGxQodAQG5v{a9l_ioO3MMEFKJ2&bXE*nPEcwHwR_hvE#gQN=!R0-=KIg)I%9zis< zadCzb*dzO68xi(@Y*w}caI?bxxmi&_`o2K=n^(+?K-lDagN;h73leJ1G!%z8C$OF# zlEAlp(-`@d!5|>nzmI*(vzNB1toRgI*-Tud|MH}&YJ`nNFF7H%`Rd+TDM>!nXxFb%~+j4n)fcWf++WFG+kT>S0ipb{xD&XM@dzZtUT36$gFQ0 zS;3R&mOO6Vny6>1;M?Med|&RZ$|RiEi0FbGDpFabf2Xw=yN>b#1$Nv2G-X1duJ{7L z^uj9h1kmfp=oGnZL-Qj2H4Na+{b_KCe|R_ugg|=gPs0Th@H-Og0+l_x(~yRt8{40; zNG8X9T?&(H-CPCy=HNjB8|?PC5j1yIx7q=M@O~-}Z1D&TidZWN=_qQ!hF;sg_V@HP zCOe8W4WmRhd-Ps0ujgxDUwIm7lxF>{XVa>e>v-+e@A+T2y|0%7%HgqE$*RjQ*|taL>x1l zey*AAtyO&X1Y!ZP;T@ikvk=iQe87Nz00;ztc@G5`33SAWpVs>3Ze&ix9simT1Dt>k zl065+FX*2(_A8Ap{Eq8$JY5z@U-^YAB@7)HPrI$=aZICVMxa*;^;85!^Iow}s^;ZR zt@Dv}Ch_N%)<&-=IiD4+VRhD^3bi3=g#L>s`b|C&Mq{Np)- z;sSy3`)3_=4x|HbC-H%FA4lfDrh@=OF$k7G8pz*>{fKdEMqWd#+oZ>hvcMNR*La2Q zht?|SKU8R19YC(^d>KBr@Oa{N{bE$tOa~F)N>4UJPC4avkKYSOM)(2(<}d{obSEAs zAA(g0lT0&4BSL_j291Y>)G$&WmWSCdW;Im(GP|BzY(wPf3%_>A7}C;OOneoJGhQz8 zHtq(e_?2p~bzb^z$8uzD;k34Va$fW3_mR|z8tf7Y_(qjkmNF$@*8`v1sj9`t9*$B0 zr5DsC{)lbz5W=0GXqnRXUDni-?z@_#-JtrF52*6E@Q$89anrtxpeE-%e)oONL9eG* z@9!AdZnUd&|6N<~LpKG4hH~42V!kEb1euQrrSC5!#X5k9(F*`ulb@>v%_oHM9jv(< zS?)LiBzR#8>?A|z$i>to?zsKoUsr%B0WSbTuk&xv1Ctm3pSH>>kS6jIdB9g!UBrBl z={JQ24zoE|LL!YaXPIRF!^{GlGVhrAi~J{kE$eyfo+}K)|3f+E|ECn7?7-it{6HSS zT@U*ud+Uw-3*VpoL4cv_nSIfJvws1k0~z)G$p}at__Nw;6i6HWWmIS|bSn-It+qY7 z=%49b4o;Zt-Nep`iZ&LFsU&*0uj^OXJByglLLRGLk|8J=4z7Q*z)Ij;>ek@Kcm8sZ z=%B{+#onp)s(1%slzQP{6D#(k;eoIjN`+m`ISdB5mB?3fM#mgQ{7Jk{Bx?ENQug2n z!8sSofG`Mn`y+w(r%3K~ISv*L9=70V0yHfTd~pG0Hh>^_zelLL-mjk_`*gSMPHQ%nko9)P98{_&?AAZ5BvJ z0lvKh06<)dy}lA1ASjPucGf!Hh9D&ziuL2s=uJn;I7OXrE+keUO9LA-=|dNQ1`P{n zcudzIrc4H_-!2IC){I^wY7+%16kzw9d$1##1{0ws-a)b_DH;>ve@}t#i%rtQ5G&LQ z^6E2S{8gcyl@_QlX>GkX%nOyVZ-`{v5Rp9!aWQNBpxTJif}5KwYTl4HJU2dbG%ZT& zC~i+isZ7;AwemvbU$Ng-w*Fr7!yXYy-2 z=FVkIxS}@eZ?)3A)Io=$158kfsrZ6v`*WnQ_n2uXM zJjp+sRdkJ-HB@Zztk%X!QU*C383C7|e5#5^GR(c-VO0>S;VTP| zIh(4bo@B3_yLc#a0TZ1D94F#ps!f6>Ug^}B28Nf#3+6gl1|E=R_FK zW!Upl-)LIE{?Y*w_>c*h_Oj!F3$i^O{fi8x4I~3s|7TeSVEnr*1FW*L&pXs))~kOv z&wmUSScQ@i1Cu?S=g=W+-TuWNE)2*Bc>i7h@8R-C-SV?ieE#>Zx7_}vYQg-wYWdIf zzwRb~<@^5({B<|^oaFyQ{p;2n|My_r0bC(4&-}{pkks%(XAs;)cXTqW=5G{mSGFj3 zvh6r2=igj7Gt@K64c`3X2;TBTvtQ}&KT>|Z3YVqxyOd7g?B^W!CzV1VP4L&AkJl=( zMtJ6V21UjcU5<@LS=ek?3caeYj_8@%E z-#?-^>rOHZf!tK-X=z>%9Z4xU8dJsCTb3t8XQT1sD=sSF*K%m~G#uJkA`%fD9HWqk zY~dC8SR028tUI@kMcYYo+aRPeGv#CwtD3j`k|o7P~YNpLFnty26b}dR7(mWP4m&^l9)p7BeXL-F3r>_ zbiLDOm?4W_VfI6zSsckMF}|B(S^{gDS#f24C_PC$dYIIu8XGCVST(%KQ%0>yZfZ)| zA}rU9EP&~|1iyqRcs1&P@^I7b5?1ChQxKzF5kl&j*Ui6LO2NOp;L#z{Br2U z?sN>-%5@y-47+ydTkMF>S2CsobIVZb`FmQOs?blk`rWc%NNeyG>?P@LTUl))dc2lh zTgeZVj(rd;^e`p?B$kp!Q*Td@X^G$DuoBx>c;+ai;-kD_>Hbt7Z1k&MPa zTCblPhRBNMBeC<*LCz#==jy?>$&}0?iE%^Cs5)eD5s`wT>E#@lP4LPK)CTBkua^k` zZdRgW8J$>)*2*C~f7|fpMzlrc$ayBVtTR;s>KQc&L%Ww<4}p7y1tcB{L1^-52a0kE z{la5DZc|W%OC(IVx3BwHP?OKV5n};y+f@t@6VhBMsrro@lkJ-*XL|#Pz9=tN5#AG+ zetjitUhI-)d?~LkFaE+0V<;&9Ef_MA(VCv|9S9C0#a%eN7k7V$@HXF6MKgt8rpjwg zo~KobM9H`+D1M_cn(vs{BYf5gPG}HvBg_iLygi>T3(FM}@Fyuh$V@bMI!>v8Uk(U| z5F95~IKTgzI)I_X)*5ivz0~g@@$&U?vVpHpDou9JvFx-d#TZ@*vpVlyyh=ukBBKh5 zIJU&B3*DWj`|(@jr;PUuW&x?TKEifgPOOwozFXn%(P7}4z~9To>2g~6Gy2#MqO@J-@qJ_F3jSQ^(kX>T}Qw8|V(kH{t1oE4-5ZaaJ&MSnKSvhw`(p z43`uhD{iQZ)-$fN!;C&)JQViVbtKAoj5rmL2m{=tly``x^p7U zP;L*aQvKp@YsD}D=HFWM7e4aGAh4D;^S%BY+C5#^_u*}mUI!nRs`NpI?qbij;SB#Eszx=&C|(8LCDZ{?HF$RpF*Dx}k(o}M<_liQ!><({snpO%Lo3)^Gv zp;maN;4?0;%-*kEScw=+T6yBo5t(c7S&n9W6}0k2vuHCV0VO8HJugiU#Fb~EGEa}l z0*lnw-C!}CuU`WVn;jtwxzFHee0T6^x)+h)9Lbt3!K$6jw^&paAAMgF(bMCYvD?t& zg~dCM+IG#lY{v`;Z{nx?YX9P;ln%)0hSqoRy;L?NaC>V7j&D~Az9?OCIyhMFT9_sd zY1q{n;DI4>C}hM5RtslF09zhQl$K`pY6WrVdvn$hM_fw1z%YmTB!mfbO@Pu!9!Y!;SlB;BgF%0CpgE|yxUJ5=S1wfe5M12%)svk3)YDkyaH+G z*u+`UGnnECDR;imcoZzEKCI0$W7bZ?MItl-69JjrpWf7oC4nW4oyZo_vQ&~DJ(v0J zb~u!&y8sbeFsm~3X%6^1w)5X`!uY6d~k_2)X){H#vB zQ(Tk)aDgzYh%oCe7S{aMO#q*#;fo-c$nEs^kKj zfY48X0>L$c8pt=E&e5%oRW@I3^$9P}Bc2;I&T3>jdc_r)>dP?1+r@mR`2!!>Nk zRBi649=32$4L>4EWT7PUd%(QR2bbKdM5-9hB5rA3!Zk2h;C-<9=2sW zt^;PUYj#(5Tr=Rk<)*u!dyPC9c1f-4vYmWCP5%vwT}4CjNd*}u+?%JmM&G&b-%T~` zM`gOdGEX=hpzrY-iaX~p=MFD}_I%M8b@Pfkv=&~$Rk!Hre=Lk zlzi@MgR(^1x9H4kJ&r=~#anaiLnqV8d$lE8F1wIXsvanY4!XX))DL=|+~#g#J4=1k zuA5Awc;6GEL&O~NiRad1MpIrdhcw(b6n-I67O8U#RXB@ydf|)N{zPztGN}9-0?~{P zDR=Mg<#G&(%pOydBcQhjk9hU_Eo#$OP7#kZXa%2XEhS`<^0k8UflIUYg}yj)5kge$ zhZ;4#-F+it^wsi!MaLL!86#F)@xg%?6CbEH7hG&q3giktg{UwzIN!A}C)Hze!wv_+mVi^OP*;kYHSx*Mv3zz_suI)fp*Fhmjymn@ z9x6(Ds#c&Pfr=2VwSBSx%OY5u1RC)uT0@TUT+TIn^o$Bd|;Vz z!s&3B@jF5%(Em6kN%#&oS7E4t$i*il3cFpSDIr|F<-xwF$mgEa+z?jRJ3SZ=rF%_S$S|mc-Y0D> zA--`I8T#H;ep-fyYJ8mzCYGEdvC4N`q0X(wP??xp8hXBNaHn;|H^(ym9$sA1d=sN3 zHWp1yMup)>q&t^8HkXrT}&Pn^cc-2|6o=W_&<_9Dw`C1mN>O~baRohd8o`}S= z7ux%(XzHg9R%TF@Vi7stn9jS6F({y=LsFoJLGAjBeEblRVIb^F6V{Ma=ivXP|NQHM2pFTG_eeGcw3-$e%IL+bEJ{GUpIL((FPLfU%cJq}DUia-I*i4pn#bYvI zc5&Cx@j8uo?mf0r)T7pdMuKuk%Hzu2&S1O-3AUNgz(Z7;6O%iKmKMAFo(tD5(Ug6* zr*m`k-1z%g+5uNTNRf?&fZ=JzFEXJa?J}HZ<)Os!U7=(`cl=El;PwaKI+}L4d6`i^ z)Hd62fJjf4`fT_!qE0$-=kzU!U)9g=3#{E{4O(dvv7U?uiGK?g3I?Nh)Y*wpG~yO~ zh!noK8+_@t6%y(f44()CJ<8#sY=}&6viN~rQS<8L7Dk!RNwJdKJbIc%c}*C%sQq$h zJRaP=j{HKqV(!vQhxIIoJMnu-*0Ec@^St&Ak=!emSZN*#;wfaeB4-(Hs-6WkB5{Or zNmcY$sHRVLoR;OHOC(O!wDbWQ=K{8$t9@Uq)6xjHlJOku-G~%K>^m3F+P}?Wnf5>9 z8od;7Fq}l?To32@EnocbT?_Z@$-%^ay1*Jb_)RJ2H}a9p6OP3j7u;?E8R;d3z!qU;A84 zi!k@foq(0X5BGd#yUEAZW6iT*=I6K(U}cCx1d3TnWYC97>$M-K!brhdQ@cf<>I#pU z=1z8nx*i%o2#WS#zND35Kr`!sKAk&ECF!sc=Lt}F)UKH}_&!0FQzB@TLGBPmkvgvl zzi^C?+bAO#ejo2mW?}!8nTT0W*b<$_*bU4)%X^JG3u(cxiStWmrMlq8Hd$vc!1(LN z5Hjtn0_Wu-Da@iRdDaU8#6-}-uf7y+Gt>e#q@v)EUfrnpD?*$@Td#!-CQsL0v>%Pd zP-`)~(wv}~ux%tb*JWf3p4g3deU3%BdsSeY{8QNsnvm-Cvna1mS#3Yv2;s8(h1l^p zR5%^VT}#X8G{uK?yDKCFn_NL8Pu?J#%D43zsjO@x4);&f!zqanDpF*nf_@0Jrb=^I z%E0ap3tn^0(c|t<7I=yI_%<0&#xG=+Fxwh(e{=f)f6lf6U5~9h!?1Dn$?~kl`Mm^X zB)UH#)-XVUA+5t&k7`sPvMifSl^p5tg6wmA8u^~b5KKZPOURmOS2D13K#F(oBgw92 zKq{B)f^di!G$C9@rvT39DoU{nuk*lRn*RqyK)S!#luQX+p`f-#Js*&D#-5h#;GU;d zkKOlKlpcXp==9$qilqnS;@D`)`vkBhaXb83*M75K%>?L~EI`AL|ND2r`XZ4PPp)q< zTkOB|Lo$zdSYV@RY~!Z0dJORoI7Hx^#JMpNZ14?t!TQSO{%aH2xwq&itc;~a%+MHi zQ)B+7obwbR?$Hl6S%PeREkai7KmJers0jtpV!2ixzWjd9)PqOk0Z%S6E7+K1pu#3W zIWC7Jb2SJLj)k;$^TXuKn7<}qOn4Zq5PTZ`T3UFdi-HT?San3^g`u-Wz>bYexya~> zoX&!W*%>JaimyC&(8|3xkGGnj2- zh6`wM;JKcmEpuVn7phxPn=u%;Yy0neAr^Vc07-O&N;8TIo6Sx6PKCm?k5^0?zSRZ0M@jMgRtqRC!-om`pO}>Or`05$w?-i z7V1hbf^@&RVfUVS2C&nvh(IS}Dn8c|>ZX!acD1fB000C-0=tJ)SNG*bSu^rm>9wsE zZj@;+!qm317OT2j-HL~s-vnw!yXi!6oa(L&05oBgHzZ73@B14?5RP4_D_y$+xl27J7ZQb@X1(U*(`9=gc2X@Z*L0n$! zh2Q`G|MRC~p4dy~LD}dPaZZ7n`tCh&&Ji6LRSbGgB6KkYs~a!x9jW?aipOCnTVy|$ z@!6bd*+DEj5}Aa$W!ENHV2=p!V)y?AKWqQ&3!qZ#5K4d65(Y7C3bV8s%D;J4A+}F; z=GEbd#E9f#i?On$n#+dcT}*1ATcWB(;TC;9(G7v|>c>BVr#4Baaue z*#!>HJ>!FCGW$E8{M}X-&+Peq;;kLW1-Yf&Pu`X%|Nm$dulbsKa$!GVH)@p{FGdG0 zI{`N}awh7z@Q8GV5fkFfA%4JEFz;+w^|ve{x2RH7Hb6(OqXl{;#G)u}l2_7;XG88X z1b(#A%%kEFf+j`HZBm2gD+y4my+6{$g$|cv%rsDf^cFd`XTfpmdc3p!@&pazt%uX$ zw+!e7Zh!yh0N8X^X)6G)gmLDn{BD%jxakS{J=4w0Vo2{WH`5Kwwl3SQ8KcP!Ti--*cJ0!Bfw-eULXR^sWRO4i|yQq0;&c85;t0WuD zgZQw|TPCQSbTyL7;0%1qCw&3a0&?SJX2wb(CIpBxLC+H#Z=^VRZUmncrfh!iYuDM# zzUe-&dyeNZ+BG}lq4Jx?TvdRSZ$kVz3fj+PXi0VjhTl9wr)WxyqHII0eyMzL)*Ur! zYEZ(J)-EN}-H)j=Q=U*r)MP}axk%&b8Xz0lE0qtk`JAxM#;oNw->U6(mV>w(ep=E5 zJgIjzv9<8JTSq)7CENDWsS44a@M*g`S*|&Q^_}noMST*IyuCv4zN1PAdV-*BHfxgRYllKfpzUV}9~W)Y$!?Nfe1%^-z(RTbBOZ?pwKkX_q2^fFez5 z3*fvPLXB$Hs?UJ>@3ttb;OMSIvfmr^O^m=>ypmY#fY{p!V@>eK| z7^N@JOqf5MYdF{2+A4%eqRQLW{((SMMUPP39NO|P+jxD3-$lcSq%9H3zSboOd0RSU zrRqV^VYY%FnuC0lifA4OX7Yz;UdpT0=f{=V!(6YJub9ITV^L^2kwX$WBD1Q{MmH9? z-#jGInOMEEGObbQ9JGhDuAy50h^YIxq!L?A9}^8|AFG$(@9=-2F}HPHJ;zW|>uYe; zed_lTBT#XYS00A3D_WITYSPGnW-~X%TVCVz|Uf!!<C$IPY?VhZWopUScKOqeR`gzqAoPhT0vZw&0t#rXw((kB zaAv>@MdmEZk?h~}_Ll4c_R3(;5ooeh#CLjnIp*j~c1B##hKpVCV0f%>*E zaHfpn5{JeE-c-kjN5p8Q|2XX;93(2w$3K9y`v8w1z=vO@(Kzn$LM?kV!j6lrUQ zFkj9M%TGFj2H}hS-!Xh3wSD%-57Ps|JE#|-QNI0$+5lg)M3Dc~PFKT^04~Q7dZ-+4 zSmkl#a{Pbo7}0M6Ky$Jb-@h_cvJ@CMZbqc^MsH|XL()^Y(Y_s^)X{L#aUKj`|K9-} zm781KEY*dvL z|BTU}ZCF_XUlBcWs1>l+hGzOd{^-#QBG6S3y<6svT}*&s=@%gE=pp~-307v?`EF4| zOf3dFszaemF8daLz=lt4vhY9Dh&*@6mbn2U!)SP_MrufFmt%**x#-%xt3c8^(n__D zJbh?vb)MJk7f896FOK8tAGnb!W-^Z%t_yoxv|jzz?{Cv!GhGVgMgeIOWYU|W$-T#0^+bk#rZK_m5B(*6HIz5-SB<3P|lD&HCC}V!xAMbV1Dtb zh)4k!svoir==9CyMic+FS7$|PVI?=C1TG#y%s+g1nC=^%s2=I|o=Ja(d)-wgqeXkx z!#7+C8JyEC;*F2Tz3)f1FOhx>NY%;+s9MK^062<-IIv5uI4na0>2)J6UShx1U*!xb zW(E!njByvt_z=;6eaKr|DR8^Hqno>tMfmx_ME+XbmfgkIKta;M*R~h_A|H{M-?|^2 zOi)`A#RYGDFagv>f`+**R>?PonGgE?33+`k_B8#1x(<_PT3~|TzOog|LmKBcHAV_H zV0W){Ks4KrhN`;6mu=tra~*64|Af0!q5XXy0KqGaz(5Z-+{}TSr=AdL$ixz~4jyV}cq$B$$UjWW>}9(nS(3l{6c8 zv#LhuA=7G_4_|K?w_Ufk{^%2l-l}& zIk6d(yy`Y3_>`>Nw-eTO?(qBG;U5{(2Ui);KcfZ_yMN{n_xeDkWDDeE|U;JSh++np=vCpuk@9}4I4QV0_Gq95Z8$Ns%}KUuuO-s|HHcltXprFANKc(HDz zNfJr~@?vc53BrV4A+&KL89ZrT<-yyW?{ip5CIRPO>QFiE1}34 z&AD>-xej3I8%Jw8>m6hH*w|ysG_7oLn7fp^*mkxA{=2&bYe1OE<*Q3`_JVXC`nahB zAG<2Swau>`P0`)qfr3aI+vi}Q6IBx~saWQanjKXRG$FmEUt%ei;W!A%js6*MDfI>L z%PAe^o@1HxU%%S%ESp^7QP@{Tn;t`8;_KMk$r}Ee;_yylSZf8H0{bfva?@d$4J^b2 zvETq{hCaz65cY;C-eNfWxR$@HG)N@jfB?$ac=KQc<>a2-<}KU3-lGR<1!nLr6RZj3 z%Sfc4uU`G#I9ZhgC7+G)PI0QpFX-%Ji4rW{=S5haGXVmo5*(1C1wDj8!oIYn*2UL;QPkRkCi&_ejQ$-l6Zg3mZ73t9u%kw93{V|VY_Ct^wXBO#V{uDuiiafH6ZpO!F}q-_T%Z6mM%kYkSlb=k}%J-u~|PV_)B_4-r;L= z2ZE%CTGpf8>aJ*T&~IkRn?gOaR3Y%4;oZZkTz$YV9E{6ar#Lgp)3hYbmtiMYW2Y#H z!@jlOh(r1AQffYIKx%zJ5rm|+y{$q%p z-i;f9A5c^{kG~#$@xIdpir)v!q#~lt6{2_}PtXNPBV(GI`q>UTRRP*RJ+iETihlu0 zPuY<#dD>k5H;Ow~*9>=?IttMUL8)GIKnZzdcol$$cq>uwQUbu);&ItqUw2KIlIjzB zO}&#R*0{H@$k@r{_>m4uJxRUTvCS3;hHJvK2q3U?M@5i2<0t=CqtCqp_f^n?cYLY| z`mQ0&+5hasC?=1>p4El{1=Fp9Ie(oU939c!p8eA=D_h~CJyCaq)ef%eRO-t7T{H%9 z2S>1Z^VDtXLbClTps0Kl1>uJwtqQ>4Hidk-_>gnBHydT$_0AGHh?@6@1lGUE_JI`o zdKvqdf(V7CLVJeen;$HN4{?rr`Rp(UNf<)FiO^Z5z2P`Ww%Hhhu35LPjDPYe@u)v> zxab4f5HaTVN;lfn*nB)**@c#8joiIX!u0=uvHmx|(}o;y{u2^89}<-M(If$u8pDx= zEpPK<`2VJU4JMoZ`J830ffLzlF<+9BpZgDDl;TfzSYQ9eTUqb&!^K!8E`eI+p_cI6mlN@w-JPzX@INHX2W$5EBSWSOy?#He z&F_$hYCtA=zB@ji{d4jsc?JU(KjzGYqjb;OhB&4yo^`H8C!{1 z*_1UL-oT#O>Izzzq_5`y=-1$8JrFGUNcG{ZoX;E_?@BD2&{^4bt;``H6!};%TW&C$?hnQ2=+JGhbQY@ zXFRYjB~XbvDNUjQ)b4ZONSB{Y>xaFge18Ck0_=z0j=}FA!Gu*n?9i+<)CcVRX3;rV zdk6I1$3-0^RUr@d1?zf;6K025aJ>t3PP?Y16`OJgBnlyt$YPi1z>MM(5(MW&`##3cE1PHhw?#19{3_XWOe_Lp$2D#Exg#rBDVo*Scd@>ZYuk98r|pD+LYQ<5U< zg(Ia?N*^qif`NgSZmcv`3&(zF0RMlKPxRD*K6>coRHJhgv@I@M32v_QXiq#q4r@*6 zcsF31YmGWqHKu5qvZ+fj6GnkHsfhn2*^lVtoCv`QB>^G-aXvRK7Q-Ntw%h{qwV(u4 zQ>-O=zY*6FuHCa}PSNRRcjdcAodiaI?TcmJbzOJ!mkW>9af^GuV~hrPVM5a&zSjBX zF<}>BTXUW{JiSe|&x1gYOn0H}Ww1kp0k=-#dn?+)+$(?(@lEG>@{!ZhhT-~SF>gLb zs)=gxpE1jF{nAZe&AlV-o`!13Xh^N~n&&r3r6J(dE+*%z0=boo^}D=BUQp_DMjn23 zuHe!DfZolwnB2|U;au{jsIjzTjPHdF>!V9Dy+AXh-y;T%MZPI=`ixpuO?pEE_iT|b z5fMB2NdNy|Ns3|(>q(RGh_E2UscL^|hOCtsjo%1ddK_Dlk&riBKapFZEU9%;O#n5&+o+Q~sSQB~e) zWp6;y*b$! zyDzo(y&|Le-`M?6iIh|YNCd%^XfS};|FuJiAPuq zlK^U(O%H?Bl0~4c_1iHp;o@EOwcYdl!`y(8S){N%)3#&(|KTHS0z!}a9}Tu2#Tcgl za3V<*0@BOD-bpEW$mI$(EdTxZ7VW^!Sz zFBPUf1<-6od;S}vK`~G;uIL+7qmDuxh4|4qWMuk|Cgt};y~^RgS^|yO6vV$6j4`BK zIIIPze5cdP6ozlUuIeW%Heapg<7aCt&qY!A6gCPLs{AE~aF!ALjoUsPo-CzqO|-S$ zOVinE~G5-bSLrL z^5(>j4)xt{efg@!jn*|Q-9R)gi6+g#?~Li{`lT;_Yhkb!*MG7|FM{0O0e>-XYgq`1 z=z6?RoA)`izZG8d8v0<%%cZbZTDPuTJ#2L&{kxxP3SRMl-00d5^2e!ozH5Vd?c z(ii*2KJyVHKnxv&r}5<$&TfDAb+RfEyO+nHZR9#HZxvO*lDW_9WfT3D(bLfyJ>x3C zg#>cV7HJ=|b0w$L1t>aP6Mk7-oq#~*ePnGFU$k7!Bgw{JJ6+?Wew`h)y(7NZ z6)d@k@xRJk+s6LD5fl?N_Vym6EOH1d=DyP{D^;qHx%aqPJo+F>m6g6Nflc0{0?`3w z79xrHYvNkP5w`#gfhos(ogX__4D~e+1(&gW;SZ*%T_d0Y9U1cAM-Q!D zQ9hz=)>f~PVu?@A=l)=Xb!WDY{Up=!|I=LD6TwwNeS(vD__?M!{1u&??Dh3Uu%t2V_&qDnP)OCpr9?W{m@c1B;P9MuE}nZ373PH1Ls-mF*0JcBDjA0s-~}Xc4?tX z^AQ?HZwLlA*#`^tVGqcVhzOa_NGkV10k)k^J^vG|3Xh>@s^n-l3)B7TF54V{UXK{M zzNzdRF38}xG~rq#q|TJrxHYKpVbeU|39I+>Cr)Zl-j>esoHSsAQE%s2XI$B<7%Bo;>AZL;^Ne*P}en-5Y5UKcmRC=l@QkZ}OK<(Xom$Y9a%%iJi5fk&77q zFmrvr%eK4G9?k^N`z~%e@+5bhPrC*N?gHRidC|Vcm|GgId@mqpVCxdzTy7qmztKagbv@-lbD;WskTR2%U2u8Y zR|+#FqO3ipYhAi5I3VgBTXB+x3z+a2*WYczqcnJ_^6mNR3g&8?F5qA~>}Wt?)GPnQ zU0S0gl6;GqY&ak?UHQ#1#|^<;Q=E^Xujg;14b4T9{lyDIfB)ROLYgMdbbS4JsUVP8 z+pOl!KWS@`zeEnQ$f-1qbs2m`>1o&fimoq0=pob~l3UGLx{sL70p(#Y`|NPDm|Eu-=FFa|hzKn$HI?=4W8IY6*;qTWQ(xggDlKoF32XTqO zO3goi92Ym=nKt;TF&K}dRxP-&#}~pzci2+gFFC}}IQ|LcugAMZeD(_9pGV0D4z)39 z0;%-g+-pO-6)f`2Sz||tX)T={b{RUqv8jp_Iijx9HDU{t^0a#*ZJra@@9|&H3EbO> zq(^ri;_RS{ht~_L02B{SdK6Q%B2^^A(S`jJCA47@{*3V6k1c#DMjxW6=0^zvc9}($ z^qt36O#Ni`pyiXt5y(~XNHC|qizzxjymlrXmygoYnf?T-IYObHT2&-+S5BKa;kc~} zsX|da*bUe%(+UL6PTgvo1zbw_L`c9x@x>J0?1ic9(;yvT^ftpR;D7mxBRw( zZkd;mv=r?1_AeC`K_PKoaxZBd;)y20Bc550O)FM?L}-^BZ9>F(S+)*Ox7ot|KNOFS zBsfvbF4wiechc`Gka@23b{UGa+cO$Da2L0{YnJz*a;*3_Rh4b;N#*4c$vquwv#aKh|@ItCVryhH$k71R*neQgxw;@-iNLmdQt8skMe6{_0P<8+CP9z_J^#7VqN&_%*>Q!qp zLh%Fwb#}jcJ1Q(C2I?eEVKpo}g?B?{fP^4=&Yt~+mrdTBHX1POzm3b4a?F|iHV8vj z|I)=4+lAm*MvluP3JM(a+EOFTeAIo2hl&+``6nH||3IAwIaGW~Yg*>9FUHWv@^Q-p zm>qdhaudc)c-GYIa9%BS2#dvTZyjlo=c#RO)$r>)+iE`Yo4G0pzLT$&}bZjRwP$L$d(a1M*PjEWqlT;KRbd=K~xb@L0);zC( zbbt2|6&FD1=SnVCXE%0YZq*rOLX~h;x#N7p1l(8QBPZW})T289SGxFzmuKV+Mps>v zBBba>HX!dREJ1G+W%EP#I&sYW(@i)f(3`NsiNLB!aa2;sl^-ciH+u82JDE__=ACvk z)3mOwsjFgjzx7XC?-^^aG7>vti-LEnt6Lv{Wxd7KAuK{uG=`%vPvqBKrzKdo z|NqRYV4p&i0`B^uI1v;YTLOG#LBQiYsQB<8CM^AOBcI0wFRW1+F98=d~ynKpv+P~xTH z70tnBg7$J^yIdYb!YjP{^dp%SD4SvT<^WAurM7KSU`jg5{Mn_SQx`te2Hp*bN=F}!X zC3kV+|CrYO_Uja4B#MKgg-k?+nd<%^(*b$xo03-8Q za-j{)q0`i9LCg&`+0x?Yiv5-*$HIi{Urp{rEMrfoZkS}qp}DTv>Jodjr8m=;CaK@R zm9%h=JV8!-g4mKZlX;HgE2SI>1H(Xp=sTVlTXR3_2N5pbNo8ICu?Wk%sXzrCY5u6m zc}nN2jbk8@QH8|X?=u~P{yNJ;Q9msYBUk%zvKMI3@9urlGs@Cc#C`D5u4}wY*KD8; z8viYYU>=U`wtBTk?Dnh}u&&=-d16-0d(9wu?cxmk$`NhHQ){`+jeG^(hf9r-H7+ywiBZ(e;<{7X-+SRroUXo-KL`#<|$D>vgLGaCm{ZGLb3_H^Q8M08dsN|iJX1q-R2Be7E9<}>HmF+5zdt#wf z!W~{q>;os!>pWjL9UgL$f63L@MxU(#X|#Uo`CG)ZS!|Ss4RDFKKjwZM-Rc9lQ&kvl zchqi3kE1S@SdTA=wLg?iIv8tFmA%`TsgPI;Z|I#4x{>@w!hUa5(z0;}h)s$zA)UZK ztgRVbexRX@uw~z}t`cf3;k~m>cq(GRarjpEV)-QN2@|Gn1*CU`j!05JtUHBz?dBbv zc7GP^Pnyr)=Zp^lGS_RXqz|dzr@E)yvTEy|prD&v#%uktPRw%L?t5o%0h1HG1 z+BAJMOxp{k)VZ1`1T)|^={OtEIk5X%CeG|;7h0|AsE`?82D&$1aLHbe@kKW`wDUGjujLOmRwy zW3JPfq**blodh&BgY_h>!#ZQFHU%Tn3YxWA%SBz9m0oT#wuUikPyDa^6|0uZ+`x{n z^aRA2dm+Vem>_wisF5Gho{B(Gl$} zJm{g`dKiGW_J_8YcKc#bD9bW(zvmvCy$g&;2;# zi>TY=W3kMZ$~8~ig3G$8NOOHFTXq>&D3~vN|M+?>70WHUz`LJig;oUvOXzIM$Y(3| zo^5{=tXLw^a{Zu|rl~QcbK!i>xj-xC$bcIKd3catsymmfh}L4qJDt|JQoM5;gH%N+ z&OIdiibHZbLN?NR@}_Ja25o)byjQw`M1&+i5ap6LQ|uFQB5z)%NR=FWZDWXSG~}=W zCtcNnJuU;Ok7=gq1!yNk;Nh�M{Jz2Dqk61y}h-^M!O9Ag?c$l;55$CH9RaO`VQq zqtzvcB4)bC^uLxeqb zd2H2Ncvt#CS5e~vj{pO_g)|iS!N!Qlx-YJ+T?=v2;xn9Guq~r_p~Mf-s-c&< z_UZa(_F-R?25=%*_xfjI6}+MqqwrsD}qt+XV8s9 zZXEc^yfP|_h$5JZaeCQ3D5<5f7U&|+rcGltIT+4QBo!VXD?{u%o7j0XZ>8(9Io0*W z3{gYEUsv~_cxiUra-YptuFaA9HP|XuFPcfUcRl!VruK}jVsF(V1eCugcr)+?kqlZg z2vhts7c>1|wI@wUjr|np6^4&vF7k;7;*yU+r~kt{n3!;)J76@?YD!^!xr_VaIR`}J!SZQ;ejdt@(M@{pJrQ>yg(YR_sIQsioX((*JH{Q(3~)lN0+F9XAc zDwWL1*_DBrOd_NF_2IA9EUHu4)v^v}_eQb7HOEMF`2pZ`b<Mx5s>6%- zR#-K6A0>hlnq)iS?iLgm)c?}g=PJZlEx5}h(ZfW40@*jHQlZP0aW`%ol7hA(h!-b#kVSJI)|M~#V#LT z|MNq%)H0&qi?(o+Th2HX+wf+&?sD42@p3XWMl@$|2rd;pSAr0pwWe(J*LeOpyhQ0k z>AAjGa(x1A;d`HU58+NRioeO<<@HJA$HwzpHJqiXNO71*+ZZ;+DaeJSM<&Rm#wb$z=(j1v#O1AvrMr*l0!b;JRMh6Ng~ZxQj1P&b zDIk9;k_av~7LZeycUIO#>Em-UB6>%JEZxl1X$|@8WCB%4&668nLydl7M+A$^1$y)| zX-cf85;IF50-Cn8@Se0-EX-2)@}!mBY|?;MHBFwJ+W~F-gy%$}>$P8x|4bV$PLWXh zHRK%W-j?pu;4zA;OhnA|a3zfTVR&pCh=mxSZq}{nQ}xT0F-7f2zRltv(|zfuf7)|; zIe>*=w30(}X?lXvHk5zt+la<E6N_P!AkUNAro&^?Zn?hzV7b zkH>en1jEwYVy5=ut8kQ)> zTRwYu2>~3@46nr{6nuYg=w-1lXg)LKfa=vYb4Q>&sGbgVFFzeQNHg3jG4yCyi^$Xs zdvR0p%{svbk_NsOq|Wm7QZbZJCZS0)EA0rp7$Y~xk590(jct?dWWTuEyxd zfW})^w+Qy|Jr$L0-@)r-uHJ`1EJRBgyPe?_N8R?`^1R)U%AIp7;R)3}nv9EG=??G9 zLj}k82cNh%)OE6>f86Qh(Hq})23qsv@IloFOc{xJT30{+3LDLw*x<|d6eUPb%)wS| zS2<8kzvWr1wN{!(I2&K+Hu(N;t)z$*5ifiex+l0?;Qs0~vQ-9E^Uiy&gAIb{ zNzpG=UCKwA&uhF$h%R`x`@*aNCp?Le84>9T=SeX9<8LHh^agm4lvKoetQtvh<><^T ztEwkHw`9I!Y2S%Qf{MZJfPii<#B7Z;ah(RBYM>_$2Vcp8_AUDIA-pTU3)2nt)q103}(^t7MQ&FJE-D@BP3>H)R0(8Grx> z#yr=-D%1^{K0T6}-7@C}+|F^Zu&LmbbK1!6M8>^0&Iv<$aQ_yG7 z0T5TcF(X|N?Ezs`f@J$>0f=$1vB__d>$4)!6ZUA7Cj#t{hiOv2PO3>{6VXlBll*@k z4Nct`j0WURlQzY+*HE}zz6%fdB1Mj4kqFbdj>FeVt^olf5X)e1ty3orZzTJLZ#$gn zyNHMUFw=^ki&q&njyx4;Dz1YpLLkxTk`h%F&=f9A0FtR6aZL(${lm!C-JgL1;ld-w zx@K~#O*m7A$jJ-xB;^cO9$Eoa0J>pwvdNIcnlQtO80@;OcHT->wEn{uv zTdz*OG%{9vN4IsQ3ZF|=o~;qfG^;I*KKOgqSG!rKk^bt6SyQ_^jIj(;WdwY+T5Htt zbf;QcEF%p?Osa>LyBS>|t6_R6Zd3Y$MzjW9G-WsKl0X<*6ouYRBX1@lCBlk zFAs$pRG^n6?BxWdB2#UEla zW)TOX4gEa<5`GlXPl=l&&hj%*=zCIvz<>bw1k_`olmo|bOmg!DiDpLD>iZjsAyD!J zxa;dgU-g?BX@UB9V+%btcciV=cT|WGAiJ(NYb4Ts z6h-uLD!08(WQ}9pG+Tb4c(@SxnX=b7Lr&womR>@?60} zP_UMLX?Xck5`c6mXu+bx(G(^WFXK-uS8EilFg?6PFj~A z3ZC=VF}v%6%!G3d4gf1|1=%4XRx}isl9RkvfC^A6LNx>Xlo0jL2skKB9*Ec9qwvtR zfGGjV&kX8w2nhX9SxYR!fM8x@LohD9sg z?m{yq&$~aiwy9`7&0MbOIL&+o2Nly>X34H<{=+O1%nyDS3GspOPloFm=@8Jyf<0Bf z<|d5ji3jtc^BbXKlB=f5Gbnddc0Pg(&rEI_vY_n)_T2&}u5L&o816P{)8CmveE&5( zatabO&Z~VIMAP8K8C$L9a1NXpR4ENA+IJZq%`APJQfhE=Hgyr4QPVBmKAOGcm18tz z2Hb75Nrbt|AHWXKLh5uwzPxJJo%uZwr5*Jiy$o(^-AZ*7!U+JtiiP*v=^U~g?q`V~ z;op~@lHs7L9tQ`+v)cR+cd`@R{fBUBuF$OM67ijPX#%Q_kc`&LVq_EP8g1)X@0=(&?_JzZASh2jGXBXWde^ACjQUlNAsSR4|7wmS9$&%BL#2U$ z$jPi7rY61&pg`$PWUUTbd3)L=%je5Yj}_HcSX!$}RXRfLWw+CwyQ?BiKh*&!gWUX$ zatN|N`s#^5*_%7dCjq-gw4R{r(M`Gn$9PJzHs?E%ci^4wxE-wGZgzaO|AIMET>cs7 zpTiUEcwRR9GsDKUg?9;fu|iNE%OX&docz8{b*| z(3Sd1e|uSKm|p~ji+t>04gRSGT@n_V88TZSTXE4U%-j*Vuh(c} z{x=zncvQ74po5+3o&rH|bi2C_7N>vz;`ijH{zOIvo1cI@Q1eRR(>Xp0aR(T|?{-hl zC2#{5H}lvcE;>#UC_`}qhP zVld@%f8C-Ak$B_U18_#HV`en4k3mmIu1>Q`I%mXk&HzC5sjO^j39@4&sF%0%Yb5VuFD%U@*C=%i-r)H*eqp$7qfcg2wf#$+AVV4?w%wH3YMj(3j*oMJB z8Oz{j-#6K*^acrb4q2GS0x?x$O;!b(-*J7L=6Wtra|v5i4%fY-)F6f~)u41C@Zlsw44RjoB?m+S}4gTG`PXiK0Be?d|1pq|r zhz<9SdH?r$+g=m;;*_a_SmdB`7oIOEhQ0gssui?_M7mQ09&Pc$Y$IypzqQR7*<~F^ zJ_S*rNCDh~=zHsn)l;@Z&HOS9& zlCo)gJ#B&RBc4tfBu&S_AMabIv*YGQiBtH;8v!U01Wgs7w_B-f6f1;sY(}%r?j!mG z#5}L*oG`xh7!Z@zve-*@n^QBr!aDhGXBbZt6vre<6RJ zrA$FqoiM%b*T6lkBAs{=45kQRfo7#8EH^{cPQ3nR!j?^DmYJ||Rw6Ihq)#sFCnn;>a zC~-*XC{&8=oko5xO}dl!I;)Fp|P^6prZE`^S`GK7Kd`U~6a&oQ5~EOz*&{z(^KBrGo#IRGr*a{~oS7uC1M+&z&Y zKJi&L{}1}E@TU!1_u~;GNKGTe?t*YV)EfIz5X3z{jxz)!6L41bOdrJjOwLt^DRxA; z;tV>SVJXodR+tI){i;l5HQ(xBk|maw`ErI8E|s@#WL*sw&%bbE4WIAcN$V2&ZqJ>0 z542Gqq}mf55hX|d#RGyX2X=c*1SAeMYZW5Ilgp@|8 ziY`cNP=mlKWg^?U-5y4KP?&r`09i*Bf5K+cCD&hOG4T!OAJS_qd?D%iHa3?dN^d!u zMcOJ0`9o1+$!-9=1`!!q!bfU4l61bt8S9AAL^PiVcy|za{Ymw8DaV8lJ~=`CTehZQ zn!&S}$9%NJo8TPR{y*@cj#@w}O1o99#39#SL>F>?Ni&TC{sPqY&^Di*AN9 zt%66DwR|RAmyvx(+Nen06IlQ7v8CV;t>muov}T_*Qf+sH;{>kZn~QyDI{{Y_S4B=exvP!oD>=|E+F%=`@h#Q>dsx0 zRd1de@11~=Ubk#IF2qr3IhyrswEL>el%8MoII>s16;3S*%6Q=XlZrfgj+F;A&Sls)TN^8mfAkf%}&Fi9a2nBOr0z11BqAv>n*;k)FqCO;BS*7!3eTk9A0{e z^-}k;5p7<2OqrtQQA84QJAp!9LV~+Tv+5_U0!%D>zt3__-pC84*P8h8ds)O(Icfj9 z>ojuj@>W(0PR0U&j8%__DRoZsEMg4jO2fwHQfmNEqCJoxuheN)2Jnm5I<)cRyqsqC zdVYD)G2!-VsKkR}uw})TWPNXQKtx5m!CHfe)(%gEmJT{S8|TeW&P(a82jonXz&uxY z)7?SGZ6T8y=j)N&iq!Y)BVM`>|omf za$8Gz8Wns_3eY`bAGmptq`g$oaulepQGI`wsxj^)oduNSSJp!=I}K=ttB%65kn1=F zV^Agz@4`nr5%fC$7sLQY4^+8j^I2snJn^$7D!Ino(x|JLt}&3c?-~Zj`huk{2bt$< zw~v8A|CFB}RPvV)PUabcnQ%h)xNjlSV-2j<33a2e%8u$BGu+xrZsegz^)NBF1&KSz z;E%0oY_K&NypQt7{fEaQA!yc~asHni`?Rgs7}{T>dZ(QaMl_!~y{r-(59rr0Bm6{{ z6C6^SB_mJTZxb(16fco=WJ=6^e>^Tm=c}Gv0CX6vtZXv2eG+LZmDZ4@ZWey@lV9~2 z*RfECuAG2ERvOd3_xS8AbF5U!yC)A@`f-Je%wF=Pb8b2lOjW0cQf3w}DBg4C(cB_J z0AN6$zvyeKZf{Gc?Ca_(Oj~n2VpT9TC?x5Y;E7=*74=wURFviR$?g?|L)guB0!+qarv3a^e2G0HDpZ*(V zUe1U4$m6@TFibK{=i&74ccUI}MH6)fgD_)f(WP^tk1<9BLe8u9V5TaqYkKqjDCIJ0WXV*j zHehsMP&N*3Oz6WZlV2`rR^!4)EpYDvqy~t-Y1kvobLjKbRO9P?AuQ8S=i(K+WjLVg3ewoRd^Kn-wZCp5!$M6G=i z`Q&C=bw1L+g#XnBqt_DDUTt)dtXgq2oH<_keLRqa(K-Hd9zYsZD&tpiO z-n?E3e=?&qOC=u3bt&QLs!r-QewUA?7_GL+ZGw$Ss`xO=Jd~1`0@i(VOzH{nvsZ^G zOE)AT&Bxe&(B@@yCmUg2QZoG&E14>3JW$sdm@f32+d`>-{h^p#e3S9nlGN~b=*7&S zKByT0aiG~ArTyXPE?n{9y=2(kn`>Q!t(PR8nr%CYv*k+YYnz7Dg|;yCB(e(sF7~An zjb9Ik<0bKH!?Y#i6*#6;1ILf`URNKT{8G%_4>7ZolCtzUZhXR6)7OddCl37ZV6wEqPA}>oek9Nr-K{(>oDz%m4rE@q6e} z#A*dqce}Sudt#GF`TX>c=8K{}@!^k1WDba_1Ge|O#pn45((_T?CBzv;)dWP4%S(X$ ziV*C&GnWj;_!)5XCEFU1kz%y3{0JySh4TC|n#79{eOfu=gf&c5T03m02Jcd#=S^mu zX0Wo}<}Y^|9+yq@e3H zf&sJA2({+m_$AT_^6_`{bOB)x?nT&Q>SjBe(p`eF5mwmyVV3IRj_L@~y~NiIR-PE* zI?3q6pK8|`R*c|-Jqr?G(2(1x)%6??|FzrRsO(Y#e&d0%4F$REB4?n|;275?Ut7GR zDGcLIzafZuLyh(BmJX!QXrLl)$gu}fjIrqGJ%ghJIr)h?tQ&y&6+iNU{19NSY)u{+d!|aviiX^ho+%#UA zisq%tLNvYgeu$KV-XXP=^-t{gh#AyDg-Ll(z3bN-r9gC1pIk#rb(M*$g<^yVBczt| zR!B%P;mXW?7Vy)^E*BPbru!wwdG3s_SZq-lBxQG46jrPv?#@NzUAhx+bUe5W4n|0c zE#;{TO@~u)@}E&H7RK}l^#H90mk8vRd4I_h34%qMVQ^uAIPOhm3BVLP+PRv}ac#yX zaQj*}a0rlMl$savVJZ<_Pg_C1cWOEUbb3BDl+DtFV6ImvNjX-8CreU$Ae<1D{$O3} z`r4AJ#y-dhboTf0-BG4C!Ij(m0M=u?$6_3^ckj@M&#vH)nX zo~{OWC5u}|qjjDHU6K2ud)k-)C;&8ePQYvd_&}3W33{`IJHAeD_X~-kR93JYnZMp+ z)m(6us-t&bXh(m^5LNIhh-)x1T_aHc|M2T<`1kDfQUBGAWj!SL0Dq1>H_~O6l|-wG zhK#EJeqM}?3dGG#_JCTF@^ZK!o**#2Ez^dO|EE4|u>=T}+xn#dgmJt4QIg`)(t~a{ za(7fd!rPEiO5t=0P9*^APMQQBoYqo6h%aPlwfN^##)#?OII!ry_+c*S9vx?1CjPOs zvBDj3)VkL*iYc{ieZ#X-Yf0ygUF`B4k94dga=6Er2#@`6dk#f#<@#Sy*Ov0|^*F}M z|5&az5&Rq4t$prHM4T_4F=_1SROsafiF#$(%|wUL9Q>N;=yo zdSvXwR(Y>tXq7+&;XC0B^j>h`ewd*@Nv4GPno#c1$?aiMvxr^RD5KzE_)$Cd6~aPP z-UW@rjQ@xm_LsjyGH?=p74nCc+;);qwzAK3{82}|3I;`~g-i+&2zOULSU^16q7hRk3`cIc z&?bY=_jr-L8<1##qO67S6^fI5(zsB{q~OmsJ@BX#^d#LAP10W0dNdCw6d3h1HolL3 zyM{yX|KfO%o92BZn{&G=hzk3$CYMkzb}DsBK?{RfDBTUJQnAhui1sZ z^?Ay4#qU9KW7K))#!c_7tCJTid!PoEMfvS4H;7jo-1LR>?3$(gJNeK1LEkrnO)dVo z%kIn9pTrgYzSiMY!#to>-p*Pl2KkSRenoMNef50$fn26XQqVSswf~PDCcl5N8q!eD zi$YQ9_5lC-7~&�KL@2fIP4k~jajiBKk|m)|~S zR9zGojwJXOIJJh!Prd%4Ka zR-T6n4w^3uuH3HXE;)=5eF3bck6EnEj0|VOUe@R9Fo|w2f1YqVFu1+IE;OkgeqN+k zzI@5_3QNoxUoLE^QZz@4K7QPK6WOv zdCAYd@TxS3y&F*q5C8x!${wqlpIL!3wts~-G#IX~h4Z3=)C@n{L=wS7P~+}!h{kRH7Bor!D3 z8F&^oAGvxG9!j>-^0O2ZFp=tgBZpDoQ0|yILz*q3VH?nVX6|%eOaG7@37|;hJ&S#6 zhG7us-aJcX>G*W0!6?Px*!aGKlX$EdkL`OXZs)>vH7l|@_;2i%dMB7n$Oig2eDcBA z2X?S?;?O+_*UD(EZDfK)YL6y0qAUwEB77bU56B=cau&N3X%lf zLmnyb^-ePa1-aml%ea@D{&W^OZqz^Cta8u@kXq~iC*6>p3rtAe8Lf%NMsSXlqo3Rd z7aXz@-*0w$fXcOHwm;I~F?orIG+Vqxe6amoEO=Xt4r|^Ug=P6?!NBV&W--oC^is&k zZFJ5aXkS!}W?PzKv%tIDFgJf1-KOpo2CquQhrv8X%t-`-eG|a7@W{lsc(IlfbfU^g zv{)&<$~#GV&`!-dhidrd39yfUAUWZ4tb!(9;bWN+0@ha%9egxPTGsb2=Ey*TiN7k( zzdc6Ts-}IuaVz|WgS(Ncn=s+O@^IFDE4Wit-I3efvzZ@3ZrO5tNm5Xa%adkIOywO{ z|1ltWC-#HH-lIaQ`%=~^q;EOyLrowk1Bg<_L(AD#&QcgZH)aE-!8ioOL0_ffW1`05 zPLmU%Mw^+xg^&h#-GYo@OUtd5L7$p?{Z~+x$ zoj&%w1p$W%)g``n8(rM`DI;7Z5|(-=GHQl2>Bg&>lD77w0qso%lxfmTR#uxL_C~~3 zYm6&&fB)#N7n9*_^s*RozBQwhK#8?3*B`T`kttwlt|*n(fJ<>>Sg83-K7VA2=ei;X zO=H$)VHIx4BF-3BQe65GaEPidq{GFtt%Gaq1qkc{!v)=hKVSCsn|jGj-$+1m#}Qv> z@BZ?~NiJvsdJ7D#q~Qg|&f(6GOMLHy2~1K$b$v3I^+D_^?`yV1lt@RJD5Q45gA9Jd zLIwv@8e1I6_i$(jy}USH7Y$1Uk<1>gffS`cK^5;}zyZDA=#<}UeHO6khmKIqItb&i zp^<|y>}1TA?KiLLDmtp^8>gfDKB{?mm`2&n#D&$?DOba9p64+A;u-3N>-OQyDciklucx@c++4x}IkwR)F~jTE^2FBHn?Q%#;2K(@@O=LldGpGA zF8`ZB$~4g;LZww{!cySP3vr>TlY{;s;S2Ye2-`L0S-04iA1D~z3zQya*c$SGrc9yD zSst5aR8c?^45pUASy^LkYVOTj1TGptcnB4=Te@EoG%^hHtKQ8mAP6%>NGuRGWeC_x zNb0s)vONIuasMR0g zKp)liCWen1-8DdgqE9rzVxx_(kwl|pyjFQ`teUh_!c_THX6}K%svCieuAtWi=ToMA zs0s9OYWZwFFKk%;JP-xmV^;>(bfmf-z9md>Zq?v-$NeeE>$Xa`WTxU?S$MCGP>Wnq z(vm3%eu8_2yo={#y;OYqnE~A>y1&5GBL+MUMUwz}#BhcqlIa+=t@8^$B8ri()R(=AMuMB5SoC&uZlZqfw~uG(MYE7<-rGku7pnq}kPATNS_T*!wg$NjQhf`>JI_68 z<*~By!0-7r1}>BQ&ICqj(a7^+ik!W>`#D2w*6s7*Wl zsN0%V6;Po{8ZCJp>9da$?l=Hw?mGGLKs_3W7%XC88$;#@L~M=y^l^#711u=TZWjhl z60<-<2A~(z$77|-Aeue?eVh2MiuoqYP>|w^xsBSaaVfuq6j+gH(88QOkkwEa8-*xb z;T0|d9y?e7In@KlvKi+giEI&m8QFHV?LRj$f#115?&?t(%xQ*#E$;<64XT1 ze(Ev2m$*5#r3PiXomWSuv48QnX%@QfNh^|*9qC2BT}y$$C<5+cwJypl6mW2%6QbTF)iSCEx&JPA#{B+!Un@Z|R2N+31iFxTNen~(h z;Y}$J@WMW@_GzM!Cr!e`{m@73Vzcs8of%;e*>=9!P$<_G;7bHAMwm8otXTdMs|4Ooebtq4(O&>R19&NXWTJ$CS^$}sTKi$~$ zKndGc`04OHe|2)*#;v`URJLcg@2y`2!XV7SXllGe4hMMrBB;+91f-jT53ihhNHIFq z9kS#8#_G-~q!IxP;kin!4yIw*9`@w7iHg1L#si}BC*NE;dO@MWrtQ5T=Y3anPl^q2 zy?#cPRf($oB?-annJC0LH}A&<3Tk+jpY0AS>L(%-=|1RU;z7yG$gx|C0>oGdH=4a= z?5U~VepOUJFz4#9hhsZdPZbTkYCH(2m<>*CzEKywHFu81GE69hx*pWe-Mz>E6yKAx zS~ESeKk#Lvy{DB+K6TlkgL+1N9oQKg@G>or%1i=yK9^)keBLi|I_Y!C0#t@xjIX|e z7L=e0?i{|dG$u%jMeN6TC3x_b|*6$OAyrQl}r_A!_jV09{+~W zu)W4&d4LEpx+b9=QC@gS&3txcyaDGdg;8S4j`l6WP=Rm82}7YnAmNxYeY{S_5!BEjsd(@JF-f#op4 zpsP&=X-1qO4ZJr_HYhg;@}-}d)A7%kFMpE!q9GlQ0Iqf{ex3iR%A=mCelibEm^)H# zdOq>0C&uYmX&|b_KpCUsd(~5ZY(J83?#=&^h=42{G+}!g{b%9(RBKT23i~Dz<2ql@Qjl zr`lZ9mu$&K)6DJ6?>HDxIQ4aCZ_=h(a7K0XbRIayNmB_69XCS@ITyL<@=y-&;{3B^ z&8|d%(WpQGS5HZWlg;?5@L+x~MCe^A7i-HA4{l9p48B(4R={%#fm_5zQh4E`yss5E zYN}yPfYIu3jPV?0zZmu^-r~utpAK5(NtaCPhHGQQMc7@2*sfYi`PI+=Rc63x9>%J1 z^)^JKmJM(`5wuDMkUVIkJ%20c?AAr@1kW{7%0_EfntCd$mLY+IzR%HwX+sc*&>j52 zbow)s72@PFA^jlUkEeo@a6Flu@8;2hZU*n;{dzzJyXrk}8q@3~1Z&;S{tkxaKr#{W zfi+(01kg@xWp7uSc78`-_mALf-v9l&kL4ona%YdD9|I5bk(#Xrqs;VtZERkn4Gu5^ z@6>zG5Hwk9KaF@d(Y6Iu*iyQaULGl=o5|Y`|l$E z3Dp5#3;?I$`)Ms8r*uvbzohXM{`=>WwSkaXjyVnJ=SYJkeITJThm&eUP8ySbApiYi z!a#IIV4{g-*UpZ8B23xHlk%2K!BQMfkDnqfCEluHvj^ZcM10Bg79(wJtbd~LSMFV! zt&~QEWtr>S1-Obro` z;K-UKq2RmbXj(FEtM`cI<-V5~!G3z5J_xnchTSLGCjZ3^K~^tu=~=EJ2VhmFYq}L8 zXFvpNOFp%GryNvJSZP`hPr`J~X~HCoI3i1;_5b~5(XYlsoeEV;VvyT^DG%%& z9(xJm28YUn|2;70V=vyO1%-BXv7BsFvUl!A6QZV{Z);nOB1eVLg?(?s|NkE@+BN2_ zKCtg!@nZor9~yxKQ`AUeD%go zx~nd=8EJS__PDOGJsSXz!47F}WnYh9O9vKN7jbIY)WNN}K8NWUSHDzj?);=FZ;bgX zx{QeDMBYwW<|4~SYXkaaj_+9k2sd_aa;VqzaaoQAJHBPjVgg~(T`h$OH+lHNpZMzH zG}jl*OuN_}xw&h+!kC))D?+!A4z2$ zY|)Mts}WDT=r&-k^o5Tm?}*0$Aw2h@6Lb|V{KiIcNsxF~ve zezrmEO!BIY9$%3YE`ewQLd-u0#BIS=j|D2XKG$bE+ zulGp_k=i;Au6p0i`;nMyg#^_lV7fIQYqBXN1vDcO#Jh| zbU>7U8?6sjEyTDD>Mx6J>n>6__QI=&Fv=$7bT{jh*byg2`XU9TJAIw#B+7QoG!O2! zkT_m5OBk=w!<(l=yW~nw}`XRCj&$&U;4o$ zjANc}5gwurPrqNu%~Q@$It_%ceO$H*BRd4+?pv45Gs1&`xpB5KM#$HLI%0t8>x9lz zrB3$OmA?cXDU57-Vaht=0%x!>$I<)WeKw1JYRQ>Z^PCLGx5s`gP zBCk33?iE)iTic6frNqCnU+=D~KF%PU{hDwUH}LO))6-0V+vjYqj`{m5v#*K zzBhx1_5zI+7Kz-y2n%DwJ8dm0HLei;(a8K1E;B99u&X=%gg0Ne`y^d;97ZeW1n!t|3vj%8caANd-aRL>kmjJX7tnfJ zZ#^TM@_gYo1wZo=Et(>%Tfat5X!2OG&gXTm6AoO!l!Qifg3ZrqW50`$(hZ^~ zN=Y7I*9nbu27gH?yccAbvSrQkad<-ms`{-2K`|EIkWF--!48 z|K=Le#2ulv@ubmC+$~!ZDlN)F|G~C&yEJ?4Y2YSZ<-Tofoq6o|1{JFYgn9r2tcJ-P z>`I`6w1VJ2vaTg}PjIOSgSURk7?-;uGNLEdhbS}3-zNID6lQVQm)#;0JWs+F`HJX3X;3dGu(A~oJZq8jH?OF?QDt-&@%uZ6SJQxG zV@}c~&W4EM%Qzd|cJQ9CnkGR;d`{u11|u_^ss#XlI%uCssx2f*bNs1pQ(2-jfa~C{ zq}dtmWgPFbxT`vi(Wj9#IaqtqVwS|aX9ch9GFp?6l0%7+^LRcM-Flcr+ZmAB>2c?q zl_~J~-bY?WmzLq32?h%^*(ko$otD5*6pY+= zBntr*X6=sI@-M@XbK3ng?q%eVZzfIJ&)ESm^j`t$aISn@Z*TU_?H5xlS36zBzQ@~t zqk!o*AA4JSjuP}kHYsaekngY;Em_Y3kc937CrSX-BE%+ZXnKbOxHRqO8TatWKFB9^AHd;d_v^u+ptCC8c#AuPS(N%)&deh{fLmEW5r{5w1^MFX!w2u?3rg| zQ>xNm?O{*~DZ6K3>7*nufbMpqd|Apj>Lbdn;9DLBUw?&8-S7P(#%j98Pi zFxvoloO%KFrFD&6LvjQKh=Mm)FAp1Vc3d^aJAJ>uQ(GGuw;=Nfrw_3-loB!iKh$k} zKMs#6IBg99zJ5Q|*F>2JZB5_#OwbKdU0ryzwKS}}rf(dT|FMSJ_TBTBG;TMSUuB4d zh~<`pRvzYka|Ap9T$-N2kexBJ*c^X$U^O7^1WX7NdvShQKOEt)WBHS(?DmX`453DB zHkU#;{+Msn%|9g)BVp1U{q~Ja#7h$;9+rJhGZ7>nB-(thELQB# z@YQ#4%17&baKX4+!lFLLjk?{PxVJH2!%Z+IRUxcW_2STqC!N5CY|#FYR|C)LCnR_D zK%fFgqBwyX_5j+;JMI4&LH}f!E3uL>H!%n8L>?x$FTV>Vc*wPzqzu3PWFE~{oTqfo z(jzB#f)RnSg*-DEqO7+}?9;@(*aZLmy zNOr7fy9Orv+7OZjRD1Y$Xd`9{V-^3Hb=dH<=(r;1HBo?N5&SK#=g@+UyhrB%p`{YC z94W92SgCHkd4O*ic&e#pP0sZo#B1{#)}ae{FsFKdompJ_ci96i>bZIms^{8D1fbO- zUcJfMmL5z#rCazv?v(FHFi#?kv>+oxI>O4XU2P>uOScV%v!_79{kgW|6rcrqzq9UW zY>|?dIOGvTVw;Hs-**}&u3k|HGu&^*5AXl@&)7$Y|4cRa$n2d>^BJY59Jk**Pmp*j z>G9m^n;6s7fF)8^5A*?`P^Y!ckS^pvP~1p)8h#s5j&S>2atBul=l){ECoz9Om}=8? zuvrP@dsi&hfql@ePLi9Ok(B~%;NcoS?nAxLr%LxLw3{53TTZnts&t1VFcQj!t+IkVJ@gmy7 zoAP>^HWZf0BHi!dp7l;On_?Yo;HXKKi4_@VPrG!O{RKrjq)U;FES~HIde&T_G7o^G zBj82x-0r4KPv{d)E)O~u3K{#0DaT&IXF8!A+?SW`kVxfk=Ocxr^uHVHW`^DW|&8T95^;Ya@+) z!J1I+az<>*K7GP8Gp*`&ek?dfv9&|eP1J~B@MnifYi4T>yjPD&Qg9R}Yw@KFvAmzd z*d*KMv=g%_=&!2Rc*~su6Va2nKpC_q+4`C)_p( zPoPVJPo}htjXLJaP|175qqqk~%%<>~!{6Y5g*~B!pPwoi5w^cO&EX0M$Pf_{pF75J zV;pl}#g4z>f71q4u%O;}#=m9LT@?rU3?mT=;n! z$S|H8G<%JM5W~S$4!>fobB3k`v;Y5%<~Nv$^4NbGhuNW5CzCP2%E#Ab>*ac32>l9HGNwgR#{RN#S952lVgZo+z>Rxf?q&of%&(F# zT|L7wgt{Abaz%Mp(m?_x0QhcwKBsOe%^DG&;r^#Q5>gCey~`)yCEm=bwODWp!T%~- z6(rQ|+R7EvoT)vB)vYTJZc@AxlLMoCO z_N6UbL=-c^tL8B@O3^VNu|5P5*O;@9+hvrFLPS=1F;FxQUm_tBl!)yA^nN#TLc`x` zKAs}20xWr7CtGCzcBw%ean*r;bLW?b8CV#2&g7AE)`*%IkdoS;Bt>!x0_g`q4o|&fKkP@@Z-HEt1Y9C}^8dO^@{KQKZG3+c5tsWD zS00TmFpwbXIF`jO6+j3XDmpEUD`ad_3-*4hlwh47TAQqG1_)AR^5;G5^vQyBP*9Ug zrR!$DbSeMJ2Ct(<*CJu_WmjvMEEuP~T{XvwSqRimEoU*fR(qQsc zN;7AES_Df< zSBHjzGlEpmD!i3(xBK><&HEsFxjQV9-90O9Yq7d)_+0HYs=5w!Dvz(>eRF$ckS8*U zl(LVL-kymM1pGUnjQ6mqI_)v zz+O+jRqk9PT~p_Kt!Pl+kJGsaAEJE%j4rB~T&?jZEzD`*vpCeEDo4=_P(q~SfY5S9!Zvrq_|y$T`=~z) z83U(Ng#8E0s-4Em=eKZ|(&f8LqKTptY<>_zVkgM;r|8rO#OmL*|!p|B=$=-BaUNX^yPx6kU$zRB4fy(IT9r8=3@TY8$BJE+Hc>6pEI|ro%(e+Hdd|aP$u-ga89N!O+aH~ zlbYFJ>ZTU1ZOw)d7O!G_#m&WDJDJWFex&5B1%N2@wC&K^mQV8W>3cxuw3f zRXagK=vmcRR8w)&+^VZSgg_&7fuhC|m&>V|!HwoCH06v7cQ~V;4z(y-N0-1+$Iz10 zLrefmDejyAX1UO%RJJly#|r4(iVhV*mn~^-oiCbeEoiW+R)W&*sF;h2-(BLWuI{6Z zK2FqQJ?T6|i#+R(d0Q*f+PgqV1&;t71RUSRgTCn6TpES;Z!J^bX%KthCWsV)CBZP< z+OeT;we@Ua7f>@>m9Xva_ZBTfjQ;Q_(j4T`O9r%DjOd;tIbv5>!tRcup$&y7*EzQ&hKEp>B+>XML zyi~EfmRadXK|4JaE6BX0$lfQqMldYUA306$q#t^0SEADf z-h(zXQ00A>7*?3*k)RUTUHB=rPW9v7_5DhuO^(p)$p~l~n;EgQTRE2@I77m%p`dw| zPIHgii_~#`0QBF1#0}LS^Os9A!8*wTRlEz+A6!lqd zL~nzMo5U~!7H1@P0U7)}{l7-!TbWv6Rt~3s93t7CtGqrU&Rf~pX%*&Qb}Y~=?QVvZ zMC7u$vjI#X3nrVz%=zS*bCq#1V?L{X@#eE|3DrM+j(a0BMD7x!{!%Q(#wb9)*!2^+ z=-aNM`@t?`E3zk&0Df_l3o|s5P>f^JAbLt1=kdZl2t9XQVrAhi8q!1H^|e~{NKUU` zn!#WIlJ|yuP>N|aNSCWMRPcsi3vcv)My8nM9WA(?t%h?5b8BQA@sr2baZVXHWX+oH zkET>xY17s8?$HGeIp5m$=Qv)1 zVbwZ6X{8$z#!FW?NXEO1W=-ml0{T$DvR2Yx+%9$*j)zlggG>#wUKM#*W%%lQ&F;mY zLH^;1y((R$WExwqA@QeJa%Hl=-D9(xW*5<4^^IQKI2IvqHj#@hy^XAuj!CWoSdwY` z-uS_fwTSE@;mK^9j`a9s>U3}}@X3!;t{R}W8AYM>wwGQqMGX+kf0*FK?zq|uZhz#rRb zCv@okymS$;ud@cpnOXF&xttJDhbn}^i?C&n1CK@eS}8_I(9=!9({n-1B&w83Lq&rp z(g|X~Ou-Z~Hi>f@CT8Z7Wrp0DR+9{NF#2nk$c#!?V?K^ub{nv$-U_#Nq~yrfRkD{v z2GTpqEG#8AD+Ftz$!v`5UO}qSel#dc zcroFub~3kZ20OF>m%4j_VESMG>bOjdy|caS5Mc=)K|2hr96G*3omPG7fQT=A7O1OE zrBqnta!>!i75AP`ZLuowjVAQ78s>eYPJVqF4mC`dRheLoJ6=5)OC*Ib>!Zug#luJNFm8Euh%V%M^9CaBKTz+J@a@+%S zMLB_)Ac!MN@e*3`@oE8V!Me>5twVY7(N{kA)}35?U%kFQBtCK;{KYG)<=H+c83H^n z&(~)N#jnI-WSZoC*5;9?-;gS87y)EXVi%&WKfnL;qNt>6mw1Q&hEfWUIrs_VY-XQ` z^TCFNIYcE>1T}8f=wJk^{cqSOZocfUY%|ZuL z`$MOHX-m9JjskZ_mRDdvJoEw`8S^x6SFqrZD9dq)&pZibHRXmosl!ni-<|dABARe4 z@gOD8Wuo71IW@<|MSujZu>jSifi%i&cv#tKr_O{DlXFyGEAT+ImlUQM3q>X=S2cb0 zsE`e0A((6b2f7lF+5S+%YFJL@PUOOEV>G#lrtY>v-PTH^?~Sa;UNc^^oiZdB!)rJE zM)o-8u7G|nIvn%bQaCiD+AC)&NJXh_r1nDQ&9sMeu&Mq(O((Zt7xA3=@$G|{9eG&_ z{5)jWjbbtWaOu*TSw(uEo1TUHcQ%ZivrQ``p2na?$XPsVhMgJ$QD3KPhAK-+{M|;I z|D_t!&Jvh5r~qG&N{2vn{fkGu|An<-3Po|3>mJlcCV7RO;lwN7_W6khl@kYyP|tk6 zk9A6q|A1IF#pll^s;pY-(CIWGNBs2zp+MrnC}LhoPR_g@h5?E8lL5yi4(RGkQ}(jDbR zh%MrXjkdJR!D}t}w0twex+lzMgqt4a+EFE{n!9<}oy@3ezaFa@>DpIT)YYE4-}=<1Az!VXP!lPOBK3yea(NDl+=~sNfHt8iUwt@xN+8%Iu^TEcZd> zi9TZ{gux%eA!jM>AwTPm^>t_gpHMG^qx>+emEu;U?%AFRx#?8<|NrMnjZdOyl3wNr z3p2m4PWa*|(Ieg+CJGqYXq-Y8oWO|1eRE*ID;l&wRM#dQAsVJ>=MndKBgWv(1wm|7=6%px??KijDXCuaiI3Re4M~N{IFmMKFFJVBgRZgj#-nM6T zVYV*kG0{$O_aJ2z`v;SR6efUspw6lLWj{P=SwR&!;O*tPa9CIcAFT`E_b0|otis`p z9wR~_R4z7ODZmNBz8U>H;0vniU_DV!E<4rtbS*fwFdkMAuo0R3w|z=v8f`5Z*K~Tb zpJ;EX`%D8cOA^*L`Wx@Z{DunDf?ra^9J|YAzTmjp%|P?;t0EJKy%`eVQoDvzA^mOB z{F=q;_bFo9K7>;Pi~4nM0?p$C$Y_=7HtWL-N%gp1SMqd_sN-+JtKrV@*zC#0Lc0}T7ncQPj{jPW zus1v-h(|qC%pWrNL$3qzbV_XoapEK;6PB=J%L(gWc>rC1HK}BgwA3Lip0J$c8A~U} zck*@$wUKSn|209T)o8~YL-b5ZFNN!RGI~9RcBG&kGaNoFk{`x%<4bo4@BNjk%fAw5 zkmunpw~~^vBT*D1i`N?qf4FtKSuoV7Hx21#MTv4$w}|@n*DR~2eAG)wr5VlkIUN>xks4Th}bQG}}xU$FX@$&16Upi6JB6rh&A(irCw^ zYv1hRRiS52ACFES^$kr69;8NHP>NGm@zQ_hyS}*~xHOF%;s1(hlUAa>AyRRe0N-+153)VR=8MHi87}%ItU_C6uq;|2 z!mTbbm7675b^{ZrC=8{I8|6n~MD`BSxObK_CvAJ~ufO zp_j~LvG?hG2GtFCTbEj2xZEX(AS}8~+m?dkrgMUAT{68fR>Z?ezEGi4Mrlfa-GV(SCx$B}=kBJv3oNy^}T zNEAIQ+R8(qUDE3(LpnZw^WA@{k&r8^PGE(dEYdb>*s3<3jlJXyTnNbxGc;rM38gTFpSQ7x1~xhp`wSyHYcJs=E@VN)K{ zP0|X?SQ*lCibOEi9PjEtZG@Xf}B%i24F!9(Xvzg|nLQ-e)W3xnqP3aDs>>?HimYnhaLL=hW*! z05ImETe)qxxUGx?EjX+DnSHwGQ=_Ga-+v&qYY^+P-6a#o6VtI$LW_e0T=-$rE|3ls zqrHTuAOFOxuBt|N=Fhkv3TGSU(!@JAcG`KTo8@@W$~9N|=^1syA?n1jVWoG$D5?+I1~J^@?R^j8ZVxS;vbUNSQgW3gbRSMMS}(nbUJz@(r0`r zK7?r$m6jPdoP*n@C~>!1B#1TEN(WY*m7AI#Vs@o9nVp4Tm4_`;7sLHtM#*}pg@c}NR?Lin7jf;i;?XF3AusWH8^mo-SdMC!RrEPg2{^csKs zGr8%93L~}yO%|k;4~fXNiaqz{5dTuE_rxak?PXd|dA{nP39EYLkofj7^NS7^Ch0vK zFE+$uen&~2Gvgz55VpejqyCp9I4f>W14p-;dthDDSfg(aE)&~fJOijqLiV*=rehRg zhV-)}Q~sBcpuguw8MX13Aqj%rd$%UQq84@OIr4zmJ03%geya2|{heDN=6`f*>jRlIpBDzjbASw(;^LWF?~<>1)C_AP)C;Ls$Lg0 zcXZtYmmtWtE$Xba?MmA=D{b4hZQHhO+h(P0+csYH?(Tiw9p~O35o1KGSo52@D$;yE zx+`k}8n9gKz@Zg4+%fkT9^2n=?)^nmAj4ePADQt3g62I4j5wy7%CwI4Iqg7+3Nb_5k$8G=iF^wwRu5ACq&4j#CGm&7dLftDi(v2ses#?0 zu&z!I?RFuIFcMwzN+&&6KY{pvyCB%6Sdqe0JDa+c!F_p3iS zFEcEo7XN~LJlCZG6V-nyT0gG&GgTTnuhx}_J?)U~ZYOyEA}-OB8_#ZRw`%i zbs7a|h_!?6>y@(N_MyXF1@y*-_2cSuPAXaMYKB_;_UTDE;!Q+f^V{F)ET*DatN=hN zj>eGEbs>08grf4&P(E($+qs$bAg_=Y3msvQy64+qGXY8d|e^L_*_=v1PcCGnAWPb1Up<09;$X^nz< z>FY=lZE38F(p1mnFTLp(742zt+gaGgJSM@6IBa zW4}>|&{N-i*98OE%`*abWH}%!)p6lPXaEoy9|{pB<{!HX1>$H91T|sdHI8+H`Mv`T z8jW#ZurL9CuxNJve*Y{k$l_38qnBdbRk@KUsNn;vTQ8QNZJSZB$qm{4pLXaEjJ22B zjofA0EMed+&pTYL+2tIFsMI%5SJy76T@zFMa9-U>_1;$NpXAx@+Vy;I%p5=lHbq}1 z-&dc&*uN4+3vFbcue~9fKCvbR<4q;Ucm~FrHe9im5q8b&uqig`9(NdMoR=3+j<$h^ zJ!SGn3cwcmuOI;20io8sy zsnpiyn3+B;i!>Fl_d2{KiWeWFGn;GA(0OJx&4*rocj6u^?PWdYIXvHk1POu?u=xXE zLnnT3;cq-Obx-@NRRZKfL_X2h_F-PGIj3E7gVfgERq2o(i_EUg?% z83{QvK(kWM(0F$-#hCE=^(~#G5vua$35=`X2jFs_P{*{F+})c@fWiyfRCt4QsHT@m z1Sq%t_YjkZ_rc$CD&aV1Kh?yJE!uzNROx-itqa)9N*A|8w>Lkf73Q5LDfM#BVSs$n zYc!ZKRTh^BX<7(r%H>bF^3V*>Gas*)PF6t}*))0M^`es@w*ohY(WqJ@EC;Mm;jF2x zH6}|aQ3yQ0&>9b;U!EZ8_^ zp1&ge1*b+fi~k2sP4noL17lG&7<$-RWEy#%a=B!6`2>wJg>E+w;aMm0rR(hG8d9oS zC*dhwjq1QQq^#D)CEzUMqY>MZ#;x#;$xCSTHrj+&I&|ar`JfciFAOmj1Q%+)J}&wF zbq*-$IaS28!=}12*_*cO*P*?9&h1FI8o%2}|F)cnu&Nix0^561I^Q?yA8f3qMGKH7 z8*^n%S6h24vI?CR$afOpBlAlzrie*l&v^8{gU~(tv!=|;dYBt%x1}bI%z$>9aJWw3 zo>j=%ULBWbArdEa*oV&HEi$)>VZGKeP|sN} z5u99nkalaEqXUt2Iz#|{E+Q|=O|&GFC6ys$wd0UJ;iKj^Yxo4~m>X3QrWoL+#7TWt z7DfX|$&ISBhQVR4z`*%>Il`B2e{vmk>>!z6upa}FMPSdbanEw?2~m`}f!0s_Fu?8) zg7>FXYc>amWp+1Z*W3<2yIZM7Md)UB0GoHT;t^2{_{7}EIfqOEl>O8ZN^v)GLn7;I zz%Vg$pj!9S+}J1a@gw07BW?sZ5Vnm)je5>mGzCTE(qI+ zNVYh>nLo!XrTg{3w5k&*TFu~Zj&Ku0KQzJszE)_v?7a^5NH+B$nCqD`rY07{i-H0x z(spl)9>yL!aEX4yesn&hz<|i!u<;OQFYg3&#b(!o!TBc&@;4Mp3_EQWLY8yzGiuO| zgbKlbWJWobJ(_5_f7EB<5BeTZPt@O+ZDy4&F-tRA&st~z;_SH`*Uh3jhcCl^0ty~+lI*SLmwpfyU~oM}D~ z@QT(d_aR%`OwhFdcHqs;jDj5j1}w%eaon;nz=(5-T64WL{arrwTX8Fvh|Rr9h&s3p zOeyslXgV2WunWIFmbRF9W8*}`1U!>*WX7td>XKMfav%s!3P*IDrX0WslbrYEx_v@H z(k|mkmJ&3%aJ)j#kxxuD^lhg4wNuSHuep7(%;8E~J~GcsS6n&EGJjb;3Crhx5N%CB z93{34fePg`T)!!n)%~Mr(>ApByHO%#Iyq%HhCb9HT{FByR8)&6N`TwRP^=XANv(8v z$dKi#>KDBJr-qilWNn^hxX~m_Q4Gk}q7Bd)N7iD~?p|~Ht^_`>?^36_bdy~-s1aVQ zILp%FZbf~sDpj3uiRCQBA{$qE-BzRnrY!6NIWwCM?Me9A%iSOS{>1(*XhjTfwBjbm^iBuG*Agb|=@`5B; zohN$-*r7$!WKznzW1gUo$XabTy_iLCN!IWu`~ByBGHQ@Lwkdy{nS&2ix#9yH3&uO2 z6e@^G-FHYdntW5EN!Nf#8|8jOV zF=yX=mP<-1-k0Pb6)bg{b6MQJ)Yd=!QwgySlwQ5t2^W98Nkg8}*_}d8%d^LJU^{()c}dvZjk3G~&UAFXFUKSHl}kUH*&*A6-M!`1pV z;^wNyvQ?l|5_;70A+=XS>O3Ruk|JxmdzkjR6+r(qM9>lY(UjU0c2eaBxW)ya@XG}E zS6JOty!gGOr}Z;hk6f@GK~l$utAWM%nS& zo=Qsa`8NR&hrr=`S;`N@pQAI?`uxAL>At6AD!1mli zv<3_qci+^IXI9WVb(N|#QtYg`F!c+~VP4Jdhh%zbbhWY(N`;74pP1r?ID(DdR={e` zj<*5cbn~GH4ly;es_$Q5>L?;n|96EhRy>1nI%&=>qZ#6P@`s|Q*22baq08y~Fs(hL z*YCNEDdRW~ZT~OX1=V^DUy&byVk+{Eq3=Fn`AMm^!yQ;uPCqF7;-0?^)fOiOL9{zj zg6H4q%%f7&FS4_89{vVXD{V4HC;tPcdI-BI@+TuhQV{-**DM^bdGHp_k`3e*5Me@F zX8KwY=UY1jlM79d$?@M_@@>vvR0T!*p1+L~6HS)6jNQwsBAY{z&3R7TaG*{r$FZmo z_dsz2)=X}pw4kvpVH}Ulv2ueIf!~mVI{=cf^LTnezGrJ9s>b;TOci77{})U(^NECE zCUPKV3n9lvc6aM>y zml!NHvqGds^o{s^_N zwEqE9ccBj0e>lsfz`LtG>zt=Pn$V1+228`aO!bP^Xf$KpTdOx_PP#X%yE7Y$%h0}I zsd>|e)FWdI0|$JbZB@aY2_fHF)^+)Ch7%b&%vVxd-ASp>la>a69)T1fJwQ@eb8A!H zB+-Gruuo)-Z!tUa9s0=}aY-^84{m(Bj%hYI+*r$qXG_6VSoNc^u4&0$uON;UOs!_G zc2J)jhsyehN<rrou0{hK`T?{6xZCQwQ7x5hTqL$;Gol`PzWJXvq zqVK+)!@$^EeFQA3eXdofWd_$RNxlgZD2fE$rLIFESr(P~e_4N3{}EGREz;d8t*W$E zD|DOjgLY**YH)u6^zTYQjPvG8u&?@ZXviID`#_+Bt&ja%S>~SaCJ{Ap~t2gL$}sX#8h3GLgcLz*#ZD#q>HlpBZ!Kf&g3wduX&7r49U}H#-kfR5p37oAu?833QxZONq zO3kWs!0o0@WhsLyVi-rj34Z(}DHw?9hCbl4eZJTOT$d*b5)1~*xivOutiMG+=`t*g zC+yO{%fRN0pEkPJz~3;huwt<)^q8bI1NX;-d$QZmQcR9rea53_z4#d=k3o6U_Gt?M z)Nc$n2>7s4SeCG#u}D$wKuv^M_A+yiy(s23%vU|iVTw}+x4|_kuU!_)4ymX@*4^`4 z3H=#S+JD@E@*F<}JGfCmX+%#=)F~6Np$H5AnvWPI8H~S+{&Nj4#j#yVSW1*VO<%`Gt%i4!!zA= zABY4q9b+#%S&eK>f7JMgew}KSMDJxu;XawRjc>yh7i=mRCw-Cpf}1gUPH+#c(JB%_ zkO^pJt;RYs z8bnpy@l*O)z1;BZbbQzgO2LjqrFqSh-z#%o&wo9ymyppf&b$063lJ?X-aM@rdY!*G z>DB2j0cb$Vv>^SM4!5~x%tA*Oqts4Jv-N7+0iwT$Wal*bsQi_37$6-m3ttb()T z>U+=6_f*#a_d#^u1)a0fIa>+(naS0M1UJ*ftYYDBDXIYu8B}*pl$JIm5DiS&t!#>*$`{~jX2&YL# zwg62Xn{%xe&V^7tBH#0c20}3Ru^+@i4YGqCSvjw_`m~7>Gz}j~^$;vyAs@(~kvI!l+ zBg6x|<>iA4Hu23)ZMQJ2c6OBg!jFX9fls1^ZOifzd= zSuSqM4XMjd>{OVPE9tAcJ37@gxks-AUx_h-dFUh#$e*Rw4}3g$brGvv?0vu&nZYG( zkVeUSwd~|Xy6-gz4E>012FpMZ@*ll;CN)<;48}d|Sw;(T3<7+=6@7-|9$+h&(-6lr z(Wg=K)p!d6_H|jN3vTW1-aGnPK_bR0pM`2@$GD5iZ-{vhWCD z5#`*?Gexe`;(_=+(3=1Pc9cxuR8KwxDzl$uOSCD5-*QYH5L0R~$2oUXsMcQ3{lGgt zE>mY1XqetSJKlk7mwTvXEM#+FUR8gftsLo%^Ek9Nf!8|JMB(>0f+O~~ZjPq%&o$(} z_>58G7&5^8ubqi|C9Xo-7W{IG)A?mk#Z(EVFDt%vzgcW|EQs0cs)kXpb}zkj#W=+q znM1;}xAjN6O4gTxLSBw>IdkSrP2gBmC+VyV8)Hxt(1{GXTf1VW$6cs>qk3T4-X@k{ zYz=-f-;+08p8i#SG`N$79pG_N5mTSDrfAUiyLd(wif1@=M`J|(RuO-D0_ z*mf^pSmVT?hbcXP)l*;%0E3QtbBf3*zS@PqnN;u3cy|+MB zdltcU)QEl9h7bC@MLQLD?<+`4%pZsJYLMg1ULru>*ZI%ooXEa8tvBXcOIIG?Y1gT( zpv+?_iy36&0&Md&qxv{?HY%J&0p(1XWZ-M?K|G1Co4*7^Z}z~0!k2}xjSIKDiI5=y z;~Xv%difekr3Bq}y-Ezo{A3~r`-%4)V1EVVe8sVg^%1#zYj_hw-j1kTeUa}SSCwUh zCZl$f1iCF)?O-zFZ@n!7pb^RhEeZoOF~v_2oFhbB2%&KXYGWX6%rgK`O*(e=&R+iicX;xV~Br z#7Zn)$WM(%wa_J)%2dU%6hE`64!(HdhrdAb2LAbqx0KFC)%rk6iiC5w8+tsVT^+=( zAfu+U3V!L#s(}X@0dcmIPslA0o|E>v!?TLpPTE!G3+M}EV|W4DiyH{REXHZF$Bh52 zaMaW$51LTF=*XFTk5hYGSf%u{{hgolOEkd7Pfq3>}6Ihq8S^$7?KAM_n)16h}DN zh8iRv)iu>!*w!D2Yyo%+FxyA z2K$*D2bt>^bJ%DB>>{ich)_~C^C6%5uW(ZSTw)T;t$MEjXMj@+z-k18sKaTt9<3oO z>bL@J7x_nAkcC(;6TjR=$Crt*4GTI>cZ`NAue!8Sc_sV5dQIbGb-MV5(hdqk4?DA>80dOxNb<+)JMeT=UC}m!+=!c3qda zToaaz5XiU(Suxe&vCxR9brUv_`-%PCA9fv}aB=x*RP)^$As>~HitF$$+1=R%I|9NG z!{<)MVYODD7|B;&j1m!@jSZGWMSn-FSNb8My4^-R#PdltIoY_*3&%dbCJXEY`kLnB z27>~!t50Ok-gy)bJhNlpYgH-91I2`vxq@|w#FFb7r9rLJ1N#fJ?*raUK$4q-=9Wg;;ASX zw$z)00%8>@P9}LN?#F)ZmRkm6$D0_r7t_TfgxC#zCua?qpVTQr0|X8YmekARZV^07^G6?$D&b?izLQuYm~Oh^2)=7fzwd{8byWp9$?Y6SopT9s=5T>0t1J&4 zE!Zujjvn9Uf7BA1N)Gb3bK2-wjmzYQQ5HguSi}cKT48`af1Ta@EV|Ju1W3%AhwKwa zelUCJwH{6>1U!zRlnxEDXsj?(d&r+%Q41o{laZo6U4c>$Gp4B1q+nVJ4`EgBX;|l) zna5!xLhnFto$l%}<~Yt;a2I&p^U>DCl}vB|Dx6WhQCSDf*%Yiu>KeT8O!~Ad zsge42Mg4S%>bwIXCE#&{eoLbQTOr)MR@QELL{0bLjKufJKdt(4(&gf2+Cj(zNT6aw z#2I~wz^sJZ*nyP~y|7x|Os3~5BucB7LmwX3|o?hA^Q2=7;081G%Ud!tyPW} zy_j!rGeY5hy^ zk~Y?^@}@%X=n*<$5s_f6OsDY*H zkEGpI>_~VdxzqdiXn-}jmlqM;sZ3Ka8KU_M9*~%2+s_Od%Zovn{qK|VC$D6hCEU|E#4D^ zf{*)mB!m^ZX3faR)FX=M*kyze_ba*6_QVK{Tvpesry}vfI$jq*{5HYIKYoL+AiQR8WS@$!+MnGNP_$Bt?IbM5AJ#@-AT z3*Ls}f%PNkRYwM6u3_v*Q~*YIV&5Z~g6d+bY7JpfY(y}T{*`u)Q}6HqANbxeF2qw|YGtl|$`~%*SOyMk{T5!5 z`3uh7w1gfl4)V6b$e|B9(Y9`j58 z5mRgaM@*$Z|BsluX@`680T&=C#nXfp(TW#}`pe7BwxGIhPX8gItsN@4yczniLF6N_4m** zNbj16&QC+Aqu6X;0B@Qj#d0qC-r`PuXXJe zS)4_p&m{S5tU`#3QYJ~+`sC+ZURw&w8H`Qs)9Z>)eZNri@^5`R5B-tb9bcNK+W?`@ zrNB7|c83HaAQ67!@$~7p+uS;`cFC>(0aMxk0#k##B>n+Yf&K+kIYH+e{svS1Pth0u z0aLI43#Rh_3#KOj519J?511m@v<}EHL3Bs_=Qp?olsZwH#fA83G0rz~`2kd9yixow3q-N0sN15J3NEf}3>w zr@F!x2&1%5DHibc2C-|01+w>dJvBksYlZ69^q1o$(I$0e@4)`)(EE}Orpvp_hxF%Q4#}KNI zD2dCFgzv%Wd7q$Kk7*M%vOeNcDynTucd>OG@o3#~WJjp8yzQJ_Cb`Y0#`ZuQ?kfms%FXCCa_3+0Uj>wfyT5rcyg!%TBrjwBn1Mhmd$Z@! zVCAGGNfD#W(OiQtuY8uDKhM@&Jy@GzA^4mNbqj21`U1oqH9<1Rd5*QkhIL4&*dm4` zLDiIF`hoNkNWNC-6H4vZFytMgf^3VGyTpp1$MnQxhO?Vb?4J6lm7$)7c@JR~Ra@5~ z`DllPU5M^@8>lZ(vx?BI`yLAqXsHer(Grmsetww}0ke53W?#9JV_xAKY5qkQm0~J` zST97!xTO^yti{*X`EiP(p&j-R?IpU(t#ixWzD0 zlBrr%OC^x79n$~{GpwsFX0zabd&W9XLXMgY?zRxQ$4L|%Scxx!m${;1Xf6mvT^%;} z138Q8#bt6CR?YsJwS@(Tizoon0VI>2n?QJ6W*?e*B*22k^rn&N)U}*bx=R;Uki<)p z?yb=XSvwb8RPJ+p2Ga?YJ??aXV0Zc1bSF!ej&sdCm8-hTEMwsNw17~mdFDq)#GW#) zqW2^9?c~+Qnu13a``|CE)oMoHIZmPbx7tIkC(*4RI6KTL0Sf905ESNMGb4hl7(9u4 zKbk*ACI=Lcc}E~Mn@e+wjAIk8e@qe1QpMm^k(GE=^$nTWNJ^QHUL}Z~>&#!Znx~c) z4dbksl4w?IIud0RGO}dB!4pe3wL#dR95;<30KPU*sE2{?PSY$_e8puqD}kB$JakBU z#|*1Z+YGB#OsQUD-#Z(E)vvaRwZU{lA<_}J+E&Uu-sKrSV)v&Q$E_M6y0_E(GH{h~ zk1SkVAYn}{ICh^6#pd@YXb1P%(Ua}unu=d)6ahDt-`u49bGWE}=}`vmX7pXrw6z1D z2g8QDADEY*Gpc8E&$mZ`VjGk?s1t^FY888$=v>TJ~+`nZ%JaY-52I1xC(~9D}*wrpncTyPwRq_ zA|F3$3L4bVT9N*$S;EMU6ok1fGfV}*V@KFH;qp%&?&b^!A}K{5;k50~IfstW={zB4 z1xzbMtq}-k|7_~=8YFvw-^^kSWlS@wiY55Ea=G!+@x2?zsrg*I%9R2>T2g_{V4davbu2jkFv@z3oObcGYz7N_Ubk=A75*TY7i~p>QSj2do4;P zxqGnOQ@c9P70O@}dJ~I{ph}iE531bAj!n^L60Q+HmP#QI)^~LvRM@d7sjT|}+mOxR z1rl0e28DaliL&lvrKfA35x~jvPz|Vs1b_k(YAJ~x#KpofV|Ye#JK0udnz_fT*&O`h zPh|KoZf>EF>p$@Is$mZfrx;k-DrQKFb4(TckY9|A!zln~50j_$^2K^>pCroRwzz*a z{*n=a^^i1S^Ni%j1IEhMJxpF40ALLPVq;t24jH9SGua?5gd8Bd`oSfR1B=umm*1c! zL#w8R6*ddJxw8dkCjYU#n#?cDf^4n2+Y7%tT{>N4utEB+f2TwS`|uzV0oYq!YxcPI zUu9KX2|;QLy-O4BFJ)EXf0WfqH68{}1dB45wwZjX?{G~23f=)x*=l!*z)LZLui3M-nwW62^5ry_@*aJNd3bUuDrh0Oos$@}>r4QckQ-dibQl*k5 z?DH=wT}n8ul=L+teBJ`pNegw)7rcptKQx4DJ}Q89M?s?uu&n+HkuD()RN;#ViTz9Y?wUl-#g=c z?piy$RpA@BB}`6Q8fc9%@pfyJT=;E4q~AzYpPpcBzpMT>%x+gc5S1glSc@sdg$(Wn zcPV=Q6YdDY;7tT!H{Pa3pZ5a8D_w zCTeH*W5AARLl_-CK6=W?&ICXr&ypW9iQ04y#LdReqqqJ|=0rvt{0Lx@mA7u=VHnY! zC`K}`yvV7@Fpd-KvHObQr@YVUS@5uR#vQ{DNt~A1k2MJbj_u2PO%v_9X!5K)%MkzI zdM1j&UZhIgtxgUbwfNUJaG}=T!-AhcZ;SF9be2(gAqN!VXnT>4{z8T^n8eF7#@UlaR1hi zC0=t^LZBY!)8$AmBzEo=exD3ovly$UM>~HQA@I^}`@ZBNtTm)wkZMg6=ESyF676Jh?I z&p-GJjVvQ!=AIy%&)XwMwP&6=#K9dOiT1Z2UjA_Z#5b*eMrDg~%gDS+`6lY=DJX}= zqs!+*hC(!is4YknmSVU4vhWMXN}xZLuJrZ#K7!Cr+;Vt+&q0}y0O%nWkC8Vdl{40}?YKwQIr=k?SLDtl{Cb30_ym%#<=`v1t&dgz_M9iR5!N9sz zo07!lkDNI%(Pp7=vIL;wh$Wx5_6!=7QQT-1#bO+El}d`AExgWgbhF#=uKj2i1)h-1 zt|6vYo@Pu6El`vjo0?kP)J}|I!F=y0jOAD+aqgbM5QZuu9KMuBA7B8trw6>lzQkw} zCW8GCj7@0BD&!U0T@H9;5->VA9&XT}d z?3K(N&L_ijOJg4S`(TXk1wZ}uWQE{9fw^n)I)_K|1d|L0m%|)skE9Ca7YbPvDY_^n zbuLZ5?q z+UFOHP?@IqH9X$NKiu>kkUN6;1&Xp0lR15l#_f5GA0N@YGpHH9cuj22-fS${<{QHt z^73Ik<*lRntoiPI93ybZH?jgR=8}bThV1o_pghNJghE$XcTE zX(dSDQ>ZJ-4z;7^!Zi>tGf{hLXT_!Y#b8N9Cbxw^QovPf@BULB!%?0Iy=OHj1I%njWfDByAC+RD%;}tj;TU8! zcY2eg_duRLolq<&270HZRrwi<1SfRC113c}^(^phc{S_!LA0|+)0*68F`tP|vVU!1 zV>h7{YCJ@3kzP#CxWE*}u(=wNRJOd&6xb3m5Goa9Ct$Y#Dk;y-dAHxzHA~6BIyGdj zA3m46D63>nej%8|8{O5N#yK;dN+Ii~UvJ!GgMMK|id(wSwNy+i`o23eMM<#Jj>UWF zG#z26*6JFPV!|IW^Q=*dNW5_8b>tx9*T{azGKmy2k-%foFxOdr-xiqPo2A`Fujf`l zJMrt+>@8G6iG%n}0C)R>YdnOg9Zn(??A9WGetV-0sxfGL@A?nuM+PpHr}>ATwfzdVT4M_KP2Tb|+wK zNlQsiFr)CO1mK&Bo|I%SZMMtk=k*F(Pf6ti@fwo3?JyRDshLZgG(;|tPEWy6p zoVaJ_`I3Pw#g`w&rl1-TxSMBoQk1l086(6#7kbTIEuM#ykbpMXr=HkK;+={Xm|P_t z!(hJ9U~pq1(graeKrvSnpoQ397BfpKQH6dO$!0QpGV+@bj)d>VlDS*ky>|V7`Kr57 z|JzqB`)ozLXAL_R`^Q(s4juo;SDi-tudnLEVAQcbK`%Wr#iakWf+v169r748n9+R| zhD#AR^EHR|fAv*AqyFE%YG>E~@>Mwl{`FNmo5=s)zG}O}3OF8M^nf`M2Q&$AjZa)a zT_S==ut4m8eAUY06SjT-FFVtY-5qsL39HS2d{wOC|Lv=Slq+NX*H_*A$5$!X zS>M<~Zs0|W_|jm1H1@hgl7Lw&U54$3#@hez^GX+b)qyNU(@bhu2~1wBPci#bn4;~V zWC!qr7B_v>xpGA@oKbVISZond!SE|L1lSzdG`Y_vNSi-eAb2?0fT4mL0-% zbAiTYF6wwB_0|KBN?N$FSaWV8$KGY?rjVD`i}NI?21P+ZXcomVTrnp^LF8Mq74gP#m8D7UQEw}! zu=X1I;*yF!ID|pvct&w58)}lt6ble9l0lKdfzRw7xh!+X+Mk2x>F6PK9rwhM+i$@GV!zsMY0uUC&CRw z-1o8cV`ru-@)|4=$sGx~$$E?#zff5{v$v)X`UQl~-=)Q!5$|KK;}|JfqoALy_ogTZ z(tA)}1|hV(_PRX+Xpf1ezDQS5f~W`bP~-XxXF}kh!GHLG6J!bNSV|1wdwK*9{h)On>hdPj zYKfT3OoaNy=JD)ZZ-W-cT_v1VYJ|GRmU3}-pRo@^jwo`WK>M_O?5_1qO8+iJs1Bv+fmma4OfU2zZZ zvc&1Y^st`#CmXN4EyI3p5lVzy-{p5<=Zci@n!ObwCaASqL>kv)rqc#y!!l`=#?f++ zVBbC1u8cRe{)B0u;&zqJ8j05JfQ0mskrtAY#LpnR5S5)3L%wjg=G%2^!H-tP?eVul`gjrg3z2tTOj)2%PYI`Mn{ zz3CWSr-2kshRPSMeA0fd(-KYR&I^8iLaGE^IexaAfDo51aJks0#<#T63h>Rci{sWY z1nL);s?LOQAfV*m6Ov#69|vo1&`&cCn)2Q-1(xm}CJ2yB zXWEs~j!OEIkfs-_B)ohf;fnz3lWA05S(awbfLH@0G410_GU=6oooxCtTXdl?j$gGga>^1kQ)_h9mM$u(NzZ2)tL%kabge9Vx zQXA@j9O|_cI(JOK6+*rWvGqC@6HRqZD~gLIibN62S2asbu8n<))d8XKtNc!>A6~o* zkM$y;u+|JD0kL&-h4E!P%>`x193)9p@!xofbdjjD!>IFveKlJMDAZUBZ)U*0bUf;GKEAZozn>by2 zxseU3Pzd0kz>Fyv(ojysg6%eKj3^J&`&G>%#dX!PKSNIBF*3Zo`=VZX`sF7zJaJ?; zR1t#QV}!4!TkXlbDLFBei6?K=uZ3Uj0XKEA98PR9Gd@p@B%yAfdtWS&!g6%`({+8} z;p32bv_`=m8o^J#v-_%3LAO3`gsogoTha5IC?hi+a@2l4Gt^2a=LrTOmPXF zC#}8ESr`;!f77cT!19mDeKPD4!`g8X<&5J%C6uR4?^}UqTYxtwxK-}OiDd3}K{KrR zco4moMsxbu3m}5Q^DS zhoitPXw+AL%osThL%jj`bo+TEmnIyCF;D&W{R{1F5->74C`< zUA&n{Wf2Lom~ID0&8i$_K^2~L?iM~=?F)_yi?Re#ejT-hd7;W+)iKgCwpUX0-;#it z>rJJON!++&tnnKQ!r=bA`~-jGRUqeo<<(>I?!V>L++u@&^P_k{Xpj%5dBun0xa! zH;)n=RTER2gkIz24JU&9tfH7ydgQmy@LQ0Avfpp{~v4jz#~}LZ2`J$ z+cvvw+qP}nW|!4v+qP}nw(Xk!c<)RynPg^u!%22>_Pf`!LK;21>5{4-X@!}4LF#iR zG|?+J;f==}Yd23?hepaiU)yi>YFpaNVXIx54hg5X7#L&I7N{7AX z-6POEM)2;N)k>ON{o&#xiHEMw(u~Zb5LRwlE-AjNUZD(D;mR1m3GzxOa5~u9<}y5Eu@7aThVEO}s|`-G zp_pZ^>jyeFGSvwwC4)I}H}HEOv31A!oR5h@Seq{3k}$NH;#sa-_&UIg+r$Ii7 zTk*9=35Tvpy64SfO0cRs;jUhK3`CN>tH0BK_&4j>PZ8}|y-i+0$~9h@^ctME!jbUV zVKWqFy{x~8Lge*j;q-VV*qpM>L$mR77ZRKwvmSLp$|VXWJ8l8al-WOvyCdLcFro}p zfvbW!il}V-gxtF}3M!w9O$i3VdSj1-gkbA0wUkSiq2M>R(X~qiDq>-QrzrXi!=jXDF2E%G3$HfI{uf@=`VYK{mGwXH zYWM$wS2z9(uX2~(Hsb0h7Q5(;?|C*2WAWsq?k&(cR;zJdZ0xX6sbwwlj=Zd%)H5;5 z?on|a5lw0v219?v3UFmdx1ZB@A{`5M5P1-QpI~M;FiDU?4D%3y7vxR*;SkRTt++mu z=_1Wlk?_K6jlA5ddX5htXd;kr4mE)Aeqo<6`Y3%1M4AFLKM~D!4K24AnX`?yqS^sx zXc3%5W%G7K+K&y8S+6+zFy?Q_X4jOshErHff3N&_)4B1zRiA>9E!`zOF8GG!Zw{n? zIC4kL2IY6ql1?Xa^gklQmCb!fWiGqG%`eIS{Stc$ZLJ+uA&nMh^?o<#TreX-Wp#bU zU~BYHot2EAEx|o~kOQt0oM^)lPD_QoM-B=50Bk^+ zIj;}q;J1xAVx>_Cry#6ZSS5VlV({(d)?hMN)sW~5ToL3SQ09`4xXTqsqK4FuLD--M zA^Xr|5n0hIZ7^CXAgF*VDH|2l&N;)ScVhkP(}1))+4@wGON`%E=K4w(c)DT)fv1@5 zY$xhR$%2xh8QOQ;94-S;$Z#H=s+@mJNF|GmC13m5nWFk3XZEF3)$%@1h8v-MTN=hS zt3OD2N`WH3%zQEN1rZw+NwQ3LRdT}ttgZ%|A>*H2*Fepp9*PLOw*9_yO?`!G&Pu@D zBQxN&55vM0Ji}?$EJDmcNwn5Sdwx@4E3EIx!`@zg__7E@I#tc!-hb)Z>z7VAHm>0a zTxW5xhziZoQq{zCiakY#f6O{!Bnj=;TTqj9b4rRBBOta~!^y#8B>Tdi0|1PJloV8| zE`n0p!Ud_CdnLeSlGeWtn7Y>teN{7Yl!*t#&A5YF0k_ANV-E||lu&5B%3{`*_$lBC z58~yzjV)05vrGNf8oE1!KYYgDE26P#mGeaHU%|3kV7(#J-1qmR7vg}}1?Oo&`>`g= zsjlun z_0lpj7z*&M#si+q0zs=vQl+K1Ww8P6(Z1`va1MxF&dxJF+!wb94!9sa7j4h?6Z`X6 zOWb&3WZ$ndKnY5M^9gd-%p^BV;U-(%|M)L`^-L64?R}?KcFV_WF+(8==zSNmWi`a$ z1V)Qg^s<4QGLnl77(b39@jv=%DlBjvGRdor#s=LbrxNVXE9z@$_G)LSKR3Pz&D*?G zA=tEvhK|m^%!<9U=ENBsQbp%-Df8^XV*7 zMD)|GTFBR+T%L;Yd1!9Ff91G+4o;he{3%@j9F0#uJ?^QCK9KwSNE2dNwt<{H{mTbY#E*fl|$HQ282(goK`0q@h?|p~aTm$>!Dj3SVw{!t=p{Y6D z1MBG0ang-|LX%N7Z3?98)sdmz*~epG{$99pI8I@-~gkt+j{_WfS9bl|I#z=m!Ymc)j4L9G?%lk5!DWl|k+f-uY-G z2kSIcazSd)-uOn2MB9vt875QN>U(aT5)qa(@&_1krr$XlkCzCRAl~lWyv>bI;lJ^!i|G-yWO?k3^v0US$l3ov9 zA_B9mSKX_`Y@;T+TG;WKb%rpH9{@R|Fv8a^BT%rTA8JAr_v?W~e}JD`}y-*6^^!dN%T5<<)B3mbN~)#{^0YZ6&nCBnr;D=|NW ze{?b)*mX{z5t)iN=l>~f_k{1hy7MtURN5b1U+F4#)s6l6K#qRRkhdzhX(MU4k$-T2 zw6VdB^UWB{76GjBT^&VY%}kNL`RS4McWw>viD~R@uDu6E7%AR^Nvi)-x)~*nn zedV>Cz^#>oMcLq4v-XRCe}Mfb5+gAu>zB1R*1Voz5a^R-_g^w|7bV2g+Ih~;Wu%l|_Qhb;hiXUSF4=UtHri1JBLOUhB7fj)|F zBYn_j4klv*bm%YlXowK`)-~^9U0uLqwnUlFQ3S=8rKXR~Vo|BUXk5=^JIbR5BGY%v z)}7I*E0_2M^&fe)pfUspxu1@>1Y!3sng(gd+9YX*Sfx!ELr{b5scY84oh&}tUks{% zG0Q#_HY_DSHF+pMB2lvQDil~k7yIAx4B8~}Gl!@bj(LxYWP!8Shr1#zb-$I_W?8CG z$DvhJ{9`NY(+@*_hsoP(w>n-Ktxa5w? z%7I%WwF0&EiA}Pm<>{JNFf7H_LJ`F@C7zr_%2|Nmp8T0bLdCvuYx(Nb$;!p(AYa|9 zl#PL3diy6RtEg;igYs{fv~&Rs-HY5*f|Hari2V);DPlsM;VAg2rqiFUCw;MAeBBZu zMNVDT5vC~dpyQ1TRCBcX^d~)c!LrdPhVY$?^K0C8e0#^lnCEOXJl0?SMpe2mDratT>(QaeuJ4Wl zOPkl4kKg(Td+ND$b&|i^Ug3=z`NI8SfTt7oZVe!=$qK)$sDYQG>Jw(f3c{%7JdxQB zB%`+yhQRP8=-}CCouG4}B^F0{k&aHck0WFDs>kgy6EYOiGX-6xpI!-XRkmIQK@SI^ z_O97@Zpio=4k!HPht(`I%*<`Z9UgFwXI*pNEFd@9O)0-==1`Hvr*sESmrQcq4RXHn zSY$(i_c!WSf?4)mynYJLE;%gCVvU2js`$K?d4rsJ%{`~Cg6Eq5z)eJVPz3jZX39#o zuRfsa`kYE(WVgtX935l#7YMl8+;Jpv5Ar$M`~sM;+(GTb^tDy*b@f+ z^a-|f9vCowY>h^GfTv{XB_n9rn+5dtDMgV8fv|VJS{9;S%)Vi?@I}hJ*YVGUZvsKX zFUlYq_we_CZvenukY6n@A#6j>?!l@ozv2}Rb4)u>K~!mxHa;*)6p1@G=_zQ(a_P%c z#qOX8C!)XEqp&IHb2Ih61~MC;tMDamJXqd2H29i8Jb|&SvQ|DD*>Oe;*$hiQ<>m6U zx7*qPXQXDn*bmf$+hV7yE>p&t%@>)Wp6laIQ5dgs<)>qFI^Xmj_l&7=`b}=h#fDy5 zTcRh`{E_<^WBh(W@D1t6WIYiZ2<&lU8e%Tp;!L;kQy-5O&q94`#p#uEr9Kyf4=IlS zeJ`ancirptgIGMlOYkYo6E11=EeNC5W6f}U`M%Mm-V&&73CtPfFpjzHUcOB3FEN2;&!~kPORQc(!AH-E9dA$Ajhk8PA0NB&9bU#Oj*VnahD{ z{sBTf-6#v`DR__-H;5i=6k^&KcetR28JW zhlxbOl1VFS*oXMQI{IqUXLfSeVi0}D;xrWxyuO_5RdO52&q!4U^zc9*M^3pvVl zuoGrMmb#o2w_Ho#hQgqcqp!yZ_CZvJwFf)d_8~`D{-v-6E!NmN;kn@tvf@quobIrN zp+jE9H8_n6>YK<`EHIA$8t~MJFZ+>(vF{5R=dV#=U#V?tYv)4}iLU*!)-nQ0BdjI+ ztFYd$iB$=+*)QPe86+95)gZu@rjI~fyEVcP~36=qIGQV{`dbbZ_V zlb zrJo@*<5$T0Gd{;H9Tr6IYcaGL+ddaA+eXiLs0Skkcz!Z2f5Dd`xzk+h0pW8EDk;UDz%I{K=z#e)2o9x;fk(-C+NPCXq@&JTC3;3Ip9KZ=A2_c? zALt_3J|8vg=-Ul@jd?KRArcY#4VgqD!fnH?;Y0yk5z4Oa9bkAJ- zg47}8QxzVa3G^zpv9SPjt*vRn>i*0LNO`!S55)^OeKaU zZwa2r0=*)TMf5*G5a|4}4wsBCm34uf!g4s~HMq^M4enQ+42v!$lbH4*un)BG;mmV0 z`PK914tKXmiI4y-bVSBTZz26V0zy7e@6d08Qc%y6K7W`wHa^z_6SqO6(R*>U#>_M) zmUrjV2WJ&*_mM)AD-9=@&hHyGf-(4XO$Q-lpmWXIwtS7}DQPx#?!tVg$~tTancAX` zFq9V;q0rp2b@?lD3!^nTq-J@`FiE0mliK4CP;&KQ`m#9BojK5+&Nm1dgZk=MgSZ!#WH~oK9%+YS zY%6ndsW9uXW8s~PkK*$0du$&=59QhSSfGk77g>2D7t`!_i6=NP73`^KbCo=q2v{GjJ%ahw9Z$S`<-P*pqPeqD7Y z{V;z-KfN_mzBM*4`quN~q8;66Rrkc3UK+yoP*o~kkH_B|(iYY07@McLNRVY4in}hab{c&Q*n~{VmiIP=1g+> zr@Z<|qR6ain?x9$TSufM-r-zIkbZlcq*e7bV!o~wO+=nqrW+!L>+=s?%#wYXCg}){ zvr++ySt<_RzP`bCOfVl8T4w)#dvNw1zx+hbGCbYH7I+! z{L{^>Lgnn(-y8;b#NVDCeKM@V)WSueHTJARkKFU@J4k@MI1IysxxE^>(OC?LXQFzXq(y-~N=Zg;qzJ^Xs#~d-=Oj@v@tn!K3-{@#A$PoxE zf+i9f4h|Oen&|X_cT?+K2dRgG%-2!EH`Yjhsn8wkeE4?QXmH1H!MUpwrz|!Hgr89C zS#1W(1G08jS3VPqbWB4;uvm$B(|KeihLCRm%`CsuRn?>AuMIK$ zu?^sv7{%YQ2m(Qi$E!f@0slVLV>-_yxCun4S~dNsPBi_CWzFh-@%|^v%JLtUwN5iM ztfhzXHkazYGmr0E6@Hc+F@J7^NkQlcj!c5EaG2LjG2I?V#@KXM`nGqg#_1`$9iiUD zRZ+Ht{GQa@@EVB(Lkj|!v+qG8&BVDAq>i7jt+l^@U8b*r1j!LIPNI}%Oc?2-B^l; z)vd5<$xV54LTP+ar`j%$Oi(#rqmPyn>42eM)^*;vbomRbdxGp`y^1%dAx`;87s-}> zb>i24J1|3rJve@3Lc9D!TGW7pBCJRLdkhc1AasZJ&eUiuvpxyXpu70HT00}vOl3_Z zMa2w!VDyyD<0c{N7XEH+j0N{m6lD6Kt+kQ#=8u@E(>wDjYpL!b;K|v@U@k6{rka@$ z4*=H#9Agsx&av2*=(#L&bs%EL8U!=q#T@cXVS`0aVoK3Se@W-lr0x4|10l|UkU!K$ zfUCH;N;D|xVc`vGE}$l;xoEDRV<29d_HiUMDj{Hvu;rgs7lLn{v3u~t{murZ7|j38 zvho%FzhGJ6=>4L&u}xM;{aaq@+oXK2KQpj|jRf$@x3sS?=aAq}gpSz+NB)M=lT78W zOD}yuFtbxPSxf}h!LQmuAgc&xi7fN~<1K++a-49VnEV5MJnIlU2A{kq>CU1Mv|wQoG1-_MS2<)zUr@kG~1L6{J&*c zp};IJ*6U^m{a&;3!!N-66i z5VwCagVKU^gsWh<2G5~^j_?#RA<&bSYHOQ~nMPzci_P88(^{8oO$&pbvXH8E#*Whe=Cc8ex5%ODdqyQ%6cJ(Q+ez zSTB`QalL5!st+-y5|#q>G)%2BhTZO=bkioH;k!aQdN?Y&E0{FII{rgcHjjiZS0F#5 zqk&`z$dh8pP^SUgQ6Ue4(WAPepGc#xMbsQ7Q%ZxH&*0Vj9#gLv?e0F5UMX_sI`Yf`-I%q!``QgVfsp=Cm0B5ARYeQ0`8a_=O_AnSnIL2>BT8+j>n2^btI# zUU8Bg1?~dDgOI9K{Fh~|VoUh{#w@ZRNM7`V%5IU zprk+t;2FtA3l@&Rv25>OzxmrA8YCL%>@LCA3r$x+0s#Zd^`FO6Yjt`8CQ{nx9meq| zCN{^1^g+=>b^C8Q18;Tmft9E~SnvkQL-d8&-<8@_mq;oJkJ<%JLJmT~1(NwQOug-> zTh@hY1BTw}vc1WnuQuWFYN};$G^*-BDy6s4iAe0^4^0oAaWgO7dA|@UZ?-2(P5s34Dp8`a93oN6|I703H_eM$LvELp1O7ON}{*O5Neb>qb$0~0=yq}7Q)Q}Q*mw+< zsEc;es$2r}B1`vlOe*}o_5gtVZJ_k=N#LKVx6@pGLbQ&eD(vkj&FrwU3P+~QPmQvZ z3|`;L23Eaf=o+ddu?nX|Cr?-|c;bu~h%CXg{+40%6c@nrMzleQom@o};K)p!8W$&m zv(pypId#Q#gas8e24U4$qnQ}{Gt14@u~iINQ^;_LQ)+^# z0tLCd72C^e!~3O*8&EpGp5@0JZY7g&H^mM1VD${}?S8^U4 zKbq4PrKMvcg&X^Vt|+oH1`RzV&&;}RgOE4MA7$h1+dt}$=vWn58zK6Ol=w~scLa!9 zT!wh?I?&-NRRY&%*cRsxh^RRgkX#;G2#)}Sq$boLN(Yhl9eA&7ZPIBRwKT{_pVORJ zC6Grqjnc0=N42JN>iod{qX-nwogH#hEwhi81kZy_fp6AOp(_-z)7=$6cdY^SmfkZp zHmkN#0?PF=@Nq!0(hz}72>j5>8w95l?ti=bO0+G;)2bC8 zEr28Nw=B@vCd-)bg`>HN3bHlNn3$$F@%#A zQgKVqCFVbw@S?2h`bXsX_MM3M3||>qyGsnZn*!uHJjjhqmOIF>tv~}0 zxujswT@hmqQA_cElKKG*wV0%JrOUt73N4l(gcg~d1PodH&i&9Ls=-_^BADM^X}>IL z^%>kSAt`;~=mQ`Oq`KFjLloSNz=Dtq)r`)+(`EUYh{iVDApfGQDUD3ECA=OAiB~nO zu)_0T{cMn1h3sG5pxo2664V}Ty$tCsm>)>uB-w0+8V79bok)D!VLj`tccK?;Wzy{e zznMQ11D(+|AZ7jS4>sr3x8yhrB#kUzg zey$mccE+L)t8W`kb66&(9gZhyp3ORBI5XC7KV5~fZ%wwZmDQa-{%x{C@)P4MoBTCd zVar1PZL&h8)##4{c}!|a{4bOB@s`vnwTnR$Z9xBAWV2R@bUWluiTx7~GWm~|#bGU< z1L--Ae+R`xIL`#$&C{f3!yn^lt&`A>6MYi3$_+RVH55%*(=IJq(sv_msc81EkS0fm z3@VrdAOYSdJJql!qDc2iPyBiP7c-DzfL&KKZ5U z+SwJdoslY)oUQV+v{5T;CJDJ;n1%fQ?(9KbKBW7oWKiQQ31A1SCCt$6c2XG!`O zJG@^=wl0OAFS6~4pN!Mumo)G^!O{`5o-J`=L;Dp~=^ z=kvr7)+}16g5CaJ;cUD;?94QM_Vo3bqu+bBEFBEauQeG;G4`=@;+FwiBMzp{DB|t` zr4I9f4H&jDLC1+@5ia=riIpqCAW1!V%4Z@+4(O@*@E& zQGII1AfbLT+)}Qhe5@(Xp>&sb%vGN75EY~o2QbTHh~MfFSJxfcXt>ELAQqFKq zk_DP{sJ1Lb#|3L1S`pJX^%=qwC0)h2F(X-U*9!3$I`YD{mncYGEb)6*;i2JI|B^Yn;|r8Va2h1}yo z?f-!LkbyM8^wa_eS<}T)L8)u3WJ$LNyQk;ewY`Y5LI$%>y`dEap_a@T!;@B<`(Kq+ z_J34X)FRn`sjOSF|590<{!c0^sqw#6*7E&2M`f+=4M-Kg*)P?pTcqb(5q2Ml zI4yxZ{)ftH^S@M9{P%yWtdaktvg+6TUscwS^Z%%mW!KA+k1kxrMAd1TP@5fVEG z$BMd>zg+!>Gw>#Ug&Uj~zpzw)JFKl}svkUb@Ih2>(1t$*9&}qgv-KDNQ zgd(`jW$Iy|_MjhCtux8mCXImr6KPNm4rv89**sb ztt|X@gYvwonvLvSOQT_uif>|&Q$AM)G;K}nr|fR&TiTn#@uEoYN1lf-J3%WiVK%#r znA~6RT=o}j5U&9gb0P2UK&f*m(m;b3H$_P-bz*WXpd1MVCP97LQeUed$QVh+Q6sV( zDqnly48jR|H9hz9^WrvuTaLv2e{h0+?ZOf{Un$XRb+f`5d<>TAbM;N#e`VYLVQK)L zo&;9&XgWSJj7KsjI(l2&&E=Nx_stzcdKiU+t5DjcklLtcc;^nch|10^;#x`9om({O zGaf~CDfAEVwQCx)p?=`)p_JR+x$9qgM#d}ud1fGo->z-e;!yCz5S{yVWPVr;V)1oUr zVuHwFUT{8f%|b*W_@Y<}p~bE$;G`xHxlfiUKL5poC42SaaW$81Yq0>UEiHW}TC=jX z`MP7d%OIKE&nWRy8$)NI)cW=d!`WzKn-F$8$^g?Zt)@F~rTKG<(U#Tv? zTau*B1CX;!tCoCwc?EJiEnwgrgT#r*J2v{}{aW0O&sjV+WQ73>=xXHFaE2!Vfc*1H z8)Ov8Bb|GV>ca6ePhDRnwOEwT--gY_AswFD6sUoK7s$SrvvO()Cyw14du$mPv7Y#c z_gTOix(E?$UEKJRTN~Wif(bq^_b1nk&f3Pd7MO*}_-AMF99c;B@>XrR1 zEiINA$inExjuL~*>(WrrM2WN6g_MUx3bw}iZJ(&{ocB-}^n=_5;&CEp599tNx0VB# zRgZn=Teu=;PPsz!9c9vNe%wTu*TAy||CL*D+JyltlQU&gYPOxcho@We3XVSBHV&Vq zjF?cQrhK-@-YbXnY@5zs&zCD+W5<&Yw}qHJ1o?plFEq$W#>Jo)uKg|q2ACkaL z7jav05m)8`vM|p#xc$9K^|RRPqh4U2VCmYfDoo}SRFLl#9x98_3N(g#j?|4d>Tbl4 z@NP+kG!K<#L#dOkvR-h{eB zXu!C60UzYdOKo!$qAkOzsu|<#Oc1kC!&XC1?5^%t;e)AF#EDi(*Or~{luaGsGIF6I z{2b|q059Gmkulchxe0OfD`Ix!xBA2>Fj-TpBQXob`;_J)cr2i5CT{fQ)K^}ThK#8x zmY#6nf4bhjOD`3Hd=KVY3#m7s5t;5@hZQdi=qrmb+-$bU_2LG33J9$W%+FR&>E#g@ z_n>?zAKC-W*-{s`T@q1nUmhDXE-k-%)5#?{X-et2krnXVp?vj<5Ge0bQ-wR_^F|Sz ze&)$3*-0{sF=UMfwz(3`cZRsNpPrfd=lfR%XXCm296Fmc>wOc&muw(!+e>@fLlZOx zbqq;c0+OE$j6&_D`!?wgi+jALatlPO{V7MX^FQe~@|@M$j~}o1hoxx0N}@g)us%FoF?8FLy47vMPEF z!kiQI7k1IqlXGZw*$^0`YaoGpFk^n%>ayFOeV7JeBP(7g1&<0@A zc^3GeAGqe3Sl<~H{4e!orFl7j@YjO{A2JOKWy#i3^YNOOqtnsZO6lbT3aAyyS$|Is6S{aN!Sh@iS2pMXq$lvYS6ig4itY6jAjWQ zkLwda1iXkvYDPG-nZ;!9hQdUC1|Z$|Z!b9S*q)+`Vh}E3ik90l6=W)`u5r^7HRZT1 zZ_MHjy^0KolZUxmMbRd~rxzl$>`4W4N*lk(j4NBACRv7leZzXLW><>Svh@7z1~xwA zVTHIOrCDAII|MF;=8{J=wg|(bC#}_d7fjg;{O1-6ubK3V^;-wMex;B2r9jtO?FM zk&6dz_2PQTY?(2I{C4)GL-sn9x;J>EPA1Nk&`aQxb3j3IgPY?*6e-_>5?#-Owd3F= zgvvM);9}3WCALJ7P;^zN=Om!d@@@4Gy7ij8V9-CR3+{XTqcZW;a&X8HB3NS)Ek5-( z&yjZcE8Nh@s$9)miA&x~9t9OM8tqZ1P0{leF&S;%)LY;sGkp$A)zB(;0fT#V%+H?i zOJCWu8(RGznLz4$!@JC35`9?NseN!f80P@hU`9|A1}4CA1NGLky;%>%0lfWXtiSR6 z=#K<#*_-*v%?+7`+uO{lA^x2}!2b zY%si{*pR#SAlDh_?(|w^(^ag{-!J=MQGLCk$$RzK9dx>-qCRy70DE~%NyXBdOhC+a zUo6~HTvHEHSr9|XO^cTKX>p(ZnPEzBYjA*!$o2c&St|}QXmn^pfog6W4Q}qp55q>L zOfz+HM%}`OI56b*$%wIDH#7o-o;@6KvLiaVZg-NIH}d-1kceb&Si;&gl~KO81r$Ts zkHr%s07V%d+@&~l=0Ljmec^3~1?Ln(gyBa9FPhX9sI2kA5|TdYKCL0p80~BB&3aX< z(IkI*xWk}yIU;Kypj2T&LW|*uz=q?_=?sWcHCTxg8wU_H41ROl2W(!Trfnm%6y0e@l^dq417TOgri0by>%G2l-QLjk;TpKsy;jICY9iC^R6F6)pe%VgxAcx2vnojlv@? z9cN2JjOacd(*V=y0X8v=HWi)d*zM%QFh{6(%eku-R1YywDiB0!e_>h#u;~gRbYGw{ z(9Q-eps&s;zPe}MAREntepU+;WpAv=69_i>Rl2U>X@Ru_m^jFoGB>e|J_c{S#D~ZE zdp9OpqRM+ZwmNz*_GmXKs5m)Ia+X{qXEb6CC+iM|3wOU7WK?|+pafyOJ+PwcY}%$us1BZ_{zW*cy{vLdwd$f}*1uQ`v3h)irHx7v(29DSxelCgH*C&5U_DxmFaqjRKH94VDOSJ2gH>j?nTwWW*d%fex96(ZLaS}k>T!A zy=hXvxLLKP6=~stY~FTctF+gI0AJYdp_=j)u}F6$t8{{nL?7aN&7duUg=lNFU7=)7 zMPX~>GlFU5rOK)n6qGf0S%D7tnJaKIQ`?j_3aHLp1;^?2M3nw{0Ig8#KU6@JwNP(MDVV62>tlSiWY~{<_`tC)gRh% z)=(-fnqU9|MV7s#vyE^oO7WAJaL%1a5WB9hRi>{U)}IY>CrIL&)~SJn-DcVVsN;rj z(K+6ACe8>sU~31wBCCKmCWbZi{3->Pq~usEZnfB}mI=)6$-pg6z206U(g7#P*xrT_ z(kiJ9_?mO)d^C4VMY|4hn)GA89z2B8T4}0$1Dw%<+x!j}uRnsTdA*<`QTn_t=B|0{ zvSqXnReNR%znzLj@_|)ljEx1uX|A8MbG6$xrUdX^_r8;ntY+?|;FqSINPXun0v14J+&gYTQL;p?Ktibm)N$ z{xKuK>7U7+D8N&?aDcG}@QZ%zn>DM2bn0mO+7O+aSwGwAPa;zQ^a2KdU@{3>*ETuk z5p^v74rWbp+Zt6>K1}KU>ZfduJ>g)Fgh;WVun}+;@IX0(rmn+i4MEixmG5yAj?mvA z@spT(btpyr0;o5JbvZa2_tvL0$8$e{P7~ODoDc`$>pXK5u8gKqu0<47xb`eNSGmo}8w$j>lHr{TZlANWAw8IiuN^mXE3BOISqBsM1 z6Tx^=*Dl$ysltBV{A09L2O=@YthaDLSD>#-k-Jqgn3@PDA=Xy*y8~xFtX`|Bf&$ zb)qA1mYk9rgbBqDy|C4&U!E0g$N5cgO!0=RlMAeh6afuAmMosw9YrxU-{l>~#}_!r zAN|>R>318sRp?C!hq!xAUMe|v4Y*<8QmBg6*w+-zB<$yPCcWbeO#4O6F(9u)zAU+; zn3I+&F(k_MQG*cp3q@6jpRDQ#&(PHSwrq$*(ME!xm={K5CKAr&ba24_80BiaS#4oy z*Otxz5NE?YCH3y<;?2;?YVs}a41WtE^u%wbbE&B6@&M}6raqckJg!Vd(;=yqNpREL z(s*}WY>{fD!HbEDBh==ZbYvWi7X>!`DGF8Bcf|`b23vKP#8#{q8K&6fRzt(c#`1bf z3xwJclQ0-+opy_M1`89+V{wI=705hGZ!B_eC0&peDS@*pr84$!1krCy5Yqp#Fb0UC zxx)>u`t5m2w6qbab%=k?z&nSBJ7LI`oPW1cg#DKlnF8yiH)LMkS&NK3fqCN8FZI9! zt3w5fC3?_otqQU#l-p!p6^)KuyYtXp?Tu2F?ty9FsXHU>+2t@-eDr1-KRgJa8}{5( z4bxVQT<&grhC%3e!EtG8Q1@B&;cD;}50m|F4nbN6F-h@4!gt7Ptb6*bgeQfEb7OGl z{PQ1R`6!G_4m4@N3&ehm80bR7<(5gB*GMYS9u4UIhB6j2w9! zH}B#A3|szEVR{BeA{QZd<$fJQ`bKLhGwloL-xc6UmEE#Y;mj5=Vl^f)g}eWeA3<}l zj968a>-c9W$_n3zYq(Dx+YH`1_PA94f@^tl8)a$h1+O;@#-kAL&sQ}=gs%>rt;rE9 z&}_=SY>i2|-wa(5e;z#w1ku9jS@yZ$s?lwY=Oi>6m*J$N(t3-o{@24!RgA83Ka#~zs(;a~*y6c) zL2(6jn-z`d4y1s=%)U(ts~S@5L%$-?d(qY+Bqf(8;6T}`62Wux%RSBpYK>JdENZ?x zpfv_;oP)HgWe$XS0s*tFxx(PBQnDo_A4AGO>%ly3#rAH;PL{LU)5pwT?8IfjF1XgT z*i*!MfUUviTZqGrz5yEKiJPWsANK5)LwipHbc3$OMsRY)D@xjFkjSonRdhj{ zTMx>`*tS|!5#$4M&jkqfAM8j^y@%I(L7MUo!Vf0#7+P}6d=)yS+A-_DrbZ*ZrU+@w zH)}kgY5l#)*-u7SUqf(0oyRoQubs5a4eP+6_lGqzZ@`LP6mp~NFO-%nO~G^Iugsmx z^BGGp-nOCDw#ynmHS40ani8~%HD8(D5LGwJ=#P`@tpUtiw-q6s*xm7pLwpwD7np-9!6f}<2?~+;c_&WoI3H1)cvTxh8*lm z5%rzv5~XxW!U?=VEI9Lb$TCKBu|kb)ALSnPfj*5%m>eKidqw?_3r5rrz$|1`kHa9K?77f>!#yXvBs5T}2f`>I zgwMYbvT9s;*xS}jX-ejuKhBRouw>0Pvo*6{MaBl&jKGryO}Wr_-}S8e@DUA`|7Ep< z??}|@{<=Sws)|hS+syiFRkQZ5x;ERdcb~AHIX@*v-n+L6Awn}`bRwMYWVV5lWK}P5 zW|o;zl7MHqu6exZ9);eC*(^BUaO6P?Xb9=IcQRy4$Wb4lxn2A-mpdYM`X8VvwckLXitQ- zI-6U*%BiafgEja)?g{?Ds0vJW2Yz`(nI%y#<055t2mUZBJ55H$(iuU+@1WY&2Jk#C z`41!#=)vYu0$!5xK*Wf-!L>jm^*~mIb6@mgP)U})0Qez}IaFXqn!CuW$Xc_-Xnve2HeXnTP+z}`FSDu@<E`sR7=x!?VMdnfhR zS*t3mRw}8a)|ubY+8W5a5u%S%8}|c30GdgDK%7l=qWYJ`A+zw3JOL+Px$cD|DU!_m zzf7xgzis7n*x_M!DrWq@Ol!N$KTK;*<*@^MGPI3yXz8NQr!KaRT*&-PZ6oCf8Y()L zYS6;5fQl9ISWF(s?|C5rz%8tBFho-+e*5$|#5MN-Fl#%6QPmt&-T`&pGzX)pSE(1n z+txS5m$5p{Zd@bo-vB+QB-heZT_^EqT`$<(vI_t>XF-&6R`dS4*1I(V7W2I5T>cZR z_=z=ot`QEV4=6RG1Pu-UvZ#u~E)&$K25(pNw{lBvh-xfpa9}RyCLY3f@DWo+%hi{G z==jHJ9Z6OB>$D#JkJCz6GcZ!>zPAdx>)Y`O^~MHx8#UxZFk&{Tb%;{OuW+Y(*=IDR z&vzasDUOEFp+JvZaFiv(LEcKZAoX$3_BT`msx%T|1t+4h>ic;K&_2f-hN5bJq5F7Z z>^|n;k@)n!5_D1ohkUTpPr)0~3zO*?U;u2PADd;&qcb6KZ!8b9ZX^mhh_w5T;_jr^ zf~{S32V?`9qM9Yni#vpWBIit%y$RfuS?z>+Dmg=05fLY81vRVkMp@uJRL0gEJAJs4 zNhPUUUCRu>KKFajNuITj=%CWbxKUq1Zukcc3B zD$7#*eTnNs2Lt9VdMXt+nfY^>wl*AL?F9;_466@I(@i2nNl(WfK zPv;R0B`b?JU$nHajoQ#mLB1`P{OW1Vs1ZI`iLZyK%#u3HN_bR|=u|#-UHqyA}))8%o3YP|QkzW%tF!7*ZXQ;-D^*Arx zJ*9P>Foch1W$H>~MW2S};Wjj1`pZyqV~@3S^ci-Ti|`=Ialc^1+9uz6UxPmiL{dN@8mdN{I?I50r+sdJcW91R}y)|NRI4gHRA!JbHI+?=0mGC$r>5jskL}1nOQE)1c6k2gOz88(hBq&b(|N8Fbp63SF24 zNU_PdCxL`&b|;!Lyq6^?>}K7;Da-%`SX!jxbseW?rUSoPA9|835#Ksi-|PDZ-JLR! zYCWYP92r-$3p1Ajx^z|(8726KNbvz;{dL_9^yTMsRaK‘)YIbQgyT@by!bJ&Ve zA(Rw`Myo7&yS4K*BNR16z1C+$vcGqK)*kj*J#c|B)l`WTbpBh{maF<{_uhAPvYE(i zF@O(XDyB36r7W>O*r*t_e&MtJ=3}V@ywty7q1-vZj~nLzt%%Xie|ZzSk@p9PtfLUi zp-h%7x*TS!oAD`n(8R!!9s8%#B%op2B-u$=zXg%I>^ z6kiF-J2pS6heqOWNKArDWJMfc8!aq!dbqf*8HqPD}`4oHEqw{roG|Ovz z+MG-HCI;~S3Q%bqgyS9_;>uj@`F-fMtgBp;W z)=Xe~qOn<1vd-=tMsXsP)G4zqq;UTWYccpd$Vxw=va`xgGeTq7RksVHJ}oQdPrXo1{@Ign6L z+IJcl?U|`V_n|Q&o?dl$!V*evS6UXRW`57sc|I^4@xxs*s6-X*KVp$#Ee@UHdvgj$ zv1wxng?`qw-5mB2ZKaa_o-Gr!6Fmb9cj3wPKYBlPfci=HyTJZ6NuSo$Q!QE7jiE{% zrE;Z&hF*pBH4F-im(bDqDr#g7@H0Z#rOuyNVKs-~my`a?kdb=>z3Vc>DwJ7y{9aFU zZt>SL8c;zQ_#9@SJ6NlFPl8<}hong~m@(}mzp`zDIIsvg<{r<6=Kg>hb-zO-va2gw zM#}-L*jQczNwxe&0I(rJ^wN+i>o?p~IER=CE7$%hNXJru?w4XLv>>b5^6w|%LF#if zpMI*8VRZ(urK}Fbx4WhveutDmIzQ?@w@Ojx>&J?5<4b5cy#URZu`|MIH1cnHkSdC` zXjtuEkB(hFdV=h0&l6Ne2PTxD?+w7^kU^N;!MvR&bnGw*S~yZ_2S?!`!VN(b(qcC_ z_Az`V*iX!IW5Qvpo?h~MTNX_0APpO5Wfy)vg+7eP!xCb}xk^!k5|B|$xzrPA9n9}v za~n+YZ`(Kww&?pe?h8&P93AkC2#Gz*@?+FIVA-a{K51{hkmLC*e09n7>~G;?xSxm= zKO}P!)r{ky8Fu0(HootQUO(F9u*5oSLth4 zK6+uvp^LkE-= zB4}!mbHW;+QTX*E*WBajtwb~bK30%5(Uh5W7y{z$(}MK&x8#;Xw@oef)dA5bwO@d`^5VOu4=32Q8=qW4bqP zLj2Uz*f%f2wGv7{9&gwn$R7Zv@9-x*)VnGm=Lr>71PN=+ikHl>mITw5H3UGU`}bP( zkJ&KsqGvC?yaD4Q{)bHQ%g$3NG^w+V-y(Hz6;lQ0!Sa^Js|S8L?z+X)AoZSR((}s3 zwohKPPd9>m5cU=ZxsF5JYBNj0zQDR9T9FBDHGOv85C#^Tb*@#wwL-%(%=9nTN38}g z*Khz^!4BLRYtCrsFi_=~blU(v+0xq50!+zp02y>!6HEy0DI-^p?%HYE4g%xfQA~tJ zXx;9<-=ntx@r_j(3vE`GNYm^U!otw4NMm{6&q}~4b>^#)Oc84+P#tu;)Xn1@G!G`_ zm3?uG!7B4l5?wEwe8bvysZBfx;N>l)-l&3%$B7y;Pbn8r8Qx2r?V2mc z5CD(Sr!i`h$@K9)H>szC#ReVMPW=%&UKxnR^u?~?=kp#~zRa(}daEhQu(&fGDzhE- zdzNPr5gTVl&t{kbdk7y^V?l?flI*jX2S!u>|WaK2*JT4 zgAF5P5`3SH-1kwbty8nN*vl5jq>Cj{=<-?W+_w6yhjf0fb02R32spQsHf|E;;c zJ2JI)P$z?a|A_#roUyY(Pusxh-I%gUei05;an9o3sju`av}8h72Je7Sp5Oa)aMvxL zRj6W4cUn9rh&iwu7S@8v{K54~%(8NC7LW8CJizvXhhva1=BRED>s7Xd*NuZ%VPj6u z1VJ^w;c-v`glb*+dhTSX5j=*9dZftUJaR#`|EqK-+HU&+9L(TGZ4$>k&Cr5We*YT` z@FBQYz2m6dK-=+GmF-!U{L_ns$pLpia86{`WlmPC6eE~@152V%U+-l6d}INAKyY8= z=Grx@SQ|0#2m4PJp{3)+9yzZz3Upzk`Ec*75kMh3#{G$YGc4?y-=sHGuBsCDAH_R& zTT_u}#qU?kZ+N2mVO5{omo^#M6@M>fP+jU)RB|uveBg#6D|}eR0QP{?P{>J0rIqt_ z2>Zp}NWWWW6sMM)J#?VY?7;u zgt86rxf6Kyfj|on9p+*bPZTC0%F-Wa=N9yfs^xBqW~AC*FxqK-2OB_UP8!2U z)1;F@g{cWF2G_2!keg4jScAxB8Xg@lG=ZlEB9t(*Zs?kd+yjbxl^yxDfAqAi zGsMzi(qji}MzjhipqmOkc@u(}pebP-oC!<_{PN7_otANTK$5hNMM>I0mr44s z<|_I^^TYc1i;&UDv6TFe=Gw~mL%m?FL0upf=ZwwP^6sE;kTp%O;ZeB|o#(ISx}AVc z`j6&X^{?i-4bUbQ75}Tb>K6RfToVY7BgU|l#q3dzjRG7D`u%^hxhg|3!&d@>#7$!=2XB@c`MZm z{w>tU2Y!;O3IEHvcKBHXS;X0Y zgZU5VYG{?asx*h@XTTnl$kq&kD(*EO_xK;qby=$D_8-pm`y7}ZLo1^uvc^JT(qsDY zAI?=VIO~f_Rvg|=2WNTu#Sbf>tk4B=*NDLR%sw~o%W^=luL%Fd+g6xi3uRc5<;uQ=#GoNN03;auNx6E?%rX>NZNA0YjgbA`v+=|RuI>?ZCo@=UP| zBF3~=a4T|F(_UkqI2XeHT$8R5G*^bHSR3GCO@VilWeg#Z7QAChLCaV!y}_T#fKq`o z=8auhaE*`3=n!n8ND2Do@!PS+OkH{w7Bsa}VdpA=lJ&oyD_r*FU(Xfw|9GxVr`QC3 zKN!$9s+-ZwW*bAI?n$-#j-HUhw;L_5TD5MPC=D%OMA8@kdahu$|Ci^=Ea^@UQPspb z*RVMKjm~%Rs8#dkEJ{dP-gBvo3T&%v8hUYPtPGC(&Pj^~SGj+QO|Sm;+LJ@^F|P~K zG&fxCZGtmIviEWBbgW0pRDepuzm)CL5|>m?>`vyOg%v4~Aa*val`NQlGnLIFV0S;Z z^mWg!;BaEQERTXRZOTFz{SodMCi%nzLQLSxJw1)97bE=l0*A*ns07|te0(XOTj4aI z`5pvwl`idi;?!lgvE+E&O*I*Vf>uv7!mh2>+}T?2b8Q0<0ga#fJdrB`h6ZHH2m5he_T*^(Hgw689e3rns4L}Ll}^OwWIMnxrWurRT6 zK*2C_oM3rIU-S_*%VE?vevmRh_$CT1vD5)t$=QTOA!#5f%CE4mQ;(832i?%rc4NsPB{ zkk;CHZ!iuJsb>B!Wz+8kM_~U0;yiHD# zBoSjigyH3~b9~sx3L@yNsd%JGi8jW)@Yu|4^r|n657+!O{ON7QC>B^bv=HS<+6Fbm z45Z~}jKRt>LUC#{_-J|GD)bk0-T8?72Xv*S`Y-636m{|s=<3YSnH|hC`)9{tpYpVL z3PGeTl=bPr-G~iR#8p!&n_w;5ssa|%y+`mjaY>DqJ)AU*8fi3wKVJ{)At|=Dn{=i@ z+KCIhLSyeb>8@IGh5DsYq91mlb;}3jUFUtY7 z%TFFsD%-}TjW>S+9Igk5PXyV*g%hhbU>Xr`;C%ihz%cPnuVq!;<~SE2c+CJ-zs+3G z>9FivD<~P9XT{yZ&?}&2(lS)-6cu`DVBDGrS#oKezVUr;OsBIti#xY`Le;fGS`Dnu zs(hF$!7>RYD;xDBEmpf-3Hz$6!}o+2LK*c|l_51w9gz^P1_5D*3mDtoN3I1i4^W2Ho7`hE>etM4X%Hxi@S`G;f!;f}LL zJwpxRTPxWIxfH+3z5MtUa_eoW^vV3QX^B=?0kTb0e3V+fv%;1~6BjuqZ#r8cdD9Wq3?6TSY|J0j>KO5thP^$R#& ztPqQsiIYx!^A9e#$TR|`bwz6lg5G?^S25vlV_*VUb}^PKv437HQ*hFKn3AtMJwBMfHk>f zSfpc2iW|lSdvb4YZ`q-kI_TG1JK~zvd-F83%`Q+I&leM?BnbCfuG>sm3gS@9MSh*n z@3Aq?(_-kU`6gI9cz`Iwlu4&x9U-#+&|Z%WV<+%}$6!mQ^zCOsB5K7^6x;V~(R##5 z)<575w74~Z!hn?qbE}Wt2|YAg)t>b)@k$J{WBo7jihjHFAL5lGB3YLytmO~!`b+OQ z{y)Sk&1Upp;?h%)f1{Pwq^Yu?INqk$qu*fu6kJyhB zd0Hb$EO32>k12w)&yjW-kxk_&lEPb3u#snk!FK zjF&4l^H$+MVFepzJx`LY@YK5FizW-H%I?0)ZD3ZYWOgvJTSjH?qwLhq9ILi~n|}!N zNFO0synB8DmoD{x4)*M5wJsLP{YlK^_L@w!MW z)cIfI6)9HbukkwQ^N;bW9{I2F8V&W=c*PEB{jc#FF7RLDHG<}^@k-nLkMa7g>wk>b znSYH}f8MTuA~wxV6ucQstY?IXv}Z$CsDR8%)kCVx%qbzZ{}8XumYd({K^&4C|0P}} zP5&WYd6n&9DF26e1y)kXOD}u-+6@ct2NJsp(-`*(6Cy(C($QoXBscU*RzpZ*M=7&1 z(*8Xpw2-6+_&giNbaUNp8oiZL&{>Dx#u33Hab_;+6T+rN3F%)*L&B`BvBm^9QuTWd zSP&{AR-WSC;~fWcU!QgpbP9ch=cuZkB=Zoq4@qpUGJf9yL9kumqUQsAh7Z3@{luMn z-bm1RF7x;i+}s>9$|tiYN90~XZEXyVEh|Ol2G}m;=hWu!9?;a+QuhD}Gg@%YbdXyZ z|2?J@mFN3^3$K%je}&h#e}z{Tz>XmA_pTJ9NkoZhqreyl(w|OE*Pi0Hw%+EZGG{%; zy#b)#4q%5i>3p60>Tawgd|W10mq7sTYVNc9( zXkc!{ks!ZOc-NzjMN!J#es1inWnWUzJDfFwBpD(SsNQJY1_U~D2XGg>+VsDJ@s=Pc z@>gu*MM#epI>s6!ty-USfOl+cT*d_YEpTH>qDc`A%~w8|)`gg=M`Hz-`vLH7GTuAz zp0B~lK_}KP(ag!y$XpL#F>B926zCRc`r7+?Rn3qenEr{r}Z6`iaIt*LA=cpag# zFT{fIrAp%v2^7=c_y>Bln-vg5kdBTzjWMcvDn2kRDEKklS;UbdPcyn?!Y`S5yYBSf zGL;atYf{!;pq{Pq9bB!-hG(Upduhk;4vp@GvR}4bum2<)1XNu42lp zCYxjqq|_C|sDyn#9@nTsWKF-vwDF*5hj(!-9~x)cRe1+-d!P37In;v=e}#>saR^oP zWcLqj&o;5P?KHDQOkr?EQhsYiWFZSu7^pLKMoe0O>K4PoF8kP(-L#4?K(1lI|x(|abj z-a>`kykQ{H?maIt4Ym*|XubSvwzFwz9EG*~@oE=^#mOrV@=$Md>LTv!q+D^-pA9BN z!Ftw$l0H~n-evn;pT!7ePX;d4J$(hSK>HF(+e0q*u9K(iEw! z;N2t=QPra!{5Gvu3sb3{`;>iy{SZtG++T@*uryGeZnGjU?Jz7#Nn{jv@Gz&VS_NQC<-p;k5WE_kOwJ?i@Z4R@gp?f)+la|7h!y9Rp9m4Cvd|Pw%gji5yMB& zT_6G++ZQTaIiK#HHtgWfO7%}Q-?#K3u7<)o;lR6n>*9JLU~ZT`addijUOrPEYxznW z3DO}M!M!8v92+7;@cH66n|`)jn~btnx%5I|AIfez2|y*99kHnlj%yL?jB`Bx`I?TH z=NH4X{|zq6W_i_vI~LT63nv%yg*W-HIL_e|d@RR>R@r3JTrKoqD(!pV6LD(~bZDb3 z5U&0y$!GMR#t~8Gw>&j30OI1^Ruk17TuA=H9Y$>U1%sz_Yapt1O{&ItwQCz;j~f?1 zxCXX0Ll6l^Ym?qauv8_6*lF!wIyP({{TwHV3t2r10UuX#^=u@7N;7mjT0c$-x113E zCVHC)CPe=0u2X{=O_Rgu{5k&lj(*=Z8}e=&XHce~oT>`IBzSq{2Eq-HAT$wo^)J+I zjNdyBGBEujVhKJO7s^i%o4L#^#(}))GapJhi5zP=54O8;}rZ@6Y3LKqVFKvpr|Aq(Ig#f;QXb)VM#PpP_gIP|%0U;=;Bf z8!8@3zD_d(0C@5|38dRP6!1OqunqjJur0De-&=*I>Z++f&}&ur3D z?4tdl9@&DeE@1O~$g7MU?MCS(lqR0#+}3?#P9q-I&d?=Ath+#QWAnefYs6pPwFu~c z@vc(;hj%^v%e$tc{>!^Y{=dBI=)b%xx$g2myld&N+$r{)xU6|Mo_iWFcC3odl_^`G z_arK!BzCDY$M>zTj%(teBb(g8^i(CVjkl)MFz;0F4sX6x!AJj7k2RTuW0E*piwN!{ zn%+R&xdyBfTVr~+P_sE<2m79J%of`K~%~nVqV&Jl}GLS2Y z-g^o8AM&6z9GCl=mV`<~Mi(nXykMR^!@3!(eB-irJ$3;23+`;R?77g<$9 z24;{jR!3-Kcp&1&2OCPP)GzX zAk&(3cz8RI({En~l~Mi~5N zJ)-AU9Yh3uZLeu;=+}q#P(j5mbs5cp(F?8f_=C90m^lZdC@#kQa;AUqxH>eojb)uW zeD86?4{WTG-(G1rMYO6)f-fC(-&Qce)bXV&n!SvNuNGu>#cMr2tuf?z5;3MWaaepm z`c^3db)lQ2cNSRCl};_v79gWaG*#BEv&+4InbOI$!{HH$TgnCh?qeF0iDEwyYn~Ha zid3mZuECNfNEBGjl~NxwQcY6`JObpTtDU*VTm514y<+`Oiw^s-rhV$t=LsH(p}XGV zoD|m4sRKKqh-2}+1Y6A>|Fo^IjzJqiH>v2u{=qebFHk-08M1$SVQ70kcE3Xt;fXRF z9G#?PynFbPV@YeqnZgMR;Kj_I4Yh#gBkU@5CvXNO-U`+0dXfNrptg$P^L%Z3jq?>j zpRL#RR7JsMt?(EfhejIKYr*^MtFB9(%IJL>RcP+$Aky3{*h^lf-krtEqowJ@+2l3+ zYKH_N8afYG&=8}kf*f{4ujw15!{GLz!`te|3z))^Eb9f`5w1M&AUOZ+5Z)IFZ@%@; zY!Bu5y^MY<9myoi<_xRgw8K0uFTXo3S)6hcSs2svr*8rI2Bp*; zoM}_k9Tm)^-3TvrF^Jg9n5m%_Kgv1@21=aw+`vt3;ByUx)awtnV)j(ptLzd(!+S?+ zBVR=67nGsph=>sLl4458q)`2I7ZHro^TC)YsMmVkX99ZZ{H(=t9X6D#z$@}p2m0Mb z4iR=v@KcT;|I@Nh%bvPB^?u}dC;-CElC3Tb z$w6Ndih`n0+%HQKHd%yC^iT9{78d ziLsMPca176Lk%_1Kxn(tNUYitxeMQR0lF5dA=$pKBYdT;dJvqnR%WKbscc|;!>{eh zQ@;A87hi;>NTB~54bh&!DHeiAaWzL4$S`^UZ}77n4wMnDv#lF z|6w1-XnmT7eZM*ih84^pZQ}#a`Wnt((8qvwK08%1?L4X3D|$3q+@17G8cDx_QR-ls zWAuKX8`qa}NMc~Q2PMKlB+I9$XDFu63lqlh3r#Mi-{d?ros5v{9JJcXKT=aKdt4$= zywR2T#+XFp`bncw^W^4@w|66BIt2Bu^g1mM7-v|g|4232wm-iFA}(lH=Y@SPTLAc{ zNyd8^W?%tlW}<;_Le^KBz0{{|p##Re^m#7f_B?(gghw1R@Vp+@`H<<>G;`na4`y+N zT^Zc>P`Rw_^d+C7OTGC0F>JD$J|u(VhamJrl<(T8B+}hWr_NTZKPC3h9+qo8WnTfm z*L1mz$=q=nSm_yA(Nhl=`Oa5|&r~S6R=HjXjS-}mQin#4kU~6p1%b+e`(;K>Cw;kF4vWyU;(-IaXV44Vew7*AsP!!5&u!ED zKZKCk>6}%(wX^~AsC-0rVl4R4_xWCStOCtXLb8t!g)cPeq>f?2(fKezHI@V*Wv@D1 zLrc*ho*+{Xvq)n55zJ_!XhMqO4Qs={tj!}x zjMiC?3TBov(}HRp-uakE7$V=(-8FwlE?P=EeY5!Gng83K87QkAgK*IJ(6i(6XZad| z=j8iZcOnv>>JNEjjxST8<5@f#aTO_qL^co)Kcun~@Mo6`c=Ot599c$KGW!%h0~KEO zhc%6Sa#*~uvh?~?X2AV5H=-Zw%{WJx8U!~&I(hofCI_7ahBPRauyc7dy9bJ}^$?En zmuOMJ0T8uN6Bifx4)}^l>C*g#IgX&Sd^a$EE;XPlLco~tYQ5`1qHAtudn6ohMYY>h zIE~ZxEwkB#MrVWPlOK|O`#^rl(t}xz6JALNf+&;!5qd@6RiXHuyonz7aVJ0P8sG~x zMpVaPwdQU5BBuS%HlJ`gBqHHIxNUCmy*3crAKX@GntnX)@Qrgh(D(5$^DR12%xZ4C zE=8DZBg09U-wa#!Ds|Vx1_m@0x{Y8vzuRh3@#XZokdLRqkM|tv@DdMM%VMMOA^IGNRm3H&U*P!E?ItebtRJnH>dzUz zmGWh5Atyf`>VW23>5(H`+|D60k=r~$_9!C7$Wa^tnvp6#V*ETnK=rlb4it1gtQ6dQRX5bJj_l%7YrhUcB z;F2Zx?2%yORPU%e`yTMMuAQ_4#9BYxnCh6~wVw6K;aoGD>j98KnzLfPwXvD8(+1S{ zfCfsTtTvDM7w?Rl@0kdu*Ob%@{^;nGUt^zhNSvc4mr{0e7yLeJz)^TUoZx5hQ%a%C z0h@>CO|H=Q%I33<{NPRwq4pzmds?&<+enJB?9mp7S)vsj@7PbdynOTp?|RmO{1jI@ z9RldN0N{6CmnEu~nS?e*Z@S6_Ue&Zw9lOwZ7tjtr4XrwQhWykVyAj%oo4}y#Y2<0W zp0!g@umfdtpVTWMLIaP5Fy_niNmD_mF&Qq7OEtZ4(5E4P?@n6hV+7SN#h*faQA`R!f^une7JS)AAS~=Wt@~@#lafF@IPtt}wQkOWvPwSpPg{ZY z35JzP`H-zm?FaiAF@-Jt;Rg9WHtcOFnY-u`WBJzv4Y1pe{WY@07zbP`N#HvoaC5yu zrGwo2^`h3*u5O#~)vIA^+X7i`9JvhWMP%0(O?8QX5y!2r^#0pubh-!Z5L zEGsibj#a{zamXRM+AjRK2v|VF~ILOn&acPz45jP4sXZW3^+Mx$bfa zd$nHIuwzbs@jR?8q>g|#XbX}wr?K6B?Ch)hZIo(x&E}jpf{B#(A5FgRB`c6`vh(7_ z?;3l-G5CDt^`Hqaq+*m28YTy$lTb8$&bCLDTeq@{d`w>lt@cH_*Z`%0pV;%W!aHW^ zS|{+1t2L$8d;H*AQ~n*QUeqtaWO%bWeWF7%k?g~v9&N%K@Mp?rQNDc6_$}D$B7?Gm0RLs&&YZE z3Cl%l%?IevfjoZ zJ)0;0Xm9J3F`H#;{aV$vX7koY3uSn@H_te}h;0Ff_!jTSa$PuyIsjH*8Ok~@alGB4 z=s#Gb*CRssXJj5Bl7)mAH4i#+FirLC$hE8nl!^26blpHz=e&Gs}#aG~7CUA0_ zV-CKV_m;srqNUc}}3i>{x_WwirQwNTE|Z z;&R>zVr#sXw|9_6SV`#!mvxI1NJUm2(D)E;3h)TTs=AX2lZYZq!^DuGV;R=1X2I2f zW=^J{GF_bVXKOu*XB~1$3QD_zG_X7}FI|ZTTm6kts|dh_u_*f{330e9(Tu7QGE5=*10Jg~mY%?{6vEJ>tH;Bf=-+PAl2awCNiGF;wLbttx#XKg0;o`;J?- zhoM#B1mnJv@@7Tfu5(A?p5g#xp|b5Mg-&{P!xURa>OX^lE&HB>(9(c}p#p4ZX(bPj zUz^rri~AA#ndi3u2q3GOFYht6BS}A%kECs=LVrHw2XV+6DkZbx=N_$BZG9LI$Po{{ zH<}d6lC@AO&H;p?!UF^Qo@WQ-9W_TRX=UldO5Z|p^eU!le+>sMtbZY3&EP#j4%B(GPtNtefKQBhf; z=BTF;CH?bz=h90T^FUR%u;zzx1JtGByK_hZ1Oc13aC7f@2zD|PWTHkORtEv6)8#ZC z*lZW(pCgf^WPzbn z(?Bxr>Bd5PnVYi^rAS;{k?SwZVCEZzk&|RpW(De_?lM8h>;FuPpH?O2f38Rvzo=xX zYbRdnEzoy@2IApivayV13|a}JdGJ!l+c3kkowm`OEHYU?Z}P4SP@D<3)h8|bQkg0H#iz`ipeUbOPt49LNTz$|h<_GKY&#Mg|#?|HOo=3h=E z=*3OyRGAr29uBNDvg9O_vYU*0v?1!XO#yMYL@ExW#TI$k(zs%*q&p7b2XrGUq zhiI{9w5%W`?X1WBUHrzuI9mDo${AW*B+0D*E-!qgQ8BT(eOl?MS>qn?u=3nkJUe5~ z|8w6|b`y~0P7n63;x@8~v;Cr#-kK;&Iix`_3Z0x)!T`$sft(tc0*U+((4+AIUOkjO zozBToGx)Ndsq7SBwS0si<$ic}AZGxaDVB)?OezssmV52j zg6sLs9lab%dX{+wHu)XX7o)J}JAe`yd;3YcE{sx=5&e9c zTJR@CAD~sX^z2R4VOB$Q8A1{^HupkG1ZeWeUr+;uA5qoGJmqP@J*A93whfQue&!3i z&qj@Gy%i-<6~%;x7qyjLaY zYgKZni{&_zzmP6eIZ8GH6l|AmvN~w$2qg5a2>)a@LfF~0ZQYC+gNizN%uZ$ zlSWT6XpM2FKTavZzH#ksM{i=c___RYW$#*qO1La&UZDTB!+`^Ynr(Yo(4N@UH@=fR&=N1v^ z)Wz|=Qw%L8BS!@29H(aM=o^0h+11O+5_T@wLWE?T!97Ypx_4u0IZT)dS28|25>ms_ zZ2ciyNl2?Wms`+vzQ+yL3%d!aaq1^}(7pO-{9d?=un=)x*#X&q5{hQN zq+{@OVl-`HX*hv5R!UL}`aB7m_#C5s6i1>qd0Qp=aW_5P_B01v7$k)~U4P1}a%LIN zmlL%!jL2tQ)ry-mIM?;~WoY7e6BD~HY%n0U0h3{tA4h*+2bA~Bc_*tpp-s^%+37JA zkz~e(>OsB5@8z(2{AH@ zG=#t(4BpbJtr#o47M%8}_DNglQZ`#rWR##}k?Kv}{bwn~^zmoBxP>lPuXduSM3e1csg zeit8nFfb#?UMSP18UO%$dPS4TN{Ya=uYq<49k>oJm)~8AIWXX!1e}wc=$AeA%qen!#6%LuH)1=67JQp@oDa`i8`dg4y))u6saY&VCFq$J2T9IK{bqJTVwNO* zT?tS9!vYRc-$F^6K824GwA}dNJr>?g`{jDrezl-|)rOr!Wd7Qf0NsP1iDxyk4K7K< zivI5Z=XZJ%g68o$#$-U8ncxCYGHZ<0kH;F*3Bu4=gtfOPKAd5Dmx`*&Q?#W=+w^xT z+=-EQy5H-4lpvm2{+aB4lkgIGwl>7E!T4XHsdg{myZhpoU)FM!8?03%b*ZHo!}6_u%YRT-<6a#Hg_yn4PO~ zYYC#GV!&|My+E&m#jy(nJF-~tSy?0CE78&U*(*Wdc%^UD@FY8Ps)zjZ`f7=Bqk&7Xh{lCHKz$|6=Y3)LI?W}ib zLk$J=#v{>hvoEKhg@R#{Sq6cwX5=?l<+xVh#TFBQBk6)HMjWDl!}PgH18!c_)ah=^ zu_x4c?la_v&q!N7p#8v4FSJEot$64PIZEq#{hiZl~kk%S$iP3Sn8j38px{XHejI$FM~5 z$eO{ZOJz#Vlb)*Ka{7}Lq+0UDC0qMSG1pLOyIMTKhoTsDL6Jai4r?P7FNmDGuC%mY zEBhmYsP#mXX77MfR%w7;nEYb9PqPU}1QHtMpYjtvjNa|gr0$~x##i1K^#LM1#yMds zxq*J_yjN|5`&QD@WI# zfnabJH8^^*e-74sHG;cM6hc->Y$yy7mFe#kB8+j7wEPw3gBSJl=m`I~a2l9c8GC_w z{Oort0n|BZU&r=_%qd^BY;=U}$6-EM0*LE!BGazhHSav{q8Ovpa3R*-jHiRMjg`32 zcz=gdrm=)C5YQiMD}w|x3;+b`>%`rq_#lGofvcNMl6C#pbBhzJsm*#DY=r@){3pLrGkzcct#EfrS# zUt|CC48TwV8C5LOen9A{b_=N(hc&l*U|84bomiaM_$t8IPEI%~UunB$FpbLfzj8~k zFdS=T%X@4E4v3iM(6|QwWMVNPQmWYH8j(EQ@U1V8IcJ95nM*9pQMJM6l9JVOKTBm# zDix@JQ`ACXb%Lcm_fsHi9cl1f4jCrn{j3eg3UVw7qLfMe_`)VGwZw6~5)P*}xM`T1 z0`YplIffb9`81YKskP2Lxiqidg(}cPqIz>|6BHR)3axx`685!V!N~S==}OL9zscjg zV8YTR_@Pl!8UVr!>D|+D?^1ESC4y)dkpqCb@r)#7Y+8{@xY9Dtimb<=T}+2=%g?xX zx^2(k@hZzg5uYOcXFbP7&}ef1*Ba^f{(t1XWmKKX)~=1advJGmcX!v|Zo%E%-QC@S z26sYm2*KSoxCQ-Ix_h79-8;R1o$noIoHGW$m_^N5vua*-SFOeK{GQJv(O+fxM0Dd% zZEgAhZMlUqFIZ*uf!lWPycq9Tzv%cHZD3@ z=vw~O0p$2^5#%9=q0{;O>z9Bvr6u@V1bK9#e~Ig-FBITB2C@HWdmxm>$|@`K76w+h z%J*`m#8ME^?@CKD*@67LC}eD0GEdvgx~)_h zeduLYRkPgS{edp1(RG(WC0^2r!pv~QN8B&{u0x|&Rk#}OCW6potmmWybZq@-MVr>8#!k8maW*lgr4y5={|v^vnow=W)2atYK`4&o z>kPUyr43bg<9J8acl5BI=;DB`*5LdC-7_xDkmUmhzf1JrT=y@2<23LeDry3z0nrMv z9TZh`muWV-QznIp{FwlJp*&?ky57LNI1Pv$h&l(0{zx1MG~m@qxquevz7bHg?@H;B$VaODy#6eD~Mqr?qh_KcC2Hl6uv#Wo{hN6KM9^loeUAiB_EZWAz0c)XPx-C!#gr zM(G@qbY07y;2~mCmUalb>wA1qaW`%~T-#?p@l}ikt3kJT%4{21!WzdFFAQ$H09$Tz zNL=TfI-4`9V);GE`8L|r8o+xVpL_`fhh$1&2|rC?tT25iqPERg8(jem7EdTI^H|v-2JdOKMJ04kpmOP^7Fdu=473-xrT?NQ+0PK9aZk70^WbwI;y||Izib zqxo`(cVMv#m>eOmwNJetR!c+%A^r1gXW~dmat1D_SFtG@)aK@`?*dH(6Bxzb4_3u& z3K(nI?G~KKD@b`X8B$*=h>B-=D@Ys)s20+=@msd(>IN)^FJxUiszM)@@dP)=nH{FM zRqItmcX0~ZL&9D@feS@MPWNflIJvQMnqO%7?7mF26q@>Ob~#YwN^kkQTBKxA&pgkw z!`)ixeris{!gF&IB!gnLNLi-c$i0W32_PXdCwb3->SieL)!`Mo)~~N|yjry`K?F5Y zBs&a=alyGS?rg{mRzUi@4ukOP0^so-h|?z2se^>l(F06|>_aE7UX-&QF*nZgFhYqa zgpG<-r)yvdq^rYjsuj#G&y=aBN^@V%t=c}{;=21>(gQ<4EnAWUFu)@TznkXP^co? zbkXX8yh-<5yXXDp1$d-f4_>&8sqIsk#I4u|)m)3}n|9sxd%RuYmWQAcF88seiLbcl zGf$;bRfKze3!mVbIluDP7K{o9PC$@b+>yVjaXIcN-FTI0Z&B;5LvM?s$EkpNrP}k4 zM8r+ohhNAav$~fMvZs3q>aM87s>9FEe-U`^6XIgtHZA*cRp!;>1J1D~A_0ibz!Iexo0S!3LBHQ%PT@;cOM5 zIazp$tV04)rhP0tU;Nr;baJe6!9wEfXW3TXWXpZPil?y5i+D&*1PB&K(3-&1MvE?wcs>8H%Mh z-KG|U4+9a_7m;|o*V|Jvh1D=Q?l~;Sn|to$qvBdvLHhD-f3ErdbzKc{vRDSf^B&(a zq**+H#LKNB@VTC7BMFTW{5}>HEeS{|^$CNZxQAR%4+N#y%y2$sOP6^$c9T@ry~IT~ zx7MT^Ys)3%VT(-VZ@~tN_9RPKV^;0C_f9SRmkvutIJso*wy8t*eiVm-;rgSPn@F4L z1iDDZ{nGf~T!6tsQdO9a`?q{SUk1ou=w>!6CqbO{9( zR$`Oz0e8)Mqwn?Qyy#DpP6!r(nfY#_d*COD3Wu6sB^z_RL9+jEZ*p0>7L7 zM=4+-19}IP$4_sJo!f>#&25hXGni4Il6qnpP>o;)N!C54l-TgkUJg0v&s{W>e{^|?lZIB9x zxGq}t6T0DE0r(F|1WSs2r1y)lVij8D;czHr`bQF2uwjxV-INALWxJ21iG!R!0;~r? zi`9-ze265pU=<4h2XQ_udw&U|<_K*S)EL%yo?iPg&&vevdJ7N%!JjemTjl=- zdMIH7knFq%Gt=LP_cw(6L5QCtp#C*Je&;=tb_-~XvlW|;es8N>1)w#}|KiEN#|yO3 z)R@HEfl+AMy!E-~TDAL{Aw&@JAOg@F^FQfv|81V+=N5_!ocl|F$ncnx*8}W;wEw@y z5I~s#PEx;Kx__s@@1+W;x?d6C-=~d#EPnv6{-gZ=H}UFk@c5lqf`CcI1J3&uK!729 zT{jXof1CCH2O$Cg7T}ia@3Wo{NXKt?ReuB4A8`EVivF*H001n&&DCFh{m%jmpiKX! zD1HN$+t2X=LjNTceq${_3H^!)zb~GjCaEtWUvHce~Vf-#Pdj3SR`)`}TfR2d% zL2$_M*jX^Hx|VbNWZVBS!sCAu8vm1;0RX7~&Yoewzi#aSK>bG%|4#$zw`0hkxbSB{{gllpnn7Em#37!1L~hoEC07b12C@tfX4q?sy{D!{<2j6*h_y^ z^8Zp$|E1hje{s;DD~xwo+_ zzhT}Ykq30d_q5G!!-sPFiX?Au$2-V4GC)WRAnY%tgI}-$!YGz}^e7DCV0a#Liym6? z$zfsr7&mOSoMNEU1HMUk+sW?Hw?1bPO6$+N;nEB}yB&8FbIt^X2f0?hyh&dv5o_yf zvI{ynMbqNaktiRv>kbi!xu|x5ykG}4j=Cl?Q+d+wOjIL_;3O|rH6J0?ONa_aNA}1x zKJCsa=L_1Y%1*r>P0zO2 zXI1wP>iL-4NUAul<1gVe$GHSdgeW#FwurWE>sVJ~FGQ>+lh z=*0upc(+ieR(7Ati*Gf+`j(O~I51OusUI&n(6>rb^_fVtSk*KW6qq=tuxW;A87S{g z4dwLFdZ}|UE{o}q+=$k8DMZfr5tZJ!#mxm9A)CXk6!SWr(K9>ua^EC2=pM*|ef;*g z-Y5F>HRfrv6=c{CoZt{-<`^`XJ${fOgzrOBlndlJ6nMrWpJZ0``v{D+9@mj!gwQ4x z*#IR3vOWs47tPsHsbt^$!oX?iqNRX)lYp^8oDEFsZ~Q9^ej3T9 z<2hxvMsV}OXcE$2EI1;k(6G}lKaXwRiU-j%CUm8jRX#?p89swZZLqT&G+hlR5hGQt!FqO2kjd|NXSo29NA-lc z(xFno(5gZ(8ue+p|fS1=*h{}Kv( zSUtdnt*h@%Gu@;V-fmN+N!FEMOjmSFCAjKvNsxaD-ju|G@9>kWr`p|VfzL41UTVcU z90?R`w2vAjy|FHB8LsA8&jX}7Ax**B-5UnF6Afp@JiQWpc1p50{VEO1O~JwL*eo1KL#zNZ$@e-G!#C?&b4br6B=D9J%nDny#k7qPJx?7^K-aRD`-7GC zw2$v#Qt8C?_l+96VaYj>5Ti0Tq{1x*VaD5=Dq=*_q+N@F$Md(SYCzz!o48VF939PI zx&0QRtSQYTY3YBMf+Gi}}Q^PSy`aIkeoVELKC@D5qYSvK11l)@_%%Y7k4Af6GR;PA>qFCQI2IG%>pE9g%t~9 zBX_f^XU-7D7~a${5XSGv99LWUAO-|>cNB~4Vz-?p$Py$=g1(?bd=oH;B;#OFguw-; zvMoA+5Cq)xy6m}0y>Wcn+_6ze?_eyrnTb+0Mpk&Bhwk3AD{VNDR`L2-c^)?QLjpA7 zyN&)Ccy4&Up|Rtp@$lAc=cmQ`7D6GugR%-BLP)E=0yw)H5ySaU@R5tW@hCit4#MN_ zEyf(Eu~ zCNn9jHMq^vu5;wcZ!_5#uDS&Z^#fMubnW&m3$8x<1IuCZ@oB;GYCJ&$-^H}7XplMX4QdmS zHrQysJzP(|CDDY+FJ`n zO45BI1LBkuQffzgO=lfYSAJ_%aET~7c*~2v^KEvD$8;V4N{7q5)CXpd+wrPyB=Ru< z=_GZ-DR8l|U}aw;BD#G4MVvPoQ2wN_tfh)U{xqzsI*&T@B%-Pa(F0Lu4@Yx{3xDWx zLrGvqY$g%8VYz&Rz$;8lB_gl;oyJf8V#f+3v#wJQ71ATRb!Qa>rxe)WL4{y8<)o4g z5t4`Jc8Ggx%i%#Qv?}B_Hn#Z;EFxg3)p^^-lr;ye)jQJ}*p=WKOH|z4)mD=ir3jYE zU7DTv2Oeg}u2v-vgu0G7xUE@8Ks#CK(%bjmu-Wq(CwX`iH*S1m>K!5{b(|coH&<%s zzVUJ5h;@Vtj`}|q1FD0s1^Nj=4>{=^Af}6jUS-(RDhThZj?X*u=!_y@AiZ7*zT(^) z6L_%VA}7bWO(VnDs~)%RTRUs&>UkuqIBZr0oZ^0z?z0D0QLWRXogzTO&cgo&r}WJD z?bRqaiRQ@eK{>9+c_!9V5czt;^lO~3%B3IdiFt-R;_8R;_(*VF(lIkFq6>I~*O6jI z_eX7#yi9EoSpCWvyp0>@EG4U-y*8Wth=eElX&~iPHgZ5_Xb`y`F?MqTiagR)mzMrVRfi+o)7 zZo7_>wb41(fzY%sQo-{`C3@J4-+>+s>I{4{=vwEWgYr9NRM46@%M9>{iEXC7cli$_ z7s%O1AO**dC>9PC_UDIdKdfV%(L@VQzbnaH|IDiZ^o^=OQ^kpr?CYrXW_j3AG3a;J z{1P=e=+)`>YCzfQ@PRRLFwiU8bXhm*daU7z(zD%`qJq14@zxjk8fyCtVH5KFZA<}7*kqXp!L^f%{YB-KUx~RtZuU};D-AgmNAi$|mEI+LYM;pIWAsF2Mj1fzU0(Qzb zc(b5|8$c~SOgX}`qPN;Y*Q|lBA+b+Xw6^+01n1s8#5gp3p&jP5ZWmH4jm&x4hIon; zI#9z%m&HQv@s(cq#TNsiouhk2H8Oy+C8mIucy72RE>^glcEInxhgy+wQxF_HWh!iu zU5)AGvyPR`Py&zJs9hftme#n?bWH&Gbuse3WS~o;fOEUhmSirnxOD|A%WFEx;X-ZJ zkFE%!wHxqR!Q$t%vupOPyEDD$l2!}db(d>+N zDQR0IG~Nu+uz8IzBO)D~LGPZpxq~i2GOTu{^)+xCV4sc-C{ZcFOizbnN8M%_W3q`T zm>=-xpXHTqp?~PzB26atY;^2b$59!!D+IBUyvHdo4neme$#NL;Jo%iO;4)zfAtB=L zGaIvf=bgBdwTp#jl{J>Li~{ECZC~BqgE@RJXVy+@WOk5HL7N+FemhdMx!Zo1wqiXO zbk|jytP_t`9{^VJP-FtMQfSnY<8-G>ldLYSqW?+?2fAa4(a-(`&a&3uwG<~T*UO1C zaHq1lVkw5UKQY(Ov=tl6OpgM%_M}$Y+=ULu(qf7ZG~#-^R=6jz95=g_3!KNpl3)N5 z^ZvX*++SU)H;?Mu;=cC+Pp%{$vH|l&PfKbWcZpZHRJJ4=YwC9MvbU&L<2k%8C|K{d z>9Mq-E9WC-m((~6U2>7Q)epE8yPV@CasQ|wffE9Yop3_$a}E#iunW>=b8mb#Zq{+` zp&#NP+wW-N)LlpFX%uoB&v+cyDmqITRk?o8QZPolWngw1b}Utbz#2oSvr$XsSy&j*FFq zeWs*#f@hDdfUnQ7bg7hBI-=_zSMm`maezo|P6_sVDsxl18u%~rLT2X$oUzwzZa-r( zOii7FP@Z;vU&7^w{V>6}wtMzvX=}oljHk4Y1oi$MbuWp2d&hv_gPy|#3_fIsPtiN3 zeCk=YDLs6vqVNpMINJEDu)d%n^02RlsV-?VTDTF;tOE%tDK7m_H^wY+(dCCrRL$;_ zJ?yJB7>?;NGg(`s1xNx1DIxI=1{YvdksW7w8Hw$z2iuw1E&xecucQaC`66@s@-y+?^#%4aN=R}g!E7;-S7>iVY$2}|UHOZx_pv98?hP+sg z&ikPV4JlZ$UFv&zf}1f+MjPY0$hro&c0FG4w5WbF_?a4rps2u>g6qy`sGMdadOC8v z7r2q}P%08+Y!!bINzVwHI0byT4TCYMJj1Pl(+Epa&GxWFps%gDQw)1AUswjl~ zJizWB@OsJ_yNNL7QeHS=VtNkuVn>B_nWK+C=*#TKlcTQ}vybQ&uz`-PtNsa%Mq-8ky(OBH;|CMBR$FBqMY=(ZO!zm zAndJzAA8XsvIaAJEp;fmhzDJ9|G?h06aI@?R>J_!^;6YrNe6P?Xr)EskwDMA^kf1@jp23$o7Sgu z9Q%U_E+W_I;*-;fnODysjAyjLkpf^@$VXO;vf=ZMeY;YQ3kY-4C2Y&jw{y`vp7A|9 zVhTDz@$0?tu?vH)hsBB)A6R?y2$3)2>zl_5tKVnJG)!8-*R0?Z%GjNK!`ny7i#<{Ac z@Ng$xt=f&p3ypTu7>&j%^}^mtPhi@;5ZJ}O@cfS$K&fTR&QpWD4GKZz7VB?`QD?4Z z_rod5TE5f-pTys$f`+A4fnTiXr5s|~RgF3n0vN;t>LyyZ!V}PckY0}DkC`Ipt}p>tHZeR0tZvC%)wtyb>Z8)g0g2}uoMpD-eUUfl8XkV-nKd4Z znmTEV))v<}mgfCVhnqWxPp$Omw&9o5=Y+~nILVAy*N|3#L5nsmL3+DnR7FQNtuC{XCQPmM!3HEl8OLpu&66X)KC2wD*Sa|Y^~O9%umHl2 z_{A}@{Si$6h8^b$Vy&v-S%C*dQ8U?~l&vH&k($GjDFJ*`W zs$xA~*@-EaKL(}Meh8EDTExK~Pkl;Y)LuWGpdqFjL?{Ghg9_kTqJly_=Pc#*X6y}< zknyE>Y88XlZ=;Ina$D;1N19J%W;>|;ijxJQ{Ps3$3v+D+R_aGNg5-d9L`HfIL@90@ zNFaN&nOPsqXSEenYx(Ajd;)j@yghPXw#p-YOaenn?PIm#LX2#du!*We7O=3%lCf(# zljVs;@Qi9$Ny%7K!^##qAF&vX1Ttc4($zD*-J94)YIm(eOka|)X!G>Xtb#EV=~uIN zgafh-nW$b$3a!bBUtLhGZW&Gr?7rHTaKl_QzS|S`OeQMLH7|I=Tu%d|PuqT_2-nSy zKsPSQ-PS+=VPk8z=JdBm4=r73486S0cqvKP49|^&7s%kF8HT`H7qzSm7dn&Bi*bXj z`C8NgF}rfDL83$j9=HO$dHmq@UAnP5c+D#_K)Qy5gDsB#$16Tqw-gQf|)XrT^6uKhDKfFka&&6&#c`rRW=KYZ>q@RFf2oE_G{3Oe6o%^I3u6EQ}=l zC~VL5fqC;QO3(t0U);<16&lG$welWK&SfcTlI*=rHg7b|IHLmQOw5FY<}3G}&t4LnsnMqFCe3dt3Zwn zc=S}{!pJ&~o2rcLN;2Dkd?VjC(Mom0d+^cou5N_#vUbU09bX21PsfV9**hQg1HFI6 zkvd>UJ9buo=j$ko>I3*B!!UOjae7lv(x)#rA!wb?DN+=1iRgx>;_t&;{b+HQcJ zj<&&i?(aV1dKC%}oQTEg5KKQ!(j(}m2Aud-&JJ@jT5;nZD{$Vl$S{O{7kdN8X){$V z5KwtgM-jFQdXV~(W_}$}(KlwE zByx=lG8Da^x|}JW!FYtxNHt9-}8BE$)LkSp#pn(qYTCZK@Qpz6ME zY%ma9fYciLGPxHq$`bBq;x)KA&(KV`Z}Ji;olXyr5dhgK&P`!6j!h3vre>xm^D`Tu zjx4RSng-jo;3DjPKkd-ZFFbu2o}7~wO(eC523E1@vhm*tT9YgignK#;T5}3O>Ej}K zw$uZrIw*bO_jd1jo7rL=nd7Z-Nd2J>H+o71=Wp&rcw>YW79yHMuYo>Z1oBMTY z<$GmlL7dGQ7Dh^Fj?gO<@nK@`L~Ssip3MD53nH1zVabiI__we)X&@rMERZceiqOn4 zF29#Y1k-$NHvJm2c?j+shg;9Uy>dseCQUc-r12f50qiGNi{7Y zDqy2i*K)^o5lBWx_r8QoM6+oyUK=BjsmhCcLiqiLGp1b zlB1I!2pq(KQ^Tr=Np_&awQ02=8pv_Q6?Dm=F+&{#VbnvpQ0Fu@&aCRuru&%t>QHwZ zs-P$MI1jZT#K646KTFE`${|L8UO62Fq9|;9!N5D0@e&5AJPzR!(wT)|Ga)@kOm8;J zEX-j8esG5NT|(?DD>{1OHq==RTI#3t@U#H)X&41tx_Ei;274b?9=!|iPwxk@N=WI| zL(C|B?P5eFFK}bY!_8cP#Y&3t4rC*KN!4~QU*o=+OQI>eEDa%mtco*0~Mzk|OjE zlTivy3D$bJ1-wf2kXCBPwwJNw!?$SJlFyB(isFp$Dqd0!L(wifN)}F(bFOe~4A6%T zyZQ+bQeAM)7~p;SL7pX_OkwudDx`#ExMwsHS}Mm7zI!g}QSaTd^KgpsS4yHm2Xw?8j+dP)GtV8)=np=fB%ofAnyeeNlG4aqL69srchESx&2)mc|Zzg zAJ^QN&J#ivYTse|D?jA)q(d@YZkNnkRDZ}>Xyy=!F;c40VG~-(ccj@CL-w-DFFWEI zBdp}FvDuRgLKPgj(`hVIh8k0er z)Z?uX`UW*xzHDSt)?&G~jXS}2ZMc++XJlBG_XQ#`e~~ygI`$c{qzqf9r+jcF<+OM4 z$tQX;$p1~QO2*1MIoFhMeT>6`V1292Vbhx^WVKemb zo@*k|NY-5n0lvgz+?PfH<56*tMinlcsEKUO*|GR7nzxyK6caMGNJqlykN6pgd17WI z?~cD#zF+^K5KD2&g{G!TTkwL$oZ>b<-W}i@BVYrWLW_yW^SVrH@qH?G>#&(o5@;qq z%*QWFB#CVPp2h~0EJvq+6qeqTOF|r%#v(}yx_pDrB)_>#@2+=2Yc#dE=O~uXIjcVxgkpHG{s5j$fcN1b zDbVvk3+9Pa!ta0|q?w&zZ9Q4&cFUwy_(;D(S|iHnxh`_liF}RsbTgS(BcLl%$%N(D ztTCb8Y%WNTWmeLp!luFRY&PBw><{XSvJMkX_$C4(ezQ-SFUnr*)>16x@m#MQ?DC;Z z=KS+Mw1;2}lfYp^4V<>yllhn~g6j{YCu`(RAI=V*7FZ_Af-*c;*Y*ja4okKioz$lD z;Y{+p^9VBAuQG$Rw(B=#-&b_flY_>v_CodNK2^+g;3OE$BJGvMkDuNdJuBX@NNdVW zFIAL*)SR7$Ztw`L@e>&;27#`i&8E*RSMdjBySpV;M3i>Vy36WlP%>Lb{vgUhLF|%* z6?T*#_W$I0O437SHCW)NU4X>Z6Sp|OHV=B_tR#4zE>vRkm0(2GaIALDpajN9OyD@t zFnXvgeD5tBMnVLpjh{d;2Pwe8;e#|oI>Z+*No351ObOPwNWS;h_HD()1(Gh&O5P7! zMn*KoG?H-|=4govn;REGyofd+X;+`XC>O!;6%S>jYURCGg%bv|+hDewCA1}8!F%FP z6S+SE^(>G!Bt$nz(~k{6cj#rK%W|I*4YwCFH5@~h&frjrU9rzQx~>X?8&TtR_qH{* zak#;@eO>)X)<7@HthC>NLb3d)kNJ5>QmanaO-}>KN=pV_-I zFC2B69)I@UwJ-!<9nT~Q=YAxvaM(g|$_Kd>3FQ{dl^bGWebRZe_S5}>zd&BZ;W>wr zAk<90R^VH_=(?5Qkn}$H-``T>KzOON}?4aeXM-ZC0ww;QjwBf zKU-;8{FeW1os98Q){Q9?c^WlkzE=35$@L1RR!`UmqZOff;PJAlbf!7dLMbqJ!WFt4)#h2dej&5kyO z=^;!TR$d5)W<*VGZM)!`tChk3wXmLbdsqc#LL@E!*_qvI^^_3t(yi^?CMcq|05F3? z@SW5ur3}rg_vHBGjCxC_j)F-yMovB{ zZyWa>EB^;Jkbv1#J8T=?fRbGy=^JQ+3p<_Vc2v0QfbF^^ZG~F)Pa7;$E|3NdsMQe z?33MnIs!4re2OGLcmV=b*rW>zvm>&^r^4mjF_ULzzqCRKkgMrRiCNG1Op7sL`Xggh znTBtub_OwD-s-~- zWj161se@Y82BGZim$0g7aOGR&p|B}>0px|7T7XQ%RthhQ3S9k-KJ}9?=(k$oi&gf{ zkkGqLQu@stzPYOy-IsEvUZf(K*r*uIL>Tl#Yb0p10PQg9PLJe?QwdD=WmcmMq}=<9 z%B&I*mg#hOY3puw_lL{;Y`ot1gL%!$DGbzZ{J~fQ}_dw&tKKx3Rql*-B(kX z>@EdiM(55F@!P1<=FO9mhW#RXufHk8S_O#A`Y@S5KHK$K+a=rMH z(-BG+^69~IT2h)GJoQa@HCR|Ena{pbMRi`XPb#ED0#Wu6Zx{%8T5`}{sP@!KwMY8? zFh4S4_b5|dFtPcu9i84^q{8reDQ{fR^j-EsYMDZ-vSU!%^deCeb_pjCO!$EN4B~sN z_2e=T!r0A|Xm13`W}V%$E-xKn5${``kSfJ-U#?!#QD9}{)Li2oT4Aef%ZItdy+;cj zq86GsFu=pI)GR!jD-nf^*Egb16yv_}UAjbUV1Km*<}Yw?AehqI4wDG&v(+4IGKLo+ zVCGH|MSFp!j!<$oNG7U1r#{bxgWPevpji=e&`EsfyLoeuDjmnn-t@tnz*Buv0r}g! zls=k7{wRF80{P8OxsB?WS`jlCPt=gMv!p0h~|E^3#vQ)hkA!8GSKD!qrm?LD6@=k^K{B&Y^-J*W~F-twv| z5$;dF-VTcIZ9E@+hKNGoq~h|uuDA)AA53~)Y`$9;e)rZDz0&5ACBx#4Vr6e(2R$4( zkG=%`e)aX^$Bw4fdV};IrsJ4GDWC>4=a>v8{x>I8o}1N+In+BRG~C>%!CQptF4Y(F zq8hq8NmmV$dxuW=6X%_VT1yJ1jJ7f>TS`dRc-dt-?3b6mMx27k(vkFuWW7mg2j2>^G?$YiCczX75Tm46l=H@X+yBEw*|WTM9V9g68@2Q>CSM zxFGx&G6|B_j`8TN6Zk&dL+iCF$u1AdrG9RrCs%_+NA6q*$%d<~!ps4@wDgNp(je6u z%>gOiw}U>$31m$OJ$hfP{e(FrB;=W^Fvd{!)&S#Opo123@abS^W~*5A zjEr6Z6G_e{4ZfR=WquhGMlKTiv&Od(XETX=UzDUC*Vq@)1yYU3LR9Q`1l->(QafpWn?8I%Ey4_6&BKzVRhAF)*utP!-&-xIqiz9@@7B%3DOO>bco*%Bat-&?P| zt;V}+UyM%uHZ12nmeSi67EqXzo96%;de)0$r$&4o$hh$ArPuSEyOa?w1Fmiu!~`Y} z@{+Be1^A?af0fgPZy#UpalTNBiL$vmf(Y)m&UZm##*!c;>iU~U(H2H#q*j?0wKSv$ z%yA3IqbKaC_N$*{wWL~zK+@U zk-X=GUWN#G_TbQlOGAxVJp6lriV=zXU=gGks?aasdlVti;UbFmz1W#6*+4SvPG!sI zc(S;<>P$p+E)o1~galGL)T1)4m{0k59RA8j++zhQtIT3yiY)i6;=>MC{^X?c`wLs6 z0Q0Ksxm_gDiO~JC`sleLRqR&H1x0be)Ipyzran)ImB{x6ghh&N#lr8@K;!whr6|#D zigT`%aafo?ahp6AP{6Mm$i7qY`Z#`e{^Tg>-9o(cM1_PT`OYP3w^*GUljczfyXDvoJ3O)*j!`~|Yq&^TdgW`PsRL`L>qfOaG9A<= z4iO-3(VZ8&_p|zB2fV!;;fa!9usQK|T7=57SNig48}^!y#e?1Z#6Uf<6=xR$L}{>dqLg@FdoB_!=9KRwLLL#Q1;b+v zV>t!m++?(H)PcrWTyFp$KQusc&8|qi3S=3$hp{k!kAtf4%3U}6!FrMwFMu~qu)d^L z5jgj@heoz}bk;|9bZ>85ucGSkjJnepceh~~Rg6a)13pE^;5sp|#er1hpHu&FS-E76 zdZ68uo2RYg#@>X-ax(HOK3qsHB9un$mz&6pbThZ4`rQR49RIsARTi#qxpCU`z{^=H zDGjV$(OgOxa0A$x6Z1#mhIHf)FxFOeC}s#IyHRx_?`6UboXtp|D6#cJh0q_}Ev`aj zk#7dhS@FfW#j$1R3}yp+UCdzkDyf-NE(V$tGf4BKho>FX`dG=*i*+5HAJ}ar5bA9+ zv1rhfZfM+G#U=b_wH2y#reVmg3F|?tTlb5EcT~IwOeDY9Rg~IW-e`qlcE^<(n2E1^ zi(e`Ar6a@gZy6>}hS9vz!NYioukZ4T_iB9iL#yj6^>@$4O1T`4eup;x=qb0iCSLb$ zDbyB;!&J0plyyi*Hs7kHsP`Zbq6QuM6+9C1N9I%2)7a*9b{MnGh#IvDv?HoUBa&C` zV3y(hxCeEIe*6^dRvP_uRv6goNklXF(I`n06ptV1Cs>+UL z%jhw=5;H+S!Mjh)R`xT#K_ zwIpbYsxBL>a*7_g3IeE>o!3v~Yf)&3+R$GFlWy)Me0+ojg_9T-xW*ut{U)>tUd@SS zfU1#RZFle70go)hID$=F!?#g?vty=_7kS{22xH)L_jZBHjmy3?;DBEAb!dpnOZXc0 z1wq(!g2M>Zc*F@)Y`uhCQhcvsKmLHdi|Q%c!>;1+=rM}!_4C1?m_u66~4&o{YJ(A?YbVKH11{{wkWPRkZ454=uGUQ@*);Ma-3i{z

lU0%;hLz%@Dfc}!=7j-?Ih=mf%dFltw<1DS$`jmFdHZF@`ux#Qh?clc59x!T; zNO_7yq!fIJ3|5oyLAetcLrRv$hOW09#>V;1>Um8O$T7-`W;n2c8kTSsS4GQFsHVxz zK#DGFh(F_yttwcTc>c_aRAH4LrrO|9;JI0bRNjQY9L)em31j|!CU2d-sn!Gn>NG{b z{h333a&Mx+<_+c~r*auLm~?@NcP5?{F6K)e^S5^{?NK!il?KL_3Z13hKH6%oP|)m+ z-)cTID}I?TvZ2f@HCutogyjHDZu7D8Fa8qUfgyz>{$;P*OP4;LwcHQ^`x1W$$6Sg7 zE%IEv13YH{i;rrLCsjDN>p@P9GmmT)Jcg%&DNen zWk?|5`5Y(O#emj;N`q8=itq#W-97pAmnq!#aoSqoBb%GB0Q$0hA=pQ72e#$RHDl;!#YC@F(c_ECx0+1AVU|Ncbb5(<#QBoy9?_4rw}mAWyQDOI=cXLB_}|w5RCn?_h^Dv?f{DHo3X*Od7U9xrDsY z5iuBW;)^BF&^uPqf!beL?5M9c;gQ=8AF9(Ml-tGT_t=i2-R;oqxnFgixsUnEZd_?# zQgf7zbL0xvnMB|P`*k83=e3)LI3WL)VFcHVH=A+oIczGIWhGuX@Uo84IasMZ4SwJ< z1>TQ7qnGL$mZmH`wY=J%?Dk!oXdw~&dVhubBl`7tMY5hJ6c^F2Bl`fFOJXa?Z$EMp0Y}{(R~PGl&1ODJd_>k zIqI|9wbt*`$fh6@ly$;v>(CQ0J3bw)VX(45%#{@=%^xMqIJ2Z2KS;HGPq5h6>vL>b zm})xu=&(KagRY;~xT$B~AhR+qe-z_Uj1k5}Zd}I&^yuY%r9@S;>#UQI7qf{K zcfAj|oq{=~N3T!9*2jJY?_RpjMx+W|O-e3`TM!0ePGq~tq-BfF@%=J=!_?}Ul=;a7 za|(fa;Z9`QLHW0sN4)VDJRfiYSqg5Q*Zy#p4%$>*NLfJ?##9G?Xm>J)B;!ly_m%e{ zf&;sk&DgPXJf3d(+y2;r&@|*}EOij#pE)*9Y>B@;n6!VtcooA~{CZ#3_Ti~9xmwEW9!`22!L`aTN>YTGe)VfKp?}d&w^(&mui^d7SSK`lSX9@QSjV-rqRI ztg{?;$c>XI>yOfshP#UDWyStT;?vM^?1f;u55Cmya0Vzr8hPRf=*=+B5Z=ZYj zdGFrueXfteoWD6@jyY!j7wgZ`3ens8;woHyuty)+(WwUWG;p{WT~u=o);)COCb&QpnzRpOQ_hhxeFjt;XcwkSAsZU41 z{e))4g|zc^Jw-&83?XX@Z8qyDEz*?V4rNXlj#HxeVc>epU{nJKb1&!Gh6T&~k|L)& z%;AqGR5e8CrO)-9sRUd!oO09%3r3AK={hosox}>mMzuMG36~q@RiC^-w}q5&TdD11 zdr3stfkodOKze;{*P>f_D+!YiGHozNGZ5 z(s9)j!za&UK0?Ys?#KPGjw>>sT+i(6&XdJ3o9vRKk(3)g5)LK3?%i49X?h9 ze0>i^UMj*Nb4d1=m}Yg1A`%j2z?@vgOfi3mhrmQ>6>+oouNAy(IyqAUB#B0tnZo<%jhvscqzuOb@PgxU>Il@s)iO$|i zc%KsLN7hee$_^MqSy*>&Z24E$ z4i$5!zB80i53Uro<6ZYEHR&G2&686bBrjDmq?omxBCZ!)kbHNhd6rtJbC^=!8ihN0 zd{!_7bAUA2nzbMN#v#W}fQ6?fp)rfWG^RRb2d0EPcQn=i?2CK&u;V#*N39LPy3h?R zRTsDZCYF+Idu;jYse8X^%U&+BJw8e?-6nbX`Ke^>96xergFETkcRFUi?m&+1N%<(` zJy&g$2VM^3RxV2pr^Ye}fmYE9ZGjua9Z~4SBRPkm8(tk~sXDVVM*Ru)!rvupY8v7*tcvgy}Gr5ViXOZY->x{GhmVWq3!&YUp zZeN!_v{I$?6s{r(<EcU%G8FV zhvFq`)X`7H1_hnth&vBD%H$MQtqpbZ6>?BR0;S$Rd>qRj`*grSpf6ot{ZqU3YR5~o zax=$hQDs8^#mO@r3IUu%7|9m%P-Y?i3l#QH~1)}DIeGNI<~%i!ps5N9>({%_NJ|~ z`{g%{HnT&PaG!D$zXri?>r^)v6uoIJ4~5dx`#+b622A$h-Y06KC*b!hUG;y*_l5Bt zgN>`2Eo5MuJfS;F^rpOT$bb57?4Y^*sgpILct+%e#X!`0tWlC;oaJ z?GuE1Y|60RlsF#vU1%343JFUjCHU1r^w7wIuY|Da3%fdLtObY&xybzcQQpW5Jj?np z!;wAe{Gty9p`C^3%w@V8SJ#vE21!G6!Y35p_?nY%%g(F(MDYME#AMO$11K1Qr ztLAh}i63vdIq%tekuZPgF31SP!0OZ!Y_UJ(%;6hHD3Fk#sa; zVX>0$@%jX(frv&SKb-L};>gE$kBSE?$K@aLU_JjzsMsQ@56{ebox0?AgQF&5^-fi3 zgs&Zm>_jlC*k!Y^$}5oS1ub!0d)&iKb)^&Kv~3$3q0nfmcM$%P&CL;UAxtC6&7R%_ z$n)P)Eq3C!$L_oHi6*un2W7k*mA-=Vw0ou(FGBk@3qrDE(aKEku)&DbqihnU^+jq) z6Sk$yQmk3P01Uk4jYBMxOlNZM8{BM#vXjDx;mGyhy+$fLlSW8BXU3a!ws{@rY3iO7 z!`+v)H?w2P-S8X>6`#jYX50Qz9wHp(X!@pHS+PP2s%zxwX|RE4SIquLYFGJwPa)YF6m{4+?uu6AY6h0MwtU;$ng!V(j8L7j zqr`+a*hd_jQtE^W4T!1HdeS752xQNPH7+kwqoaO=Noj7(dDKR)tAwviDNYDn9O}#{ z)MJo;SCNu_*DqX7k#u3ntIU=311?12{wIZo?;Pz>IIRwFYpgpu!=uDJ(-f)*t?-DJ zswYQ3UJU9EYcYJPc%CusW~F^GlwLy*sRPBxFjfpd5q9`Rgo@N8tf6&7%Jz+d-CmjY zw;Rp|PYy|=!_H8=cEj$Lb;0#7qWp)1732$zWkitB+X}mV{bbt!?-ti%eN~d5H%cKxIXn~tGh(IY%nTVR zlsbXOs_bZ;$Lf+y*?RkY0hrFX@Y>4zRJ>^TUPHR7Z?YU-t zxKrip<9-}y(CGndjcYZ^!0A0g(?7OAaSFdzt`JoYs~c;Ibs_NDtLHHeB@q8M*a`Wfe22?wBn$O9G#aqTpr19^K zvTMm3PLWqN;g#Lvr$y+8-jFjaEZwANV3lW89A%~KGUJ}fEt=G*pcgu&Nfe2Izu<(g z(eu9fzVdN!mT3Ll z-TiZrl2UC*5qNuD-(zWBeSCWyPT|z_T%#&`6!xTHDf5XU60)rBv@GUjNfa~*hOo@5 zg$J*_ACB~HFdZQ;EMzm_cd_7Wtdf3v-ixp;!(LU?QBRxVgA{tr>8J1E+-AYT>Veft z##mmoVtpn3(eAY_hL_+w3<@NhugW1yqXzEq^>Ni6tj4dKKMy<-@u`yRB!^TlR)gzF zer(mMscEQMKUvB(-HcVx=uVHS;XVONUvV&-5tgHva4#We4=qGc^QnL>?s`s?w2&or zmOlzxq`XNMRy+dQK{Nz}z+0_3<5!Mz_pd#Y!#b43p2=t+EjURnI%%NnsTO$pQ)v{Y zmF=8zT;0yaYZfAGr~bzoAr#+PfG2-a@nao(EBVPAvXQ z{D?~FcC`L164`PUPUt6%0DkX)8`4`7cd zi|itAN+U%ayN+|FpVQ2E@t&0j+%tIa=*ON*Yy}0nm4vsQMV-PZ2XeLyUuCec>>w)F zC$D>tM#E5Em^uV8$2!w&w>??vj<;b?v&=t!SFs*ilZX)@Hg27Wk>CfsJ+3N#sB=S} zs8Y6vWX$G%V9J@sK&y^t?yCr?`VreI1>vN#qKCV^6bE%KhuFC9Y>u%h5od|r?jE?LqzAc$zEzwF zDbN?D0lZ#rGL^f2hw+1BZJLgSEeV@#j_t~3jgb&a@UDm;a`H3e{N!Fg<3N&!L1P8Q z(o-eouQ!BN1GlNwS!tN>>Fs)4i)&WVZhx75<*?l48WDGdTad#4wY2DlOVJ*&$RukA z?|ff?no6Awl|)Xm0RcLFFs;%PL-rOg(OczP5T6%_8f`o?aGxeIl2-ZIH(!lVl{aOWgz@JAII}7bUhk&cu=lNx2nv=D zsj0o&G?S{1&zi~6MMyHF@$0)HWV^9#3(P9O$Y8oL5X1YNWTTNo_<)&~DqSB+7g5`I z%>PY{h3=0yUGGfJJjJ;}JGq1E4PUGE6BFpPZ+5Qj>o03Gu`%WEW9%O*kZj~|Ta|PU zLL1&F_tpu>BJgXcO;kvi<6vYDIIn2#H@;1LX(BiHAgZ+aN=Bh2{rGZgea3gD7Qusc zM{cT9K2Y>c|6s7M46>1oxO+CXNrKq1PWjTyVAWdXK?@xD=TO!XxS3-QN)%Fql{Eri zCi-X1s8)YjOTaO~Y$GIM`ScdjB5g!Uj%(PP&*}L(mY~HfIrI*70t^A-N0E#piC41x z4edpkCFsQsJvXC#`r09F%Pbbp7gfZJz6O;7Zz=FJqjGYJ>sahlsR+^#Fs^#~xIVLO z$F@f~Yve;&vte@Id27Y7W<0k0oOUe!yiefTT1zDEy~Q|8Cz9uA z`Y^c@Sft1Yqi+yl~sQ-)c%k?|Zx);ehB0MYpA z7Fz!4G6U4&)frm2gp)66&#tT>rBATH&B6hTmh@FkYQl9?*#7c#ld5+Pt%uhv=`*7r z?5Og~4Tw{r3Y2fWbu}+x$87d*bzi?Z z#IVOMkVrJOcJf=KKxFBB}At?bY^YLzsBWw&Y$b zVs3*KZks2A9oZ8lx@@`0&F+Vm@eBt+mkmuffnXa zT>(|hvx~4$x%)0Gt1jpQ-nq+=oO}-pLkvB#0#BG}`0@+K2b&ikOpJgKN)<$aa#}uKzDh`M zOnWnky<8h!6qzFXBXA;B8?vJd_LB~2K!8vEYl#YP@ApAA?Xur3&_LmM87kpN~1&wtN(mreNwoC`cWIpWW8-Z9S?hDX6WZ@_yuIPWJr= zN78!advV@IS+1u-se|}+*`5*Cmf;L-=Onnkz0KG0C)J-VWs+c`n2Qr4-KK)wF0f=a z`zszTcMq;a7vdA9ls+^m^w~8Q!YDOO{j?c=&K!rj1?z+Cm}U3SmjNe< zwIioV#ch*rs5Q&RPW59hQ|9leHm+nUT5*h@2DrOjHBd#;4_+MM3hSr6UWS&d3O;?0 z@Y(X{LARn8G;6S>`H4YG0L3^I`*;OeZY_fllfVw)!IfT714I)`q;4cRP2A$&|bBI&Nidy?-Mxc%-WIM4PjOvg^hL*tL1Rq~&_$`5PmIkENfjdJOJ(XoMeuu=5m zsr$&ACo>jrXPFs?ix2k#(NNeW7RU3&UnPF0Yg$^*@t4RVDzom+$ciit<(pP@UQEwV|^t(7o4G=qKyu0W4~iUxFo~-d|3Ph zE3^Kvmu9n?=0mKKI33@JU6lL#fE2X{$!ey)h!f+X%{sYF9<-=I(vPtHa+%n!@2!ZV zw_J^4Da|VTx1{F`_x3bPWrvZWz(iAF(eR_vkF=}$wtAj?ehb{HX@XAfOs>VIgnTGk%M0#38NO;@Rk6sGu*V7z*b}4F@kkCyLax^onK&vVD zHkV{I2sWm_mMcRV#UdQJju-cpBT`+cm6anpZ z`+2S9$k-O2)pNA5ZZ5u!KDQ3G2kwWpO%N1_EzfDeKH!mjxpfv%sXFJj@VTtL9j7zp z4I(UD&4ohZqiO0SynK64eJ?pAyTP43S!8l;2SnTAtL*IzqALd`FoK7Rqwk@=S5waVa3X0ZsSqDOX-$jlg|4CIRP@}P zR9ED6EKPO6IkG!VJZUStC^2xeMwAZQU3oOAZSAeq%IJU?H6|B%t6>aqvj!`XyOEhw zOfoMfIBbGUQY(>gCIT{9XJx}Fu@8AG2UlT-bcJngFQ((PEYY1b+RUBL8U+P{<9?bQ zmc^iah4_w5f(GI^G`8`spm^fB_4}o#W2qlJc=KgTDE0eRJ{mJE)md>9c4`!%dL_2) z$Uljqi(D)f92gBk)XXy}8I%8NQ}zJm%J}M!0+uK8+m9Fi*}pT|>dl(3po`RvAVx2cWSOxx&yX7zfy57c>LIOyXhi~>X6@Qqi1)Ra6R&jS5T+Ks0XcEH ze7$m~KI~iaQ1S|92KqZ_wVB5@)F%?uJh51mjx=PNUsa$${E!fU43*mSsR@l7{?9K~ImucEpl@S7WTK$ITchtWt6tD1}E9jnD2#CL@ zq*<#V*~6JFzMl7xK2!<1QTe7iOrE6v0*5LR`9?J)sDY=&s5$5@cVMVRc#Qt+i!;6t z<@MYRhg!KCwc1OWeoT7SUdjdd<$c@ijEir3AAfr~ci-go2HnnO@eOsF0F3vrie1yU zhr~*O8EE4#5#a28^bo*V8@%2iK~nKYW>gU$L&!~ZBgyFAd>~T%|;l$jgBeN@bKYE~O;>YGh$J-e)xRI3J(v>ZY%Vqvr5k z6Lo$keSU85Ofyb#(|!I`?~v?RT~vVioy9?I;YFUKL4;baBj zdU#?t*2)5c2^kkbtkpMdtHd%Vl4LxVH?OJfR@#~lo2C!eOBi3(nZl?w-&~eP66=^B z-50G|HROluf7Kzolm_3#c?kc22Y%MnpyD*hpP*v&`XM7-oxy{9^w7{lr+%z!nJY%Q z*}IzTLhKGjsB*8<@t(d@@p+-+ZNUFB2I;hrnR03;rsPu;8#(nu$42+*r>+nXb@tGf zZIE5-Gf7;zQ(f&HS6OKj5Wxln{Sso%k_1h9Rxjk`-Kod!&q=P+7k6*R@8>r=51MP3 zi|RvuylTH$$lYAm)*N(XN_T?A{OT)I`UDSJS^c#aS4GAA@TiA>e@%ZyMYEbRZobzO zuj6LSITw+8o@V7C`qs&OXGHz@I`FEF&!Y0##>#Ly&k8pg!m~T=LU3E#Q>45H6>&Ph z-cM2pdcJld&%>xh#c3F2aExj>$~lHI$*uHbn@uyms1;fMT%uKLQPG8%Ka!~OzUbmN zn1i6bFD@6o$h0_PsVh<5{amRENzjE2LQ>(hFAY5}97or9Yo62gvQd4SL)g@#tzo4e zUg98Ul+Uge&NgidgeY(AJ1fmpZLUE0V5#hFGs^TJDrf>v#bs2t!tW4G&5G`^L9O45 z_cPEFMuS$HB$dfOw%6E@LWhGcjq#(sK3pF|_hAJY81x>GN~EySH=fB{cj1ZTpqVY>1Y4QQ z)A$*;cGq3KHnX6^s6U3O-j2Yx?ECF8lEgRlyUs66AyzhBoU z39E`cFpRZu`MIu0AeiTYr{4FNjF&u>355yUEjX}Cxg4e2BcC6fz4U`1h5U@novJY} zV{i_I=DHaRGurVYQHrSfSgjy)&lk%H9Rt8LjiUlHH!z{IPa?ZZU4Gq=e=u@#y+O+7bN3piDs z9&8(|cS;|=I8POEkmd~-yqv&4RE%#lEm>!`LgLV?r1~;yBy9Yu+))^! zI179?0oKpgjIrG8C{AYIzHmUO6JP)@80G)xS1NV@rF@W?f?{8{RKupOWL=Ddfv?M~ zDpeOi3Gy69i+#xK-(=CJo|XQR#5$l5nx#uE0C#H=wN!Ux1_A=DLiiOK`;%u481BtM zd?+f9&8n@Syq`AB;?13id=yv@zuz2Ub8_-IKId$Z)UlQoz6+ZkJ1YOG>V;Xt&iSjS zO7LtgO8dbhtjtUPTxZLSIzQI;CEnmtc|V}PXbV=MTC<^Q&LfyDhe#jj(0hW4aCXMd ze5!X)=5zKXZgo-Q>bV$YCX)2jLyIY4D%VLH*F6NR8nf`M?2py+pmVQ z)|YigTr%;BV?Tl{c*owwF?g&UFFk01RhJqyY$rP9lVMGscCDE?DNds4l#@O}$RmGU z#bK+{PO>sEWHldQECe>2qT#G887xUD&9Fa7K4x??{~!OptL;=*7}E157^ za?EtL*~L=D=UG9uk=S14GFKMOP~)W~J6h8YR8mu#pJ3n}^}O8hVjU5YUrmz*V$Ye3 zwmS|ey+DkxgSh7tWKMi=$^?~x_x2u(_sUrGYo)7#H)kbCUiglp5R z*|{{&aS_j>9J@C5X`_3ATUtT8Veu9@j?o$AP|L!0uR7?Tv( z9b@|Eg>dM@VEePK$t08TM}K8TNx}Gf?^Es9OyY2dlbis9(xaHvDgn&|+Cbqn&xLtu zV}e=H${@UOPL*x`HPeUF`^Uw=f6i4Kkmnm;CymsKH+lQxtJ9JK!8tJ&ZtpXitmuK@ zT>m)@$DYcuXirTN_`TX)iFV;3I8}(#=Jt$QV``))4)NIDF}nT1N%(Me$j`rpeN|7( zH#PBno@PVN19N+bVbx!_#u&5MhXGy*S?xK^yKomH7l zJ8kXB31$wi^N1uZkHs4f7%PFVo2C7FUk``^i5vvTQOu<>RtDp?A4WfcPu!$xi5kvR zQ798-pJFV=*&E7$S7&gKsX4RPl%IL$)I_mhIDG8ckWdKg5$+0?_C9&}9$T`kxy9+s zn3m1nQ$?>!X+i~}dm?=$XeMmmUcjQm>CK8@A|=dpUcYfxX1joD*<88!Akn(^HMB`2 zPYhDbl%5=SC53%A*K4V1MAjr)s{AsnnT=J4dJbcgt1_OBuF^BTG5C92KXQLFqV~u& z;WvJ7zktI;dtFVz>CTQA%&w9g+;+E|9t zXqh~pgm)!H@yO)Mbf?^~IigDll_Shys>{i1|IXMTQ9V#aZ(c-?nj=)%KEGVrme2S@E;=;88vG+@3YG+3@P^=~`l zZQ<)0!fcn0`H{4)i+^yV6VXH|IC@xu#}tI5)}bM&WZoWEq44Tnzu6wX!){H&cP)s> zS{pwcH2jHV%m%TT;FEytPjOS}vRBMPpKzHTh#InndKGuqp_X^&uUL-HKg9&Z%(s}S|Kezvr4 zz}gQpC03`bXBL<~Z`lSX;V-zVw;t35N8h|{5@*(cp}GG#9f6WkNh14eNLe5&TqnLR zWkzsHVJ>%?07D6rDl<{hkX!&$=V_1d@H}EmVit(Qq#lGvdO5?*2ZiN2?%J_p^kr8IC+b-R_39A{cH(A7y11{Ve!*jP zNh*TaK*G7xHj^XXd=qlyA#K(d2`ENge)`3^24XCFds!p7m7n4EP>0b6j%yKuIyxUK zOKqYfyl<9OBhzclfasD#nO*Q19?Tl=3a4*@V2>?K%oC&?)4n`Ji5MmvHh-o$Xry%9}HqVm$GDQgJVot(>LA>r?mOG)^Pc z^%Bi#+cBfZ;Z6n(jRoQRQxP1k#(VUsS6x|)#o4vW(qgVHOxUkhU$G^>QV7;*u9_xy z=@K1$g9G#;+L3s-j<`h!@|ba7^Ar+0C1LR^>>Zc|6pN&RUTe`p9JF#hLYe`RhnP$q zJ8+UUW$DsQLbNZqi?dv8om)fROMaH#KB4o9A6Q%9?tZ^GvoWIZEj&dg@Dj^XLi*za z2*3KkX$mw;YLk#QKB-Z&MWoh|25WZWoCJ8 zsM0^n7Z>9r`}7Z-7Q)zTiFe0Ag3olg=W%v5$9ri?2dP)O5ouF6m!%J9mQOK zc(d8NsT@cj*u>NkZhVy2_{9E+bM#XQk>;L%Qy*aqRnMxLCT}wWhOtJp)2G4?uSM7; zGV*}&2NA8Z>~3-0&&_K?c=huhFBdWinq9D0ZVsHjCp1uIrY(MQ?knX>^YTNth?PgO z%#m}n#EI1o3`_X+0qYJc>2zy{vnn`xbMJ>LJ@IhA$rfzI{^TXULA>#-*Vz7X6 zjw<8OpQD$i;p(PlW@EBa@yAYvB`ASh8|hSRu6DTgReHOKXo@8D%7kt0tR#p~w6t}E^BIim5FJmZ z+FU**q8dC*5;K8*gT5%$4wJfwaG0yj=wmtiaTF2iy);MpagbV#lJe^TnyF`K3g4*K zF0@PMeweW^(JD724JCY)&cf(gt(p&Z_vYJ$B7AgyuYf0Tr>Sd}$6>j~>irW|`~0jx zq_b3Ut-q?6Fi6f2BNdwcWzQ`_>CZv6Td`>nF`}Qmnch`rDNr=?)>^?K0cr4}P_Q&tp z(g-wKs0;}%@DwDAUBq9sN~^Gb%T-3S(Nu0L>oKU;RL4&k@81e|3@xa$9m?%eZDe&L zuov{m=o#!IF=#{kNv%Xpxnv&EB7Ae?%mucsI=qqi$#SOHC<3H)MttgzkKR`=7XFBC zMPSzwxT5QwBt#gyihr_fZ9$T7X@)>T7mq_41DjK<&fNRLM}U5_ZIAl1`(WQkZ^A~3 zae1f_IGQV+w|>#FPMjVrEh6%!mEk=dTs_Om(sgJo#zjYnKhh==8*y!f6mA5!WERiq zBHXJBs4L%-uf5pimmYW)+rkiACK+FCz##CD0r9+oa4X{xj!v(?qkkyJQs?EM-PqhE z`Y1Ee+xk<63`NSk@lrgyY>|kDYW4|@cQk?WX>0|IUH0~0G>H?694((()W9!@@0b!C zrh8i(&#W6#yQ(&{x43n1G_n*&nRiK$6%yz)+6P2u+zdfEX38qN)X`ruu-G^59Vkzy ze4p~%eM)=)rIE=TGJ?@kmII|ThwH#$689LbEOI8uLNw$?N%`BcOcFn&usRJ?y1rOk zD?{}A#khF8DJ0~tnsd9}zWPmaH7Dt7C|D&Q6W#swTe<>{T^V{!vkSYVw7r2hJQ%Md zEo#F1?+QzF+Vw%K5aKCrP&j>3smm9ZV@vDT@S$}49wNu14qFO4K!6vHDX+`WRpmiE zrYhl5`P^ksnlmUi(@i`*|J8cVeA%(mccf#qkv4+1QR-=2Ri>afjPQExhH1v6JARGr zU0nL?g=kF8;~s}gzK5uoyKTz;>t*?rPhLxZnP%%VRSHY}P$?!rEYggaM`0-7i(rzN3NZwrRJRte0jiWD!!N9 ztshVxD=OGd&w9>pIm@0nSBrEM@nJnnsY14-~DGzD44qU(VJ{Oe4F z<&SVA91)5UVaaQ0yO9-A12isXvQl+$JULLC7w5H9{%w=NTuKm6)do$oY8dK>aSACB zq?>XUbEZk7dXIuX7E*UnJ%h66lX0FB4HHL-Sf31NqaLsZ0T1^cfH9&E}76=mmpCm<#ccW^B38|z9VT(@kL()n zTd=jMz4zX{-}`t@?46BgOzcj8(xF2@)w-bu2)l9-AAnMmWnHz%>`stbD zd7olI>TTe)*_KuYwkZ-S1d~3C3N{;=tAa{*+m_a4UW9&prMZ1vEfq(OHL!^i4XMFX zQc8c+F}8&@#Rr>f8@s+^-O1(9pWhUUi7)ICr*vhafE(?xU-MMGINg|RTzwF^A^$Nx zG^OdNL90mo_9%lzc<3uBj+)cM{YOvu6`9JcJ+i-kkSXZy+vwFc8B@tvd;XGnf1Stc zhiUdVd@p4D@Wj;d2PLGtKgzIY&Zn5%gr=-uNvYm%V7JvO1`?XGzs+g;)M^l) zvftQ)$SQTLj<~Yg_ObyHv06k;9i7ogR`0TyDnnV~kX9(xL8Af|ia3i&PXe}tf#KoM z4VrG7H-YDcn5D!gdyciaue(ul=00GpKPhw2|441Fl#&RE`{Ss2a1J#$Xgw!Y3pY}V zLxWnx#2o&Ur0DSEtPcJFtwx8@-rIsV;TERTOHrsMs9R1P(~hG^eVDWXt(r8&nP`x% zzD!uIA`CMF{LgTzbA6pd(%EVwsi&}%UiRVFyw$*@v4;riX0e0$Oiq$X*bnqEbOfZ#c|v9kkifkIf@xSAUS z>75ID9Rean9RheYCGhi)>z@En{0A2Lhva{jg97TLbaphb0+`y)RzK?m-V6L6*Kcb; zy?g{>)&!F09xY4on! zl*Ye!gvO30pbU6{d}J3#YtmnNZg?kWLu(*k>g4Qn+aaJ#nt`hk8<2w6U7J4(pizNl zO95Gs!0UgI_*H!8H|`DaPC5tVrP?*(t`K75P)Bh z3+|l}m5>lH=DX2DfD)>`ffM*LWv~*ENS&O2#u~^%0R0OS_cQs26O=$xz`g)4Sb#vC z3m`cH{^g^;s8#I zzw_ho`tWys{522$u8+Us@V{k!1kVG%*Q3Av@V~Ji{tM>>;HdX=(fqq^{OYH_+k2Szvrf3^Wg9L z@GA~~*N0zm0Dk{nAO9Qo<$r5_{rx=t_wNS3=i|RMj{Xbx6aL!&weJ1h2Y$r?9Cm-t z$^SSf|M~gq@BO#`568#feemx-_pzs3Q&KEU(*%>xn`pqw!X$VdZ(eTT|{JpMm0B>0RQ-W@y!pS?AP@N(z@&G| zEbrt&zas&|096G`Z@su?TG*>!LR(!dJg^>LoxxF6rful?zR=I?;AjO^dZRs zOn67W6vz_+blXNS9#nU*9gx4H|5Nt1F3^7EAAC9h-{k`j_5Bkr05DkBt<2p#Xs-$& z&_6H__6r!_yY;&P81xt9gEs!qhtvhi?&^b&@7>k~>ii)OvGUJlkl@4v^>4?-AM%ip z0Pk*$|7h<|{X2ZfRY0BspxgF<@^|}R0Km6(fihrQ@A|6*V9*DU2a*p!pgb^Ee_~P~ zy(UJ*noTj;JfktqrLw_ye@v*`&|d5{~!8)j_27w0Rl1DAE1mWKx6>@ZW{!!Hs6g6 z1j8Q~^zBZ2e%b`}L0g~=&O3at4siVe>9)Q<_5Z}Wfb3m={^b8FO!`~@)}MbR|F8Ie z{rTtq{xe>BK)iu|*YyL^+w~2U0pkyjh1+ojV!1ysI0wM>`L?fkf&A^f2g@G+fkC@> z`F~=tufYA}w$4BKAim{+_W#7Bzsqj@`IG-Yi$QfFu$XZ8Qd|3A&2|2zL~WBMom zU*X&M{4d5k0z40Zdm^Y0tly8p^PLzFa&V2q0=A-jAO(E@^58hb0>>J-w)`G*G{tu? zaP~rJ128>6;64DXso3E8lMf(bfB+o~&<;01V7&m{s|He_zMp#@U>6#E?jGcU`rtTq z2k3WQKYaxE#@kr^SNi|Y_<^?m9sNJ-p@4pZdpzh1xPQ0;1g`Di90GaZ`4!v;!8}N& z5Rev%Kq?Q=?S2C4{$2xq+5zz_KzIEd`vYtJfgAq7V87hahr|Hz-FXl0jd%Dz_u~I2 z47TYm|KG*ne*52P@89+3|80HntONEx*tbBxqw@gg4zNy{Ulm7kYWFfAx8fb ze0MDC1AK67g7!fI>$_v`=a{^Ug8}~ScmT`)7}pSsf0X^fhrB&sYyonl00DJEA_D1c zIq1UzK(~GXZH5Hv1LyXwAKZ8HpghRG<$)MHciq{GpxS@qTUi|dgE0l?5m@#Jpu75i z`22I-xyz@AfK(a!t#@k!v;&?e@5n(S|1b`24JknXEB0>vxoywCs{c{_76}#Q$V`)Qo_* z-L6GKz`x7__h3vXXCpfx1usZ|fX`SEhAzg=20*H5WAZZvvJhl Date: Tue, 6 Sep 2022 07:05:11 +0200 Subject: [PATCH 34/41] Adding textual description to link. --- examples/Braccio_Record_and_Replay/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/Braccio_Record_and_Replay/README.md b/examples/Braccio_Record_and_Replay/README.md index 6674031..d44ce70 100644 --- a/examples/Braccio_Record_and_Replay/README.md +++ b/examples/Braccio_Record_and_Replay/README.md @@ -9,4 +9,4 @@ minicom -D /dev/ttyACM0 -C angle_log.csv * Retrieve the recorded angles by sending `r` (Press `r`). You'll see the output on your console which will automagically be stored in the CSV file. * Close `minicom` with `Ctrl + A, Q`. -![](retrieve-angles.mp4) +![Video recording of command sequence](retrieve-angles.mp4) From 283c03c47696cfb0dd808400b375452290884705 Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Tue, 6 Sep 2022 15:17:37 +0200 Subject: [PATCH 35/41] Remove video recording on how to retrieve samples. (#94) --- examples/Braccio_Record_and_Replay/README.md | 1 - .../retrieve-angles.mp4 | Bin 465794 -> 0 bytes 2 files changed, 1 deletion(-) delete mode 100644 examples/Braccio_Record_and_Replay/retrieve-angles.mp4 diff --git a/examples/Braccio_Record_and_Replay/README.md b/examples/Braccio_Record_and_Replay/README.md index d44ce70..9010372 100644 --- a/examples/Braccio_Record_and_Replay/README.md +++ b/examples/Braccio_Record_and_Replay/README.md @@ -9,4 +9,3 @@ minicom -D /dev/ttyACM0 -C angle_log.csv * Retrieve the recorded angles by sending `r` (Press `r`). You'll see the output on your console which will automagically be stored in the CSV file. * Close `minicom` with `Ctrl + A, Q`. -![Video recording of command sequence](retrieve-angles.mp4) diff --git a/examples/Braccio_Record_and_Replay/retrieve-angles.mp4 b/examples/Braccio_Record_and_Replay/retrieve-angles.mp4 deleted file mode 100644 index 21807891559583b6e06fcf4a970c05bcbfe7ce10..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 465794 zcma&Mb980R*DV|;9ox2Tqhs5)Pi)&($4STR*tTukNypBY=ZEjTcf9}HG0v{NYOYzU z)~Z?ijD5~1ARr(@GiMKgrIWoa5D*B^Klks8+0fOP$rixM1Ox;GW#(vV3IwrhU~6LN z{LLwc0RQ?b-Vic4ua1C8Q%Xws$loWMX3@bY$jY;vi%+ycWEDik=~xMc)I`3SCZ@*U4iS5RhmEP3Ga)l0BMTifBhx=@3uk8lHv@y4 zn;X5WrHQG%jiDXAy`wq9KeNzVINREMbL;`mmiBf|+=Rx4Mux_GOoWc6X5X!esgaGn zu{9qPHzPMAp`o3jjfaydAEP@9_xD9;YszP0X-MegV)Sh>5dxe%{@v<3n(#5vGJX&F zZU}8H-AzsO|B3f)o9a6n+L?c|*$Is;9PMol_5U^0+0oR-#?tAV!RgLvV(k1K$JoL4 zyK7={vP(%iz?=-X!xFtyV+w+DQC{|)|Al(nhHcWgdpHpc&$`nHyK z-(5l{V^cd*V;5&WR>ptQbTs^DNgYj{EWU?38uJ-Dni1L>eXrxUJcQpJK4unLMnZ>w zlILTjW&bt-{{;Hi-O!zno$DKLayA9^DaCQgGaza1N8ZSQ3I5KRYJhj;nvs-^+Da~h{NJ9P+LSLzWl^n z@}

hXbdN7Hkaa@8YHqg}3puwuR7YPvS!{I*p0t{Y$2z16|CGYF}_EP^KpTf z?`8mOr?Lhc8!1C>syIDEg8PRikeDA2IWo>2T&x*DybiZR3EmEt;ios}%ab8;LLg#V zollRNK8Wi>U4&{%jY29=_#!1_R+9rPWT=;uK33d&^>jzN!oD`#)+}Uh$SH%>k8Tl` zNeLm8m?;-6Y&1&LM|izXhXNVfWV^tA`1h%^(=U zMjjJ1y5rE_4U;O0zb``Z;`pkZTxf1CLQRt6HtgqQE<&yQ%A28VvwCAzcinik@1MY6 zr4UL;Whed^YAJhr1vj~J$nnl3Y&M*uz{~(xKMP}uuk6fvh_c;;93l|W9)GlM$G#Z^ z;wYRWRLhX@@!xJaOVDE3a&@;dX#{vl^o&SSH`5P^&OaALt;Ey2$5K2@+1C{6&=s+% zF~R>j`V^=}Gp*;3o0+*`$i>)yA<;L55iKqen>*lpCQN9llIL?fNUaT|@B9^=XuMG* zeuso@NVfu@Ze4P3Q)gz+T@B|H#t~fo<~XOc{!Ma@Zd4W;1RW*gKW-FtMbmqcj%v2U z()4EvO>2%`@*^nsOYvS}`B;E#hU1vw?GPmbqC-e9ZC;d9A20waI3@U66SAcuq!e9| zLZ_h6ZNaK;`P@~BAt&4Z!z`#p2+BpkCN{auV8}@ZAKbwg|8{iM<>lO2Ouns2^I;uq z*m!5B%mkqvrDV%m$TSG#+M-Jxa5F)4mUyU;_mU7+BCK{69gSXR7821~M#9MQ2gspC z8pA32g@4yNU9%))kRiuA+(8SOqlD27=8|CfcE%_ zSaURSvx)v+2UZzK#oK$OjbraAs@}mhhss9QczI1b^yNQ;PDQiK&IvYz$RbR!JY&Q2 zbyD+_%g`5uk5^xNlbgU6R~<8$T};^rM>ATyd^_1p_dUuR$N3-lAnnr&kM%D?O!b*qADqwjg))6 zAYA{HL=?%uRXHR@@xnAagp`yg6>@Vdfy28hJKyb*=6&?Z&XVODHw=FzcN7^}8oB)f zmdLqvU!T<>+>KUCMrbi}D8N%2Ok6N^lmz+vOr|OYu-QMBel83rXSwVv-R!FguitOp zs~_{Hv@V##7p6!zi|m^3K{IL>XIij@a|@f~*B3IW=HGYIB#zn6e5TT*{IyfX=}SXU z+RV_Vsp6bcc>ZPbCw-Cs105F06C<1%LOr+U$dAyRz9;n6bVN(EXDsgO1?luhz<3JR z+1VW7XmGQR9e)%E#>#4}n$9&KTZC3-tb0dh*E1MNNvneH7kHp}>54^jW>Pq;lTfmL zinOp-^68*T34%*D?z)^S5$K(#^BL!km`Dc+0{TW@u*m4)Ab2iFsTFxxhwPx!Sw1cBuQ^iQogQ|Ugqg?Jbr5KU!(hdbT0Ynu!zRW~5tz$tu=+m5WbLwVySnx6QJ6pKPtOQ)aDI}9>5~%ytY1-1eze^)BZ7P|)IPbi0Z=K4_ z=v;mGpNg>e#gR^UiL4DE#Yp&LHt59!WPToJDW1$iu-UwIv(&=@R5_dj1|5nu92|9p z-{MapS-pb<(vB~TijmF3bOf>HW&AmXI2YIi8hKCz)3z<^C!ocnh(bmZRg<-}4@>zD z7zAID?X_GEBk-#{;{%cpmPXFc)iAEM7g$u#q^JQHdi(GO=!Lg}CY6snCVwBo(rs47 z*Fa2kCNs(f$SY4mFCr}Q^(l5uP3;rWkNvypCO*&!mqW8Fr0x~k<{d&|SM{N_(E)9R zI=4UDLf=Am561u*)^}D;hN>DkZdGdRL~aB7|3+wk7r z>;~=C8I}RprTCkaX2plh)!a%@!y`C!f1;>hMXw<5F7}-CjQq)?K?;SH5U)v9s9A0p z<*o8Al2o&Cwq0HH39+D)z$T#`3L&ImoMK^{BUl=g7dvGfY@SA5Oy_wOJv06beXxO` zyZ9Q)<+jb*!}wOI*%#-jy1Qy^{kK2v9(&i(;TLMae!dq1UK+#d!4{%%eWGcmQDA6n>e)_G{N6^T))b{Xdoy>zQ9;eyU2f(e+-{gh)rS=YD-kL(oNuS zGRy#4HEI`}(e0_Z2a5uzV`d5{jIiknx!3|RLkPt4>yI&F5zjLQxJ^+=3J7IeGNpHVf8lyY$ zh*+yCG2LkGN$T~xuMD37U{4F4P8%1H+BVf`9pa7RIqe(k!gL zBn{+hEc2L9)v-nxULZ>B0Q|V@qHA?L?=2mH10+Pk-5KS6bYi8Wmv*!`TO%RmI-o6$ zOlqoz*jXjESB4|988k)@YwWh__qgCDQ;yD5pz6!oDW56^#^cbEu_;`{)4?j ze&B?9jqe?den-Hogy zSY1oH@e#yNnc z31%}Ds%+Lyo>U^G^!U3?Z~a2ypgGMVe+3sfnptL>p~ZZprWUd^ud4W|#$oNW)u*xj z!NIB}k@ZY9J0gc1gIc7INbV?ZPB{7d z&}8*v7v<{G4X>o46Io~6#8x(FcpTDL1RS9d>qx8zpMh1EIj>dq+UuA$5v!YmnjN3C z!lOfA9p$eyc#4^jE?sWOy2Y@d|KO!qgv%>1K3(-_N9vi0;e?S&;V(Yy^yRi0as=>m zuhVj8R6C?3!`~B5hS(CsT@fz_LBjZCOJk(&ccpjyrcq3rJSg>8Peb7kezMAmKoF*R z99W`Ovji-ReP)YCbx3<`)99D7MN!N7zsQ4`U0hMKEQ+Qg4jR-Yetc9MVHiIjGDf_w zXu28s)a}`bn-LV(#xhDGv};i^vyT)*jhR8uzgs(yibT!$?ax&@-DvG8B&ay+a}tp3 z4)P$sjy*?7V+aH-D@B9qgLP^ftA3o5TU`*pd@*)RDzz+ctv0R?3?7FNXLf5>Tv+ArWM?HA+9e*H1fI>2uRi1MgVW1=dPclB2A&c z^RIN5+VmO^$AUi8}BLxOg6>>?~`87j*`(>++~<8N1szL?kfuCREYM z6t~pRg=J?_>vDk=@4$$F?o1`sfP~@BfBw-MuI+lK@uM(Nk>1>u5qHJ}S0cwI{8>iY z%p$HkQN3EDEw$@@Y9Gq+@K&Y$bq4x*9zYYo1NV_E0s zP+z=dH5`|+hKsihVsEoBgEhNUNH(k)66ww5-a}Q&A%>Jot*O4 zYqeOKY}^fHYf8r}pfB`FvKGfH$@!Fbq}&auO@K{q-R1cD$7kL>8`v8`6W0^gcQ0PS z&RL`0r-Q-c^*IV=mz3dslVvn9HDY?E1MtBH%HitPl%SVZ&r-aUHoX!rAETj(sK*LbB=G9)hE;|}9C~axNijyT z$$UnsZI*X(Bsp$mmsElHs2)*nqDkRQ?@^O6$PCGH^S#(iZV+8z#ZI&4WqUHOo`qR%dvwvq7m%zna6@MzTMs1-8D-bO)H+nsT%F$yob?Je zhh?Ur*gW1DFR(sHK#XaKDOC*yQ2EqNj5mgnPMhXId|Hgx-RGehb%qDTOL5i~&G^`Y zhV}Q`OejM!AF{ect$*nMP-!J4tuy5l1lP|+r3_8Ts*T>TKk(EBCVEjtjY z9G@$TWugGew^4fsJ?3y#O)vfR^;I&&rHfeXgkH~|Zn<|=V#pQyLDp3v>_RG-@VA5L z<-qTPLT5{UaPt~AkZ`pUYd~9c8dG7@&I$`UEG07QXx*J~34t_YdT;6{Lj?A?$iyt|fs|6A5&}2G+Vc&s zak1@HE(A{L%vv17@PMQ<&^p6EWD(hB^F=|{Y4u3P%l9|-(}+2{vhii^Pg}URYPECI z5hNTZ$CAUdal)Rt^R4X72zF@!`IvuFz`t^aU4O2K3+CrnT{PSWhn_c*Buwf1B6NIy z0y;n}G$%nq5VFaL^qfrebg&^~^+Y4{+$wG_?c7m1O&zD}VfPyW@-{2+7qCjM2gPBy7ae9e8GnDtvUF3zC4SyQyc32>U;B$%Hh)YI zosc{A(4K6v-!Pz&LJHT~81BvfiLnnAfx$ykwP~VjLQNi{3PP+d6y=xw3CDF9^=FMP zNPKMlP&$Jv^+rUzE!^XIYFk5B)*BCsTLHZ9GOt4XlEcl6_KRx=$~R>PEM7>3f>}Mn z`ZtCKBKd3Nm{MQhd2!g7!nq#qIx~=TpqF}c&ydKgxOiwUY`#xfQx#^hqhSg%{LKw0 zhBOr7gC?LBycn-3nIlY$Iw%dneFA~hiX@vZByncW zw7;MbvF-gKKtCLW#JY!1|AcdG;Uj`=Tn?L`H%7c(f_ti-oVSzv>lx~I{MMgW|JoMH zNQ(Z->9Me36&5G>28#MpL*h&v3z3=QEf!94cBoQo$Tw6oy9s_hRA> z4|xkU`l=s~7=c<&Ti)vPopLVwZG1~s=w;b+k!~#Zc!`LDh@>cIQG@Gr58>L zv^q5+glER2%Szei;53@Sf+fQ?C^u70n3&H!givupR#zYqCSHv zao<{h8exTN)duCN?F?0z#gAdbks zokuW-^~=T$wPQAQ62`{$;>k^QBPaEKtn=LbD=+E-4`dCPC<5=JYM}n86&Kkx+yJ=X z^m>w$U^0qxX2^fzEZ~mEC#2>!orO)IR&m8(a%b56D#TB3`n6ii5L(rE`;j)@tRkr? z=!5mPV)bZke;{oD9B4bshjS&jm#{f|@L}PXpfTd)WuH`}q4KQP+}&@DmW?q#*fNAi zhqh@epT;7M&SVwYY>07dq5U^#1a@KWdwpb&=%`?zLjV1Z8bTO3%{IH!`tOp{5#8x6 zLtn1^*<~1{vXnZ!A0HTy)R&Oa(*8_8%B!PJ2ywA7l5>r<;Un6RxI3^d0$*0@!g>bI z+QZ&)_(~MPgRci)6`na%aNl)dCPYk#On{0W4plhYUZj_1*Iolc>4sgEdHF`4br`Bn z=k1^Bekl@eq&5n_H+`k*TmE?2$av6pN zw_&Ee{Q#ngq+y2ow;!mNAXy@7*X2T)Mt^z&z&M_x+i1PE%gUX}=tw(=hHbrmZ`W>o z{RP0G`zrC;yPZE!)Qh2#ptYuHzBD%C6k@uCc-Utz0aVgLj}Z+dpW8xXE||&f=CN6e zhCga+TI4;&4-4qKwy7)Ss)pJ)fd5ceN#uiYRk`(KPb6y;ZyRV+5B(LN<4RFPkVIJV zGs6V2xXmL~=IbaOuK^kcF(qhrQz#o#OA$g96>pOEJalOp=6_Wk2SE_%_K%X+2y7@Cg2aSz+CH8a zY^KMQ*ov+Gx{^9Zrz|&sN|L>;qf|3Ne#V<1+!ZT#v!&hGjqT~t(~v!5giq^zzCIyt zZ`Ox0Wjgk+sVnbBK`>hvmw38;kN;D{H_Cxf#Hw!CH@w5O`{KT#+-NLtJt8;sY&={E zc)hhG1K&`55EpqundS^P3rLG^3V|9G8o4`hs$vNEjQkef^{nq7u zb>TsFQf6kE={b{332}ECzBxhF9;fO6Y7G?+b-lN)p}^DEB~OYe_yBA>Dg1 zKuf7F=AxS(|5mD5+KAHV)X2HI?LkG=<8f+0Ybf&i8~F{ z^r0H+DX3`KxS|_8=n|H-hn?-U&#PH>y*Spx?BDbI%t?jih#dr*<}St}9Vp?4kpSQ^ z+-C9-_VRUX!mR#9uDe_t*INtcK)KZC{~h+Mx8ItI7Bb5NT>Bzqm^qWCcEfuF!=wf4 zt#GkR9zas}QjP%GU=2?dJRU|p!tT;d8{Jd+dqv5Zi@mf-+tesc&kNNGm<74?ZJGelB- zDp891g%pkVrym`W?<=nIV)DS)no=h|M1u>m^9GBqVL%KFPQQH0-0lc@Qa65OtXBcW zIq=9KG6-h;IaaAU;@^EOup!_vAsDg|qDX4H0*PrXC^yStMbiYOe>&8~J7^z9CeDSBVepT{86PBM5et~!g8bbierL+I z%YLgh&;gX(R-vvBb2F|LBPm)En;^jpru?YSC+7J1nA?2@oiJZOh*kw^^_w65`AX3Q z|6rtqpga@bSkj9OL|+J4uQ|{fu^2Xy3a!~8zY+gKP$)hp9&%Z850GPURx!YC9bl-( z!i_qHDYCRtI+o6jiO`AV0xVR$iENYi2e2?>tz+2ZUF`)sK0k zt{0|GQ|UKVqb;ZN$g(T{Qro={;ilNlI`=@MlFU2QB7Qx$Uk7zGpjb@AVb+U@QUXhow^6QJYw%1+%@v)X`JnL=246;8y#g zi};zKT)l`tsyrYQEY_d0Y4pU8$pl;2=1(pHV3M=qX_)%K!vZZys5}vPw@jzDUP@fS z(qzi;v(%@M`NpAu5rv8+`OF+x37b;2u!yZP$Pn< z%rxRu$^Z)@k+SvCJozcNy1TLdjbK;N` z{96$YgOG=a;=}apvP0Q^aHk@?&0mTBv7nYJ0Tg= z?vxhW4Rl&+soR?SaPJ1%g;#i+-Zw^IhiUBtcfqCYO0Rz2bmQ3806vifXe5~|*9ZL2 zzrY_9>&M%60e1si1S-*_Cm#`z72Yn7x6cRA;vfE|89JDXdnR5#mLHE_%Bnfn&UJ`x z{TysrP5OzsHc+44GlfL=*a!nNUnJi7c6W{N-8r8pKqY0}VT@vNglp4L!PSZ-CmmN< zr07kwg|6Lacvgyf3v?x)7VM2Mmu(9krj+^?+jlLR+jI3vFA%4!$m!+Y$hiSgVRSCA zL*+IVk|rxxz{+35G$#2tB=0k#eXSa|)TsHJp@EG9wwW@~sYrWoJxL<0KwuX(0NBSd z($U|!rIVcvV-PgSKt#TqM>k6oY#1uM(*QG_q}js0JMq6pGE52`?YFsoLyCA}SZZ5J zf(RV)Z{j9;VTog`z^sUmd2CgkzL>rplaNz}A)HAzdDuDzKtf=CNGFT_NZP^HItbp9Go12o1`; zpqdnu5nCx`O+@Xvu0DS=JKgWk-;<^0T93}#k8Y!XB$%jmd-+~3Ga=GDBlhq(5jKpp z7SipaAcUcwQR|$|A3xFm;fN|-m>XA>H!WhVoIkrAKv(@d1=%M314>PSu$7xKC{x7W zV$Z=6w^%SpO?fxDN>yK(yg_Ti7SN7NPOIt_(z+=Z0oej?@*_C`XC3irH;NY=>CV#M^s+jTCt`afccgVD?bP*EqVEOqgy=K z)x>-t(hANRCd;WqXx*Jm>E45^SGN@!;yC-C+VeZV$q!bT{m6zS{!yFw6Rbya zME0SGii>kO;+U=T&)~ZC^-CkHb<#k6U8$#1nuCfj6W>ILPIT$M$Iduj@Lr_*Ua4h> zfKm)fX=gY0=+w!CMJh^8vr-x#?ah|5jhD0A`vlDePj{nbS7~ml46f92bYX#HO;&&LmLfM1pz#dE1?M_J+PJ>C^N{a8GeKFve~bay{;x0<+#mZ)?MZyDq#0o3bGx z&$gK!)-cATOX@Noa2Rg}qy?`!_n&SGc2P#xivG=_E%>iUM(4XTAn9C3gwx4ez#Asa@z!D&G~en{#cAM$`>cSC>khcs%^h|3 z$*eri<9-$bON*BT>x^I+gOCNJ#)$lWCT^iW1%xGs!sM;6wNuQx2In|IL(g2xF-ba= z2kiA1hzuqE-Pmn@JK@z&sACoqW2>q0t=-AVYi@gyo&c*OQ=)Y*7uRH#s4pXS{_xxV zFd&7ae1LO7?9`NF_)|G0@L@NZ1acvk(}{n)+0xKa|1yiC!B6^Ix1ifGvQH4VtE={4 z3?;vULixO;7^2O4ZQ%$y4ibDf@N@LJt&mg6ZWjsjvpJ+#KG=0;Wl7_%hXv+vsZp}7 zu>%Z>eFW*`RBo-KI!VR)Zpmt^rq9hAd$Yg}cwUL3XwDbhpa|}nz^=WMF93V`xN-X^ zjuS?oik0?qvGFQ*0k=S<>xPs?zxijm>VR8TklQF^wg3q)+Q+b-1SkP&if9mWP+C$v zT5Hm^8as=tA9taVm#-=SNNCR)B$pdS_zLXekujuMKRkL=R50tPL03|6{9~qocu0Sd z;Nr(|C=xKX45THca0gmxWX6}~#Pa*8-?j)_UaHry&x2+d&`3#yT)^BR*+>ue^Fh{R zGGlpiZ=$|1vDAPD9j2T0I$!XkQ6;=^0b9lN-AG1Jsx&aH#={gO$5~w28%KFbE1QuJ zs`9BUG%PzJm{IrYPsg7Hz}c|m_R8t_7o%rXZI7t|L_edJT&GQiw#krnfK@8D@#s&f zb5M#!f893lXs4vJDgHSIDN%aM1gb0E0XLfmxAy+JWoHW#pyEigMsC0>yy7gS3^srM zK@Y>gHO>Be-Y>oD$n3?pV7d^f0UG4$4J*iEBCJmR2rbckJ=74;Cg;{U!U($2`Rc$@ zZ3jXD{N-+S{O%?afF%m03*u|x%0d`fkcVex)7bp zCx^`}{>W%o+|d=0Aif)hKxt^rQ-BBPD=+#o&)JAB6q1SHEWBF|V#w$Sl|Kp!7fy-8 zGSyATuT-OCpD6&+hT*6UmYRZ&i1p2vV0@fYdUSs#g0)12o`QYfi=MHEs^VQtRyfQN zw#ke{1L>fM{FK&>_$>z41l|3D5)x_Lax2B?X^;h?@u;QEUF*+J zo;kUC^dW^KXP6l^Z~&xcdO|p_?|}3)t*9p4&KvwvTPzF@h76*!N7bZ@-4tA5oYPNF zkdGxGsNvOU(jSViYsLh{Vsj&TRJf78fWhiybYf66l5EK~@ z^>h}Y$}|-KQX94hIwYLx)Nu_y7bd;auxfUifj2@>xV8Q2fd~B~g|VX+PS;cUjy-D) z4s{CxGDGGooOSa<6QDNTOE&0%s2ncWDlCd_H%6f9InxP#Eh)(s(GegZP>@7WZ|ECp zpgPb}B!E$1);IM3{DB4)>FF|@(U@T%uf@lH`972^D)fsKvj&J~U;!i2f6$;98HO-l z+`rtDB(>JHFF`ba$K>iJ*QhV#jV9&j@z)99&WM&M8j)J0+dPi)ztciKe+NPq$`KZ} z|1b2Nl1=YFC~%J9PjRdPhwme#|4I{d?%$~KPx1eQ>nZe&mI?i`V3qL$d8eBRatt0Y zu*h2|B7GXviTy;3X-iiW)#GmZ>=XVa3PfHKgdSLds5ySjFVFLL;V&e%IEI|0#ijxA z*p2#g*K5<%&03w6SRD;~O9I_G?;2z7jDUrcf}4qt>-x~;57?chXxVrfR%6x2A&FdS z+Ci{wp?VX}*{v_FsWAbF@MC8uJmYFwn4G+r){vVJtM8xTmeABx!Gixu81|oaLl?>k z6-A=W1xDI^B`y7r2Qud0#TEVB{y&QQ??ROP-)IjI5U{z>uS!-K{iWKK&KMYiw;8C& z{prXoJ4p$c@zhgvl)A@G_VmM05?c!(C)85azcb6B%Jg_*vNiMJ%cZho9lzH0v{{C3 z8y$?!a^)qr!;G_?%v3bFnnq?>p7G;9X_a z;HYZfuiFoqE!Tc>GQd~-Oi>!RBf)m%$HuuDik&)qK&pu0lm`dBopm{+do zTwAJ}b`fX=)!B;L5tyCtnIe%J{8xiA|8H5)gmT72(dhhulI+-${^J3r_;!46(bJ!~ z|K)yfQiGmjLz7LKnHgrd|A(bfA=ZG3=~(0h85v#Y2iH4tmXa5Ay8-TUQRDd>p-p4wmv!h~7c) zQ+IK{3&gr+_69Xlz16tyM5Up(KcU%f26tHszW~o^d{k1?5YL`)3;mg^&7hX{GIF~T zTz1u!3YsTR4sE#94q6lNYHKe_lzB+z;%4caPC?FuBYXDe#x^@V<7*L5h~z+8LiZ=E zpq1GIN#ylht^m%w0=KXb4l!5bYpZ&osYK;#QDOX>%WWI81kSAs_T*;0GYTuNKEs0P zZ&}IWwR58wyhCA;a$BZ4>>o&^Xo3lrfq6^F>%Rnl9|_1fY-9da5e_DDNBJFfUEuc% ze*F)0fktOX7m&6k^mZANqEkpppEi5+Gq^J*aqY_I93#_p!*OuDYCMK4*!osbghZ)Jiq<8^rEv;86Hi8|Is-m z;9F)qpVU_)EuYn*gc{CzM0c#aU^LY)|PePwxU14{2h(>O0) ziEPaa-HKcPe`bb}_$N)FT%~{N_#YTZ=-=PJxeot3O=RF)r~idgwh3jrv&yK~GgV`3 z_>=;ZZKU%6Lh9ISq(kwu4)>o?!@j=NtFAf1`7wluN#Sa!_Z75BpBrRme0b1Sfz8hu61aC~1VV~e881R&7p--o^m-*o zQ779<0C7lj#>`K#ViTZ9H) zXmUvab|!M^#Muy-bSHj%U0^k2RLN!SI_oG4VJkeS#c-9%jI#^T$1d;C&+ z|C=?;@wh@bZ0Eg;9Lt~dBv~%?CP{2wCpL%K$=;9Htx0e*ah6fwum>DTX}d>*E`LCS zLXnxQD%uxQnMbl##?aP-Y7hJOa{;<%c@xaVBYj7>TJih@{*iX?1Z5j_6-`r2#)TX+ zD@pV1wz1Bb_8DWJ%GKP>hQyKRam5ip_C&CLp-833G9bWih{(}45adA2V|s%kjZR># z0uH3mD|WGWx2vA4(xL;l3Nw?dgcZrl3!x6)%y+sdNkw{ij_*ruie*4uQ51SBZtHi+ zVW(4yz2~3htqt&2KqN?7z)t~sqRvy71tD^@1RnD~-|5{ZdV7U;s zwy3HFv;%bM5ff(nvqpY-VC&;W}p>%#86yGCX)G=!XfGZ_auRd>H!v zbpqL&_2-|ZN~-CwY)}ge7!txnFQbd$h+RpB%~z(xh>EntO(z9F!M@KXRCywX0^~uIWGtAK{*xn4@PX zIri5Cfa~a-Lh4?@G+l*WW6R#BSO+p_Apx#gF;g>tA_mqjHZj*gQK;K#Ce_`mrG-Aa z|L$Mt1EMgM-X5yM>92-BNw`*Ws96cl4@-pFa5XxOW6>oFNq;75Z;OSMY#9@huSL+$ z_m>=`U7PX99PNb@7sPa+jUT+TkMlKk1amXS6u+y9K5Xq-Ev^txcq>c5Q=$rMI$);# z(t@J$4M36ztqPb$rf;#BzGdoQQ5qf(h3r7SawBJuXgj~7Zx1^~?qjiua83@BY~$gJ zgmV5>78p43psc@0R?RS^FxnAv18@TnJXoq zGs{6G%ZJ{uV^7QTt_6a)+}Oq}jqzMVSv`?=&?hUDPBh2?{d2Jsx*5HX4WW%bVLbTv z>z;@>7?@0ET%0cBO?rbwj-ok;ECrbUvTWY1A!stp$2C+i6^1FYH5-T|L6X&x+% zRrk=cQ!c4ufa@?`KfTeR)UPTTI_jW>g@i~w3UwpY1e&*sqHILZC_AN%tJb3W8Oh3P zkw3INmxS1Am{~-Q6x?y|l@~#uk!c5rP|L&lL53ZCgi~49@ML~%wcK`dIAjxL2g;mt z!?`#3LM4}gF9rXa(cqJ^&tx#c7`5}JBhu0>(2(DkeagE)tiN7$6X{D6oGMnT=UXJZNX0{4V?mSL z*s86h$-&}A!-_{HYCfqO{K`dIj05{c-ojl-98nf{I7bl*kn7x2z2JFO?gT-6QOHE| zl#GYu1fb!lcxTDHsa$5#dab2*G5v}sjgMDkl-pXPN)L_NPf+6@ERAMDK78jxICCjD zdm7D^yCj_}5f8ajm}chwY6L9lKRT19wauNAj4m_(6kP?`PnRwNQ!pXExfW4K#e z+xY#?NHIb-JGkt1+}b-cv9w9J9a1Cu`?n}!tTW#`4?UkSkETNnI!2*~}D!S8aCD!@)_WmN5H8H^j-#!m`6g1n1 zEDVq32Hm`S9&^}Cu95||`u!BhI(u0>sf;@CfjO#EaZOZY>`i2-GGKpD^t*kN_54;C zM`h7q+q21)!|y}sF{%d5apVM5#O*}`_z@m0@Zz_1i$(?p_0w4g6)TdXHepKwZSNQ5 zUogng@naJpF<1>vUXNL_)B^c)6dNcDBIx&ZfNG_zz=LX|P>n||Hp_DkC<^t{Yj%#B z&?6hB`qGgy88qr)nY}}*m2{sjH?{riFa6;2+`pi4PPm zi&*&g%=4MVQtteCl8@SobAZ|5(Z>je`*r7U?1iScP|Qx>Y)rhY)8w?SO?qJkQ;kyb9EcjdD1E{X-1((X1A_Ux!y;8d?LHu*!SY)!9O1qei2^S%LRY_$Y4GxO)T zhX*pgS9B59BA?&|`H}X*RFm_-x=$EudSqU=lq4ZjR&1Wi>4^bwX1aVif`z>C0#HYh zoN{zH!AW;3t6mr#y+L5BF3bteJJ1U%{+{5nk?;(f&}GmcuSqhePH~p;IrQ&tKiAvP z>{SKPHzqMx+!syGyhsj+h)L@5sPNB$Dory^X8odTHfs$ayVlguHMesYw7~huPX|O2 zVExvzCF^uv0ryDZW2KW{l$(;Id3kSeeayms1uKCfPo+^VJ`bKmBoX%9ri~Ck@`jdU zaPj#NuddR!trGJunLX$%DW$GBgYkAD9?YI{W@vMxJGVz0#G^EBGf=FmH2Jc-kbi7- z3n%l|@mqnCcQqK9z<=I>^?n{G(;vHW3zF@=?x(z-e<2&rsnto1lo~cG>s7kzswvvU z4cS5mA9bgGRV{9kuT;5L<{D@@5Ng$>F2WT8@+}YnwO>!Z4v>8Qm^ zt){;WCBWs!3q%)RLK&?UzZQ^x~>$g zL$_^4gN~E3A4=AqHnKmh+^o2xl^h!M)qRYHx9A!4gdihb2Y-BRi3t!@ok9wB!7gBr z@iiyXcj#7evevocD)zq4O{EhEQrR2MVjz|yb))~S zHrW@@=h7<>MF&~7!`7n`F|Kb-ApNmOjy?*X@rIH>aPTO9!xD;V#fe5$mgZ1MXaJSf zAm89z0D2bp^>qKr0@VEkJ8TwLoI4uilDY(+RTd%f@#z%*iNw|PN@)@rc6x9;>ixba*|h*-TAg6ol4?XjN4hSKvlc0?dK6oOV5SD`lp9Hlfv z@{eDE;}JGM*!zU4EC725_Eu^A{mLgd^{mEp%9@Q%jQ(P(I&Hr(F2Z`-+chC}r}?B| z?SA}eU@fvVX2NlMOtlr0C;y91eqNd=x1}hcJnr)Pg?5V!h%dI!8a*WnwzDx=5tOE^ z;O%D6EbfzSPj4anz6Q}c&k>QEX+=qt>p!-E%bctU&aNdIR3)C?R1Tz{v= zF8b_B2|f~`=GkkhveC)G>3mau|F5N_oEnYSWr4#aJ$<~FH=O$akCnF!$} z3GObz-QC>@5(pODEx5Z|aF-AWZoyrGYl6Ew_ahX={8k7Ii`)wV0I)dDE=ty;D~Xxe&hkd10184|lk9K4T1l z^6z-IN5UI$>T@V{8@^AOLn7v77M|4+d^u2YI)DpRZdMJKSCAV7oK5TDuY#%k@G=bx z+a?GK1kzQmGnMoVbYpXsV&@HYpQ#78NY@K90~T=X9Pw<U*J%(gj-wrq&eV5v;cGZatI+ zD0m%(4S{Oh*P-SL0h{2ti$VmCL!{--t(6V*V|t_>)K4d7u6!)8!HM8bG>+L zyFxn1?xb@v1*#K+RlKj(wbcQ|*0tF)a;55%+I|->NUy z-IRth-9Db+qsz*dfZdfD$~Ej^dWlWvRm+;Lk~ga*suglp=i_@AE`mBJ6my18m!frs z+G(1O3+X10GU4EU17{AQ)wq6k$+UcVZ2f69||t2iv-r1w$$G0I8%{ zS*B@wFkoP9w=kG|#cXaIMt4CQ)h#(v9-FK@tx~IgDrn4l!$5d-ve~2017IGP=g(A#1gIj4v$bejLNK8xcqnk}C z1FBbgo7hN1+hopS zT;4IZihFWFkE!7?;Vn{SFjyeY8RO~tEtiUPxlT>PTToo1F1`}Q5I%x-PTsF&WVB$P z{h5x<%bGsH<^h-cG;Wh?j!(X8=Ga5H%5(VikuL1vt*>sa9a%QoS|svAB5;^tIQB7KQ*P&IT63^r0lQGjMY}i4{3k;Ei~+3Pf`j-M*`2-~~~# z5tE5m@b^#7wG7pnNxDcla-s}Rr}{FrCVdct^d*tQy|-nG?q7*X*@D@PT`Iibdnn$M zIOuPMI718$N_-lAGFunQ6aF&p6N5GWt8lj9Lq4HUvhChQXmhD?hG8;^NauvWd9v5R zZyGtcr3*lbEwlnB6I=h%Eg~ZEy7x+Fq z0#4icBhd9myOpuWHrKS^kGJb#xCgsaC7qp>;$^4$DWOCHLgJ*N+R6~KdaAI?rRu4| zFsL~_oxc7)AaGtsFc}HZ!W>_b{RgR;J-$kSaHlt@cQ^dlB?pnDn+^EHVr#g7e2C+R z0X?sBpq#?)(l4O{p#HT&vm6<9$#O_UQ&YJXrrSqrqld7VM{hM5ve z6L1G^VJh<&nIvaElR+c@=Q0wkZw@62IX))G#Ou|l<%r+5x?0xj)tUq7vG8$=i7ODL z2)+0b6niQ#`pT2ExW4CDP@E33)~+H`fYha%D%cLbF_40Hh4uc3*YMR zEC%8VFcgw%5$_V_(ChMa^WkMNVhoRg|IFMkV`%haV=p1zeyb@3;7M44jX;7)&s=fqk4S)s~w8a z4rHgaBCv}zt<7H$06T_czs~C{1bcrz65+Q1CEu8-46Zk~YuTJe$0J-7iqrV+qlYO3 zDO3@qHgfq9ks|sgsKXP8t&EP)WKgeIdm6f-!5IHjuvh)n<#D`}MY5Vs`K_^i%kE@7 z8d(24K~8`pZou>{=WR>xFaaM?nM+%jDX3Mh#bs>gLsrm@W~}bX1*P=Jry(8WE*)mY z(AYe`M)JDR`lW%{Wta6ZKawQ^zU7oVLl9a5bsJIbf#D|)D0w#5J0@uFV7#PgFFH`u zP#Gyl!w-DN>z6=$b!zJ9KZx`0<=h&u{O&fwP&~^`mM#qWj13?mt1+sjdYWgyzz)-& zzuS;!Q}DKOY*hcA4|YG?*IBu-coACMf3&iuX7q0PwPf{Jz=&D_RG6f4g|SF}jM=S5 zDrB)~$DQ_j*y=C9?^b8mV+FHS-nd4G7A>o^Wh8S+dmxxsJOt%MwIur~ zaY~5Je7+7?d0+i$*y&u*a9yZ1HfRK1g^%!uvX1e59$_VvAsJFN%7@Jq&kyqqxU9xK zeSIkFS4&9ewT#+rm#W&#%0$HeK zoT2RNA?Fd__5qKa*f539V6_%y8_7;RDgI72pw86p;Wuj&aXQk`P8^_9IyXbU!ZG$}7TtAmZ;w5(> znGjIl2zDrcMRGHeZ#~(j*jYuMLUyltT@SS$3~UVaomi4dHlIeWtZqAo6-T214jNe} zZ7L3zlI;SDVUF7PPCAb^UoOBMM~PX3cYyLvKvF7j2BOl|e9SFMFHWMnf(_mY8QX`M zuPKA@9{!$yscE`TUC0<>*+i-99JE8wMhzs<$&I|+uj_PLb`E+RlI{z=6nu+nGzdh? zKBWF z$Ga5T?+iz?PY4u1uTb#OUt!MNyJN`5)`caC0ym+`1>4Nj6ES41T)yXMAs8Bc6V&Nh zT_-};S7{WDl`%A`nBh5b{4A7hbSb=4wt`!Uj>RLp=4l{tgGI8l!x^6Ij`DWBas z$s{M?^%I;9SASPrmFE;LeSz~5EGOe=LQ)sW;IUM#w8p&{hR4-5^|5s~=f_tRY_gVe zM3lT-r}ttLAh#QnZr!+2G?YLmc=iXe(Icp2hcm6^CL*aLw{A}7s$?B+Vri-KEZSIt0UnoloB8$z_KfZ8rRdswW7L_CYYZO?FA%b7{Cr%%{6drH+ruK+!oQM-aGi;= zXE2b(=&p}})V;BurBCH>tn(@uj5~ooLh9FFrTgWd@pOgbuQI@xThva>mzCuN~ z#IOsav6Ybw{ni|*t)fdgNybm8EfkaVI#Tl(cPYS@kCW{aL4t4D+6nZLd&0%tYl_x$ z^>C_F`T`DJu_IFI^k8T8fv#fnc}TO$+J&2S6JD-2yDAa?H6zd@*|(1IKLl^Jh0iO19adM6heHT%a@AMrt)+CmkFZNX|So>F6P-ZX)=|KG2wURljPJBp8 z@nD)NS(1T0(U@Mp?-7+wxwviekNN1N1>cSCP(vpk7%Nsw0&#+IPPpp)yG_#wtMkKB zu#ctvEM%-I%8qF@@pxzK33|B->_TX(BRZ?aN*mx$QnPB3dm2N|Sh9 zOhMe8wvzKU`AtDN&X^C?^*NGTxcWf<$=j$2_hr7(}1?F&8Sw;BgqRfln zt~ac+-Q&Y=?!5au!VoZzG1d~xeh8a3($8wh;>Gr3Lq1)yV}Jd@6UklA9Li2+UiaoM zAb`FA7{%s)eG(pey`B z(Bgjx9>|G`n21NnHg>Qt2MO)$uFU#yyM|*xg4E5MD$fkU_Tc82Ul6|2s#SaY)N%sq zaA3geOCOIX<<^s)YvlW>#d6UX73{+3J@KRYz<{00=8Av0ntZTZLOuajR)8T2yr)a- zmY%jmPT&GQarhohwO~*m=@tRZy0!vC-=mOWX{DV|45#e+2nc4MfY5RcH0pIR`onBk16(Q6;bxB zfnS^kxa)~NAxVg?QGx-b&4!U3#)MQ(MJB^nQewi&yWoj6i0;>oyOySJB`z;oB!%;w zmOjLx^cfb#N4_gvsa~)Hq8%Keuio2#l+uU(NCecUf?(fdn-#wn(u=D+Y!)9eSu|_O zw#Wb-#_Dtlj=ExlFiDXX){jIAhR@QAJjWueI3v;(h71mR1rA==$K$iAW1n~&XG2fp zMHb|!+I0o@UiH|x(YO*c^06{^j+%bWGHYV#Y6!(_;c3cb_s|chP1V5v)Q& zd>SO+q;Zvf-g9O}{!mlMX6#iMw}k%S#s!bv1BaZEth&m&lNHFL z1(Ac!XygD0{SaZPgY&4WN@B6b#$e9-ttVTb>i(Oy*}F&txpmb~wZ}E!C26tpTtNH} z-8`=BnIX2OOP^oCmUEIs&!cs|`cyMz36vr^!KPDVqP8M~7|#n02gv~mewK-NqmRzd z9O_4vs}soZWS0yoNa`De_MIBT7Dsz0O~8ddxh4)b&FATIDiG>~xAUGkX^;?#=xq;u ze_#|zF}W0sd0nT;S!uO62CC%&#IAQHc3e*3VK$CDSI7Hi-%Jn@_L~#Yw6b8n0ROZ= z+}DZhPjAG^?>cjv+Z1pDgJD>h|;C?pwyX1B}O@2Zd3H=%MT`EKr$K z@io-w0uOH2(qX^pr%SFvC3gF6EtvjZ>-PIwWC!> zXc7|C1$D|+Rlz;oNoNu3$2{0Ms97%m0JhX}?gX-RIK3efoZm4<=U)%grul7Jo@B}m zpC%!~^6BXZ)3^9Iw_dL7%ShnmDCGF&43VbZ37Q??xoY4+S)arWF0{CK)lv`^Cz{H9 z1D@N5_qZ+Sb49SQ;~}|b#B;_pK65>gB^n`>7EM-D{PWc}a7a*kXYmh~GINSEo(C#a zxD}~mu|Bo~<*FJpbW{sC13Tl2o;y|*40Nwi>U0a?ybIWJ%NrPj_yucPEcL41OY*cb zPb{~gPA&}lN-6%>zW)Zt+>O*%c7K<65nb`LX6l9iW6(FdG#mESRyMQ}WI zKt61wv;hpqXzYunnI$RO}NUK6kI)#LSb zg)_|03KCqnE(N5ELnb&&U{VSv+4T0c!Z+I5L7(Zz$FQci*0>*b?aMZFcDyHAQhC_Y zEgnR;a3FZ-HEy)2gx-BDn|Az`JT3UKG(9<5-L(%#u5iyD*qjK(y2Fqs7AZ%b4{Ja-5E_SJx>03dps0Bmgx!T*H zCr-UgoHKFQBsZW%7;?=IaNMp@_3@=O2MBgBq{r;wu9m+q@A;3^*>6wiO5P422HQr=<|{5?(DmW&*%#tK>XN^c4>O^QNcdO;XBf|Io7WqE)L%vwtpOh3KuqO z-?i>uRn>glq2t@}0;XL^ER2U-l$4!K(fEcBXF$V}5{Cl4&3k1{&e=VxTD5QWXfWUd z{8?ATq(vjKN5m7r4M=psti93pOsG*eroqB`JPgnqRF zWZWeez*MU%TMV>#?e(_B4oaTa$xy3%3ROU0L+`fz2gu#(W2wcBW$e|G1p2H_O=-Bo ztUVT{x?6x*0~JB~O0VxIE@r(OlR=5a&`fv#a=EF7Pd;0Uivm45G07Q$NIpqUtw}$+ z5ZpVa2*SMiuk*V$@4~bkYYv8>mYeNN>jca8L2OM*cLa#Nq$F4=oLG^WOjHk+Gt?%w ztEhv%AA%R#ZSSQ)XES|~D)oO2?nP7vWiEv!7+?XOI zYTmks@<{gWBLEUD^5iN{0&jOFH}OS&F!fy42dcNFZS`8hfHzap+P+GU^Oa)5O; zV7lDIZg8_A!{==k^#k6P6y88orNcT%O+Mx}G~T9@GVz{7rGyIwHT+b>k|D->U<;Z@ z)I=0oeKAM?ZKw@rWo0ZSRcgt0c1Y&zvTq7Yk8`L z(Ncwwa~w^eEeC!l)zYpb5cYw>HF)(HtfQaOHzgF)PzSs6qTpnQ7M}r zU$f*%L8}KuQT6pCPB}Y>QLa!w;i_xS;7nNsfyiw7Juj)w@HU;rySM7dVeB(S%Q1)B zoTu{LJ<;4pJ~Gl1^9&Pdsg?0f$y_7Vby0z~lV;wJcfJb~A0yyL$3_}-SZEUs&c`4p zmpbp4pvpqStgLW&=;DTBQK8mapox7w!m6de|#Fws*w;* z8CFju=X?Egef-LsR4mL6O%sV8hEW$dpd`?#461ZeI~;E_sz*{j<=o@wyiWqU zRk{I|K2XAHwVukbtGlJXJn8h--{_~JC>m-X_H*x&qL^ZK!&Gq0V8RPdc8kKH-fzOF zfC`{`W-^VyjWGA=wbglnUE<)E+&%QDoLx81GKoTtsn;c2@`Rg4i*nk+e>}R1|736c zK^=yjZ6T`L=-afM09EkR99m{=E64_Xss39(6QBn>Wv&QTKLu~ZGP(RIgduh<;%~Fu zLs7=kv(mT*l-~OD_N-D?1zWGF5~ZpidzBOUU9BDI zm|`I1%2BW${cv*SUmwNMk`2*1V;ByzgF|PCc%9fOMv@k;<5AuBlU7S2!L`C}K>8#hX^d1hE0RDjKG ztP&3&k(^aK8vE#%b8g?;7Oq`h_PXh{rQbI>{?kuyQksj-*emc*7ZJ^Pzzxm8lf>qb z3YFaPMUXMLi$7=owF7~`G!v8Vj10PK#65#LhQy6ZzZ`kqDwPB58c>8o@Uy1F;zz>A z_LrZS0seU|>fi-{zJop5ODn|ruU7tlxdPBSKnc|IrTr+AcHM4w!_2@OxY%hm-1w4l z3+$B?gVeod1^Utb?wR)36 zT@1t>Pwy^qlZchzj7^W_@2^Hx-1ok~c)$P(PblDacbFh-Zz6W7N7&_IavMGM7K%CeCk&T-nwiqDzNwnvHvBNJjZ9j8V7{oCX5 zFdm_;v~%qwAC}729_x&S0y(AAmCUJC%y+ShZ+IS6R%I)E2q7YLE~24T;2TcQCI_Uv z$vQs{e>c3q&-Ny`MSoR&C_y>F80JoI2*mW{WQ1c+mtKCczx(CGQib*Oow3KMgzY!Q z4BlHQ3qfK!{=oMWAQ?IllUhu?R`vV^F5$98==bV!F&LFVB#(DRMoz*n5>1KV@1SnU}WdQTaVJgZhW=!oUt0Nc_ttTOIRWjy)7AI zon~ieZ0)uw_$NZ1y2CxiwIHXM~}%6HA2KMVh8x{-O7{mq#9=Arl1M^o2^Yn zMv^A%bL^fR=%-zGccQ*jpep#C%U1hsOTs`kZ7lc*vlBkQQ2{X-u$yrJ6^G9?FTf}s z!HwRvM-j&_WC?(Gdqx1mf7Q4=w;KPmRS?j(?Puko^pje%UOWi$q9QDnupga}O^ZK- zjOWHcD4~`xTK4!m`?%}~oUXJ2WWuyBMkMl#tD!w>`=3J&Y2RTrs1?~<^L3Z2DZCCQ zvrL>OQ%EuDLZYt+o-9X3l#dk@pm)bR0Wvb~;lv_ucSO$m=t=V_HHn=Bxyg(=6gk(~ zzH!vZ+RdXkhN3YBMg*ral>4lL4p#N!niQ`=FoU?56(v~{t45T}{EfP!Dyyd57#{i} z<8NW8KC_GVT#xvl1wfhk|7I8>rL{PzGe@MsW!xIts1pm#SI(I_Un%P$)0nr%3uSRzA^z?l9o| zb9%_?1QU%M&QLopsBsbA0z{RJhs8Ex7+-HpTC0VX(8CF6n6bpI87H>3*RAAw+J$hv z>_<6cS(_3gnH>Jmz<^%G43eP1J_QmcKAi}w2rXQo>s?s70NlNN66TlXdSWMXIPLow68z$1DBYy>b_~;wkK?NblAJ;{~83! z$H}_C3TC3DhaAk8)cLf>i>Lo#H*?RkV%B1MzkFmP8@~o_#}c{*PjH-Z199wzBe-_NRJ;YoA|zKnkA? z0Z`5eP;CT=0RijFPr z&mI-G5O4r3 z{1}pIgvwY;2y5#L35vc3(r`B=m+hvLEAcaYC>|?ndXNHL!)V31fGBP|0p@lcq@I5T zwOsJl%Pu zqN(;CjoQBQYek-aZwKYYsDe&ydFDk-moJw*h^$kx7Pc^cmSNA})&C>l`z9LCD?yXG z`DFn#uPYQ9QeKLd_{4i7l~CsoD|FY37Ft{aFAThI2QcuQxBW}Az#REdvrSuj>>Ho&I1d{ zU%ZA6 zX=EM5ep&$1k`w)`+wd@ZF7*vwe_}pp7Nf$7bVB>ekAYXuQ6(=_!g)$>NN=TkN|4@} zLVGAC8-sabDSsDBRFHt!w>Haw|59U?KsV76bs}4Ot*V(DUluGgK#`|e8FGYkkuH=z(6UvmA#Z;KDd!7fwfVrIX|V2;zQ54 zpjs3-r(G&~(D)r9tG#dKA8Iu06>W|x0A8)$egK#V8D{zMXTYU)jMY za_1Pprfr^aU7v=aWk4ED&j)oh%oSPFendNfnJ~mAlKZK{kq}}>3vnTpltR<`J zg=Ms80LuW`{fxT)hwPpq{=Y*mfb5<_u8_YwqzFK?LG==J0ia0GcTc?89Nj_IJjo0^ z7Eg!+Cd#pru$(aCN70!9(LNhHwg|UvZGFJmqi+KcDLBMyK{{j6LhgL&VgrhcO31|z z@t2RJ-^`I|vZM||cpxYF zS$uP9;sY#OZF{J@O8sDS(kj|wyxS*gkEQ($`~9g0K6!}52P>9WXM(ZQ?w$KU>iySK z8SlUy9)nf0AfOS@SAuK|7bMdcMB=>nuNkxiGajo&$%FIdix4z3BaoQn%kSJtk0LhG zXU-P4DphZ{qvgH4-= z+vw7O0cG7kU(7&w4G=BB>jT0&0LbZy6Fr8rWw&c^9KX;x*8p^Yke|c6z`qOmIYa)> zKo3y${`~C3v)KY2n!bYAw{L+=Xnz^b81TM(t^WUFU@BbZI zto#WrKq;VUL3!G2wD+UFM7)N&qvzd{cO8aRcw+v%H)t6+v%n?z+11_g%T(j_;Hh7d zUI1M-I0-|^M)FfHXz3h)`nSRWBfzoJUlO@PLpRL!-1Cr9`(D$!hgcmWAsllMobURL>Hl|`* z2+1?flupxjbB-5FSkXc`kziYN-1OJRSa8B7Laj072z&~eOgxd0ryDxW= zA4t#Vmz;o60b;`Z9nPia1|Tb% zEz>)<6%)@Xi$3u=yCW|55p%7en}jw!Z58_Zxe55D!G-dfk6AYdt9>o1!`@&l1@c1W zT{3I=HO5Q1knpQE?3}$Tj3cwK;w&R32+QBURn=Z@lk|i=CV*gGn2M&r;At*B%c>|` zsZ>yARbS%?Yks?f-BdG0ejy|8IQQu?o4#uc^5EUx_i?+BKqNUMnn$CvDK zps5Yh-A@u`qs}?6w~|-dM0}z_1+X)SFtl5abK%tZLKLrC!Sz^x+LInp%vQTlInLw| zIgo!FI13R#o>;%5EgjUa6hm+yU#u0x3_t@&^*Pr1pHh9+!M~q504n?wZGlqSudCp$ zv)>Y>-_W|U&49=cJ;v6 ze+|*KV}21l$ohe7#ogeO2ahKZ$#nZC$g(XT(V%?%jQ*Qa+}3Z~ruCOwi3;23-tlZ@ z%;Rc3^o>C18<=4&T)ly-(_S4AAHg*bOGM1=WGxjrjn~`Fr?Y)t7-KgCFoyj*;?uR; zWb#^gz5YUkZ2%B40N*tLT>HPHijA2HeW8GP0w@5!KLaR#+oghlR>1QPfKMAgeHC{4 zJ@C!zXiH>sMmh_f<~P9!$~M-e!kK|{5#6iY=aMKcwdpxO6xd;rUh%Sds zd}S|-_zB{_!VUncs&D=cF09*suJ8XP>~Q}O!p7?JYb0PuKyU0nVF%ELrNLGLfWx1z z0*4Vm1YkG7LH{Rq|DO*;%Kq}r;EzN+G~+iBlA~KY$Jpkm_~1A$eUwc&?B9!-HX77R z=2cAPzQ}*jV7w@!Q8|CBDIS!v$uqbaV!=R;;t0LPO>bQm3C~fDENA!%(i}qJhuq3| zlu1DvFZEnHjIl=-Bb%-+GZj#_-HPKXQD~{WJ&Go3a;~GRf)w%hAP;X0AV)xMmtH#PD znBfTQ1DMFu!vL0$J&%@e+cj1p2tRLp&>S_o+&wwf$`P||VosIJF>VCHq7c)4*5j+4 z7|t5*IXR%chc4$_?wXw|+x7lNWt(JgG@-R8vU*@m!yR{poOILCP;ghqAH)r$%$~4u zzil1p#s{!UKz;{!+6KU>DnBUr&~F_e0w~Y858z4%5fl1a;1>b-gUj$wvKsx|OKmBu@m(l+tu`d6Et{{7dYz6`+$^GV>wtgi!k7YJVpQ{$q zIrOiFU!`h%%YW3xVB)41ntTM2w@Av=s!LLhLU;4+zwan^u3gC6liy#)p)ffQ8}T5 zFM~L|y=DJsTHH%T``}V$5Rqn;;^@Qj)03CiB5d1cPIe|-Lr%mF53VIy^}Ek~0V_=vb(I$T%zOzjRfm0-v|&@ObuIMZfX8{aXC z{-oUvyeKg$dzCKVy<{-zo=KX{ok1C^DB2h|`mxJ`ID~)sNlx~==4I{~6f~n34uGr8(xdylFhH{km=^mt=&RU17HW==A-xdIep&2)9fiN- zWe#G0ai26P#N9ypfE|Xc4o% zriib~20P-r;R)N+rA}vR@MU_;@_Re>4{eI6CmBgm>Af4Cl1K%zMd+%^xHQxR!e>6- zk?}gfte-Qv&~h-{Z#0Ve7>U9KjTJV{vOns(h&lPFlbRFvwatX3;o(Uo!hzAyiJkp@0;59*~9^M{CqI{m+pS%Zs@;`h3(V-wy6;`0Nv^SI47V1Hd1h! zsSxOuBeEr?<}ekx_pn98$qb{EE-#}YR|9?kK+&I1sr_w+-%pVJM0)MUl_wn)n`J8p_j|Twxl(PNth!gQqeT-N!)mk^Nw3SO4 zX4-}aS;v3;wEBnsVB}2#!@@x@Dhf|WNn52Yx!2X=*ESL2iNp{-nHFGmH_`Ut1d%wF zOdZioELY7lf~bdMCK0M^TS!?P7jQ76n`QwvpEpLv%K}+Tz@b_TqHj|sVzz^zU31m% z``+zz@`eZa_|{EqKIumsc?f#+7;ayWAj_QenLGNvv2BR#a_s#C-WV~=+mdEY{#Yf$ zARuBM;`9bl2{=FM6iK8>AT7>ljfKv}iJyiXqTudD^(5uTx?<@4vZAif0l2 zN*HYa9!);C|7W@Y4Dpvk%gggvudx!pv6OnFsA39_x%%VbfMd-Fk|$bejjq(L-Gip9K<3G zm&F{T#~GFT^**Vz+gS^LGoR=G;Aifd;Zza@^4SZr!@SvlNleKp$13R%ZF2$POP z;6Bt|0*$WW%eM{aeXbO!LpHY^Mn3d8H1sOlsTj$N1@dqzULn+=>5TJy%N0Hj{ z3clKzft26Yw0etYbNj&6$1+XXAb-w}V{wU^>nwlbq;<-?!>?^iw+R-oQ#5$xdL+-@ zr23->5q(#bF$itBSU4Qly0b3mX$#0rJHUfP<{n2lQoqz-W!?pr*~uY~{RBr>2*oZf zgRX>i@S+R98}+(A!U=(O)ckG#cGLMQg{JVQnR#-p-V zwEqmLTa*GF`bA(cMF0Wd|Mr3sQBO!dZ4-LK#|qgm9e!dUz~>nP>R_zH-n z#QY|I4N-=%NNg{9Bf7YvMyHT4tROx7=%3CLQM#%Lep$XhB)gp0k3b1yiKMvMy~F?7)+rY!K|!#I=;r5p*=HCj&y2zm_}*%t z$Bv%2^>wiWT1mreC`=DepBMSe0seW`;;+<7BI^56m}>jH>Vq`YO9z2xI|pcS=YP@S z-oFLA{>PDlI27TRZyv47FIJmSen&m4h%YNLZCHr+b^cIviCaEtxu%VqEFD?bk-NEm ztdsj-D7|O-Q4X5DlNb`WurrQkSi?8|5=EB#a}m8hkeMTo_svQYSP0L0PLDvgYT0-O;BARZ&`TiEt zwdaNU@;EJ%DdV3TM|dt4&8B)OQ7#$%ob|PYlfH=Y_4(K7RDV}d!!s)1w)D_*qsn99 z!EkbGfB^N%l~hjY$Po=qJ-<|m9!#)SroN7lUR$go?xLPdVlwI_Ukd0pnK?l91%}V} zC~vxM2TJxHZyU`FhtCLmD26&6k3%wxx*$P^IX9eVGjytH-CuvdsBAMH(i#6Q#D*Uz zPh)JH-aRoIUmxBbbFqL_qTLFWO_sC*@=CT@)vnjaRH5QWJ0!mf!axPiz7d8wWQtl{jP6OM_Vs(Ap6rA;Zps>_u?*F(> z;waR1fNM^b{Pg7bIvpJbi8=AgX+QU))3>B~`O9EAbd3XvV%E}u+$c~VgJ~d=Jzusv z$k=A3LfIFa02Kz<1mW+aSh1;_dHruYh+Z@hOYO8TU0_lGT>y~$AAtw}!Jh+>H#QQZ zus**>j0AKi`xA?R=&xr!`Hkhv)D|tSz_b>dW(mA>YykY?uMffKgk8Mt^J?UjFVvrh zK7d*O&jAY8p8y4@z9Jg+N#U9jaW`~szJV3#b&n)|e1%&;!#Yyftw4)}Ch-LBTE@#n zKux}Yb-dhwegZ24G8dl zWsLt0!Tuv#e0G5U+>Fm#SMHAk zUs&bSwEhBkj>8=*LQN$A7NU7UMJ`%36|?=jzzf^Js(=wOe%%3l0`jP&fk=L#fOi8Z z&xzYVSJ3{e^*>yv>tC)@xqt^&GZ;q(nV55-F!1}n8Si|8(`yW~XzLZx?RluEAf#+Q z{ZYs(`QzoXkJl`0%q4S0sUc732ZWn?SAwH4j9K@ZrKP4dwuae>Nk^OQ$Awj!pP(In z=z;JZ7PSMZ%rWAYlCQojl+OULB*4?uzfSCg{MfI5a{vw?p#E}K65*CGFU^p6fMx(= z&)(`UHT;aT@&0%#5P?_wC9}z6qrba+eKwCjPU^4U{mI_`J=%XdDZnoK{o#l^K?ORP zd31}9MDT;p%RDv$zoz+L561pEO*^1BV48nJHW2+E$Yw*t2Wo_Q$Z=&AU>Tz3ubdIS ztEFMx>03?v?WuvLo|ywgy+4n`AjnVO_51u5mhR6P{_h83rhjdD1*94`3Dbf4;sg(| z0??rq?83o(I?;Drai`2|_(b7+L+ZwrTE|BNj6Ogz{M##Aqhb&vUxC&G?8TQ+Z<0j% zn2cA`XHK#|2>a;7g?J2ubSS(mih&5QD8N?zmCXpv>6*PP7v%Y5_ZcnzEhRv)!t;j= zgQMZ!b^ryibYO`;Z~-D$@9b_pL3&Wad+@1VL_QgcTg;V8+NGPN@5uJDI{60Ju}Z|U zd=1C`OUzP-dI0iS|G+ZW>}MacG6Pe3Nb#G`KyUFs&uJ!gPeO9lMSB8U@)NFLG~X(k z?+grqOvX$LTA7s4>b^=knqLlj5_VT&f4@(-lPLLD4Cz7!P8(Su3PfBujo5C zH~ldbZ`(WM+#JuL1LJLMpQ6y1YzdVQLH6vgp7_Z};((%&zKzjJgAYstE7pVhF-<}# zIfpH#%jr*A)p6Ir>pC+P~ejB-Lo1((hwQ&6f1;FUa z0Py!SE(33-FFJ&k8QQafwT%utPU2Q|9MWx0Q;GZyEBTF~-*U8B?=fnkaeyAR58R8u zg)I5iIxbPbJAm}x@CnGKo~tu>UK5{u77=e$D#-TLSTKivsMs|3Ja3zfh2`-T?~RJvimHq-`)} zo`WP%EkElhpL-dFx&m4Se%abEYMg;uz6`1eRPFNXn8@}MPmmm@S{BSsC>4By8@4Q7 zT51Dl73a=-UeVXDO#;4$#z1t?TI6736+g%>TSC}Eu`yI+c(lbq^`E;2IxUcgky@vi zdE`=%C{h`}bC}iqa@e|A^ae3-SOh(#$J`tHsVQ%?luBc5dQ8A*RIgDQDxd%9b~#z& z)iT=6>f*;ZN@TWXdH2SO0mAtP_ExR>Ir~o$HQo~8TQka|2gPR4A;*l4-aNw}(7qRP zYlO%gOX+U3zv!Pi8z63g8~KI70xp(+oidvOC@(pKn9pCQ%phWb_Gc9Sr`iMod(z`C z6n+-r05L><{{kxhp#6;eM@wa=Xp9~W1g5X=h`F*xm{D`XClN;M zzjd^r2sZu*(dzhUitVYR^6Lbx#a?bdfK#*qpj8Ax38o45D)2Hay6v-nY_WM-=u!Tu?sM@d`gqSV!t^*cWyd zYVq}eS!(L%!!78+Q~PPdu|^)Wk`wq*b}8}XFx8V2PHZE!FpGNdq!!G$fn5~Uy}`lO zOEAOAmjr}>LS?26Kx_}n4&9G-a()2?XLAl|`=O%J4q)wB4aeAY>r(dKRNWMon8p7u zKf?Sc7yUmgLHz&wI{xpD;QvFK^4GopsRZfX{BP^{KW-=bpHK(HFIR+6dMycQaHOQI zKJg&(U(W;l4M6{cs{fyG_y3$7{J*3B19$)LvrGRI?to~UZSg(6;qB?(^1=~7Lf@W& zUt%vL01e>Lw0W!8Nn>AGGsvO^8$k7bb?tRfO|a*bpW?F~nUu>0&_V1c?`pet&$V?T zn)M!aWXEAz&h4jV9(;$N&=P=o2!g!J+Z#9N9E6(5~y&B$=Ox9wM% zS*Cs-j9j!TE}=hZ^h#8j_<(=D{D22J`jE ztYUOYtA78PG0`B%{tZtVdOOwv2Mh<#ao5dbOQEs2^?0ucF&eB`S zX_8?h@$+zq_I zX`_kU|@tl`FpL51F|)?M{gF-~Gwp96pYOv!**Y)%_v)Y9^_EFO_jL0!mMm78t`*f99@;9P&KzGsmiBfq71_VePUgzL`v&aU6WK#`WS5Ya4Sj-;v`g`JG1*2>4IFk=5-6oJ0~__EWP?!0a^9C@(x<&xu`~RPSCZ=wz*8qX+LVc2`BK zkHvm^-EGH6n|EOm%442V}0^9QWKJ*vLhc@!!r< z{g3nhf1?vkng4Blx&4l&7RYG(A1N&$d}%+tn^Np*0Ks?UKC3GSr^=jqZTwx}yT0Gs z{-z&669E83`%S_F0r-sC3F~&m$obTnWr_@^hQ%;HDKpASTf0>>>^J6Rv32_7g1Wzv z-X1!eb4qFa6x_hX+S#_fZvahWDTJuqk6ZK~3!hxiB2NMXqlU6SBqLx+%#?oCR|HYu zm6BursG9i7a);^ewN-O){%)PSDNi&VyP2XA;T)a*!sFS&DDpA4O&Hqr9bAg`5axA* zN@Zoq$t2cw90VjwcAGicpU*Dnu86}Aih^aD~qXb4R1QbIUXW-2GWm|Td z#c@--VfBL==u(CBabYw_3c)Y%QRfkwft|wk(0;EkHY@a}8qh8hCu}hUAX2VPW|f(I z%+s#}w=ZtFGklfbBwl>Y>5)%Q7NKq%y%s1V)g`yLrySr`=|vYo4nKiBffjL0Iifj2 zzjXLaKw{k0+9JbqKK95D@Xd_0>kgXShAL7cpPMRi|F%M^&cdE)jAD>GSNVq1`%3G8qd4l zAW-3}{@L~K1z{QMrDWe-l+EqJ_6=)aP(T2RH z9KAx%l6|KpK(VMUVPwzP{}p^vTtw)l5P~d^e5NR;Fd{td=P?hCyG}@t`NliUgp_;- z0v87me^^HgIxEeYl4j7hH`lX|cy}@i=Z{FR4V#Z+cFiGcQRdV|&Tl+T`ThrelF#O! zGcu^$B!faJ&tUyiah1Y9>^ZUunc0p$r+HP7r%~ZBoXf--m;CFrQB)JKf?OIMSh%zRq&pfo!_ zVf%h(X0mqwgUEaoNa%Kue7Sf%cI!YoKRZy?tpKb35)yO3im+=>VWyasUOJV?4BRaq$&q+#$Yr!$R@rm;B@Ux?1+S@Z6OawY{Zk?vMQkag+-xk` zK@fNVuO${Pty2vf4n-A)n#sK0d>;3W=J^nSqGA@B|3UFDOI zNutxcYoyb`e`%_Fl6!tu;B8p`S@*E`mx`)kqnv8Nd3#;b4H$V5Sf+Y4^=LKcIAwzR;{Oyj1eUI+^nxw4 zcBR4$k=qhNpX?Mlxo#C*DLt_}I$9lDnkA0w*p{-A#(QECR2TV3Ic0dF|MiOG#Ff%^ zS1nx&5hBwYaC|Z*fxG}wou#m%H*SbfQRd*B`bd|zTycfM%mqiC?qEeSvodhW!6{Ub zBD2g3OgT3Uo+)@wVJ82|e+%$0#n^~ltwxn^>`;b{%d}2WU<%?5Fxh6%h&8jk#0f2@ zE*Y~pfAz~&0jg>L=XkJlqz!!D@NHg1SSPw#Y2KUQvp%{Fbm=-PpY3>{h#~;tOBI^X zav7RZ&&AHdGfv87@k;O^0XBp`AcXt!FMx~K_~1!|h-S;?-@s>m1h|Dx{&`r^M(ong zXyEpsdA6Pp0u6}bfm9TQrm+nE=t$hnX)J8%=UISy1+9A0|5ImZ^< z_n^IQ=6s+L>`Mz_v<+KH7DAgyze5ZHtJUfx z-@)MRB)+by{+Wvk;^dhCzC3+6qRe0dS4(0J$jL((5jAYqN9eeAVkD@A=49z;`VGcq z1JB`4?*ksI9-rB$5ko&cfMBzTAqQX&+djsYzTrGuSe478=C@!;!+BG-IfG6*COobw zun6GX>B7El93d1@+-#1Jww03f)Pu~s$N6}c-YRHZ(UR(T{c@!fa>|);F7l6HgJDQg zozqU?1WO(Vta(3p;}{T%!E*0Tfc33!8f24PttpIjDHv_S;{27Q601-sEm9J)hEIm7 zQq1J=-ymtH?#CQJ8knhWk`9%O7e}L}%Lc(ssVSpll@9hE6C)dnf(x*_r@>ACiHuCm zj7b70F<4^|5-XZ50j}!xJ?Ke^L$e)3s>XC&vEoh{^n3kc@@Ezq}lDvMzE3 zgVuGaLLk7X6CC|8RMU9WiwB=jorm$gkYoKz$Feh8LHSnuo`Rl@^2F$6P41ia@*|WZ zuZZ?Ft)(|L#DAbwewy3-m*3ybv>c{n2Cf-q9nVlsc#OndavAa_Hh~7OG^ad#{+{!Q z%$5qA&2O_G$9oJC;1+X>m58a^Jm4ii_}e0`Qw^`V@Yu{C;#~P^O;_~M-{h;WV{+Pu zO_2|R)Amvi7o=6_dvjTMh#jpDQ@HQbPhq|PiwP5REW}^ljh#y2-3)8}Y%RXRQx<7< z3Rk#``XTWD)ANJ#ia4gs3kqjW4WD=N!MGVqD04#J?gTJ2h=srX{)W_k%`W1V4x!+; zpsj>JShZ7BHTq=UvpO74B7%#g^VO)Xe|&0eg0fu|wB{7cC1cEtDLytzFk3;sFaJ?5 zY~C)|u`F%D%Dm(f^|1m%M-`X_O2MAvtVl-Q?}iRHgHT{i9unEnz=I%b{FI1V(D#^p z@;CKVF3Wb2O6tv$=A1r@hd`hwrJMqo1MnFp1+O?fw9vgcH_dBq&mIHR4u@U6SWk+A zIq@gJscLCks`ih^S5r*w2Sxhz3BJkNRjMxDz^b!8+&8T;;~&rfE3?4~ss=PB>) zjx?&l);#w2%l;^~d97|(1=FH4Mz7;yzy%79LG`>OZYpM;!gvv$n_t*p^d8Oje~}uU zUk)WDexF1Z0SGTt#geiU)4K|!!EV1_ASGal8&9?jh>6Py?8&CPTQXX)p_3a%HnKi7 zeoKW6=P#4-44+v`8Cuow&!mHOI29L>@%R3!+e$1Xla~x&vE*EdZNAGI4K8)s+Qhu_ z@P}Q)5A6%SWu}>Y7;#C9ebmmlIAnFzn|~8T^(HA3gX?_@I6V$E4mW6Fbl0}NGwO0F z1T%_%m}C8d83NBAxrAI=kv6vYaabIkTc;w>qVS&X7Wbs!J5L-Rh=zT5G?=r0$^y|= zMkUDjI#;b*L>08udeTCE@WgXgdxq;MTjtNU7LkuZusotegt$yk(DB>)UoKMJXC{34TQjKYolc`W%FX2ZX{TLPAWjc_|wq(3q}OuqtXj-@HL8 z^EoTla#_SIFe&c{W0v$h9nBeMVh`RFp=g>WUlmt|ji6uPYFyyD4mFvUr8 zlj6@Kc$B!vaFGwLs^f{nR!OR%a3Goe*t1(ziLMhmH&D?8X+8+pZ8Z4vYEV%McM)@+ zoxF+^MV-2oE;+bnGc5$(aZWu6I2tWwxV=vBrGBGNZaHB)Jei+%QtJHB2KsC6bM7)k zlc?qZ?X=MN!5{i#XvSLNBiM2QyvYOQ4F-o8qPQ(Mz;t|SN_vIUp5H*NH(wab@FuiV zca2x?K;;L`t~lW7`a9(Pv5fGnJqp??uK46LKTf`EnC@5tws^pd0N*fUUX)eB`U%ojO>i=r15ELE!!$>7Vi)=m!al3q;M%ZgB&K;!it<$(* z_&!UVTPA3nN#gjIG;Ku-X7v&qvrR@Y@-xAg*wW#e0gpjn*b0Tx!~@tO+joa68-6vQ zo&Bn>Rzq;_khpIMz~p*w9D$0X$Yrxc>QBjmJo6(CTq02MwLhuHB85OBkthh5&j1qk zmJs{+0k4qZ-0iNL&bNseQWL6Ax-$elx~&BJu8fS~539+s-=!$mkSbJrU>b{IJA8{l zHrdN9vt9kG5GHFtm_4^+jq|zOi?obxdqTv3r^3Hb(`V4+xmN@;`R*ZO)vZIgiID{w zXeAL`Mbhjvpo(A{@^r`bO!R?>&>i<&eXfyY0meVyuE|(30bxtHIW}OY`-f-P%XY0O z`YZ#PMs3?aR(G8)`4VK&D1o?W695Xd>Ag1knN%5Ri6CP^?rE$ux3Wte7;6i8i31Dp0k%>L}JOocrt|dxCYUkxPi}K*b zxeR9~U+rd>sKjo)Xe8nWD4#y=5JVP%AMUT3kAHyFk~naEYOMG+=uLr~rcv_`#QuD^ z^}Q3uqsmp=F=$=(JPI+!x~c0ISXdtvH+aI_!LtkRW(>A5AX(qS{tg^J`nEz|Yil_r ztBfuZnVdy;RWkZ6&U`>2xSoS&)d;lqp%GNQ;QN;QEQJJ}Gi+1E?f&$gUJMdD0F5cg-)i!z>nK>O8cF2-vO%}ruW5)t^0!;udg4vfdE#xlVI)JJXTV`)>aE@><*g<+0 z|06cWP@As&b3IHOt81d@mC+{y!-@9LFqhc2LdnqX5opS?{dkWS#-lf1%uOD**DyB z`2)n3-PLZ>s#&xDGJy7+Y2n>u>^g-$J-R>Hqc^1Nol1^~;AkwLX*C1eGdQt#sg zZPG<&zGD)kS%1zY=>na5+6-Q@J-})gs>Auoj3{|mkj{$}R9u^?=>Y&hgn&B2l+|92 zL^PQ0wa%KV{@5m3(Dg4i*Z-+#*V>8<%h&<26zMnaxG)NJc9RuSb^Ta~Tf>(hP(G`lOXyt13j|5OWh5{L8>ogx zjPV{16@q3t*W;zV@WJpy!>GFYqV$Q-108A0U*=)|EEHFhwX=>zdE%xJwOs=Qy+%Xf z8zMtID56-jhBZ*QX`X{1GsX|D?9VOLKQotaKKoTTBcN?XTXNgUWIsRVD8JN2o{k25 z25go|m~^7xv|NB}ERLk-ZMWghp@_))lLWrK>hw3(>Q61yge|3t%B=iiH3guaB!l_n zwh3zUQD#Edj3B;^^OFVph=HUcQ#Oi0$5fE=6tE8 zET?QX6Z>(0LAcA@Sn8T?+qJ~F$w@Yz=gXkxvTrRqI5ny{f}XN&fkk|f5<0sC@45>l zA-tg~PDbp`a?qs&#igN3`z$<8Gp*P3)ex3j23m&{)E`*JmIXmIuq6G-7OvSIhagiV z-HlAEjElMmRt83%moUSJB396cLV~JOO!#_5f{c9cr50DeawSkAG@s<-Q?-)6H?OtY z{47!k{rw4LETMNhu>}8G!Igyvn-XOTuKpE3YMM&LxeWJ5%&#$JiPZz<`svpniO5wO zQ%j64Oq$^3a2=DLpevv8f4^xauh_j-h31gVq-}rJTFTS&)mp3c0dj?}KhCd@XTzFq ztd1@_XVTT91<55zh2{7qd{%V7OzRE5$i`czqvbOeowoQJ{&`MKTpFPMo%rbK^^xn0 zpkY0%9eb}v9*JH=H!GdWmubbmvawDXERjFHvHTstuObpFzlFViPq*Rj6S^ZZ5MD@w zINrTX0^y;>XM~%98ac()6V99i z`JmQ5`53$_h^{z;Ndd-5vCyRp>`1F-6Xt3$_%DwNB>~{rRVg(r+XuA25gC*)J(20uLOr{6>lH&yhtk{wj*E-}Up! z+Pj*vQM6m%=AqQJ1PQZ|u1gO0l@D)K=%?hWK0j#rx1RyIgab|Z1+eXdlo$l9i`s$< z__syadF9*jpV;rGAEzS&G-(upXSZ2)3;wftGfC?tF**~=u@%?1g&5UG-AMe$2nrxf zBorVh^UCHsO&xpFUT85Q8l=<<^~a>0ub}YbTFC@c!XM~4wXZDL1Y#k;AK_Kq{yO4V z1o@nK$*X|(W_tVL=zXNHVc^4yAC>LQHO=f#y*jgVNz>WbdrjUXYgsJdmG62XP>i0e z?X_!)`$-fFt5ABqY1j!l&OoresIMIcZ~P{o=Mne?;6AQWv^<6GudsChy++}kzK%Auf$fhR z&BC*ycUo)ZB$S`%xf~mH4In*49>-GD+Lch#cfRk_IcUOJ6@)IW;}{)je}gkL{L52< zpA$$`(~UP<1tDn~FwSzJJSp0bKYqQTayIq1e2d}SZez)9fP@3)?&YGE;#Mg}Vf}5V z>s=N6^PKaNO|jfQ=GHFRE0<{EZ7Fmy2j_UL@sy^Fu^83RURsU1U&}Xk3;IktP={h9 znHHXYHH#8%)q$54QgN4ew{^w}436HwC2Y;-z1d4EY7hqtMbx?Aw88woj|^t7m8xc^76LwV zA)?ha>{-$~f}t=4gM*27K%0C;nDh4;)zYG{@8~GV=!h42ed`nc*4#|q8d~8OnD1L@ zM*Akji%;EY$IFtI*FqWswez6|ToefmZKF{gV+%=xfB%B?@S%NX{t9e|`)8)9AGp(9 zk2)cQdBVyf3dO4LR^!aiyb&8(-aeROv-9qRV-5Zj+@X~B<%0*%M-|;G7Qf{5<@mI7 z8j(OEvk=s}0Q@WagLMfS9f&ZvEp(6iHZpHqgBS3p5^z{$gfB;Nh!zn5 z;R|GJ316x5Mlq(^9ADbt^v|%wtT-=ljNVpPjV73@tQ}H265Cf@n?b%iIzX)WQ^$@f zq@11uopIk=%YgAZDEpeGYH(!cw)O%7#j!R{^mCC_kZH@*kK@vDRN$Bix{CA+DU$ct zA;$iGW7tzXf!*Xzwems)=Uc3hD1(tZs~9ey8u>${MO$fo1`H zP$4)j7^K2d4}#R~0$7Cdju9d}hf-`CvVXKD_f#^A6Yu#0jIX*s=z|;`W^WzSY;U9BmtA;{JoQPC?BOey)=qIqTW6cQO{-qgj(kP`paH0 zIt$*nLC#bhzhIYNSluVn?doc`9od1he9;s`z%9P^@9R}Tt#7mPk13f_0rlWXgVelgB2Sh`Sy6*?<+)Mv`i_FBIg#WFE+jH6J|D0b@rzQr!{?4WuZcA z0B^XRbPKNIx%oR2&ooFymI3faX`IS(e#&otI) z@KL@>d5UcBSvi3R7KUps7i^tZo7>OYnT}-$@-!$D+-B`<4U}v9^wMERPiU5~GmS4a z5>KTVkf|A!kcSU+H|>NAyLEg*ZyXURsD+ zSkuyTlSxfDNA{HI`bW0h+EP2ZI(GCL4=2eZ(Y0DP^#>x_@d= zrVHprWj4soyBzYpnqYG6=W>voG`2r`DHITNp(>EWFAE17XKpL|Yk`hRYp;Mu!7XSB zuKN6!()Ck^8O#A(tk&aU(dJyR{);lV)EfnKFN~lHs&|()#JlY^4z$O;&~oc(8i_MJ z{Ur=!xo7k_0Oj2i<0B;yBBWT*EA$`(k2(b2A;#L z@gIptine>N&#_W2IK~4bz@&z2(CBdI8$>@(YifkcWujeES?#MM0hOPp{U)dn`J$W9 zS=vNuRRdZDAt7fN8c3coSDgkd%yacUZf^+uRl%6`7=*2D(|0ln1P~hR*VN~)yvzdlPg`dsji{}h zDEvLULk|6rvt~tI7psZTD8$u9QX@7Nuy}oF&0oeZC`dtjf$aN|!)K^7z7cMx(zRhd zrY$@SPNyABg_erfOML(HC6hd$t8j?dP=`dX+m$R$6N_)D7K`>ZVE6#jV9$`tHs{|z zrj~vzap1)N@(108(h0V3_%p{B=OOB?fjMn3*G^H=V2i|{b_N3POgKM+`4tW2(Is7e z5bA4z(0;4j3i~k(MNl*sFsF+OYh%rCnx2-dwawQT^Usax+M2Cqg0pq4j>iDOHYkaZ zEL#W4hWLHaAVqap*g*cxFa!*I>lIT%*lY8Vvc{{Q6OfwKO&rn}JFs0dP3*$5j+xSD zc@V?xMG@P*K<_t-M882>_$sh_=oo9>GCVJ5jP{L9zg&!ub+a0rYiDQ~>P~areE=Zd zYSkvttN$4!-`MAVehD@E#DS%|Of$goqQbsj0V59!<^dy<2-K5y2OC2RJMg;X&oRGT zUt)FL-?&Du+9>R#2eR+Vz+ZSu{w1XbEQ!wZADDCBrgMQJL3R{XZ5^AzqZ@ab^U2jP z?rG6l5FrN(vNb2(IS7Wr(|mh4cN!O8Vi53_e8*jyd&UY|$Oz7XY*48(x?O|Eg4``o zdT_pbK8N8zoxaUk&?*=hE$BpYrz$l|QUKL8i%^N-6kTM5ck(J@DN=9nfYN0%uegc4 zog@^56pa&CXTWmTc%Z~kX#Y0|ukB{6t_TZ3?^#kL_cxp?Iu9dMIy`(@;uHKrAk|er zP^7+bCl$vJf!l3X44**tkmX2%pb~?QVc(=tyfyHT3N8V2rMF zVkMca^}4+C(T(j6$vnhQ`x{`JC+<7DJ*4FaN?mNZdtWSC;Fhk0ck;bO1Kd^B#`l9Y zk0pvXR|>I8i1}hhnk^eCs{B3zEE{B)M|ID|dDST>B2wl;p$c3Qqe(U5-?BB&pPRJ5 z?B5JZYB8cfm#MGBAG!FEEvZPid_n+7*TKB@n(;YWU59g zgbrOBaoDL%UtJ5EusD1rHou2V3Y#F*=VxpxcGe$KACj&QaG^6{55uBCq4}ML)3y+q zRE}J)HkAtkME&JhopjshwIe>+iXG^!0eA_&NFtHrJbl`g$b-{`KL@oulnM)y`g5gI zdCQ-OVJZR{TF>O+CkBTTmeoPx0ft2vRq3`13*_FTjIl)kemx2?x=L54gL%6VY@CU@ z&w9|nN?R$_jZCngQA-p5xD}bmY6&@MTtca}PMq{S>ErY_CZ5Y9r~Dl0-rcE@`L>e7 zs9yJWfeuwURQQX|wOt~89=-&`xYi6Wzk*-x2iHosM@1yOSfUdoA5q3jsZzgFxNsblj_C6Yz7a?vQo;N<-JUWtLw&Ji|$Me1z|Ng^YzrIBd=eWFg!U!BH#^_=0Y}qLBqU&Q&xK{ zs+7rM1#cVzEwbA%byJ&zh+ir0JW~Lpwb#XBdAgJw&5;~L4dgboD87!AszzY%KDuta z^0ElG57q~l%0Iz;U@GkEnuDQW8^q}hq|gtw1AA2$-#lvIn=vCp*r@)!e&{cb^9Zb`cF z1`!=TWP^`UPDb;`6|S_UH1qfaFM<^wZ^DGX)1fnEo?b9YpTA^2xpjUOQ+_nIwegYyqv#*Ez*}tfI#~mk5;hGAWT+(^9>Utf)+gGs~A?9 z-SPHGuio|%e}2BbFezC`VI=9G*9c>l7w|oqU7e~|$u|ny{;_p$g(X0}HVb`S&uBcd z4+anQE!2sbXa-p`Dh)1Sd}1wx40Oh3p_E>}{PybrAH>j0C9c-w96G;wvW0ZUVWrgG z(t@%BMKf+b#aM1*3kk1c3RC_AfjuQ3>?71B@Nnh2>3r^ZY=-4s^{lpvO)C`VWwNAd z02oG6)SwY1v8%*t!KZNLG<8-PU#?H^uMDWDbsYR+L0rkxj#bKh=R4h)z$QW2#fla~IsI@%=V($9q($G-tjv1)e zPSd7nc=5W278VFXF@lFAG|&$^~ykPb~TmJA2{;eN@2 zmkC|e-tE4Fzf!RIn)NE0Kzb-@zv3HMX1B$`+*-@1bDiqNdyzSb(;fmb?8pMZhvXn@ z-O7m@T3+k73o^Sr;kJwO&AupfuF?YJLBSo|VaSHviYNK9s6hil=;5&G8el1tht)a3jLc>nl;pF5ZSeG+AGY@mQ&o6Wt-Pwf9VIq3Vn07gsx z#@82>cA9KIl&m-sr4^nD?ZfW}@9!rV3Tb0Vnah~Lut&$xPg~^8bFKtIQ9VOrM48~P zG84|ciF#CG0N~j;)~MK}Nc$EXLLV%oU!8+4WGNbKCq_LFgC_lvqdfpO6hk-vQlK;K zZd576oO{Bf`tNu*5q+mK++okBX}vlv9I?|2Nh0U(u5KP~4(082{$;6Mr`0947k4X4a)EDl{1ytYr4^njpmYsu56vf*VaPz zvL;mZHa2!U&jB_%vR~IfmUi^8)Ye729tN+h4b^ncpgE_KQqYsr69G=UmeeU&yJ1exLpzc;dB+EWfnC}s&%oBAtc3NVO4Y$?Vv|dWeAmN~a_6K8n=2vP zr=W@~WX$&NuB5fDqr*L+yNz%JvpQK&2F8X9Y*cypjp{3=V2Lsq6Q?N3t`{PTH$QUt zJSEJsId9wV$KTch-u{R0H$T?CU@3MhRb^Hk0u*PyF5w>2A4G!)*416h+1V`K7(9 zq*gilyM)o|Rs^z*B-zzuG>hpN6)mnvyY#{}Zj=2x1XAhR=xJ@o<1)TCH=>3A`e0te zRvrzbbSk$?k0xSk7yO|N?uCw5+QLOouv@Uf+AK(q=`i;q3}_;|wwZc}1A*lBXvg9K za^b>AaI~XQzsPM%f97&l(#K32tYTp4#K+F#s3$rZwsdnq8>0Ab%(I+g+pb9X6uH;y zs0*8^(w`Yk4*+~`brfZoU75_x3b4$#)acR?$k)0ML@PypDhP5)FS zM@EjVC4Y{$_g@%;qTL!Cs4dl@)wjEqM%_gBFnXgWAxiS!*Cj|5mh&js+9}KMgEVwI z2hAa!W~6`-@ld0$PEOzTcwGgN;0Ng*Pa>$z&~1tJF1VR*sg2Ox*v*aJgaOMaf94Y& zINbt>>*VnS1nd$#^5@xBaCgoH|d2i>2mh+95Nr*;xrMVPXWPOmDyi z6yGqbW|xKM)wwX==7ap`TbS)~?u}u2A86j@XDjaM=#mg&JO9W%Nw(!4ytg{6C`V_D zopV=~*pkPuRP?SO3U{*dW%oJUYjqQR2vP69vew4!WJjwG@?)2zi+CxS zeNpOfe%s&D$*1Xex<Vzf4}N|w-bNuNU%GeS@Y)Q@!&T&}-zC`lTq z<@effM>1Usu=p|!5`-xC&?sz#m>iEu=C4w#xy!O2_)yCnG8v0H*WxtMUQP?mZcL*A zPVx(^Go|nOkO!`M_l9%;P#odz;?hx6AX~kA(o@#p!bph~rOn5Q`f6=zoO*wyutowa z1NjncP=)JO;Lxn)aF6{d!1InB9mo69yfkm+6IK~p4{{L}mlIk+c#qsmIINrSvIm}) z`zn)kCG(${~Ckx?6!J4=K3Pw@ACT<2_Vs z#`A~|PbU1=MTVFo-W3tQfc@vywZa)ilYTgX6yJ|#c)CewAq@G|aWZwZB&ou=;@EkxEl%oNJ@up@aXLG-HCY%>m9Rg>~k(3+AV@pP%ZRh5gmF zXBLCF@GxAl6OvLsDc+*s-9TyA&Bm_!YbAVHU~XAR zqY3Nrb4X*~V{U*0J{n755}T4UPA^?BmQ|ZqR~ha;J2fsM=RogVGgTt93l53Qj+cwY z6NJ`m5eD8qjG{i!ZqUcHs6%k%*TmV{qPt@b%_-h2yRZXUG96}x?Hey6wIFYu*uC?o z1a1cw++;WzwglPCKSru%g-s3Xo>U-17TJ;z14TBf7UVK(8;xAjEgSJN-F(ofw`8n> zIKC%&GvP#|{g4U`N>4g5K_w;m{-rsF$`yyG7hc%bn-q$I^8sD03q}O$Qx6MGX?zyC zuwKV2m@Gr|6`aQ!pQt$P5)G=f9e{S0wx!@98PM=;#3=U1EyC?c-*a0SKWH0ZOep_v z0=M?tr}yw!^nwnY^pY8F)&Vk4#%SRN(Q?M~dL?vl8%paVO)1L^P_6S z^N&(sn6qN?LMe20r;14~36M#yPJgObDfZ!g@5(!GiEWCn`wJT?OZgmck)x|tI9KjY zglFcXW1rl#<8S;}vO9Co&ucC+3d(LfR%f;Zo+|Fsw#jg4>TWs6H`2PCQ#9e(Us1r6 zlIpmZPK3oD>k|w*r-k0+GL7X_p@qNC;yW-7Y-kJ-uR$`0yaWc>ZcKr+dOpylgqz+P zqS37XUIFYX01?xtQ4{;9i`tj0jmK_q);hgq?VOPWq+>=JZFKFEX4fBiNSV#o+^z46 zLRr3#in8qo#kjFsHEKq4Q#g_ziUkc`WKHQsmggbz7-5&AYF0&lTGXV;jP;UOF<`HR z^4QrX$HB39EiH@8x%@`H8Y9?F+aZ+%{C>K~BcK;u_rMX7S&(e+FfAztsY78;>d|~j z;&_r>C8~Ku9+Ga%?e%aqA_~=$(pScaq?#IAKv9iu{@h#_H;?b4<3!NyOEY zO(0Ie3Sx2zYb;?fu$6ZVvdNPy7Mxo@VHo>7Tt2@&yJWk+7>gBUBW6LC7a*ti{XFn& z!rT&!wKIfE;FaD%$H?`a8tPoIn$cd!d^~Sac*#dL1M(`z%al7uanh@_$?h{e(X&K3 zY2EfkxK?*ePmfm&K0B1;s&i6jgjE??x9`qC^1U7bJv$W7lSZTE|jI~OgUxY>{!#hoA9^?dKO)5R3HMRHV^!2L)}Uo?|#b5I`OGJ z=}he%5zBkv1-ROFbthI%{^ydGW5fS2hEL#ftbk78!F!uQ^s6*e91%Kk2pMAP> z%PDrMOH;<(yGIo7kt2tN*KngRz1)33jWY-X?yP07vAUnjwG%bb9hVm zIy1emSxp*zbd z3abtz92xg3=Sd%Jgn<24AT<O_Me4ud{b1}jfJjoMy8}he=Qx*o6AKNZjpPt@vURk zU#>}A7|!&;2DLEU{hj|(e1`~pFi&6X?6`xr_STQVftG+x`QHQiVBiaA5FTsI=XT&z&7tRwS4|3oyJ0Ew`lppw%jzR zH=Mt7xHVjHp#8Ln|T!KIv$@*e9LHS6MoG0*t$+l?I$# zSkqtzYXpj|cnUPZ(R+Dzg8?5E!v()SN~t@g@JI=Dh<$F1`i!%bkIX(w zgl_(*QnxoTw`Jw3%To%_K5@sKI;c0o$J$LF$?{VZ4GtFxr`3_sKKRbM{Gnw(R`%3g zP6!AdeSMy|hewC3QDgo?emb(`T4*H|bv-Fs)K{0jgBL(nofz#1GORDkgb)a~o{CWE zKrj@DCKVD*7?@S*XYi8Ihr)+`4#pJQ$*wXIPtmwlqKLk8}QpDsHKC$ z2Q+-6)$oxhAAzaX?e_Wa(cCF$3vaUf2m?y>QS|yeF|2dAm%4oAL&_wvQ)5X;XKi%6 zAXx{G3vg)KC0Mp?`tDEw3rlD$5C7^D7Eaewe`i|P`zA$LH0fEQ)VZFWb?DLadhsy= z0bdiKny#nb6krP1d1ABA??AIE@tjgABHXQp6(Jl=_)q2&ddIjj9}!#)n?gkm`iSA& zx}gJZ7*dHG@}EVF6D0>A*1~XG@1MaOknvlbl|)K}oU$zUf7uB(GHi?s!LeyQCX@GX zNA*+@=7h2vNZB(P>}FU7MG~zd_=*rO(l-|FQPH>ni2D0AfU+|hj3bMKc-U+T@-JOb z2-Dgw=TaS46A!_hnBg+qYwKvd>R%*U%m0Ys1}{X_wbX8r zzNPZ=c)i}&A3V#%%(^?#;9CSF9;@QudcGZw>Q}r&C^IFa_NoHfBul)ZJ5~+psh|SmmoAM)+&&KO zbrr)R!hkOH^Ljq!ajO@aJ7VLdY3Z)z`s?7}NVIE5=k2eP0T12ILlmN<7Iq@_G~gt;j(igSvAk#&D~8i!^x< z6(Xt{PJsDa>YwbI?!Lg>P=d0wB+f{=FVfV{hV{|buW+b#CFP}^jocDslLtFXM-3V@ z&(ovX{VWqe;HEPHj-#fs9hJ>Up*}56>@#IO=ylB)iN+K%+wiBt;ds8P;*0TS0PEy7 zOvLxDFbyXaHo3%JmB|!n67J9Sd;r`gSqmdJ0ZW7O!0H)j+4pA36%yV;uN3FA6Z)4W zv4sifgK`js9+sD5_N>=d&5^WbpsOqQ9=R;-Rh|pdvcs0}E1x=_cgjUkn6V=gQ zdfXf7eY*R@r1e*g`Z3 z(3;{6L1a#Er?m(4pwOW{>msZUYq1sSktx>uF0yE_xI6zBVec58*|zk1$F^-d9otFA zNyoNrvtx9uj&0lN*tTukdDCn4Ui;bmIp@6Bl@GaUjETFdMvb~NGkGN+*H54jmaBfO8UEa|&bxz}x79h+PMJ%@kptKy8eHju*1o}02zm!x=lQ+sU zAOb{2fX!1BxvrlrEe1l66_skNjGGHo$cg(u5`AW9iBK2Jk<>vYqmNLayAxt@(^BHa zv&k$w`g5=f!)vn-QN@z!-~x2B|*RS$%}1SIdxuO)%l^7aMCB@UzcW6z_HCC z={BnMzK3RS?=FWH%a}z~uf31Lb=Dhvd~f|F><0YY+$ycDtu0>Kadw)9bMu-bGG_Tn zlIR;u2W37GzMdRk&&J}S5P76;G7;D~8B<3+H0W~(-x>|dAUDA7gjmWE z&@Zz)AjM@S9&TnjVx<=!*DWTvdz=nKuDyV2727!~0l-Vu0j#zsPLXb;e*At8nn^BF z9x!F1{lxKfVOh-TfI=o;>}kL{i)(>ly~iHBYL4E15X*R~2doH>?$~qc7MK}I@|YJa ziBst(^zgi~CQTrgY1M*>*9eLn>xcl{_kq^5v$_Z#&F5N1p(M>_F~2tr=!Z^Peb|2> zTsz@Bey;PyxZiAZ1137q2G$uf&#kvYlLL)2b*tAqt7a6gKOt_?w3!j}dkI|z#kl17 z!pciONRVB2dWVzYriBi|Cth|Zf8rtF7Bs$1!@7{?UgOB(TB&^Fj(wjdQoXPXXG^!C zdVh))NbKW74(|}y3Y|O281NpUuR%E$@W|P!oi-e+mGPkj56xQ1sVt7Yb>TI5@Bvke zZBqk-Xrlaf*!2QDrb>I^&f*Z&>-z_&# zbW@h%)Msa$la1*3q||$1lx_oJH@^NF_KSP7E-90wBWD}oZNJMbjGlpRa-%Il$uMv7 z)dGfyMRdj&xg=t6>43ZF6mK8KIaQes69kpY{nb9wf;6+m>h#^r>(x%3a=z%HE}Es@ zXiO~Dc=1lM^pTYgUsgeCVY>)`ZSZ|=KiU3vl>R2vRubB}!XYlY{V0zjDT&I_%{?>t zmPgD5|5~*2hIgD>7o54}XER{thx`i^ECF@Ib^#0`Nx+ zj^qU}R9!gP_z41qhbZ>;+=7M;_tZPUH;L3r5EKC_TaM7+XPH>?8swTy4w+vw!K9rt zOBGBF)b2c;A1@C6kdlh?fX5fQo^qpKN%+Z=#y-Sc>slmd{ZfxkJWLNBo#f3qdihQ7 zITryjN1gY%3WD#0IG4Tr3W~E8UtZZ`v=8;`2Z-5XUwyfs#!R3IVu`Z=0oixeXz!t45Q5ByDVh6xckGuF|)v zdMt*W4lyTNdLYjwpg%RL8Mlx?BI==GR;VZrdi6ug9V^sC4;%EbItklfjuyFSi>IlGDk>) z41Z48@Z#htQTyO9NzVFUR3e)-jrvKKi1bd} zwCZaoc0i?)*51U7Y23MyzKZER90OeyEw*N;$n`S$s5g7en$4et0n^_zci*|vCrDlC zVImvs6+gxkPNW-2Q;Z@)WzU z`FyI=ZqzNQRX91~f-7(Sw8n%v&c6?OuH`D;*&xuM9v#!ZW<}q^t^=V#} zXG=#+%}GUKTzulilEL%}up_o^H#lpEB4JIB68hZ;af+{m!th4E7q-3}UeJ+#dmR;+ z80NtOx4bvM)4d23=3}ef`|>{fp+`lW61I2^?vPF67##=Jo59`=Wqp7a;aO&rFMD|` z_JBze?X%@}Nc`!S|=(--D;k!^-9o%@7SRKDF|wmgZI1kW$ge#oh3+-SypI=PcWP7^1` zi{Lv1CPp_NULp729vtc+&EGHTyLzD-OlPCBPL|h`Nqh+6FI!<@kog*U;pYNxf;9%4 zwD*09Digfp`!jsy7#5l)-0)YILIwKUmy!{sF*s~;(viWx>aO?<+1j=B4Y)wSvoM!- zq4Y*#GQSv}oRZ!>@R3K|ypZYjd~8_ua=!hj~(OL-_-ye&sB!*M>bAr$oH)cBpH`>h1 zoi+LJ>A}0HID}uERY#_-B^hMEX$&n`6qZ8THOz9oM3vp0rf9h8C=IPYya952;g!mK z@}zeB0$!Ir4icOf1!ZC9gPN$hA!xQH$8tN*;ft|N-PrK4nnr;qro4j85^>tFc+m%r&ZSl^H}SZ6D^`8sWrd61~44ndQO^hAUY8$ zfZmEZWV{OSfq3|+{N3c*)*v3L57O*z$?17oH+Ohgi9Lv9#%{Ai;iL9-OcWaM-ah5?j1Q6=e68Y$xX67#qceBhl;BvMg*EygCqe$X$NCydPFZ?h!K$DH|aL{ z@BE=;Nh2O)7X6`0bZl@YZk6(WSf*~`si#eZ%o&M3P}C!PZA!0+&S6_1c%{OFq1cC% zG*rFqaA9-Scxl84PZGf-Y7^t^{v8^plj!S^*)N3RM|P=4K+EFN4eLH8;WqX{Jq)<@ zxlyXnmc>0~MvSEPJ=)4^MSx~q$&j;MYmVRmIb*Mi)3pX2H%0DHP9}(H$sx6 zl=Y3Tp55Z$LatO<7zZ{F5PUDY-sU14`ZHgLEQSEi6E7bcD{rm=sh?>4IoC-JPDPIB z^OD2eo3xPgeCu>^dCWyyK)s9SrF&SupLEYa{E);Jk_vKilmUYGJg>EaFL?_KilNg| zRq=5F;`jG}6o&(kyiSObhSP{VMSg{B~He=Xq$Sy+>Hn zdBtN>gHRI|0E_^uf)@gUw$s-v3{>A27Zy}abvY2DU6BSlsL{AHTmW1p=W`1H1;gH6 zV`f(ger96u_!rFv@DiZK-xy+(1fT)9331ZUzvy2yoKF(X|KHC7cNkH6FvKj{Rd8GR z;8J$|Fq9!vOQTCPfo}TLCnpmS>yvATQ3*gcpHgIqUO4xYB5RqLd2TGUv;awX_iWwS z*EF$DxD*rU)DQCKtzgGIlu4OTnVJ0?Sns-^+Q_zQ}c9?a)n51HO513`@8BN31! zG(a5?c0h2pv%^^0)4AoLzU6Cs1q7^nG@-@UiEJY^kYfbrr-&U2oy_8v8c5l1p0`ly z%CERNk(1d9F9cUmo7r5VW3c|r;Ppb)dE|7hnW74wJ9dw*UyA%3-O#*2Ph5I7=XH2( zM4ioB%2`x@HUA`F-qS;+oJ?J*JQCO5KN~YSI1d!IN&J^j*|I*FK)-dA1!Vy$9^q~a zzcm=qevke$+~D^)%JRt|72W{s-+f@WFMimkmRq*b4eg}Y#Pd1-xVN@o1vFWl8HhyL z!`exrs_**yNI>z=1Ap`Jg#Sg^{vAWh&rv{&zxa4Q0Dz;lQn*L}(2#Hp>+?$&zQk&k zMd57gD5a3`X+4lw>*>xo+5XJRiDF3_OnGvFXKrpuPKlHe$Gjs`jjZA4p09Vp&E-%v zKZ%F^JEI)J44kIi-&?LdNW#7s9R{jOVRuhusaJWsXdVOY{mjSWxMZaNe7E@P`({>{R4L zJ=(J`^&I2P_T}PpfSy&}O!&8(tMUf4F;DgLD0sX2r_dfWdQE6QWOIahQ8ENSP zvZLi~fDr4HkJ#10ccV>LO7~eL zl-G);ih#K0D*i}Ks(I(XdDE-CSD5gr)?hxKq(p-~QPGg#pPlr|@W2r26S;*epPoxF zJe&OEn7=4#e+w_u`T(fH;c9xiA0swdQ2iN){2MQwaU}dnz5AzH>Hc=yZ+(qVs}3GQ z@Rj19L0tLIg`oEr^iKx>K%9*kNMahM)qt753!M%^x93BBkTL<`wMi+G)f>UM_xM${ z&6v{kTs{a=BFDZ%5E0|9CxSQ75I)tF?r_0S*79cMXnxv{W(Nn_)H0jie2WE)j|p`% z(OK(e-WGjalXBSCOhAN^_if2pq#nx+mM$lp=0S)5JG7p48va`eC^xBk0{hs8Ymkgo zC=y3nK;6gEFSj4zb>L?c%VHaFfJQ;V#US`!dgAdRV$h$ZFD25`gc)yimEKM8eRnAs zX`l{az8(%O88Ub_N%Dsil^!+=1=0IN;T4zVZJ zSf&p>7DFaYzMn#EIuv>|2=Lgqaa zsNOa|>y5KvssTJ?6MABx!*OTsDH3}*2LObVZ<65Wss2iX9pBGmvH!yB(SLxf81SPl zqAceh{uu>;Z~7emjr{$*5;w50U|S?3teE&9dod_P~Buh zx|#1xn?pf42Y}h?9{i%p%~UHh;FwF!-X&L+bT*_Waj!tuj)19n3 z_$d{L28GB*Ob$f>khMmM zJ(d}^k1#yoq%ftkFKv6MjvW6|cYAFX;LtUQn&dFOAz6f;z^_RxkF zkva+;iAd{%eXpQq)7jt=5=XTga%&}wMWt<8HSyeVFLSQFF#;GbkV&6qc=agvtQ7DK z*!E8_cnCf}?I&3NFKRD{2fHqj9bsEsqUXCCS9LXJ|p;B1mwRW_?b$-0lo_V z6LI+||M0o+|D^%)PYmHl6z--K*StbO0cLgvZ&Mx&-f31di}g{-I#^fJ9f7xOE=TD} zptQi!cRNTsYV>M~k9zChgT(B#be&S1=#nAWYLD3T)Hy-AlaN~x4o&3)_YwzCyO(^f zG4WM;>J?<}<}T^UTQ=1%nnFZJrCT_DdFrUlKkmbyA{I*ZL`Xp&14h*)ho zdbEIe(QFuidWh~OT-B(cJ3|Gp(P52`jmf=K@+Sa*Dt|@oZ#k9!OVob-6}A79vI^1P zO3w;NLgdafSclff6x%*+@HxJ_gMUts`B}UH82T?D09_H}3s2W8~IaKEdUG)enfLPxJ3a>Oa$q z|I_-Z;rmCNL3UvK#{V#2j zPgemV{lmij_s8wM#<+wR!$Nu$N$-SjlaZz(DGt>>s+k6Fvx&G!Q**(Nni1+Ltxk@@hii$u@7yD}&QJL0*}R}sfwqOF4t{ayxV zml~gs7^VkXLKk}6XfvqUq5ph0W@#YGmSSE-9*VGyo~3@~(+uVH1DIx7DZz%jMBsmd`&mp8_}zKAAyJ>KjzF-F@`W1oYZ9nKx-;P|f6ATe4o%|zh}B(M zf?;!OrcE`iYp{Sf2HN>ppCsQL(@Nfa-nGCkFfD3MTb&r+THz$y!BmnbBZ>W4NH zjVMCE4nheh=$q7QXN?#T|5 zqVLk5GXS`L{_?v9|CgSaz^8TbA8_#hOx*wXrW8l*aF^(-pPlG)>AkQLjtBwJ*pk8h z;k3+sc?4%*??ouP=J%HP`Nc#H&Aj1R&tv16CKTw3$^{M%){0xB9D{|!lt43Se$5!Y zt<8JT!>Z(Y2?+X)r&t<-+lNVd3_IYt5FK{p!y&iQE$KsL)0f}Le^j#U^9@LUi!>Eh zvstTmK{EdeFch3FZmz2g8W_Y}nV3|DNTk)@qci$utidn82c2BbKp?!k% z+z7rMGGCBh(cZx$JT>7MDmcQxQ zWZE6;>&FZGJm&ry(5(`&fZvB3mUEj2x#trr#O=|>Lw6?hk3OkU4;DitQ#;Xc?}7ym zT-ZlqDyz)sEG$3@)3Sr^m0unC=6iKU-F}^X=cnt=Io-fDfserDlr97Bjlm*s)_KbF zODIx}wWqm^^6O*CyU`6*uVI)7DO3-3P-NRgA(%K@v3hCq>8}^a%>oWk@M zmv|Z*FJ9&Tn9*y2DBfA_u!PVdUp|xauUdTjdzF7S5edJ=Hvb)~|J6hg0cJM*ZWoY* z7&Rv`>`&>4lryzXdSjvf*?8nWE3u+LYU{s)^mmt)cdY^7NlB5ggGn!TTHpu;E=U9D z5=WiM)J}@(iN}&guY!t&=&n@RLjV?z5WlRqZa%@klO}YxqyV=}<%EaSdkr&|@S5p~ z2-)S9Z1{}SgT43-WlH959r4NX0CED?#rsio<8J>L-;Qn8*mT!;6f*P z3)!BUobotZD!%@FyvBC@ktn#*CFywh+l-)KA1>O{#EwgDOr)dDjiPRu0;oG{TG_JL zYEnZdmN3+CJUa$t#sIut5R>7EGWB9f^|w=IA-TO3HcBy==p<={PC0Rctg&J;o~-Xs z7E;Bu*vp5xw%fYmjlG%|8#d$M_}{lrA_>>y19`%I{{+bEcftK!OiTX}pw8L?^B7A4`pTA4D)q*XEiv>_jOJb7k>Ng)2jc!tTZ$NKTVjWKKn4Q8GKju zz3Jf~%3nxP)RrZ>tzS*uj@c0lf@1L-{b0fQQdagMyfJ)|8I{lY&M5uD?G61Y*a^xL z3q=66q@qzFV*sdb% z_JMBar&Kg2eg4AkG%Qy=?Z6_|hzeJkS?9dCv8{W0)q)cac#9C5iNF>8Ejks<8Bl1M zp0R***=mekq0bTT+nR+SfTq-H=x8WTWLXaP*xsdxS2wNYVAXhoYb1@YJHu`aRaM7^ zk1md2=dw*-HA@Q!I*&&K=mohKp69S&vr1PCrJ3 zp$_cr*p-DO>)Sz`7g_iI0Yoh6c}rI=o!?cUewtSFnc5SS$9xwqdB$pXpFBj%HNnL# z>(}(~=YO|6+tjyCKz=bn!)0n;SI|0DjeN6j+zI+}7+DOs)}1^13M^B=V#J`o!zHCh z;Nmma1y^8il`O;xrr===6B=9rE*NKSHh{h2wX&lfrPg_i^3iQCva@cwYKRJ~d)qXn zuM4!S-VD5=E?~OlM85PL1(an&My7w#x=V~^n=!t6hsts$XA!WE7y_~1^;Mpow14;Z zZiRYRvr-edwxPBpx?J2(+X6f{g};EvQ=b{4!q(+!)u@hI|!F zsTa^onjlCl*HePLr-KUHK01CDxI-!Ll%Pv|5ZL;QD+v+b;0H#$#&`AFsZj7j*8Oc= z*^h^0HntxPW$%3?u>7ZwMLBJ70~G-Mk)j~WHj|JOJuKsFh+v2JNmk}5JbY4%O^SF;|yl5wQd?09*6TCa6 z+~lRcJLvBzRHB4+D^LPt;`XgaooNStZ*$mR?CJ2MGPT4no_y_9AV12kpPJx3gtgOb zy5{W6hhhU%dw;2Qo5AE|SkZ>5O*(<{$bq(0kdGqnXyS=!q>tK@Uq#KoW!};Ioiy~1 z4B8t0h+P{lG5m3BzstHPJziqL#+WY`CypTVo%k#*Ed=~tGaz#L%;BQDH^&hvH+9jLbq0b5eM(PuXXOz0kPE&BnI5NR<3nc)yZ2QVD#yvmKpoD zugSI7u0P_gY^nU>F+n^YV%Q$b(TkdT*W&#peaR14){Z4cv+N8$F)`XZ>AnQ^--~|@ zd25(e^6=fpOn6^bsNa!L3Ecsr&^6)2w6~`+x|I2ec0sQrp$0 zx?DOoB%W2IzQ&jWb-AJkTL~ZKQM`hx5%WsHs~WEhGB8uK2qFQHYK-vbl=1ndqEE;t z=AdYhpSUE?el_DHtm&J->yMUUW_7F@9#&~DsrG+T>>dm5&8;CKUrkUU;ngDor1la^>I2|~?{Ef6I$cf} z%l0bx+y+4ZwtNk#8(9-t;Am;Pw_+D2uP-=&9%Ig6(PLn~1TOW##6H&hKv*)P_BH$0 zf(!h($<2>Mlioe9Aa#$TH$xWrI&rElb+?vp3N_!4Zl9#Rec2o6wO@uV*Eh~vSMZ@ zpXSbyF}PjL=#03 zpS4u)Jo=h~pJ0sX2gFAYib_%H>z8rm5Z?G1-KCtoR`q9|glV`A# z0ST6hu+XDw7Mew%pgBssMPhY^j=+i}^DRE9_8d)F^!y-nSEoYW`J&q!J_KU8xS4VP zr(BboPHSOcQ*)ngG!I-C9-F1>m|M~mtJf^aB*QS7@)0TfxD36t)2#*~%;LC)1vHs+ z!J>k-L2l$-#hq&WA3ed#tZ0Nw?+itRQE*?+CP=DDQT8KbuXFO&*EGGkVEK5gUwAT9 zqFvIzXH1;yw5+VfS)$+@URdi>F;y}x$YW6@8uF^P<===(ffsD-kP9-2aLJG$h zMIl5j|0M6*U|PK>Es)vRIJ-zV83*?|*IFE8j#fT&bmJ2-#bI;o8I`7PNKJ$V zMscdOpL%dR4Rp>b=EHa$fT7G(AmgDuBSNB(9DHR&Xo)qe$^5hc&`04hcIo|a^>uhg z)Lqz%C7PPb(5T$NTV!Z3bKhS^+?xwdqyEK`Pd=ysws2rnVg}I!Y!cS8f;Hq zvp0b>tH&5m_lXP3(}8-}XYuDK)2$vHHkq+Q*Ka%-n0gH(?;}wcyzRCE5pc31n+s3) zKrL>sGo+u7-Ux}DOqYCKQ4Iaf`Ny-KaMG%*`0no%a^mzm{qHIcf3W9e?1Wp(8R4!qJ!x50VIIy3j zVMtbrQF!^?yCmJ?E&72%*s>v-tIZT;rI8+!5wWzceB2}|C+RaV%GF1I&T)b2n$%v03vY<*}$fewdfZ; zZYC?`v=9Q+MjF)M{6uP^8se%nQ6!7y<|lqOJHs?|I^!59&fhKDVm?kCG?C z8upx<5cQez#05VAuw3=f)68&ei37UR%iMiLOB>}o*Zv*#|!6zBSWqmDuIy?aPX*;t+Qd~ld^7?iM(^`wUK~56t0>~em>mX zSiF*dZD`$;IdTKezz(aj!XYOR+ z8-P3+V$$rVwDf=8UVt6fCehw1AGS5P`37D2qezplzW%jb(^_!AxG#de57+(t{Zvr_ zgztn5Quz#$9lGwGm(A}7B5YL>0V8QA$OfSS_qvEJ{qoNC zP68=^(;q)WBe8v|Jr@$?n^1n*rL5#i;Vs6c_#N{iPq1bekYhw&BDRJLp%P`}AKuiH z_kczMBE1FDUcBVaK8>^N3R5vyp{8YoWGUpO#c@hAwq2Tq5VTTT$n)!TJfT}af^A@L%DjMi0W7uNl(i5W?z$N+%|5_o?^sh>smhbSOc zlq@a{jLyyyz`$>xpS!o0o~&r7-?c+l4LL?eS(<^n#^C5>9vpTX2`z)WJ)5uugmz2W zgb<%msijuUn7^l>gef%F)N*UTV13*L6Mt(=8gQahAyBN~vgdi25-%N-+FS1Ka&qiB z$oM9YLR4W&>rncdVXQnAN|c)wM2%wD#8_T^3Yx-kOlCGU&$;AJ49aa*p4HEYt>@;J z?!i=*Q$)F!z4v&S4IGV_Lv`s3?+u~lu=pM{aFzEn-IQjUhORPVSMjKNW)(X< zUNy9|q@c5;3vs4c)ZjFji-UeL@TefS8C(34RYJzh0T9mRo@j#|j}W#X=RTUt3z1XT z0t(47SS|1*EC=ZXG3*2#VuJAR5Ag#d(<5m8tK9NKNd2WIFUEqqNbdGAl&QaJ&5q8T z10$WJIwR6NR?3i$$s&83oucL~bRC)D9}STS4p9@plpU=%M4Qlz#Z})8g}$HJll{zT zkPcu9ZIuaaybSGg-v78Wpdpr0tMNN3S{GR8$}kE3xktO%eu`a$GeL;)LPuAH4;eVt z-r(!ft_5;SXtelMfrYwhD9Qu_T^Qu(?i=B$SdO_nXyCLb!^S!()`EL z!A=OneA!X=&U&v&P^dXfUJw<8?2ZDy+%EvD$+T|-nU6K%Uy`r{EbT3q8NSd>07In> z=5Tr0$tsv(XVy2zHekY`eIBZ1$IT-kFccyL+zjFZ6p< zw5})lU#BWwQtdvJz58%o+XnU7vCxBM+{J14P(T_6(nNKwlZs5D5>E<<;bc_|VXQ`ph zHgyme&*JapeSSa~o)+X2cPgvfX&g02n0%UHxCF^ReRPZeUBALu`jH2ApthjlCY_j; zcfXulxv(h>M*KBhu)D*@j!odOr>WUJ=h8m}2W!TKK6BLzJu3%68g3j2=^9GY`>x-- zvLOm|HPblviLIR%H+9m^P>B0T`B`oKM$U)2E4Vb>7@W}30rZ#1_PdLtTq)(C419PkheEEWL(~d;g*L`6HNb-$HSAWBgylNuY-#yX!hy~a$ z{bxdz5^q$1+$bjT4@tf$BqLtq6-|KgUyaX2yjgl8W^&DRk0IyL^$6FMK7w6~h3&{S zdOKD)HO7{=IKu?r^H6}yKG1wlpoRIK#Rm@l&pM5-F=4IV5g_ahX|OteEMdVIg=1hQigu(Ae0lA`*b z8F?)&>!b*9)a|H@dL*j$55eyGx9a?kvvnC>c}!=8FP%~N?=1G9F%q?0NKz_j+kJJe zd;CrFN^3_vQ%&p(mhpg2v7iV>3y%ZaQi)g-7k-#&Hyhh8#WQG6u8W5B=bin1oj6;VA26Rt@Sf)`|a~FdWAVId2*i7Xl9A+QHi-A&gX8DshfJ zh%`L&?YMvYY~bC85Od&>99!F`(aCdrf(%1{SB%0nN1H!UPF&i`{|0)peihH|4OQpE zV*JD+x2K;^@dojJF47w$y7ch#X)|wf)40><8_)!Q24F$d$Xch_ySe3RJ)U|T5DpSo zG@@?GiXi%(!_}C1!ybjw1Ic6j=j%w=+Eq9iLcmf=bzI1hnY_C-Uw~XMO%03}Gk=m^ ztX>l38~Xj=mCAI2&n18bK}n6k&)9aqUkMHes@0nAn^pT-93kW2UIzAv$+{nIz%^mH z&Ik79`?h5Od!0H3C&orOVVfW?dJP`Mi)Ue52`(h!_AY0GJ*9 z+-1u^J?X1!*<%5`_Qgg#Fm1x^(a3lN>@t?UX5eP;mN=u4=* zXlXB(NZC0a7~pX-!&y*Vdd}C&?n|0cl(xABX-f8@J|wFU2XVxR6>~Uz)0lf&#o9I# zMCF3(dy=E2<;QEeJr}jbB#6M|F+N1vA<$7^c>NziDW|pf7Rc4RO#N8n$(|dH+DA|C zI`1$LA_cM}B&(*9V3_xCGWKhBa&Zd%9B)qxePxB;_sRk7We*ptV+B#P0P9Wo2f=p$ zA_&ERB{dW~a3~zVL#H8+{79~N#ipHX*`-dDjzZ2z-pp_#@ENEVY7WnMsV`O}uux4o z=kBVTX!?cbKA&FQ6rPAI6MkaEHsWzbYj6hny}m|H;$#z~m5ds4su@{2$(Oe zYufKwDa3?c)&l`9E6tb4?-=AtD0EzOHv{ccB$JJB%kvi&VuXDFEYNd|7{>`;YwX2{ zRFZG;5fs|=6#NG%q>Zz81gAOnz3m6f`W#yQX>xflxQuZ~V?$`J$pE9E9SuiEM2{~u zb}lg-)E-9?4p)qskCG%~13?}l0N+XOqY2&qauPXQvbW&8XyD~nYl+zoWFoz}BQ+oYU zPu2O>lPMn|e`}n+gVRU&EY<_;Wb~pd)%f$<_)RpUm$SX<6^dnZ0KCRE=>H}3!0Me`) z1YaFcS&)<|3|}1qfM0ei>znq^aRMMo5~I4YG1-sGdddwE;<$30Fo_6`&KO?Uma0B5 z9b>v|^hSjtS43*L4oq3a^qqPVtqvQ$&A1g6c^~-{M=9J>Y^Cf^l`oEZ`v4t~Vn-sLhu~+V5Wk+Xo}0@7RT2TP`9> zQJRY14qV|VT^MO3yT<-jayO6D2c}^0{3Vj60`AsDa?75YLLgZ?rO@##;xP{G!{XxibQx!B zx{8W#|67Z4J5C4HT;u&0ASEjl5RaI?n404Ojaa@fTGS*LJKYm-%1Ca_`OyyI1=A7M zAF6Y&`TAtF2ntTSE$ajBY9{cTwI^*I&v&uO6To80S+6sxIPfBv_;w<#ClX}7z_-b+ zFWYJ9Nu-nj2=yn1)$;*cSeRL*>t5oBVFa?w;RNqT-I^rxxkF*E-AVG@^!l9|<2h?+ zkAoPu++T2u-}4_=&+>i7F+P~x3+D+Xqun#d`f`5;5`|DCL*&8%10R*J?&7}V4W5mK zAR>uw$lI`Q?TV*6VQ)o`FII(G(3Rm?*1ZU9Vp(iX1kd6!*&a>7kyx$6_e4ic;y_N_Yb`<7I2XrXbv(Bo zx8qw)8{%3E$cb02I?c^=qlDSLg!_votP*cws?+abqJiUuWRNrg;$a(_iYYZc`68ff zkkl0g^nV}e;1BN?0K4Ej61PWx)CQ*6s z$(ZV#L#~!D&>-mDp0&?H8`-F#ZBsJa_MxZ6QPKjysRgc&pe&#H5@r#qOg76FPxq}o zyx@KqE+!U&5aQQ>iQCp2!SQM{nZa_3an^u8Di!?2UD$M|Eas*_HZF)MsQOQkxJB}&=M+wpLvemjg0K^@ zb)PaPIxazyS5&t9?kJ}R4+JmAaMVByJa%yVdpx(rxJghNMrU0m2OsFy4xG<1r$AfZ{Por*H-i$~>DWIV}z|6P~SAt3_{908L_6Qvi-;|Mn@x~Sf>pKya zD7ax1ls>i&Z#FuyxWV)=->{1bQm{BZooew~IC@^cMl%A!8}L)-Bj;oO044LC#4n;& zaC-|FJfyy_j6$N7!!S_il1AG%c78MaHw|C+mbm2$0BDX5>?Sg3IsrPVwG;Ycw>O^O z9fN8a;KExRbXDO#NvBF46k-xzUV^#43$4=k?6WO*lslm!slJYD5xY#77PIrTB z1UY?jpkPYwdk_#ps6mQ!&{Td$Txa?vkzR4v*iYfRk@g|vsnGFbGq-SEP%5i0T+>yN zhhnxLzpqZKSexKO`EBPz95ju)@#T?H%h1X`Y10b*%)CU8W0RQ8Ln93GnjOEMl z_!XNV#>1?iFb;#3qNkEJ6(+U&a#6%{_S<3=FO5eZuayBJP-<-nXo?->IyFp`*L`-S z#TdkbPTcTT>$(SUnq+Tv_X0lf|vLPkakLt|m8r z7A?XdfaH9*xBO1M#aB*6hfkIS$o_LSdH{DCv~_u~uIF*e=ORg6*}*&onEDHgfOBvH z&ly>ONI`y5$8staQHZN!jqZ5Sjod@aW~uTome^so;uFDmJ4d(?#P9`v@e{A=Wc*@A z{%`%hko$OZ=`{p`oR~=1q}zOiSuVTnD9BzG@}gsxG9RPI_sSxWRM+2X>`V5{Uz6R< z)dfbHZMy|uq~eZ%#r7_P9~OY%=rDkkfA&(SsLhg_E$&B<-nFYnV_xeA!B+|>xOsS= z!zf}@f9k1vX*E3oI=5{otz3Dp($$6$$W-K(97VW~7!`BWUM7<&vbW+mpNbKgcKnie ziS5I;uC+auru9Ofa;YDJsdcX993-Y^cL_CO?CF>OSQ27bA!7imHFG53!7T$qLWTX+ zZ}xC9CG67GHC1XZM-#O;xb@hwbfQ`FP>EG}>TF;MU}4Z?@X!RN)&_u8X?+}wKI1sv z+2Q~eO2mL1XJXFYO*?TvN|LJz9t(!r{$eJf+I)2`v0Uz6G{wXTIlUMqERtjsN$KbW!w9-AR(IPq%=}if3z+vc6z5A- zb0D72DW!{bFSqJ9#*^>-*j87igL8ZpZZ*#qQ{rgVym+zB_{eHB@Jv7#LZ>ExA8zfq z2I@{chlnX125ViLLJat&zW#}GO9gZ%)ZTK^nqk{EaOtggXnQX^)FdfQQY&#=2~+lw zbT;p1?>~+>f7oQlchZSBm8FtuEyZY-0HzF<(6tsEcRH!O6}AaqVJ>) zJgX-nQxHfhiqD;wc>*^BUFsc7YhS>azh%y>6uMAdQlkS8*84CMkF0oh+ek<8Sj~Cc zy(p9eAD;0{_Q{pbfMk$L^fo%yge%YI5@~FfLKoeVwRQEEYA^U`#XHH_VnHO~#&~f+ z_jI;8N-{#@8@BVn#aypPgT3xtHTvpx%0L&@>GYD&%SE#v-o(rc<)u38KU_xYQL-EL z>}>Jpv2NnHxFTo6&EI4UZO1^Q>|d=}3N_}Pm$V27d8A5>d_>--8Lo+1nq@PK%tHo% zCt>QoU0hWn}vsqvUy_xEX!X zOc)O-g%`xGr8RjuYl^k;$;^!)vuraxp=@-P;O!s*6*)Acyv!N0;SN(DlGL%vN z9S37eQ~$Ak(`pdV$!hufU?5r*`|1ncw!5eoTLyKjO-XwJvj>t&6hs`-J7x#?(aO9n zzO3mIFf0w{qML)?rUz#ZdAGdq6K0RAoQQlP=Gv)g1fO;zeradVAZH%hpsjqCA=~1C zMNPkT{5b9aC-?D}qhTi&((2<)vT#cGGMQoVi*%2c4&~A_9O`fN819V&gb>Jww~zh75yv81dNSRyrz)g~w)>!CEAu(gVI%*9uSQ zVJbzF2=~LXx*R`JJW`qiYhxtKx>=tjuaV(<3~6dW)s*y)DCFcOX#mW(oyJ7q3##V3 zHw>LTR$iNPdJZB_RTa9$!iIT<6I_m>o`sdBUrw_+U(I7`ALBD&jvK{VW~l~j&%kIV z83Go|yYLcP;Q3@p@EM!!X;Gl9^)B`%K*r$8Mx}>WoLh)j+wI}SoN-;?6*K4ps+B!a z!J5}aTFH#miQ9qBSPA|=?%pyuu4Gvk6_dqeNfubl%*;#{Gc(y@X0*s+W?9S@Gcz+- z%*@QU?eU)3o;~lqcoFxU8}~%?kB;hE1zGu3W>&BKs^5MevFMhm(+FnVKFDg@Y<&%{ z&e+rka#cDlQMiafP1@?HRS4Q+NxPhl^yV}(+O0+4?IGYcQK}189f_sL$0;w6u`Z~| z{p973>c*wwud`LDkN04$A+Y2z$VXGq3x$gq0bIO!1@DM7>_*H5;CnxEpu5rP5b`*ucP z`fj4H)oz8|UMI9STuq!k1{YeZgI&Y+&ZTKx@S+uc%b2@5gdknvfVDpfz`kul+~=j*V}D0 zM(D{3LPMt;!o;bk6u@qNEhhcWX60s~m!9GGL|SZiK^lG6hSY1$%BD{!2X5jrAZr@? z*_d+zC+9%bJZ0|DPjaa90ulea;dP*@H8`SFuia}N&jJfCX(Sqsz~^YaYvqxC_a_!y zDU(6;RVPC3n5J2|FF@R6mNuJf6(T5Aa{IZB2y$+pUgP{ff5=Y#X5J^75D**Z74ry3 ze9J5}MGilb2YE=s_fGr96I0o46)B=80e`l~_u(EDD$biB;+rhKyf6)q$#ZS4Hrgq4 z!d{LWxe=e?ke)PC0ztV;&I6Y!zJP8yAG++6@#AxRt{H0lo7^Bh0!T6@XmSHbC~$Ga z1%}!qfxu6D(U8_5v3$9-@!#RI)!YGhbKQcrdmtZDe^S*BrUwP{Hz%4@(SXF1)yxvb z7v4f@GiKj7Q67DXMcnE(2@q&T;5a@8m1gON1e-oBveC9ZrygC@Qu@+Tm+m9`96m$bc8;^R3V7U1E@KrVHBrw zI}oS(mKjTW)8_M=yEV_9Nw*tX`%0L$u|P;@P^rl28;Lw0($yo2IXZfuI{kpP09^fN zakV$Guq)4ntOq(S>q*O|SjQ8SwdH zSU{khe%#hn!4;I6Eo5jK{7T!oWY!jC?uokEQw@pgrB$LZ7LNK

EomaJIz^a+r{FTZ`uf{4?fK}{#4oSqD*PC0g@S(e-FJja9=q0Apy!y_W_^~YRAfS(2lbu7#SmGK`2)qCU1Y*UX9sqdt*bCTNsJ`T~C~cG)^ZZF$5RQiZoa_}n4k_CQnUu0Q zTIQ>i5|ucoFeu-$TpA9H)$~TE!QEc}DHH$wg74L|bdrUtDv-GLH)ENtM&SZ0kBY-> zq4S46vX?5ppvy`F!x&c<-dUCzhIZemjR7CAlJgOFcs(9h`F1s0$itFmdaXFp_~%%I z;c*}p#mxL!_Rrn$nkBdlnLOlFO2Z9YPmisu?~xDWBe7Cg_Koxe&h@M1+KB9bL}2v! zOLLAf%TNy!DbBz$w?n|-)=3qqt)ut*v20z)ZwXRY^cnmqa(Wr&KrV(6>b`5J9ZV$% zGP3pr;a3@bQ(bmhA~`pR>gQ0P8&{CZdeyDVz>1Gn}MJ?0vg zidMYAQjTcYI7PQbV1U=wrGV3Ogny{puQ%YC<4l1-ah6N5LJy3AK48C&_ckR0;o7dy zfWo8v2(f`RVsFJ-fq=rO6{x@mAXB{D9U_7dyuFD=nAD8`?Fj*==K)9(NVdQ(3cFFg zB(8q83sK!^-Ttcw4AUXS8krKqth(ib#6I@e+Huh8NDz-pu!EvwJjsnQk4r~D%@6#^ z#Y|FOKtSB*mUS6h0g&C$C(okeSGn#DQq4}YX@SZPGD0j1?ItoP&OJ2hB$C=o?M-n$ z43lsL83q!ZY%$g9ta=cIw*v(6PMN39k2ifM&fZcSn5iYFTf^A%6$090Z@{fov%Prf zf|}t1apP6)XHg3WU`Ye4-^ogS00TSIWbb-S%GRM*?m@3vjfK_ozFz}f#on;<^_R>J zWLjzIurF_d43I*HoO}N2jSam9^Su&+q`e8FEGGgOIKTcPo>u?0j>?ZeLqbjN5Xo39y#$)xNLc1CU!&e*5DEv#8*DpHdI;aU_nIy8~G2gln zp)*znqz2je$=>)n)RpFbT!$;jVkD)JwP^}PR?&1zpv=l|y6y;9jeC;3Ja>{G``EZ) z7rvxWQ0S9XPI?tJAxH79nwk?KSPfEM7P0DHO>kxtCeON$&BQwfGf`WAqBG96hS)Hv zSQIlzomZNb8C-b9t3xZbE0PsmqC|l{vEO`&DTn zX@ArNHpfJt)|l#M!ga&zlRr_3YK-rvOEsc_|&9<(%p*%20;A;C*UrhFnnvrg<=I<5ac4i*OTNLiqgFts7AMNocfI-PzHZ`gAj87a|btsCs3m% z(&kqlbV|RMCtsQ=QbfZZ$EeKFmcCXers}Epabs;o;MIqmh0&+@1*SOW+Z(ZdH^y&3 z4gt<1iC_4jhhdy83j`f#<#R>)b<&O+wDCKw((oiqm@|zm&9y%2$6tQ08$oiHZ#1Jq zSek5l5$CpkvWhIkGT$stTMTY+%oFM4nuP_e0`L?Ph{DPur6&EopYVJS82 zc)18LX99_hb!a&)9MsFG>6=eOKO<;oJEm3*6rP;@R3VhTi2?mQ?s9ehO|9bBiqEVR z>E!4J>B?3MzS7$H$Ie&YqCfJ;(fKprez;SAsVQ*&aQ_70m-oOKR6-d*&no=c!Vjk% zK{1iQ$esHmg}-WIS_A3;65410bpVR~>!aHa`1Z`7!uT(p1rc|Kt!Kz}ty+vCsEXsH`p%eowPJa5*K6*}SdBr)@vvVH z8a%=#Z*Q7WAX@^&9aIUP$nmI$6NDIc_s~Vx6H?wF1>TgK4qeBWJb_?;e zJu$WHpbUc5*N>pPZA|t7gIV&`?{hws=GI$capn{;r|B-XAy?YM;Bb4Lu;vrNq6|Mv z-DA68Bu9Gc>Me$0fiz9-sxA=u3O;E@%30gwr9A-6;rX*u4ya4wQW0b;ne!Aym#)b{ z2(RwD5EXM5PvnIB4n2-J9Nadrax_actL(}7_V>dg+!3nvxXf2+cp$1IV$xm;$G6_s z1%9}sIgxrr3gd70DO13pyjbq{34;a3LU%ktk6|g=hEsp>%argl;=}%g(x+#y z^R$Aef}NrFLvb)W#3qnrsNQctm|zx+%%wxtufJfALL@qBs`5-et41tlXuju(Nfro< z9hFCMc>0n{zIV;^AwUV^SU+YtKy5pjHj`-3X|)dYhIXpFTwJiq^%FHY))z?`Pg1!F z3>W$wVbW$ew6yZShzO~YK~RvVtyfo2`@&* zRh{szh=N3%##R*1{oqzIGt~3UGSelvoIky{#CQ3FoN$kWpr=DgA?pph5hNY(qE(Ei zaLSSm(g7TiztlVMfqVz4fu2y0Vj*6CV~_DhHy2ep>x^ zAuF)C?b_zYBFthd(tBWZ5>Cb5BtaW{bW|7QM2A&7^^^efk1P!u!(&8UT zd{uB?@*hh$yZyuz@Wz+rf)1l7i*FGvIlW*6;|9U~mS&esWLLRdHuG+ILDJ*(I4@>T zrC5Ph7h(U$*1?}4_k$`1XmkTrD$o#H>oVW_$GpKs*8m}p%)09zTZi?3=BENS6x-iR z0U5FY4)p&>H^*(e>`A&VsLqyzaq|KcN=+>kE-#eJYiypO?%!|`oQOW-`V4nb{`y% zr(!dRdd6`t)5$h*(cDpk1s-Ww+;i58(rz96+Wm%Zc+IUK$)#$=^1~cYOZ2-8Ov4Jg z0_{`=ta{6Q3c8WHXOHiiv8j}MxXx4;Uedh< zRo+MtG!lzsc;?cZJ4tc#5{?-NlM>F$sk9FxC8>W3vJA5Dblg z_i-0~jMiL&(Dc|iMa-Wg)YG6dux2A&Nw7%|p+9CZ2D3HeADd1gsViH+52|ZzKG4;LaUKmj~LLi*-D`=Lr%i|a& zQ>430EED=kqpC_Z61Ap4_*KQ(XPO$1;P;B5)^aX)uW_Z~r$u4>^w-5|7miu@-*2Bt zi;Tr5c$%gaY3T`>rxD&K1o9NGb&}7x=F^4)7sGm#uo#2j`3*Qxlf6m8txK-h$=S_Q zJy))#|L{X`{fE1`Yty3D@sk}@?kdX!A({<*YZ)z;0s?un^8w1t@%Nnl7U;c+%k2q1 z(GctmOWvL4d)H{so9@Tv9^D_!LD?I))N?we3|^R>1D-|!&Zq_`JqUNLI)MA-hb;yE z5hwz($bV${|0q_H5>_Pe1_A;Dge$;Pf9CbG2F@F{lYkk3a|h%{Xmi2fvvMg!z;&TU zvltn(Ob`TxQ?fVJ5h5$DY<_XJ)>_=M4<1_sThoF5fb`u^WVZ|3y?w{uvd~S1ZpGm0zQ95+O1lL`+uLI}RB?Fr`t?88eJx@u^ z7ZZMJ%#r#dga&Pq8pL8Dz{c1EDSm1|7?p|JDgaK9M26ChGj0}xYEJw#ULE3I6_*I7 z+P;tt`r5E>uuL{Kz%!7u?{{rs3JFp`h~R~s*X}*6I;4es;*ssi^uiQ0i+wksWN^bs zxe;L~8T4rc)<8>3>ZF@Pr||gGmdNBI=m zvfJA>cogfUmt48v$x;T8q) z3@{3bHJh2%Z`aZKMPt3FV&7u3ix@*zbPcl#cEy6y!^sg4Q;MI;A|BGG(k&CVf3wKe zFTKSf8jd5L58g5Sx!$NzfaNCmJFURB$v5jA_yDOtR00TyW(`n_2tX|WNTNqm{w`<^ zghcmEa!zGb${+SDKKP^iuZqI$fOk+m#45AKydysNG+^3|V4QS`6IsCzYrv?1$M`)6PDACzVPXiW zdxNi3Il2pKkf}L6s~)EVAT*;FWX;Bnuv@QKa%ZhuIZwm@1^YkJJj$edjeGZDPJEWD1W0$*f?Ch zwuGKGvEWQ1g7=cQ|sNKJB z9Np{4W=lRLW7XcftCq+5BEE!BXaRqwB3ube1R|0BG(m`A4QBsS0zlO&uu0Z9{RF^a z6wr^WIjd zT~dF)g@vA!(&o3}nNZXZp(L!r>D#M3U!ZdW_tAfs_c5gZs$D-&Q?dbx;0WK()t1zz zk4Uoe#c?vV`Y1b`Z(2$~5V_$w9OywTNOZjUEJNQuP)F+oZ2EylSTHNN2jEr~zkBSm z=p+`LH((%F%3I@2s`YoztT}`=DHt^|<{NoYPqS zd)aOLn^r|8BiPTcCH<1vtuBEGbn4Jp)BQ*EN-+{iX;_v!E;l860l1Rona|_-_D-D1 zzGloCz9b-psgNg1qb9h>ew|IF!EBo4L7&^p3DZMdZ?A4s`5P5P4(A+`xZwO7Z8p>I zd|}>V5b>FvAmeEoeTj!2^U%i0BF4w{3b0{BWw#>sVvhGyd8DdRwj>B;nq{@hb6VBg zVWO~NcYO(Xe?!3cDX)nP{?eduesZ{Ki8O^?yd9W2{GPiIWhiA~muP*}*gyCof9K3N zsNcE8II$*Aa>NqD5J+X!)X(@JMx>zb2z!&y$jB*Kzs|1ZGu=9}c=wdI^L9aRCY~Td z^d^a1%_qZ(d<#AhX58)%-FEB4zByFp88wW|c1X%z@ z|Nr3Z01%4(#@PWPWd6f80nR6WBkcfA$Q?2Q0`UXZvA)6w{4V#CzC-dg=m)0m6)z1m zN-!WUE8?Qp@XL9WGk=t7e(j1B{m`?!_s!_+O(EJMIHAkI)su#T?l$S39z89Z8CPOa zl&}V&;S?qu>>1e~L;Z2a{}%<$*I$SQ!ut_*VgXKMe*5p+jWFEfB8-?)>ck!nK%Xfu6UKLmMn|*xmaW52~Wjy+{d#9)eC%vXs zSawB+TWW<@4(q_X9>Ob)NxpfK5qKq!zzC1%eD=y3J27|S;gqGxaZ>CJ7~W6nE}Wm| zM}G_){fMeOa1RK+m)MZw$MDfA0K)(W>db&b5d$&E5Lg^|CNXcuIV6s#P4lFs~1}{;M0kFGchxw7p%k01o&as<#J) zyctdEW}=xub}4E2fvhD9cRj@d&fhbOthunnj5tJm18Z01+Rrsc`{mcXR%Mvbi2oH z|D0V0&3~4X{yZl5eRdF!U#@@(&g#PCySMQ5PvE$z$5%+)PL6=hCj{vUk@O?in=p1 zc^o@Ub)nsFI^f5eE1^)Pn31`<=eYt;uK@-D*bx4-kN-H|e=>{!?EP*S-K(sD$Ve1@ z@Xr8E;{RzN{~8D==(ZCgh|9A#;lbOYA1i?WZ{$J0_lt9Xz#?Lo5eujU=;ycX2f|4Qum11A2fm(wa6J8b#DC}!$@7#g`Ju|h)9#6aE->$mW_r#Q z13|eqVlI%Q29+RUO2omrPqxdI95N{gip$w6Wzh8SmZxdF496)x^M^M5fAClVmgN^Pe_u0zzW!qT`p-H2 zMdJ03bNU+s|D~_L`2#>dOaJE}4=@wJ|1JLy%KUfK{F3PZZ_B6t?}+)YfcM{xBN$|AaUI4u3a=KW#MjzvJz1@czT} z{|D;+g7=Tr0W|x&<@<>+0K9+U?yoib!=3q`V)Oo6koVtWs{ru+#f}P4qW=nb|J_af z3*Nu1_b*5FFI8#(saXHys{YSG-hYdw1Hk()AM|fjlW*GL9_G)fCO4ANL%lr(^qABG-OuMLYFn|KxP0P9Jno z00>SVaLt>Di(Bqz3Nb6<GNk!!{K`-l9DfB56N&|&(8yeTJmnAGGeCJM z-?}4qeg2eLI6I}+g1?Fg&iwfM#um9BR|sgOOXwoh&;6obPtR1N4j&%eBFjTfbF2#Tti zSINa!1ofgT`Uq<|{(bf7ZRrJwW5c1*u1DUNC)ORaLVR%{s4q<G%V4MUx3u*)~kcK|CyCsWD4srxT)czyhl1!uYfX)&H%^f;} zfQ;>BhLnDzJsvPQuO_MYslw=IMX~_zY^kQW#%e@z@_JZCeh1s{f!_F0J3=N&-|N74 zz%H6w&~gp6sIzkEUnaXA;fAB}9UiphGsKv6WSsRlio8hfD&*G_dgQ7NT5DD!@FRnU zpTq7$VzJtGUn4#^XOV4=8m(;QkI#PSxyUvRnm@NGl;vf=^F8RfAwUx&0bHGO85dq)8DYH2&$)e&dUv!wj_78w13!GHY+0jk@gmDnD_!jN@2zW{0mTquvVf z31}#pW1Sxq5yVU75ME#J)gRkl?|NRJ`@C+8Udw1Vk=`TkMR4tcOL!D`FzN*0KDNw` zdfJvkZMCZ`#-vU`#CZ9Ma@X@k5RwRvfnlP}?Yx2I1rCPw8Nzq=$${qdq+p z-K8Ki%@x&!>B^RrN)gM~AAlZ&yM+0}f{^>38$l8ajlyAl*7F)1^Sq}!RHL@{Jg@ui z3C&%MF>45<5u0^Jvtj{8|K>vf`Du)jWWNnVQHHV*Z}niC$m=WGxc!sqhMWgDW)T*@ zKgsMH%`p5;Z`DlA^aq|cihk{SrocwQW~M8u7b7-UmxQ6E06oQ)4S@N*Y3HZQ_#ka-j>@V$x$a$*1eR)mU=yxl`b9%qzlNaC&&L0J#kW%2_ueykpFY|MB&Hp}~kgg@!h_3SP(XkWqWTevX9IHndw;RSgJ9Ybznt^HpI! zFXmQ8(lL3Nv`IQt8*$WAPkeo$w!G0~T`Xgc7U)EZXHxD{w{HUP`~F@ZzJj^)kbpz5 zoyIIbimaWzH|FxFy-FklCvLDVs|am_CxO>APoyzc4n;IRD}3&wAjfOnHjCiu?KxGN zUn(Vv;Im%0!f=c~z20lb+1c&sr9^zBh9y;v{f^8V?XdpwGt%>Si;k1Kwqb_t2?MC4 zjouSrXw5-^=rCMsX__tUS}-+6aA=EhhvE^}P&2IW9HrMxv3A6rVQTLhA>>eZNIzXR zW~TDD$j`i)d}Aeu&9GVYKwX)r4p zHN}md!QRsWvLRdC(FdX}?qP=_ftF?9Ft!X5lW?Z#n89A3Svm;0OSpcozCM+8j~-5z zKXW>3SU%yN=8TUOIKCv9e{tG{;*8QzJ2T z_L{bxo-%wo$byUCuG0pO(|n)&7M()A@Pm!}<}5z#^h^vkxXuy0mEG-_h#Z(2?D5*w z)PS5VhBbD45^I!*-l04C#F<~CCib0&;5@lKo9Fr1LVWEY2{L>n`@{B@vUuSHR4cgN z;$DhGf$S#!CDmwLb&4i>?q{%I8cc{#;>Hm);Sf%7&rz_#M42^xSa)5FOfQrk@JlO$ z@e=9K{UvN_kOdYz(-!^k=99OSGfxA&V2LN77vn<$hcBZbSk%ZxfQw*T0e|d(%m7}B zLgCey#`&Bd-=7Ck70Ch~$V5f<5Qyq({}~*)cCNo?^h`&$T~*a0tH ztxJixn3K=qbYkQi4lZ)BzFg@j~tuy0r zmojc5HT_~FQ2wu1XGoL~+|nZoa418L;2u(fxna-ft*iKy71<@>_`}!y{AJ@qH^Hzi zx68|#2ZSHuKi}m~MabqOkXPQic~L^`!X>!QuinW#ABoSw2$lkW9mHw!gjWpIyo-kC zcom{JD^gf{gZG$!`sK}J3}czub1wY{v&-a^Yra)yUIl8C%0-`({Nd{EzLR=9zS*YqP~LoHX6 z(?qy@G`x3wmm^0KWvKx-;?F>_p$nk?{hF!BW(Y{ZK}os64aBwk4o4{(LgI2y>--jx zH78eQ6#^Jtqnk(0!l-9zsZc?S*)lI_InLPLPLAM}na+@E&Up`eRjPx6G6Ujzxp$I(a`CVJxqwhUtK>ZYAvb!Je zuS;`O9y8A^Y2y!J8%%~0KfP;~T+ysOR>oDgDlcnD+%EvbP}+~V6-e`H#GajY z*x=F#+fT4WW`$g|D^tA^0k1Eu6yJ+lhK!p&Eq`vvRutqW%opuCQfc(?Fe9T#G;C2y zrxNO;WJfWebRK?|q%2q@P~vQL2^&+YEimB22bsi0wK(u_bBGv(RBF#;Qs3|XP+bn> zKb?qq4_@u+a$_taiSHZ1Wei>S#Xw;Net-(7()s93hhku_1+|k5nr?h zUV&^=clXU5zsMTiD|o`q$)X^`^-zXMJkZnN*z0#~f>yk5c~V_FPBglS5W)81w>vW7 zDncogJ{Wyrx%uvCQd87I?Zo^tgLv#L2?r2G)y3UA|C5E zPN?&3MhT0=-s%_cY^I%6U+rw+g!R%_8DFfAc1aeM=?X*gOYTWmPHN+ z$U;ccmkr?FD%Yo1$k?QBT*4HX$lgk8VEd6?`=$AqN_x`He6eL~Lmgy!T07o8|5QxQ z?qZ7o{laLMTnq*91XOmA~esTLHOW zJHje(&LS6n{(wQ5QGYyRr?Z!^%Av3xH59JF^}ZeB+;N=OXX#l^=v$J_LcEuy&Dz^F z6*dK1FxTbN?ri>x;*qOJ4W(rkX~lp^WLeSI{JO8jY2E}0;5EG9fEMOXp>ak~@1&_?CmT}3<#f3FQ z@7ZbNJ6D8}O^D&*jQ-DQ0 za2V{^8wURrp2AZdEC@T6(mC0(n^TmzvcDyo9*O6NUWYp7|L;ig2D69h2*6S zL)QuX5J;VF01n3B^7f+!vZ#wsYvM;EKH!zip!G!MowqZgk+^rS720b@k+d}|fw_fY z-A`|k*(YEz7sw**lL=v&MP$E$IBJU`cM|(6hDQ;vof=lwgG$D! z8K0b6uGMame~bPs?n3}OZr2^&wGWT0;X~R(zUc1u{rbj^wviQej4aw_Eid2Ql1IUL zD5L^8N{bj0UqkIE99ll7VsZDg;xV*bnD{BL)r`Uya*si6Hcjef8%upHZW}9M_0S=X zaBep7hJ*6*Bq2~YV%x0!m(P|oY}fO7i`QCZmE(yCpN7==g5qd)8hH&xV0OrpGHaiE zSBdk!p`fG+%=o*kJ)5`#P3U}(SS95)u&Ew78&$(-*==GIkRr|^A_{xyZHV^~udGx& z_8`BL=0Ns{Z%E!c#0R50J|v9sWZZht_X*i8)!(e3?$<|b;dWztG>TT;<_y#C?3k0R zEG$RRonLK^zGktT+YlyDZc!w%_#{&~H8kf$dCai&0TE2Rls^Dg!BnnPZ-yROR#*SH z1Kv`^5BIpxk7=l@ z<%4qmo3fVpYg3igFxrR=zBIq1hQi!92b8(qxb*;|!7#y{_gw-e=N!ZkX0rOsOyz5d zLwD$<$I_WdRZ&V$KCcR|Yt<#s3mFRG@?NZ&19@ZYdKu3=n6@V ze@t1R+_ph4a6%3iKPB4TrS^QVeaHEPwxeq`4mF8a=#j4)7fOPoE4&fA!e)ha{0?LnC~aN}qa3WAe2&8`n(=l7 zbn3+|m5^rd(CxJwfIQ%QvkjQRCNA3a`El zb>Iv>!|0>8!FZ6+ji(B<=-X!T@5fL*y-sd+7ao*i4Z@r{mbN5M#MGD!v>h_!k3D!w z1D_=34f()}UcB_k#BFHrE$~k+B}JiWvR2q*DU(HuOYk(lx{rQxeQmg?2qS-9d*s~1 zCQ0?@%fAREmK$17uXI>$wV#S>d7J&2n-CL3st^VkoKacBxs;}!Q5XCxQhczKLy4=z z=}S+yohq?7Ba&CZUfJ_#-~iz6($~x_WcbU7d^CW5 z?TpO&P+od63dvIhcn7R+n7^@EBIrB}Kzqr&IJueB=MT}z<(6S|c(Jikiyc6{3#7eu z?>Y0Gxn0EOl|leJ$7y%i!f@U^Lj+==< zI+<7Sd>W7+9MoNIz>0yES{ZR=5DBvR>dwhun7y8}!G+QG+6ux+DU4=e>j>*%i0Ja+ z+JP*G6WfCM^jse@A3-(Q^jZ#6OWIa;P<{;KLZd-^O7co`zL0|b6*Gq?^-O*7^F1j{ zn~Au~sPO~u%OSm}Y<&^FYu%2Jo0U&cwWeP&jzAMcKt20rsk=mAqB^XDVvs<*)=d%> zv;4<$qcyKWMCaQWYFiND!0~g%u<6J-nm&X8yGfVKuJEU78H!m!Psp%%<;EbbWrCCD z&kxuK@siC`_V<;*g-TdH{V}F`>(}c($$KgU>{OeQQ_r5+3N7|;jnp-ROd`QU34%jo z)^Iqu>y*K6${OoM@o>nEfN*Sy5J0B6#V_&0E5oW^znz;$h??&Ac!fct4wO&uSO|*k zm=iHx)5mnASr-+bmt?iMWxU=6qFw_bx+S>vPa6QKWWV*!#4<#odtu4gX9>ecX45~B z9z=u7^4D6gk_5f0Z{Z<70mI1oq=4!-8EEgbUsMy^iV;Pw0D2oPCBO&OA_p-JU+}oJ zCA>FXp17%dU&;M0ELrRVUhe_|ooRgOu>DrHFva7r zPmcmGcoI&bGO4Nq7o|Ev3K6zT2dvt)?7^^0aNP8~Ht_E;!ymKmr+dJ^QGHOpodUuU zQYEv9p0SK^R*QTsA5Tb_JT;J=r_9`Eama(Bemun2tfnusGf>q1Y7FUmD+DTCe`j7~ zJ1J()o6msW?)9Wm!+|$9aRysoKMdxAqe4GNt5ph>M4-6L#u-k>Ylw>OsB3z4AXLDx zvaTUIOc~L$Jjoj^a3J*5J`X0Kkka|EdK6KWEr&)l?#YltMFcG^yqqsl7ym)Kk)T^< zBKoH5S>(>XxaX6^)~;g^`&)QLXA(A=SPpd@bb8{xC@kwD1mM%TVc~>Sl+> zn=FU5H>=AaHk=ppeh&0gu8XKl_VDo-qp{%1ZT10bSI$oA4owk_s>iCBiH91Sv+Wg) zm_u08y~v0MUJ~x|?!JbY$!x_mB5a--w&MxC zebgq7u}GERgxQ-i=(ohya(m}OsB;)Y@LGlC*seA{n%qHoKT2m1j4!2TD{*AnH}_ru zcf5mhSQO6*dG0ze7%Y_z2vY+A*AghTIcBlBr^%^lTKAZ*WCgs_!G|l!3^f+*aJ4D_ z4MV13)p;xVD6<;)GftQdflx)HZBM7hkS;gZdoUVd7X{!mXII$$9Q(z+eaZ^C)3mgd z+w8I)=Eh@#&$7rYhOeHeN@q@#;7P&Ldqec>2jk_JO*JQeOksH}^-@?F&BzI)NuY}h z9rPmRXf5$lmzGvWx390SvoSVmkLcwy8eH!(C-T}u99B3kT)^zSV>+PP1h^KhhGRXI zS+Zt>Ok>LF1Ua;!G79b_LmF#2Z1wK>RH&bf zGyzlS30vGLGK3zNr!rT6I!BUGi(Ao?5|H}-JUbc^Pzrn`mPuv$t?5PhS`I7X!E7;1 zKh(}y|}k0hG*^V7ZIaUg;dOKv+u~pLlrT_-=<=P^j6hRyYZiH z$@}MhssmF~>Urdcs-;U1yM6hq(%H40k|`9z!C$~@lHo0TM0dnIm=I(-#c6P-qb zCp_)TaQ{@@K~UFmNe)#|C2X1wHFX6nFE+oE_fjkPC63QAV$8DmJwZmhe9VoZf`lhKfBfl$HVoNZyakBge2#waB`PLvyu3MPKQuUdXF95=wRSC7+!)7EY4=tdIF*0m2sfYx zJCE0H@ae;Z1vs#?UVoMtHK?}+A@zLD68Tgy;>)OWi4k)wFmmzevp<-PLQQFpv7wHp z!L)?xfeh$13geJFsAIlzyQOcjjo@R~VX=A&FO0Cled4*iFXr*KeikJ+ImU&!E<@~< z)O>VN6APOMi!J@dQNNeQ9f~t=o9LNU&6=&>mkb9O!+E2iyxbg$Qh+pNgC^a8xBr&=7O4D%`X$u3_LO_-b z2MoCz9Dv_wI`DRIjLvUqq4zdLD0}e>v-ES=4U~m;3i7Xv&mrkG<2UFk%t#Fg^bNF_ z?=MC)1#b9^DsQBGgz3PIO4HwI4tp_sMG#X^U^Bg-9_*C3Q|wR6_}VWqedt>1I?(FBJIzte;Ak@SNhLJEp&`FBU2DOt02* zew(C6Qk7UwfGbQR$-q76GUnm?CFazVQ477F6=+;xdBYsJvA4%_)$NVZj)@{LuX({q zKotE)I%Sm+YQT*{@4$l=hW!hY-20H&K8M3s(`Zk9!K1@Qhtkl2D7Z@=V(~J13QUO2 zI(VBVh;;IN25eMMe<+Eka_!}gw_>n+zsJa}h!LuBk0#RCj{`lMvVUV0oZjJ=q(Y$aQ}RXLB3w0Gd$A*#lRBoOJ!1kM(c%!qf9IhJlnqEk_S0%6!^;}%l6xUBU2M2Y! zK^fULsq;11YLf4=`(+EenA-Zn&Jly5-3rFjeVIA+Dhgn1@+uTGef^XkJ5LF$hTJ*5 z5fr`OIfXf2_>ky{=7jRUGy+-uR&w7lM1 zk*qGKE>i`#gH@>stEAnTCcO{G&U?Cl@4<8^3x`yuC$y&rn%|#LsjW}&T*d?1@dACz z-W>_h5Ee)H1m>pX`kawio~^Yjzd?#f<7S+nCuvje67E4~bneYN9x`SVIf6m;-5YsQ ztKN|5yI0@z_A3Y#kxV*XIi3EiKc2{HEFbXrk7=b2lwu1TNG|<7K3Ae2*nYODO?dhYNtXl>^s(^-3#tz5 z`%QB1HCgo6o4s=c-I(J2Ni_uerUYxwpTHY5re;{+(i@*xG}gAOHK7QDl5*Cp?%W#l zF&lT8=%O+>|*IYoxw$S*e9-UOg($s{w!d+zPlerV5JRc84s}p)!plT zf@BCN1nPPGLckpCgmDdzi<8GIs#YgEC9BKJbelo~&BKM!Z3o=uiKEo#M z14yfHeNP$^yLrEOo~ZjGr<-Q~A_UJTYYz<%xR|1%5}F8I-#pCkF9u>>S}x*}*2FUY z(3Jf|PKlzc78h5%gRtqFLx831oV2Wtj#l|&8=T1op0~N|b-$<(U(1S}QA7F!8EcPn z7~y&UKCo#Z>rfLgNG}{O-Llu^lcUqSAA12GQJ!6`9MxmdzUx+`u}t_KQ`f?*-7F|j z#&@7=OQiYqalO;^9}OD|gJxwC^!V*VWer;9_HK@{1SK$E&9s`R*zk_9RpPY!Labt; zjXW(nPYs=aUY$N3fe#|3&}`^(oOI-Dxt@4#UxCoit`hI!<&Yb4WLFAb>pE7w?`Ars zrV_NlT)?VXDfQ2|^1dq-IGwSu-7a4QztiRPB6ugoqPeJZD{Rsj555&>nCdL!p-QDU z1nFX7;I6ya8IEM`P)OX$fnCo`=g$n zySN`H>ok58da(pwxiChy-j^BQwq}Y6W8NJ0x%3S0l-{@3ZG%ToyK1l50ob@iM^t@r zh&hKGHDgW7x@mknH6-@Ad}=%;o)m2iOk@4LbhTp2YaM2=u{kHnR&Xx7 zvu;>g=&ZbiA^)X)!eRWGJkyb+g5AlQ`k z03=^NsVney#EFtAWOweYc6An?T{bh7aw`r06p-gyfLWlxU}GHV{!TR%BOUn@f+M-; zE#ti1jx00l&KKJb&CZ%V0_tf6BUJg^qKs%cTanwq%TSP2-@UV(_YGMOf4Ab0DgVO0H0- z(>F;nxbC6#{Yi$;*Qo=c+@x#4R~GT{g^w)E`$N#%@V+!|%Kk!?T;CPVgto$|z<0$? ziLuHcGUr8jSWqON<3>#(lxApo-$`JRx;< z%LG?qm5RJ7g*)=PE-HTk#zz4-%MRh?_51EjO8OS^iqIOICtgw?&ZrL?bmV6OF@Y)<&lHEV_Bb|A z;lk{Wuk1-ElDyF1uRu%+Xu8(HCRh01q&xuUx3bYOWTJLscd)CM( zwALXE4;@~aIF=9RgblqGeD?9);pvOnAfxID0ki5x+OZ^5mzI>*T3QSOEypQm-j@j9@Xu(whdf*Z5#oqd-(m|Ue5*caa`$vm9&!wzbt#MjPkXJDd zXXQP^m&KlURt8&t{XSA%#ie{!3k6O31XtiRuDRiTzw`Ae*g@qa#9MEmyMv{=lxUn_ z1JwF1YUkv;z8`%!OmZmK6#mIK4i%%pbD2o`@KOJJ9@qKsmf)gx#`_<_6uz{Bp1VSu zV&CRrJ4ka+!Cy|2bv06u%oydeu0t`#f%Wv+4G+o6m^z%BSDHKz(wMM)A0l(K*f_xp zHayhYZ`>XD9C9un>09zdD`i)k5bv}0Fb5cZZd+~pW#WKKpP=#K?2HQJ+nSA$MPR3B z;#sj28qZGv!wJO~_Y2SqLm;<4`6ZpR9?;v<}z1?_zI0A+t`D894x6Xw(INX{nE<~J$ zJ%f>Ko%fVX$qHj3M(ch*)jEbMaA_kWTB+TOnMl#YIX68?&4n(Y+NY-~!yJe6lKROM z?Djn3EZf2tU+8BR4L`!QYFbH=($K`35JTimu}qF9jO4(aKL`V(G_an$Dlr~C7yO9oMLxYyxOXliFv%ZL@# z=p6MWc%r zjDewzhTSfL`Jf4pR8ImDvm;?0c?f++`97{AdMCn2a^_PhyAzKHeo!_3ioOxKXFuBi zwbRIFEWdD>ec4qxyuR1e7V1YGJ9)w@lMjXrmp5;k{i!?066(i8zO>=6Fwu#1{mTAR zqtm#xAm`Ebv}MbmR>NF;zl2v$?UlTdVUeI80tZTxsYj95(=S1g1m94dEOBN0fUhkS zBeipoh0S)PbV3YU4|iv^h$gDDkjpGYhra9stEEQED%hGt;)NB3Tj&}D8pcP%oon=F zviZz09)-7;x?mTMLD9wsy@fMi?W(_!fytV$HM-JxJjHMo-3jWEm;*^H*U~yAcEh>% zZFnl9=&k+zTHEr{sDaqeZRMCr0ZHt~1*@0+I#QPa5|u(DGnsJYD!Cs${GviI4EU9Z z3M6*yWCj@8#4C6^T3JaHs-6l;TD2gDB7oG>?c{jN%WJKi*M?@)D!lae_skWkl~9wY zKzSzZpEWlH;4x5XjVGiG*YGp?8Ub2kps_GphrETXx?z!rlzUJ|bp?7?6T;7q+>*6u z?%$V6R61QrD6%*Ym73c+4x>oBRnF%W)x{3qU#S`PljSx5c=b+kS(jb+#0E-CXSuVh zo@&T6Ry34)HMDLOzxvbV5ibEavp*vk!B24Oyq6zl!YxmLx5R>cHxxEPd{}}lA$$g3 zlIGs)ETrP2oaMVa#{^Z6_Idr`>ej+3dR8yQ5iN+eXQj zvw@G(ZDO{u&O5)<9q&miS*cNnOm)4%N0P#gqoV*@B9mJU`0;Fw6hZQn=!QkrSp(p} z?o3Md#)*}qVKsqf#|4MHGVLP_#UJFj3I?!!Rl9k z!`uSj0%#ghf)?x*pxk`#H9-HZ6uBRUz}>)X?Bjh&087b8OStX(bS89rW&Q zhG38sB+jCNjE1{JI90V7JKy&O^m1S(g?gw3a z=o(awdc6_PCfOklW8X0?+ZKn z?w5uYMUoAC7=>P>{QC6OC&?6}VI7Knwm#wBte{Rs+L*>w9Kzh%u zEv>i~V=*^{_2C6?m7@rn44G(-JwJ<_zCNhJrA&&BQD0}UEBC7u;?i=a20v$j%Sj)o zl2ObXPJACcFW{oh(X| z5ZbiEV3w4qjx0dZZj9zIPdO1w_JR~(Ugy(jWZWKX^~MP^NK8+n$`g}Q7C|ev>f4x_ zBfx!onhA2v_rM4%W7k|*u=%#o;9`wiDbB8$3j*FH$x`N#tcxxv7Xx1K*_d?FzH}`P ziyKm3$fL~N`efw1?>{+du!S^`;Sb_SL>;m=ha@(YZh^Ku4@4#{>L6wF6zb?4;` zz@Fk5wzvx$3fq~<@F2G{W|Oa7qkYT$Ut2gNWdX>`_A7s;?UmeMblNK%e zRc`bGW8#l=C2q|@&GZ|Mw$3NU$v`{9o(qmmaZLLICOcj^fWu$j*a2C(` z^goDn^#G=;942;^B1@ZnO=^>U-?k^onFe)HhFAwAwZCHvyLq3*aCm&Y`jjki%l)>p zzWWe|s@rP8Ig8%ON+6?r^~4AM8Z}(gh`if`F^E-Uw`LF>J73{00Gi+xc8IgIcW&Q` z>vdjSWbHp>o=T_l3_WT2zU=(2=G$_^)d}#SPXt57SCE(QC_sRnN=ByQ>HM*p{DejE zx%??k#zz%ts8>) zi$dgFRijNKM#i%J8-1kB?Bd8}Vg9#m;X6jU!a3vjZuwK*OWyvwUq5EMqa`?zN(~saehNRpX`p_ zSPhR4 zU(k16g(~dIq_a!@^7R?Xg$xk{y7ox2$eZXW+9`jX9%pA4%u-BEQq&_3D^sn{D;%}Q z6$ZgxbrZilxzjoHO~i!jnV>>bT@I^Zgs1*6ZxeEmJ30hN)EW{nF@XWduO#t+f@-Md z>WJD*`fHPr^x#1biI34$9!)Bqj}uGWzjgwqs$xfY;f1+@%3!U$`{8v5Rn5X0!J;_|{> z`fZK4KWV2Rv38ygO`_xnhjB+0frxygrL1`hn~3Z+e`)FIdhI4gY^usZfs9?*#*bdL z^gPorNJr(jRBayLS09=~1343dh52T0tKygqUpW>>ah->XKygP7k-PZwc1ba(H49`+ zwm#hSjxK1~Hu+}y{O>Q0adj#ipn>QUGg;m!UsHIw6+OU3*}P<&4J(hTY2n{+9^;in z6TdS4s>Wof;50)$SIpv0cBc!w>2qW~X8e@0r-WLtKarGF&r6JuaTh7$3)zc5U_3!qoPnh2P>f> z4)aHhGfs+?;j3D$Qa(3#B=mhk*FOgsO-L~Z=%8eO5q_Llm!z$v@RY>RfVu?lFHuYrTUgaj&-uQ8x{Dn4{VZqPOd{x zbEL@{A0^?5ctR#%c!X}4yiJ=mk%l@ksv7f4NZZ1wOxTRL;$3W&HvLRtEvz*lA3;WJ zfrvy1gA}4Ll)ki^5zbO39ar+9M;LIX5(ZGoalLlugq8@5iK2LpSKN~oo-TwHg0FeO z(@#Vn-(JeE6l92+uFjG<(>@q_xxN{xn|(aB!TTP@&7Yepr;j6xuy~M+*DT&zom7#= zxTA(U$vKOHk{CR()ihl=tf1V=kgg%4_zo$R*)Jrqpv#_1$vOs7kjIIF*}BqqcdONv zoE{*+OWz($>~NJ-;FeZ|l`FlfhfuXV`D~rK>*XMa_sN3W8|5}hyuA^*P_{jwd6;*0 zx?Mt2U(Z$}dzL3hJIRki_l&`fk2vums5C`71oa|9_ua^Emhvadf)&)8CzqndUWoCL zE=8!i!H4Ee3>uCOEX-tbWO%(9E#_i9io65!_&_~@uju0H47ACgBo0ME%PK{9jdJqC z*9|Avb&p_p3j)1{(pQ}Q$}rP$on{_uT$AI-=6X+yXoYk3 zMV_$Ny;gW4BdApy67vCxs1B;+$Sc1nIQKOl-F{(LTqE%R+NrPo4sef2b)AmdJFLVD zK|sd}@SyRwpTsx#E+)qn(kejVjKdI#SCNPr{-rAOfsqT?KidHmX?BNk*(D*zvDI+L zQU9W9aYRA-Ogo||?5mrOxEq#CFT&z3C#Z#ImJbMM=bWbHoJT%{L9a8AntBo0;d8<) zOisMYKG^-p>ZLNDbihUtAcFAN#bB;cTOo!3M2NRb(}^Zb69LkDl)P0OVqk|uVikhH zNn;mTkVmAwEWPO3!QiZVhHP1fmnx@q69UcGy@+MeI#y^8Q6m^&ru9JiSAk@GU*-Ps zT47T@d22X7o+MvDW#4cJbrJYx{u%0C@ja#VE69W?ObsIbhnM@lyP?iUp|24Lz$*LE4O4G#2?0gD(;GNB)vh{<4g=z~)`2RmHLt|}0*1!JzBh|+Qb@yoUtD7skGSnP zno-5ZEbLywd7AMI)X4?^UfXuhtYYPf$&S;^HKk^ux!9^$L7RaQ+V%L`E9`X8A+a&+cBX*~K&`k^UV{bya0K>F_{Za3TT;fyDrb@~5{0FWM9I`*UM^@VNtYt# z3wCaH$E-3w@Ip9CzRbirA|WGyB}quNvr!E!ssnUMtb+nP;FoZo_5+sI-}JD*C|49z zu;I8vyK8Ojv{dc}JwrqV)-CoYY30tU!rZP_*0f30 zoaLmv9!zs|c=Do7_1gIIX)xK^9Oit4wqYp&hS|fD&c31JQkx6*+A38Dv3>kQGbgiN zemgvTTQrL$mb3>G0-Ty&Gh4TH6t|tR#=*!WQD`^Jkx+!L?OUo)q#u*IjPnSTv5z_7 ztS8HNH*xVUE&Zn3OuPMD&dfdl09_vl8cxq!N?a3PBqF__urx7FSUoeB*v+~w@IO9o z4&a~;+S$eQ&qn(c$z|CJmz&1HDjTlgB;DMkKKZ%{tf#JQ>*$}Md(>49r+$?IPl&7j ztYp$cWWSMwT*8XC3d~M`t7@QZkSV=xeXF?l@l2NYvYN1y#PdDtz128_2<0gJOrDq0 z5GDI_)bc}Q(c$KyW67-oz2r{Joq@C}YdvDvq6@@uLL-GBg6Q!+>J~@;*^@+AIr``YK^THBtJs4c^`*M2uwfM zs%H)X=6wpCrjWt88cUb2=MB+$hfaf$&!R^B&KGW8BGhJxXjO-LfZSzEw>C@{SlS1* z^u_OFT#1t5X(yvdKr#`6DvyeT{pq9?Svb-Uo|o!b`Z}-+CBc~e$=NX63RBn?&gcQtK2b-;HK%y|rD6kvVs_eZ z*`r3M>0Bh_rcv|7CUXp;b&AiIFewOGk4w8mQB?*2BB=dI!hS_chf6!&xTR^?vk>_qv(A=7|U0HId@c6x3yW4XJw9k>=aKQ zKiXMoJ9)kD0fLY}_e7{RBEE1BvVe51q@76Gaz~X}sD@Gg4CnqsS_AZIOgXf z)TaywD-Et5&4>Eu2sVu$q!@EjyEw?Evu=dDFDLQUUaVw!-MVsm{nc$E5ox^4@2iIc zkND=984YMySY#wi-3w`*R{GE`6T`6YgDC;s#@Z-5{Yw(;($iOF6iz2e#5L%-jtYdB z8hDVpGbv%f`Xe-^nJW?@(h*_cs+sdet_xh*yl{IIp$j%5RJ#;)!4(O)&E{rCykinh z@j&b(uAp)cD#kjk8%PVO5I~P~F$>g(;CoUFK5|)@*`BTMHd|c{vq2+`BWD*QaU2pp zZ}bT&I&^OolhO`@*EhL)7SmlMt{M-vwbL6Vz6&921xjv zEw+4*0bE1k7x^$_c8MJ#PM4>eK_o3h?W9!m;#3rEvQO9W&SpoGV81+KTnQA|v1oeHXc@>6_p-n*1Au49N*uf; zEe3mRQZ%|mDTlr6016r!mrF;XKL;mtv}LTjB641H=wGNm;T5Od*vUVHL0}LSxD+X1 zS!*PZt*>p}-v|{1BiMok%qQLz+LVe_d)v2sGc;*pv(uJw@$6>&_zqymi-_pv*hE>) z7TQT|?u(K~9uK6b48*piE~Vvne}UL(ku{mEHa(@a& zc)l@!xeBu>r&w38-Af@a&G(jcZ3Xi@r>mZ_Ja`sr zEj3syKlLAsi#m)H?(vaYA=2Dzc1aw)vwjUjDhjHP=*W5a&GWG!!ugC%WLw|R_i%CC z8`|G;bFL&r#p}f+AH|8a=968FW6o*8EOoIgbiHYy65G+R7mft`IftZvT#Q(@vqy{+ zit^#Iz@YO^*QTlU40lWkswNFTvp?l5lGtI!X#%y(wR{ zetuNG&c=K9`vgFcqD0DG=A3-A^_Q1tvxmiJKhT? zjx4g(pfje|AIhMTxYeT9RJ8@PDwrfLzv3h8!-@zA3VxvcDk+{|Iz0MNPBmbX}WBkdBKSk zxZ-Xx-a<75r1XLU3AS4|jd%3g_meE0MjPe>A-yt|kgXV(XaYdblS}=TH>Xse_n2;k z8t0sQZ{Z269d$D>m+9t?=De|FFr$rn8J*j)KGriHdw91O8O6yI52*^UBEmfhe0-wb z?6MN?OJo0zpZnw|J-w#h014Aeg^Lt8HT+)p-H1ypt;KN2J4BdMDF$1>3KNf^guw-= zLaV05SrBa*Nr{a|bis9G__JsXtl&?^AXG(Z-x{neF&!(;E-5#d!c_n7xjvWq$E znhhl19NNsF+F$K>@9i8k_R%O+ffi|=iH}mwo)#}UFwhl%0=3G;?A!V6$i2tN2jyEk zMx{s|`x>7?#}2JJb$GZgS+eQLd^#VKyzL>|-=c`^sjA_Io^U;+yKN4^-J{CPP6#`R z_OT+c)g8np+E1Pz6E|9(8J4QtN@pAy+36VEczq4@B}teh6Fbzw62nk=l~`#z^uNC@ z*(1bpytA->`+94>4wmAMxd~??K&!5qvE_{>=%qIpakXRA)ASPq&g=aJVfP3O03V=g z{vzBtb86)6654hy@qJnWUe@!5y7p+-h~u1 zCYM3H+I{&>sa;3^ux#4)jd#(jay;)5FK+(UeT&ImEaP;AFLr*ktNq48_cOP&l3&Lg8#HoX9Ypz`VTl1vv~Kc>SR zWoZd@&>Sd`qI3#=LKd2RJZ$_clb;m1;cd?<8AYq?qn=7Yql;?+mM#y*tWtt!GdtG& z6y2`$Wti+YX)rWdOt}?=dBf}mR|dYN4y?dbpZf>g4foh@YbST#6@Dax<4q%ZCk&ge7}Ax z?q9qcf4O%9_edPe{N zf=_6Xk5kR>|N4!yE!U3y>m6_P^80*(TR}T@Ma40REa16aiV{m}P)P@dw<#~M<$Nia z%!5%%+p2IkA9q<2J!^R7HM%j^)nSo5AIOjdP#bt5I-Z740O$jjckEvee*9yTHvkX^ zH;~#)e>;m2%8`c9GU)n+2d6i+FdYo&x4M;R!rB3sVSz7(kwQ91<55SbI|T;^f+k+D z{+KP+J4fPryt;wl-dwL&Vb9{0N;j~~+?`?W=dPC~092?&(=ll*U(7&&m3;Nx!h*UI zo#>s_w3Ov(czKAi^I0_HAoHw24o}sI(!eUVZTP+n724ib=KJ`v(X#7!TZrn5J~f-a z;ZE%nvK7BV+S-UWbeV&B$5q(AW?Dv8F=(wsF+lfhkolKP-`AHDJkssK;1@)LU}@$! zs*bY`c050>EKlhOl4OhPD+4_fh0*l= z#Ze5f))s425Cn4v?yj-fI~hv|6?d_CT3lkL?EaE|%Bk-s`O9>#YU-NOGY}|;W#rJe zFO4RzG4cdNgzBjS6rmHmDd=V$BlPDYeC*j7onn_xJaR62CC_L>EHp03RaW->9=txp zU-8Z=uJpWx^4<_3GIv2Md`_-j z@h6Od)wCiMNpO(Bz?E=*TyIID^yb}EO}~=i073gTXASfZxdZk(w>U^O{E+rJAQpZI z4i}6lm_QVH^AaRPkCK%AS6wKWFL2y89-|u#pN^V3!LaBz5vA;o%&=HzXCWsJgOITVhJr9Ulcx{UrotD6>fDcOwK9J;4t zW^~jp+b{r6w0xW+8LP~(NE%BQFx>C6R3<7u@gbGPn}m8TV;$IR^5~#=Lt$jj&15*D9b$QR6-gF_21wA0`ZWEQsUu3w?TtQY9N+v+yk?fy zR;w`j19tt>@aAC3>wOKoJxgPR7gh_^TfnLQpBwsEC}8Tk0qZ5~k$pFJ;ey{xA7YXW zD+!sQF*sMN7;!eEW|;R;Q6?1_chs;qU$Dl!$h^&{uegtOslQAP>`5tWUz_Ezw(*`aWU|;DmW*SPO1$pm=o5>CuuQ^tO_R}!~3JHbigb$-V@~$HU0=I`m zZ<%96-}+n;yBCEnF2l~s2;qN3{+wX2ndCJ=5(3XTWjMDjM*XTq*t*&qx^MdGCV>Jw z8hGMx=N*mv*2;*4+OiC*{xXs{>OQw{%LsFc+Fg=Sy^9+7a)!Y<;!Q+-q;w-5o=WjDt zu6Aj-x#-7D69m=GRNnye$Iv@WvQcM|U5+8NK04bWp0sVJYOARkkc_zFz-{TvfBl*! zDJ@v?I7{vX@_LXSec4WMZ+A?=Ol-y^$V^E?E_;J*UOw%!%NOUWjtj4??me$V6z+az zholL#_2`z&a=L!C2Im~dpXMzsw*q%82aI4C{Zpc|wV)t{VNJWjMQ6PmYr5TCr3ZBz zLs5!#@PUlDSve7R@_Xyk$`%P%)z>+u8jv7~j`wnAXU1^K_1PR`8maurrh^Ums@gJD zTK*t^yO>n$sF~;!44sS%4_}@1>e!6Y{?jkhMhsub1=@Z9)<0Ng_&NzvHVCM&Q=90E zCZh;GR|hfhlIjE)s)~(on!~W$H;~pARAQA7LR*O=Z!z&Ri`&;gUncfmZ^StD5+c;P z_ZuA1Q_^GIL^$EXj|eX}12qA$fkW-1>LgD1JPcZtX6I~M1#(?kwsva^%``V=y+4+; z@tOz?a<0o{Pn>QXr7N>#e>ozi(^N0irbE0SPTzPCq|{F}};XIX}t4T;_oTFZJ;qQ!5swPkpZy?ipF+ z@v@GW>YYVCoYwZ42IYzB;YgJ?dnbHO>gaRJpD21n_}WRcQU*`ai9pZ7_vHYnD_T{> zEfTozGR1T~#^?yLYi@;X15Jkby(NNs@1O)jBTORUb^lbwLqb5)p+g)T2PYGLP(!zN zi!FH~>`q%KB~)JAU7wYYuSt3snVH-RrQZQNAic6$JvlWwMl|B70|+9bx;0)PIo73) zR+N{w+c0m_)(F=M@bkRVsLxn3*H0bf+8Z*2LTKW8gsip7( zl$Co|jfK_aJ5CNUV>+_xdNY%8tFQxChjOBz%*L9#bYy$wah0%1&Vgt}KaOW{bzn^JCXZKzW#$98SmL&0BQ?Oj7 zwPMlltpX4dF76ad=GT8qSovZ%jG7(^fYgm$yt4R&!3PT%@dM-3(XDuRQ-hbT5wJ)E zWHZ4WJxv*pP<>Ny4#sZ2spt5Cb`Y@`^C{Jy6=yXw;e;~M@cW1yMYr2+Acc6-e4t#R zyBLpYu3TJsZk-2xEt+_bDPhtvxsHce5CS|xFS}J7@9BwBdY6+F9<)?`$*zv1MpE1{ zEq`*XGiZ|K;`YLxKg*mhSxnL{oLOkq?Nij|_Qezyk}soYP=5Hf+Rjq-=f@WAoT&cq5(#f~?^C}s9ues?lQpmnOR#KzGwjg3b496g00f;h> zP`HmB5_BP}Hzpt35QXL?E|?}B?z#8pDezE#{8sf?nXilL&6I|V2K~Fia~@<_05j*< zC($~h+%?Gp*meyNo`CoA?w)5M&NHW@x+s*dOw?;G0v{hjibMOkL#){OOPhm+uIs3{-UQIvi z{QSHqkn&29FozS7beEB91Qf5U51+Ya;{8HoZYNBKF_H0{(rjqT?y${#^|U{?jUGk!s-$-;m}EKPcX1x0=V?NBu!RRIYE*gCB_ z*`dqaf#jsY82}CGW=c=6$SBH4hn4^g#j=&?VWn0oX;5ZTW$mUF zNUyO3c%4?tRAraBgUx})c0VWZ`mJ9nug%gW@Z9SOoerf$tu$8d)nhc*hh zah;xLyEZ*Ac~YzNfuR&6Xxx1}K?2Gm!Ez&qQf=YX=;rS%{N z>{`+;4qBZVHwkDsQ4;y=1Mv?q#c5bVwYgl{aXmy!@yKSy$;K|_(A>QlnZMO|p4 zzilp)jE8&F#}8Cu>EzoNpL}BLux2LrYj`(K-h-T+Y;c1{iPMvI(b_ze^LU!kBdY_Q z(5M@?WkZiC`^1;Yp74&0dV=1X4g&Q=px*S!WDuDqO4XMoO;a5oL3?6^x^ieuT)>N9 zhY&H0Lhmx0be8*Bt|DNg+kw11cEh)9Ce9e+rK~1VGKJ3THBBerK(cfy!9VtsfNiJQ zzOY?Ak_&KU@qLv>O0LrmR*=>5kAw6XYAHErT9@%+V)Qfp+50ZA*8IwKCttF z3S=&f^D|~|Xdd_gXq2B4es9&0NR|C9FR5@elP|_a5z`r zcAod}6QG0-q1@amG^!viaIV=qT2!`bPDc39U?_0CkfscTQlO>ZLY|h7Z`f~3wonGz zh<|qR?@u+MEJfLxWAkZZU57zFPM$CIx;K}Os*1KZtK(4Hn5<%gq*DlN=jn}RO3C2j zV0BRkXoA|%Z6oP`id=VaZ?udA_+kTn7CJkBK;7(65Sj(*DJyG%T^tO_>FVQ&Cq)(O zN_FVwx?k&SO2cdsz!0wr7NQp%?sj0iV@0|bz~ELs1ir))I5s(moT4i!)hjAs=FifY z@|`Z==krp>6fBT18ZDx;eBfrJn>@Ut6O#{behy;MP{o;EWRMyp8-Cea4{A$#Ncei% z1N>wQV4~<=xJvLakN03U*SMb!>{XWGax&fZR+qLwT%$87hHVH)wywmE@50Y+eUG>q zs5pJ=KGC?_i;{vjV2?6g8^HSQkIlFT3$Z|}tL;Vbpd_Rs+$zH`68VQSyR)LmCRy}Z zm`k?o6HC$Nj+7F!zqpC!>@7rUdhXkv=ITwjFI1s^|1J;+51nbgYQW{7|wqIn)YkVI^3AJ zhdZ@4=Oji*srR?K4wZ0!>HX?rW^$tOH3n zxUix$I#W4P_=eQ33OU87G@HI#=;rMuE4-jIi77Zu8_&LY?){-2A;X_cgjNosw>|82 zMifeTpzyd-YL-_z)^VtpNz&uUQ6j8TB|z@DBTD2oxlfIO-+8ifF`}aM>ZnZRMc&Pp z#J4Fj?bXlp=O;J7uOEmg{OJM$RscQsk+QJm|M*1b=PzFZ}hp|;(!y2-CWG7Ke6O#)q*9E3x2 z;>-36Z;_8=adSTuRz5CN;QP1=i9bC+7=h|<^7X%Uzw(6E|KZ@{Z1awfvp-~63jS{W zb*=<|a>*~Ldtd{Q@SqqN9(0Eqaw6dIL3vGO0u8;Z!Kpd$3EbCu#G})RF>ln3+B^uT zZfSkOB5bL;A|;_;K0tbXkRCuzob>*TXy`*h%#m5^%=#F>G#E@K(oX%0%k?Sak z<`MP*2@C*?k@U!?=r{_aIQq2@t>*&|jXwkSmzFp3<6>{#DgX#iwLgXThZ6DX$FUE= zAnL!Xb@P2#KLiYD|FkMZ@T6`0f<5y2u(R-|F#VENQf|?X1p-_@!B4r@zw%=RO7lUw z*BX56e#uT825en&1=IDOo}6{1`(qTqMnA4Z<u(1i)cyN6`WyX& z#{Z1|D}1Cs2>Ew({6BCqsQ-@hCwd0$->tvUKQ!q6pkm;!;QmR)=9fqn%5TE`I?SFn zJH+?vpWlO>Ve_weAC$NI)B0CxHvYi*2jhMX@$c6kid!G=;txXomlXhj`}e!}53uP2 z{SP+%8}$DGl|J(O2bKO6{r@_TKFaei9{tzI{H~rqIPl-m@jk}#qs)Jo|L@cP5DxnH z#s9(5zl#4q%2K{Rvii|Df7ds=7X9hR1PKfv^{cKvDEgZ}f3Jg&DF0u^ppS|6F9!Wn z{{C!M|2==dEBoIt=VKcG&76N^wc}$PKlu5(Q+-(fiJvonWZ*CM{0l$-4SzoP`MVqa zJum-rKl=YVgZ}6C@yD|9pJw+z^ZSq5|L>Xn_m%&_&%b)df0Up6e^kd`{pT-!{;I1F ze*W%2f3Jg&DF1KoLI1l9`au7SLI1_i-~IFd;hpD${eLau{w@3e>OX(w_xJq!dnNZb z?XX|H#{d5e`X6qC!l?gX(8nDh5O-S{Su5r~;zVnlLaW<3YoV9!2%NdGRhhu$ zJJ##99*J3cjLA*Vi9n7%u}-=b%&CT0`vQ{1wU|O!o2^LXi@%s)+tv=`BL6c5NaMF9 zmuA&W(QT{_tDPMTgM38$UT>hxA!IC*Of8Jq$gGeHf+cVn^x$Xr8I<}yfO0LEUD6cG zhlateLJpw`ov1!Q8KZ?4hDOXa(@)0tV=@SMItNg5pHe`VDfOq+{|^8uK-Rwp$hGFH zOoB-}nAX2d3>%;7wCi=%xtzI~TQxBu9>q~1CNqG!A~qnp>^WDJYAX1%vm_xuXy<5p&pQ{hiBg zc1OEcNE4#ub48YJ8wUD;S4ZM$M6}J3Rc#TA1C=Qk5VH<=-GGP3MQ@T^WZ`+rnG5X9 zxqQBoxDbn~DRtF-qy~SZj8|NO?^M-qtxo!Vef>sfU1~5nc9h%`63P@25C_)*$vELX zCZf#o&$M4+g5ABvk^5GXKfgHh!6E~8lH(MJI*nGuq&5_M1crX5on?CbaegVk2R0FzXDY+CC|cVR`=JEdPCtt*?S zci3kjtUr|T??!ni-RqKiju{9Ql$4}0PBC-$<=&E028lGN6i-96GEw}Azd+S+Z^3t1 zK}@HLS*!ou6rORprNozwRD|8*dE6mE{*H$?(B_4xXYDzgFpWZde&VufDmzs~t&2s_ zwX$o0_CByLh@L*3Ru(+fkAIzs_5Yv6JHRk*D00Gr8~fBx^vU?NUz;bT+TTYUHo%-0 z$mNPHoYYt19sDyRDAQ3TXHH$=Ef2pg?T}zrkAP%12Z$ zbFIPQN_}ksH0M0#C_e09X|shBO(phV;_$;Mr6GDJd{a}K!0u8R@Sb7wxs7qM5=c2gZ)_WWV>XeTUsYJGMh?yf&Dx zP7Zf6FI)h=w^3iW+GSl0s8)cldOj!Df=QAx2!t$9Rk3%!o=yiFg>(g;%h}c@fbO|# z=GSTF3%NXivSk#OUS^0TX9V$%ljzeGO-`rDZu&d@?7gcTG`ELqyY~?U`zAs5oF)Xx zEi0e*0puVJ2+6&Cksh9vP9I3(^2+;FJY%%gil6bK|2|R;h+sIz(Iqzzmfg5^bh0PJ zVRGK7+{GhPE{?^{{-e*_>&mMq<7rdCUB~nZq!Fw%WQ!O7)*LX}Stg}0o-Ceid<}c3 z2EPkjr0310n}svp+r%v!d;sp(c@okhsIm|SsUC*~lL1IH+&WLvLg2wX+YPB?Y8?yT zjgJ}XCT6bJ8tbWHoZzx@}9!oz0s+xJ0=r2G|_dPD0z3FMnSrbPU+`@ zo;!c$JgW1;{-C*0qq@`w)Ryo#SG8AEha_h=Mzp4G571qb)g4L$!=uv(&z)E>#b<@GF>Qul+p7U>}1=oHV4aWfq zbBpc}hbHl6v7wi*O;HOn7SNPm(8OD99s|IoahP>Bd?)HF2|AS*SV}I3>+8FhEWC=U zX-PB@y^R2PzoFB7aaQl848e_(Jo0{Y*}a6E;7{L;^1RA1zqw@hEYf9?Z>Y1Ql*lto z(?4`O@3+P33?oL}Bd!nzbWu= zTH>&6;73-=E1))WCs5xtzU%EX=W5Ia8n@y7a=?A1JIC|md69|=?;iacfEVk#?$F9ZrWw^-l7Luu@7uPDCZ9K~m*zpuKu| zJgNV^x3?1CS`Qq=c$(j$))%gL7tc$La4zuvdI%ZB)&t~@k77Y-Kg&qc*j}vS{)Mk| z=cDG>-c>;|?R#p|CQ3(^+xg9sCji?{BdsAMLGY~(z+E+!tO{x7M@Ls0HATn0pHgnP zZtkkO%V=th>#P%g^_&wPRn_m%%81!`4=@Ia@IW)Po=NzhE^wSEF3QBX)+~ zj?JrIsUKj0K1Ki5Jy%DMit@9(D{?mpfcGZqhAzJE(yTwAn*WYC|f7yHQhEe?k-EPjx;4GxD)MnR*N zYHvOhcK7Z+5fI$;3^0V_*c(+>6Tcg^@`EHXB^0LZ@rKEEEvi5Xr%NMdb!(>#ia?09 zpAnCSvRPU28JY0ImF|B$qO)Jmmw$$GzX3%;;iI2867pULT&v6J?RqILEErTGoU{Wf zlB!DcC(ZmLj${8!bb?K(ea$wAw2f|Ws)I9vpFSJfbNj+Yx^w6qe z_gAL^)AgYPBQK>l1QoHPXyRHBBSx(5!nWD1|DT73*KD*z7t0CGla5P;I)d&reok+% z(~Q%_O#%eTGm`>Qz-n2zl~=bpa(RB64W*|;c%%`O76m!rZU#W1abT5ghfm*kEWcOEK@ zQ(ks4aV!1Ows(VPva?AN6%wAdtnPDnIM|y-1IOjk#3f%CQrzUQcz}?}PPdt8L3SDf&p7%b`LeQ!dRv zr}H0Pdp@%XXC*P({A3-?mUnMFn&{GY(w!i#`iT>huktRjz}(4+5;H?|>yyb-Fe~zF zu_kS{8fesc#_rDC+Dc8Z8)xkX)f^@90Hw2ign|kA5NonBWb~!=#u;O7(IXN3p+eX4 zBpP4rASlQ6A(fe#-HVe8Iq?(POp+wF#oyG4W>8VQen{b1qYmmO5{*|w-)1=dXn^$i z9^UG76iqr948q{t8YoMCuhe1p3)4TQ?UUJYOc5`o7jB`7FHE!9KAuh=JN^9x?>)^0 zj#QkK3se$cSWy9shW~v_O_Ir`h=ReX@Rn}_ zhx5=}Tz#3?p|o9w0zWFLy#*hrYLA#mH_}#jPFvpI{yV?XGwF8{5-d)r!7HP134!Yg z{a|;&2Iq(RP7Y!ueVHyh-@xX$Xjz>MA%CmF=b9ap`KD4F?#>d?M@e9byGTyyk=p*V&SJI2 zy)P*(e^PO_v~UX0kmB{5n&kDb7H?7w0nS;lfnyj^LOu9bS>vs~M#KH9QtxR%$e zQ~QA;ha_*+`qTkV;T7^xqk2Rs0rJMGyoxHnK-8N;O32~gI%MlGuhOeBQdK8Wl3r(O zr#Bai0&k6ke*Yg;f&I}MLq1Bm?Z3Dq&QYk#QToQF31)F`V|fGHx0nebhjwuFegLhj z8hAswWs_2yi)dS)0El)CIj9HgxNZ`QMqE7{e4*o8q(dkr=olp9UENp>L5>NhRpvkpzON=so)xDL`3EK!rV3bQHtMVD zs*>9dP1e;U37h!qT`ML>jK$MIJ0~W{orMQii8_DhHDU$pa^a;BX>0I2f4Wu+HQ6aG z4qqWXPB5LYfvmaW&QpsCtP5Of-Qz+e@uj5{Hh$K6T6In;{SYX{ zaq`n`3mcBXRyF^ON3(Yc06R(L_({ifOGOM`TutT7qc&4iamsw2y8MXP)o}qn&gkDZ zO?ZAtk(edr*#MNoPGC6f9>OL;e43#S5mYn~_g;fQ^vb%4NYaU*#tUn#?c*A9ekeOT zr=yc&bKqM1pLE0Y;NAUHD(>PKD?OCcmn*w^=R(s;GkuhOkUg&MK0c9PHQL~~zq=fh zGCEE$#2N+yKt7-;*73M>$e-F>yZWXpUe?~a@}QH$RTwGb;8P}okd4t35!@tB4Lab^ zu0nMAHy24J)Plh>f#m{P*LZ4?R{n81VB12PbEvAq4>2Id`gInu9^dYfnoU7zD z!3g*?qRJGO_kewn%NUiUn^lzL{t+0*wsX+AgFm{Umz@aLewrN2`uRk z&jl~(;f9=sKk34PJQGG?p_c>tu%9;sBUt45yTq=$_onO>UY8feFzZcXys1j&1V!LS z(@lQOT&_Wi1OtxbX(&Q8jR>`So{isDuky&akKGC5g+^ef>v2s-+^YT`?GjFhpfve* za=S%4QQTSoUbgIa9AYD89DmySV>c`iUK|v;~wxbg$jW{*nJ zcdSRCHlNzN2mid@=$6l&L&mkd(bN$(!G@cK3hbTCr{g`8|F5mN_I^X4n-(|;R8#R_ zSHW7fJO+`nPi%e;pgkA%dg>wfX`KoR((9$YjFLvtvPJzkLH5XT$ilt3qhwx8Qnu$o zglQw}2(e(-dDuJ)jw~BL*8iG4g6jAvQC6ZN8o1U8FmInLe4L;g;I(P=@SDUH(WfwP zCs$AWrS&95CSb#sMpUrjKoKCVYO}A!@K0SEHHW$?b+^hA&(_ED zvYbX~A0TYx9$A+?4RMH8Ef7vyS)u>9p-g=0x^@ARQ9ZB0Pr1Kw(xm{(D)@ezGu*NI z^N3ST0vi*_kjP@Bem6E0$&DSGTV~m@#H-X>$COb0PafN8^Ol(g>7XTpP zYJ@8}WY>P#Rc`2lto|-i|EM%*c%bglKo3S&Lqk4z9V@Ro5C(t(PtU3`DBat%!3uPI z8?N_5{!L{|4!T~X0G(Ivb=_J_`a0;O@Ct>*<@~h)&&Ly0BMg4Y z3wDt{UjmNnLy+oOtsW@JlRv+ByenxYCt$R)p5M8;s4d#BOsD1&#GuI+QdLUfk zaW+izWeJNOIat@Z_2vs^IousoKn@!_I$RKbUx4kNfd$jP;~35QE&NEzPvglYIC_5F zg;X78rB>)or>wqJV17tL@;OaL4l(XSI^yV@?E#QYN*gTDxRDC%F+0wDvQ)1h8s5P0&C4E z|2yGI1dW{=pY^DVR-9>KT)14b7#dxGNw$s?(V&m6v4b(5er)^h7D|m@8m~W~$2cw_ zmx*_Su&P4=@W%^q?d3CxM(c*%i;u^8j!aOISdVZ=w_?9n0B2K$jz3oBGckA zP556w4EwQ$Yly-mojSe=3#J|q+lJMt?5XORubYy#wfDP+t3+^0_y-%hoxKT0J)Se) z045qZVyupoA-Hg7R+&Z8F9{?of)Ja1-G%czvbyCFM$HvCskEJSCmtF z+*|$axgQq+Q-$9CccG!DMAEW>c^ZekcjA4_zc{rn+fidpyt}FK#2`1NkEazPq}&>% z|9k5?@Tu1{asg+M)>>MiuyB8cH2k6Jejq8@P~p{$f2sqXZ{M+)~PD9S$s4r>L%wDW6xy-ib?G9#m=EU|j*R%GidE~(H{ z;8j82oY>sInr;BnkGPOBh-P8H^58dr_~DJ$oa|D;%i+AXga~Vg1EI!dr!&7~wBkf% z4n&^0d*pc9yA>OM307#^=~T%0d~-^X`vm$)t^^F%i-s_<2_~;3{#)f))yprUzx*yH zO0{{{h|!C?k2GmGQ@B+-RdH=jn7p8)w3K+wiC9Hoa`;r!m4UaJ1l@Cr`6UfQ!O1#} zYSl5D$V46&X>n}{hj!$h{@ygsQA;fxRGoppY0ta%!hpbJUIyB@AqGAfV;&U1E|vih znY~kXXfi#0lV7fz%O_6VqyGEUnlyj>#UrRn%!V8>UF;UXkMXBwB#FPrsCzEyKThv2 z=W7auITMiX31b|8VUUXtUpxp)3oDnvGf2)VStA1Ck(fdpt~=q$lu7lj{-PA-tuceA z{u}*UvH#mTPkl96T{u3{gHMkSeV)MXtP^4pc$lhbnd4|QAD$5;SR2eyQOl)>7G*q;lG)iveWVfjs z^8E{*1{p+#?jcUdav^swetqNskUyq!j5$w}`<1++L~*~41(;)WL9*;dcHnqHRTF>; zdiyN8{6+e__anJJy$Mh|+~$2vSk2jw#{t)rax8499pc;88u$Rb5h^XH}$$ivWa}Z(TD@^1)Tl~33LeN8xAuQyd;?He)NxW9g z!u)MFcb$?y&HZAJPdC?8nWvI$9IIahK8vQ)8@n7u6;Ez0rbyHW(1NRE3o&y0u_b$R+z7$JcxmY{3MN54u>~X0rub zVE0aIIa*-SWrxqQEeE|5tdCv$RGcu)kNtQYIZ!DKaa$m9pPc3t8A#lWXJ=gXxOE}< zbqWzYMZ3@v+0ufYhY7pTsRIW9FaVcR8wW6V*bJO>6V^ML>A+de*y_95e!rxtYgv<- z!O9y5y8bD1I-j_T;I1)KCbFgCPXm-Rjh74G9CzGzm5|!RFjNLD^>Q(do8U%~2p0UH zd=i1mq(!}Y#(y=i?64zndF1m@?AGF04-QkR%BfwXVW(FNE)%^E6fA`h2@`H>(B@De zcF>y0YgMn+!rvN1SMARaXP0Xb7)(=*&E_O_ZbEAwI&8b@)ALelzaC z!h{UMr{w}R+#@DI)uO2&@<`N~2+pULFPI*fzuEGo1``xcEH1!lMWAKfz{GRr<1mf> zx-FSdZVf>)2z*Uo9CJZq>&79lZ$;K~|N|`skMA-W&beCT{N0HW{Q{9L0b{ zE}brZ09?tDxbk7A{1Tm*grU*u7ecrc_UqFqY=Q%sW0BoD=P*>WbCqx(aOdQOc z^YXoVSzss%I91pJuCL^}{j$yk1?{}Nt(u0--6jTppoVN$p| zc%20MIQIP9Vs{F^>q^_+F$1klyn=u_;sIf{F~T-JBO{WknN<3;TV`N+b*G?7TG9@p zK*sUQx|^d>dUDpsL3w2cf*+)T&*2=W#5pBq#rr9q1mxG;&vj z34jo;K4TDklS>eVjRipF1HhMTrJQg%v!S5Qx*4xhSTV0B)VIFL$!R3?n*y}qKKVQU z0w`#NXVL?VP4VcJk*&!2fXyR~O7g|aUk|Kov)ApPG{xg1PqsoMi5Eixg2NQ%;wa52 zdwXm}yi}{YFJGIG4XPT81_qC_KuauESSd%KWiY+a?0{muw$+TXvHzs>I?Ylz!1M5Q z`0Rr}g5oEo{F!vu@pddOKryI5>LZY@+!;B7&$0Yw;qdGi_7|uzXg(UerENRW|kGPwR^EDz{ zb7Clj3krub`PzjFr;klSOvh>_|2#IZ0(I0!^sx5{q>5pLR&paJ?K|R{cvKDb8s+L+ z`V=lxQn6hOszx_;Kf}9urXjJ1uW$P&WxQQAR3Ges;SsD18o0z1LL?%WOYxwE7R|g; z&h1(U^X+BU#IY|jstL+KXrrKC(BuI}LT^))9$?aFk;YY_Ko*vV*d~FLbE?+H+ywWb zZaoldP6tuBoT_Lcpq64edULLzm5j^+5mfM>;Jrhik4yUjeXaUIIGZsf zRGtO>t@?PCx$?#pGu9HQN&Ulm)(thVRF}t76YW-G$xWc2qJ1E+<}@Z`&*6S)(~O{Eqsw5`*3SY0gt;2AO>!i;&yjL@1rm?fFu#U+gB zxF}<2S*zvCImjcJIS9J_J2_Io3u1zCI$Vv|Gj1OSKSiE{X(O1K1M745(1=iw+{q=* z(A$!XLE4)7C~~|Z<4&rr_55iQ`s!d{Me6#hNA^cp-j?M5uiS2|L&(hVd#LCkg-Xsr zVh6cAJbqXE*G7PWo2{8$f@d(lHBEt6p{C=xuED>UQBHYpnvB!FD>t^TqR@-Ff@l3c zFmm=on-k@8BO0dbSd=rql&Vq0PauV z7LpCM(l#S#StG3J82|YnM`6D(lxd@)7w+z6lomJC0C%uRd_JXE|0p!_YD?5qoQ|QC zvqoZayK$=c7PAJ+)e3Df`o{mjU!2(rs$z+5%;m~WCJeXySC2bTBnz-9r-~0Zf*#bN zAoJw^aKI59Ph})y_6Cbfd9>S`$^MPJjh;$Cx!w9s*9cXqdJTdJZYR*MWs!QHfj7bn zouNzyeAfAGd^<0nAf0r4Y8%R4e@TDKLYuu0eOzK z7|)t7e(B*04W{|GG>Q3gAYU!92`2pT27yjT_-2Ard>lV!b>m9Ay%TtzuGLl0vk3AN zlz#l7`vqq=bl`S*#An$(gm+S20jn+x+E2LS$N?aTe%JNjlEs;gUQzyM>Xye$J5CeKNXl3PyxnW&5h`{4=1Efi- zyLqUZS;{4eDLOCh4B0m98NY+NzTSA&=yS{Jc~X}vd+0f{z{dWf1J~BA#byGZxt|M4 zYfw#g*_w#8+=R1v$Apk#^te`)!D0J+&_Gl$-b-rZqF!makoYzmH|43bXDTS$o_jLnMDG-&=u&s3l_St7p-vTuEspzk8&PCD({N~t>`0m-2wO2~ zqvQe@JFXLgrtBi2BZ(&B@XEc>=!~SHGzA;AzJvcLZq+Xr@p*77V`d~l4#qt0ncyTi zmZU0kaL+lT_ILQC`?43MY67aMjI=CgYvfQ+0B_GQR)SqF4I*eP=9_6ZD zRm3hze`7jJ9RCRq@{hOG<&y#clBMXwdi!o0Ka&IjDmVJajk37g7kcwH6yih+v1=9{ zr`pqJkQosnz$tgzCSoJ{l}G(n#}ks-%_6vC-@wTghY#q_<6CE!+Wly3pE)-(h(U~y z0V>Du-;Jr)zbN6~_>1{duz>IyB>DrDH|P4a(D_}4IG!DS2THT+{xHw4*lq_ygr;E# zQ$(KYS>8NuO^{EWbSjCJ;|F!-FgbfS9PfR5GPZDHR7?lxR^Uy`a^mRUY)PFBk zy~1#KZWeZBM=hWH+NP?y3wvSTo8kS*(W?-UONFD9L>J1M%p13jUK}6+DgsA&99~Wc z<_uvXzP2*9a^nJYm9z))gR{g&CxOrG#8I6i!0q9PAzqMlkzsAnBVWRvSL<@ z_2FiXFHxgi3l(k$GPSPb)$*-SQ_qu~|1Z@67A@%tF`7r83`t;y07fDd-)>t%yMuiCWx5In&MAf8E@gz|ad2 z`NW5R@~e7};(@a}|;{GRt`k*%F`qv31~W$4$4B@K*f*$c9FgaKC!Qjq0zgW;KFiny}-pX{Tm0Ki~Bjgu!cy&!zYD{J%Q7?__q#k$US z^@3EYD4;np;ua@3Y57<~(ufd!I7r zay7?A9T~&tCvL&`_PR^MymBc0G&%`O>E4F*zwj4Ck&ZOM=;$5XYaULo8dSUdjPDmV6hxGmRSQ4V~>ncI(+CgKQ23A555DxbDy73=jDt? zKD_Cd2x4Z1!k%Iw;1Ki|Kbg)L1iWU@{+wj<(QMOeMO_)*$2KxI4}oTw3d8z}$27>} zVvc?6T;#p7apU(LDn~drQbeis8zo}^B=3wjFq{%D^XH=KgZE&p+rHgr) zzca#RW?SaFPzWU%8$Y`YF^uXol4lVX&Vyle+2qn9*7s9e_<)*z_dwV!9jZX5>s+kbHoCq!(iT;fC2A( zb?U2e@{WJ(Q2-P}bY#h=Gb%#jFS0@$0nKh2>Q;jy7aAP17eD9MMk$QNfi$damWYLE zL&3o6SI(681G~_Gi_u{D%{`S|S6jUgvskLH=CS^WYoj$WM^i<>&-dq}U@~6t*;1NU zTR1%%@b(#)L~0@T$YeM1u|g$Gsx$xi3uJ0K<)GXJfP*VF+X7|usB$0$8kWpj{fz6W2JHvUA_Db zYQ6{ac#`zpwvsw?baJpI+XYcDW8(?%jX92J7eq7z>NeEXB|9k$uJ6)rjLSeF;e!Gf` zQQ4;-4w2#iDR~~(Wi@d@YORpYUy19h!8oODdSC#9=y=q^TOT9v!PC~U`KN?BOGMj2 z)a|HRt?~*ETOTACkh^;WjdYJUajL_!PXE8jMvy(9COb6AvgwI!JE_kM1$935kn|iw zS)h?(TlO_=@(TiQ-ohCh#)4@D}paA; zr`BcN&;yI0DRIClb}cVwiRBpO4hM@iPPQ`5zSMS|AL|GH{`ux*7Tsu>7ISJgr?b+C zGROJiO)d^Ma#NZ}(V+d=cWb5T#e(yp@TnncC>=r(;<0#3Uh}Gfs#6P9{asrDucK+M z1(fj61iJ}XA7f0|DM}%cs@*r13U3dO9a6)|PUwRp#P28#F8bJ-F)A6y?+gvPc6u&d zWDu-c8vjMDKtW&_Q0ox^?)vSrlRgl=o?{w88eqS*Jw@Q1uWbH9NuTv@-@4;{SAl;+ zuBWz6Ab5qXl~en2ZXx8s{U@5D&EdL^G^)4Ou}fCgZg5mWcCs*ZAbpqHZO)c5Ib%P6 zn1xYxeW$wZxa2XqA57nZB@b3Fgzt~U~w9* zL^Ly@LTjZ+8wOfRVj?MdgZ7UE+kZm zi6^lK4*2$ei&OHP%4PIpq7c%xLl~k&s?nW%#$r8`!Ac2q-;u`}7RaDbM7oz7Ze;Jj zLz@wHL+KMOLxub1CSW6_oWL?2#{rUT8tp7U68M5rE;eI8MRPiqofkb|O0sP>p`f{N zpge(^f0pQGKktblH*F{)jF4%`@}aIcKI+XE(eZF6E|T#~NkQI-0E&35#e5*f-XAjD z>+*Fn`@aESq^63*(=bHb^tObl!$at=A3&sfe2Q}d!PJUkEGMybOHZ|cZip%YZPeG~ zx`Mi$YsFP5*-?t z;3DgS_K=NoFTL%}>MC^ac1r*$7IrwQ5R>{#UplBw{P^1L23ak-D~Y|#4{!Rj66hyh zY^=+C7fyR6OwJU(<^EH$KgZ1z7hU!!u0=F+Y&ydfJyag-yCU`ki%ofjMAZL99Jk-; zM8|3k->5$fovdUg%}aN4uGjU8bcG5c6oeH2oQez?zna}f8(bj>{1gR*1XLI#O~l%i zKvr7mN)ormE7Y5!vZqMIn+OiAC{a)TVqUb30;b5TurWvMVYUE@0I4Hc#IREkVE>_l&pZ8A9CU=Ri*|z^Dvbh(M;sNt>-@r^<$ht@aHk z%y6k^%LjEc_YH+#e#pvNI}*RUA>lb1b6F8-O) z!mA3Ec)DMn>LXI7a)`yZ_8cqJ;M!rKlse;kXYWxriXNbGd+ZU9YY1tw3C+^pZe40Lxe z=pvgLqK0kUV!(l7`8F>y2DdRwNP*JP0rb+*C=$AA+K;Y;UjmMW?KHNj3FY8&P=79?sCtP>4tZ3WNQq}o zuu<%?0&OaT-sm9;#yEoy|8Au&m}2AmYLrXpLW+NF_0X<>QGp455?v_Z$St@i>KShV zaQ?Yj|Fmt~`5qW|m)Ns?GLahcZ&&<78sxQCn+UzaJ?R`w-tZBTZLA=2bjtKVZ0=XU zzMUam{+{ghct0EhSdjZ4UP^B`{uGc?666pL{%?};=3Fn(=kkYYBQ_}hHv$@h&5@WD z7Pl|MzNw|7Jsyu8i*gv1I+*NK&Fu!SKZIAsePb3x;PGaxQD4~&Q20f zxNlv|Q4Y{m&b*>56q0fzudNlDKgmCb#EyIkQ!3t#ARH z3$xS-&<1fefV>{Z$lLpA=R`aW9|=B{g~Ij=wX;zc=<)rahC)q>9R2qjbQ40k<@#62 zc{|+_X}zbnselV}mQb`)jCFn#L10pB>=I&V_u%gWR6{&C+H^h8m2p}M?${yt0*}HL z3inxmm3>cKfV5$Z_VSRk2CRPMm=$-{weo=4DrjdeeKh;j7=Jvj%uj8{q=Q8)&MBto zBGT68F2)}OoXjw{o<`k&)5K>3U)M&<-&D?39(1SV%4G;A!9IX+4|0BBbIY;+?nRV! z=am-{tl?b3HT;zLRp)a=WA&(j`N!b5>y3*z zF82Zu!sTBa!9L2=*UNG7L{`w9rRC%bSCL70Ihu&@dtM6+^o82X@rmd+zzq2Xq(*O$ zNje7Ir+tr0lr*rr>6S}vU)X|9;5)v4+d_Ly_pOO{gKDYs1O7BQ9X7}LM_xt6{^;C3 zUWO%ihRPsD`H2Vl6+!OHZC!!qg#_}T(emOX;Sa5zu*V;#EDXfXd$PVpRtP-mZ{JVJ zIlPVdXpfxcMe<)-!aHffaT=T=QJ&QFT&3#BRLE+OKzm*~`P%1*5&iICMEy$7Nv%IOa7GEaE57!-?Ijo0_)_mdhT5ax+ARPAl(* z%O(^8(E4r$4WqV1;^y9Cfz>r(#j38M^o+M@by$(zwXrh%=Lg6m;csC0<1u4=ICejY zePYOyX4P>cGJUQ5!!kyp+EX@|MY9dm!8hD1Tr+agV|Q9S(&-YOlqclKi3jN3;#GW& zMHsR~z(#Hu=~kAVW1(R?Zh5+*lfmAOZE0b|Yz{72GRCcHJv)C_% z+p%vv%EGEc)Zv65zzmMD2xNH~M6>kv3tc)W`RPq|jQ1&M@L3k0jal_13Gl7r&yjx6 zFQA=hx>N%DeiGc8L_mhv^}-bMwckZ2WRMCMN($C1rK=G%qZXdgMb?O_;RnLMf@No0tCaqnmugpT~9GP8YOzF>>oR+z|lT`b3t@1giY|;iY z%zk_e{ELymKk~d)_92~*6%~X}9&|5S=OY5u*bQ;E?iQ!4nB?1=hDIJYqE&}syjnom zTgXEkg+w$IKGGU~)p(^fAZIzDydx3?sB#N2kv(jCXq0)NmA=}nhtz|XS4&mxRl`$u z)q}aH4cF3Tqg4$AEF%NKs{1p3{~8jIxD-#j0^Wr;Aw4F5tQzhzQSV}F3nuEEsUY`VtO)p+L}gnPV=!;1 zWR7lXX=cfPNYwFzldpcqma^B+$B%;{yD(dtHB^)qiiuaS3@Mli}{D^^p_7t?oQ@p%F?nDbOyb#}F_LBc^E z2EqifQUQGGeKahvsFQmK;wW$i z0#TpN%oh{yQUz1?6%AcBLN8vR=75cJ;bI_EFjM;qqGY9-6RKR~czq)-71CfSiZ%Hf z^V5`xW2_e3rkIov-^gW~LV|KtN1Kh#V7?lo~pccL1rg6(>=enreWwP-ZLN>t`+$fsw^FR=ZgLWbQgAgG1~j$ z37VQ%+@jz+qLR#?90pVD#fC=m1`tw8%EG({GIQo&JEJ6b3OtU=0*LAC0VYPu8T!~=uL`_=~1Q$f# zyf4fOkLM3#q#8$nWs)d}S=7EAiLBN&?&tV`YN#qU+(AQi$skN7HeT35qFp&2Kv{qh zLV7n4bPZjE2ayCp2gO(T=%%no13c*hO+`+ou|}CG_2O_EP1%kwPP&;WvDee2s1SNu zo=2SN;n>tDyX|_MetlNc)U;&@ax9UF-M@}EykF;as>DXhx~IDQyer_J*J>!E*5OK` z>nyh@y_>SrUjJPQTI4+TktleieT;GYz%mr;gJzkn-et7n2ufe|k z{JhkcqZ8YEE;AzA&@?U#d4to;wiNh^EOeJ9Md7gOZOGLc@6oDnbyT2HsvVIBHvhgi&88+H(dn*lytsv2eaARz|P5hT@edH zuLsP?!yTW`^ZQ;lJn=nKZ_zj=M$(MCL>aBJ7w~SbMwP<}N&0~(0E|F$zrV1ibUE(X zK{5V8O#m`)?m5sIFQ40Qrr2ZG?MC8%$U?K}4y@A3s3MTPP82iZ5Qk*d(%my4Y~&su zDMv=Q#46)SPyMXW&{KghZQ=v@=^}D<#_VR~t;QT#&}6mMX5E?YSp4UF@P(h@n;> z$Ny!6N8V3DOuz}4b)jSKy`rq{ORb+)s*9Qr_hbI}qFK{Z2<9VxBnz&bW%m4{(mF6Q z+@ZwtSip^4_KY-g?2^nR&NX~bi927ozyl4r(_kpVW-QhN64e9-bIMTbDMs$Bt%y!- z+>l_PgHISIY4Z|^G8P_48ilOvc1rl{%@Y=Dk;gsP5rR^<|9Md!Jdgo8cNoeSbJ}!D9}0O*zY7ug7M`vyY;G~ zyq^Ocr>>=WgUQ^SwF&f0BKA|s*JGJHH2ptbMrU9C#yEU14>=bC7dx=9;g5 z3g&qJzX1Pg`2&pVx_JPP={83|e_DBb!NdIAbu@yqix9$%-iD6^aVb?~9hiX6N}F8& z$?Q(L#TybEE@=Xiye_j>hMDGJquDTY5dVm`NPkOSXUai9&WLpCCdKiXosikV9gV)u zLv5%Gk_oAF?WqCLv|*2{keawt&QJ(Bp(-hDYw<+n^#;T()UBvt2o^RvQ@5hjf(o{H zJz@kB$^Wr&?g%f1VB_yp43vfL=wC*?mSW^y#2ynFB5f0ZmxJaehO3EtO|NpiTO=Gi zMeDykM6Q$)``FF0eCTy$rX=iEJLWH+z3IFSL||>dR?F)w?2f zBOy>w?AwG}`T1BMx{En+>pP0EQs-lgPOlFMN5`ao&7b_ysF{dsX8I4) zJK_|c*4n?{sWfzmVI=qQwMZ7oW)t4k|NYf@q7ZUjm45BGkQgERwJAPBJ#R719xZYqhmQcFk+xtsqEjV+HlPx16pMjJ>sI_6ChED zSWE!(fV|HwjB#A1@FpKb11@g&)v-rO7{{^w&BasBFHm5I{o&@xH&+v29nsujRfrAn zR&B*dsW%3ucoZ9#@K1 zvoul(&KiBa{p9_7PVTSKE+DifcVsOTK*AX=2CM$O9FmiWnid2v((D>a@XBKB^*`-O zc1)ZyX^l`ue}~4BoBS(&-+!fGwK{jBG21CUKznZyRAipAsgG`(w-nf?LC`hCf<3@j zrX=@yyzhV5O~RV2V052i*0?Rj$~7RZH7lKs3PVRj;3PUc20YhJKz+=3v-}i`fY`OY ztiMH%nw-;XA~+AeNJj*0RO$%`rmq0k>L$vMHa(G>M!pxKdzY?O*t(+Z@zg5;lXa5S zlln7(5USyb84Q&=*Aq>s2C+>tm3Po(qNz6p!VGj}f;^|Y<+RVPAG3g^MeT@D8$rP3ui8if|C*j$2_AwFLGmlyi4n)_}r?~^YjPw_Wd5+ZDK<(kJ~aXWT_dTBB+agT~Xi| zcSv7Mdr)fKqWnxL$HA-Wbr+8%LgQW46+6G~HNbIe5wRpdn9XcOO-`0)47JQX60_C8 zP+s1ae?N!QY%>Mz>`19@E$CD&O$aE!FxPQ-Bt&&rMFuS@1U2V<_j)4wMm`95@f&i= z9VPXZNn7#h?^k6KhCZ=bIZZBqu#yuiE95X&Po!`Z`8qvp8f<^ww3B%OyMKXx z0cn9kQGn)1E5MzD{A4G+(WN6=Lb%dkGLGPHh30&PkEcV2we;uAxgb4hgP5burALYdEPj(M-?(NFC!nCZnHC@Qj2@oNIdgpa z1ERg@D`{@NJ(7Q`ddAwrT0A(vw4u~b-VL?E6fS+&|G-spyknirfRqE!*&cA8oO6*V zgu6j8YOf~phrk2~K(CAK?;s6g#-DtYEu`TFPe}=7;Xln`>KKHJ54FG!^Bd^Ye^49T z@WHq}I&z(6C=DJq0;J01`xgSc{I)s56_sTj#!so}$N&ui6b+a%LF<;W+k~tjrGh9# z9%x||uGjhi`hjCYzf*ja-hj1h zYNbzgo`Pi4?Y`v<9^CM*ae+TF=UQ{3AXqY)dF0zL_hy(;(!^3i9!7+|c|o&5Z#~Jve4?(*MW;&9$wpW5@OjZK7cP@fg+vx_6f6IomfS zNU_vg>&eqE(|Ve&Ub{tQBF2cqTOkZkkA8#9L=+3iJ!F|@JS!EOF=!n6AMj>KllmT(_rvZ4;93_N zilZ^B%9PW6J*L`ph%Php>(%rry7XRX7eju&giz5k%YSovsOZ=?C?>B@r)G%vb)=nZ-5R!>&*{}@ zGv{d?+)c0=g3Z6&1NNQubuQ6fvTe;mi9Id4NYI+gNz01TcK%O?o^yR$DPZL+>}D%9 zFR#cjgkQf9;LUqR%Yq^dHFviiIgb{uI-g3*cyHsP1uyKn z4%D-YB&^0==SIvHh3StJh^BwJuW(KWlV(^A{d(!{kT%@jV{aLQE_|k5$)ikO8x<7c zlm?oVFeofBCfJ%?QT65u;X()LR|9{4Cx+H>nnQ~f=o{3ni3IwL;UTM5doGE-;kIxh zHRm_;_Ik}yG`n8ht}snw0B5Br!q zTn9`FdXPth?e!9JaaL6oo!3x8_7BdH4tSo6ZE8wqW+woTB@Nu_mbp6*JTmlA$F}#C zJ-66aJX|3o><_Zs$WBmrzTu{@`gO0lfrTWks>|u}3SaTdCmMu_p>++?rtgr7x5p(` zLOCN^!k^}E4(DQ9@&h3@*xXICOwE_Quj2&~Q={+UonbdztgD(R8l;HcUuQ~Q&0mK9H=~0LzXNs0EG2+K%$d)eP}`&Z+DhuvV^ z^?^bCN6$h-!zS?np5(!|(F0&%zBWu|Rxq(zK>Cyhj_+iE_z1cev5fe+p%ianAl50( zn7N`c>iMA1E|p#I^b(v>I=RzIWUDv=VVnz(xeJL18XpX!J5?u=qaj>kqg$6~)fzMJ ziby@hq|&E~MpC%UZi3yvnbEADGDFpt+6;yeiY@!qU_CegQV0saJ`Na^%Uo&rdr!|O zi83?NS?ALKSz@1;4`=BXR%~}$?ml=73Tr2;Z?pbc$fY38lAXFIgM3694il{F`8T8& z!nsiUxZ+WrGD|d8dNPY5oEq~!Uy-T$B8Q$|3jxDw*{CwFe&&sn!D&B0f|?L>$Koc> zxM_Ui8xMS`_od(|pcs%jBhcS6-~vS26L*p0M6~TsyA5Q}zMDBhKvV$j&8X<{cyCc% zbT+a(|8Kr_4WTd2HwUigr%76C(oQ3fhe0w|MMLduAbRR@k5?oRN#o9o^>hb_#l;O1 zXBhlaoifR6oV$&A7cM_ydyilu)Im_pxdM85Mejxfr;D|7r1F=i|L~j}pvf!6j$JNU z=XN4N?Au7z9A1Hrz3ZCPXVInD$|b*pcxvae1e(f~d3vw@gRi0ts^f*&R#3cusn9WX zpmt2PM-@EnZHJga7Ht!gSR93Co?1tKc0(R}p|7p*Oq1u?{ z;u;lv_k6c>=^uHBAtkRAM<)3yGnLMKQ?2ly7ei4RI?1u0+kG^T==EjgVbi+z5Q)jn zQZYury^32oRF!UP;8??YIFj=G=rr$kD*4;sT~48@p3J!aWeP4cO`fwGO7I6hUub+{ z>%wj%{|K#ceJWP+duOEtW@!5czQI(`ohmi1um@rPuEK2f0K%tI-6-t-Y!d-e9_G$T ziQy;y&%%i{Ic>Y*GR_#)oF9tb`YK=jb1Y=$t>lm-_6(j;f!50;vJ#ofU-|#e{8~GO zsspGa^Mj($ihj8cGH6*+L8lCi+{r%{ZLs*FhGzWv6?`}aAvF(nr?~V~gs;y(UNecs zjxvOwksqQv&~E-^hbwPdjFJCIr5Z+^lxHsKI7@*amZ#73HW`SOv8cnP0v=0sVVFNUlbsVmU8gxKqEhu| zo%2R#YMr-$+@ygZ=2ARXD!Z(GHzQ3J(eT(}j-%Qp&bpRZ#L+H>oW{XG2k!alr^k+{ z>#-FN1=`9bhq-xCH!qD=<`If7Y&X5jc{-Qin$u2UL)XFE7HsDX>Hsp`gHQN9xrhVN zDo375a{0RiKC-%5;k9;7;f_ec`6%vo4XPSAs-RbvJ+n(iJliLbNAFcHU2rfDCT^T$ zc4wm*Kro-f=EL4KjNgiBOp#xvVg?{{&7} zkq_~#Jclk~In_*yl?TZTa6K(&mBY?fC}HUEz8Ki0c-Tr|YZtZbz^$ z@DyqiAMqSSnXs6h`emfr^!ePWvG8AElDUlphBap{#M6ml404ZvM~~GxwM&>PRqq7#Mwfpl5Xq z$QsI5%}JeR&*pY1N?~bRo&lsc+%5fwmF5*!O}Af8#y+`-G&PAMrSTS6WtL5Y-QvJx zP@%r>8cRDGTo>t#AB|DAFyBlT!tb5gTWygrrA%OgGaq1xbZtz~nFuR3dwN<%z7u&+ zr9$hO8i&v4x~;f9 zKZopoRNELXxY4p(?&>q~AYT@#nwY);0U7wn7M*Dh68WiTg5cc;SGNtn9qo7dZR~>5 z5QjG6T10LXOPoT^s0W0#1+`M^hzMY&-J2;HWEsbYAigaBVhkazY?LY^IPfh7#Cku2Ngv^+jHK^uKRh7!=d#29i{N70}aO-bwxCl_5DTb76IP8 zAKmOPtCe$9utUFdmmOQTXkD_prFV#(8W}#{GuWlB)VyXTzA&GC?SZ4PFN*svs9$gJ zVs!m}tOLI9W>-OVQ!!5kS3U=FeB{zCHR^62K26>|`I`cDhD19J5o+zI9N~6`(C{BR zs|B>j%*v^P_MEN3(%T|0=t577xW13pJ!|90gqA|#xPZ}KY#--QXGC*p&n|RER=0NhddJEGhT?IT##EQQKllZaTSHg8uwKXjH78oSyPIxOgza4nYL$!R<_qVg)yoo#{`6-+8Xzl5KB zG#Ty~R2;|>X7NobdN0rqNnegct^~!y{qO~}Im`lydHZZ=a?DvseRl?!%vfzo#YC)# zR+KypOY@xRPjR67I>?qZ*^}+7knkz;I9? zpId3Yl(6<3dOZpu_sC>8nCU_#OsX^g_zHu*9r0;(f3Bu<2O+({dHmq55c>A@d>m!f zo~!e)j0S~XpziL-*Qb51qrQ8A7e(p{4#e%4-)kV(N1t=n+{QWkUQ1o0Rbd##&DR(C zh-EB|sl_VpkPhP&OLzCV!}Q|X)xa2YU~uFweF;qp`I{>ofgFk#JeGOJ|0U96q&JaW zz5EplLls$YWjMAUqKEdCRYZWbnz^Vf|$4$T4v;up^;O2u+qiEG&Z=TZ~S6XfAL+^F5tzd^)n|D>=ADc=MQI zExMG1cO($RE3e6yjW5GS-G>bRLl2>NT7f-VoVi6E8pf=`Ui9&eYB*aMe-_vs31LU4+Dg9#QZzfDa&c)) zW7N%}ooEs%XaP%i5#4C}+m53L4luSii(l((Su6xdoH{|%{`nW64u1`Gzq-b1Nu}xP zA{Sh6oyb~7xv=N(3#l~~sev5NHbf}AuLL&9P{q9BGAq!TP23X7qkbvpY#`*-4D`B9 z$3^Hu>C>AKFw+kSc`UL~&R)D__Azv~aaX}$Q<3^x0d3t>9%sdoKk`!=f?C4p5$&J! zYR$u)CqKwd6==3%IO(vEr}-EYen%WwMN(9;V{9jjKJ5rf#M(iVYhamapilD{nSuSl z)UofIi@mPR2RrP&iF`pR7Z|UgEq0@O-Rskz-mgusj*sI7JvIju{GLw4)nBKG3-moA z*#?}Ok!S;RFzm3-)*}+*a-MLB=p#dGc<@|e1%r`tV9H$sxg&hMORQZoxgM{u02^hg>r?n;+F z8kIi3r+iyTkv0!u~rI>n^fn8R84tKcF8)o5{&9snfmL zEC8&9dg7=;O9;ABg;ZG7a7R=fHrmQkTin96pQJOOd3DIr;alLkbIZLebw=33Uw!o? zv2Bk0Ik81@Dj<_>YoE-Z5QZvNPTBM@Zl*>#Mjucz-+z#orBYgcrAFOq{9v04q67`d z^RpO|Ruet4VN*u4FI_{8>vb4ya3?#L!eAaZ7O<~&|7tz%3YpB~>5$i^!DX_Tm08z5 zgAS`Z9KPMIHw<d{O!trm>ijoZb%9cfxCeOIuOfUbfj>7*Or}3*yRl@P)MOw?)%xof5#GTL zSpL4B?UWF89unIByt zDYDVs1QbGM^5dx8A5fS;-l1<`ePzJ`?WMnW-VNO0@N? zQ$+8~qDF2=@zx5tFj+;CCOxj*xSyLGvHwiqBTPWkTTF2&lpm z#n155B&is2?pv=jA-pLv(XQ;4!KVcb^u#EtybETAGVuRW+UMsrSDbEi#pFx$SyNvm zT&l+|43?_d+RS4m4eL+}?M`TqW@f~QkOx8)PTIn}Er(!=6bDz6b4D8Xoq$C0=>z&d z=~~ZbGR4^zP5;N=mxTcEGx`E%$5qK&N-3Kyo*hbc1z*jes}%jO=;+4sB4DpxPT{Gw zl!Hk|W(UNm8G5@ia1!a3cU!I!OmD$Q=R&cb(`|)=c13z9We*91ZQI$iZU_@_YvSgHSU{!9{e1$GEc>aUEu`2wm9K@VeG zb*$KQBWGsavyXm2tMl=Ka%fPwO_BI0+$p@OrmFWln93;qL47Q!uUXPlwBc3cyhj{m z3|&ncuGJvO938M&(b|Ufy7q$am!61uU`6gXID?O<0G1km;Mps7VVsS$*vAJr0;B(z zrCYUmBo_jx)Co2{=^RogC9jzOSU}{?jt)S1L+3NATC@8zZl?8k5h41G-4{e48jYNP z3Q7mfi)92Vs3j#jx^TMZ@__`-IdK7?5FtTk$jl0tv5XrU%&U#bVJXBZ5)0t80*Y?j zHQR$?qY0MdI-o<}-}~w<`F=0>a{CRca%kfk}Z0e7Tm}x zS41sp2Tv!pKo%|ddPz+ug|XtDworaL_0IAi%%Eoi>%$I=h@H;ed?bUQ^cH#SYwInD zAwC#zUNI}hiv8!?UKB!My{|{_U;00BVnV%WBvoBEW9Du%u~N};c1XkzS218ean$J= zWSz$eVR!=Aw-QzRMwR9`pd!CY^M!2--;t#9JPQSTtiaZjuu#VKFpPE)@WN2BE}JY0 zyX#u>|D6>yW0wtWfSl?-o>eOIw&T(!yOf2FM!Cn$W5zDVAPz=1Ft?sX{L#%`TH>e$ z8m_uml>cCG!p*3Q4jrb{fN8IGRavvkvH$Kw0fj(hwpt!^Si-QAa-Kkj<__@c82!4C zczN&HOQC5DyN~2W0@sJ9JgNK;Q?Tvl3f8;9f3z~f4SISk#R#wo9^ml%-a}?`!1NxE zGOv^YcsD-_m^uxjoKXAz4peGAW<0p_G$jIn%)z0;+r|`jTh*UqBCdw0bXa9+<)Ig~ z-)xFOi8X~*OnrYPJ{#H+zcKpMKz!r6RrSWjoELs^2w`%sj$RUrtP9l~*@A4=u50;r zgKBUF)jBud9c3n`&DjthS$;9LK`|$nX9!a(e$*U4@RmqM{F$#~%E;DZFg}UZE5n|1 z_S!g;EHS#C=3lxD1ns%#O43)!z)4}wjFXtU)9=aM*ncb9J5HTkW6b@QYA8;t~3;K=xO`g722n1~s>hc!pC_aWNkGEr% zu$tKCmiKK-QTG*$T%t-Kh@Ko$6)V^ubnxxsMEy;`IKz~*@7GtSKAX{b8W}p@k*L^F z)GP^D!HFEC=))hWy0!=aco;@?tlF+EtJr$4HGlJz20LO5Z*v+qBYPir4iSEVV_+u_ zod{4+6(kpD)+9_Uo^0AhJ^GzVU_wIqxLw4!*W0Q~b7=;hQm|0NQm-q2AV1K8xy*&3 z1!o$?fb(>_CG$w0N;C%w>a)#D(U{!6Q6{cxFmBdul}9IisO%4u3WgHeHy)Ti5gU^Z zSHb_&=3rlCxu>MmZ{>pwbnV~J)uqGcq=kY?KQ7>}*-*6}Dq*>mMEZopjTI>H_Z~33 z`TK2sb+FxgizKA37K0Z!k-kZ^pi;eEOoLicKyQ@Rm% z?aliPY#UG8(!{k8c>ay8YZlk+ZBtmkgRhgc<^@V7O6JHSX(7(5r^OQpX;$G&Vsr3?~JfKG4@YQ!+Xv8dx~Zzxy}w) z8bq>%r5zO{{*c@cd~sM7?&S8|t>Q`9nmV6zf9r!AeZk5MYMnyTl7mR)Jij*n+tFoO z=1C{1qZB#52U1W3o5X)96FxkN(^Pyp+6@6V7TrQ&l!d4bZ9;I>Gh>LFB#qfp0>l1% zZX*Vr~G<&@~aspMaqAe-Lgq^Zxfe znidn-16K!%MoeOOWMF#flk;X+7CBE#^<2eqf`RVwnF{LtSDpR7<4QX`;kqmlX*yRQ zKCu8wx5*hP8n(rj*Af=276>+~=k~lQ6UnZkL*yE2c^^qW=oG%!SzbYQX%oC;)OMTT zt#M9hSzCydtR*}i+6j{~q7Zsp#tbVobQ)>*4T8sZUxryLo00)`H3q;4^lNdv?Q=n@ zdypjV6Y*IP7=BOcAk(yS^#QBLOO3+HS(d27L7_YJztgz@CQ*s<%pRx4J z9GsN6)4*?WBHA4FuQy_C4ALhsHK2A`YW~dtdr)-0DZaO|bh80~_9}zWoENGDph7`= zb#8P(x_w4gWHS_R-oeL9#Kz6L->=P27(GtE*z)zC9VYCy4|qw$ACifUji!w1{=*u$ zk-X_;U#y8V|E+(b00CThL3>s}O7Zel`vCxj-*B@(Y0{2Xrd>Wq+mwI5pv9;7nhc>h4ePbgv-V z^HsZp0MNz^Xc@itHUO5LotQ2M?1T!aG%)hROZK{8g%`MubKR?gD>3@FSECDB^-PI# zk>T`>I5rqwCX@iz%h9GR<&Lmha+%vuLzG*8nqiw(oCt4thsV%{ucF}&lP%6P1Xf?P zAmAaDv7gxii=aug1j0GVJM{z`losD+f;`Wy2IuNw@pBX?E;*1TkggWzwOhOb2^+5u{>(L#7D7diG5zuSq*;|zpfGPm=lf@>3Y)Z zQv3c{dA+(@8f1uCGXkWNQA`el2-wqYN%N4gQF)zk@w`bl{59_jJmD2<(jLiDVY`FkR!4X@3^Pf#qde$?+PL!rm=9N39gm7d2!~ctJ&Y@neYe+N?)_59vAkdohMbI{+-|{J6 zf!sx*gMIj{*PqILLLJ(WQSAY{9wZ;i+JI+r)=_7+(XBcSf{nE9mY@wEhaxNYD+LR6 zmWp(mCC+8g;hF9{O$F7w1`Bmb4XE-JzL{*Z$>I35VOd-edYD?%d&wd!HQKQEAMUWf z)e_K?sYBO3*T-B51J(#?M0y9=gxp}S$*ZX^-JZac0g%xWkU$w-&hvuJ%fE#Pdps-< zZ6};wKnPe?ypa{jgO=mgXN((v?rQ4rB%AW`FCZHlD6F9gO58G>`BV)et`&%D_?FkU zaAh~IBGkANVlkgJ>GRIY-;)bYzF~Fi8T9dp*RvJ?rA#G?OO>9GmX< z{CEszqA}fQwxYjeJo8;|@C4th;po<`gZV_LO(phX{1VTgkZIzj7o66VZP@Hj%xsC^ zd0U8Lb+c`l^jnFo%iu~On#!kCzxq)lKJ@2*HZBw8DwAAlRv$oV$Qr8T1`ewedLF%K z8f~UnlQonja8IN>YC!8th4zg@_$2Q6G>oz@F$Tist--l%a$`_9j_7ZKNg?*CIjnK@ zmwVd7I^{bsm{hDza_$M^lFi80OUU(&-hgU|E5Egc?8B^oe;n$HR9P*D5tuW-Whh_jo{kYSVi=5aRY&x6bpHvq}1MbKD z@i&gJG!Pbl{eUL$_EEO^MWj3rQYey|`x^(W=Xfu%m3iQ^ZMbF0bdds_H z5C1ub#D3>rOl*MGV>z>f7@tBJ;?3j!vc1rl{$F0_Dk;gsP5rLy<|9MV!Jdgo8Zg$E zSb9zcOL!de>~}3Sw!~W&`}aDaGdG1usw6k(t;3 zv5p{&1I|Ujh8_`nJd}MiH1^FUh!qy1h8IL>u@2kXqZo)-mQhC=&-f>`XdWCdnRh8n?+$u z#|VT$`bjIvXh(DcfXg5;LFrTvF>-{K<7@7?o9lcMessQu1oQHY=PX2m;__#_i)4Hs z+!K78uiLIOH&sJ+iB+Bfx3M2QeUK2!1Y(EHP~)T6_7FJOYsh0O-blQJ-+bMZAzWV+ z*y603-VOHDpPc3`;~lYHhr=3x&astrI}@5)ry0<^(bW;2+*NuwW7*)9VY&2!+Zj;& zmoM1{je}=ab7#;MaUU|&K|SfMQrt!RZacGEV<9u}nT;k5tUNbIa6?2|8o)4aHAz5L zgeyC4mC$+(?|*j23quRA_G$et2SEGNGtn$lALJhbbjS;i1IT(dV2&@xs~-?rxgq?~ z-RMEE?B}j?;e~=YJ7UC=ckP-V8D`^gx8lJBu!DP*qaf$SFt5M76fA(n^~f#XWW)zi z+k((uq9|7Z59g*djHjmh?_6-Y8OV9lE)4>-_rpQY`oK`K^`P?d_^QEaxb8c2Fa)J6 z+Ljkg9J3zF^djQM^{M7?y*4r7BDtb2p=HrushbdMa%C)UC-QKBFF*%jV}Tvi0^)>U z10bxJz1=HhWM6;MVqy$~QJnpf-u!#y`dM%ltpmlYUV8KT1UX?K=M6LJKhB)OXZ&|x zWZRlcN_1zn67VxL3$z2`512cRVVnEQCQDADGOji{={D#86v{-HAXz z&qt!kDl$gz)&N# z7vT`nJC7DDk|-25=?m2qJA_8U%6GU`g$gX$jrrmi?mX=bXeZPgWO_vb*m9EO zw=9N|&Yc*+k-2y>s%=uBuVOC+*WP8|-UI?U@p@USG$fMDEoO4*+<})wfjFuK48u89?riU_@6<;s!${OJhXh$C9?oIHg_m zVBl&^!El2ea;hj*Cp@;9`_h7ryWnwwl~o2q4X)R}IJ&KWoqHe-f9NA1qwa_<=aNi? zbZ2-OjAwwv{lJm(TcTZEsQ^vNP~hYW&s_H&(1fx`h@&vaZhDiGP7mVpN>|fy$k=#G zGHN_`zo0wBT9k+X{xwu^hQSL=1;dY$H^dy*G6b3}mrSgI6z-U{N9U-8^XOF^y3+x< zRjBtU?;-UK*%a+z*W*o=TB}H@8K5NFdd6K*;0w`HNThrhXjP*8Oe{)U_-*wUL1jYY zUDXu3zwR}_aa&QbBtV#o>_tsZmTNq;OxTG1O5mt3Z#`3=!|ApehH|TlRJRuNDXyl3 z6kr%@xVyR{I;*0i0`eIDjsl05EjKKWaw+LIz)<{n26Tb6WcBX=M1Md*DX-0wXr3B% z*1Y5lDbU|UbWBdUFJaoUfWPbzj$`XuJt&p>ga~i^Ilb0N&Rzix{Y1^siIvEOVSgIm-HrsT& zxrSf|{SUt}TmJoaF@{76!Pf9&X*S>aJc1lJL^M`pdNF&8 z`GeOL`J<#Nb6_xCWoMW?>VX&s7JOCKU}JAJD&qzHS`~c*Ee`QP$&+Z1M3VAnIaMID z&^F}yn&DJ0#Lz1iGK0~!ySAdEb0vks72DD*n(!ZaZyIl8(lPBpwWWfSMZdxJb2fdu zg$&5B;#W)}3nygMaZv)5B>C7EIqiZoQvOzh0TQB}fB#9#h(7n+$8Tqpm8)tDzN+&Q zxAl`{m<>RKqW<#D!OtSD+V||jaS^tP+yBA^tK4a6i9%2tEpEy_-ao9xXN&%W8TN9N z>|7_k&mfXwnIo}Vn0UD&Hy!wz*bJT5)Plm}qO5Voz9;a~krobY+uckYdV*-Em&>O> zKxHNuc`Gw>99u5{Yj`7(goO;or;)YKi+z$3FLf+%W!ap%!=5U-&cDkzpU^n!AJ>sCU1%STJ~si3t3 zu%ZPTmTjw%bZ!r!%FH456RUq$2xHB=2L0zd%vX=FxM)<0#GQXKV<+=qt+6;l5FFqZ zA#9HLLIn*oZIaJUo7y!waYyLsV!xr?&EG(L9C5%0%P$fU2o0d84~7S?tHgx--wwnRdo8tw77EFx3ethNVPBWWpHhF6u}d* zNpS9sHToU0;muhQWW0?tNdqkalsZs?29>2|g3wfecJw4z1zODKIF=2mBDOC_322*2 zLpUy?pt}iMk3Rq|WXRlkf!Be6mGcWEa}R1ViCgaVyn^}#55{+1p44hlsx#=3sL!eV z2AQEJP6$m8ni3_^jM0ZJHm`G5B3$yLT6g&p+&_~T=!MU&7i`bfYxDPGFsVS-+lIMW z4nX3bt89hVc1aA`-nuk1&e7Y9Vh38Ac?AI1-}bOSO~w3)!q$3!a-UXYNN3k)*|1ywJpaWicRU`W~0*H=w)u=d2i4QJVJ zn?~kF+*T~)Dj^21K@%=+Q&W1)b(4|CJ*98FXbmuGG|LHaXPo4EEC&*abV)e1WD9A` zDsQj6I>6B85R~#Yz?*jV1{i5SY29lEXWZZ+`jDC)#jJ(c?_=~O$_orep_#27Yz`*E zMGogDp%Patp>6wHg|WE?W_qvrny+(al~Lw8TOzTrU)l59O9fV-t_?|t;xu@pL4u8h z@nmoa+opbXI9X~D_!sPd<K7AOath)fe=+EzwO@(fRnnM<|m(BSuq-%nfEmdac5|k^agNS6l#~A zqrMp`+(;}GUi&#e9l1r__Z1zE#p$8pBf8>xI`~J`Qss=)7cVR`RpjYSzZ3R+UIh%P z#-l?CVE=Cri=sl!SS4-J-A_qaYO>5=Exrk`UZ0&qP>7P?!KffP~MSdW+)NGPW1eMrz%n}6*;tcA@2c$pR~ z#Ihmd?6Sd0GHETOZgq=3Uj@DDX3JotF^`bigM{lqOf%~R@UBt|xM-ATy6=V`s?@%k zrt(yV40E&!WcYhF)>gIOx+YT=kD244*Be!of{z2b^AOm1_YFFpLt*cgKJ?z=_5vRb z#%@Yr0`!URp*MNJUZGCZ|M2EH3Aku5=1VmcIkg=gEu9K0u7=h}iLPDneCkzFnsh4e zddhvsoh0(N@^lj=cI3CgLXm!_DD{KBke)o~zgHKYNyi(#T;o&Myry0~lb3O?Bc;de zPj>7CVMpo7mmo`!Prc~CdUQ7k;VwKIfBxUSzzmYSSm!q7o_As(lS{M5MDv<&Sncp_ z_9>;TBSg3GkQCLT|0c4h9$u^epyoBhD!Ac$QU0}@upN^vxcV`kEAgEfDlZ{+ zWCx@?Y1JEeKaCrjuD?XNwO-MxQ-ikUyFIITrA(RwVe4&^lKcI%(GPTAKOJ77kE~Jd4;BKub+?03#or+r zrQU4bC^a!&cw7UX+d`fT1`>v>Q^mP@Ldw5O>HiQQJc{VVe+o(q?63wo-y+xojO*_k z{Kxe3$lWPIIClX6W#oyNKbgOzZvbY6P{9-COT`8rXIzET^!w~U6yKB;LTeDLtTO_qJ_ekYx9o%&3Iqy9e^Sq-|=)8Y-UF+ueTl%G7?qG4V*?1YZY zeCg!Wm>%+ibGlS6#EWqR919&V9xDHu?A{CKz_@28`NaZlMKokxrLM?9%SiS+Y~^;D z2aC(Yn>h_L{aQ(%zM!{2tbPEiI*Q%fqI_+?!l6Cz>nf46_h;gjrTQ2M35ym#`XE)V zPN9>+84XnRnUMxJv3=aOw?y!v?F0ifvPQz4Z&X|gNh|+ODu#)Ol_#64z94I8n1l-~ z0vR!U`Bi6x8lqo>6pf|NgO~FnMFQ3i;O&at6WXtPN4iyGDpI@jMj2X42~chF13pHA zVo;j<%h1WvnDsOYfZm(~u>79Pi-hh`G>J2-}xts5I) zjV#};kIO?vp05{gXB@ugoDbktfHfaZuV?$itMuceyk3#ZA>bFBwi$8^9ER^tP#>Q; z*%7un(wqTM#*cdf+BijG3**$o+(k;#8bd81af@=^&B!$RL!e}yP53rYIwC!szkHMy zHEk#W-7lLgl*xcn_!aJBf6b0Z-sFGEGiXamVQu4T)??Ebj`)NBXy$L+OYG>k>Sjt&d#86E+xrh$McHOll;Pr{Be=`d)l_o^FvA0UaEtTXn!S+Ar&j(N!FFky zg{#?%dG<{1>d^v@KJqi!2)mq}vdZGfwZ@63g4=cF_ju6r6iixSl>?#@|e5b;)WT5ZNO3mv}kyydWeL^!P%hlJ!QcO-`+_9L$u zw^7CWJ9*E^Q{H0_Ra__D$I{_d(8>NRD5tN+K;QR)!fHmfzm=yseaZrF(L6(ArIi!p zoZt7}UkJ~?C_!cn-3u#OQC)l7PW6jEU`=tD+&@MC0=3QKSL6@~4*I?*@7s_61Q_Ur zMR_W{+GOVrXM&h&15zx@+VE)HT{`;LFTP#3+{}8Af^Pqif$W6HhLm5G^iF1YmA9_M0@?po?_Cx z)nA%g?Dt;qEanm;oyL}c8IvtKFxb{#MJ9RV`#QgyAJ3=*avMo@GT$*CF5g5fLBH<& zGn8LAVN{Hdcy*V1dgjw_kFY$Bnj~CfVL*7|c%++n^Y-y3c$cmOOXbHeVa*H3k~bcd z>o0D{uF8Kh&}vz1|870AoB=LpC6nr=Wi?!f+D=$v9eG}1dicjiN`Bt8BDPV5w_o73 z5x8aP``&P1v{>M%`JsE~!~0biF-&^k1tybhLHRn8>d2|PGxj2Tr@gvUs_nX?+Tpv_ z<~7Yw_vbg?`u$Tl7}S~!wigMTix)`6!nf~ld})5m&p;+^81Qrza`iytuXnZMy#17n zXi?><2>0gb?`X zsZ68go`zKlKvKhRzm;s660U$DP=){QkvB%930Ye=&p6l#_fS8uR5gA3 z$o&X&YOe8Tp9;)$_!@A$>WgqZUj#GjFZnXfPUe7%Z7Dj+;k#{}Kn#*w;lPtBr<0IJ zL9M8dDh_Zx9c*&T@6&yXkbX7#8CJZ2JAnZ+(jXHf&CRz{0w zUE1S&QXTK7a*uN(D541V;=??&lgb4c7^hOo66lG|t6x$JCu9{GDkrpG2CpG`%&@2E<-b52KVw@S?XQ^10_e-pZ8C}q6-V}Nb zr5^VyPfH|c~D!1*S`*wJBrwBOc-o?|<0himn-1cwyk!GzO9gv37b7Wm283k&c< z6*;IyIFXBLJJc+8dgf9YBjS3jDPwdf?@7!cY-*!R9wVFHt4slOHfFW2$jIK=n~`Lo zqe6t?=FB?+VmZ%DwiYEyC8oda2o{)ZDOb5m!r^Xt2k|th@{*KI|DDh(i7mec?(l}- z3IYOf?u8G0PXLP&w@ldMR$93(KVC5iQ8Kl5NgU?hXpkSXgg|Ee)GgU<(|!7z^Y!&8 zf!;ygOeU(XUVfEl67j94ZCCw34S|kUsFRTQ%IC_w`m;DnVMe0 z=2J0A_1*FJ$;IzFP={FFK8N z#MVo7&WSvHS};Wgv`2w&ZV13mx%04_nE9z_)_-vEAX zMA!fT0{{RJB2_Zhp5x9$^h=oaVLLKnk$|#Oj3x=HNaS(B0000I0iHcXp8x;@00093 z00RI3V88$X04M>TKSXB$tGBKo000930VxAUTGgZlJY#!Dw*GY-T$)VLizvP+G4KEY zJHA1hBs5G!e*go0kE)t9V?m*%gB->)PP#lIu;;G{JPo{t(`kmWqzoR@5|a<@7qtd8 zEi%ky$3en1KY?8;(9vC4%nU$v-mb1$mDkb5z_0#`XvSy`zT9@;M($W?zi)t9nm0Uz z`KQ)Jp6Cisyx@mQfrO6pJ*N^RFv=aUXpD%$aOlTkepQ9Pkx2^ASBr=s|w{TH3&?WzT$&O;L6q8Q_#uqu-D zj>N5n`M-nfJpK)0GN3>l3j@a~_#i+@&5=j8eE5%noI)e`CKYYjJbC5c*WwGZ?di@+ zTwpA$9Les+?34~rx;B?QnMnP$zlbK>P44RywuH`m(e~$DJNgMX&Yv984UxqWX40b@3D6TwQWvK|D8qq&jU^`2 zxaZ9#{$UY#87B)A+tM?_S_(%Lk`1Em6z7Ss4@+@*uWS*53nB%b$vs6= zdLqL-4xw-~M*8YdBD`TXUHI-JkpE%QUm<2D>HbvSE~M19a!#gncngiPN@OPXd*mh7 zuKOGH>L!n3g%~RPh{bonlB|Cp{!Q`t!&Iv zN1hL7fkAO03d36CmK&}cUdOH%q4=@@#Q|XT_-g~BeKOqYWA}{v?d#D1aIkCXPB2%; z;7gWcK${JR$i4LnN(M~O}947({Bt#Ct2|^3FFFlmb6FMVZLIgCtUDzDqx4% zf=&4}g~$8`Wk1f8Z!qI|gGryuA=MH$33NaOITz61Fj(WJ3BiodE_fNSrjr8Kfyxs} zltS7x&ueKgu695X({T6JRX8Cq0S%hU3^)u1%y7`~lp(*NiFrqHwX*lEIqw~byE9x+ zYN$fOR{Qn7NcS%8Y&Sw4)&uAUYWC%U@2D$& z^628DAl2oQVuTQANZv8P5<}wPF8XzH1|WhsEn(nIxkQL2efJ4UtkY5ZvD@x&!_B~+ zZP!K$2g0KFD^E)!mt)cAu3&}~$0W_8uq=Rp75j&sw!^ksBOR9316<(-w1uT7M!lwD z;{mz7!V0|~!8xa-oGwNQOGqUpLL&!Uf`;D>sN>>dk3%QaF5oR(h@Yvq?quo1j3C|E zF8#0gug)v`>+`>()re%qY){jX9k8M>U4FyNWB%g5v-X=%D5l~@d(W~+U(CQGY9Ec} z7g%=`iEZTG_y6vxiK zu9g`ZxvJ1c|NMu@P{_fyDES!neBKy0KoSgli5;N|X$p6YITCRm9OJX;zV|IwEc2Xo zW8^kBp3K%vqs-uYOS!mQVboC>Ov}|nH$nI3JQ34p9PKxS4t)WAT?Bc0DuU1dJYILe zBD4(@D{=C=CEI`DV)pDVf+Ish*hLI57vn7(NEVs6$=-tBF35Xj2`3e~q8`>(W%l#C zF-z{T))#`2FUh7(q1^=Fd;aPeMxFf8Dzn&!RqbiYXv=ppwFcRqo`UVtBD@(`ifp&y zNG~~&&*Hwdj9hljh2W3JGF#Eba!@DkKZ1Vq4ZEs5k1-P^`g*T)C=|$*52pphT&Qs+ z*O-Y*y)%S6&DKyDFH?ZPWWl$1gRZn@WB`_Wh`ap1=JgnVQI-MyZ`>N>Nf%(_yC#v z6=(lV1lPnnbvh%qS1}v)nZ`30mWdTlOr=V-tblb!>^<|19o5$%6%uh8b8Hl%`416H zzANGBf-^@n#X7kBUbsiUM#uKbK~6)W@@+uesP7S$MR*- zrYs+ok|dnOkN0G{`teuWIC}!is1yK0z{g zN_lTP`)2f3k575dcNjO~i?RI&Ab*$u1`ZYl*;ZuzUgGY_8y(>wA1OA^p>tKVQm2|m z5opz%HEchf3zzf=vx`0nB?b({LwR*n^{8f3Tx zXugvh&k0;7zr>#L+<1_~7d&2WsZ$j8Y@~UqP@<(Kc6F2q@@dI&wQrB1O^*r42w#ux zSoo${vNrGoLOn&LF4`_DaKfdIq*$Z0x65UVPQ*!5nXOPsMD1zc%md)NbShqzh7Nz@ zVa>h?(X5nsO{B3W%C)!4B!6Cnf!!+t$%LRqq7TLz2Jwz~=9Y}iNcbbVlxF9o?Ds3i z41jXc>1ds+_@`(t#({6@fV&>Yi*WV1Ol!fS$<>fPbiNjUg6ul=ibwc+REv-}Z~Y*4 z-y30$=y8xHhFA$g-AfTMEXYCvYbdH3rCDfvlC1_bb#dl~#@%a=U=rk-8c(bp8u}8p z01_iPFy%rdM~c*IZ*Dvv6baW+u4d(c#z^(o3_zM*WZ35mEyeNf+y(ouOat*0;~J=7^`zLE(^|%`|Fe>P6Q76NxE!v~>Th z{g-ofRr*E9FsaUr4W$DW4#6N^#(_;$$Xb83>|s+>G$zoEt578VnX$Soi>}c{v~SlE zx&Sunz06n>r1a=!B+*Q%r3>tQtVP$+u{aL>ZY^HI_hh?>#Kx+rZ2Gh=9egU{0lIIy zZLsFq=ehC0?{!HDI>fE@Z0eB@@OX-T6!#$7Y$sKRGHP&~*T#iW*@fga6D|{igdlRb z%0?ile3$!qG8IitzY);0KHgt*Sd#6)a|ih6Yyj$MW?*&v#$TfU_L?!xHhS-y!Fv=! zfvQnOW2(4LGE-cKRPQQ9DkeP}w;)>dpOCe+ky12HPxaM9OTSkJcFy15>m~+-c~I&K zr{kuj?$vgo;rG3A2C zI)fgZ1in$E<%CS^KS7uHO4=-a@?d>Wup@unh;Q@ZK69uV`#D`c3!lEY(0Kp|gNMpBH$G=fPB= z*P-IpDLgcp1C`liEpIR5zX|7&Wn$e}UoaR?s|tWl!wFy}t>5~*825@jSOzK<3HC9^ zoD+g;#t^_+_F(w(&BknisA`3ZND9!WiO+4+xIisryRZ~-3FiJ@k9~YPb}oF`-BKEv+2 z4B2}Bg}>nD^pIgtv(RcPsB}j@57S?E;gL&{ujcEw+@rbnIKPL!X5-hatuMYrWGzfU$vspc^DObqv}imA1k{E~-j% zLLS(mq28$a=02bud>WqUo3R$w@Abk=k&gxoTb|KLWI#OewCV(zA7$ouTNrdivHApjmCqz4{j_0J;QNC~bD_+Zk$%56#bc!Ms(nM0 z;aokT&B+5O)nsFO=?a16wIYMyZ)xnY5-XNo5siQn{(x|4wb2**Z0_{h!EohSn|X8~Q@hUN%w%r`e^ zYv$2Hu3B(EPIX_GdH2IL$(xdw#d-5TJMpkUunLD zRXwv-NiH!e5C+uqKc9m9VB-!{WcC4^dXfKiqQT){WY3ZV(fx>bxZTXNH)W zF%$J5^%ohw5%zFwL65!1MW`b7Z5QQEKnk>o^rz_1rUR{5tBwFrQMnAVSs^h{R|7~d z`b1A%%`7`7YI4db?}aaW2w_*2ylt{9y58gzlsXtovhfN0*lnel>$KGr*)1_ZAiuH$ zH&^?QG?b-uzqX22^|?0Rfrs|R)zOq)Hyqzgc044IiS728821G%5MmI56wLx69Srok z3z+M)kYfr#d|5m>Qo8O-On8_UN^jAXfrb&r1Fs*?00FXSXd ziu=)D05JLK#s<)V+km@Wd{_PfE-w@4V}maO$j3p2{(I?FYybU7#$lFR3oK*^{|IGd zkY$MtfRA_K@`jPbvs)FURMVh~y*PF)5s*uET#JJbe?8&O>BJdWJ5qQ%Pk)jrX08H{ zshi&Jpy?4yQzSnE8luJYU2Pxj4!XZEMzAEIY$c1{9NCFtOj9N+#OGI%AsuwL#Xrv- zg844|^Nw)yS@CD*n;FK%Ka|~U4N<7Mcl#BGz1VE?x zdAA5$adQy{x)nW2Rp>ax5AKeub%bA_oZ{69{40CsM9|%O9pG!bQY`O20EI~@j~|PZ zG0L4~4u288_ns|ZN>UG)c`qvF#C|CRS|qTN@**v123F%Rk>544q@sV|3RJm+D0|l=Zuq`SBE3oe&)bv_S##^<UhsGkSVW%6sC)Tr4g$6W@*+6Y7#RIqY;44 zm5g>;9MkG@I-T3kXpGI$w4&)E$6jBTYLVonv{iRJ zAt`$`>>qt+ozQ%q<*c*xQ$*{GyzDuTLRk*yzKokTk{E?K9957>SWf7FS4x3G$j z9yE9BGhu{bBo-^97290H0C)#Bb3`zUcQeTVK{u2Nd9D*p-=DRD6`3*gq~$*eJZz z0&thM;4IYz8NxLWQ|9I#RTMdOHt1|q)eivrS0}kfNfY6quKvV*Oiv(;fwwkv!yI`G zc$q#U_fq?EfwnFTSx}w@BKCm_!TOX08b*pGu;->%M(J~Y>vnp`-Q`UjIeA4zt;i)* z&)?%v$^99g2F>2L2@BSuk!<#yC<8BCh=Y3=J3sfRD{73-M18EJl{%U4N|aYv1v;lm zNDnl=zyL^r2jhagSjZ3<2a6^{1ViuYAt~mToV?posKr6!ecMA1VTmtPD1~ZYGfG;Z ze9x=pN!T#@$YIF9!h2QQ^+P5LJ6MdDNZpmsIx;iCs5<&3)S=#Bh~3{Vy0OW!#Byoi z$PNg{!=XbyV0S}VgY!3WQ4;`kp+7O3cXtYY_(#(@u1-;nl~v{4l~f!)H3^wne$zos zy=T<+Rh+1L_=El0h?#AwFxKY{pP~p9_IA}5v8yb!-w?&I#<_RyCV+mv%T+SoRJ9U%~lZ4&bg0ef0WM(ss0W=e6 zA?YP+VJ3E;bZLB;HL+l` z$dD%Q5T?zyP3hG05Dy6Hob6Vw?=HEfbty5QUyBp!MhQ<0Zp64y)6m#qf1x79t^sk2 zA_pl+l7xGLMjIIr#z;X0kb?J2%Esj?aIS+kb+_Xu|A=cr~;I6{(@&!J|8v}_#!XOf0T$-P+lHE-RtRA!xE zt~n?a68mv4QvGGAkJ)(PktMn{0bZZ!1Mb4LEZhWEw>M`L3F4xa&$=-J`_6bjxRi+a z9#|%rzxy3%5?83^6eR~OuvZP2R@M{Kht19(JGrsM7RK6^mZga!MZa$#!n7OhEX6VX1toaVmA_By|sU*F2J)t0%SLV_13B04uU4h3`12jGgw zPRpoOb!X@N#hD`eWx=dyb{r}{ZMMQ@Aa6EH>$1OtS?b`DsPZ4z{T{fLWUfmGY6FG- zQ97BEO=qNns!Q{}<;La>D7ply{;UWX{IM`F5V%I!L)C>_(YivEG}3kLBUgqy-;8gL zkAA=`w9R+nwLnP5AY&3nbsz1yA#|NN>0UO3I|Ps7Zb(RKBa-7`w-*B?7cCGDM~yh0 zPkidHt~+Gbnigz|Ry1!GAPv?NM)BC_qqK*@Cy_puE~N_%(h<8YlnPzr6w+|BtLDxO z3lz{o$M)BnT@lsZ&W(kd@D+a?g*4f1(L}kDT4ObGsXFV-MTt~*-Z&mo zH%DT)x@B-Obi_aydhx~ZN2Yl=4IO&%8F<4Ev_`q`UT|SL6&&cZUDQ$ES?+QF9eo;0 zz?4D(&du+cV@?Ovqw>_0uPD7OKEuZz_`|&T6ef9!cKP9c;j+6Ww`xeSM@to0d*uH9 zLdnpFY!m%joY>4~QRFc=E}lG$Iw=dhZdg9mwz@SdFRIF2tBxTu*$iUEfI?7ISIW+3 z!P;#RC)zDvU&x;Tc%tCSs~_qNk>oCd*(>#r*CkfcobeQGV1lx$yGuLS_Sz#Z_ifeMBqj%(nKDu^nY~Oj=kj zI9(|*No0H+lAIUzIcG0oHXKh$itv$~4{PRT0@vWM$rQ(-x5bBt9gqTnMQ7{zsL_$n zny3u%12R@p*yMFCfhz3aF1o7F$YGD9XrcbectEpX>D6`JU;k}zcpLF_`PpS!VWeq= zZkKFj<(f{4=7Sw0%VDMN*ZN+36AFELI_x} zvq%PFQOpg9{gVtoavqbQR{2ZVKh;!32JB))r3G1l3LHSxFL@ucj22e#s%uTE;Q~$T zMfkKptklR&=~`ZzKuHQMMYkWpaR`BJfwk?FRQohfQ){(vzMR&M%`pU?e7o~Izw^7( z(k5On(C8l6^UPFD9t`e~aDUP_TPc?F7&^qnFVV8=$Q(&iAT2XPyij`Rik9O_)2R)L zm4zSX!>K}`j1*3`90!KS+w%~*V*?{C-3!#V?}^1xG4%k6_!)h|tb2F&$v>!g3~qK! zjFSp?C0n4?#~1}-yVie%b)v%s{L>Svc%X`~WV2LtK;i|Ze*~ke$#&qtE<+PmpJY_G zGGZU+j0%=KUPjHC$=x-~dhP=5XpxA%WGh+%Z=e9?%Kl>J8pTjo7?jxy@Br{L120Mb+J zI!iHPEq<}V;+GP)aXKru785uQjcduT?sD{d|H*8=%fb|@j@-$BW*|FFC}`pf+9eXn z!Gelf;%Bl-Z^TB?Q_d!MT-S~6wO42<#C*%5RG=4v=PUcwIGCf@;%Z1MQr<$YDJmv+UJ8aKiW zt2)lhf6AJ`VC7H!HCKH|8FpS7y+evJcZbJtfDz#pmBwJS4UPlCxjF*%v{1Zp79^4X z`q1nBXvhEmd|`{Dz3u?rcmA!KCZ%TIQ8Seb)UrI0#sB`rg};lWqpI6&lUX~O$e#Jh z`P?GSPjX?oE%HD#&-dMH$;vI#NpvhUyte@-gNP-I#H@;Z-&Y8ER8DW49-N}~@LGsIlIB!$SP?w+U z`Z=9hfH%@004oOQmSi^j?5an}kuy`~WoP+kcu(;8T7AXmgGIPfmc*+&B<%2PIV6h2 z(8S_e_2rjCfDzxKIY+bi zx+wz#<8p2jz5fLk11dB?HiU(;ZXCk{4|V>LKXsQeUQaf%1Rw|I9J0BBv$y0^z-rU| zb))mV)K$6gx~P@3wc*KJR1S2MtDf0W+Bk7^?YvsobyPvL14HdVN2_ps2_R}_)x6`- zse#x&K7%XA7TzHz{e|q8;KH*ZnHeiHbM0u(%9G}_+BqRH_}Z)5fXJ0Rf+~N0s6uQin=`h3iURz+5a z3=Q*df&L_hlVMH(=d?S-vN-Yv^kT6JAigc{qL^*~XOc>x1WaPo?LOKuRQs9vSf)fz z96v##f$Uzw;-h)A20UhsCcruE+k{uav}NtIW<@E7Udj^K>_2?=7{76rDEJCJv?L%#f1qd6>zV|TrmC&>)&k#!dwV8vCAiF9-l{9 zQGZ`N)}_5w$l(o#`|v7iQtar*OTm-ohkvHzLr*??*L=*v$GYxf#_8iYLwnhS2bj7e zm}0R@3=PHqVhbA7L+n$OI!9lcyf}C-fPm~_E!Nt>yK3>4Mkl%vrvqqNK}#qdUJ!@39wCd+I{4sYK-9`CqqqlowYI|GbKM8m5oF zq~4x*p&!6EJd6MTOaS@^t_nM>3Gu#SH`!*|vmBq3;gex^|L73=f}2zWwB|z5aYD7( zoj=Pru^lhn+#vRLpMRsH{Y%J;(PnK=GAUrHGtH3fYc39q51^Tl<-SuJtsIOeUUzk6 z74d1ve+-VnCwCFHHsJhnrvCf10VA&u|Ns1dl0}3S94gYIU<3%m zzB!oX>-So6B}f682YJw%*X(dvcJ*6&lh)VYBsT%ODk zl=~A)67?%yz5`0%{Mp$)ikG8Ov^AHCi{E>-a%T2E>q~nRRJr0cTA|?gQkniq2KwchD;(if%+t|(8IeqSziiv zq(|JqVe8=Ze>(39PeDLh>wl+;f-M@XOwO3b>~{`?f%F(gTH&Bw0kYJw@s{ZPPnzl_+QqD`Kqe-!j5&SY^B|w-?jTNqj7k zgS^5k;(iz9IqC!ls9oHH)4hL5{+_bZf~MI8^p`JDxL2ngwdVeij~N@uV&Z74*f?lg zqPOzhy^%J|QY6Nb&HJ$5P$yx^DM3yeLRMReoxu2OI}3r!I` z(}r9uF{};%f@N_d;2WMi=T%6nrrF*+hVUJd{Swrg|Qu6$EjbVrL3Y>7y)VFsQOkcJ0encqAoc!+;YNy#X3VBU;q57Mt3Gf zSYwXT*gjkQs?9olCzrW*on|Jq#V?~`Bs{&Icf%&zub;|;yCND`ad3p()KVTpAOD9A z_^f6e6-{!BI_KQBDJqT)H2E>eFv9#<{d&3`nmDm0Dj+X-)>8Wqq@H;p>20F%a;a$G zp<&eX!{;pAp=9YD7dc!Ve#n#<1FYFmbLBR+pY)QwX*Ap!+)(Ijk#n9`nQjNx9z`aeJ}5TK#AM?J1u}yK^*97bk4jGo z^{^bo3eJ)JVjbJ5L8?J-gt%e6UY4$o^0fdLh}#Y3hV*|A9fO_!7V?E=q{&zMb+!qdq-*L#gN@nf}N7^$i{vqI(^i|HW)`FHwn$d^OhS4BR-W66HV7_ z1gOv{uivB!AyP0T8K|Q~bC+XC48jiN;23p$KN z_ikdJ5;Itvex!vVx;O!-0gB~WaZvNYX}C^0rz#%NiF+>H>+S;jlE*1T;PT>kzLPC0 z4!r?G%2~J5We9V;S?3(kSSqJ=nR7TE5YU59dUTH<^7Gfx=)F&c9%x^_AwdFv`<)w? zoj>`y>YSP-&9dFB6eZ|c>-m1D7lt7Cl6?swg{Uo-lg@G&8#RuUYIdN z&2}6h(aa$bPv3Ax!pfER{+i5jMeFa4T57U&sn)?a&=G_fNbW*`_>3XBy~u$L^Q!+Z z7x6sEs9TfqkwH%EI5#GP$WxCcb#n2>c*{aM5>`F*h^(=HS*A^EG&FhPk3H|shWSW< zp@m=0TgCqug>Wa2qSngGR7^dHD+iKu;X@{W8j0#TLDcupTEz(C(?`a!DQb1`vv~ex zMs|wJm0x@aT(^$av7F`K7TNXXqV#n%QYn;mbvvgmcN#n)(j1Wr7^oeZiZjOr_<=H| zX+qleRnio>d z&xfqT-p)BZ0Ild^DusXM#@S&a1ElCW|L<>b@=3WYyIotUdnasPC%gX94QVg0(jBa? zY$x=5dwOJcR5*)5bQ!+|sDq~943}UVtbWw2^5PKI{63#O2a97r?_&}VCq(dBVn>l( z&-3>QmF8d0PR;-P%5oXsVPlU1AB^f!vvnnDW~$E@b?IH-cZ6lsSvOC5-Ob1A4}Xq1 zgws}*dH~fYE^gzSrSl$ca;GeAPeoVZ>1zYiq2YfhYpikIP#eQcdjQXYq(jGg<^bMczsl4S#q@9OrZ?F zeyd+ED8qYbcdL~b95ewl-%~u`p94OjOp=Ws#q|Nq8<>@qN3^l#qNz^b-V_hR<>DC` zEEn*Uvd3MOnkWRNobtohGq4VV-D=S(r{I`6z;A!tZ1Tu&YQK@5Z*P;MviWI^1=<>S z^myOUf8YWTo)4uB;UH7Q+-#wq=;bu%_zHh#Mwrk4jG+~4I=2*34lVH|p_QE~zw_o0 zU6M2DL$WIZx2%V!!r`XRS=f`!_;1RiC6?ByX!=PpV6II^T@5l}dUvVpJ7ub0>drL% z784VSH6#)i$gT*w(c z00|ghnk)n`4QDXqg-DtTW#76Z&fpC7LCX&A$YWOm7_VO!=|rS9W}BTs(q2B8!k)2M z`xa%Y$Q|E?)Bpduvm^VyivRzmOv|KesCyG%f7)a?IV#OSJ@N>zwl`X+2mf!utR3dV zh=8x2C|0Jf{h!}v{hgCh<=`=&cc0q_Esv}Ys?7fW=60k9T|;<4lFa-&Cm5{g&&x8W zK&qA{KP?TPSq{dxxUD9gbw{DW^70aeswkZQj1jk{=m^QJ;S~;eQD|w!y595_S<#3rzfew za8|DKaK3IRzn`iUU;Ynk|NRtL=w$UzWU3lAKkCRblTytT142q(fpB51?4Q&Z7C?jq z`9*bTKh3EB|3aVK=T<$8H@dWMY!SPpczjOF|Hs1_gWGm96ipK7^K}7sy>&_H!9alR zS6=M;+Ys8WSgmaKas1+y1d6Bg@vvjG$*9lPs%r5_{Sc{Ccn;uneC9zhmy1Z@T1|PgJfnJcRZvZ3JN4MD}s#25)rXIYxvr++L+M_L;Chf zn?J;yy`alHDju4nMug)Vkm@gA**C_wTL={^1xlKpYxrSwlJuFrStLgFAHKwtglWgC zD`96bDAeMW6)`~CZq!`x)UED#^>i&eca0VzeRg`&`)toWB4bufAQAd#9P1mbj(js5 zBX9;yg>$+yu%c>&Bc>0AX`EBN{}7WdPC^6`NvFCx)H&j zW*f>9ZG}NzF*ZMk*H?$J5I(Kk(0E2Uim*v#+}E8uWP`b4bEYiPsgqCt`tB@dL^oR% z{Z?`OjAVB*f%as9+I(iS#+`E?7?Z{*DHTFtH+Cq`KFoENN)U#1N|(mp`Xb4$DJ>%A za&PxXp*ayK^-28jinD`&7%I`xS@t-1MUJwf)^TJNqv2CS4Ii7QlCE`Le+-Vo;O4#AU+Fq6z z?&R<%aZ{GDlbo;oM0$#DDm3R8G-j=B(75Wjw*X1`@NT>zj^5Y9mUUKlytG%k-bLN2 zT9Hs)CZG zLWrG_{gVC-YMplA??r=6;oPxjkn4N~8&On56a{7@>-+&D(bya1zUjDRqS{Rav!opf zLA?`?XW%UpbHz9AO0g+u$d!R$*$Q(79mMXcO)L$DX$a8%z#ud;jMLnLv%EQd03^Cm z*pd60`>uA(PXk-r`hW;goavS=cQXJcSta%4rgA~L z{RCc>&%SB#ansZtOvbXo%K(~U%-C$EGSPka_Pjip^EhSfKp3W5mj5JP_Nz84p z`7<9B(!2Z31c@bt;a;cb>h{8a3{N#*@T>4}i@d6X1cNm`9c-53_OLzt*&W@hU0LI| zGPW(gVw1NLO9*^F4mOyBSknl#B96qH{tftQ#h$hA)f&+xBTsVmuh9rpbj9@AXsZfA zbrZ94uCB42m^WD5#L6u1oZhc~09in$zkB|vmRitfpU2pMEj;{_8$KpomD1!cWLYB} zjfX?PI|F;ZSab>pb8>x^`5%(IaVAUtTejUt*@AhoC8b zmgObXjGj@3J7fANITSWZ3p<=rb(n*cxvF8>B7fyjweo}qOjQatwS4Lj^Ljr3!*a!a zJsViyO6-U*fM@3Oz=H~tB3bm*dj#N;puY+~jo^qcj46VICD~49bt+UcL@~#w_5pvxnK>#e#|Yn@y=q8!evVb4I-g(;V4Ctw-Bo zVA5O;n2E?Z4M?N6%JVhBN17*7vzgwurU-4s?|(CDe=69RA#QsSi95_+pL1udVE z9+-a7n(5ahO>y@ECJO7~0sEg3z7Oc!@PeIMd>$(kE;f=kYJ9Nv#nGgeL3-H9nw#ET zU&n`BF%obhoeI1tyYS8%C%w#?YodVL-8&XRSxp+LRfRJMpJ=h<)XFf&NxtIyMy@OY zCw^+K?brbp4(&?nTcpr?_x`^-c_IA&LboHHYo=G+0kdlhkkAsj=r_o#0BP``r_+aK zWew&(C~o(`BbKlvF6>|Oj>G*2KpJ6)8FlTMq*DfvjUFLfrs z?<5tjkRe+i*$apka$L}$94U~11<@I{m3>RNIW>xr!x7-cPZTd=lJWY_k7Sv%{5{No z{&n&G=%dD^8;eBmZ4H&Up*3c`@?WOpc!*3i47)Gm5-oxPKuDz0Gds~fB&YwL z0yLoSJ2e8pKW!8OvNIxYopR?F*Qc>;&p3{?`fGRe>du4Z9bT41s!!&yrI@Gb{uJOl zu3xR+xoXel$~XyoCNp1jBA+$k&YBWLnO5RYiXulH;_8f|^?nfVXf*Yxp|NJabxpN; z%fP(r({e5hV^}}{f~K9NLI~BfJOc~=@sq-!M7T&!j_}u%;BZV*%TR`h543H6zI}qs zMw$g<9m{rn%m$6)Ri*I_I54W!(yl>>N4Q^l8S)|$R39c^+XFFW4W8v@!p?i%LB$&g zlGx_TC;$G~UCjyuLwNBU{DA*Ph;X7kKjN2H%&JW8+Hg@O=5xBu6~n7APpT3Z0$FKs@s0=l^3 zel_$$N?h@oN5_4oXWWn#^s0Olj~l`A#TsA6<*1@j+0sk_D?ByGE7@OIg+k%dSTajV zacSKX$a*sgYonJaX$=p%UF#txY!5;A`QZ|6s_kz=(ePNV`N3ihX9>nDTPkanpLLQr zL2OCm3m}n4e5RJKr>_NNbTMueO;}j6EP5|F0)25>aF1V5~hQ2+n{KtY~DMHMV(0#X0~0{{R600GfzrBbf<_q*ryRh$X}uEYxN zD87|MePlFPPP`lRM+!XufPxqoAKT&KKKN?V9smFuQ30M|M0Wym000930L;oVmDw-; z)LoHtUQvQla)l{r%1+qJ_Q2~M>A@wx+$Ys_2~l1+dCq*RoYeu4ResH1uG_a9a`yI> z_IL(1kY7PD58)Ed!TzfUM+!Cw_mYtn2CYyNKJYti>DK?gj1yL0-$K?S5zs=rOEdb_ znG|riAY+$ov{s{BCfH@qvN6h>H8pSH0k-Vb)$y=BhYn~>5Em@bLX?Ah~xB1>Zpn5aVU|y~|WGWNoUl?E71>iQ18}jX7I}y#@ zGQ!^|?+u~2=>9oP92vJ&{SxjmNzrzeVIn%XDQj}xYsS6UBJA8u2}VBQN%Qi`FDkuU zCezvoObScO6;CWb3}+**pm{QvF$H~;t!A-B*L zr$D{7sZTr2uv-``C71nHGou582*|IG+jzaJ>Lwj|7jj(V)0peD(@tm5%O#NjqyhX~ zdPEJdpjRFqQ7i+?wM+!V)2d9E3V#*R>bnS zB?euX*2lu9s3pTDnu=(fMYEcvm3`d~N$t+TZ08QgF0t!d1w}KoM6O;pJPa~_zu7P043E!GnC(;nGeBatkegpO2B>j9I?-cTT&h^l~vZTI-E;7bzip4+hRBu*rKuIBAqPjw2filR{^luSL zOaQ|TP$4ht6Yu!l_f6G+r8{IEvk$n#r3)1Qo8@GI{0<#Y)fk;L1kS2gUS$G zHB zfhQ^oN#`lbH{37HQ+Jv>r#+5L>V<>_^4`jJikp2)=RNe(pG-LG7N#z$eV$=+JA02&^dxz}X7%DG zMbU<}b6ew(`8=8A?i7~Jmmuwh+fISGX&Nz*+*1V4S0=1b-*jE5o`+-Pew?4M|I_Wj zzC7k5@fy4*y>>=NuwQHgJ$q=*FFEJuDEBTrF~r|GZlFTRVCRi8n~kznp^*_{o!#*W z^si>cox76pkuS~URwKF1+eXC*d}E4UKGE%0!DuK1d+d+CSbc+`YHHsDdvC$a_QKL| z{McGC(Dq{_6_KkIT`kK|Vw8dbo> zcp>f$zrVqn8;=mRoqij``~`$-TRPaepK`2LrDn349ORpk>tjEx8)F$!%d}D=Fl|** zYyht9HSm#RX?$()|IvMVK`V5)V(=e#LosE2#mRDE zkIhK9YN}UdVURTUZ}`m-S-2ZQDBe!KE3j>e;zS5-j6-ez!Nc7fDbE=Pj3$I&bKyFN zl*@0Z2s5vfKKj@AX6Jd%Lg1(woT9d8i@&K=8Q@QBU^{Aqvn(FG{zB@eCvEv!knB> z+#j8!cH`T`#3JoS!O9AXIawaqTVZ4^f=5vdl`75TSjdZyj<*CXOse$r9e75U8V=Pi zvntm?ga8zZ7NAy*^0&c~T#?PR5Md$QY#`92{Q$AzC^gC5xkO;{o zcXh8u->wwAez@w1VKVM#ziq~ltikkLwNC;kIMSm4(;ZHv$_QTR>H-a?*CSZa*!%~& z9aVKJ@9@qCdIPU+>y?It3Wl)#ibH*(~-!Vm;+KXp%xxJ5r z3X0bKfr#f~>4i!LXNZ20n?HHZ6w+TmM{gU=Xf~^)Tokxw=RH2kpU&`@$nC#1_tIb57ziouba8zm-IhYQ6mKRB9s$fR0c2Le zTOxln2XB|NF1P&vhv{3cKO+1XALYyXfQg0;!D4t3)j0rx0@Dgouf2T~I}j zeUG`{?r{Ota^X4@hP}#cXAYSun zWX(nq!OZFgNj4l-QdVm!W>;lpuGv#l02pH~eg&^e5D6o+9um7>E41LNvRDH@8{o!% z7Zc&&9~b_n?U&@1@LaavD>VjBZttjTrN7cqU=E_kBpifT79H>mSi&0u2d45$+! z-2KI+8K#>&31Si3AJGhNEH~gW2aJ9R?%v4IuMpkb5|_m*I0Zh0M0G7hw{dJUK8bY*-MDeWctrJZ0ENXOZztkRcOXAn4ID0s^Me9R1Baa9(wvnZ&`$ z4DYKZL*Qv*oqbt$;WM-De&#CW%-gSK1onRA4PnwVIXa(#(Rg;iXH16X82jIp822DA z^gonxZ`ws_7tYpx8bQ?$okE9tI`nT7zyU7+x)_9oH?!_MI5HR)EpblB?3e z&h6UU?+OzAgo>pn`6oVq|My#^bLZMJumT`-YL)HuyLnI4bP9*_4Er5f#_um{WNSxP z$cS~ZSH|M_u@MJ;*4EYjxoy_p%d?reKCdJ^y z3iV<_(3CX)9qORvv3!5tzbz)twQ)64_`iJM;80QU_yi$lE%mU?nbh5}#P>&xgQpo0 z)yKy(F|7tcj|X@E;^xmq&3%}63aQBF>V8~vAUjxS@zJs8*!HulYK6U!xQHOU@nDg$ z3n#tvX%chNo!_mRha^Z?J1vDXj$M9TnlD4TR;#qE`b3KrrQru|!d>bD`U~XI#PNHK z4{bBa(j8*L@gh`w+J-9>ISkJXxClEj9mkImUe%Yq5^ri$ptZO~JR-tI#5CE2IoBB- zRI9#++JYco4r>+T=>@;zn4A=HD|>#tX^vkDG$$A-Q10Tjh4Vm6l#>mDi;-8VgArJJ zibu;Af}-NUzb|xr1JFF3r>KxYdShn!f($HnRW$Pq-)9O2k$F4FIbA1JTx+@KbzXU# z_$i?8?_L?ATilNn%eg#iVZHBm&KK)Qd2L$eKFaM4N9GK87Z_%Rv8%UeVP zDjoDYsY+l<>QT9ayg{-aE@}&rYK8UunLU6VBtM1FouFdwy*Nn@X*>t)*gI5tV&ms# zl478RsS%G<4STXFdU?0}R)2Qkfss-}GkGP7N{&H8u^%3tKr~0b0{HtjG{Pzf66n$A z#@8-N7&1HY8$W{Zh=nB_LOs}}hQ}#?)TRr+qCqn&L(cGjPn|qQ`Xo@bA__W4q;JHK zeg7<~xZVeTIFl>B;wtwWX&PA`?F;Lz{p~_E8#LV-teDzkcaxvIDc)A5m4WI?934BI zyFO&NGm*tfYz2d*nC7=qRlW<3U^^Fo_nOORlf{?2Dp1_kVj1k7W^J|SC!GO2UhN#p zsdZCqXf=X!Di;j^y5dM6lX&?uUeCqM?-SUT73y&e;Nqy3P_;Z%)b7#d>G2Git zO*xESm@p-XfdC~VzRy*Z2mgD5z)bCLx637WMS!7SlVG7;faE=b; z4P2=wIaluCx|+TM=i&33+1s~hle_{+tCSRG`{xuPeo--VRKB~tj4<9@O74(G-gjRe z>_!$#XSnEx`7ShW&=A(H?OQ+mu+-TVBylavvB79YD5ZX<1VesUD*1)qq{-pJ9nIl| zx>%dl8tMiaiZvt=6XQFA49tY2<9EySmFV5a6wtwj{VTsL@&YZNJNf_bG!dJS$*->a z3ig<@v1hQ-rBI%p5_))}yAwYKz$6zO!(-@Q*TSqz;E9+q-z0rkh!P+-Z{UD3wlins zlWG3+w@FwzH!>!ys4mxD(n%P<)B}EiYgujz`9z>pWJ_ncW{b7MA+R|AK884u z0-OVOCI{mQO8&N9ju2V9@nagK%HMOcCPt^7=<=U@ zVXB&P_`<1vcKIM?sPSxvdSM&(kuA&NE0MaCWp33RyiJqNf`6L)$&yu5%D1sNiHJ1} z^>$vHLtOmj_M2{24e5GlrVdCQ!LC@og^N|5S8+lu)tqyN1sEotPd$dxz%BH ze?bbyd+V*=?rzl$gw0Pit5>}^^4%-=Ci|-tBaT`E-g$Nl@3;s6D(J?;0e=b!mkDp& zQ{`+WIph7%eu2*b!p-WncC&l6ZB4DO0mF{mG}1PxgsoTFujSJdj7lBhvn_f!4ea?W z#?+hKbPo-f*b;x)L570=_>Ge4#{sMp=RG6d?>n5shFS02_u?C46 zAXEB1LUePw^m!yf-7@?#?n-QJC(=Pis0jBEHvJ{v2$Uu0WL}x6=8>zg$ncl{;K$0Z zv+Rk621sL(l8T!*4i;L9G8pepDc8*%c)3+nvK>s(xJ^$-WN3Yl0?DcZC$IWuZJ2|l zx*9k(ZtE5Y%f161p=gVL87p_RW*J3sI0vf>tZ7Up9_PjkRIDsLL;Ph{Hib=68Z^WM zYp6A09ZW>jU&coENmjU%Me}VSQ~GpXpOEE`2n2A1=7zD^cE1>FC1fSzAPm9k|MSM{HCH9Q|J;p}ng|PMcV?Y`&z9cLAsZ>E zXI$7L_IXfD5ZDO!?sbo#nz@NX+e*MFp)9FntgAUe7PDGa!k-jqsXl|oUPvGg1R7zg zzU4zE7-Bc~!(@JHfvY@!Cv`IXy=hEfZI*Tm+9FDI;MfnJ3>WEEjciq@`HEFGa}JDJ z2-zXhVQHF4eSJs5unGNH`fi1hOXKDZ0tI$`F@kbV@HNa69 zgfik(Ns^q3M2iIg1`k};-5X?kK1>7tcW$G5O`O36@^r?*5A@)7_~w)p(V*x~;B*Fj z744@a-<dj*Iz5p_*{W&12Ed zHk6(bNtN*B0>1d0Gw+HB7}8ukZ^11)_`Js`^K3Io=qy%wSV7dk_T!4CTsr@oF1%_Z zXykP6e=D#fm;N12z7j4gtzOKno8(r-U#iYThVTL(mfNpK<&eCTLm;zl-xfB zuf&nO$y$xGnk{vsaKK#I&%a(k+) zwn6NY(=Uqc6_KRb7)&YzDfkUazb84JU^W|WzGx82T{B1$*aCO1+=_a$Bb`yn5FNOM zj=M;1m~BVd=m=d$wvSk+=D(wn zYeCae(cTs3W-fdSo3WI?nmVREh-l-rK}h=Tm38~&RlGKCHV}AZ@bNb|O?@MiwRLQB zyodnS7HWTN+<{OevC|X*azk0yZ|B;W|DqtT4iONSkP*|Lcj?lP8NHcoP@gbt%G4cB zH;!c-%O)euHP^~Cv0wcDeg&_C&~KHcvhsH_V+gBW-ct zt+lfh8T|0x2tFV*I=9{9NSrp)p?7E|T2EvjPUI2!(he6eF1P+F2+A;SEkG!w` zyZ4=Hpq@WoSlTd;U*5q5=ptJ$R!ZJbtXf9u(=DB+uc!S+xLCQ5aNQ1(bbo&zr+Ltj zzXJ!-ast@xJ+~)!U97_sDYrPt5IOl~BDl(c+ZYr77P?-~{xa={;ywJ%Lk{5#Jv%zq zGO4oNp6sVlHnloesW8CB3tuo76yO9XmGa}YQ@(LN=~2O^U))tSok*SD4H0oKr#tpq z|E;TYMI4;^0M_>|9Sm*Il%dH8voC3C|w0>5gV3~$quM6gFaR*q=^4{z(#wyws}tTqj@Q8RtLQ!UWklO zj(1v$85GI!^aj)7;TdD4Jxg;8y*bOfqo0#^Tlv6ak7*J>3aPOJFX!ns)5+GnwJqZ52A?i&Lzo-XIn~pkKxSa8rwYsft@n+wSG8T_Atc(KallwK_Kn zwpglmh5?OfOdIs20~03&pCLV&O|R))|46Ntwt{%ljXWYwEU{4;izX9tCHzC#uj#NZ z_fR#R_Dw=GoM49*oI|R(ikfuTqOVDvJIrgzvb#G zC`#Bh{)_xuasztG5b(H?^Y~GLKhlAj;rfuYRbu^6WT19Ie$uThC zFCJH&)N$p!AX6LMlBYZgtryFH9u;nQGVICbPmmsVT0CWn{*wrUdysPGm*TeEw?y1Q z@Oz=?fp+9ei?qAj>0z8DxGEJ(6lSF;Hwq=z5?I+ap?SBiv)qtKO@zZd`nx_3i$Z+c z9Ob`nGPp)qr}pL~HBgvi9~$tt|M8dhz5_q*Z`DSOj+z?&9hFOzRSzZ(BoV;x>~= zHloqaZNO~&IJ3EWmpnhMCH7f-IDu8pVYcN+Szm_{)yF$&=pvHN4}~U?d=AVED-Rg% z-P4Bi40Fhdlyr_H`vYCQb#GaKyCPzYif1_EZ$nHSQL{6G2J%g&h3tqgdse)YNei4P z@Wv{uAfE`G0oureKb1!}Kl*$5{SGi#ug7mDU0D#f-teqV?@+R7&PFv7PdKKU3Tu1*l)iNAR(O*QC)kNdbpsTLVx5qFI04=Td zUpUpJp8CjC(Pu@@P2M3g$1FcCk+WKR>zANR#mXe0dc_^S8ec-Z$N5)-r*^@)TeA!$ zN6rR~v3Tj|vEbe3>BDP2Tz=au{>?ed&mYzD%fho+`sBpPnVf6+1OCH943KVz0n3y( zot~l5{jO&QPFx)=br!jnsitG?*Q-?~(+7-=Y|2BxcDK-#j6fQoI4uD%T(UCbc zF)@_cDXFTCw{ec_mXDm{{5Vdxr5pYPQ?3EY(S%ogyQ><6^q=-!esl@GA*`#{_Wpnt z_kenr52b<5>`0a_PCO#aUG1e#pYhbK68ZIli}Jt}Q9VIlOPCZtkgzi}{NN2%E0COu z+TgctqOzg?@p%6%Y)R)Q?I%%iq`H_Zr`%Z3vcjJ=GV%yD-8NS*Hhw8*UtnBrUsVnw z1RCUTk?rLVbSH?J=#Vi@-MWKRPiWc1r=g=ZxN3(F0*}6X_52kcw%;Y8 zTTiQK-cHNxOiByr0pl=Y_US+OoRw^lEAdOjXY`&EH#yGDz?F55#q;GZgd_>;b8PTd zgYc6b8U%p__tLrHNs%YzQ!V~jZKnLodL&YhiN@re2>BA5e=i=5#44Ut@+5>8c%Rri zDdW|gOE?^OTE1i|N2I)wvu0MbO)cT4%=T}~L>M@kOLF-^B>bV|SXx__E$;c29#`A5 zQ4JTiVL*Sn6C$)Kikh)YY(M2Y68wGZi9G`DLN~J0x`1iR z@sQ;T_3(cc9SfJmlOyw#h-FND)lsv)0z^x{+hL`nAD>{++ElnVQ->eyIJ(b9Uzut6 zm|$9aI~k=7%mbqgynYnm9xKW&bg8ibP!;#AGple29OU#VlJGaF-(4(UV{;`1TG;O3 zfG)@Qp|3tvSg@(3v|%BJpb51)O7%fF!K)32Y>~0(Fjv&}zBmi{&|ZqF%TC2coBc~9 zMOUt{n*W0Yk9Bz(WCQ=C@ol3`G%g@%??v$v2)UowyZ--{E)1IFvco*C0Xz1C!UUvt zlbzvnW{SY3Mkum#PxblFj*x*;-8;(e4|$erg&KBQF(r_h{W&xwr{&9Uu4t9NDp3W6 z1T(I`*BW7%>jO*Z;fSC#Z@lTgpz6^4YM+oag~7+j+AalF<%CH|Y0U9b+gFjm!ss&> z&?E~8s*~2uWzD?4(f+oKuiUY>spoXRW&VG+!;go*vC|~0R-XxgWHDPf7x^64{`>8x zg+*U18|Y{2ZJ+yK>i5voIJ$Xp8UDH>Bi<(oz{KJf4B~$kGI)~@nUY2dfO?R2n(_I^ zX#HT!`H20wUMT+Bic1{@;2!g9^%BMnV>`D~)&fT;cZW{_{>o#ch!*v+0E@p`3Jmj| zg&wX?U^pQJAfa{XorZXrTF<%$9a`=cp0^WJ9GgoenIHrBFS)xwL7v&vm|=F^=!15# z(R-{NTi32^$GU~vdvzxV_I+10VZ%1md(m*kvQR(+%rv+=_{`yR+}rqG_`Ka-m~38P z?NT>nZ=#0?nsBp5{|~s22t}Cmb!24!73+%RF_61&A9fx`MkRniF8jn>@Y8keI70&B z8w1$Rr^!A?`5~yow~u1h*kl_62BQd5_sTk30|V*9O87$QL46nk4yH#v)8})DCRF&_ zpMB#Fg!uj#ePf zav`N9%DWq^9N6dASLTIMIExHmLSu7mSB@^w6#yPvx)skVqyX62y>Hpvd*oMx2+bV3 z=7OT-ITkDzXRaSu%ZcyC6L!$hEN}6qyNW*66n?n~R;**#n($t?@*EOc>4+-^Lb>WN^0A#_nvV`Kc5EBq;WVcPmpTO zhE;slTEZl!#dxsOHPGU0g{^gt^dg|e;km={oJ8$F3Anw=^l@C#%*#PB7myc-cDTK^ zU$->Y9a4g4+#I7@2!T=T6NC?xgOvP&QwESPyy(yp$IB=9=B2y)*d4!X6`k`U)@oE% z0+wYn2gLmGBuN`4QVsG;uD*$A;I;hXlJ}AVqD$xW!p#9jyqM@JPdC6%GE<9rK45#P zol@VNPzIrzOp+aFT;ZtB&wN^H3XmY=7s?#ZL6C29#+KGqJmo6@d?%LPVP;K7YNCU4 zE_EQQq`n19N^9elfs9o}>-Pi`gEQV9fAeVc(Y?2z`FRNlY5H7l>hScps9Fw=9Z^Nk zE=GteMO%(|RBgzH6^r1yo3$RjYJY;T(Lt95H9tNu@Z&O}VLvkXDQ~6ZVz?MDuSmlr z?FwtiYVNekpVD_^fD_mk2M3`5SaTG2xLB+lU-%4pAj)zgE@o;O<} zWEM2M0sWdv*c3V}i>tp}>*)GprM~@NVjMHDgLGq117c{*ppz_Druq6}8hl5_L(rx62Kv&7Zb!&?rtx)cIh>$MX3z1|hwc-$$ z$ZE$+Zd{VD9SYZJOSh$4be^@$lKtJx!E>D&aYIY-k(4bDG_|Wmt3wjIst&YavrpSkPC*@run7~g(ki%`pf@&Sb3iII{by4XR zIv!uIPvH|r>3(q!1-(6d$jAfbd;JFpC#j-)y|8d?GtUh%mN1u>ja{CBsWPM%ud5@r zj}T7ncqVsj%<$fuB2(Ku4>|Xmx4@J6V~X>-$xU(!xznozbBxzdTCC-zQl9MnQrk>> zD^M0A=RWDGtWgJUI{xjTh56ZyhMxnX#Vo34&(=!5TouaULv6Z4H`LrjB!A5zw9b)* zlTlAzrD52s8)c&j$1_xFbeDRE@$JbS^OFqiHC=}HRR zF;1c~G5t$-pFb2H39Dl+h*HdY!lf^tl^Cj^TT^`+_DbBwgW2LVf7mJDk6{qEw@JD{ zTey;d#EqYEkCmu4->yYsDz}Ccs00&f@C=PeXxHxW5m(x#GsJ0(#o^2$>`o1HM)S*Q z9&7J7!aPxzY;afJDtzeS%cxk+tZ5C=e6od8rnA*-t)UaHi7JN1(6ySEz42}7RT1kM z9C+4IWOxEhz0INI_~dB}Ql;tE=~u)?b1c$H%uUG&1=o}@yI z1=p%!kucTk(-ho*+&68uOBLS?IE=YhjSwaW(6~sM0HLB9n{(DMP=Yp=*;opFI!~!= zRMRJ9zfO8R$JdJ30-A0fY^l6tEn%K#gs?v9%&F9OkY`1z{#NeCE^(CFB-!KkUUm<# zY$8+*a8aCz08LCIChR;o65tAjCEFK)w=QA|4Cr!3MfqZa%2?)H&fGnEI1_g(nH z%YBko?`?SgQd8|-H$;l%cDn63_6nQ!`Ol1@l|Cl$O@*mU3P^M*vZy+{c0AMCGv*mG zR0h%RGn0n1nVw33mS#RuP4Qs0UXwajO1o_8-X(&PmQ8E$S_8n&glpPUk-Oqt@jvYK zMTL(q(MvSTs)s7ApF14*JH3f))N`mhl5XRqD17l!%v`{rkl+Rb)W91x#)Hn-U>Z>kirY!c^*v4{_3S6Zs%;&j(u`{{W^%4i5^C%p-f zqrpuQt$~B29Sx*9b?3|BjFqv?7WOCnINbqn*=M>OuZOYEsjD|(2sZ%d=$0C879!Z} z0F`Ncw`(6eN;6I5d*V+Q*n4a(lq>9=;STq+TuaW>QB zRF(Rr?RAMd;Pw=Ai1~z~>c)~vSk`o373Vd}aw>1Hb#n(Auro#NHSh%>#Gss~-ID^{ zil5`=?k2vj*#irZd-CCAN=zN@c01zdj@>dSVZ7O@xQW6i8_NaO4%@MPf#w7>W$GQjfwScJsZ zP}VYr%1+nqp`vWd{`896tG6>Y!-^7%KjeiA=0VA|T4fvc8G)iw5W>Yg_;lt@o)X4P zZ@qnmdM@Yy}sGZZ025i6&i262!85r;gG6JOS=Om#QQBmzDs&vm$mGhR0`A2(tJZ zYBwD}|9h7f{|#YOO3rp&Np7nmR;qAYla0ieTH+A@h!!SoczzUN#pf2*R)4gVW$42` zyu?Zy0XyrF@Xc2IT|0}&4F*q*IjjI$aD_p!#0cB2Wev>?nF~i8mE6479pMni0A@9X2bP*989mt z8e~*|2K6044|$*dCWzWrjvG>Lc^fXIsm~pjJrKk?juP3 z+O~pw)r7>ewdDyu>HH~3nS)KOd16~&c!z6BC{m<|GDkSArEey+zXl2Vzfp<{j}on( zK}G+;)DF3g;kaC8iM-e2wm(we;iq~Z04VK+ErMMc{NxrXav@4(6@T2+U=BNaXJ4aM>AuYq*9l)v4+y~^_-FTH;VFhAh4_NONHw9F3ol> z)IOd%BF9`$_(-~zk4&4o_T^%JPCUUGwb~f~NOagsyM1pKb?^Xj9c~%+XbX`2%oj>`lvwAU$s24vP29)#R%8p)3Ut<_qlZNW4YiZ$Gvv$WSAlqqe3h?D+A z9uv|iA-)UXe|Vv-tV-l z;qL5^;$Ov7gPJ({M7^Eom1XJ6Ji+23hhS2JIpK#Flsc6}E%^wJst4=_dlOqTi;oM; zJRybQgypK6wx!lsd`{PJ!%kzFYH`NJ5%(4~jQJR^Isd!eu=xfmtj|TOB};OZ05UtF z0(qvIgUkoOUAcc~I0s;g0EfPVlQ+EdVstww$WF7e+D zsb3Np*NOAz*`Iy(DvsW&?Z(V)6Y7$>3IA3M94f(DFP8WuC}&WUu{x#QBVI z%(ekGm`=tc0d30^8lCZzC6ebl zktLiqeHd?N6%2L*13Q~!Hr7UH=?Eq=B)n2|XM93s4>q^zoKv^3k*6%q@-Ky(97 zsSGBx*#X$S0WK^(&wB3mumeJNSs4mR1tOS4jaMl7^wCa1 zTqG!UbIqi(N$LCNSxJ@i?S9Kfpr>Ug9F;;-MGl@tZls811PNc#w`wv9>;z>PuCS}4 z65WPS5%8N04ekfKqLW|!kT`4f#SIpURD=c382W1iH>xEwwpGw;b}+vW#oDa&T`BFN z;B|@P8A^D51iVzF0f_-)7(lZSidgJBP;dkySf;NM_B42DE!DvfzTf|@DoSPN7?PYx zxNox@Weda|y*)a0o;%LXI`{am`(+Ct-l_ZsdWcgYZi&6b(LS&El&dN>LV?WJM80r8 z#7U4YJu#5#c)4)YNl~ed>pkoI2bOx1;N!jHz$V7nqY~Cp8%q zpSc)m)LGmM!#m&v9TTUEF$vL5%6h(qX29dA55Rj`Oql-_FFRw?DAw;0@$(Dik2|kF z8E#zM1?iw>qA6(}1F*a@)aT&+yDaJF!Yu0i5Sy^ZSK7DnmjsOg&!k%$(9j4I1OUid zWrT;%lpS;A9Vi)#!Y&^exrbW3ooVKQX*ax`JQuZtD&Q?!qZ6);cHS~nNrk!~YCTyyoY&z6rM;*ESJ7E!6vv~g)R^EYjwmr>ql#M z5ZX3Ha_I%=o@@W9q`y#;ME&O;O%LYsb2TwBwYpw&_A$;QY|Y|_PCnx8m2WWpAKrJ+ zIp)O|N&QOlWR^31!gwr&EDFQrc{EKzQdbnt2*VToJ@?$O*%k{CT?2V&C2e#|n&zM5 zB>0)(;F5;i9fr0tuIEUzyIP8D?t0HU_D*I{kct@ho94$Eo^zI4px-aB8n8wh*`*!1 zdrsJZ_O`OX#5+Y6Dj{4uu_oPPh~2!kNw2X2E3tVqOGl7Y8Z@kLVR~O0CQ;FB8P=C1 z+7a~wet&X5PHGh>9l3vJIRAjXT~~g!wQy7o9a$Mx7>{(?aHbQxU<8W4^E&9Z{(sT{!U)e%A`*$(}jt>=L(6PyX0 z6NkJNAauFNVJ9<(F21@-*MkdwWrGDSs#A14ujG4gfjPpAr>4SCj?jIzqwN zay>g#sLzwrB1GzQ2q+_q+`W+6+D&}MxV(%^Q!xc$dQH6$zgEU{cvrR^$#|k|D&_Ur z%jd=DjMS04a7MVpZU{?kY&#bk^$cI@hEogK?;l^mbVR|Ws9o1sZ&atOn}Cjg{#edg z@EuTCt@ypL_POF_a44Ori^7cAuLTq6MmnJtI65D?Tn7L1UqQ)o^J;tI)f(~2(q=@< zgt-v)jFK!%<{Qqd$0a<`>nyB{S{l&Ouc zB9Jp+{jsbAAvq9n4;tkGu$*aF({l!rSQ&`zz1Np|tBKQ%ZJ^=b%=@#H*RbPG2aYJ4 z6+6j}P9@kVbt_Z2mD!sH922IG;GM*B;AT19-XxqG-eg{RUBBJG6Fzm1y(<{gA8LL%IkDvuLVHTYeS@1Fv$W z%y{UX_>gDzNE?|KU%}flarL4JzKDSy;XBSj+l6)B7A&L)GEzLrQrui)ICyaz+#SF3Y zIPDsg1>?#Ag}Po)T-4SpNE2lRI?;NDDh_6U67K~#~BNs-%27S>csf)G)J_-;npb0p7 zHvaRZufeqz^T7GROpM9>`aBw?q^P7qct(#F5_8i6Z>8-GHqq`Vne*#bBgznnhu*=L zT`i`^VnxWXp+<&q<-QB0_31tY52cU)&uh3wkhxaNC@f6dK1R*tT0}?M+`L84NV_c% z3L+u;lc6|Qzi&Q~9Dx5ynp0V1Fxzq`e;a3Fv{9?;0I*@Ty8mS@@srD%*#{X_E}%Sx z*TWYygw2Bt?oi%%(Kl>Y)*QXg;dWsFul%I~*<$OMN8B5|K)6LLwXzPRC!WQc`w2iP z)_XLl4XpBncqjQ$YnTg{^(3rTtTC+-bCzC+)zY_-&Uzo?c^Dl-WfF$Q0R)q8k>-MB zG`K?-Q_E%(VTz*^>7{=0WeuL8B7EI#)s=LzC0fexc9({SQ*I!X;F`!IrN-AA#6^u> zB7}iMZNcHhJ{-WJx@Tx(OLv_x7qPu^o4=X%VVf+yK}Z*^d^|^mz-;DXO3rI+B(_DS z&@wKK{s9aO)lP&%s}Qax{Be68W2Z}Ig#<49t^5!i?eB(c_LV2M(2l?2o~vwG#uzPP zGfk%eBv^n&%#I|3${TUdeV!y>M2H`dpLdHz)<81;9vRN$7e$c4_4}~7L*m7|VvkBt zJu(?efS$D`UoC=}P>C(=smrRbuO0rdeN5+y&@FE}ubAqHaHGNYlmjn^$M?J$@c#nY zHEz=W`gQeS)LcWz&H)O|;=L0cFmatw@5qxR-+|j9ccWPPMT%`}@%w)#jnoX=Ju4}g z(T(fGLvsH6_W_!hM6r^!o2GBJGK;IhDAtc0m!q?@hq$@STa&|3QyV=cXvH9~@%994 zS)eEemQ&y2KTk3&R?Vxs+(Nd{1tQw&dly&zv?7XsXgU~eT<1PwDYH_{plR30Fe`7| zZB^j*!ZyhRpG>SJczvtS8pX9%hEFjyWzS7SF>q#CMa9DIdX?J)6TWnv{EMg0Z>ee< z|6!~q18gb()Rm>*F@wRTnV*9^m61O&*=FwF24!azzVJl2>+`E^EGg0v{X7h^ETkcA zOHYMTvpE0hU51bw;3pcofU}JoQPw*#$n%UxA^`c5`!7OFdSe=!6q$L%V@ei*`(pAM zO(dW50PLDIg2~4RJL@FW8H%r>O4mZlhGYr#DEm=FV*WG>c`CYKK>3>q`i0VH75i4= zo;4QgD1_xsy|e?;)(6j>BoVUtnVIpWmFE9ZKsykpntV}fJI{{q(175)WE za|dv58A4XepBda}MWvDOI$#19B8DW6r<<0ZDN3ek8jLyz6x!u7xF7G*VLT+LQ(Rz{ z(lX6o5@A0ok3B|+9hf>3YNx#2cWyWl^d82b5tQo0AgN+-}C?28fVeD?_=L0 zQE92AZ5+yugV-rZWwTQ)T|Grp4kS zNZZC9CC4>!rfKf@MJkAh18KPO@1+!k&Qr;_09HHkuI4O9t!7usTr@V3G+(^6l44Ur z?DE~WuI-J)+;SVKo-!q03nYjOd6!!eWuDun%-$Ajgdz>Q1 zO1Gm#JriBq89;{g?3?+kb<~7OVrtUyb{8*5(}*DSWw-=P;LG#Z%zdS%K-_sclKVpQ z*DIt%;*81J&^pjvvKG1gnYj~6@T1o7NkA%>_m}``R89IJkcr@3bwV-V9nefc`7OUf z7-70JGd$WP(pkP>J`O@$gHxocAH|I6Sksbe@(K}-`fL|f#|PL9#qrQ!_k*$RF%^N@h?n0#(T_ zC2t!3_cjK9k9>s8?gudPSrWQzfZ?VqVA3t?vE7BN`N}e~MFwuQWY{}?2q1%X#?W!DnqbCd4B&0h*>_J|1~b@%w2%nOn$g1JvM$fA7z;=qEvQc@ElO8sxqO+ppqzI8T}})I{cxrN*bld-QPLRt>mZki6Jtd0FeTU2gBU4mb=* z%>(z-UK<=HEDn$({^Qab0zR^R#9sQRm047}ksnb7Uzm7+Qo3s6xBt0S>|eEg^*shC zw+=g(S&1csX&ubuuL0fM@V*;@EYshP|C`zm5vzHlFN6hb0000ML7s+16)Z;p35yg5 zdH?_e00093SHS=P01*M6r9@`{3p2TZ00093013DN000;Po~J}t00#r;U;wGgf!F{5 z0{{R60Q7+X02LTPnyfTTe*geI`uD%jQse~m>tK6XQ31Yqla6`YAvH^D$|k!=s(!q! zeY3yIKLU(wG2e@F@^#z52L~+B#{gW7{ZJ%!aR6A_mP(?Pwq^ck>88op;qF;6)u}lW z8Zt0~luXxq2wXN89PPPXEvHDFIVA?!kdlXpb3?NubCbkRLf?;mvde_OhMO1&Oh>ud z3ynxFrW`Bz0bX;LjUGRe@UsoZ!5TlqOo#AQ7!O&34A5kj+-?18pGND(CFNy$gU!Z3CE{Z+zr+OliNZR-zlf`+8gtIi^gV5uk9YQ}b`9Hbg)xH9rEe_`)?H0x)O zYH+rg3|I_$DPl984m7(0v6eO%EjV%?*0Y~aQa(@UhQD4jqcxfj>$bUv#pvBuY_hX$ zXMsy|S+QVQ2VQ!R+?rxnjTp9SuS=0@3cET3J@O~o%3aR;6U%BZuxAltJoDPbeoSCp zs~)L;ch?A7E7-G0eXMcM%0Zl`Hm*HgSc`c+i_zZ=&UpP0(}aWekA>4?nv)g5VHJs* z$I0}{VP2r}OBgM(U!QN`e)qN*edN3-KM*eQ3xujDW1I_c$C zL=FHZV3Ge_rt3r6KT+SGc2X#Wuk_i6bXJaSH%y3**74ZW<(JbtpZL>z2*~g@O|4K= zo$Yg~CtUAz&q&2-E30<2waUtxYNrdH4uD)QFPmrmS#sBeJu&=8jrPe4=&?NP)s{Q* zS1oI9Ni9jo)SI$H@-XO8=HazmkA12H@M3aYhC~1oH`=4J{~9~jH3`{n9~3{~hy($Y z8J-in%sld44h0PCn1a#JvVv-sAYx3f^_*8>kCaDhOq<0qA3QU2qQ6<(j{A?LB+iij8z@$N6P;I=@&{y(>%yq_tb&j|NH$ zA1tT8??5bhW}J?Ekk=dGvU9x2yW0a=X`jh3Ld3DewgFhxd!0RW!xG4%Z!_%>>p$|I zxyId6)dpB2KX~s(q`t!DHjqe4U{A)83A~ zF{RJ866jp-&vN3Ewmm&#nFJ}UL_@^UrNn81DwP`R6sz#|ETd;bFS@c)ofqr!IxiSz zWIzc%jtXH2*xUPy5XNi=kp#m)SC})$k~ct6FZj=yBXwJrwRlJJgckD~0OlEB*@EVK z(4s{?6h!_>;b%M*DSr|Xrp4e~SWOiw0YG?fzqr#`35j58PN0@d<7`HOy3!!-PKrJ- zbDTQwhx=m8%!@g_mLWfZoBTN~!&WbT={blnv{wI6ZxQz>WKNp*AMJ2n_L}3bH8ywg z)xURauT_|^b8d1#;gMF3e3PtT$^5pXb#e9ewm)E>boO(07qh$%d!!LusOwu$6b_AjJ!H33%6qy*8iTc5!SA=T}_>^5P>`xJ7x<+ zkhzwL`)o{8ko8*PkUAw)RsLH{!Xn`DLWu++Ct@&3(p7?ayDdyd%$Y5|qGGZsLn3>p z^S?p|h_zHx_<=e^RD6c#o&%j5v<#kP9rgF(iwD<_66h}~q-PB}4N4Dlteb?_nNmVQ zT(cId7ty~bJy_I37Ps^$G>XHl0s)nDWgdaNzG(jbbqsPXpzsqEPy4rWd?%Y03S_O~O*&9t5GMBR*=X1W*VE%_7Hl&Uj#Vb^i&OXl(?15YyF=TxPBbfK(Ce4(_&{vbt?PR}ej>bm%hS4cse64njA z18HLUP?^>*U9q0ZRG2f6IN?9=2@X?6ku)(=r>VkIfXI4{o+EJ zS70d5G3)qw_I{jYBD2iKJ)bl!_M^#@hg2J*OmI)BS`|8>v0NyFDp>QEFj+h1R5n4_ z*VC&vDgBvuQs`Wg8h?O!BZ(Pu-wp;!*@mw}R9jmBkhD2d+gl~@P}2^7`Mx)5AN**p z3sc5&9rvE+aH!iB?jeoEa!<>}l)@>N6iOHq-w|rHH5E$bJuA?Eg`N%+9y9=J4Tf}0 z`^4=A$SuTnh=V>c6j1*)MecV1o@7cTuBB z|7ib@sH(RA@{FTW5I5+=1%wM~RnE-*?)()U0gy9TClY_{O5d}2;R(|nz0}I5GU@{s z#bnXZhDM2NEW0T>2C)+H$cGlKhkCE&ML-~TzasQ)CvGNspT3;@55_bC8<=fCod&W; z0F8_F5)k|O{P$IN{97RUFf4vMcqofQIs*c=SqXS~=+NH{IxDI;SjOXr^bN>}X~GGR ze|Iat$`%Rz%h|1^QwKLI$iu#FT}K_3r`wgzX@G1dlIcYrj%nENS)J#t=z?KA$OKh( z^9Y{87o)(y(^enhrRKvxbS6YvaY4B{cuy^Ohk|}8`SgmtcXC;%No}+;LRC|ow}*qLBFvfYWq>T_ z>+bNMVH*gp!$UD`SN<|NN-L8FbF-^G=m(ObzMEvZvGUpEDq>}t(H2>{kj;vFOp&k? zMb%-Lm|UR3D%cbgl3YxdvmI(JPNW3T$Cy|4=U*)H)z8;-xim*~i?mrqAtjiy{xZ~z zk5X3>Y4DvS5U8bVPH{ad?60;L#B z8-0OBx*h>n-sl|%-SzOlS`l|@p-4Hc2V9|P^Oq@Y{5OzWY(P#$0$7aP4xYJnzK{QL z=UxQ0x%K$sfP`6-GCmmTm=~URaPXTI|OQ6*9Xwdl;kMv64`kHL4|y z)*=SaP@}FCgllYFC-e>XHw61r7(D{GFk?8fQ}JdN>vqxpghMp zjQeLU4vz+~duhLnTVZXRdc-0UdOcTF8+IHY9GD5w;r8!(gQ?yq>a38;1>i$K#1mz7 zP&;Q3DG{;=Hj;-bDXnk(EY@%UpZp>@+Hkr7xla1S5nTx|v0C&?f*xrQ+++Il1%Lpv z{?`r-U|LrK0fvl3*xhx!Gbnav1k<-gMXqJ15x8wr*7)5Fg5(4l&)_Q6n(|=Lhc&k1 z?#J~tBGJcRKIhkO2*yZA^=lLHK`N%gXxJalx-6iZG6h$aFhRlI z%*Ml@y3ZgdYFD@49g{2I$EPfXn?^1qQ8x0dSZh?CG_y4!=W2r{nh=ce^>ZE)9pgmy zm5rUmMG9tTr&U8VUDV*JQ$Ur5Rz0-xIri9ad@>Lo+o++9C6`X7%wwjxnO-wliG!f> zpG$*p8-ep!V!Wfa7Ax8kOW1i{i=PGMxo+zG6?shkc>?B7C}8HNjWq=A&eJUoKg2|- zMEjAIyivD;(G0@(!>};D9OdUk%puGzAzVRem`8!&iXr8wKp6Toj=)Z_p4y=`m~9o@ znOa`-Niz9b#n^t$iNm13C|_?Uxrcgz^GhZkmfO>DAvZ&QAZ%S(6LVj=pN2R2=pTEUVg?9(jmgixl2U8j%ByGwH0v!a+sVs zr`r-B@;}$w;;OQV{JyzvIs+jrlS0RWHgojT^-j2G1|5N7~?uwUo6qT^BE% z1(B7VfX0k|X@)=6zss58mFBjlT_RuX)dZza8*+DFpuEizYgamq!f%K$^LZooM@WnX z!bIvkWsC_r2S`!`{reK3vQ7-6#s;H}A%ZU?s>tQ^4tB6o|I4hmFU|=W4)*zWwmG8g zQW$|G!93?|$~1;2#RK4jSgI1;JLbi<2WO^971Ih4(GsA6j3Xt16T4#<{9=A<4ns$E zypuhi?n!n+>k&f9c5;=6qBz2vJL1QdNXU46feIN5!yHHX1Y7v8{WRE2vE|iq_I;B* zY;~x$#Nt9>NK%pcWB%muySN3CcP1wzVN{HQD{CV;>WK}FIc=yB?vQYiWR~+jyBZ3T zv}#Efj?8ALQZ$1o^MyJBk-KB@F0sM51Fx`murzFZXEHka^Fn0_wK=n4l@$^IBvbmz^?TJ?VFs{i1dfMkeLUn=NOCS-S%lPJ?0kg zB|V785Q`eV)1gc?PFeDLjJy;&}mQWPL;#UQAxaaq?wMvoxwuC zoHvMv0gI7O&Id2?`l^CqYJ)_}=okGpx9(tjIdpX^t%UD#^&}Y2Ch4p9V19YL)&@PC zQF8hai);R|mY3F?8|w@$)-p0hEY<_~NkK2lJZ|N%*BhH6tk*&?rXwHQDk(r_+%LG= zfdg8#zCACG zkj`$5$=f4_0}=iL`louvdUv|`voi^GrF5!#nH!?b`v!r+)F6NfmusbBJ%7)81O0c} zm!8ldKzWYf|5f9`t$!+|!}L1s)==#?Anla4wFY4sei{Y;z*Xw~rDgTFj+mHi%)`#n zPp^iQx> zu7!MqmcNjvjfHOexdd)tsqJ}SNh-Zk|e^H#|HZiIa= z!j26T73UUfB@8h0000O0iNkZM*s$&V5k9F%fY_3Xd<9jn` z`XLukg(_J;arm=8_w>f|S*zr8bQ@*}wlVr+{?>((9fOdqD(Vr)5;db>Ww%?L zLYg3Of^6m~1&Vi(GBUq%c@0*N;T8-Ci7pQw4qIGHgSC9p!a#MaTHxm+w;#c9fkT-N zr|>57TtDW(_5jpvSQsZLY4S+76b8V--2r5hMY>IUt4f+Cb3E@o4mU##&-88|L2B5c z;E=;B0u2;=^D&@i&Ksx+^tSzZ6HsU@N~vYdCTDx zJ9wdj3btExky*8usePEEs-?eOGr8Z~nJ%T;Cc4+HwM}>NTC#_3GzSWkN+t(RK9xsu z*B`3HYgxWTWcz=+emsNkC@6QA)8c~@(2VtptPOpT+;2Kuro<`CIW@==sq0v5!AppP zxk%~nZcFG}?}%#owi&7h?%v#sHY7{%y_aF~uJ+se1Y)=jx%33jKR~8eB-qUg6DVa@ z&jpId5_XX7n&c$`*zJLwM|-OpFqGJ9*%qvVn#6(}_~riFmmwVlSyVZuI<-CsC`pFJ zc0R+}J7r_+LbX~XiuAky2;1&^=|-}a817Qgnr)xG7gWQOj|>Rxm?uf3QVy{SmzS*M zlUcwsH?S{i5l3-szHEbvw57H!_t*v%v)(dpQWlTOom^$3Lbrj$X_%^%;;gtU6C@bYM^$&yEw^3$@q8>2)|DfJW&>@3qU#Rb_c<}Y zZQ~<5``>Z7tU|+#>NJ>KSS760!33e*PTLjuHPZqIH7o%byPiTF8o*b#b-H9J%2o$x z>yO-2;?fUz^L{(fw{jLwF&Cv-z z(^nsOh$)^SPs3u3vPqq&(b@s_<(@_M**b4MU=q0xozjV;jJMv=QHfuBFjl-iv1MR4 zF5IO8S@;Cc#4vrXiYN?I>M0T>&YQ_4jP82jP&Mnxo>tNpb>A^8JuY4W^vUi}(X$2b zrs*=opw|h&CsxQDY>0R{fJM z(Onhr?E-wXrdm8UKo68HR~xjRL?;Bz_`=&pI|)9wjQ^0o!o*7+x~NmD;)pk3C;4j8 z?g}Y$?qH@`kF}L^$0wx^W`t;{g1@0G!@z8-w-?Wy*G=*6#bOHTqnpu8Y+R{BOFir) z>QzR&s?(q#o4KWue8%-A1yd(h@#Ch=;O?%FIFzf@x`G}aGT>-HUn zl+aJ;`(B;@VtVs0Vmam*JD6lD z<6%^p0Pt0G>bt~abQzZxf!6>%4ko)^e0y>P1T>beWEIkYqB|NScpL_0WUE^|Io*e= z=Lt&U2ehC0*DCB(Maz!UoF8}sok6hSV*-k{2miKB?$%ZCzmL)dZ)iADYxVG^K3R%XR2P0J>&zpbIgG0Us9hs*B_O^BYa`r-kWz)bbKX*tO>ww4cc5>HX z^2*XY>mAbPA~*i9#&$2d<4MQfLQH!X`-R!+MhhE(?L~A;y`IIQ3km?P%80#7A8@KA zfCQig=a&!poG9_12ZiU#!WJn$qKDQy+EYinGyM*-g9q+qKBMnv&u?k~yPn`K&Z?{)1puO~K8}R@mIrrO)ykK+6 zWs#13%E)n%yGA|&Q0gS)?~ov!e(sN-HL%n=3=TZXfQ{|VL@mFHlx1j6u&nRmseVV< zf}?6;u7iZh(a|b)x|MRmVhzizZHu@tm-y`))NpewIB_gloM(2%V3HUXeYnZk8R`sv z=m9%>lQ30KVj(BEpf@b|!q@Aqjv{2I z>@`G#M`3g`plUbLuYkw^v~sw5Ab%3*QYXT&3@4D{EAz|=cFZ#M0d}e;d@0O zhASk~OFGJxiRwUCN(_m8e2HY$TYZV1c|0DrFdjQVw6!`1-+W>Ne67W}PH+dx!{ES# zi2>7%Uj?239j!TqTTrBLz2%`S(zt&eZQh2u4Ym`bcn~HVhH*@2J{!Np*|$UhCj2`$Yk>+ zy?J2q^b>A~| ztP%!~dkdS8Ie`W>(z9?xkEOq!KW`v2(9$o_` zD&k-lt@cnyX{)7gkeEVNXM*sx9~;u0(JTtC}!pzYhrwA_}y8TJ`lg_6oD_Swygx|0*IOBR@T}}%Qw3=r9C61&t)?& zSYPdu2Aj6tDtUEd-<>{ha^VwUT{GqgjH^-@X)_);$6?~5?$vO|Be7@#Rgf0QBysAI z_c0|zDC@-H_EZM1I&8N#Y9Y-QlT#x&V6|TKj6kyi?iOhY3k6)O34$_5jn8=O09->; z8ejZGb@@g23+812)%Wj!0QAEFX1^?_D-Z|6LbH|`Bj>emWJjLq zX;Qxi#?xniD}szI8ZWkgk@kRz;T|6Ee|~?U>OLtIs4nb@k8N#km~q`fi}9*pH8!gz z!!`amvWpY-%4iujttrl=i^xC-s~2|LbpWH;{I$VX@vc!KycBznKPHRq84 znKs||ETNOxEv?+Wt-Q`#M#xH}dBAoCoJdJsh^wT!rbnx(vQu8dfyR;mIY-i;U-*adwUE}B9lC+F(3E(bQ&H9tyl>QsT7V!b=*&&s#4^f@K z4Ly?^ppxtuH=Gav6Sm)A6W6j}H_m=;w06qC-045iF_R8Wqzni8G{);m)#HWA1SBrI zAB@#GjYO*w_m;l*AUB349!@Q+Rdl7X&YRBYkXrc6f17!Pb7V2oLWmCY<*+}|^+j&z zR?w+EqrNARzB^qfac@6l)8no$-st39jp5SJk#mD>lmTGOt5nx=ra-P@P9xq`t2%Ot zC0>?H&IC?mvNf**Uj&^|1$u?Sy_pvOX=H?}8HkaxqC z=p((|QFt0ZsBvI&yHB0l@5%!}g4qPXf$0x#$vV4+U?caC$bgNVNn%qo6bYH5Xny#DR&vYNF#n z-b?npv2&P#E1Z5xkGp{Vq8U4=Umy&+Hryzqz7X1T~6papYk9}l^q|3w@%?S_co1HE>asej!(ME}rN3&B~de359R?fIbPlgd=DpJm#M?C0mA_@N+J1076l+j!F9S;dfK1AWBL);c-qI91E9BZY+pg{SYu{(?iIs`crtd z;!`!_70}{wKxdJwW11#nu+Aw{+)F}MI?*V7xFM|ozdNz;8z9izObWgi@V;d$zP~g( zs2$jBnU6reO~orQ5vnXB4!Qf~he$nV0%u()t7^*#iAUAL{FDyOo1s7?`e(!EH=L1! zPAo(|YwQ`+LXN6>QNK*>;Q_+l;ei-ykeQ+BTgoblADOYZ`_QwCm0ysX>CuVUEv`6O z!|af_#u!*f?2l0pD*z^%DO5IpT4s%5NvUM3`Jf@z7%jAbHv-L`AV&n86u>PWxNfIn zO4VwbrCz$NclZTRo*9$@jMvR@+yPMwrUH!KP;a5S>t|VJeUlOeMmMPUQv>X61u4l* zY7#1Wh(8i&@1&8)$QKxq2B3^T#%%d=C`Md>wK=B72l(|J09W zi=ck89JIt{&r{{?b;;1kMq6~8ApGC;lUvtk{(aiCdZ0eVwsc|9FGwsE~}mlVT7~W zsxb-f2GuyDnMxhi+$~N6 zI;fayCNiu`fE&78>#ww(!bSaxkgbU;QlP2UclrQKuw$_oE(YG4!XRqdEO_O5;CH1S zG841Mr^)k_#x`DrDxtwa=ey8O;v$l}y~MMH0Io-N9BHRsz!D~6+svqRq01iWT57XO z?!l-?NF8J=^eWU#%^BCHNG2ldZ%F|$2KUn)=%}P}V0gbO|9GJ0HI8^2;A1@WZ}2Xl z6_?vk+|8}L*=_GBxgAeym`WGK;>pRs9PpiNihq{9`_(znGhNPQ(WLO8q7FTropA%7 zl><3V-g)bo6Nr5<0(ePhEb!?`o?(A+ObT=RU3>$n7K^aM$Gx%O!~WR`a4|Ft!oIa; zC7>IhBi~$s(TvFHcHge)4m!c;oAxQa_N2C324@Rl@>!KsGksYC_H6 zdz|OPH8hn2QABeE?FgeFXgiv8ux(Z`m(o{SiHN`+8oQJ+L-}UHXc~%U-mjF1&2_Wn z$7IAJ*@m;SYK$&e$-rRmwPsp#~>>{5beroCE*EZlQMb zMVjo$2wVD=8St~fRe^P)2KFyS$+!TtXm_?%==vPUWszI89WBkTUNaIc)gAJS$X0DuCZ;YW3EhN{3Cez+j&&bDSm)Zlq=%j9cpCY&Tgl_ zWQ;!Qrt|g}r}<4Djx)XqT0u*y^)ScHMLqG5o?1F!E$<2HX`PGlm_{m&WA)GQfU}kL zyr6DHFt>fgAiRT;u~T#dQd)EimIK3(Fu!CRf@xLt7CVz=qWy0p7B}IQ$Kmspbe1qb z2W2wL`x|y4=|?5IPw9@QZUaM-+UuaV)fXt_C6kQaNH^XZmY`q}cPB}7E#NOR<} zFojQrxtOGSaaVTKlnE1eBLRV3P4JrH9i7&PUslyJaFo~8y^=--cgQn~QJ2rllcy*1 zY&=I^VU*WJOFH%i7rCz4HdvQTv(nzqk0$fRhH_zBSj{&Bo}nsu_{9XRjRtv= z=12yD5|S7>!;m(I+Lq3bYbsVi3Et;a*`+o;0_J7_5(rwrVg25ca&A45e-Dwpwfx{@ z=L6<~0)jLN2$)=Rw4UY-1RA5ue&vT#<6rsy@OL*w&^taW=Dw+8$fk*ANZ)u9rEs&K zHw#CB`fRNWWtrT9mGRpY++ACS2>*A8JPuo5>P7xZ0Csg?H6k)6Ol|Q|kZl&20+ybz z;71viAkvOm=+YHzyjlkp?q@G`UTG+_#b7||M<|OF)vq+?^Ib*mpNu^#+OFz_RpyFs zF6FuPHfa8MSgp{mtmE7Jq0>Z1I60bAw*DKrT%{81MvdelWZo@GmJ`|4qRg$Vp{w*+ z^jdW06LCc+Pew2fJ#2S1fF3E51b__|s#%}CX?j6F+%KtS4!5zgfgOS$WX#@h4U86D zqW_h?M0|sQ6Cp$Xw@-!Ic23kM{dpvpvi`%{LUkbvIzmnA@59plCOkEsRY0xYygso3 zud*z;Kczi5W%-bRpAP$uYLX4y{Jn+Hs=%E5(M_c~*UQLu7%AXSFk(4-ze+B$tx6-mNL) zcVy%7ZSZQ?a~YUtLgHo3{#OERVN5#tEW=>bd{-|Pc#{GzXhvG}-}i&j9RMBzvCQK7 z4^EinrL<%RaCAli!`U5hr}_OLUl za?Q+vwm?0wse<)LeI*1v9N>N{NR{|BzJ$BUyQLl#-bwDt!Qj*6)HvB3Pn(&bq+3M3 zuRpn33l~c%ujmSfzx=JCw|9yL2JdHRxM#mI{93<^fklb-<`fL7tx5a;Q&kV|>7HL8 zt5U-Wm*2>&qG|`T$+J32%@NVpH3q^ofKYL@`xTI@hyUAV8?^$tcP0}u}b-4c8O*)$n^2a{JGih`&;bk(7Aw;$@5pP-3L!vm9O0tI~U~LbfXaSc=Te@R5_{ zpv=`~e9n3CQ#kYi{D89|KFjGJjFd_{pW zzu<|UE+W(@R%5p}kf8m%JF->> z_Y3J4S-^DNJFbmz+*!daIFhz$w!O?m4QYIAKdHzltVikjG*2{fnuS6i3#Thu-~CFu z>J?IAAgv=bU)T<#>V&j6NqTsdKJPh@=k7cRa&_XDw^fk!;zdWR1tCl+<20SZZN>YG zJ$x4|bj;&Wl3>2v#f#lFf7q$!vRvV|<^PW@ba?grK*9 znmBWpx&f9=LeFPNvE#;R5vkHoJEc;yB`{F!`^rd+sfX@ zTm-SvK%4BhkW1a(90B#IMw8$O*I+334#lQ)D|@z!II-s4>?6P1yL006%pgZaGnbyd zFY4@Ra%Lg#AD%!^!PP(xNC*$1!0`)pSC0t_-N$+|L~_~$wLcpy? zr6r1GJX+O^*YRfMLcoKT#^R#S zbZ^qIrZi^V=hVrMzkE=72=WC%7d^7ZT4e3YbY}M!vqRp4MICEb((|C7FO-(30v$`Zh=Rrij zaIp46!7~GaXDJG8QOmr5g7=zH<$YLc^5N;&xFK))1~ZpvU%odx@*75S4LitJ+XK5K zeyD8-eF$OSfWj&XH*5uJpi$_A+&;=CiaYzQP9c<`*(JC)WmZN5VMk~ zw!wP*k@8e0({~wIyg~N2Kxh3Pylrhp^{4Du>9io}QUkr07*hy0LA(TfA4k?YsjOzw zbeq(FP%5kAMSPpR_W=?RyPToEs7ABIf~Kh`-Ud znU`-bIsGQ-DLR;qgK`gA1?~9m;%A4#hZB?tM1liDBhTq_M;s`RVIPecu39s>lnOv( z*>G63ZW5?BX^gs!j!`mgzd}E*$lLBbsf21~dqP|Qp^=$`^kdOzol4rmSS)|D8a))H z9$f(Lf=AJsXlk-i9zdukaBXKp0=&6N@fL^G0HDSK=J^|~sDlzMnHUx%>tCkjlhiWd zv!Ra39e*Ba^_~;VzeUUxfVI&0XW3!6Vmr;Ox}Svgd~*Q}&~bGx(+pjG>OunbSJI6m z06B4R3>eYT7RB0Wq)E@o+6uG^xlM5BOZ%;J_xVpa4W+cpQX5Ms@Ri(QoA9tg&cdoD zNE@YcgHy|%F1&#>Kj7nOqU|-`iG(cKLqG#bG(uFrs|pufl=BnwGei$Snoo;1Pnh7l1%%aLshv)seGS7Mo{|T*^|px!(P#Q`=1{Tu;0{ zS#8ZhH~n;@ScVH4@E<+a*nxq6N+Fc3AcMx>(d{QO6O24eu9ec3t{lpN3Y=hDM9@l2 z{Cby5r1B}K2e zjdJlD7ni88==LZhPAeA1fZFU09o2_%Xt0HC|LYa-CxnFrV&{Fl!(PZNGhJ|IaBobu zhu<*|eYpo0JG0TCpAJm!%=~76gCS|R&TS6x39Ic09cJph`>C@5b_2GiMji_6D7B9emrdlI6`-vuJN7fdY-9Kq(q|nXapI<$hmY%4eD$ zFyf0FJxitA@oj06wz6BevENsx|FALY2lO#8YIjv&FmT-q2AvXa9xuKBSCNI1d{pwi z0U7*76+<*CY;%%(tFficpAMsI-4&&>789Jui?d>(LSZgbhqKVWr8$S|LBz0m|MlP- zRI)4*0s5u9CUcT9+%^Gu8iFJl**7rkRpuE`9VV?KyRsUVBW&=L*u%ot@_fQZdyOjf zI+(E6>IN8+#iX&RQwnX}VO&gfen__GIG?AL34UHTfAttOrPChqEHe{<4)&U)z6KJj ztx~d68zj;1-p=XnbQaC9p0MQvo^&>r-S$QjGJw@P>p))XIcdEQ?LJR-e(6P^GCMp- z57MI?Znq;PHnutmxXAER2KtY)ZlU1lP*7uRVfq=1i{a!kBO{dSWRHAk4=f=fWxEWM zRlQi3Cfp%J{QP;h(@p8Nen-CQP0pyH`LY{4HK%^o+2X71T zTb0)+vB`NR6I>bIY+t$o6XN0#E!D@HXxrK{-IEn8yrRF&+Jmj z&NvuaAW!t@7r)jThCv{&Z_-TsCZJi6J80(&rT@dIxIQMPSB3RbjM~;am=F4t9Q_=NCh2zy3vRxn#eUW{OVoK1d)LX_!QLuLC_3K zYs+l8)R!<>2Z=N3;x}@|ytNjJ5V8 z82KkwC(8SetI9&qiFT{VJfjipfi?;qmTuvU$zpk>U9&Qhsu3giTyZ>=&)r}oLq+UE zwR^ZbQw*(gnSKdhDAYbdR3>NUSZ(ia`rZGQym=kj{Q_g)#G7h;Y~yG1TApSw^#E;z8zx$^%3SoROBzRRO_CSroMS z#aRdze=|FF7pNuAerWOgR^}D65-K6J?jnPeuBLyV?UGJd{p8eim|E(lXkd<;MSH9x z4V76O!T3t5%jt7Y+ypV_tvD9p=h1LX)$EoRJ8WrvC~q6L&!jWwE7!Q}wikbaselk{ z-ZF5@&mWow4%e~fFVR0Je5ZH5+J{awlD1qR9m(|ruW?(SL#8Lc-wV%WS-{Nxut=Oh$^Rl%>YvTzym%VyOlG5Fj29 z0000TL7xsq6)k@N679124fKzzzyJhmZbA!qL%;w7rvLx|7y+LxM4tc$WaVeE^8f$? z0009300RK|fB*mhDFL4^MSlPW*AS_$QCxd_fMn#}TutOyV+uoo7Y$fBr>?W2SV%$u z4;cUe54u5{G&D?0|Aznwz(Tv|={oPv^Fn6hU#Ns4#oP z9AcY*@Sql0e``Wq&+A}h1}? z==2e~^vUtec=L~P!36H?Pg8ah-!5$dvCyuAFgytW0j@WBdZtNf#*^{p$n|L}UWvk4 zTfRY#&<|cS!(6^T)-tUvcab1ckkF|Asm=aJtwLC+I?ti59C@!TYRdjKiU&FRh^>CTIcz2F1Y>1*>ye8` zE_1Z%4W`b(02;23nowY>Ly$mA)~p5gJwko({txOw?Xw&J0|jkLKRa_i%qq82iU0Lp zpXc71ua-hEYp2Y|dZe)FCofM0!V1wi_UkH@rsot6Q>L@>0Qfy~XPQjyM58{lyLp{! z1AX3YIZZShGxeAwsn}27i*auZ^NKfIDS24;?*ZhNOq9<-_MJMe0g!rlh zDmY?m8geds6FN0rnRZ%9O74~vK8psDq|@ahH|KPu-3Q8!aF^(}d*Rco8Vt(ui@axg z*2x;JF0y2l&YQ|>iI!08aNAO&1QK1*D%DvRATxD%QRCx(AA1prJ3i?w1 zEFiZbP)5ImUBZ2+upbep4@c>ZjTQwl=~mHPk7YX5kh32G)MIzSo{i$_ax59Ut(ifl;N& zQq)LVlC|5iV5-5^uoFr{r=tAo^1P3N_JQJ(h;u;i6K1cgBH`We8 zx)cWegglz}28^NH7MW#eR4+;JT&yiXCR8e7Z$8@8B3!$IaP`NCF-aqv7TVj#XB0s+ zBIC4rmw_|a1&*zU4g#kWy|{qOA(bkH`yudpsm#E>=5NoX!EsE#Ux`Z2>Gvqilh-;! zBr36AwUlqCxs9`EYB%qXshNyA);+9;E2(L+&{wvg7%yxne(+F7bVYk+?qbUB=68ZT zg-r!$KY_gX3c4-eNt*-?)+E>{Yxsk|^8`N)xzJ*7Cspex8B^QiXd_*NaotrK9>}_J zhE47->qq2CHiew$pdI;a0%Ln4r!K~S@oPxnA3uhY2C%d;=Gxzw0DF@|^U!h48p!B; zeWO-U&Y;&#E-@w0|4kHGJe4kdjaBBNnwS&2K+%ldHVoTC{zAjH+ z_p*5N^v6BtI7rc&d-?a=aT7rt)#(B9&gPHqMxiaDkBrd1GEp% zkKvR!49d(oELCPBV<4PhL_1Y;1$OUxXAG8C%d8?`3rZpRiAz>?Qf|pZ+j_{aAW|e- z)v#*Btq!kDMNT5+&T!NtD(#Xkr}2D$a}skx_l~0+iWwWTJN5)cZWZITO%QQkiB`lK z=QC1vFibhexZ_Q(kF{EZ$hXBD@vCnQpnh?n@WZv>ZWtn&-}4A6`nWoSx(*SQHuS}L z)^rgXvU?H@`?DH*7xK z==z7Q;O|}~G-VD)b)`^a86u@wCbt340m}R854{VWbCCbE2cmsNPh1-X?^P^8@1jO! zABt^5m{=16A(MwV1vR{pwnkX(vC|wgbI8X!O)0ct`GWRn+_J@vZdhK;aK_Qgr+CrYY*bbF!O z@{HRBL{&NwbRRMd|58fPBIqUUfH|M?)7iHh+KQ66unNq`S8O3&nM2=lAUa*(@K8o( z*$ABr8Y+ZX9XTVJMLPw75R4M8;$rdYEFt)`WqLy=5c9{M4e${DXMb$ruX5CxSg@+e zX>VI((C@`C&qYJ8)@jF&Vj*QX+7t%*Z7~+1&3?Ws3MtE3l5}Hoq=hi-TA5~ybtJN) z&UpcEXo=A=UBG6J)Mra6Z`Ubs_q@U^JUNd)2?PoWFB-l_M@a;bHE{$N?y|W0mZh9Nn1S$3;cC5Q} zPzisT<^Uz0o-8o^uRpMbflFW5Y@2;T)}`Z9lQv3n41{;PAkE_Hr0eH zWweucUu1Lov>I$)Em~Xc z#(A2qx2r;^OCgO5j!Q>;{JumnJ34)z!&XFx9Hq&26z$*g}+N zoraE*QVTcYTHM_ZK_=~l$mQrW>|U1_P)wl|nhg$K5djo#HeV}ZcwnAad6nk1o}p#m zAxLVN79Gd#YobvGNRXoz7vyJlo!*I}C-<%F~yl)3wmsTWCsC4ox?{G3C4!OrvXL!^Bal928_ zIdpw?q#Vv@C6hahNnTWtQw;g( zXP^$E9x6bJ!>u=RI+j;2RX$&V! z9w3e#N_noaH_rj2~H^A*=?K&J?Cw0cDY#1Cn@H=_@*K4j8P<83tZ`Bf8PO6r+<2Vd&$q}!oGx=Zm zl}BxsI0PlQHNDP7a2(Qxwh(;CNT4H7#FK7$3(=t%dFAL6()0iS{8D8}?3rm% z{OAWbu>)Q?KW-zK$dOj90?GQ`9sDmo$~4&^-KZgWh5yauwGOanOnPxb+#HmvKbI|- zN?1CO;RMSuEe~*#%e0(jp9)Gk z$OcvQh7!f%&aua5wf2vLm=RWpK(ARA@|ePEBbx@e=W7&TuDKwzRhLGn?z^>vW+!SA z%0^#$cxq-II*(F9c(Z3DbpNC-f4x2~dZh<-0000cL7!4Z6)pc1X9iB~7+q*$)W+0) ztYi2-!}0)wJ?@pR0wSG^3n>5q02KkBaYcUs2sYzcFaQ7p006?L7#9-&001HZpL0k5 z00vJG>4jsQD*NSo;1K86AEUtGU^3^q87`@c7ytkkXF;2IG)zzbW z@qAOQmr8yM^6l=+Eq=L#-5*w3_01;cy2EJS7qquQhJrMqPV-$+TRqxFVbYih<1S>e zrE{q;)WMst#&4em;y;3zT`3Y5tcIVu{ZJrKWt{R%P|@*5R}0_+;U~e`1IwOoFcrs1 z{sUy^9j%>yI|b$vQ}eEzzuV^~E9(CWttOk5wFOp;NzOmCyyQ&TX(|({1j#XWsD`Jb z9D`Ndd_PQ6AZs;+!N4p$<n zDsRK*(_AF%{@p8i2v$J`8fbG`anl?F*Zn;P8D4JI0`O4;g#@502r zX!WL6VY0{RV`iF|!7}m_oFZwmrR-h$g^teQ3jdW(fJzm|7xSBDJaV++@sz!L`=7`e zV^=GW66#aQ$b6n0>461uUjYfyQFo1lLGv>YO5;;1TGKZMSGUh$O*pzmh@DGTC7aZ` zXFUP+P$BiG5eQ{<@%9T_&ni<)^K?+0t2Bq~q&b~j0sU}}uGMzK7k%k9c5|)!C89H? ztkef|QGVb(lDT9qspLrbXMznOTdZR{qZlLz=_$a2EaX1GM7JJW0L%G(G)0V@zE&gy z*<2EKUQ?y(DW6u+*wcVlSXtCS;0X&NXar_lz+$0_r6ktiU}ke~7J$IO)C=fe8#DU6 zHa=GmKDnJxDn}3=0yTydi8%~v9hQrc>^@}3ZwqP9sGm!e2qgWwQ-pUe56oNQ02fJh z2Jn_kx(_kIs}N*8g?7mANRI6d4Q{im5!4v&$RPL_?q1Ia`uf39-7u=?yMEGRi~6zF zK~t&HJMC`*!1I3BknU4bMbTH`ym``Ug)RT%J<^Nw8*>5muAH~lF(iK7q>I0G)a8#G zhQ)e3=6Y4c+X)ILu{r;;a4@9#bNVX3r~Bvp*M2G^0r*FocYl5_@*{O6StE;CA{twZ z;_r_fsz~3y;A(qz!}*ecVrC78BtUu1nXj9P^~25-)fw%^37i0L>I$&X;^x9vU-29kh_uhEnt6Wb3LRS#I=d3+Cd!0|MqA4Y1#7?*m1NtGaotjNb2D3rP#Kk z<}`z7Q&VZaIBu8?Bdln5+g2w(Wg;0@Qa=5$ zB@|)eL1D4HJcENd28GpQ-ouznc341n68&y?l>j}v)dSyLqdC5%z6JkZpxSuJqv28%(iiS!LOp; z5Dr2emfALm6LkI%M1(+NWM@F28mGZ+P-7eiD&Kszo{`=6wIrH}To>#W=k;>sV|5vw zThI*5HlZ~>X#=S&@m32fYx88%&6q>6a`56TUK$tqt9n~M@Wh^x>ND;wV8 zW95;1+gx#n)%>R!&G~8^-a(005dUk<>_ZUB4B$HQ*}UVpw(4hZC>g<}P|~@=il`(+ zW#xRBJ13vRJyQp!68**qf_V?Gl_r>1mJ8p}u7sSFXb^c^-u5!Tz|>drXkWI&)a?EK zYvAo&VM8q9K{04t6Zn#Vn*e8fZ@Vuj{n-^lVj5Tnpdm#DI$PD>qC+ofoM_t`U)}V@ zL}Lghb2C%X5m!{rHpTjo2ovlIu0I%DEUR4!Iz)ISh6jZRQume^CUj|UxSjhZU`Je+ zTk!a-VExHzL0efKrTKVvO%mKio=9RYwGdGUhOYD2Dlf1JgfmD0|XvWx%$J2)_ zO>F?3HG^KR9?pXiA8^f<5IJ$;M>h>8s`pix&{OP-N7K7Y@f6aa8U8+>`B776g@DW# z00L9fFR3TB`c2Kj6Nw5D)hd9GAO$_o49lX3`dD$;c2)oKfo4wkVWx42p(UF)gSiA+BYz4iD?!P0rizL!rm^C zbq=1=VSqh(kf(BfB)RFx$sxntsk9J6cU3{5D;6ZVXVLIe*Pm8v7x|S-gFbj{WsI4e zAKbz<1`mc?*#9-#%i*oj4_g7vEo;ZMN?Tx^m3{Pmv{c8Mgh@ype zuQBsh6D}gmU-lfoi;jS{#Aoyk?6G#cFY|c>U!T=EBlMIb6m%dqiGFL_my(`hl)mB8 zdbyps?>^HpW6y>V=%E74PBL1WSE>}f5O|-j#NZqp5qk$pt4}^l4G%+u$55_-Z*xcv zIithMuAgaDV#{jw*9Z){4ZQ;8b@ziZ>$(RrBCfbU^5LiWl;ve6ieUB6iCo;5e9^ol zq9Tr`(7vNoOuN5Kq~b|(?3NZAvW$57J`{+MhhecQ7!Wtm=c#_BoFnCxJ83GDl0vv; zFU2`AX|`K>q~xLHZJeTw>>|v)6ci}bT2Z9$5{{Dm(N-1vm1c}e3(?IppZCVHPjJh` z-USA-1DnU>?@lS^OWpY0;C-4x;J2&p`002C^)yqS8_X6OjuhCW+fgi#YMlllr@H>M zyVAL=#UZGogy(O)j)tU)OY<-Zf2RjM7%@PP%cVw&7Os9uL^FJnYEg<5SbuOeyOmNA zGdJQhr@t4_o9J|r&o-*M!Z_Ix6OJ|x43j;S-K-``tm{jOCqm|~P~v+M0f;S_uI(%v z0HWBLUpY{E4vU|1)dgUecW^X)GI6&-2-HrxQxXa*G(IyziTrqdi}W`f6X@pDr?FRA zhl;iaj-?%q6fHf%^tb}P{&~(v54$#s@qYi5s?VB*W-#2i*n0CQuMi50f<}<58b>v* zJ8El2PUp?H%?Zxbs8+N*f<@2cPN>vUR8wL3&zcR)x4L^b^*i=_ zWVp-&S46jLb^x2w$W`6>HEh5^e|m8jpo5F@v^Apx614cE-5+Xj zpQ!Y#?mklGnXw-ZC|Gpj^d0lLTfW~vdl>{y1VvSIGq4%SHRl&@31uiF44sp4*L3aB zql_RNz|L8>B>C%W9;3X(HHly054;X(<8#(G#f&dQ%*UYvlopwFTH7rqh$YPaFX7^aHYs75;~o+5e-QLP5576pnZK66A@4%NKzS90z{c)oI&Q~vfw^S{MuaL zNlw)l_p>#yJ;N&KIPcWf%Qazk!7l1epRLz)@$&N-4-_#>BlV>`0C&+EbSvU!?wz<& z!dox7kcU1I?_`T_H_hG4zw%2z{_X!R^iIC(A4j0ae~0)!)%mn&Q#oym@K+*-asLbI zdKbVu07rSy@OeHSD9Dp`wT#FXoUp!BIpUNx+r-~p)w2O|hvYXno8d}su%>3=mC5lg zSt@&A*Zw3Q?k*QFGPZQ(dn#)L?EE~ty2a0t2XGub0ZA2;CT`si2-D*UP-DG8*YIXM zqcO}8aBYjztA|J`C{E>wr@_3~JuXMdBcClGH#a$Eplp^a`G@&qwd0Mo#6`V*-(N&e z+-tIH)$!UNix`laKnBvcGrV++U+s`@j6L4jQ#*&_;0GD!X}sTbxr)97~~GKtu@C|Gvq{XBXG%&nuR zPRRCAGmO6u{LzcX>k+!&fmS&eXhjX-Mb+S`V~e{&N~2LMD1}K@sEPrhr-?GU%wRtq zxl(hbDKKe?n*Dd?f9#h%*Iet6(89yL)2R6$y?w~LUZy>bUOuS#)Fx;Mr-3mMY;Uy? z3&m=9Ho(_hf8DvRpY8G+jr2~HtlhCcVNV2l&Fm+AX}N5}!sS-Cr=>{LHUJjOrGtY3 zm!bPuJOLz1AR?p!f*STNDCFT`Uo!CJ;_Jt86AQWiP(oipTf+w{i-D_Ek{oTch8H=X zYG%urN-ZE1LZKZMxdH?AO6M#B=Yiro%hLgLQkBfQb=yX#+bPSpkWe!8x&|EW!5vRe z*z)~y!AJZF_~i#-Dc3meyx#h{16S0sAX9G^#Pp06#zoXfk;%qff+?wN0uuuI5<6?G zpOou(a1)8!cAg64VdxEVX}G7x@ryUF^zXRZKw;!`QU)-a*issCwI`{ueD<^9qJVLP zbWqO=XHokl!vY$YhI+!XM7k3KOagtG=H}akM3w{hSfa!M~xcv6@*Wu z<12q{MT$uGGDlE03f?Vfa3C2ySA*~RgBBsNCs%o$==@=t48#{0$|;{$R$V(Hq6 z@H_(@GdU{Zsvru9Z<#IwJDW5x&pjzbcTxmPUx=HfcJ(vwqVs?&T?KU4^r61w{;B1- zl-_ufE))D`lNksMb0GG`c%*nMj5oYiCjtY$`rEwl7c@PJ{9(o?w15E`Bkk z`^3r9dtM?lu1G?FV1M7ScP=K27UnjQaM~cgCr^+sF#He?%y#g=$sDZn_!8IS9UT95 zrnW0li~lY7tqS6U5~ecJGY%aqeG*63PDs_uj%R(r6cTTEY?>ycWzc@9W2{QA8tkdl z1fai{o6WWHL*@aMSH5VcF&>7T<6~hrTECJ<(LRRh*tpL*p+v|n8!O5Qm@zEuxNe0n z3rg%VGy3~z?>7aPfoOcZ7=@YUQP`ROLmhyWM_CL=9E1wS_K}h zxIkEq*TbN)(bGBJGIZJSmW#WtR}?_{PSg(hT9G7+cQ=&B!m1_=gikbaOYdf?N@Td) z@3(|2i%1l0fkmX^1@jcL_PG&4Yfi$90^4PGz~K;idY8d;Oa@ybtKTeMN#zYDH*08) z_>5IZ&Mkr1*w>r4otr98T}y?;for2c~l zDQh?rW9ye*^JOoqNs)kIsDF&b@ffNq_JXWA)~5h**@YIax(HLSrDrdYFu*Wz2jO^t z400EnuSA)p0nvB5i2N*Qn0wh=x zs4NqGJh*|((0+l(kxIIfP|Oq$pKEB0M}lyn%KvXyf1i`CNzSM9gyhOC zK75gYe7j8bKze0NtyqsE_)2@8*ZBB*9WOMy5b+)5Y?bj?1ON?v871yo_rAHzV4yzQ zlB>Y%*`Q+X)wk?;_(lj0Zn}F6(}S@nh6v&x9sZ%YHeJlI!e-=viU{;AQw6u)R*!{6 z1ZQV;@qm8hatb#F=3TNexxzChuYwMBu9`AA$kS|wPhG31c?Uq|L%wIVfuj6Rktdpx zD5RHdp`zsWTsd)3%eaXYM0qt;hU2A+k=w5CZ_i1nq&oV@NZ~I=Sg9*6yE^Bdv8TJjJ8+@fid~bM zJ2=0ztD*flze;U85lr_E#>TYDkU#_)1M*zxA)y);y1cpa?l1G)B{vMSZZo)1+dMBc zXnPh;smB)zz1DVMpVdu!O2=%ZdonDvCU&}6^_>_XW-?w3gpQwPrD5r1eE!}V)&DH% zhe?J1_?TaFSgnz$k%{ZuyArgY>ka;Gs@6FdJ4{`efRo94N0i7)I9@=&L~gHr3a>1~ zpLo=-rW(%#Z%3$E5Qo`wYHqE>Mos`3;QRfkFyu9V_{AjSiCD*f+9sp2D!h{>qNcdoVJYI_ zZFksbyDbn9P98~Xe@u*#&4Z@n959jBf#%^sl&U+w_U#{+nlyx&BAiL&fl0~uYVAarG*11J(zZnkZ47yx<!Pt16ESnaSbyPJ2P6wNPEV;9;^|)7Nsdrg9n=v2Z@Fqk3^w$^BqbW0aH10k z7f*df8WYwff~sD-tPo%kBQD-~=>v+d20v#Qmt!bY^7cstJopSOJYm@uA4bVOlYm9X z7E);3E2{|+y0EYm66#V%RExuc!Om+Q9*~9xapLGPiEQG%YccX931ot^obZ9y0000u zL7$dI6)pb&F*gEl*DrgD&wD}c=1tTK9yr|nUPLzX1fpX;YKp>GQE|G+9aH5F(l z{(k|L0000Q0iU%;{}uV!#iiYCXHr2t0A5?e0;m803P=C|02l$Ew?+RHX9iB~7ytlB zb-V#}vWro`0Yd-)6A?k1yfjQt|KvbWE#NF==~P7Txw6!9ULl84+W7iBW^AMVo*~s{ zyo8B7OinB@7yXm&qZ^e+SbYi6crzV{L(O{pB&RfR@E|oRwinO`C28b_fRZH!%H&5s ziK%2B9;erbOD=H=YJ+m3>xJjQ_d)4O*OQ92_Vq(s5VU?G3O{+&FH|j_2X(=J68Lsp z*`G-V#dLi3-x1zv(@YZ``$+X-8xo3aAe*%|)0m%bFnZ{o+u6A|0gWyn%-hY7e0=({ zIZPa)R9>kBQ-|)=P$J)=hK`qHas3&&^a@kY`8adW=%>>fi!U69*)2^Fb!Gkm9)I+O8Gw0#?zw^Afe`~W8sX9k~Gg^)~m z2ECUFskNdzK-Qep47=*D_>9)RXIF*n&l2*~A>%bmIWs#yHqwO+Ui++Ubtez?u`(Ws zGng7ql^-P1G&R#A-7vFjxQ=$#J9IyF!}CNN7?&J(6=z13pJoG0b!N3&E&d}oPUgxv zz=%O{PO_=O0THN3UtFw($pjGl>l)4tHhj@D)`8Lr4-XN5{g3jB%JkxXiYYBb}*DiYT}CbOJAmAgY~G*cfpmV=mX zBW3H4Il>!-EZH69HF_Sdkl)p&SG>K5u>M!G0b-DaUBt{yO_+weYu)1dKW+nqv%Hcoq+P9hJY!#10^hCJeMd&~dL6<{LB+Sf$uZ6i)&yex zny+?BQnOffLNa@-S7lcbj3T9YaIxkr!42u@vW#UK=h~uF!{$@RBwQnNbR>|*$#0C) zTcOv9&m#HkgkQA|2fjJ?!CtdnT~->wy%CS@!{>S;~8e zQUVg_QSjtPnSQMyvW3X{;|zuB_uxDdXKmctOBBgxnS z8YdBlPa}vlkqn=y1S{$3EFaCy1PP838blQSq;N;@qdn}#hLZ#?)-8CukL)GP7?*y- zQd^`|!Kl6Gl{LgC(myrzCxkBQK;9S%AMTbAJoyHVP%m(8kDGZOnm_n+67jT3Y3I;h zI}EPqa42NoLN7t`&l09Rma*f9Pf%MlYG}&)DC>#j{tLFrpd7}=$C=|ESZgbR$M%Q} zJnF>8mzPt2#I~WJ#5JuyR_BgmfDGV$bEDB&H_DhJMo4j5gG$mH|^? zO))5Oql%$K4@lOf^y(^T$YI%*D;?oEu!OAw|BmmQ;23D_`+Vx%xu5S0=d-{D6fb=f zG!Mc-a=rbDNqb}PU}-HS>7%#$T*!jD${F&cxWztNkQtWgy;6ncI1~~~>yfl*yFIUU zMHo-Py0?#HA9sI_8}HD~i~Wl%Iu%}+?+W!B9b;}@e~!v7{55zq(o%R&ki&F)nkyJv zB}5>jM4J!HR8FQW@)jx3P4FR|=7hq(kj0PnB$ab{Yt6W^uV~7@cz?G!CzcWe(P_kr z+t^-481q)H(C%V~nzQmdCz_#fv_bY543S;Oa5k2%aCtR~WY?4>LnO>TE(X1TejgCh zYxl%%JC!kvgZ&w(qXwHkQ)FCqYC#1_HqnUyj?N}MA(oLjW_epZ#cjcyd4jZUkVV>8Hb0YWUot2q3q*+lC18!spU{bQ) zH@fNA`dh+C-LBD}u*M}<;spQKon4phfR$shMo_@5s)h*-DF`-W$Iklggi^uVkHv}6 z`6t$Crxa+#}o;)0>MmRc+ z%gLNX9Hdci`X^!bog|Ws&N>!q>!Jbbv4_%s0IzvDm>f>iImN&AdP7c71|$N&vc2kS z7Yguzh1c03IkP&XlvOitTQBwt<#VTdL2o{$AM^D(EQ~~rVf1O7(}{$JV_;z`2Ri)P z|C2;H$Vy)AERGCjKd#>76iS(z(Kbp`*o_+d1Ad31~h! z3W|B6MhtSNDOg00Mmt9x%r1c^=f#)ga`+XQd`6Jh_v=*)Ugw8*eQ!gY(&7P4_k4jx00aLjmVam`Ur;R7 z6Kxe$E+$#m6;RU25|};}V}PJPzlSOgO^RQ<;e;r=I`B1%7sA2)`v2ToqVI5pdi;q;J2c(K)_=VI4&O^S4C~)F^HnK+3Hf7x z4Ku<}?M|AGbnZa4}Cn0S4tajeGC;P+{L1N^A^9N zT;HQkkGIQQuVRI*?Op~k80u~)wD-Q><2{YMQ#g`kM0fi#P>QU$opO&pW9SFnA`D=v zEjnmY<6n%6StWSHUlBO7d)?Hq!;(MDe9Q-D4qGHmD+ZdPgJu>!@W$=$SpY}%_Re@V zBO%ClVC+)xZt^QH4-Rd&Y8}6f3-AtbW^GU7kM)b*tjEZLAsUXSLm#FL3^1y8L`Br!&xjZ_m$!JOXV+iLpVmb6mhYKD za^3VV0v*X9Ubi1GMe6ZRNW?<5Su=~axVTenx7yG|Mi{x<9Iv2coD8Aei;I`qzIfD~ zWGz9xtcQ}<46B6?2Xykbx|~X~uC*U;rl3T&YkW|4_`yf?Ve(Rd-{;8;4g7w3tt_QD3vnN8E1OUpl zpSM}sZPo$DA*SEl8a~F~79Rj(ma%H9M}8rmHL!F=GAWCVI~vcRs$axxQ_%Q=ZnxgP zRVP!vSiDqq?4Lfc@*guF8!CjE8o*O75uJjD%Kx4-tRI~A3mI)tV2Sm@2ma~O;$7EJ zbA3OR(To)mk{nQDX#Xm1!`1@snqE(pGC37Yhm*2l!AYllfR7EZavX>o>bV>KPG;-* zH4we(iz@|DzM;R{C6B}`!fh_naN?4r`?9%=Z@kqtR3TO}?eKLVXhzXyN5zjC(B_jW z?lCu6!j(%{E#yk700&>co@KFy90_%iJ@7aeW;aK(Ln2#LcH(B{XHiUbacg#^`3(zd zP}&m@K;sbZuT~R9n`V72xF~xW_vER)sF4w84@T~ocR9`@Dqc@Fd-F4hNx__N2FSud zbBGgD^i|4{$Mqq^+pJ|(MKefSPg%{Ytw7iA({?|vjYZ9uEUo7|C*W-m)ZQ}rmUH4_ zvT=BSp-r!WO{_~aHU9*(o7q@k6#ISw0$PinlYScfi5g;VIl_RmK4#{ydH1PGV4pqe zo+CAdq6sew&xkI&pJU{5RWnk|Xew5(LOV<`jOX=~2Qw|GR>2X;4RzBsrHyn~cU8jh zWZACy>DrfG<##lSKk<&l_o=j|C|$+}R1-XBMB4*0-fBI7O%~`j6C_4n!0RNr)QWwa zqg&New+@GmJOO3s9hD$tBNzgJ59gmwi8_A7jh41UoJ`}a`}oeCA|>!hBnkd=huSQz=82bMNxXTxzF)g!s|!rp_sdrqBGX2F2<^~m zS;!`TZsUE)_oq8_7k>eE&0`G`b$^yfPAurzc#9lwPjy6&!Rhi3CGOuLX72_fgE*L( z$f<8d*!O;4!Ua)>Zu?}H5UD43R#tny9q&c!U}`NBO&JL{w7%2{371{^S)z=zpgRpdx~WP*^Y zjfk%n2qQZ=$neU`;D9^f80{4sX^O)>dG7F( z6E0V<2pPYKvf7{QaEn9zeAW#kp?ri9>A$o?Wdk>glFt`j^>i})-^{Rl%?!g7SYu5R zI@CfP`KVn~t)}f9wuxyNH(gp>ZLjkbd2a~_&y4LR{ z^%(TC-$F6Ng_^zK?0b5FiXkp%>u#}`HrR~D?r1=b2{K?42*f7}HW)6u+?*p6-&x|( zkQw>uf_1i(232uUYAbSBmvSH2$;jweGk5*9`2p8M-e-z$NY^g+ki?wHZe{0Kxqnia znkF&f`{{Nq<1hL}$t*@ej&X|7v2j-6_&Bho5b)fRb@=Fxm9ZU0u!8pDE(lP3WCJOm zqzNXMS1Wa8(WnQ4$Py%QgdsC$$;ryCv)g%7l!Wm&e^n4>*-e#~N?w-af|2WLYI1L4=S-(o z0Eld4&(D$)f1$@vPJ>gJWNf_ybS6vJHhjmnjfs)!ntb_TB^3Kr%>uP3iGSL@l6H?vKZ!buV6V&0BJ5G%wMtrE9G zG$qtD6-xlNooXz2>pBM-o;3Y$VsKi0&THpvRS{(x zuxFu;mING<^}|0%9`>vLq;@lBa!d}6uE-$t|Jqr5OWz$q*a+qe zfes?UCsS^bU9j09oloLp{(TVXpEXJZ+>VOYmfc2VVY) zDlxDrjhwkAJ&savmqpMQ%TI$DGk^B-X9|igK*<*JJdEIeR3omfZtd4LeB%|g403Z;cq~ zv3sa9du|& z#Lowy)i^xjXrtsE_#|MmSiNTHyUy4>roBEFW#528h&UmbU$2LyWIV1!k3kNq4`=G@qGbsFBN@=`Q~sOqmF2@okge(WB+tMjx8XIT>e zwij1>IFioMi;|_PNB|Mse%rn7bqdiC&M=LdWaR^rVV!s*LYwRMSzs2Q`-YWnnJC?p z+g^A93kqQ@w=47e;nS42)VjX=8Cyd#ks(cfT?uiyMAcMq!4r6>diBvDLws!8)?Tmo za!aFA&D)z2gY$Aaff{oYv+?p6f^dc;>$F6{hoqmb@_}nqOpFB1om;n1ime7HElhSU z=n&Y00&EM8Zg?k1W6(wfW+`%yLd9kFG|ZL`Q~TUXYW6xyse#Bx0ubfk{=i%;yyq7- zi@7>S=u);S@<5F!u`XlMhqjc!ERg^XhYE`MWt<~ZvUj2ift*SuY11IbU+}pW4;<^c zJ8idkrM>RSYREVOLhYU*jUbssy&Bh7hUV7f%h6^=O>6U@W|VCKcqVHm3|>KbiP$|> z_%t2;Irk>`8jYJBwJ36tvRK_^unZ4};g;Jjww1>Q%$bsgesrXSgY&m@+zH?H@aW{W z>3tqrwV44^%kct^{S2;{o;BCVWx%)ttg=H~5z@r>a+4r5HSoO&M|%#ZBU1!P2L?%h zG&dd(;!J&4gh=0dqU#!=J=I-uQ!f=v1>#|MEv))1YrK`sp+KgvxTMQxr@%J&#x_#O zNnJ&UhM@6pqD!AIZb= zb;HbRxvLB`N2ou{%SFE96mjr;r)06omV5TLh4NKysltJTGy|`i{_2m#?!i{OUPy@F zx0@9gk<#b~cIAS+squOgfq{k-k&bFz9Yq)F3|hrvnJ8|LZcAKio-lia6Cw}hM8(+^ z2*uX@W1Mb>MFE(X`YOq{NZX{_V%!B{Z9$2#uFUs>`nUTHtuGM|YlFGCMs~tDUx(D` zWl#)TU>K@|(5%ZZoc_7=f#>hn)Rbh`BPQrdyV$lR<10QD@JKcUhp>7iZzeIP+#C*6 zt6`0{5kju09mz4+Pi0Bw{586^be}1qf7R4I3wJVbP&9wNXko{(lkI?hxk=(gz>#9T zHP&pUCrwW;M0~Yz>cOJ6B;pCBOXL`cn27gTv)?Z;(Ql*qiRGWf`<_RtKIBGJY&Fgu zS=G0qXr|!SG6H8;M^A5d`I)4F7$ntQzDlc}vXAX8|3-ZD&Yh^|$<&yh0!cq>?^q8q z(KBG3CIZjZ0WV9@bu|IvS2lWCCn#|c=Hh-@woc5ii9*2f*FBAsUudZuPj-Z$CqXM! zV|+L%3nu)F7{D3qJya3rgAhQ7zW4|e{!zkH?+tpzGZq>}DR~NBh>K zZpn1@Yu`SM-PmC($O11Xn-3wNY_sq;Qhwgj%V%5J52lXflF#`b${x&Y^zh&WL}`3BcTeu7fBF-cJW*P%nwPfGt zore+de#qR^SI1aQQA5=s-sB$w#kZ|U@3#`aVj$|X(H~7qhQxZGJMeQqVNBZp zik?pqJ}eaEz_K}QoJPj^2t5Z~UWPo6wX9{Jnb{I-cLR(l@>u$!y3 zGo*2Fzy87U+|#Ak?Pnilh?Ulo;P2QDuL^u_QAu%M$3nXwsPpodHypHks_ni{?BL7M zx9*0jHG1kR7})}ffLI*6;m7TdM1Qz+q%ex7EafjPeB0RP--muguxo)G-VD2AZAmZd zrlnf0S!+Mj+G^^eLK`2YvF~zJ1;&o_U=nSkXcel;){1%k3g#M;*yypa9NQB^1l+kZ zM<~Br58ml3b(TVLjf8?K-EVdG4Tk-`NAQnD>Jvi}ZJUZGHG9EBLRlF6fHA9u@k(FI zvfKKa4i8h(r}Oec>61g$nD}s9%8@Ya^UhS!lZBp4qK*EAdT!yuk8Lomn?lyUbb1y;!&KPrPy;ZV_&p0un7YiIZ&t-U^)Nr#a!XrgT+ zdJN%?NqD9k;;5O{EqLEvMSAG5F3kPL5&}*@%8V;na2YyEt9wwMh0dhl5G0z>nRCIj zU9u4Rw_C$YRBph{wduiHI7YR;SR%)52uijDB5y%He|3tBBrQQ$H0sHins4B5uvb%E zF19ta-H!Q928dE5=a*7*gj)(XKNTGUWXsMUZkf1}SN3dKMg(=tki(RS!l>Q%k28^= zWU&T*bexE-%&>N3Mrx<{CG8WFd8MvrO!S2GcL(gWi1%3?lLqsHOCp2q05^%A8H6KN zncbkhuJKx>Zw?~9y4rMuTF02gRToa((uAD;%wxIbSNvZ!*X`A?$xK{>xkZF{k2wMo z4OdQHp-v`D9-Td?C%G%y9TK!}#?hvX3uQN54_W#*obYM7Qly7o69S#PDQKc3`(;m+ zxEqnWsksY%WaA7x)T68n_{AqTo+!gW%6?UJDNl8x3n2nyzy-)Z@SbSS8R-`^fAyhL z8bEA5<5k9rwJ^xt)TF#QCheV;DB&=$<$o0xdSEXR()f5BxT|V=Y|N$E^v~KlGHL z9_6kYQ6X_^?%T{~K-V(R*oW1DwCnn-scXBbe&0_&oI9f(23DgF#y4!GL@ZDnrYm$v zUep3$9_EL--I%h8fx}I%nUz!|E6UJ`CC~<2Uk9J3Z3dI~mJ1X-O0@P;#ni>pu~5L8 z`Fa|PsUd{@R!eA4#aT?r>dr2g*0%fXG$e``fsNqW<)&{n==03rI#uHsWL|Y$0H>8T>(krnm5K2i&I`_YdIj6`;?_Ih*C5?#5C~vwnyhwBMwA>p zlu|-)N10#m`(@ZV(oR51Ha%=y!ztN|+EYJeH`-EwxjGMAd2U5Q$?$fTqK+yM0BXY= z-*xvW6UEQ>MvC)@SjfUAx|p+jYU3)@Q}cI~koQ+T8-|g^Q;J*P&v$%2{w(}IiwOvx z+GiXhkivOFzWFxP>M->0b0mf`glM3%n$`_JeHe+wK?M2)C>clY@F?1_LL;*=|H^E~ zq5sK23Y5hy`~jdIWSXaeB+VIp!*1U00OEg>#LWLZT! zh>)vVi`Dp^I75+hDR*2x2FH%JJ0Ex>L$L7F8x->B;{;#8JkiUdzw0fpE6h6}BBbAz z!#fpG@!UX~F7Q7V5DBvO-z;VHUKKxq2VgWWble=jnU=40fa(Vxx>n;ZU3&^lCH2dD zl--Y43&WueXIJ~do$L`O+{-G;#Xzz0gFbH2iO(UUSd6y90cd_-re88eV2~rA@?r;# zx@!x8L_it}!n6xmk%zL(n($#JCCMAu%W5$Q4 z4eb4J^IMm>O(9w57kt8}tO7_VLDr{^FM>^H+(spJrj6RQy3qAV3qI!EPampIWlP(` z4~m+xs(VVA-%c>OeubIQc~ttrv~wREygL#d3~ewiKQ;p#_?7|p<7v-F7(apYLy^~g zhAiy92wATGhKk#)5TiNJ?Ckn?7flr-G`uK-=<)5kQ5dqFmR=f>#nZI zL$6_o^Kj^3Ah5~cBctusN7Pz`hZI<&2w;uKca2|Bgc2pZk&PirSDIz`i3KZm1=8`7 zsUZN>EbWQF#9=Rku`nZ*?P#$3<&1rfvoLjsQbCZXChObRUkWf;!-O_=R;<;rj^fnA zGJ_?!8tS$)u^{*eD1`- zL*VTs%G~59dDiOh#iWc2u)SIFo$6Ey^Yx>uAe}PnrH=y|2ThgU>Q1)sE`{RG0RR0d zdxtr=2W$c}gyiL35lbI0r8;g1jlzhHN4+I0j>UQVi%3u6o4{Yozm@r8#W{r|5+Dqg zZ)y7^E^{@G*e9;17%sjKpwbWvA_fMT@>5ugY_TI+*H7bQRtVN5V(bRe;3I<+MNb8bf6i|-pe+5*`TZxeB?tgSC51z& zu!bu4vj77q%kX~+0F4IFMafw;rJH`AMNa%_W`9q4KVY8G0Hjh= z-I}Ht&>wL>^K=&e|Kfi3hMVwjwD{jB(I-mEpH}g={GgbafkzTkNDr~?kLJQO)fHr$ z|EL1R{<9+L-QgXZ(72?(G#Jrf6o6?m*r1m=zpaO{bOMHUnPIB zp#Bw`?0?4UFZRE?@)?rsUp#-aXVd)~{hR$y)Up4U{SV70`=>|q|H*Fu-#o~l&ddKs z|Fntzm$UN!%bxQ$`{&-W|C7Dpzj;2{oBkWc{A;J!A9j#OOuw@Ks0Wn$Z~i|9vwvy+ zAKg6to9T}hKKWn%jS_yMpVI$h+WHUmf5z`~T>m^l{}1*o?*Hcb9BtnJMnA{(pXc8H zX8&9B|C)pU`>N6ZH_zX)XBqxC`pN#EDfZ|5zmI>entvw2|HA*)OjhB)dH(3&Q}*J2 zqkr1`WdCOZ{D=CFX8w`=Pp;g5X(s1yo}+*B5dMw+_Z5$T_SY5vClcPLhzLmv?&|3; zbTrKT-H(y&4#TXO55TvB9*vUpKRJA~3Au(?X_W#OyBi+s^P6L*=H)JEVuY5tz8s-#`o_PWTpt%;*?$JUYh>;2 zhz94B-c})Q1$JGD@w{lI?2SY^DHnpyCM7lt(UGQ z`bE{#)3SYXV`oX17|0BTXE3r9_qEtN4pRqQQ?dJ(Cx}?1NyGL=`kbBi80J#Q4wh}x zaQR!f`pZteSI*2fHpcpFSa6*{Erk_q2#lh)VL7O$XNUK59qZk3QjO6_E3;$<-aaWk zJr$^AAqK9U3K$qDfTl>Bdy@vPOonaH?tKNq@gd^9octI0DntiC34d+!Y+Q`5EsGjb z9VLc#s=%!5ZO;@vxQrJR!fxp0Z9(r-?U%PN;NYb1F+n&zxvbVu^370z6ABO+G~B@B zhc@%r@122O*Y%7mf~c=DfG#HCm#{YqDO#onrn;N+nBSy|9Xto$xJdg=dP(cAbr8ZK z4JKb>MQy0I?K~K~fieSF9Ji8X-Kq)K1tXvj-cRfO#DN#!7EYTXxnWv}sR-nr(mRU^zX6 zUBfNvz595BXC#PIJkQKai*i(#x*xF^%iePBxEw@=bol;e$Nr}MUAiP8@C#~MAaQ*# z@EEm1oDWu0Myf;{7mG;=I4Ja)c4$gzKI(pckxT~b$qHzqSwjp_Kps0hFV2zSe3Z>^ z$0Gh83|c&xE^j%P;CK0vwo2UYiQvJETMb+s#}BJh7xh2khB4m>Mc~N6QZirw5u~3 zGR^*ST@fkV#=0mvTd#vB6myU37?4QR-Fh6iJLNjHuhcjW`su*?STV?$F=^(oV3wPf z-;I#z7N=k;_sjkW{3dUZ=}s2dT}E_SR|tW9q+to%4=h}QYH(}P7xD22a&i&a<}GQ| z`!-9=4`QN&WjK0*IU@ZGHpHt^ZZQrdbDLUJWAbZ*WRCAi$}<~SWU(M9SRyj(QNzBQY1+)XE5?$IBV`j%o@GnCH95h*qte6sHN$Fy)r~zZWG%yMgAzp- zSH$*ovg9*~Rk6ObE%K$dqsyv)JIRPggVE-MP%&H=-^1g$xd)axWM6tU9^c3j<(;`w z?0`ghRP1Tf_MwP#@R`S3CG;&Y?Y*zjqn}gzd3Yx{(xzEE-eTo#HyE){ck0hVCZFU; zjlXPb(=}h9ne1!&_KQAD$Hg$7HxlAQ|6#=o#XmW-Oh``QLS})6)erHf=N+7EAda0I zc~6STZisN)O|g8>aQ1*YV>+V95c&*X4Bdcv`$xIU=1&bhrW9JXe3*^1byzBEo$~ zgB&HpPI3QKd1Sno45Ihyqa|_yhG>!Z#o!^&Stjtv0<@!*bgkOZ^9pYlK1V9W(&2~QR03kGd$*{EO zpX%DowqhOCb|8`<=19-zoD~uaS@VhK)x65k3&%TB8Md*re`oubDHH`%$T#2hEjt;ba0j%Q z&FiGqDCOwIW;-rfJY)Hw?_nsu*g%LyK~xd1gMnD4lKs(=dT3qKTdlA10fb&T?=Ud- zm&BFA(CXNbtyVWz2vD|n7M>f3;f5-K0h4SPzx8rlXxIxwJ4!UIKYHN%(nz*D->LgS z^DP}L!#Ixy5$=Iwc{P)uhbmZCIYE^OC2tHaH`i`4(nI^2uJU%#zij76SaSFne58*G zkkMyu5>nSHG*f0193^Av!raw!$!#z{#+THAlISF2uL52_q73$=*+;HB;O(I%ogSYO z+1Y~p(mAv^5eyeKz^u0xgU7h2IDhyb^0jrV*Fl~w562gMp{^PmcV8Ue6-z^fGY?*Mdgxmw^3ivrKk*Y?-fUu@J0-wcR=LjWCsV&WiFzc>#J7y9g(i4i(z6l%z5pHJM z7*h<3A=dv)gr+5czx1)xEOQpQ?(7HVh~2#+>i!`mFYYual|Aq5BvK;L1Eoa_8Het^ zzhH%?Aeqlu3w?5dH%~safTLOdsPCb zjb+sJv1Pkl4tT`PW4~~6S9z6f zK5y5Z$anbrlon-}TXmgz{e!{WNAzE8q=OfX=Wo+_4aACQmWSlj7hY|5Vyi8$iFlYr zh-(YWTxAeU^Bnjdd}Zr{InU*i zpdAwBHWio5KIr|TfRip~xY5qVmA5xkeCJxuv3Hu2!rG(Q$3ks(BnXeHk+{SvPRmi# z7ndyNS59O}Cv~mev91Nmgo$nOO03a5g?MM)1Ik-lw^`5etFq$lIUh(ERn5Kxtbncx z!a5Iis3L*)vJJP~|B#H`X$}4Hd}`Y<-}^f(B}w@p59fygRo(MbQjKv`tafspO%cS> znT4T-+fL}Q;#~m3nJKfkKU^8_6EV-%xosLWj$Y(Ywu0bTxvSYTd$q$69_$A!VQ66& z-Ok(6G-uoIk~&b-etMA&TZUgFkfEwHx*5551JrFDu3ZFd`3hR4qPB3u;+uTG`)zJe zf~`X^dHJ5G`8+SI)6zW~yO3Ru3_WeOv!CA)cMW96>Ye%)TLi7QJF@VlVu4wNATiyLwZwi@0w*NSH^fQ)?z#gBB@jb#0Z!DT$HLcI7E z@h!~|4%)ltcU!Nc4R@G$?T#}S>qC^A5qaD3hk<%Mpn6h48n>t|=Y>-z8=3?b>cywpH4`9b!ucb?fHpH zj~}9hDZh&uoGBCK-APVDBd>&8RBn%+`GU{|5rRe@upgiAikc$~xHOcipBj$JVu4hP zB$Xi|H+8>ZX+5WfT)oKI`OWkq@NbJF8usQ``RJ9EL`>1a+PRk`BWX-+Lo_^!<*P#c z%K&ze-{FG>u1m8{izN`fR--|Sb=079c3i=R7)gB+QQ0Nu3#A*}!pcMf$9oRz8>}LW z7Fr`w1~RRkJJTDgSVY`k4>)r*Uu4(5kz>;C(>LB&kZ8Z%T6h7KYH^dYd7XBd?O=87 zRI0aN*sd1p63t370?MN=560a&OA?#U)33OQ*bsXsd`XUhxiR*#JYQ=Rr`}uvJ>3f3|wN`5J)xJM)huP8l~9L+dx5&n5FW4fre@={QZsC z-m}@Zl*HF(gdLnTD}KtTpbj?yo_}-`tR^o)cakveX&XwpGUD9?#eUlaT<|?Oe@6)N zc4m7XFy$qDX^~RNjh-;YZ3-Lw{vjASP#Lv}?Jb2Yr&?>4i{5n}Iq69NgBizXP}SJ= zN^k570F;C6b1nFHzbZV)4T->1JGRZ8F1XSGjj#@GM0E|Gi&qyLXb z9)RflJ;@gU!0MsA6jmd^{X;k+W<>XAZSU|`9Qw}ybDxYLAjD%(@Tw*32LeXPXtt4j_aDc>06p!gM``#3$C-$bth698pMuH?y zG^BVkUd(_HO#y91dv^l=!C#8CA0xqi6i_n|f4Tq-_1P-UKk@Va0N7rUzF^8LYQmb` zpMQbNKZ~(GgXVq4#``QJTT>uT>bmQJ{PyP`iT-EdXGFcvz=>OJ>20;V|0c%)l9lmQLmNHX2O-kb5j!6iorc0xmVb#`*9tt z;!st~0;nby2BW*h+6I0%iNZPufnCK{_ZVQi)>krPKb5OrgygY7_FkHj{^L1`|CdkZ z=SHy4PNI+RZi33{Yo2z~oqYk@r~yR#{jH6L|JlLyk2c^B|1S7nPM3eH>8}C<{`8jr zu>k_9{S>5(pNr(*cOK;wUqveW?K{E{At#L)`!Ow3yy_u>^Z{BdaJ{$-CJ-a7q~s8c z5UXcH?k+vEZWClJC-D|9SOn^_jhyI^ogNQ$g{1uAyZ0`3ccZI+r`mnxH=W)MjY<9{b`V zRYb%J{%V(*Ry`IL<787g<`%c(7hc{_JHYV!hgCyjz`PplYx0l-Q;rt{nNZ7+9o<(Xl{n}dKX6Z%WvV`6hlIJ2rg5@12c@~^q&)ZY9$@w*6 z_ejYlz@ZP{}Q=vI=@8T zYr?}nL`~QXbXUHZl_f**Ko((kf_^I>qOWKrCiMgP42D{NM)}soswLdX27h9jG#aE- z$CR~jwX7svAwyzlXzhjj0L$`P#fwrrllb*oES~_Nr;#a3A2hpo%I7(0^^?9+C^Fv) zhPwOm4X%WrL8kQJnXy_@35GnmEEH@QB>u;^sI;|Om@Vb*#-r<6SB+>mI2LGQz!p(0?GsC6HK@9VK+FJr&NxI!jV&;K)Y1K!2H9uwRAL_V z(r8p1(+Q`SCB{bN*;%k`W2?`X8fKjK<@9kBeFO5$xI6_WLCq;>A{(7D9{$0SZ|-Bz z<)m3=K^q|Hm$j>rH4_4z3z}b0NmmPe`4!2>@Pv3QP87a#{_{mkRNXXg*!)L$sRT%x zp%;ez#CsF4sN8@bI}LUK`)lu@6Uw+2lB=G4LnK##Tb@(*Idzs|+iW{{9X5#x`8}h7 ziZ1^P9ppUkM|u`=Kab=nx|2u6@Vcijs2g#Lso@R4<7omYEEC4wEMV=pD`-Yd38jMM1rHGptJ#{Vb}s zwNmYPt#kD9T051lM@p(#F_%Zh{pSVYklx;KQ&A4d@{WY);WQdtBLDPe{xM+?!9DQ) zu!)w8QP8ABJZkRVO)Gwxe4z8vxjxxe#F0VH>}r5bO<2zO1=$vm-JOJa4DWjah}Y40 zYppv(KfPOCx0S({L4qR+W6qWm_KGB1t5GmhnMSMil@c;?`-w zv+;pRgzwckE_s1%n$@hYIAMo*O{#bmk@>gv4<%f0d$&Sy3iX9JC9cVwq{Dv37ddOS zhc$F>lqg9e<)9x!=B)P=k9K*djd1p|=aw-7FZtwX^{?Y0?S7Fw-VZb4B|hsOqKV{T z*j8Gg&)29NGhLtyGoT05a)q4@bnu-J;hZ_42!mpX);m;-dH(O}koQ8b51*-qM6Fip z6F}my5`|*o+s9Pv(=VgWcO-?%YK;mJD_Qn2-z^eZd`s4C=Yh274me$X=aajWzk>m# znaJP~GeI8aHCjmL%dyt`8eCJl;vo5<>}3!6VTceox+zW9SR26cQAjN;3r~=a7yPV} z&SL!b=Duc6NLI_$KHE^!I`$^cLZ*F6CMphT%{R{L+$wL-Ih~Sdf7F{4ibu@|UxMg( zHp!soQcUppRo>H}^H~YAG(GW={7cKC_StER@_craaWVvq@Fi#j}2ES{|IWJJkN3-B!If~egs zVwCsbYLE@ZAV@#XtT!@lx|V$}6=hkNSj8$b#5xMs#L}lnFrexwvyswiOGinxjl4vn z7sMU;J5s;CFi&qMMuG=BLH!(=zUi{u#m+2uT2HxO<@=ff$uv~Sk=yp8$R8B?z=S>c zNMACs{u?M^9!m8`s#|k(zS$DHr6;Gmw<)fspf?b>xLffahTD3)lX*H=*{rAsO^`PXPFT z(4UpK$DI4_1iyQV9|r0`-Zd-4@y|*E3Y8D#XIy(tTQ(BhH}3RG6I~!8P%-PjTxYiJ z)x>LwZoJ!6FQ9hK8joJ9d4JT}3qP2njXlwhGlp?0H>0g??1zjTK|}FudZ(q1e^6a> z3*3hl@1Ye&X^6`@liBj409hq9+oY(xt(fWYOL$JEz12hzG>j3bwpM-m477p9NgWk} z^IVB$>yb69bRGlStV!G;H-Hp&5QhMpZXL}-em8%!L%<7-S1cZGj?46f>nbgw)f^&* z9p9qaDJcz3vY2qdbhtq!`x2fxS|eT(?R-PdYVnn*V*Jamz8|}37)0RF6g^mzt;j}~ zD0V?HIym==CUEzn!vk-lBMe7|Wbk$BKxHQwQruhi;TiBME3Ri3_kG_E>G0L)Jq4^J zEgNLlor%cwsrv9&11;9PJDF|NUP4V4*_zyeVV(J$;Jw*i3Kzf36it;9m#jw|bwoQ? zUBucaEIF#uJyJ(>x{rz`?GWfO2^cj;_EAHtU+&6@qbEtrZSxIcawXCQwMGGW4?M(5 z(DM0l9`L3%L^le_gf7-b1Eci0g~0Eg=UpX}+F|we%(U&Oz%=JZ`dNMrfx(G-{{}Mi z!|9i0@nY5d-VRRCs_J>13&A^-89PtMwg{IW6WM(P{f)P3$#P!$zCKrP?A7*?anU4L ziST0k)apo49&@9JmN$RqW2N zM=*yZPm=AZiz)I>Z;9FAhwe`?Hgy>W-?IGDxyWdE0yyPi6P-2sk^p8*6)Q zqNJB(&oD%Y$SUtyk5Sa#MsU{5<;lw?aE_4leZ$2%P$0p`R4n;%A zq`NviCXg!$tdVe4V{Fiflj9{$(R8kI4plQM^4mK1cr_DsLZKPachxs)rJa(?(hn9! z4Spa#a^1&XJvk#KK$^=YOp|LQ2$Nt&U9Yi7sH%v=W z=>#YE-0oE(l{I-J zLXgUF*9~0feuRTJU>FH_g%FM>9F$Ds?}XoL$(`o{zxjIX#5K~tY>Zp|?&weU+y?)a z*bv?FEoO3IRSnfFd#i$R8pArO2cBe~m`st-7pyGey39q-3Q7dp?3<=n5EIg#Wf++e z@id4#`g4hp9k6XBll5)NlycN_ic6^kQWfUvN|C>;i%HzAT?gYhh~@6=X84s>WSB!g zHCA|c%^c?;)vVFRHh$|Cj3}AE;YTlZA|44#jmhk=ao@ebY#arH=sxv`QkrJXMkt zcJ%#JuXrnh*z3;$^9fJmHoe>9&2Sic)B3Z(&0nVsBx>*oTtby-3tb=Yrd^n%KoNk4 z%49?~s3SztvI_>n?fUHb$}ruQhn)#GSmHAWA!?Td$DnEIc~7HMwCTXgVJ9QL;*8EK z%bGR1&BxQPIdRyu-brC`LEu05dut=ArrkY<_7)$?5^OvRVeE;mgyvQnn-^w=a7&og zzP3sC2ilin9)pB~N3mM#r%;|eRsykhE11uzirhB4_qBAg`Q79T4i-T% z=_M(-Qt=m3P?UNmsTg5!xBtv7J7v7T5x`%RMmv9xLT z*Gpj3!b++9Jy@_=LP_`O3Z6gy^4wev9HY>M36xO8K7LU8<%>ax2WFTpxj~ZqJQOZB zDM`?E2BwcsiO5{Y)0+oKS9=fr9gj#J(c{4_6~eNd(9Yhn`cGhk9oFw{Xrh_v@JOV& z)us|B94wBd`eM^>B>@^|eAUi(81^HL()gU>6iq^D-iZKw{QE=@V6FF1#|%FdZ)3CP z%qGF)TGV0$o>B&?a;P?1J*sqBf6u&GL1I)jOL}@4yDP<8N8`g(cfHnVRp~Du_5}kO ztO)OKkiMr+rnlw1Ez;g0&yGFHNlUL!xEZ4OiouZOhv>n8 zcQMD|s|JzX`+Nveb^WlPR}Hcy%M5$;x22L#Qxd!E*N^`M?dId@-=!Up>%vJ`RGvhWafuU!Gfy+^#rImIMziQpGv=6Yk<%x-R`!F<5b- zI2R=*v2}loxANK#JPd;dN>32zhZAf#5Bs|0LxcmusG?#Re~Y2i;rUkCCEc?OC!{@Z zPK$7fi2L%sOGq|I?nw|cqM<53#P7Bq=s*E4D3E5~l4l4?fG+f66*HZMyN{X@a#cVhQ9`oLQ5)Y zR?-Hq@5?HUL)gmBC|WZi#VR?O5i^qrHSVdM?aPATbX1k8r+O?om^ljyBzMj6 zLg+@a!DZva9~kqZ`Oq$-=Q20j^Tihcul*4cUiQnMg)fO}LaLSumd1=*TXa;-!8S4k zX1JB5EqYm0X5F>HP9p^QVVN?@`6n4%{2Nn<^h8SQ*1Hb#T>@}?lKQzOr-;36ciULG zYx{lG=p@_C1MS*Z#GRu7wD!4W%0&W8`L%}R#G_n!UfteMYkoYgC9|jO*Or#?b?PF3 z7<6k3T2YCP$!|im+6LJ~l7zw|DXOltgVCs@I`-(z-^C3PV9YfT?3avH(`L;yYm>sWRwV z^n<`+H-YRipgat9z|~8PSm)f6u7*X}CMGg_O-rkWLJqYRM>00ojqiN4>a~qv_{d;o zP%mLCxGsJ_qZM2tyy2GPj4 z_wm0L3{%SqJ4^npoiw@COP_pfU6w@tas6BMEA(D-gJSYa8$Qgf3eI~kjsq({ ziIX4p@c@elg(7ha;xm2fZb5bkSvhk9iL)dlCC|eGcX_8jRHFG-q?`s%lZKUknnp>< z$9vd~H9;2cm9M@YS$~mjJ^3k#V2C**YN_>2h#5@JgvqW_aTp2=b8D%A8VKGH&l z9lY)A`|quN%Ayp$u9az-cP&8~-X|L_IefVGu z)L$JnL$5>gb<9{o`8|eK&T5MYCusJ;W&TIdA-K8UY)@Phl_M?5W!fw)AF;hTx5X`BD=2hJBuimk(M04^cWbIcDd0V8(|WUioBs3|)X3tMkTLnr^*}I< zvQVYYB+PNAv4-RAnV58J82+%k|3hk}Ohv`)EH;KilkW$id<`k-v zE#I^@;<(Ok7wz>fSs0UtzSZ2T(1#WrH67b#qA)f%WFUA&xfMheuGCQ4wKzB}PDA3Z za!^EnPcS`_Q+?FU8jwG)l>L;*$I|dj?m07gl>01S<7Rnvm%U$z($@1@d(YvR1z~n| zG&9#c>HaGM-$v`$zBPT+UOk^bLG{2EA68bvwW7VRuSD}0uYs#c%}=s3l@dg=a;mK+ zNsiK?x?xI#W{WreJP87h2c zp9mZ{lnc9Ovws}C)}g$83rX<^@tI}-XoH#$;q(j2DihmgAGDbHk^b%KbsiPpg$+7^ z904g-uXwyL}r8 zxhyZHn0(-tR}PwxH6=>$v2ln69nPC2)nmntM2haLsAQH(km&|{xA*GcB|9$rEIBfD z>JP()STcb)4Z7dn^m7b-jg3G6o!=dHN%<&06iG{N;$GYRP&+zk3@WQz1;Ek;YQbJU+ z_En8*e{9W88J|yNGBB=lfV$v z8p=t#C#gr1D&JS+hC1GE(aa~K&m8(^X!2Na!@&El&xj$B38UfkX;(qG8p8p3w|iwq zM=NI=QE=fx-ilL{_Pa~}woqw!cA@25DF#~3PwVP;?d?W;>|S5%p0mWCW*}`VK4Uq? zOI6BUbw32LFuXZ69d)x{5=9zBc~bJXuOTd!vti$`g@1g!%u8>~>uIwJ+QfQ9LB3uJ zsZ749*}s?!`YH8cX)$Jib&#(!ziG#!i?&MDEm4p62T8tIv}XONG78fA64vQ48mU3u z!v8F3B1iB;F9LwkDbi1|d~xfUDw-h|ypz~blu=j7f{B6%`eFPw6d2NjeHzhJ0%e|2 zo*K?t{+!64vQYQSWNod;-O*;wjhZi}W$zb{ns*98+FDG!c1Xys<43@&Fefbb_cH;x zeW59trW$|1z*E8vC#14p00_%Xu{OncWSFB^k#l7ZsLU(zXSQ(l_XM@P-#k+&>u~h+ z_3Vnrm9&zAw>s`x61_pEbU)S5CZM?bsi5S>LIx+(cNrfPmQD4~`bovNStPxa)>EWb6rZxN21m~r!VBJ(w-XM^i#baCNR-#lzd|pU znjA29)RKSj8!$P?wN<8Dl6-gak_qf1VsZ(RC|V6U3UB5)-b&8!ufQcn2!3gRb6ELy z(P=H47B=lOnEkaOKo&7YpXd1pT4g%uK1J8dy5Qph&Y1MG z`{^5>2x%aa!o&Tk(aV=wT`7FC#9y?VFEHx&5OWrMNnU_%a;@*NXNC2l*K_6PWd9!k zK0v|0lL_c~^bSq~1-zKui6uUt#s zPmcoi=J0!w@oX_d8>+n3!;PJymiwYin~jUx?g(XQXa)rz>I6Ib@_enDGaiE9-kwP zjWM}%ff=^w-UUxW4}JGwi?iCOmWmo4TY#Xw&pWT<0Qp_qPk@5DF{5qiFrYlalY42c z*X##=qK@ZU2u-IBwt4&v4>Tn)jF&N1iMkn!t3UtO8>;|%Y=6rf8J~;uXF&8Kaz|5x zB8QzH^Dd(^7L%#^MegA=PW|qk0f-~RArf?IH`QJ`5Li$Bf%b}gte65wl|8ZXQU=R{ z&c8VoIL4Ph81h2{n+BEkZ$VM53N2575n%sU9(%=#eUuA_-8I zF-W&9$+PzNk{5%lySHp_A^pMTe8_U)w7wIRIG0<$;d}~--3rAqoXmw+mJFpSO2b{L zF*n{%xk-g8lod`z_lk&0Mc+GP?}$;t%=nfc|Ns2{w0gJY;Ow-1f-X%lxrdwwPElF$ zdXil~)DAH#s=Ra>0<3H55J{|yfS>LA=2XIk*a_m5A)ku;;M?~}D-3MJGbF}ZAoQTF z$&534px`&?brYQcCOvw&tXU{NBx_QA_vgR!1{9j`iZiVdV#i^@lKl1G96F>=&!4O1 zD_yk94MDwU!f+ws34V5FiL>b%e(NS9QTzJgN1vG_CMZBQDi^HiH(BF;83rI5n`S<~ z3|tCx3T*RQKkJBv1p1e@u;hLoNHaRU(NAejY~3JQx{cFfQIQ7_usPE3pEzkkhc&>3 zqKEa}Q$L3|X8Itp#xOgX3xE+oT%F*7+jN#=@-B~In;MErdU7t0i1|1d{1-oKl?*x2 z1|h_&v(h=EGkJfvoEMO8{WQA*pTx&PvMsv}Hezh#FLeC<3#|mC2hiOd#qVkz z3}G+)44KfIrJtrJ*V>=Z{6ERl&U0dG1f~GO-HlBIO$07yF!79h{UGKaynq3+AF;=e@0@ua)gj&u1lBP2#db`OC)4qW|b(L-Ofq?SPrIRU?sPT|MbfaQ$qo zm|xIc*8UKFv*1jzR5+c)Y63uCRS8OS(iho@8;5b@V@>U|T2Xq{N8!r?5;AewRQn4k z+3d1>;M*4!+ZYcbC#EPz42hNWE@X#8^#j;MXSE6J(ub+=a$e;i$>WBk^ggJhFS-9K z8mY!IxEK7MKhpvKMCx*rx3y7Rg)+sF=hJ3t`|T7HD^cjNHM*#v0fYC=Pz0MA{S!z0Faj`g(ju>>|LvyiYAuRs%MmcZ!X~aNmbwA zil}8979}#@9yzTN&fgKm_lbM1u7J1cDLIQy5f_bvTZQ%{8==+{q`qz(x-A77{wghl zZ%i|_%o1etC}5UtuP)Bx`ITSVLX!mM>L5;&#~cO z^~trGDs*EFxP`wlqPF$cjc3+LLB4}LW!Hz5)F;i5d~A;4@Xc-uk(WGTfw!R_?rJN_ zMaZuE?WNil?JkNiEED#(mX-0uX)z}UXl}zSi_jC@f@6Zl)J>E;ILN|8@ zq2H^Od*Kv*xX>MF-U47sPXLhhNDzN~hPUk9jp998bQUCcJj9)HN6=0w+(YzVg#Jg? z8h0R5*E4+iqgw>GoSYb!Gh`c0frgiTord#_j_jG4XJH;$4+*FaL~GMSa7fppjU5v} z)esLBPgZ~7{HwG%3O0D}1cTTm6SRG$O#i=W+1fIk$PVR$cB>0RoPG9x=&a#Lb%Qz! zkGNQ${6`01pNlZQmM+R74dkmkQ*jhZ)r1DwdnLqjpKBLQ9(>EjgH{3z&IX+F)zXOQG zYluvh%rh!I8V{jz+B28n@ZFT<*+^a%Gwho zRF@T5LDY(E8cJU8nEsWl5eD$@j1Q#nSZAvL*|r-FRq4u;&5v9 z5wS-}!DY2&2$y1a^cvlZ{i;w;%Q%0K^|d*Rjq^xe_kg$ehgpGC`FB_Tw;EII!nLR}ZAPwDKR9ajN?ZM-=$6@Hj z?er#{FIwE?nL3`7_Yjdm59l&9PEnhuL1+U5z?0aGvI!+5alu`AlY_>J53*hzAIuRI ztXGcvv!R#~+vj+TRnHLi9#r&-iPLeobqs1=WJ(9(c<>3~dnf1lmpIjzLYJE|B?!XR zMA8R*vob13Kw@UXn2Q(~Lz!_558lrh=X3+xOFGmpwxjhU6n^_kM+bt-w8js`53c!& zUk~ov4QQ{!_Z7I!7Zny>M;ljVAGv9-w0oQXQrac@1}2!9gPX~8Ng`$OoZ#h~>!Ej8 zAv2es7yjkk+Zlc>n&S zb;miCKL!qnhdb{|Pr!OG?gE>jr3BigJ)!H9_ybvzxwWM7A9OI*BYj6#o7FEvE>beJ zR3&?JV%#wQC#k5HK6%PtVYRQ^@JRc`^EvEi<9d9YpDBWeyS;c#x;&zbBgKA6IkUlox$irvE z5AnRhu`3eH>uPHb>5}2|oY_22qpcj2giC>abTk}@!aIG$SM)hD#9y&gvF zWHg(wdacpRejBc-sYdEnE^I7UVqfFP0RPRZK4Q+rLQcf1427%nWC{u^ktZ3(2Jcog zkB)R{Ftm*oq!H?#{{gvV@%zLlv!Yz$C3vv^zl=Rg{6&c_qSdUvv;%0VXQo@FScN(G zlcvzL%2-fREH#&lD%so9F*E1vSKP+Sj)F1+61F}50YSr6#HD$}bC*c2WZ%?pNQwek?xA%QhXzJwDbmU`#t^9wDO%B>YwMRjA{3D_}t=Ogfg@^90?LD%-HX zgg~6!`s$YlCv9Zwnp`n|&tHJL+JWs}08Egxk;q(6(pjc}SFBhOEzi2_{NBLrmX&4s zl!O9s`PRR!)thOquZfPc+sh1fV+o6<5BUyfzmH}Nq&|RE9S)E&X&YW{NCxT)Leq2{ zZ86Bf_&iABo=8;u&2{ttNXdt}$dDVe+L|eR*7a7$f#&36w0s!NN>|l+-Ym5ui20DE zo<`|etM3+I#FYP0l8>E$O#C>kmjAcF4b+VhL+PnX8ji@ zgILOtMGneJl1ky9dz4_Dy}fAAAbl%mr1XQ|CKbZf;oziVb|8^rhr0(-^URtJQg>v? zB*gnAh&we>K}ouD*X;lU_Yg|FX}zr#hzR3tr?6}qBc>9hP=mo{&*;)+o!I}V1S29n z_Orz)FofWX&&Kth)cZ#Gd#)vO!FVw-iFr8kNqBra(tYo)ZhAntMlzT;%TNev7d&uy z76LkOlaX1A7-JoEHd%F!~ z1$<(nib?Y7>~rcQ)2klrAkARz&;herV}lh`M)#`z-bJYMZzbOsKZdiLCdzU((-dW$ zxY3?OW0FfIx0d9HJf3%f2Pe~3&lM62^Rakw><}xJc|d&=0y&utcDQCUMFUg=LHgLf zU7AFb06QY+L2#F1Pl8gtB!jcCHB!9e?SMR5*4)rJfuze4arZ-jDSEC(eT8|HT(G1@ za?}M1t>s36@!Xv#Vux>Pz-#Vw<8$Sgdx=bK=y8mu37?WESLhX5FzIVx=FfY1knBU( zaG1k%Iz&PjA#ytuir0R-kxt<+$XDaLd?K%wP{8#&Br{ z>Z)HVQPue}zSrG5^`S7>&oae=c0atJ83yu$4-VIEcK<+Ft7XW|*DA*kpn3p6rQk*$ zeQDj@@_CGv2HdBma@m;r@X)YW=FU$2DkI@5Qjm zp&9znMA}+KPl89(psW!LIwqKZyL!d{W7JradKuVO{8Ut!x0jL`T6@8wfxA+7koa3u z)$=h{&4rq0oOyM;|8AEQRdAD^+B4h)bebX;F1j1%beAxitWcD0PWBY)F)nLZq z4u<;5VUHN2yS1{nUlW{>nN*HYcl>tqY`TZplA}by7?aTPhmBA*Jm;SeOT~l(SA}7s+CII-LlLzp6-l>0`V%rAuo9KN!mHhL#~F z<<*vEsKfsbp@eB9zWlQi)Sj+Lq|awyptnKWl59dD^yMEb=6eVZiB8({*%yiLmT#|C|Ual?vNcT)>C{{+UWT`@U(2M$-=_I%A&CI({1b3`9>&6~>Yo9lM6ojUx>2zn%|MXXS%Q^3JbxRz^dBwrk*d$^AzRR{QoB;a_ z3Nhb@*=eIsH5TqN&R7qIg07zg)ireg^WXa~M=n~R{O5zkkw=I|num!Xu`x_l_i%lor)34@+}T zO&$=-GRKJ?EoB@{Q)GREtuh*NY>LVqGe)qg8!`qNo-H0dNji{uB04xa0zcs5P%sM` z3kx&;1#)Jih#pv6^QeDSeQbs)?MPo$+sq&DRnYP26%6Fd>qD0H?P%Ny?p zW<=zn9uh}#4uR0$+1n@}4%KYt6CTIisMt+Ikmb-@gh(PCWwNl zRf@y`X&ye{oZM|x_NOz((cQ(#K)YcquU;cE?On;S>6yi(G{ug}YekCwge{`UC4zVN z#R5>IIicYiCr;_wza3ABXC4ZK(IvfZt^-If^@l!e21Wk%m%^2c{R6=IYR;O}pePeU{{WNd_w# zyHVvDbYWVpQ|@*d2cc?E$TCfg6LkS3@H>-zaQyqmCh&GHcJ%;u{}B|^I;<D{ybPKhhZc{@M-7eO5FL|7Lu7A-#%gfidc|H~80G{0NMnr#F zUf?EEjqp* zv+^LE3y4dLgY&DutRzVPD6@})=}Bpn`U}6iuo&rh2ONQ$Gv79K;6{d}S73Q$P&v{% zcza#&*H-*lO)k>JANx2~$KB2dcn?XAs|kocSLJ z`|1vA*shUh_m4c`Aam66C^TB(&imzDXUWn`9^LEL7Wnj&*^WKV3X~pDCDC=o6!%Gx zZPaxjeG^}~2UOvb3ygS3V~*aX+78wu{oMVzD%auM)nd$0ti!)z{0tKv%%CA)aGnZJ zo=8ds>~(7cx6ZDO)ks5bp((sKl~bzzS6L#VuYP{j9l~*yws=zcKOCgqR%nU6)ignn z#Iz+Q6&A7bGw)#Ua_xdZ9PE3%;1}DBh*-HIcuIt5qqJTzfVDy5B9ck z_BfbJL|5o=f+?6By9Uc3Ymn@Ujsy%BxX=IAOuFzz030IFJqXW7X%InG|-g~F2DQOaj=HX_hnZ`TtOenB}Y5VZ3lV9qdgp# z%FWn@)5a|+D$ft6Z=)&ONlTK1(!`f;j(Cd+a)@wW|C$HA>NTRQdKUBxty!>OY=olMvD zHdEnGI-$^OR8&5SJ7NaNdA<16?@t&QMvxU&ciNHy$1u?9nuy%SN&mso{Ukaviy#SA zad5@{=f+v!in~JsC5!YpDTl82G_c)(PQ|X}ZoSGhh`eUE zu7c-fSK?b2=t7h7HCNXUb0}#lc9?I?i@H^IOF?P9w5}c<+9SRw&8nBO0frI^=fv)(+O@O{PMY8e9eLSX&J_Oa60r zI&^6=^RGTcmuFS0z#cfFNb2%{bI}6OV1)+00OhH!C<~s>0vw#2czTr#~A%!gYtp-U$xPQ=?d=n5GiXlBv-W_O> z#H~2IwbuLm(nSNJeCV0`-Ib(2F#rCO9u``Ay_PM%g5`}F2z?@KfHn>&K}`B~^&8nZ zdCzHk6e#nR)@9yw5fR|@4(F$4f5BWYDk(1h7_OD+!Onp5eibXu)i@QZMsYAf zUO~icpYUo#9*?9LY3|0=rLbGT>lREYvy8uA$=NB2d0>Q)Aq4zPgp$%Nw&B%LiFBh5$iZ z=?2g0wxFk08-(g_x(#e9Epspb{qZ`)TlyokF$QXDC%@>-`I#!n3Mth|*Tz0zq&fb< zBAN@Y8wUOAVON8iPamnFK4unIQ4YPXuJT6qCrkyS`s?k5Y)Q6l*2VMCX)ZM4-apf3 z?wU1uvYxyHr0yWVZ3Jp(K5ghddlltM9oV}D7TT~9FwIRTZy5O*C+mrvPGrV89_v$D zS|mK|D7lRI^QRz`hx3*#Jv>M0QM()`VJwqhwXF zi7bo2jUf%>Dfao_&Ztb*$ulV}91bNszmqm`WONzm2f})Pt4!iPlao=pTu$Au2!%r= zw{BP$f`pvk2@0Aa@^!ZjOT6$0%4KFPL4@9wVi5FJj(LYZJ^3BNd-fYj}oKf+p#vWf8bYH&0iD59mZo~G=f!GHMH zoA3S>S=&E_&4t%kZO&YxYQEqR^WeUfGG%I|$Wc6dQ57qgRK24ZoGjy2rhI_ScM;d9 z;}$IN057PVZ(73LzKKP004nu!N{J^Tx08qS-8=i=8TI~!pWxZ;`Pi#$K=wLT0LRETvq7{yVU8QQBF_g_K#6;+kuh=9zhX2-C`$r9v$06R3Jhb8ax04)(^hQi?wv>`bkp-lcsJ z5flQcPylAFCd$~$ajMH8?YnS_u2{I;Z@3mAWuQ9fGZ*FzsMe=q$bRIYDR>FjAwRaK zmJTr11dCuEd$pn+uxZ%1?(C@oyFD%kghjHa{&qX+PU+e>WYTwO#gI)4HZ)X{d}YUS zWwd8r_9vQc%oJ{zd9PSiTDfMCxoC~;JP~q~XFst=2m&Aj0?LgU`4@`Dl!y6%44poz zr!kXf$5C2`Cz`M!+GM8H$I4o|8}9&}lzL3}BAY+L`TR!m!s^11o<3?UKB;YIxZdEL z$`SES8bp4&w%tEmh{JpP$9PwW*>{jA1g)@E!k`Ft$>tv}4=G%WuXI&ji21y(4(mx4 z!nLNA)>)0@JY62!`wHYfg~Kfifbvbn_MQ8Rcy@L(AUqSUkPK^^Pg$rj8>*2FV0l=0 z^&1U+21COk@C#m`8Vma;R{cYpw($t%8@6Y*fgB4&-4xFukh;uKr^(kRr(aa_+5BBOnGijTC@K+eRfW#K?GDFr8COU* z-CgXPQiXJEm$SE=aM9=C)6ZN_GvdTeDSLUvB-k!(dfQis0u22jaT}gHHr#;Z_r51w z>}9TBgimR6csHkpb#`~ zE}|YTEa@~p6cp^#PK-vMQ)vH>)PGm}bX^Y+z<%kGgbD#N_-Bl}2PC%4Fx0oiiAxyI zdQ6FlfI~yN5}dPTutsRU@C(BIPJ*FkEN1g#4Z1y#Ptxg2hRsqn$fYNNPV+%Te+1oQ zCX;fXj_2TDe@$nhlBN$Ehs{b(hkjVE$dp%cj^FlNN&)hu+Zj=7Btg65>Rw(U;v48tf4v6KfU=KDN-%^a_l*dn^&8n*m znufwdh*Ahz(&?05+~xE-FZ#7kp>+Y7>OhW9VGe2|M{+Kucpt9qRAHi^k*@<<1$sw@ zZUY;$fmVCT#HD|sFK6;`cm{09FoWSNS;?@y$PLbXV!cc7wyb_`PvSZg9letTTnzz` z2((1_HQ^aCN<&4(%lvmf(q>jv%Nu``>89ovGj)L<-tBrdTjr7^Mu^w@%$^0V4bg01 z_(JSA;&i^0fkIH`IvRMO#8hq3fSNp>THz0oWVOyORkxQb)4emHXO8xEy2uO5Hn~#(QyyhV$kxuf~ zDaY8b(&080dD9BPMtGr%XD^ztlccqrVT|V5f6y6P*e9!_)r))BFi`x#uzVsrkdTP! z_&xYvMvtaXd+AYF$IXOma?qZwT5QdJ1)YX33Id%4Q^$$&>df9g-r0SvZ5$Sw321Ii#Pjf} z9Uf*f4|voyQu1_2+Zy^-ME%-%jxN(S^7t)G+@Yjou)%;0+Sr`rYcruj)W5nZhO$6p zUTvd#dLQTmxIaMTr$rg5m!k4X* z8qQ;>8fB9P5&J+Tw$aF`RMm3^Bp7w!9C~TTey5r~n5l@xGe$xAW)JM*omG~F2DfXPOda*zhO7hdS9z5aFBQx)12%tgU){eH#ulM^~N6)hM+IrBZG zOVlblJbfA6&D(O7;-QDXCdutdUeb-O=IyNkUgVS&*|;<6Z3bp&I8dkmUK>i)Cz-rp zkn*?x{HLZBmNdZfZ(KU{*{$`I+z$nfs-Kh;`t|tg#NT##Xp(;Su7HIrB{ynA7!szl z|8*rNc#8+3yMe)k-zQ%4XM(?}Oj5or(dKnUZ>+tn+o4Jm760G)8rN=6_a6={P(3V; z-MT{}z1Srkum3JZfl-C&VNsM^7EJ)msC!HWLZB@)LkiYlN`a{`Fs?|y`VFPX{Bm*F zUv21ZnEQ-Zssq<$ztmz&{F3|3cFl|i0(x44sRscIp;%tqOL?u*dYMUCSp%;fNW7p( zy0Wr+2Rc{z^c2pbYnV8McteFw=#&z zKn=>H*u}$Ye(R(A+IUHD4hjpX2S__ySt@ReQH8oDD5naXqky%YRBNg0da0)&a8uWU znN2)1!9D*4l?djgLKw7Kb(8R3vmSKh4CwJu-9eGp<}>W`)G>FK&_0v@<;eJ^l1nuX z--gXCJn!{8iKbtZ6|g7(0DYT<)>Ddv{vL{Pl!8KkmH|t^_wNO1|B{P+m8W9(fB*O{ zKPn4s*?G`=0aZp*=E(oz-PbGrBzKEZImpexecdJFD5w0%1w*ssUs_K#GqOmN0mR>` zLt^Nf4(F1n&6oL3n5xJ|govyjm(IA%L^XfG11f&b{-AODOv`49Ob4scey>vZK|K}_ z>og6`vO8;ZBnXE`r>%eS#VggoTFJEYT}@|6CV66|m==0mBdxi|$#{kSaH66;%^I&v zMK9L*VOvoCXDa$T8gnXH)romL*lM(lEs`Bkn&3)+&qn}|Oa84Oi>}0$_YU>?9_HYE zu+d`-QwW6P0dCA}Vy**6yhX}L()*C$ngbMqK#vIVTgEDxX9!yK zGU*O@wBA(>Cy(>&YDzI9jwRNGn+7ud9G}c&W{u0=BzL~FiG1yvp>p8q-$NTunf4Ah zGIeWOrcEnI3HQRc+8jzzZvI4L`OJl=w34*mDoR=>u)0fcPr;x40BYRq9~qC4@mj(q z<)lJQP)F3=`eypcAaOt@jXq&LW0DOt-;jC@Qt~r%(x0PqW7w^_Mg^o+bm{exy6u(90;eMqv8Ux9-4*Gv= z)~l<|Eo|*_jl8OQyv8*XYP&IN)gIQnD!7$IDi};&9Ifb1Z5IOVb@dOpT_@ruljt^> ziAKptBkzB*a`H=13=01%0eAWJrEX{^g*W3Sx6vh)B!PvAKAW4kbvDmbaR&WvMTar7 zl_j5rq;s<)Z>WxH{`L*6;HikmDhI9*|0o)UAKYfIrTPG6J1yO5Lbn<_|F)|;F%!vh z2@|{gHPLlE9b5xBFmKlDx)Z$(zv!(DHk(dM3G}iq^xx5m;r*YKJbz$K-PjV zDj9IPvUG2mOr7~9pRc-4H;+mIUGWc;|Ns9NkqL-s z<(6QN0Uae8*I*|ZGNMmUVw#Q6_;#c;%XTb-5To~OHXP@|LVJoeHksWrgG`B}z0VF( z4b4jb(#0PeWa57sI~2Ajwi$#8=TsYQ?7)bRSJd;r5V*_?6FV^Jpny*D@8t#p`|>6q zw|&m*7uN9`DA2rk{%Hm`wpJ3o?hbPGpQ0glE#PG3&Dam3YxfcPO`5jj9ugSjJ;4t) z!$>P&ZCo+lS23zch7$480r2ob!@o6RP5lWd{!;0?cC$#E9=4Y8<$@^{shCQf1v7zL zP_n>dEi3E#Irs(wUx;!D$3G+^-01W+57}Z7Py(hVq-h#y!|S;lLY^UK?>+{m>riyd)!q0^P4w@ck@H@f3Xo;gHvq`M|n#WW)EC8X-Rw(YP8Egf> zSn2IEKadO>;ADEARm9iUo;Z`x-|k9LqepQ&YAWXtwycb=2~Er*FyE}Mz^mWYpJAUa z1zgbJ02jl>ZfUrHG==5FCA?gM9GEPRezQzj21ZM=4l2!i6^vIz(7;Ap7{bUngt|MI zN$NB0I+Q|i`hK+|F715(`;RT5%2O15xn}*WvSQ4|>Y@8pgh{@36~fZ@no8g}DD+N+ zv14rPGzy)}tq+{2O(tB_77a$qtK>HAFJZ_EfqYozpE!eWfq5p051?zRdL%`g81+Dz zS}YnnN&k5+RkdES56q8oo`|OPcdwGSrGVhTM@whay|EPYZ@bwi=oBv3{2~aVR2Ri0 z?eE=vq@HT<4geIjhvOLwnx~>&jsjB2W(sMMKwQS69ys;H@$Aq0{wBZ{!|Q*J3*G5( zgnHBE;Xr~(12|vPRH6k=w}=fo=G15Kc}k6rNJY^D=OgjEYSyjTvVt6Q-i|BCVoWb> z+-iU!`mPKA+W|(6(CiI?sig^4o87N_`ho_?U^nZk8Jz7 z$g(7;KXR9Ep1e6r&LzE#d&aIqiV%sg{qC~i>Btx_ZV=ndOwyia6aHiOtpinF=KXWYgq$*VmO8X`$WkpZa6B|MT-MEM3aiXJRfZr#75AI(O$nzKGL!N9KkoADzm4 z02xUlLF%cAyKUY5eH1?icR6xKZDtjHPQqFhIk-T)?eohk@|dc~Mt@y^ig=|(Khi(l zVQ^^&2X&h??dcI;N`UuZT4ie{0--o@yiUdle3tMkR{Bn#@ukrqv?vu+ZsH_uLHSq@ z=h;;cs!adrIj^l4mkPA1A-lE-X;79wnt>a)?vn_#-)-IF7C{tybYROGqysa)<(tyP z*s0B*@{Q{aXLO?xh!2>OUlaWo4Orh)`WhF_gyzm^&7>&90Zr|Xac8ZvioWZK^U7!j|(UaDO==b*Vu;qq;WEV6p?;6TD`fHd`UC%V7{ zuOAA^rX1j3vmASQBg;<|pB~&d9P>$E3BD~jGS0LfKTCj1*X=2+17?mFooSeGA3@F& z&AyoEpaj^|Sd;O5@ZK6s+Jym!Nr|w2Hk{#+@XvdG2ls1gbuQ`ha?nY#7k0r9J}WIa z*1LUvxJtfASV0v+>SkVJvY^sY21~841-u=hiTQ5gt(wP9qz@=KR=Jm=RvJVrO|L?@ z=8?*Ybjg(j=YAW+GBXzal?B#_Wo5^*W=9$u@?~Loc~0 zic^fI=v06osUznH;}xTW{N{kWH8`@)loaHjWUSbnOGeTuM6_gP3kA*G$D__sh2{X? zx)|)hbN;X_L}E4Lz+7#adfX=tJe|Aagg?G9b+a{zA0&oLd|FY0JbR_rcdNOm5IPwd zy!%wFNn5(wK8jy9yEdKkZaz7HZgG4Ipz}28Da^DBrM}a_;aj`g~@uN0B8dJbV3Gojo+Eh134N^S^QfjcQ zfXU)k8p@BLntORKkoP`eTd3FRhM_6uz2j0xk|E^X&jR;R;zrEw3{1=??Mh-o;bP@O zIAhISI)5^0)FHqJANoo864*r(>S|KF?KD9A4dl1{k8n&bo%IQg659o`$=vfKk2Xrv z2JBcDE1uxUSMvW(Wq2XCiuI6aT0*KqBH5Tm^0AEAW-F&8Ic+*ZsMk`K^y}@htMJ3p zX`+2mou854&|uCcSPmu7&#>jId6KVq{xLJ2c+0;Dszo8Z0A4n@;w%+a+)T9a(&hLO z7{#xKv&_IDax}$ho~?CWV?%!g}pe@ zG1H~LWao8KNv&|y=8Otk;@#|nB;-(^Y2@6%VH`N$iUw4ZcHiN%;g!AU=& z;0GFE+uB*H)ng&6;Ucr8Sk(;Uuq^M3>WHKlisRMa| zG9bX%T_gW{P{sMo|4%z?H-%(ZO*eoZ#+U+>fPyL3D=fPCtq22uiyv>9Q^=FXQgLIL z=lpf$@=WMMlqLacUS%Gll@B=rs%2qo1crgQMBhsuOZAWLOhAnfoT`57yoK7QrQ+fj zqbyN=G^YnNru=pUVghJ%_I7@p_`McL)Jt4UfY$c9#JM`0Ngff`u*o-B|Q~(C=fj>T`Dq^15)E6B& zYxMqmGq@Z`z;vaM9~AM~w~TpS14m~6)tM8^g3DLx9qT}idNiGnCpxQ&Bz`LAu(Qxy z67eW+WuN3RQ8$m`mb@f-#XE?yCc!aS$}@&}WySX2$3;J=-Wmf7CwlfdKf0Dnm&|Fj z_d%9S5A#~ZU3^s@FPr`uUu=z zjzek0YJZUr6fkZ41Dd|Z?MxEP&b)6-U1QcEqST-+>AGK2!z8E&3e1NR=c1C>k|Sw& z?-TYmM4s|KOsdZ;7t^t52e{R+f2+ph_$t(K(O0LK^?i&;V!`DF}6QxnAT&d^?MnK`?Vi(|E8vv6U2&4O}%V)J(>jP>E~o`Rw^rR zpU2?KFTZQC%nCjE(9PQ*B`z8@lsz=*7m z=TtKoo+CX6)p^ieSfOC{WVIf_8cAt~nxbo&w%x|u|8~J%;oie4U@tsB=fiG>7MeC_ zS`n#&-0$KJD#D0Qgve02>ihYBIvz5Jy2>zs``LKScE_Fri~c=LG+L*lA))27pWuCY~)tue-eZ-FYVrOWM0NM%Fw|$4L{We zuXo6D`|;f!kpHvI)=hr*CN*zcM#(@ZqOagQ+Cy5jkE$PkmeCq&Dw#GcCeAVH#F_Xw zdPnn&p$X(9>!1I@E3vxvFYFQ&c8n33tF@0CA4`P7U zP%%MuCQ2#BMw-zq3MNMgfP3!!QRp^8tS&om?|))bHb4N&_BWCTZX{wLuZ#yR6}lV9i>N0t(UgeoZOq^QF3T)pzkFa3qwewC=c?1e2Uem zdwFAIxgR+?xKK{PGh=2GHn)D&q#^3N(Pmm_fy4l6Gpsjj1TN_}z+T``2%PjxGTMFS zO?LcKVtp zq-?=*@bZ_QEBk*gattv7+dz{C1ZaKR%h)LaVA`S2QfQ^gZ`F&CD`=0H(7 zmD}sZ`nTY;q7@nh@aFj_g$m)LG& zYj}w;N1=ZWXzSDVtV1EE0S1~??-G^F8^<9>)IzopYdpTvGLTRe)Qg~a0h_St|Jn%R zZZ$nsyUATH@l_)U(X))~S@h{wuJkg4Z@t`6!>h|?RG6qbgs-9wr-!Ns|OnI)}dc$p53f=-% z!+__UiBVD+s3q^eiRpiBkRP=#S%WmlOo{ZwcTAQ`Y5JH=M}sn&ycnpv#3^J(3Furk zdq#W?lC~ zLRF-i@FLwf(iPM$3dK=+m2vu@x9}OehSpEPUS{~GGscJ7N_Uem(k{L{t5VW zj^{n=PWp%@`oNz3$O?Rw{kY0~&htPxTbyYFpZX%0n%y-sW^n(mv^ICqO13ZcQ1LIo zVN~hlCllW}BKfv9Y2+&6M%Bo!TV|UGdB#te;HUaV4usoIniP{1vGx5AxGzlccu0*Q z+~-VnFR&*DSiZ1V>u?_=(-9PYxoB z!08sf>K_ZwguZlmK|wmXrRLpr2NWuD zC(y`8+dJvd(I$nlCmO(Q7K)BG`Tqn}PYx*MHvNvZ%q`hZ7Br1T;F4Bew+bZ{z)=ZQdX0Vl^k?n`sxJ zuS_KKi!&<(;hy8V34v=%h8feS$a)pRB)QBysbiM(QBJ=jxf{nj@jYd&!9AvcbCs&M z;zF5C6MppQJBq%y8ohSO+@IsxciP}m^wucpP4?)*6&S)&6DBDZ8E!%FEogLwWGGH8 z=5f}<5R?#ZxydQ_FGM4NR5(8qP1hH+etndxadl)k>zd^wpi=!;#*#x%-F=OYu6Jw$ z7^Mv-GCDugU_;Y#VRzHZEC*|Q)y~8q^OTR8OzVn5_$)U2&|%{%+VftfM$zK{`_Ahr z1HLN!J7H`2+s6&R!bU;dGJOJsWXY}Ht%=f(jLuimP)rwVX!PzAfyA<=3{WzRhvx`d3iE*rYmcn6t;DFKD%+cu>y|hNmD91wb36j1okn6o zV?byKy}=Hs!L5FP4GZsdpopXkN+}w>aVxN|j!^7Fbx-I($cuMm$HlEG+5cL<%R(!6 ze+=jF6g%FzDRm%@%pVzcPLO$+Vu=OiCVn0>;9hSPg0oDTgoc+tedWib3|f?Wb%z-oU9m(|?(U(%FX89!)# zfxuGxVRBEz<0)!~%2lt#-QRdVFu_39s9rf{JchiPEe`?D_(NZ3v`cem+|NhF(){B*@^-?O`y1>Z9|NiHs!qqbDOUlA!z|&AaDXIDT&nU9k z|I{s!;Pe`)idr6)=B)KI;*lium31PvdFIbWvjr=A{`!rs!bxV*t*RZh+pRTGT<$?rja2do`p*9 zm3oFYA&{l2EbDEg&C)~S%g%Dizj>h3egHq_f??UhFhp?Q&~LP@lFpW_&;T!Z@9sNN z30n!@z*uj|#hVCoB!rm!fQ1`JTj?5|1g^vn=9Lv|AR9R(B zV%K^&jtdx)Pq_`ki}K7H?&OMsF<^3U&Jv2xx3Z)`T3)V-F97o;-KN2uryvouyhQ8- zBrulEZx+rrdT%V4RUN92+|e#@Xg&DJO=i8>KH!yR%O^{_V27U-mY5;#)F#F=ljW`x zOd|gDvMRG)iu_KXCh2QlA?`%oW0NMq+BWL8J#E{zZQHhO+s3qe+O}=mwrx*$-+R_t z?-TnE)Q5_SjLN*uJP%ge6iK4Cy%5=az4nN`EZ2*H44(3Q6`e+bVSOjgPEv@uXW8mM zxAlX-k3I1#W$se|o{T{bU%1Y@J9~&7i90cnoR%}HdX%fw8{V%PsWW|)4F~>|+YlMF z>i|J5?^Y@bm=*VT=%*M zY>Pg$|HV`1=2!(!{u@tSMvL>(4rcY7#$jW|)%s#G21>`mfhcvu$pH;Zhze%<88%c3 zZK$phR^K!lin@T<_(;aaV7ot zQ);0PMaZTT$V8v6a47k{a7j{H!R5G3(xDz7wuu!#@;KiyCL=MIrZfLMP288G7W>lp zsj}yy9+v;KIn|+GCKA79xZjyHHro?AiWxI)c~8&&?PuPQ-@StOMKn+6Ff@Y_)xYcZ zv=)dd3#8~gG}VF2b7(Nha!uyvQK^XN^@lSK9xAJyUu{J0!H5BE1-LFBl6(fDM8NIrub5M73L#_+=1esM7LSaVSQpCZ+EKwS%dHr+ zQzq5aYM{TH=+7Q90Khj#ku;kjEwKa7m|9Rp2q7EVNnXc0EEj_m zuPjf}xkb!a!fB$3kC|~Strv<+{td0q`*Ycm2@e3PVOhW;KR9^ze#A67)qg9bD4T+4 z*@?~tDiLe|L85)=)zg0KGpHDLv0PUfCk*IK#eKXzrWySeroPThK{VRyQg5EjOG<}g zvd=A) z7Co_1B+WAPw)jcYK>8)P3y4`cf!4SpJzZbU{Y-}#bE3+he+fccFS?*Gv85w+2DOc_ z;(u)+7Dcn)9C}@|S@A!L7dwU?ZAu{knRk~p=6D(86FWD+4yoABrWj|m*<@{PPJAsH z_?^nwhe?u8)#2D7g~(U3!nf(#BM1%>lE1`OzCx_PTmQ?N-E>ro;P#(qlz*WQHT;GD zX;AD7t=0rS!AAX}1$$|^W16tH`Tjbt`1xk^{WF_Ln0NL^Coct8yiSE6epfGj0)BUC zLeioh`V?{upmtH51x}f0>=I}GMEpDbrxSjSVmQZGCAEUTR)szv%yf`_^@1^h&vm}6 zf{h$O((qSmpmO*VVuYn5bDugmWQj z4X|^4_%~II-FHMQU&k^mE#0qSr}Ks=7&B(_Q)z5a@YmzEfBT1Eb!X`!2Y-{%9CdcNMIlQLJ$?DIV4WVvD9d>5M!kVf z?8xTH!YN}I4!*xUhvH`d7d>X_eBs(!`15`>Mv+S|0J{W`Gs?(pL0BIBw9r_vDq!|D zB|q-8N!~R9dcMXvSdF2xfa+@#wOf}`^Ykrt=$tw-AC(bjj2D0FKHDAXoGM?50M`zI zT{yJK%KUB|QF-Sp5f#0B+kGFOuXmot*B-r|W!&(I5Rladq zW7W+%8dq41qa2fbFW62-@(cMmEAlm64}HOv+g-yomfi8e?IxNAcub$AW#9)NUNYR5 z#<2O7?4H{i(-oS8T~S914M0twI+hPOMS~cuqnK~D4#&Zv-rr`lGkG*WhVjaI$#oex z*z^P`WX2We$Mv0oqYzWG8$xFxJnZ+Sj{>FjMY+|*F{0vborqSn2f&2YQ>zCQ!;Vp3 zhgqW8!jt8?0DHiMZ!5aym^a``0i{Zx02{xu8taLgZy)W&GVHI}rn`LE1mTI+y{GkE$DuJ` z9TVy6o`2N`K!MTkR+Lg0h-Puhw01frdo}e(_%axLzMU0Q)Kza+!*!-hc8#~=c)`{? z>g*7rP4s_6{z;k~#CN=-a3?=wqul(RCc>^fbVA-T`taB>af>Ia{jn~n#aG=*J=sTo z*B>9DxL$_57isvce;c7mePEz_rSJX}_-w(n+-VIJQlp>q7G4O}anNZ_>YnaK(!|cl z@OTIXFEJ8sBZW(r8sv_K&dsiMvOC`S%BsPY(mZYh87HY|N$mTAZkeeDv5B3AMg~fw zim#SRTl`&XfN)blP_INY0PsYQSf{~xjeP(V7jvs)@+gc+Yvh)pKovTr(j=~Fa&;=| zlVCdh_Iv2GzNkire1Vgn5O$(D!@#=~qkp3NPga)Rx6b5_EH-u&n>;iEH0erUoWxS3 zUm>DPC8+2__>?a7g~JR17O+ZIGL%Gq+Kb<#Htj9~SFaRDS9Fatg7bd-npd!obob=z zfx@X43{)IxGPmRw=(S|3vtC!37Ek?(0Qm{BOti)>wkFi`5yIMOTCzPcN zAO(7@=0EHAM4)M{9lN6H3jf9u;CbLAdOHUeMAZSd%tvon+GO55 z9~5bKxM>WWKj=9ya6Z)#$XzO5szJP}-Q1ygD!i_o8nEbSlwF`ToxAAHPhgpG;0g8j zptA^jw|J$&6ueT>-Kp>(t@DZZa=<1~eew^M0i>G_+w)NpLF<`K9X#sB=bi_Z4$E)b zg*>kPH&ffi=5DtjsFx_}7?z$d<^T@#(w|w8@yiDOAue2N9>D-)U*TpoaYlQ$V#5*0 zVNyXzO}6dn6IAmPv|xI!?pkc;jpm}A^`faXt)$TTN?Fx>HzaY~1fNX1aTNyU3W#RF z*eCPaTtU0(sgb#_thdCAGA}8lzX6sGcs)fXCP$af+MPDyE|3Wu81}XG0OR?0Pf6ax zD!MPFkCEC6y)hlUb9X6FL_f#|77ZYC3BFOa%^>EqM+fg~vvhrU7q{K%?pU_x^IzqFD2hmsLN^cKTuFl#j1T=t(R znRA#LHL9w8f7XRtnMSV85;pBEiRHl;?0Uc}1d!=Q0uuuiJcC0&wOP*}yImrv0z+M8 zl)60>TQ5G3B`V$nf;BT0K~Z-cHpm}Jhv-gj_xDQuQ;dQndyNVJQj%ckC`;S4mWYaV z5#(g~S>zb|PCy~y$hrR2RaIs(c(p+0)6YghikK`i0+Z4aiiw|+P@IxanVhrx^n<66 zyX1;E4(?DE2P{D75$+x<&;qaC`!pvGtcne7eu$>v52%HC=5FxQ(<-u8+%OE5BW(=kFbCY-{=vUC-iu0^x6#K68g z7e&Sagc^af&eeV?7kKePttAm{Lswe76S&-hMp^tUsC?-1rU|&n;7&ien)Mj-=dV|y zQnU%Rx~x6VS_Zz`-O&gUS)snP$yowPnDe-ipnx^Ezv{ZPM^%?WMRmg;Ub1{Z_0c2I zgx}osyatgHskJ9wlf1t6`BT|#!al>KZWVHjiu z@|EO1WrZ%}F~d>NzQFei-EK+7uyyxZQ1QK?l!J4Mv?^(`9XY~~0u!t>M{`n}&LS7z z@}DoDVA(elYk^|y(*wb!e~~YrYTpU}$yG+n2+l7`Qr-|R0LSJgd>{92w4%3VR!WGAj;jNlFotqIULK(%Y!|I>w%mCP}03C!r+pSF{=P zbGgD)W4jo;bTNwR*EP9bP>P=_8!)~z0!C51iF+I^iF)@1Po2hIDq7)-Hdir3Z zJvQ3L91l_fQ$7tQPSpvYs4KyGcqaV*@KgO7(OeS5f zoydh{Tu{A{Fy0Sw$OZ))A<3L7+_>djPMHZ4xiQpyxWLUXjZa15RBl02d>xuCxE$zw z+EhWZs)9;2{Ad_x>OJ9S4`i333^g6}4Pmp79l?avymn^2neMFr0G6THGp68&opx%_ z>*c(CsKkelc2sGx^OPToa@J}cr004J0i~AVz5z$LJl4}~>c;~oe*6hTJ|TW&`N1DAO=!f5 zlNm#-@$k7p{vqLC&FX=Lm8p244{e+0XkSY%^2`4 z58{b{%lo0jmIH<+Ep}@0jEFsJJr|1hu(&`eE-@fuZ9878*9IX+F&?{<9PXKb6fBC3 z{3^~B-OXs}0VF>QzB*X@=mD3+yt+m6a1JN+O~_upGo7+Z9!2wSuJ_WqC^y!h@@?xn z8*p;|@9-Xvb0cXRDoA_`oY$v<1ga#AjfH3g{3Gbp2uikVjljnQ+{%+uTg-=Ng@NIj zN-=4xkC1@_4DKoZl#|3JXzqgCu6t+ z+Ll|0kIrCB!!Cx`r#qUxf%mkU`6ySSutn)BRfW-Ay35KD;PY+XztREJ(LMWI6-eE= z(KcqJ+gwmo+mZU@4@gQAJ?%Ah9c3meRRmmuDcASfP|90zY=TW7stAQ4EQt_QaEP)D zl+|vR&5BLt*dWPn4`VWJSX?gS*MxlA z6~j8ivw?`ps*pS2`9rL87xu?>R}E}^?zpe&DfqA$i;xt1Om<$G$o;~O5>1CT_+4?0 zp=ckh<`Opgx1>;wx^KIhvG1oFTL(2gz!VaJ4cU(&p=G90_3NexE1$a7Ll{sQG|xQ@ z4G_k2A?CyQcn&~reD>W9q}P!2^g}Mo{N}2_RJKK(9 ztOf^%HsL|YS6RgZiBTOu<`nz2bJwp^?FDiA2ekp%yn#h^kMDN5xCCQ-ut?2P;~x4R zg~|qAn^7b=161uGxRA*xm}kfa&Q7F%jx%sAg*wrtq8h4x)YD?9v?;+*#?+>tE~f7Jd&ul$#dHi2+@M4+L6T# zBU{4LrL%{}HhE88g?c-%pTo&!2aR16WX%GQM?(KJSH30lknwo^W;Eewyee&bq0eL? z-mpqL6iJFB`L(hGB7`V1KVRWZT+&&WjH`-_NX#dPp=k%*CZ0BHpqPqwEyk4khHzEi zQt;5Gz(gry@vS`DF=Be?$obO|@zQR`3@zp zJMiKjk!pFndE(_qlc$P+EnUA&v4=uY2{YF!>KSNZL^@o_HP}b7oL&JDLx3PTOPUK^ zSV)SUyN+$M>9uYD_~r}rGcnfi75m;0IKX+ZW71Qf?8w1Kh%tPT3a!qHdx*KeKjnw& zxf0nx5oExEo>s~W>lDBO%u_OS7>UryYkez*e4(RUi@@E!FjYb&ZqDwr`8c+U3m)4{ zM9xSi(!o6mjJY_jS-hGr%H%VD#- z<6k9998-^0Y7{sZyT$O?f$9G$XD$eA^v;M#Pb98Bo~ifq*|S;pq;lZ8*N)STnrazy~@QOLY zpC!VXw;iS`-x5g`FK?R}K+w(R+}87#7E#RyPpOKgs{L1m#y7y>00-P?1F^fJ+ z0Te_|?M5tX)$F}AUz=tl>|+1@ediLoAGXUq@!)PO$Wn&sCVm`g@UFtwjQ5CmLt(1aYhK*dCg=FsZp^FmIsrHIZin!iv(vT1zcLRJM z@IHv#NJcRxTn;3%Il6$za2V2F@)Xx}y5|)>nR~K}<}i|7ybm%_R6txO00WzzZyrvR z1nO@W_U(wLSOO|u$m+q~Lw&Q0DAs^w1R^$f;5IXv25L8bDHalstFK^+gKNYQ`wa}b z4OC8_!e-zs0%_e{ACAAlGf|OQu`19pjzpbWa=(UeitAIa7*QE`KQTZ^-&x*9@@bex zf5o0JTMfW=%Y>HPhBE{pov`(E<^GzNF#LA|q!SU_$m`up{&2HS4~M)uYnf>4u(afy zvfk;%O3QiTOS%JOpctEivw+?2Jyk*}Xi8FCeqXG9VzguF{13H&zlGB2jFKnGnb{w# zdh^*F<1++YffuaWFaQz{jljsW`s}>6vA8IIg*_n{Bmm*<{*l--_u8ha3m=>;J!&qR>H*Z^!P6_=Jetj0Ys_tGm6t=To~M;ROlC6uXI8G z7$A&VF1lA_O6Jo7zgRMkJD(HCaO81x@TWmNV8x4E-*vZ$6xuVsfD^OtCXFxv)N-EGS_Xc|iJyAQ-h1QHoVc%k0+csJn!0 z00Te%?8l694Kc;Zxz1gIg)f1~#7oyJ@?ugw!Fc~a`DVpwp(-f_Yyp5*!mVng5-tzs z!zS+h3ouct1QXVfzhjXz{aVWFDhs{kv znBl8Nt-~~72u`>(QLXudRfE+qzlx(m{EA9DjG>pbLyO+KheE}aoNCrRYM4J{$ZY2L ztqUo;!0?#b%4($9r}+uaao-jkb@hIs$;4HpR*5;Qy^(}6mK-TLE`$|kw36Ex11u~1 zssH4d6H{;Sr0>RNWeGL7Ww>lvX>wdsWN>{)<{efNP!#a51WTwpxBde<**vOED z+^Zojr<5Q1#T$M;{mExe?Gm?9~|O_nfQ>0Rf0@h*AJ_XL;bO6yFVKSdy*j#Tq- z^xDLx(dK@ji=ZC*^vU4rz^{!KEJD)3?swx<+||6Q&reC_(|V6M26i|(hYX}&)yv~g zh^W@~2Ti#P>bT`blXX7T;ohA;L#?-7`Fky|apvbTL0P37Py`cX=(1pFHrj9(Ix#nE zjM>q|dCg@!*nIz+Dcy=JJg<~zYBvn|d2%~W1p~Y|4l?-HzO+q& zU1m$=;8>-II+|GJ1|e*zXLNB=5^7|^ib z@F6mIy|z0Q>UOGs4b<#T46a@faQNad@@SH-^e$Fgo+|)v?~AStdL=e+SS)q*({5?Y zPTUFE=m6PpFvgYRm=@VvJ`P^Qv4Hi5SDSrdr@jMZ96E>l`pW@gYpBE$0*G1LoD@gnYqiwHcNY%2D4-twr#mf7#Sayq|1) z@VlSlg#IId`HkqZ@q!XIn!%u*wMQZe=ITw#&7>%5d+C#@!q;V0bOc)o;|59D43j9W z(JNmfO~wkjUgru6XP6WYgS*KtaKU}ZXg2u#`{|;}j*?`nmYliFO+xusf>Dls&Iw2j zx$HNShw7f~?bO@pU`Q?_!7)wp)mVt5>KH16vjBJdIt+jDZV(k+;k%*RBS<(hFdrj5 zc$9;%HMT1`W?c!WExkSssoLlxxWdTj_IVe_U?cjDOav1ZPb{J4>?>o&!l|ho?Jm=X?YTf(+YpSsGH4bf1n}29!VbG0tzw=+w z0dbt(zI+_Vf>EI!(fru}0P73inrJ(iH|2&NkP}-x@b5Q_%VjEki7ugZ3|&#*fPstC z&K5ttQ8WYa@Nhl^n+nDYQHlZYyr^UWf=|1FM6kzjAndF!GCQ3#bW2p8L$N$<4xESV z&zr)$1#;ujAnYT$bhpPxcM;XLxctfSQmw764Mgu3Z7JvQapBwx=FYY@sHQ>Q-!W>v zh=~x6?etP`iN5w%FzJpGHe$o1LtAV64CvKSC>FN-(e}O8!!9cYp`Nljy`it(8}AN$UL5h*8yH&lu3a*G26fR{e6D@t>?$@P1km-Q}vB zVSI-!N#|`{7YVCug+7mcS;-7XXUss8Le&Z&69CwLH8bcb!jw#o5c4ZOJ~WDe$quh2 zih0}zewT-(J_W~H%;%MX3KWX30YRv`tcmoW)8ROq0=zWFW|Y?;H-+wr+5@l%%dR|%a0CKV_4o~H4Jr?M$&C{acNH!6WBgBE72DuqT>v)MZj z9dP3Ee<$NISKJM=c@-nMJ%k8d!}t=(&NSmfhd8$f9s8*I&|95SfF8RJ!8Ru2GdskV zYO;NS$ZMQg9*$`>qVWsDuoG^s%y$>BkbsRKzWvo8s&MQnmOkp5yl~F`PLz}r{mWHF zu`v?R)UMLT%HFu;>M)okX#?{b?jN*htF&HSB6YLMPtY%w#CtY{cmvIT!Ry^K!_$xR z0dy`33b+p6sm(WxFp;D&Q0Y9yfj3vrP{okjYjDYPH9kKgru4I=owgH0x=7G~h77pf zX%;VCdht~@hnTK?G#@RW9|Ztk3CdzUM{aPXOl5X(KT*`N;QzYe-AY4QH&W$L!I+ei zseRsUM+RW=)CLnzIs4w|;g--9Z-8N3Vg!WcRo9WIgW|@6s!k=yD~Dw6>HmP%FltY$ zyBZ1*R}-$?h+5S-{Dt00DYAz7dlWWI$71*QbfZZ~G!NGpoHX|!u}hm6=Gf7~MbZcI zMI%DE8mHfZh1s_w?%vd^1xz_?x|FkJh6CHoypaEbq(D#OA#jy#rlUUNA7g*iXT_`^dMSBPu4q->U-Zx|EqUy;Tp$Re}UsI@NB%jjNZXX*7u^aL)lb zlOQ_A?zP>S53OR5*W+b~3}xvr)rcPY*%>C3DenB+Fw^C&!V&^7cCMp~-D24@zPN{q zy!fDGFhul9TT(0c+;1#Iay{Y1XU}`^nLNOf)j00YkLb?@Qu!Sa640EL!jzlM?C)LT zOldI&x&Az&JG8${${n>`}-saLJ)vtA!Vil!9r(20+(gc(lpuUfvnF zLUX|#($9>LBR~w1T~dS1pXFIPYx-2Z89IR<|IQ~EuSf@}k!x{?>OFi6%kkCl+W#)E z>6zDZsiGJX!VrryvRk=189Dt1u>4kNKzp!mQ;g2jj?ho9XQ4b6{1|LFlt=C87dh~I zzj(jmw~HS!wSXCYiiQxzDbL5z-g0hC;7|gZJ!FOST`yea#2H$@_MWRyB6aWUIBgCc@;~>8Vo>TN9+kvS-QeWT^(FjTWPxPrl8rb`sT7wfK?Icu2XGu$2+@ zY$DZAmEzO`$*auOU>Z#3D4(*ZYK3UHS>1g#evGVo9c0g>g&D65+Kq4NlM;fXp0b}| zYD??nzn_UZMh*dzVa^Ew@y)SH^k&nsNFT@Sn)yIR=#He4N!~-bdtSP?rSO!3MF)kTSPoqGoafnoJHd;8xXD3`Os zOKBS16k}%y{;SJf3G+slxqx!?fv%2C%|ozKQjDHyNp6ddX`v*E)Bad00Q_G!BWCK; zc&)u3(JWp=jn*H8yijkmR7OvImvXF-0pfv$=RUCJ`qn#KkeksriucG~fApEs!OjEv zAL<)M@#K$l#f1mjcO4kFec&`1*<7LYkjbA&r9DpAATtF;({%30RiC)&8lb!)1$_?q z1x3=6wA525^WjGi4Sr*24{D2HBvAHpYea%?mj^gq&;{8dSN#5%$~M$P(=SaYz4P4+ zX#(kHv;C)T&JyedlP939%ZC}}2<#AKTHsP^7{`&xcXHaTrR15P#{WJQ zch*XKK`8Ipt(0Ep{k1_Eo`2GO&f+~n=d;BeW%6iEV3C+0BEx%OS1b_6V{1nq#mXH2 z6Ls_0HN%!BYj+U35D2$F$v4_#5M8Fwu*ojuWQBCZW_=$HR@$(`3ovvR3d^DMi_Lf9 zSMc6s#r=uQHT1OQwfIf@bFZC0hjY`m-#eqLDA%4J6Ci;Z9#2T;U$5`_pA!#2^C<N1`}v>DD9i2MdKU zvCTws3)X-$mBK&0!;H17b;U9`?JwV>@2{{H40~hggr5NdTH7>y&F=+H`{W6N#hV^* z07)utxz+++JWPDPgictqJlqeR_%k?^9hyW+Z;fk zj5rSiopN>}Z=<1WAiO8}QSI4ajlp{t1PaoQhZ@wty-QCU6F;xY$jejaJzbDQv#(cZ z`=%oH72bZonTlfN@1qR#V11iWRg5^1S{Aju7UTG{QC2x$`c84vOiH>@UuoyZ*Do?J z;qXdI<=a^%XZfZ0x`^uHupEyjKhm2+M9!_m{{}mre@9M-Xj6r47NehNQDXYfpSe@+ z093PGV|FCCF)Z~3{tO(?KHhWDRV}OhHWCk3rljG+W8y{)kWe=QSmpiXu0@>)A0`ZX4y^0@Q!$&K@N_dw|+_g!S&;|c6kZd zxg)VnRTmrP+T(ZA(nz+FWduY&t9qgVoJ#uEv!H@|I9Qv~94sM-8WdMPMC5X*1VllX z+o}OF<83WQ@8ue*oT(gV4VXz@kQ9ALbHm+{85OQ@OPGnK?&iu;;a(81a?WN`xEwO_ zmvChq=u64i;0iF$L(nLwT$EtlvEjjv%f1 zq8)(p!#hhe>2X{e>Yti4k9>Yw&JEQvO`6gaHn_RGR4^t`drN#LcV9mCL4SGMt$ z$B*p@KhP5jntu$_V-Ppn18X&(^U5l(!uXCW`;4nQVlaxS2P65X>cUMqb{wL}6n7!t zey;9aA-+w!(~wGJ0oEIN2=4x}gw1J_CY#o%rsu6wIhuT;(S&JdOk*^S<>$Mcrc;MJ zrjze&B8bA%&4%A3Y!K&kZXQn|3n(mgKd?|S^BY= z&;+xqIXflxx{15wEc$0}s_ix!8*w10A($2=<|bk4VlY(ivZp{QX`qrL$m!H*)NU<6 zs%&c1$lY|V4K18~39l{;JiQ#;niD=uK@7V!H@iLbgzb7bn=x+hC6L7p-J6oXnxvIydFoOkn5oq!$u); zE!90SCvp<{tTGbBWZtVAJ~A?P0iMF8zH#~2zG*0uUg8j@M!{zhY$VJPt3aM+Xs=Lk zKOEUfV%?P1Q32IFJjILq#y*&-nBHoIC*{jxMdTn0hmp0gH@yPHSW`?zl+2|go;`8t zG3cs(;_E`L8I(zf9&AT(dDZAVyhuro7_DMj;}_YsnTApHe$R4KWU zuuP>DfQuXzPabN^-7ciT_gkIs=UbUhpoq@NscSe{{6C$9~RT6F5|MBpDL z0`jkxKJ^R7Yu;R4UQ1#yzRgMv#nr1gF0-;;Z&J#>y_#Z(Gk1oqnlsHDs|5`kwSi|i z5gJj^@h|wnGx5Dk(xZ|OlG%`B)cqqXRhI;H?lN2WMRE}4{R56)-6Lv7sPLL@_a?A% zs(q=~SS{N*V?eb+E@}5bu>9-rPtXjlO*E*_immNiQbuYL^UyA}9QsdfqosE&nQ&xU zgp1yfP)NZ1|3E z!jiZp6=t6$pj)G}9qSl{{q5Z6yl<#~>oLf`NE^>}W zBS+WK0A*?aifHDJQZra~PlDs7qQ~7()E_kbn2+$o5wb&xY+&Ybk z{rN-GUI`gvz-JA}dDc(%sj$(^*Xug9)V}$r^O4W>w8!)XXreV42PGyzl2nOkR0cuh z-UxKACjt*^66Gu}fhmg#eq#iF6>roU0v}ITkk&~2NaUW^)&O2kBGE<-x_AL$Up{wR zs$W58NNhF@bk*UU{LXo(+`v7` zi$lEE?^gFbBcxx_WPFQ=1A@YhNa-Cb68BE@Dn%UwMULl1tQ@Mb_NF>%{)`=A_eJ#X zQjyib_sK2aGhKMv`!0a6$DY7T8dqUtylvL?--4u18rzZ~oe_k!&zqk%V^5tcK}gj< zk7fNfboF)H5V8=octH0Xtu@HAK*@GsH4_FX{g`>^HF&Tb9OGC=#=KIq z%nFQ%6Rj@3+U@50E6QmFwi`+G-3gJ%yV;@kZ@kN3MjlA^rmHwXdjRV``bcck1fIzF z5T?rvIiX>nINIa-b$w?j+Bg^B&60Lv$^S{H^zVD{-SyperOIuUe@GG~$+K%~>f3Uz zm**O3n_yDZc@C;&aCZssSYeFY$wg((X<1RaIuhTs-)Gdlh zhA83(NbZY?bWT*=pemM0?wL7><9IhTHK!dZxw#1PFLi79F}|K`Z;}6V1>zU~pDPez zEcPdsT1bm9h!HAfbkei7O*I+B zEfzdqHCZVbGT-#o8LXgmG;lbi{(PoT$hLp)=CUr*3dxk;1I=6(#Q#WvPQLH)|B(WY zmZkrX6hOWuK~?+@De!E;(XQTXh}SMhQ)@&-lbk_9N0s_R<2G*x+4<&qF>opuL1Wsb z4RONCgtvI3X#bWuR(baQ>(k@&^^Rh&JO9^~PKIf7P2x7#*a;a?jE3>>#l|#e;TK3c zp1kwX=Rs{L1K1smhl_l#)($@v2RV)hsY24Gt!k}BIcWB8*EFdg+81ypYbDylC?}wR z)CE35lR-w^uiF^jf1Ut*`l3$-ixz%#)CKec2B!d8?6StO5GMvwI(ibvHz2CC82_Cw zur~;+{^A)Uz{8Mf@lG$P$#-jIbVDrH>CB<~|2zSO$p3f(f*7C&$jX}Zk`Dpd!Rnl2 ze2@GZkV4SU)dB!OI%sd7!Zwtb84JY{o`wB?IRTBZ?*DNDBW?dbCjicm@PC{@?XG=q zHTY_M>y$vu4BBS$Ft+LLz5EQgwL=BXVp)<<;p%lje&?SLZUOZQ{RJaOO8D&{lne11 z&`GdP`u4)S3!H?`_~QR`oDpE>Fbg>)K*Kq0(RCYb4hMAoX(N+?Y$~nRibl)$7v%nT zuGx_aMvL&PrTb|DTCgX+2C4O9WudbI%5Ir-Ec~(3&0zA1l=*MdTo(M(2GV!Dg_CEo z5k)8YNTEMH9P#W)QkYnAr`21%M~C|WAwuvUQJdV==q}_gIdez3#=h8QjIQXnWcrY$ zJ&KES=7FEpN&K;2(3a8P2uPeRpy`Girtpq73k&^0!Ee}DDp#xA>X#Z~9M8P2d-|30 zb*cMjaZl+3k+C*%>0miBSGDI1pd1Z%=s()TLi=4|xW01RT-9Sy^rQoAp~d`S?J{03 zp4{-^!?Pi!MfIH*RC}>w`VKOA<>h#pz9`bmf^+(kSWT6CzOl2~rJVD~sNblZWBz!BGMP zwX^!oRtgA1GWP z*KQIF=)5Z>v?*8?F^W6MFs>);#bd0Ne;e<4cJS{w<7+$&loC!f+X~MJ501n5fucRm7H+Zbu-p=+Pt@dID^{qKiu zy&;PpErFl7%Odq$rLql2FxdnmSg2X3nJ>WDua)AbaexI7P!$W*6TsJVZZjvuB!uTe zhW|!HG}oV*7KfS+R(N05G)cnZF@j&+9mki*ojLDhwb}cm+U`|}x!rz6uStTbUF8O^ z^g4={so?s*;Z_nKf_!oiZJy0mUN^D^C5y5!2XE#Ce+W6B9t(?7KNkbB&S6{@9l4&4 zVu5&NeAW%XU^M~kpmMR%76d0K3}_t2s}NCU-Pwc zf5yt1-mMXzP?1M5@xn=MN6SQ^-n|W06ov9g>ig-*1-%%}Tf*G9m>8Fl&~?u-O1m#| zazPrX%}SsEZn+jyYJ@p=0H7JpXgNdo8IF?7bjrOTngLBH`m-(yu_kZQaAo0nfQf?-GbBzgju_2_ncc zft38hFZ$sV|) zqm2W!R`n2);$Rs7HS+*K_PIxonZgLyW^b5_4*tBn%7~2zjv$0%^S7+(CTY}43XldS z>$#=oa9TlXaxskk94Gtnq*Or4Ko^euAD}t)&*6}hN0G$PcKkKr&+?GpLcyJIA@dPq zirOQ&=r;9ZDPFvqjQnqMiN{qB&c1JkzUPu3;=j8lHXLCgd(3!&2sK*XreIoExZJH5 zND0GEFi5O_WRB^EOa=0w2Iv;18bSC|c@}0oY-AbFK}!4^E`BGdajOtY3DWzaR`Lgy z_kQJ+-Gsff`FNw~Y;?-#M;amyjqR&3EwDN_lK+2ZAXVw@3ZaY-6a6#UCsVISo?R%smRM93nd;k4@+(Cr0--5IPkg2 ze#MQWev^<{72?j4!qk(COBHM{gWxaR88%Yikw?ALs)myik|E*n1+Kt5A~qF2J4h^I zK*H~5Vn)uczEEGV7bZAx0%~;VVR1F^)mJtg5bVTWEFtxz=mUK)WK( zHVQUW07tJA|Dl-bPRbRsIJ8!{Z8*0iG`m`+iTHeqWLLt4US;~T^C@w!IWSKcXlpKH zECO<@9oeBKllMj7OGgmner z3zgxUK7UM{^xcJwNpQjpI_yx_8ihQU=ALOncf#~Onm_1Gbi7^is0AhhL_=KMYI7mG zhZJw0l-?-y*~+5c_#PlC@YecrM2$)Hwb3nYa#uo1f3!ZDFa)9XhvwpCTMyTb`$(An zKho~0J+p4>8g^`_VkZ^bb}F`Qn-$x(ZQHhO+cqo7_0__?o_GKI3G%ZKP-p1+5UR{+)NjUO85?-zo#Ia<)>gX*v^kg$K;VL52h*uf7DX50RQ23x@{B zvDjA{ry^+DJY30Pm(IxSd}~pylBAcOG8hyYoE11lAtzdod!_D(S+H8}!w>T;D&#@v z0A;nKIQ_?mFb61Zb*|a@5SVXW9;`}h|0MKMRD+O8UjWHtto~6DJ2C-y$DyV_WKfut zS4&jJs+4GG+|44;9w(jIBCd?5S)q@_|CbLjip8OQuy3VQZ_Mv}!8itKqjAhBW}R%1 zoOl#?bWMhf>@+4_^rxZd%jHyA#|}!)^C^&BJc1-|Q7H;39NFk>8LF&v30F57r34xG z%h|Z3u3z*#G~@Z_DKnb|PD@&wu+6Y5(;hg8#_=*N0G`rtq5lQmo#Fa4K5QF$E#tr|`79 zqQt7efNP=y9ani`a=oG4UtgQ@+YH+fV63s>H7!`Ptq@`LKQ=gAGH8CnLWB$Lqjgiz zax;2`2;kXn^249h!%%+?GjE@h(^dV=)ak=G+W`BaedD^2?F`k8-q5`BHF)wP=(}tq zf_U_{;6FYDXWV{T-}m~q0KcJr$>O;AChlCyoV%2>iIGow_@APNF*@ zYZk!)TSdchy|QmCCK%@^Q;kB0{fWn=eSV6qNI=E1WkjDst8FkMc9M~C8>GlP5+L7yEWif{%txu3&yg`2S4^|l?Bc|v2vdrsR?)kO8$3N5d7XYx?6 zgH{{-k@aoms6Kr%g5&Ion}HsXWg#_@k9C)y@IdMeQ;F&lK2YrX&0QFbA9co^hNKmmU5Zoms+(GIZf<}RZXjjqXa@l=k}wylsw zXxeM`>-)RjT)l@m`)kN?QkGRDt+W`7%38GXjzAFDQN!F+V6>3-q2(=<^i%j<4}=#zyJ(yF-EG?(qmk z-G@&;&-Rx@riN0Gz=Yw1;uFnOVoiu2uIY~E>+gZ>YJv_4PaUx(5pCkYxu6@1#EmX? zi@k12cG;NFg<~sV=oh0h38{-|ltK8*eH*h7Fy=KPbErve6`?Ko%3B^XrD$V}6IUyd z7-CuvM?fwJ%5zJxJZ=OQWyT=cL+bZPojvB^E_+{=7x^-`&gQ>g#^WeEj+Xb+G3VM; zc=t<-SS@RDn!oA0=-u}-eCTeR^HuS zBVzg7OJD-m!@~|~o^vifsjRK`@Nvy;>j14q>(P4cE9&CGh@Ri*CR)~69>I! zVqQR$1=fU(F|$9_R~0TD+L)lU(^JW;@;3v4S9Wt3=)knuj#$}k%2;=4!Ia8=pzuN_ z67wyE@FS~>uDH)3{ zB5(+OlQ&VVa)GTrF-8Bymi|*$Mn&Qz1r<_0MVig_^O;_@+))gbaNURh+aT1W_bJbEtv;+Xo#<(EZc?w^eZ8PCBRB~a`Nc?b-0n) z&#V?uLEx6poTBlkz{+5xRH709cv(7S!0>It3&6Ua9Vn^WIo$XoIBIyKMBHbicWD=Y zlAn>jy{T#yfpM^izU0K8{+@rDU;5Hy>U|0l3S?~1oZRhubL+?cc2%>8RESm&^zkFS zDWt#D%)JhD(6!o>w54b~xT-Hb?d$|*J9kFj(sq=M>flbVZx6`$_|$uoFHJ#@&GB?H zXO%JbF!5#ii;ld+DGmciocK_UrK8HJI~E)rk<;SNSpQBv*!4KV#mJmAL)#fr@&zr| zpXsutXB_-bF!`Uik0z4<*mag-lUX=Epi#CY&K4nFxD`WI{w7?YKxWim148ljA8eFC z(Mc>a0a1buy4>aALObYcD=9-AK*3NvA!2;A0Zx*C7GpFjCR1t*1Smm71ML8ArL?>+ zpA7neliSbW`;W;d9dPGrwoq#y@rgk9TK+O5WW84(tf=-#j-R>hjeulBTD&wCH8sle zqdiO9Frs`l!V%<#`ep)vPB(8z)Ox5;?PfS)4@0ioiAM4MgFKdM$EkjY^R@&~pp*<% zwNHhWsCy3g)Nqu36ObHnrHv8gEoe{kf#99~Y#%7Z2U11XqKLkIu%{@Wf(cnu(ZziZ zPB0JfX3pc$`E>1TUkz{JDjPhCAE$cs{VB#JgFs2PRHo(hHqUgQF0S~A8zq2AQ2s2x zcR65}^Gr7Sf{ES}pf{T+xb+}LETpl@q+$=`xCkV}Ah`i1QNi8cI3II!$$upgU?`Q0 z0@BZj36GqS8yBh(dbXjv$O!xOE@%~Q%&>9%Hv+A3@&)NYbN+LdM!6BBw|IbSGs`PA zOz#v{9CbBg=iEEMW0!`iFdf>fGa9*+I@LNzYW!qSrO3d#`;u-IL>a<^1Ds=F(=gGc zjRc2GZs(#-t78BM2DnmZI!_60(PQ$yQ|l$x-eYC$*FQP~o``npL7fTLy5v{D*k7H& z^3UG?bOy{Q)7ic{;sgB_g@ctkTgiK1;5kKdZ|H2s!5Y^D8ju5MrN5Mc#Au z51q&riy0BLTVzze8Dv!ivuJn6qI@Y+Z8x8nz%{{VZ&6vS3f%9^zV8K)%er*!IMk4G zg&r1&$jV4AY`-nS*p#ElRMUKIWa^N}GVI29AeF5-A>KcDHS(H04yjH{4Soc@-(6y-4P&W*%2oc z!g|q>)CV4YbNOX+>cr-lN2<)WlO0m<)P!Sl6-NdZcBC&mv32hf7BshV;kuOX z_XZk+VNHZ~e(Ij#P0(++4G_Nup6{lb)Os#_TY#%?^rSL^vV z!FOv|xoGg==%YAecSBvyt-Vuf)fX~sy&WYvoo(M=2(`_3!g{$C^Db_b=myHY1zS)H z)N()Op*LDlgdsI14ly(U9k*Q@#qLZ(>>*V~t2skt?YXHnmWV!6`SNJ~J_38~6&hUa z`OVCMN>JLfKkm_tRDv;vhRYACOyhUu;a3ViQQ=w7_tB^o{cl)3IjE0!Wt;4aCw}JX zJLhR$nriY}%54ky(4a~1VEi`E4%@J5jdnPZ`;8%?k zPrb=Y^V3^Di98S%SO(dvsCzazg-B(yIV2)a1vRZ^N!$r)#G!=i%K8Gx>BVK&LOhTnjK0I zqn1kINIWsyaC@S5?yC6|oJWVM-;3ar&7TQ~l7Y(* z9tBQvs1>E7;Xlw6LI{aY!n7^uxTRpw#~$~VIPdAq{O@ZjIAojCU=Cr-xQAG@u$I>= zt9nH@y`IP3)*qCgbkVuKhdXFzHsN7BL<}wr3BF!D9EbFnxr*8zlp$(?_JE~~W7jH8 zGfCFGbRBt5K#BGExuB?20a7Os-q+KO$%QA&>p}2Iia*I6-StzXE9GDZbb60ZZL9lg zxz;^NTC-}u#Fiq91J{gpYjS`n9}|KJvwhCTU_nc1%1ditV5 z4V7Rw7ihas#(Cw!h{EFVXG18QHR(vSJ ze*CP>TrSyg>!$MlU?>?L(6+hgAB|f1$W-=Qa)K{D z^xNEg>E1R=XmIn1o&wK0>CsPoEezYY2>s*XHoBf%CYvAooVH&936_eJPl>~=>#X(g zWcMwK=n=x#{yYiq3>D@X1lx(yD=Tvv+wiBiR{%w~EKG%cxlL*DqH=_fXp5e^3{=yU z*|l8M*hbN0qbxt*trJ~)2C=4p4z9^+QnoPR!_l}fwib<24g*%NwP05@pqPGHTJ|Z= zysmWo`V1N=5O$yznfhG&o;>fhdi*dW!0vqOVi66&P=>QW@!ONF2+ORH(U_-7K>k*7 z51wQOCbDIuY7c}fHNSFg4Hx$NrSl$^c5r?C^jcXd3yS6t!*nDHr4@&2{DRT3RD7R3~1kp#cqtxgWi`jyCEUnn&3T`%m}`S zn3BG$rt^o|{n_xzC9u`Yf@4!9G zC{AxQAKUfFx&f?!J3d8qKag;mhQ@bkY9q<(u&_#Py(Eyeu$Vd?o1Ymbfd37W1jPcY#ZL4Xr&{3FJE@rfFNe;88dfa$ni-aqUN}6vHc%h2^Ckuj0CcRmW!Paa7;O~w1 z4Ug+(V>SrmdQ&@x?nm#cLQ2_WPJ`K5xC!h^Gga1ZR?T@`dXwhafEiI}Q3e(iQQvsK zCBxpt8FdG~PD$MTD}(e47RdtU_*uu5!}X3mpc+UMT9B>#CK#hs9AGFZV?XWY;2z}; z{V7RkQB8HIuu-*hwq3LK1&8?JJDplldKXMFt{*c2O`qn<;i{R0R#tn>>9eaWH}D#_ zar`hbABQB8_sn3_Q!%^>w1 z7;^Z(q1{x;=lbwJ7`PG(W>`UnyOBq9AYQiNKt=9DLJ z%*kl&A62W|#Jz`fp)aty^J?9++*xtKp42)ufloM=_fqx*pf6aODqwR6BE}(H;lFL* z2=aDj5km!-{G{Rx2cw$G+ddnbI4o?3-eY)0|Bj@tlVItmswXp8;ffRaOCCI-@UspE z={MeW#Nb_Br`P&#hach7Iz2e7!+>k&6{K*o7lzJ*!eH`yuvr>`_2eti{z@w1W35pU$DwY zu-5n%@9m*w(k0ce8B%4A?{S632^E@BbxErsBZtu<+XP^ttbMQ^eHPhzNA+El^wP|t z^qzRQ@ZjXlO*!cH3}nv4mWfeN{es*5F$kjLdzB(uC(i}N`o1J=ib-+NscPbW@>U1R zhUJAWd|SfCWHo>I@*$zrcyO}qB5j@~YAmkWk52 zZ+Z0nlC9>r%hJ3DJYbe(j^0b@qVQC63~8Y1r&XC?9rH9C{INSM$X&`s%5_id_QcKI zmO?x$gFZq<1-h+9`*P$qFvyupvbKv)wL^gTebqYTV`8E`Fd}n5I+qV!)L$oVVTWQ4 z;?>c{)?@Hgs0%8_RMqWHk~9sHBr-(khfunaVCiWV0@<%tK+yWmU9JdBRv!h=CfY0FCFZjVxB=U5iVO zI(@0(9HK*|DWuTY7C`MZ^iHMhu%K3sY1|GoZa6^qck$UhwqaYrpXLl>j{0B!A|BQ{ z{zW{bW9$8`+Kw9f+DL5&EGkJsAHa~2?X+;`O#OMBU1m~<%GH~$t@a5hMw}-cnWI2- zL&YY+ms8;0-mcfU`xEvP2e#>xIZzzz~ zX|}L1G)U!BRXB{7JJMS7h^_#hQ=1ACv+*F95DQO>R4m$H=1fess|r6d;1x`~Q({%d zI#@x#dz=SOiS+E(LSz+1a6kDU@-SJU|8L~MPV~RXLtqc$|BwgOjQ=7JoeTdU57|cl z5Ax8N2lOB0!Rr5z2b+-pA`bza|3e<=2@YG-HhnKiAR}%A>`RUCU~G4*7h5N>FR%zw zqcXm3*v0}^Rnhzue(4RoH-$7?5GeBjXbZuXRD{JaWwMNx!~0_n8_Va3*vTlSzbmLsGq^9tlP7+ zw2pha{HBF@Er+vNoH9cNP3RZhWbZFsdT=WY5+6O~m~H@fd5!7@#AXN__u*>40_r@Q zK9$(8gnhRwPFS=ZFvPImDQOnc+s|y#MJ9C0Xj}U;*Hd_&O{lNO7gN2Q3|$^xV67u} zt?xQ|wRm*hIwDdc_Jny%9crir0y=l+TU+}0GDkITNpvVaC%mMc$z)hLb`~SJ;0$v?)#|dW=XF^aVK(G)Cf>xg zp}7Gd>@v15Mn&#*Uq94AK>!XGXPf(VE8O&JWgrXv5eM!e~$vE?cGK@9oIhu1rMU(R}f3Z`%HDATu9` zQjqq{UN1BaKMa;{1(mtzd?6!Cn#47|mGI_-_l7+BYZJ?>{M6Bqy~Ab)(UeF5EsuNc zRd_SF*=Oh*3o~N1d|m*m36Rj3eW`IXCVt$7{buA;Ha@5y zo%M$kDYhEMZZas!!rtZZHB0TjHIh&y5-ZSlOt7Go1){f?uTS03#LYN6NJqpLw-k_< zO8Dq%@kov&43+k@EM;Nh!H{qb`=UYg0i#YV1BK%nH4hiXC?ZMZBnOJGMmwZO^J!vT z7fHUr5Np8}mg^uj=D_0VhBNs+PwNCW$?t5WK~csC$$a7O2fwC9Ji`(8O0-Ea4do>5 z4YKVre?jHK7rR#na=a71EfvMt;|qA;Nv#&#h-v!U3)Kqw0e(Ao0rnYER22}PWfh1= z$3P_cg9Gb{k)ikS0OKzF zbA>|0jPo&_G7)p5F1l^c)L&sDDMG~pe-Ae9cUHM(Imz}s(xr1l4?v}cHQ;x=A|rCFe6g!HptP$A*oT|HEw1hvrO zdGA@ic4w5@XpSdmYLR)PyX`QhN&0VyCly&`3eVOsiHPIJ&zNx`%7=YK7hYrhAT0hX zJq<-s-0uT~S#GHZRB%x4-+7aGur&xW+=)*M>NMwk?{wBK1s4 zq53B-PU^Rxso@UsyLcfWi>NcSX7Of+J+hcf9aji~gnDS;PO`Y)TQeAp4>~`J6MXEE z_4=H*%+V5hsj84(uO_;d2OpQVg7w8$73B16g2yg$j#?z{{pU-mgYEGnVljQb^;;|u zj`OkDwqs+7`|oVYi)T8C_U5*Cfmq!;)+BUxL~S=j3fg2XJQuK)=8FQ?e==L*zd-b4 zs+?ul=KrZWp-&4L9X~-AmEr4wh3|R7)DBDb+}>d{aAtDsF--B2${0DM?r>xch0@}*1t z{`EBj+Lp|{Od`e=b-e#!*SUNzr;8VbegELUo3T1;xEO~BME&NFJp*vAcDd3ww^5nK zCKedu!Ep52tYW(U!mK1~N^|PVi~6JQoKZhUFeA zWm3eUu?J-8%A1-v&Z^Kd!Dt6sR@9WVF?hJN($5(38&|Rc{g=B**8?)XQMbvI7IN1B4j9ll)Jv0X?|| zlE;?a$`P%$b?j~YfD0^4%@Un(cXjDDJQct(D?h)+F}iO4`*~VV0eaV{)tnbMWk1wg zkpwTPj(DAj)MuG@U^NpG;;4QG*3w61oqZ-ECar||z!a;MJRU!*Vk2tWr2mHVnzH3M z?;oshBHvyLS_>Dlc(p4X)5szEM-Rvr0_U_G_rTHizqgm&Co9G0yH5kLM-eY<6cYT@ zu^$a)hJQH2@#^~-uJ$obC+yDH-zkH7&Ayh8C01|HL$1Cbm^O&p1VE{Lsiy2;bV?N? z@cN&6L0*z0AZJ|YMSLit-`0ooKHbF>_Gk9_HZ_a$QPT^LRn$Za8_ghmu9!;=!A?|E zokeiZ=q!_0hRK>rBfK@QBcsIQ?joW>zmx#8@HFu7oA5K+8WGw9^JFYvqfnAmp*O;z zhMj?lKK4m!(iTf{e(RM~HPPhBD+nuA@t7DuUsRM=?nM6n6<*&}2`U!9sQz*f?FHI< zbHB5wu%|s6y!)vJdHx|383c67WTMQ-x6Mm2$PPdiXfps*ZrK9T4=Y{5TjuLzal&>x zu|xmD9rm%EC=`AE4|ibqDf&0=kmK+!s0>W7SFJF%4Ga!i}@c+PjmQm;F~oJL~Vq=y~tt)>c|`8YyaeE+ynd{^q|T1diq znrnRkW`3hvHHKy5$URcS8aDNe3)+N?|EV^E?w9-nl%HoFG&K|zWRzMyh4t7HYW|R+ zGz-}d{z5|HodKk)Q-<@OHJF>y zw}+DyV=pV9=`Jc3|3-GF2Y^3%gCBDuo`s%|+w&gaQnqK#FPVsM$uV@-9MSXr#w+C< z{spw3%rtNwHwgjK5(Tx`RT&R^ewE$+0xf@rx~GQ@b-uYUVfX6v4*;9+$N*n~8cVa_ zEZtJ_!mg$uLGa9HM&PmEZ5xV)U0sVyT@+GQGmWE^PrIPC7fH8#9n?8H>}YUDlDV31 zcN954ALR|&sR@G8BTN+djPg^4mGJvysvu<6$DMDT@0+=cqjCjt>oH4iDATBT%GFg4 z4WmT~WG0~c}N zNMi!+D;dl#y$o_sTX=7Wu+#3!48E;m-}Z4Vp7s$lUkuczUi1-+^Z;wO9i)@!TUNZ^ zUuJcw**)?{?zAKI6Nz{}R{Q}6by|ZDejf&R&q0}}P#$rA_+Es$v#wqWi!YLJ#w~^a z%}e>VMg|zNwn1D!Bg|{imCTQ6^I~gBy!Ijb;_zBD)9Dl>`m6O@>oo4~^RDtm$ zq*8!)X}f`r_!`ZdJQOJOIh@$@j8l(d#aO14a!p@WE{CKL8TXeaxc69TPns@rcWve; zmLr=_6?tpTlryy_DL;SJOrPs2CP5&-WyuL;cxhxW9$T{*=j2IX{()KC#B4dRU^#vH zp)1NK=pDH7SxZLuSY?Dj!%Gp1>(7PYL>Uu|^bhD1$05G*hEp)`wUhKU_`cltP|3c`GIM?yJLk0-x*ot1X$Rv-6dcYO>xV3AzzKGKdmmZiqGOdfC{ohWU?B6Y$ z6EiiM3ya2+2F7~wXd_8<-PFb!xmhkO%Sb0H@MnkEa&a%Ni_%(#P!TXe>1$Xq08|yM z^D}m>#kUzg^ehjodv(OXKFHiR5HiEwgab5TF|%#*Fr`_nvj{ttz2oYEJAIPk#tYrG zw-r3~Go=L*gl1=Wb5T7i5VJC=k2wX$Ufy6-}?GH3+ig#v{1hl;L8Sb^iC7oAO4?0vP2Gnxhg72%Zp`a6R@scy!nsYh$c(Rodt9FE+zy(-uBvg%vH*3o413r`&l>8*H?5$|bHX`0$%=4Nvb~AM65`l#0_3B^hjw)5M?QKK>Dwgr6L!tLuN%2?8LNYev*wLsIxl1hi`G^&z zyy--AO8kAA2J&vu`Rj1_)Q8l(&oD=(x|hc{9a8M*`la6XnUVh+w>(d=Qn3r~a29OP zQNvnWvcPR^(;kf^$8DL=y`w?t#K4gb`&m$=ZBEJ;nZF{__D#`eU!PAfs(M(ib=HTF zOJ0`Y;jTC=&l^tBM|?ASHUVh~nv9TC#6&L71HrRxoqKJQXXe60lYVB3E_nkzWw(Hy zpE@=|>qa71!XocT0$AoN36(yE`50|77cGSAXHaQ4nQ#f>@sDb8b{o1dcs&tyxk+#r zF>)WCMRe6{=5a~Jnb_$c&$Md4@|yWvfDe!$+m4R&8-YA5LA>K_8>Am?49}^gZW<89 zSy!20@NY(*rF;QjEugP@9lr@d_1trN5-o-^_w?Iax-bEL89{H6oek>0jP^P<-isHc zpsMaQ;5JPZaJmK$<-8o7+>t}jVZ!)=3wGCnU5jlL_5*|(Y!{+iMV0U$qBdK^=vF$E42kyUx5vSXWS9h<9)?>Cmo zEU`pr;+LqUCtZ#$u{fS2Dc^JkAr^n=(_U}p&aAy5<2U8qIzp%n52!REEx^<@3BZw9 z2g6a`abhz1%7dv4I(#RADc=IGfGXs{v78X@u!N3mX-k%%AnQOP-1&kNV;9 z4rC#akdI7wun@q9Gle0M5cg=MdpO}%R1BSMfY6fYu?88}%t+2iMKH@6)E6HXZwI}H z_dTFLTrBqp?)FhylXFU9oDc`P_$y^a7(fnb*(oYd%j=+XN4`J#Pt|}C80u|6Hu0_o zSU#cPNXn!(J;6xsn-2q?See7W-wY3bmB_2sj7eV$z+X1wddV^;a!c@Tf8?UF8MNeF z-6jyTH_1d_?1UX!1wfPeH=Yh#8vTkh0#8h@3-j4&?%C`{@bS_*g(aV}SxQmPSo4;A zV3lNt94y!=w?Ch7z5jifdK3m(&3YUuVyzeaj{Z~b%Plp8CW&FxW0Xz1PGUS>x_JVh zJ#fnJwgjIC7ax=uTfU<62a|3>zW!4%df`)3lGO;PMRC~5 zN!utkz`W2P`qL1gw1zK4GHWidxL2k<@>R&=dromC5rVLIzmR-t(Pe1>3BuX&!xks; zM&mV$eUk5Oo7H9R5%eR3+&G^j`7tv8;D7EzsNAHP0-5shmg2d#sb&uf+>JeOWsd z#$+Ozt~uOz|I;h?Cp3Nb6J7Tug#WS+xnw&9TUE@dBZ?hUVw-Zf{wm34;Wg&( zHtgBxB@iq)4tV`pC;Sj&GN6G-$@_O$xjPpqmZRxi%FNeWkL9{mTe7!UGLsQLs0Ah? zp^)i;AkrV@mTWnxPC;Fk4|B@2yE}$1Pc=I;Hu0VFk$hC>A&LkxMAHOmNJ~fOVBcK6 z)Y}N1c$Hwg*wwXn1Hmz z%=Eos6J52U_G}dD8~SRSl>*0e_V{g{PL`Oqq+8&h6tPl>yuRlZMTTz)SD0J~oa6l|; ze8d&_HwFXWJ(J(2XPq!VbQ(|-cVkbP1fX#hSdZGBF};BEav%lXp!y_wk*?{Iz`ffc z?$eeX-q-kIx6JAHDadQ7pkfC+B73c-4i(s7ZZO2l&ZaPMESc;hYG5tR&LDRQ&RN>{ z&_8eH%9peQRNGybq56K@|6w1B))zte2Zc(*7@$~#Kqayxo365esfEw*^4y2wQs6=) zvaFG`-f1xpPWAW!GTAVF(>EKPjdVxlHZSUdjy9dnomCAvlz~{U(2o0C{yrC*>`lIc zevX!RQG_Mw&$|&SuH;@wK_TDNXwm@C8}B{`8o&mXFLh`_>5YXpR*r2{YsKjj4w_KV z%Ng5@$9MWP5&?YovH4G0;&|#bhEBBpmfsug1hG!LI&!d=6Ll$vn~ijZ{PBzr`yg$$ zJDa=aC_-pj;Rpl#c6K~C!K*1B$!`6t(z3WaPR)0}YiAXpOK=V)dV87xyCv2=_HU3) zjXh5C8O$SsLB~1ytz%}2e8{G)sZ+<~JqId4rBJ^os3E#+fkpgCK3d|%z@^g%Sh7dA zv55t{4)wxpxkl?=vF0{m`lJAk6E$wm=-+Vj-R@|#Nit}BA}qC>0+Sn&Ooq&CnXe3F zA!I^*j_nz)=gTQ>BZc8=vO0&I;$J_X8an!RL>qCp=LRY{p{XHPyUacU-t)pg{mPbeiRR&tU=oVhuuh{l`z z`{NeJs9Px@x?Hhf!*UZ30n5ARj0R%m817V8M(IrssaMxZC5X0<4#RYGo9W9ksxiJD=Y1E*s5?gZ{xA3d4(P5+*BCedl`FPybBRpFNb3OKD;#litGy1eNq0vUk zt
^DNh)xxCz=Af*W#fR^m8XE`-&-ix6}0V}n`P`;OdIWjB>jbU{U`;e{J^I{MNGxhdD z0c8)f8Jk~_Qo6+XbLOJAK-gh2Kk7LOADxv~9gWVM!_XIBMk~llk#Af?( zIdi2UEC&ypDvV8tZ~4z%$I%?n*qC3Ws9fvxppHq?F$&`-sE1@;Lh7m4RG4>M)OCfv~Sss?W2dJr*K4t zUD|Ld`rPu;2$z}4Hy0~zj(YnYkQimM^ zz(qT*KaT{|l=Tbraj$b4R6PdeUmLYlJnG4F59s)IERN z+#^kz^+w!9Od_dkM%&5cDFDC+lPGLyon}_W|H!_~<&DBk1|oKivm9+51ZHAc*5h_4 zcWBT`!F7>Znv6iFjp zs#ed)K3Q*K$yoNt<)=yaeaIZaXg$0uda@5+Wr1Y500uT>wb*KDkjrVmfPc{xYY#rg zEh8VT)rVkn^I^@vvjQuBl`}UL+mIxDi$xQ=o1a#ly#J#}G73-bSY|2h&Xz&ZHQ)Cbk8dR~pOg;`3%$^-2dCHFO1aeD1N9&rtChn6Q3c zW10tR*+PbA3*=%35oW#ls~Z4@vIES2fq-xP6S6a+GshvS%t+g3v#N%9*1B3P-7R)F z_)hCGSvdseQ0^@B)z2`<*|VaLi`j)ECIxSQ2+tv3cc^jTE=PRtwy`eeRWbyzT>7)F zQX|`GG5yblSaT5%m=x#sC?;(D1a<2r;XU1yA}Ku56esF45e7-%%U2_REw%=r*Go8e zbrfO*CI?9|5c;Xz#S02L5R5=61cT&67@2Z!##4waCNLV08qro<%{f`;FZIA&y9tas zfXFHSXTw@LeE%D4{{v$7%T_8b2A_B2?LX85O*>|j1bnlM)CmwjUS`jKsRx3(JfxJM z(_@B5V;ge_SbI5GaDIc}Nb85+{hWtKhjsN|N)!&BQEC;StGB%iXA&_+AY1f`sKiF1 zd(zKUL)B%!RwRlEu^8d(SgXXV6B9&MGRe(-H8Ykl6usXqrnPlg*U~O&Evb-5kL|6v zlrMIzn?c9+;~;`xzp{bW3|kayjwP%lvc7M@gOa}k;rP4B&zO#k!pLFaJx!v<1}gxm zfIjW_sNfUw{BTrkMNXh>$L-6HlhSlGkH58HPz=-qNo}p3>J(`dKhx{iwVo&Wg~2bj zAKF^dO7rnHj69XZ+FeV@ASz5@>R+#e&;<4T&Kt)&_DU2q68)Rb`O&^OeIVC-ld}wP z9XMDVK^rCMP|NV!belTU+6-}5ynMT_EZuAR<2kW`51Sz9q?ot!iCIfh|6oE>s)f}& z+HQ=Sy3y8Jn(P`;lX}OV!7=XeidJ_}xN$lxq;OWLOzp)n@O#)BzG4?gnh*J+a(xyv znKn{eXoF-8?GBt2H+{Lfjv@De>!K}XJ~J*fnfzOOpwIuG_V8Qqf7-){@c*MdFw|I! za^^IxHfSRkYUUC z7_N%~q6pVsY8=X=C*<-1op52NWf}*hAY6=2n`Hl5qL*0uAxf@k=naJ3Y5a=Yw^4BN zqa<-~cy{!t^2ZT|JOo*uTk)AtN%uW(N+kzad*LaLK`jIj;m4Bb9+8S6((NMDxxYZE zE9~!*C}tWsX#RuDJ|eVdAR2VX)uGh*9J@yb)DCU#Fu%*fk(wg~{J%~4v-}t}zs}V& zIH55o&+}?!`-$TtMDezCL*J^CKp0E>_q!g0tLg;4>n5-pej7R2=cGA}T@PN(0%x+s zGpb|hQoN-G{0R?%yg&GK(~R1Vx#_iz!Uu1}uu|Ff5FadnA~* z0F{NWc0u#kT-~8QT)~Qt!hGmNZL*2+k`P7GS0BH_F=aB1+H+{}Q|b6X1Rh_3$7}~q z;Ohmk1wGEb6%u@RU$0&?4N!CfYxO%N{!WrLv%3yQ96&011t3kQ0(C~&Sr)fuwBjyWp`bM$?P;NtG7gO+eC%{zn*yaU zt&2X>$~1j?w1!tq;qjLUX5MxfslH3br8hjSW&%Jrn}x`dhhW10Y7e(!P}&*%inlL7 zBwTQ&Ml0s!i9~o?M#zLoVHGb0(^gEMO7igm&T#yBO|+#C0pTT10%P{ChkZ??X)mLe z;Hj}RBKs?5&u8N@D$N|$#b%$vijm}OS|-zUc+?c699L(P=@-zQCH=iJBkG&*Bv$mN zZ~7Kjc?FB%&GRwsRXZAHaLhV$Ivxz~hStEEGYg?e+JQVB^Ba6iW=ue+FdEa2d{aKu zPH@_f8*?7VvUJgACbdQCk7uIt7kOrjScE$w;iZmL)V-t<(vgsA0t`#^e`l*w%1Mgq zaCle7QT(RM868|~!nJ^#hu5N>le0vq?ZQDP)?=V(xF_zxD_ML>W&_?mHdEEI0EzB!9W~7ADuym(W1~TAg4Utm3 zi}G3SiJU0;o6+>hYCestMlofX3l&Pi=&o&1QadoaKZTQ4UT&P_1n~lB*(A?+EP_w> zkGUf)+rz9g8m#0)?IJQ#^9uS$my1m%$?vI-U?Jkni#HkT9~DxQ>8^1nEvk78r4N-~ zz=?k&ejEng={gEC=;k#ZzQL_8MrrR4hJF{a&h;KZnwY)yM67SXvPO`i1upNz`?Ie{ zhA2bPDmak+n6`%tx_;&$YWlU7pI#5q{PpNgJ_z+Q1ZelT=X{GP53n1rdHSL;ec_8k z;5N9YKTM~`2;34jMpY%t6V1m~%8maADhbO;zGnm_^R@dSP#O9MEXeylonM*bTjBS| ztSeJ8tDS|2=^NM!LJLDwd*v)!*dMm12Ri$Hm;%)wh9soxMSD3aqE8W%+v_t>M<6c< zKd^kn<$mwd4#s0_~_R>^#R!c{=d%z`g#QM=zzFyT{ zv64Hgl^Wzr8CS!X`QDnB06gr?JSsdjY3`f7O#o!Y65-KvJETrTvOQc>J~u8!C;` zFO}`3(PAau;=nM;fATr>(yG2lnn9ue79!Z;sFQn?!Rq0yT>~$jx{SId9_@lNUUy!$Tg>Mvyp& zNw{YiKtj2^mgOlpAYmUW?&<*oHi;5UL!%Up57tQhcxMgq9Yn zyI2*QyE{8h^N7~=IWWomOW|!iR`j;_q)+t&SiqY?&%bRTJIw(6Za9677djVi4b0^A z6W^Za#eQ9D7uy8?Ln|#j+yEtHc@uL~6qe%B`x!7zx8JDiG2>01AEke+Wc3eALoQtKokTh~10fZR9zDZbKcbtvBa7 z5lZ^9CG|lDe1$C)PT~}#(lm}cbsz+(^oT0VqfZgAsR|@)Yr>z!tG0embq(SP*Sq3e zLbqOpQzoi*`h@ekjmwtqKWdYaW0MIy#+dxc1KxG0&4mQCE7&1dv%Y|v;}k}85H#>O zjuONIVPE=hE0^huLHno$unZwZa`;i+m4zxh183$|t=JWL4|A* zJwQIThx3Ki3_YQY*k-7GASBr#@p4Z+f&$rH120p;3V9zG=IL=`?73y*-iE*c$rZmC4-FM^v z6o`_qe-sFsT<8h~eL=x3TR|F$n6&im)p|4!oK3bp!+$Ffp8r!Itm=9HPl1SqUP&ii zo5U%lJO#_GmGjO3-02ehT#a&73efpI2Bg3o{p)G#wf0wFk%u2JU3mqQNUK`U1Rh)u zNtgzdK9N%AP;=hB*1>E@-z;X<`Yk)*#v~*CN}fhymbEgB>DugALQRNAmwC)veklq% z>2?}ie+H1$E7E{>?)U0r{%CX>DBFM#Z5S9gm)mRM#sIDp-$P>}Defw&Wt0ABzmQ)- z8ps=Lu6`!11B$^_&n;O)iw|QuA@R-qwL+BB@GQBt=m6`_C1*%V)i>bLa&r$E?G zOg$-+uRyp8-mc}xjxkuODIv3gI#81g8H!(%XkMXE4Z|c-O$%(m`OJ~k`fd`Q+>k+6 zk{VL1P1uv%P!nr^ZrtU0lhs2R*LpvS2s|%^j9Z!NnNxv9?xz(D#AnAMw(frr8vgkK zyq$4(5{L&yqE76}^y%=6`pcafU|cf#>o@aQg5Ac2$K|-@DMb@NKY9v`^%O+xocKJ{ z<})04F^vIzlK3$3TWh8Q*>J&X%W92eIx#F(Vo-L8CX1*$_?~!`f641P`yK-<(G0GI zCzR54@;$X3Q6*JEKwH7%tGxJvCrnLmJkI~8yYW|*h=Kgt2zZJ!0!?@_{BfZ>1P{~) z|Nj5S**$eSi4lA~8r(!!5+qPY?S#ia-ZQHhO+jerlHRqahJ!|LN`ToRcZS>x+ z<1{{+`))Qpkym;TCCQ-SvJRYg8Qh-tuev5L)~qdUB6}89K!M+{-pM%zt|^`R zW~gh?wYr&nJsAYSVH!tMOST;SZKq`8ecypr`Lg?LXfq2M!_s*P!&;TQ0~Jk*KTAF7 zfjl=QEuL@6oUQM0uTDg30;{QCNn$VBS41S@7QYK`oaor)6J0d7~&&& z!_mg8`=~-1o)iKl<&C7Tdr2s6oKjve*d^6Y?9wEOI9=e91lGHMD7Okcb?S3^=jrFe zZR^dzwaD)iZsp0F@dMI4Ox7`AQNQO;w3x_(JV{S_gpCraJ@R_nT2cdX8#Auvpgt{@ zpItGOz0k5So;d1Agh&$c!7MyT$G!mOf5Q4vBrpIiEbr1-Zj{suhbSi{8O z`TLG6m|p$x?KWUfa2$;YsJ{H-Ax1@T5+R~A^cEertA9IFt+TE54ye{Wx$IzeG6tQ@ z4P_+r(8D1)Hosw_c)R_EoK%{F6IOt6mRi}55#Vp9iUoWRVNy6nnCgju0QQ@p_9}}7 zidpm{TBp5%9wq&K@YA`vG!Tl9KDv*FoH5?_-cYo0CTc826UtMdt$53L+0I|6R#tf0 zmSn5)<`f->y{DJ4p~C=PQlMkpl9w@p3gMgg`B7?TMyEJ1QFl)W&_WF^vTw`UBk3|uL`J9NuTu!AE;SreAq(}e;>#xR1ll45Sr`5!L6!a?d5^^7r0+G0lNIs?PG&x3> zX}!J!%xV>z9Zh7|A^!+Vx!`N7#rBk}?gs3Y!0ftpJ4$Jz& zVYK@(tYTNd8Abm&?#nWmz%B4&Vivs;`>m#ix>wqf&KeqTL6C8!LuSQ5YN{j10oc?w zRu#eVDUW5j`7`ipbhZ)P`?hZnJ+0Z9^rDKl-EWy2ydE%d!0_R(2y2vmKU?IJ?3ky){A8u&ak0RY(1 z9UIOI{>`Pkj^Dul#m-B`sh^yP&j;L!Ii1$&sdrmpIg;8jTF6**+ZtN`TZGeUJDnj& zKvwBFSzRL~Yu8~8Ps6y1P7m`u_HclcM!eego)`S70~N&=h19@;v6swwo>ZjJKDPg> z19x|EIJKeQpi6mC_A8DAudHLkG%=P&R}^tFMD%Iq0oZVA1a%V|N|lMHq=WLsM|F=C z2Amhem83NI3?JCf-4>6weswS%BIa^kA&$P}l8ceKK0eFW@o6RuYLK-t5~Xwbr|7`J zyTjnm(7FAV%e*L8<8@E zc+Ef!Q%v94!Q+gm(V~3UghUe?z^dbC9G>hn!V|i=+yK37##hXurzR)?lWPUY+}n6% z$m#pdQTXC)f%9M|S(fN>s<2qIA#lyO{bm#`F%ElUQODhKm?IH&fLAGf6upLiHD<6{ zDJh0`i^%GFNMY$cAVLNt;#yQZU9mF|Xm9QTRpRCI<$> zMO^SLsio1I4y;DN0)MS=a8cTnUyk@pO6vYj%2rb6t*13lM}Il3wyfbo2N8VuR_kTD zv?rSE6KULG4LRUxm!9V#=sV!u2hST_V;!+;>w*kQ31=;o0`|iOhE-vw{O&`LzlG8O zon-<94+9k{G-T;$zA`$}f=v3wc^IOXwik)hC1JW+AE(56Yl4!PeP*Do%vlLIoCPHz z4MmzJJbem>$E5TmKct(&v?=I~kRr|~Upb(3X)N0d{13If|FW}tWMQMh)k4;ZGNK{l zA#h*#|6R7P?)|; zMLt~lgHN-(+`K=*{Ne?lY*It`kaG3p?eG?D&xS(`>e;n7%rAd&e|WjA$X<)q5b@<* zr&pAx;d7|-YJ&ztxG#wEUoM|jf=tnz;KNsS`shGo)gal%xD{^so3jpQFhcHCm9uB#Z3NbQ(PGAj?7ezB z2EU8k6=y7ATW(1b(3;y8(QJb4%|=#Xf5u;6TZ#N~V|z}EvYR}-dSL(a5qV>ysFI}A zxZntXydCQZr7(As%#oe5kvbg2)M_{*g+w`jA?>eX0>w*fVaDCbs-SSED!)3y5|mc& z`CxM`Y9?Q#gE#T63}`Bi^Dkp%E)?Iz-WK-A-_xCUtn+<`=rCntk1h`<^l=ZseTew$ zqh%t+RY6yw-Kp9#OTJ!gYe^B)uzPI#IDzVL_+MkG`wtmYu{lgMO9o>0@|>xdNL`0y zzcKGYu-LSOP;{P^8@n={a2ZY-y7MG4ihQ$IN7EN_^q(Wvq)u6-V#c*bE&{p@g?qHrdl9gIfcPrg5W8ZLn6;2QT}RoCM%%T?D0H&odN16o>cMoh9ECy`c~?1Mq>tKuu54X z@aXp^nP5hk^-nTE4zUL2tiA&F8K+^u-WCA2A_kWTJ$&8EtCKG`B|C>w*G@pLp zcIZhC+ok<{*To?^-QH;wG|T}`tZuotkct+SkoVzJ*7>&0eW6O$O!8yorS!eZQfnCu z-T;{0Y7_CS)X2sZ(C0wZYJ`#CI(2>6Y;aBQ2r;0k9!8AnX&pu6^)f+A_&X`VLomk& z=BwvN_O~6%e}f4$vi}!Mu;7WR`UQ?n4`5ia2h%)4mRRlEweoZ%g4kbnMRHZfByjv1 zOkP`_KdF#Aw`_2NhdToOUa3EDQDT(t{Z}u6?!UbRb+XYQXllT}y#&(#_7a-bHUI4; zK*wy5{o6}0|MDTp0^+1ck{lw0@Bx+xIPbaI%0hf`?5NjP3TqF{>)G;VNbF(O70>(v zCvp!K>2Xhtt8s2c{T2}QWl#5TWd7b-RXZMslNSAFOl%dLqdvEox=7EX_VlHb+#o;W z0}B^{q@SS2m8mC-N_?$y2`wGDTgU?w%?!_Mw~4X9zGU+DI#HM;SznfT`|$+>FT-`i z<1FB^Ouu<471%L$KbXkSx&T8&-v1yw{iO@_;XLhK3_;| zq$?rO@CqAI|0#Wjm)L-Rn0rmXf@fM<_Q3%1!e}+<^BTzZS z9h_Kf=Ho7UVVVlg@e9v6&>PO*4QoKib>92Dj~$k3i_2KE!DB4xvS+%_hTiSsl0QVJNL!)WNzfWO2aK-h+Lg-B(wvP%d^6#eDq@_9$j?PhH}N00mg~5zrP?Q9=yg zOFEX^rf~eO8fVl?Be#)LFqcSnF{k$ebuX0M7HR*TPzlhG6Zg)gYP>WN+U211;XQ;n zTTxJvie`gQa-cj!kcWPR3*sr4qc93u)6WPcV~IFYN7lVGH47B_O3x|dc=l48gsr%9 zlPt;p_&(@uSLM|2u09qAv;E4_n*oef!=<{K#D-$n$0vh3?u@&P$glNtnBPJc9zt;M zTl}G3eftkX3M(x*;H1;UZAa!ZkQK#*Wspi_^r0J6%1)woPuY7c)5-IIwUJq|TVqQ? z0JGE#MMjDL3HlX8`K4Q+>$lZd`{BEpI)R9JjU&+v(U9D44#FMMn*La5AWq_M8IEzk zqJgi`@PWz2|(i*kbDo z_f>+GjRb1M;vBPv?umotA^1jSzzcbQFIu|wOSLw(-+eL)>VtL=Cao`6Ya_?c(hy>Ly>W%c*7{xe)&UznF;rIML+)o5Tjj~C1n1#Fvfj|H~ZjfSY zMsyv38b9e!472n}q6;I+GK%wC-9VX1a+0zaU4lQIoBHi$f>pZ`&G(4ISVF*xMk_u)Lq=mdZtT>@jY@g47u4C zAC51&3@~-g3aOufZ~)Fz-(ru`iXurK&M1c8lS_J-SBRY)C z);a#-uQ1ZZqGE8jA`PTh9sP@YO~Ww#On=?ezz{AuHRh zi7PVmb;jg*(vc}ycuD^F*Wq7z%-R#qL6t#*FMyMiQBfI@K3|8#d|?frMLZ2{VKnOT z$m1Or6HH}&g@=*~M_QG+^*lZKvBs*YPT}h%|Az-p!y`FS%6fR-FMdh28l`<8ZLVDG zu>k+7xtw25_U$aZDb(I>Ayvq<#L&zL*gT<;9*m``d~GZ%7iT`1bd2M$lV^A|m#r)P zvF~g|)sYg_3DVG^l~;)VE(i!^Lval)B@iiU>r=2o?v?EgZ0HF~Y|ZrAHHT6VU{Fgl zWOB1-pmiv%KyiQGlU@`c)qXU>>tq%_7NAA+V~I)Zb4 z>T6;c*tSzkpMPsF7`1a-s ztW*2rmcV4{bvoA#iI8G?4Nn~7+)g!IfS!9?@jf%efD-?JYjI?&C#FWOvN*b+W4F2%jho; z@vBjMvd{_m@?^8lgQ(9Eb~X#ngnw~X&&s=TFcEIzMp3)O`?5RA-v|c=w z{ySTE%|3BhkURso##>TJ6$&aytS1Rd4-_fh=V|&VGE;O~HHT{6;Kf>6sN}|sv`Fgc zxnOz(7X|VB3iGYX*f%i_N(7i6YrCfC0R^?e`Sps~ACW@>hI#(m-V+3RO}t+9O*hr1 z9|97(@p2Yo2Jvv_JT*&ND+`u(XJ|3S4qUtij3vgo4Js3iHO<=LK(MfW}T0ErOY|I zWs+$*^#0MFVf%rQd)dn~cp1R%k{)m^E3!aKGzN;Y?UV5a7db?L{4^w`5GLzBxr9t%?3(Xq21^tctmWy zXzN;MR+m6^6vEVLJs}u?!1qxuMIqFRjFA{kKFEZOlnf=LK2<85&nQh(o2a`ak|Dl0 zFLyF8jzWC%ZW8-1kI9;YCnHaUeJ)b|x^*3lV=GD|ErZ z`&cLN+znsX%o(@+LWj^7N2FnDi6z#dFqf-tF$ALkBq%Qod>L7&MDNYEc0aRWF`b#< z6J~03Sxsi+cf{u?4y4tJ!(?8YXY>^IbPvFFCa_JV(?@~(0?34IuOmPc(1XK?N&z1n zr3<2!Mb+pV2j-7%nlJbjR>6-yp9s@iWptZWeeLjE{EbAH~nH0>=78z=*G6xMpW z>)P8kksy{h*6OT1C!%5YJGa$KR3oio<{#GDCg+`v=Ks_Kzb7KVbsW$x0S}A3uiPrF zqLd@Yn{LV>Ivd$B8^_NdKvL-=JDLutI@nLA!r7efjX85cW}5ZHa>BrNO6n+?0|2x- zF?-0I>nlmxkbb78!k4^CnPY&LU|N=Ucw{ZU;+7x({`~_BYjwi^EXO%%phb82(c`Pd z&sRt{x~+yRuyV3kMHtkocw9wjsV&9#jI2B3gk7djyW3RJovtc6)04cxRq`MpSQQ!x z(0QbBFZlTUG0p<9>aA#(=(;N>G~EeH2>$`ayLPIa^pFxa(g6dqv0WNrOfXlJEH*|d z7t~J<;ZuyU6JAQhM{e&J4GjiMWkpi;}>QT`2l!?SiVOV10~BZs#H8oY5hMqYje zOc?b&oY%n2IDdGc<}0{RE89YqvRLfbMdA{~*B`Wtxq#tROszakS%MQIGa=%DRNA~U zDQHFR3odIrGwE$g_fm_KFnT=4IWJzQ=s1EJO%d8Cu{2xlJ7n`bmh@bQ2nOBSr@v5( z?dM>2!`IS~2(v9`J8s{fGqDE|r{r_6e%m1;SQDk8())OiXuX)98ouXg453}L&LfA> zj7)2$9DG}nm@<~TD7>cof4lCJWoC$1#P(6G(U7X!=+)*$=d?GNNqK5Q6y2sY^*^5k z`Oome*Rf|MDL9+u9%dun0611~$L zbTgQUHgcm2J#%T)`Q3$ybhvj{nL-yjD~7SiB%KyMVI<>iCOo2bi-GnLuPOmt_%iS4 z$gE36pfpKEqVtuBf3CIa+_6Ze2s=K`!mE$rcIIaY<38bCWTit9{=NPr|EAvCm!>US`AyLg0A; zDE86(k|j&OD6Q~*7*xuy{$vcUQ!io2hxM!Cu1$Sao3NQ|I~En!M2UK0|_ zYrH?TkN1V+At*a{oh5AX$QJ$bDfZ|)RLXD*3vrc-DUgFgAM7?>;~-_-4=3d%o=_X{ zT+pr9OQs%_OEu1>MQR#;4b(xua6*l4IAqJlu%5rN4&$PDFeCPg?K1kJ%u!~!FcSmRvNIhd#@Ou3rM25BSYIT>i$ed_8X*P8&cLBMf~~l3bT;f%=VU{ z@P-n{KD!!Rel!3Rxrm9QHU*;&3-RYABhJrxL|QT0hJ9tRF%S74MFUp+zz;Y)F`=ef zR8|A1S(NG<#9kdRx;LHZ#-a#d%e{HuT;+AV44psH(gYASl+O%|(r=pIctwuWBjp^N*0cX|-96z010jjg{&wAc z6baUgBzqYow+;rWFiG~|{^PnA`Iu5?CZO$VEVF7k%Hs8@|8d;|wKG)*kvw$7=0&tg ziK~BITEuF!HJ|SHJh)CpfXyDP=D|1{6^%-rPN4Q7Snk-E1%R`t>3*}&sSR8+Q!K~* z*LB}*GTJYWD&WA5Z^V2Z+?ye=8YlhNb?^8;*WCmvhw~rT9r0h+-M(8nqq@}VZ`Ymh zB`SRx?{I3L5M~05b_U)PjBSFT)Dgs)kr1}(4DGYUk0Y7vNgj{ck%E&i6G^pQNSdg4 zw(-K5^EP28TUIaKvfvNy5Nx*1r|PG(JrSeiKcT#}u}sYB@orF9L|sB|p4HiYzP^Y; zfw8lk>EO0m-z5>duB#}ej^|e*4#8{3DAy^6s}mWnW@4U0g8j`Q9dmMLyu19HbXgt3 z{AOoq{c0m7LYM5?7VyD9^n8?4U?{71>GZ<qxnSLgFJO{4jqVwd%J|ap?O}Mnc$TD2A0PU??Y>4R zXTAC&Fwnaq&yLe}%=<*33BQhGb{8WKh~+$=DSO#2V%Zu?E68MyplE-}MVZ~@;?h)T z2;aj^EbVd!t;#tVfBRUo!BdUOs7(yX?)eb0^bz;2Ppg&XaK;l1thG+UdL+o^{H*sS zxsCheQF!W#UT5ONn~PdlxjiH}$%5bWEJ8om;<_oJ`^Av2sz%7~Sr!L|xdRkVisQm| z?|stmEHntw7B$q{U({b(z8xD(^hOW)lI_fzcqrvT5PCLf`H-&G{N!K(O^nfMpb(L` zr@nAC-fa>RM@^Oj2eBC>59U$tfohdKX)vZAd!N-)muk@lh%28(*-5K`K+}kr9K75_ zi>9p(r}5UIiHA&rW_ki5E=tP1GS@#uH9viA@cwJ@6Rz-x4oK#EIYf?aJW}=N-uB~R zliqHX#I&Cr@#_QDG_I|p$pj9Dv-NHfgv$@Zc-rt7eSpp^5Fq~=XI3HT)IcFY8;J_I zn9@@k{724r0fGF+4LZMt6ihX8;yZ|bY|jNl{1l4ZCZj7x-4X=-TlnW^ns6QpKcf5< zpLW}zgNa`9yTJyXz#C0o#d_T|{wVxW@I|V3v(rv34|u2Q`{5=dzBdIZC{_4jvWXiT zr$Pr%8}x_lobhU1%QVmgyOSZO#N*RTWb5jSjhA$X2z-R1daWjXv5jV+ot!p5r-15t zGMQORhGyYGG@R(HQq}XQNarXb26d;^gH1ans@6uC;m2be+42~QGiiicHY0SbXf6lv zL$L`4;MnCO7SQ_zM%SbnzW8$D*7?J1$~OH*9;IaRL{*l%09lZ>-nOrpR*&%?bnem8 z1;{8LHPE_nv437?#YFHI61vY{0sxb7AB6g(O1)czU3PN*v9AEtmXM&*4{_!7HurSD z1s|y)1-aKa=nyOXuUiZZ4rRLQ{&ks{PhUP62**(sPN|P#X%%A7ZbdjERU2wBZ`S>E?Id2FWB+6APFz@Rp*})u3;9q)&`gBj_O|I(Le@+_` zY>=qvuoI^)8;cyHjFbCH_Mj#V&~b;Rl#_h05vC?0yYe{8-&fe1_lihx|IA%PBGW`t zc0vj)&f>yWuLweV)rneO1mUbN2IR;_NR{XulbdLt>P-tBm~1~wkz6=RJPWV$>5E=F zC+H2*1A3U%I3G&4p-`~9++?Nc7~Xs;vVgVDQ~HY3F1|YJ*jDxuNAeB@BukX)hp@xv zW^9t{1X4gx6;-*MCV+a?3EU)5bF2h0(O_G2(m=;y4_-6Vt{RtSvIh&3UYzyS<`m{c zgJ&2rCjyWlFSg;~&O)@8F`kcb%*@6X(ilk>muu>^)xPZchB*jbx5%&wwB)V3Di9uE zA<0j?8n>OYZ1EF7+V=>k0Dv!glzYV4aoS#d5H3m9svcP;6XC3^K~|jHn@e$vqzjF2 zL}FJf)|}IUfzPOxHq31%-%?Q|JhN~Mup>@=cPoMi4x4#)MP5}Xa`TU!+=HrCo*9Tq z79WYXwssTLe;!uh+XX8=g`i@>T#uyqY(8^4>1hpE=l}TEyODfu;T&J`2@P6l{uQ6h zuFv2@Yg)rGX-M3<0c`q1jV;>vy^}xqpg`D}i-m`cc~(c=cnf*pb3mxkbxK$@yd|gWGW*(gg6Zc+tOjI;967P!?ke+5SNQ9buW>CK)uJi66%J!sD zzOcY(a>w+YAKyZ_JneP}iSyTHJM2HdxI&%jWTqvoWl`peY_vSim{_#=!}&h6E?*
yUw$(!5_$1kl;Z~aAcfS6>w%LaaOJthfqNh{AaoFI{g zjD4FwW!V>Vpag$efC3z6Ia0Y3t0Z{koT#k`5Ryk1SiC$eexLX)q@xb&oh*7-BsNh`An8}%Wye_??C z{o>&;w9C|4!v3HHP8YZbBx#hOR&|n1tmdWTz;oi8aF>r0qH^U|@+9i}db$~n*kpM< zBo1YPxa`5bUPP)5FUD~H4BDaR<5y|j8mB>iHsS3bT;52_vyDl4jqUiD3|f%ub3O(g zqAG&E$&2H_@!2}Y=4zn#B5&jAiyY~^9%N?VKGkM}XhVOA4x7JEat5zu4wa*N@ zE78e7a^ulA$=nH;n>;RGvx1=Ecx7BeY>&n{!H`Y!1gA(fM-3*~HPAuK;Yd~9(x*YE zWzd9M&&_>7@=(2!~Qj6qgovMg6#6aIjB1XQFwMJU~Jb3X$3G;i}rMo{R&RJgN*ln?&u?g39Xo44t}CL z_bmC0YyqVE4ZV$f`%v1^TMt$k`D@p#~D7*U|8c|@$W|J(VIyJ^^$dS z_cWZy_29NxzV9l$tWEsTJlTO|6lwsd*(`?N|rS&I}B-1=JZ@y7~g!`}xUp{6viqZ)`O@b!hVw^^N4ta)- ztj4GbThBctAz_t6V;YMc?Ts63yo=t3=aW$eM1nK04!$D7kAlmp3E5on?E zUWWc>IC)f3SARQ?5Zd`$V=F&lwZv~LSQri^9&OZ52(H@WA6?v@SQbIC+ue^b(MD4$ zHK0>-T*}{ZL(6M1>^z*d=S~+Z(hRbkPv7Yd{aRA{wr6zenXqP?IF<3KVI^~#NbOf0 znDY%PXPb@1pL9xTDT(#x!kuTGMOPYvWj|}Rav%}x7Gs{p<`|a%Ho1YvLF>>$P%NPR zolgSclj32T8oNB32Z!Ox6Jb2vmkLg-v~52=k>3!O9LJSDB%E7#ibvGk=+#Zlal zGQ+6!S)v{|k=_cLB-WHKD+=Ip8d?m9D;0dn&KfFNX&3{|!F-{Aizx~YL8s)9TBZ10 zZN)-^Q`+5VbQ!23&g(h8YR0ygQTAs?)Tcdheb%h>{ipW3KiN4euGkDaB-KD*4_ zXfHa$|5j%p2UrqCL@)H-iQMx^kDbv%nL4ptJ^3TFhqlt5cG zV;+^nAKQWe{=OK(D{=D}9oE;@$KRQfAnWDNLk_rAObDMuky`R8+iyHNTOl0lObxR6 zl8ra`;FVAoLNr4HDaDq*1o$eajDPo-Kqe>%V{NcMCF)qgb$!<8(J%gN<{A9+>D1U) zyrFuHXh(J=Gfq!|k%OcVnJ`DvQ;a6jJSW54?BnN7s$Umk290F6yrf+MmS$PJiPe~^ zur#$_L3ce_eiI+nT?`oC6|vtiWmsBzCbPU}!a_AYz^EYXabUVzqKSy^GRbwQX%`SD zWJ8MWs3p%3B!-nNpQtVH&hjXaPh#XNHBm07c1N~cFB$hJ@*URID?%;6_t!@+JW@E5 z6Zlt(_reMMM~Vjiygd^?w1P7)3pA+B`g*;B5-XoD?W3mqNB7X>Rr4(Bf<<@TEp<#2K8 zQ#|oNuNV`duIPOKreOO%O?HRz@;vB5NN9_~YZN!4Bdv>&6FRB!wUI$y)WmEC$^yq_ zbn@wdEkm^U74cRGe7lFU{Nm?AFYQG6(8J&ouOaq#@uduY)EsHgANy=Q^6HQpeZwDMFjVuGR*Va8e>?Hft-gOd@go0m;wRyr>TP0pWenT0H#Bp9 z-((&2>qH{hjr$%sK2=a#UzJU@4X%{d$NUrou)EtIpwuA0n}KNLv_4^2n%}5*>rxXg zclVDCCL$YNmP<*&&)Zv;I-=AxtYdj4lrux%wUi`}nvB9Ib7{H|4SIS+a=!6D`e(QF z8DXU)*2}kH6ITt~?Z-(MZiAV7{Bhz%T&G6Ma2!9^!97DfVN3lwZUEVEZJ3(otGVW) zMKF%tp&aGVM0_YjKaR_<4?j-a#)!`;`#`Tv_F32Q-Qek89$98Bvm$~+lBRt9#rPlm z?{;f-Y*6%;1QcKyHIh(Txh|wn)c3v}>PObcY9)S1q9991hWpUQy5k&b>r5d;3%PlX zx`}1J3~{>z7#xxX4Jf9M!f1((3Q*=%@9?Y%X*NWc5%?y}lvz@zxKdpH>%>R@j}x!_ zj}wpiA19tK(euAf{8cb7k3e=;TdyW4Lf-?C#X&{&v+kVcv2i5N={}tjx^2C3fM>Su zcTEl^irQ;wL2u5^~cr|KE#DPAx($NmMh%s6t*#wA{v?IIy)cQ)p zm89h?rgaaS_EI{nv)pVxWls;Biavgq;(^I8zM z6JhXgp-DMa`GJMTX;sbS2|T^USfFn%A<|%?uOb=iDo=Q-^RY8enV8P=sz(uDq zkj;mqxdoE}I{&|%c&@#vmdvSqfNC}GC1~@)EH6p+XvQ%_$P0~#i_B(61j7oLvw6t|q`1xyP+Qfr65nR| za|mm|0G8@dGA_&c6^)&XPi^=PI_o#a z^a<)Tr?xhW&_*ON#S0TnNIaBoYo(qyul{WrJT#IF(bh2q0)qA~*_GCuGZDC4{+uam zM5EuQf!sI2O;g6l_2gB-Ik$V&b6?7>6w{QF#M1JFUi%Pt2JsPsBU|0naNBY|7S*4yLZHSb zs&&^b{WFfH)?S<1sIjasu+WomLj2M+_#gpfTNqJPwKJ7$`Q2W4rbC&^7*s-jrs1<}tgs=DyeNucEeoklot)?UL13`3) zHiSX~)Kt1AG3ZiR%kPxb;RwoT_Nu0-tm02YMa5u4qO$c2VQ<-@CiwYhDgLBe&>EYz z%cVQ^K2|QFjEdAD9;zMG8Mnh!9FWBg=|Ldm00FGqZ$Zw~hlCR@ zmT%v7@v*-E;qEbxJ{)M_#xs9p+;C+A3h`wNU(22z;O;GQllxiTZwy|8_!!iSkM>er zJxst#i98HR@L#|&PJ;p8?_&xl0v}5d$iw3IGSBYjIj^#iaY+}tS{HRHd2y`zp)47frEI+>zV221&*N|DnI>cs!Yy z!DwX``p!9j;+XHD?H&(`1-|5li2IIjY02IiF8VNli-rtuf$Ye`HTHs(bBG;3+2I!p zmn?s71}~G<)Y$zV28sXZ@uLCX%O}&pXjzFWDbU_kAVg%{0FYJ-~w`ufx=1*|jmP zL4MNANon$cur+SGneI*6% zT>y*v-Wm>#x@96-&FWa{0KnRn1DW7|?0D=hh=1&Ot?D<-I#q08B8Tx4KD-2!I4?!g zthlNIHR;1IWxn2}RManDWFGIJ(~~BxBkP#_W@HsXpd^hunjPD1Mq#sf_F|bJ(Q?zR zUviwsGS?1-^M-MPiFr_|)3SuX(8c^%TrSQ(@Mf^#!J;#Iptd`~=qSO{&L z*+nd3U$7_cl89!7c~ihuWajpgG;1hmSt8c7RBA4KWd5q6GRp*Kne$jkKA;0^_k#TQs4vyH%ID~_>P~h;gCo@%aEr%wvNM&Hd z-|I2*sE4lkl8H&!D)W3x#V zAgpDzwK5G|S93NWBaXl@KyFX+*VXIdgJ%TJRr)f$W(Uq5jOup_T z&%JzJs%YS}a?i$Q+)p>zgFLv>s~W>Lwc<@A|M^pMUhD3E)BV?u=lri7&yb{4__rOO z&*YO>P`TOv1vmO6x2ILJCFJuna^E3pKwlxS)|(+8G6U|YK;tMm0Ft{sW4?H+N6VRi zIGLrMWM3UhH)3lwg9IuM5DwXx0GyF>F8TgATnz!xbbbo>D1~~;PvCnO@LZp%KWG-W zt-*(4cES%m$g#tTiOHmC%Q;DEYHbgZuY`B>Q_ZOeZoh$tO6BLzX1ZBgUt)mxF1d&# zeDANOid5_{6~?@V#h8=X29p;$h@uafQ_Ke~0GS7l`c!v@FRuqKH*F42#`^T$@ysV@MKcYhvS0UjuG>~>bY z$Y2cdOD2R{$TjqyvGCpjwk7nH9cEkIw(a9k&6jX)11+o8MmOMT7-wGRjc@5AKYw|_ zP{*}fK6L9?cqr?TKiR9|I|%1_$dvUb36Cta@sgxrhufFMH})n~+8@KQq;2qX!`;!M zKJ+d+#Y-tJTevvu9Pq@Dml^C)5R?u)BlyjRF1t&x1v;sN25~9~ z5uDkr!$aEz^=itYpOhcOOQ2r7wjNZk&JSws!as$|l90!PMRmt;c;()V)J31FY=cZj zR^Mu}w%QqIsxJ~gzUsMww{=v#wPr1n8KtFj@LoSZGhQc!HHb#i8LOyyb9O zl8F?6%KSRhDf&dT6~U7miSk?B;z=zg^p6(z3^Qt1LdKfjWA}#K9Et%E3`i$}=Jqn3 ze73x7X+n6uXRh zfO5`wkV)`oCGIeSGh3*Ak9;FP%3hk5{q@ZW@D=YliW;@{Bpddj^@W_ze>5f6dVd)~ zPCIxcbFH;t7h;Gb5^0PuB6B9L2zgF#Rz4s5XmF7|ojgs9dOzeroWAHo>`{W&#c@}N z_Zc3SVp-LEZCy3j-5yme3Tf@}w;r#hPLAWh{+Tf9cb1DICML@y75{vfk{_D%NmeJs zgG|~pBWf85HbZ(dlfqp!nM$l@#-bk67;kvD?yrb8_3)aoN=^IBXp-(LByLBQ;-M7X z9B=}x12am`Fst8n)b-NeyG73ka?3tolN`NC7g1`&&^ZQr+5D`_w=Ll-{om6p5$V^1_QFKVy7p(ipRlx)AFf<$O zr|%~ZE<4oH|Ksc)w*-Nf=m58E_q1)>wr$(CZQJf?+qP}nwvoBXO;-LUZ&9btu5Tv~ z+DU;2>`ZjKK$U2F8<7W#r9bFUAo)?06HZ!4#^CEbs)pSvC5SoaJvP(k6QluZ>~T|v z-wrr`9t@rOkX+IkX3JFZdD8O!7ms&(6XWN`cAG1&?#Mlu0UdDEu=eOaiXYvuMyXQ2H_&j=Ap8p$w{5@d&LG%hJHgaOSuCz|SMP4m19!WS_>o%R*wk z_QFc58s(ibNY3!$}thcxb<{^dyRYgS!gOpJc z>)W7dv9DC>?UyWw52qk*2-e>8{9zSONU!Z>*#uf8!5|%Cs90)N^>hDj8xNE$RtSol z>L;8JkNq_KZj{Cy@MN1Hmyt$Sk)Gu5*oKWYxib{h$4q+%h#GijjmeK5m*KCVyMu0< zk-1*ps(*pVIqViKE?Rf z(Rw@=e=y}olGPZq4!$1s-9R{3>gpCmB;Rf?lDOL0oIE>OB);pTcU3GU(X29=M`ksZ zt5=k%1gmC^05*(NtXt`oJ-TEyrt&eVo#2T9qk#z<3#0jw15L~kA`DzO;}RT~|6NQQ zR}R~?4gMEm+(kDpO0?ggc;5Ia3jy$z8)X}GTrk|IAMqG2jr1A|gL;ag`Z(!80^JPF zn+D2KAJDxW|4rQ1)CAhU@GKHF^r5_iqhw$$`ZxDa3jCn_!I&%JYVu9BMZ-Ni*W5^;`b`}?hzN<{BN)eL>bs1U-|x@k1Q z&Yz(tyGZJ3(c8`)dG;1^h-97F(5ULQ>T)kBogcOoNU}xJ+Z_HzOLfbqH~y~g$Le$v zr2ldp4&4ene^`16%{P7?xVSFyr*X4M2W`@CQ{wlb_(S6npXFGqn>Hm3Xox$+QOy~$ zzAe1cYzOvWPW^8-K2+&{vhiiC?I>@aDhNxdK4f2t?~Ln1YtucoQV^m1Hrw+{nCokV zk2KrIs89&~8@`;1UDxa}yr(KD&n<;ojy_`(uG7@L917WsBj3?h>_b<{WJo;@1`y&U zJ0|sO3O*w9y>gT6h)N8hQMgn58g*j-7JDSk$on@-d*+|f)lnuqGV4Ntzqbozy==f> zOoXdpLbMKFsQ`Zs2rL-N=vuR9e;SF1`{bQH`oK>achhH5RLe-?` zp3>w4RR~Dwnduy;HffzFu;`|1`>do%dN&XAg|C?uNCm@mn zoVDx(Eairz9Q29t7I*LqcvE9IxoffaC-ez$ke2LlmS{SB+Yv8(@%Bvs?v|c2- zEb1mbyxQ2#`HI){73tE={pJ*BGGJhP$=8%ONsp~54A{Zkq+||ZMuLdHHPlomQi-$y zrZdh4f%551Q~i=t;0g$yq7m#9P8l6?`gB63;Jc*rS$D1wW(Q0GXyC4HE0FxIp8M1$ zcBDp#0CZ#Z{ zIu$Cxfe$T~>@XAa-w>9FngkdEGEA4fC>1xdZv>FAU#gTDKj2%R{s$VrP0BxN@Fa3u z3vEo?+n9DLvt_K5A&}Q|HrdbLOquw+SY8uz;+i72&^vqSQ)^}KA$TrP@RSHnhJ29h z0&2EW=n8pb=I{0a+H7_SP=TqdYNx@-W2 z{D|LL;zfa_())j84{u@+3D{5xVP3DJMl7@KNA2egYcZ&5g9hXfYVPI~#>zAa&C4GM zN<1dObeA-e5Hp%~+XI*x7}0=JrWSi;s~SgGuq8VjZ*exn&dEwrR=^%u(hvE`E{!{S zKRZ|qxrA53?tP8{dg!RhxfOj^@pjbaZ~rtU?uEc}s4b8|ixzCF7d%_mqTplTUmF#D zMg7-}Z~c&wrHb!HeP>@-X(Qb7*2Bwb&jPZyHm*}aHstql;PsLWG^K@YB5MpBufRDnfs_HRB}lPm zmLG{pQYjfd4w>-Sqo`_(vgqU5B0ecKj5!5dX2%_=u5| zSyoy&wzXas!w(B%>Y*?qDBpkDQ`OlxKVBmtr3mQ*m8rF5IM%A&iK0foFAuVYHBz%2 zmD+>-y#z?i$u%Of!91jv0C9-D)UwXwbQ{Jly1VYYKrJ#Pb14Y4%O8T- z*=aKHB$l;NArQ}{XKSN_$#8ty|8PoJ`WX4ef5LmLxs_@|oodn3D&w`NU!2Y8m(}ts zo1l=D4c;FQ$u1)0>2f$;{L;Z@jKVqyrus!xA~r|SkHyl_V!~X)^v`e#!-&d`Rpe(B zK|l~O^HmJIQIU-?YNJu!sFLV%_9Kqd&`t3zUB>x1QZ3a_{r-;I(?ew>nU;=~*o`!7 zi4JD#60UDe&-<=kHw`sO4waPY*RDVeoglk*begryq)hS@?&=Hb!t_8b_1*@G#4B!O zvF2%U#2sB%@5oWeiN`{R! zDVcmYBa~yfBD{svc8f3is1d`L!{EOw$U#kb-MqChAcXIR4oIQ*iBX@phTY+@t=K9x zVL8@0$bw3edzO9VmOEkQo+QO$E#@pL9@jak;b?gO{hbXgp4-SG#k_?7ntqne6OJAC zH*FCs{HCC8XAK;!WP`paHA$}RqITLmP+SXn$j$TgO!olje!-_Wyi=pxX)&)<&w|E_ zAN@1$jnDIrEJ%#qX4JPyzyMs*rWnvsxgbnLawTBoo0MAUHJv#qfL~YuUSx+Rl+pxU z%F7`3B{vDaxjp{4n=JTu$w|UwCrabAi*gOk&S*{=e++6ni^k<(_Barot%4wh<}J;+ z40slA*qY695224}Q*!vC{s7vlzN;FYVP~6itcR_Z#+4-3g-c1xy%&3dxd7TXySx>} ztR(Wy#RY0Gk$|O)E=(f?7-;KFljTL2%{%GDt4VZtUWcmxk%P0^y9_lY7-1!;Iy#$O zcV!Gvr}_n0FONRT;Z>{~E*v9qD9sh0T{NavV$rM)3a?>|+^-jk$mwPtl#@*&V{oAY(|N?rZ$Y|GE{gy~hSnspiSY-WR@Gof zEdr3vBD)-mfrtujT2CVz9K?}Njz4muRjn1X)Hdl0&JYWatUrthUHP^zn~(q4@5F9) zF@PRz{%9f&h~~<;si3p>(C;WnE@;t1TR97goQ@<}I5`{{ZBl<30Tt*w9|#@=k3WJn zI;9XZ#(z7=xTBSRh=&Os^}lIv19jMo6E!qHXxFQ-x`ygD)#T^#x*XZiKe2F-&0Lhn z*=7A#EM-hkuB`uhULN-DCG@G44cRI(ucTd4n=#9w+dD9!^TsoOkeueiq`yQTabPe2 zs1Tq>_>13gKpBg8ii{&MTjuQ~K49ACRCJ)c-`j`5z5raS#t!*1DCC+c2FqaaDIU9~unLfuFF%_KqIl;#_Yy=LexFWTx{ z^o*_Oq*=xJbD>dD3-I5p_+m2f3#Z($pR8WM3njagKFVz;+J&RYe8;&&)taPsaDaXs zUolK==33~#Pf{YET`qFB3aMc<826sceRweZ-<;nKKQlgpdY%5G^kKSmpUN-4g}u>_ zlJMD0|DyrhM4uuj(5Df5+l4H@Q*^`=*>v+}+>q(O0U3HF4Xc;7#RlDSF%Ea6jW6xQ zAxJ90_NVXe3W%e+NPZWp-BQ_EN@&FJTS~Ar=%&&hMvw#Xm2|)$SuKV=+okE+8dPX` zW~kh53X3G>Vu-_VVa=~V^o1rHQeShzO|z(p6vTn@3YJDjruIv5i_`jTawa)g51U;F zu}+<)#KB=GxT^!eB>2|oOu*35(hzScLF}Ywd-cg4@v9_9fPkF8s6mJO2zNS+rXmfC zC_Z6Ce?-YDJ3s<)E@#K|9r&1f%yLmuzQPi4OQWh-gEw>CAA>ta8Tn&J)Zu7NBV?^u zUd(h{w=5Nh5D-d79N4k_w6B>PU(?3w%av5u71rpJ%6ynN6h&JG=m82zoFuV+=)FI_ z7=v(L30aJB$eFG1t>f3HaRi@o1cVJ;O37w^&wJ$@reGt{i(r$# zm0BHbHPaUWDsxgf{ZYGeYyRBn16gYYF}6iPMqv z<`M(%2g>o00C9B?n>tM%rnl4bJ&d^%~Z zO4lJ=*sC0UGJn4kv1NV*n8Aq;-73nU^`Rn?z6OvzZ|4HJ^U+bOH)1MIn65MEIRwM- zE1mF=8zirz3Izwz1{*d3~X5W+?HHK`gz;d5qYk zeQPJ-0j}frflQvjy^$qy+xG=$eVb^H31@hSU}oyFMnxA$<+J#sQ+C5cBJFq#&G5eB z^?ukvC7lO~#n7nSwp0Sdd1_okiz(mAC2AC(b4ijhwZ066C;IRv><%%R^wH7Mgi>!# zar9V3lxYV#*6s)Qq#x+fLnAzjjXT)iws`SQD%tSiRv%b4{E9Zmn||J;FZU?sqgi*e zoc#8^T$??7_!7nlxxacHA}dZ6M;nhrrr!82OdC!^v=nkhHc6P)5ikFnF{@4WA}v7* zZ3Dud&_bGicoXyx#1SaO0>D}-K{uzTe9mA3rzqb96aO;SVl$Ams)ZS)| z^I`}P(}Vp|xw+@t6FPcQ+}Ih92AtVID+||7Mys1F0%w_jX%i0}jx8RX++*0)MF^y^ zKwlY9^m^@*v+yVI*U{x7ok4}kM(W*Gy*g1SslFtO+WE`rUm8J7W_CTA$2Ho?5uU;z zRFD{m5;E#!%0eD1+Y{5Tp%_er*g@9| z93;8dMoGp-J`&RW2nEjw5vHMXv81tRF1}r|R>d7NqK+>5u|6U3_&n5V4Z4HT@%!0YDfK!4|W|~=vGrHz9g#=sDZrnZ?w@%;FnZg=M$tBEpv&7H|Wv*7Uj6r4kO14f@L3ygbawWD} zDOD7HIUMQM7abe8fY5SYcufNJesg2ozXA8cB}qgN=cEm+vh!(5E%7}UDmEt=D<{lO znuJ-xC@S?bh@Lp$4Xkn0XSOzzLb-s}yY{c0VwgY&2Qwu2Hd>F1G9gAoe#h2GD#8H& zq|iHUMLFWStc3e6u?)RtfQ-K*22}w#S|4VINFyDD?lSw`j-(b{x`o+VMSA{ha%{~XygRVW!z2si|YCHp90UC!KP3L$&zOZ%y=IS)g=pAUWY}t`vlf< zef*xJvR^xoVGyKm`DDxiCHbk*%jZPvoa zC*dKhZ`ye_6`+aVkcxMcBQL*wHoOTx!`H2cDMHB$V$D7hY`CB{e1j(+cBOpXM^KH# z_SJa;>;9EdB37G-?xRC|^42=~XJU-vpuP=xRNZlWCoS`mNJ^y*+ZgKZF--O_ey%QA zGlxsx>+$e#oZOU@uQ4!qgj7lDM3X%WQ)>Ufx^v`hFYhs)A|5XM ztQyPeVzMSkIc0U0>$;kQPd^&~I?&DfO{X|WhJ94H&VSg4UwR^b&f_8_^e6BKcyJ$| zGn9yDyETt$%w=?#bQ08ZtNc@7N_8Ml%Fd^YXa1rBw<#-t3sWaj9)3BI^+!fuVW=(l ztE1*{&uT0%RvsfffiOZTehv@CjBcJ@SmVb}Kcr7vkDK;quqW-Jnc9Q%R()obxZFy- zZ?=jbNcm4o5>|GtWtp@1zW(iddd$}fC5<6tYvcsf*vj^n#N~khCM9K1zUJ{stEcf5 zOvA{O3v~4h?Nljsso_6HrsPQ7ms9>L@!oU7Pz?Vg(?!CqoS(5gG(MQI$NK^vy%s8= z$q7a0Q!GR2za09)N)ru|LT?X^H_j@HNX=1Fp$=t;m1af_U{6#wov+3I?!mpVeb`>Ady2(uf#4ns0RCKaeTOf~XG=6w@$hYCzER6a= z2LA7Rg<;0EIp|8nH?o))I zJ(w zqzVX4{kbtO6&hCLzM9IB?40kkkDCqdvpMgVxKB|;KMYiXU9ogw*W6-D^0@cmcNuXPET@aNF?=mWn0!QIR`Srk*!TL`EtTi{D-zl5Rq?R7zlwR zCh=3AU86CwmBexfYkVz=qUSF7%C#$09yI;{06p$8Nc5Zdv_~zuMyhL7x4pgGcNwbZ zq$N8UHKxAD*mlKUO{)IHo}N0_oO{@CC<7Ju?C(swH#Mp>lH!A3do^YK_ZsiklY?m2J{>Q$-RgQfeFmz6{^|MNNpkGvbBTK>BPz>4 zG_yai2(~NheWUhlK}FB7PVE)ik~BQGYmrId0Y!mUWjlMJT9$rpOdq_4P$Z_fam8yk zoxC|_Q{MQYuPtClFcOFRL=>;NiR_kH!{{X3?IbMJ*pSakSC_TWGe3MD(-uycFk(|ecYox`hyIL zh9doKCe*)=La1uW~3$2<%QXEsP_p#gT0~S8q?u7^$WTvkOYgR=w3Ar7@5Df z;7L+`su8LCEJc=qkT858A>o4-2`(a3AKC9q#e2w*VXgwo&K z(vFOJ4nYl#;rZn`Kz7ZaU@;c)>j|6U?RNW>DL7RNF(jS#j84U`0GV8g*99-mY8TT< zy8eyP7K~US2?C@zoM3mI1c7-(=Y)CPW$0~ZKk?$ip^5O>!u1LInSTTX^(vfYQ%Ah6 z_HO*|fn2`AOxo@JgvqY@+2VzH3zVRy)o@%dp%l4OdH7-&Fml)JJ1>n<8ae`^9k)X z`_C*Ox`Z;Z8=@baSpIGGhbARFKH}g!=(rDo^ln(m0?byE+O);SN zp=H>-SY(-c3+bYi8DtJ?P>5ciF)n8B)=ar%ym>FCm{McP+1<f2bhMaX8QOBVPX)zG|FjBJuXh`v-u(IA8@a2JNvY7V)M@%Zd`x z+dN?~OS^WZr6EeDQU#^S>fE=w;|Yu5uBG9*mmym%Q+5Q%H*z@cHHGVJ{*mT>AO+5z z@XzJR5*BD@UmjRq4tk>UY6oA=I*i4_J-}a&``@?ByC{cQ0#j!hnp^I96F>G`X%T1D z-CuefYq7Zk(zi|}D41v`+DW=VfB3J;5hK-&Bg%=7C|d9(o2HnX0Nv*<(2?H?Qf0D; zh1tH`HAUkPP0*>9Ta0txAJ37|GJGRe_XdG#b3B#PO-6Kg+9gK1ze1)$n!4MVU~EDp z^^}C0PR(lTFRrtRW*uXo%A~4VVe! zYm~D}ubx3p+{rNO&0}bf;AF43vGbml6sn0a9InrH(#!H?g?=46aoP%5j!Ps??t&bE z^OUQklvzulPo|uVCa~cqf>S*kUz~s^F><*kFEkY#E5h8tPrqxd#*T|cT>t~%>Tr4#G`k53I^dhfR{8C6;f4uz_D1z}b7L1V70f?I%iY6?u?ZNcH^ zceXMWBtvMlmY6_EhdoAwW=~pT)UIqG!Me)qur?Y%)5y=7p+{MPT2Ft|_v zEhkzpWfg|X-?VW)9B$EEMbo7mjMP+laTfqX&=>ewj z!yz_c@&uh_4-i(RZ<9cUbr$tKX=pTKi`Hshg7S?()J7h^uU6jiNOa~^U0|ubIr15= zo$V*cA>jcj;?*j(l>L*ENga^=rE!bHY7fq_iHJTdAh^Gx!8DB6cd#L9RXKz>H2a*@ z8jDfpf^gdxG%IpFOMmgm$X_zRy>8fzKJ7l`oU{C=^IxS+ienOREep7j zSWEGOM0=EAXW$X)6F1LLUCIl977g;+%gC5;OyZ_x6F&=nH+hd&X>KZoo7G%c;mAf` zU&k)>J{9PdmC_Kyubi(_z20T~$pe>$%aU<@O^BddL+`&e{eO7-xnF_Of>|k>)1?$U z=wYhlz+A=iK%qbQ4a(HcM~_9UmAV*&itG_6yi&G zI?h7*nh&R&E)!wRx<7@Nx#s!rn0+epbbT%Au_^_j`j*9_TLtV0&2#485wPM0gdN4s zJOL~DGh@p&ixyORMlTU%uq!AzW)>gxX+bo&6TwJ(Tbjs+_gD`&=rg4KAC5o zU(`Wh<$nc=O{e&>DN`7G;l%A@X1fowNH8tlGVqu~$qsjY^$T3nYOYq>{NG2Y=^wcQ zxh)SM<>e9n6UHp0hR<9Ka^s!=`w;Mxj}e56tAek>;prHpmwY`~Hd0~$+c(RP|H19? zKsgCh^VkG&ta_Yo%)^-)QN6TN+e()cm6Gv03;R%Tp->7Q+%(jQov`Jw>_l~pBS z?nCewgG=Cfc|U|H-K;NhqbREjQop==ytbGro-;qF$}P&BcWt9KDx8|b9Eb$_tqn4a zx1G>=dME%d%~5r$rD#gTVA`3!0Nss`=6z8Bj7wyL&L=U@BK1wJiLUBg!;K!NOY2WR zP=gQR_V9)#6UY`~`G#;H0c-)P)RTSDo!&h&se1Zb2T^HWA&^%SJxNEbbc14InZPsv zvuFt;D_XGb$M%-+VEc<6?w|iAO=~ATLI0aH#m*G14CuGPsjfn}Gn{Im%Z?dRMxY7X zuP&QQO7Hz(g!V#4!}dM;1xvdnr|x#4gSQJF1hUgg8V?59u5}iw$V;ew{tZ47avY(< zD72bCiNEWO0Vi9*4*&zy)Pne3O*M|Gm-y&C5V@Q9)CWCFuWZo|j-}7;Yt9xLtXxzM zX@8Pi9>6n2dOOB$gd{(dj{@00BQt9sIQo`<$!A(X8N=L?Yak0SkI} zqsP)53T$xPaFA?|aBH554sO7l@T;`lo&-(wLSI~X74=o2GG}Bha!qY!TsDy5t{S@4 z{*JZHBXgfj{ze;&m8W=#0%^Q8nb9bgIXxfCa%TQ9cQ!RXCVL9ap%CS$OYVYiAOR^sa^3Y-WXrKV*?${2*Yeyeayx-4?(gX z8scQj9L|QFw##3v$gvLlbF?z+Pq3y!i}Xk}iD0S3~w#)3K|T?^w^7t12((9m+N$% z*UaHZ`nMSJ?-*S|(AY{h1i3A9YWq1sdpdZ|4eX~%fiun*x#)ewhe~xf@KY!-MG4@w z;d*L4fu*-0nnn}|9~d4_&KZYYD(Obb+@k;q&OsO zG23@jzjM2TkN%%G$T0l}$Mk-)12P6KDQ{8OswieSs>R#Ln?p(yPKPGp!TM#S6U8Eo zs&1_LRsO?imp=ZbN0A4-c8V`aHYN?;In((uqhQPb1T}j%*ghc?>HawgA&X_At=IiO z`i$;O_aum52Ixc2CVZ=w$WHT%L6ubViu`KyUEZ)tW^7c~m$0zFkZ@kA|GGz*jsx^6 znEDTEHRgf$m?_=ZlYcqwB>dsX2&?cUJsB?mn1uxRK(J37QQjQRf3Jn<8ZJ%it9GZv zRmOGyS`K-|?v)Ecn%&9l|6Xse2sf`f#BiKod+gL$9KxNPo(?^GlM-7*d!UcDn~4TsNY1 z#*@V^^|v(cT~xtF&LDp_AF+Kcz9TlwPvdBe3~`jm_AdF5%=0ve`Ue|RK?;Re zVtw8OJ?zihDPHUIk{J4K;67Ax>y|we4BbSc^bLRd7x>6Gt%#J{X2TIgy@ea3-h$FUn5>%-%x3hFd6 ziOqSd3L&0=I@zy3+8ChMvc7cbqL3R4uR9FlZU9gU;dzJmdX<2P;2Y+`cC%E~G`nOX z+}y2qaQi9plcw4&F8dE3 zHZbq#<2g5J1W~}}qinB>9#8 zV}n|oK7C537yaYxuSN|AsX6)En${V0v*>OHEy=A;&)#!w=0ojRvkVwMXXsXr z8+3u5e1*W<9vdIzpX$^UI6$b-oUXU7TI_*Xd@js~po)+hy|e+!y!ZY-xf2VK(zN>i zX2-dz(f5TQ5cB-B_PBjm7-?K5$Zd>3c532l(sy1g%lV$!0Y*AF!HHjX6mZ0|sYBMW z?DZpDojdc7abZFA9nIQDKr~^yxsvz~R6Q>3OkaEH#G>(UtqgywfoW_)Y|suXtH^k^ zX9rwu-f4BDjBk%+X}RNGb5j-W5ajfq+%S@5K4Ta} z=Mib%8!8!Vs)TxKTKTZzTn9sY5dBV8=9gxD8ZIPeQyRi2I?!-(sL0hz8-kQ!P8h@g z625lqZFsS6XFKD;c)1XCDZsT9=S4Yx{&`!m)H{f@AZul*pvPIDA`7%^l?Z=)Py-JNA41rqPZpGSoL> zV{A-*ZV_3DLS!qR%2SnwHG*#g6J$y}=A{#P;*G~aw&#x}gLNfpS2px46tEVEK z#J@lCr061um7CI0dDd&=M;W3ykBm#%yL|y$S&p&}PALeKPBuRB^BA)#CsUdi&9VK; z$4?B6(TMxD-NINrs&~!=n>DM7H(zO!n2{7hnd{*v;nW~7Gohu-SKMZV#t~Nh{k;Vx z^)1bc=`ZtxM@}zeV*Vs#$Kv!*+5PK@L@(-4F7B2e-KcF;W@tuNEYdx9qkzMBN0gVk zx@_PoJp$tZJYEQn&x=|i|6${)74!F>tA7t)^~b5{Kf1oatt zf1tzz-FNJg1$TUrq{loreG!?F@cK<`1L$1`n|@X&C*7Ol8kEq1GcqzVloxkN+6{!qi2X>IPuQ zy!wf9?r|LpBRPWuol0H$Q4{}@L2WcZaW)ZOTw|_gXn)kxLl)FF&KX<9%gdYWOqz2T zExO*9yWcgUpF5NZRo^g5N)CYB@Z$Iho6sL9nc&OZro?mOg?gUv1y>dj-g_z`@>bXl zkN)-VA*-AQ7@|YYlDU8QT|+c-y6v}5Ihzmf0rWBOZM4hFYOhC@J4W;?<-KRqYt?Fz zZ))$q31clcQXPoVuyDGb&_4F-Z3@@SGDhoVDvGjI{)Ghqs9KeePx{&uoV1cWnWlP> zn+6S?Spgnu>_g1T5}G7r@4cCOe4O2x5YmNxgMuW&Jz?@`&$_4e6)I(*#?-K^=ErrW z^77gdEF=D$pq78aKD7}{$@>shWdeQM!@^zX#JM%Fo*OZoomP?&Eeeh_j|3N9YneCNfDdf3S=iR~wIy~L#Hh!Jh-KE=Xj_q8?(WwLileYEf~aopyCI%RUszWQ z+0n%@5VmD>okQjicMn)BjQKA3+KR6Zgrd4jhT#OJAwmPJ<%12D4fkaXW%uEZ$!jA4 zUnk%Ng-)(-^Ceo1cB2Fm(OF66M7;Wodf8a}=G={+%L(33Qc}XSAq$FPGI5R@Eb1T0 zk1w{GU(xOyTStf52M4&&56~I=3yofCQ1(<&$AtG&y^ z(U2!orr(}psd)0}-BI1CQQKL-PKemDKitw8&X_Fhh7f1bnq&S=(fCa*Dey!G*}6~d zJWK|E8h+32jQpa62}{&e>_p0#Q>p?{{l{Jaf_F>-7(u4mcmLfbO=KmLWBxVhx67{{ zTp$@SRsW;73YD0}O!g)dByFt|rVL}prM+RA$u(U#uBKBd;M?&Aa(}#Z?cJ=NFa_sVF7HBWKh6DtWBIM0Z(AaatxpT+CIkd9KJzO{MH~ zXu8LT(2nWx1ROrhg1V+))Cbwee&gu6h8w2wFMX~q3GzhG+dww2&=MPHbI_4jR5GZ9 zUuysQ_FtGn+gPcO7DsTJw2wms3o4O2a{=VG-c7XxJCA(d$t`QL%}om61kS*wT$j-j zFN-tUFvS_1@ub6_-g>j*@6AT(m?a1XI`=eRKb2fqg6{@R9Q|2iuTC~CSgc|z&Zf=a zmnQF`OZ^^VJu_opacQiP)E!>6uGsD_(mZ569Bd=D5cN4H-(7p|%Cc#Xwo%t|d*|$Z z#J8f2>mvR@Gj5D)v{#{!C5;2DPDOa3^&Ge=tK16L3;&k4JbN0Zq=k$oz8T0)Tj~>! zgMPrX)(xH0<}*=zFl?+5nD;}{264xFrC}c_X-j6eoLfwN=UHnSM>aQa=@Gq_^Q~~n z=}RGwhO_pZJh-=ZC1M#d=(UnFZ+Icu7x65D6B^_=Q9oj{dnR2QFG5$U%0fUTEy!`n zyb0MWw3qhW8?@vOkeMK~DD{xt@-Q#R$*g1tc#@mm?Qk-VpnOEkl%OsJhH?H8oBf__ zdgXjhJkCtA+pS0d{E_0{G!syncu%TLW2pqs;^>e|`gb;)E^7yXu^>g(?AMfd^h6I> zIkO>AA%&bRE>h1uOy^F}g$F9k5XxU5)SC+htT+NQS?k^>0=Qc)IF``35e`i~1oC@B zw%aP(zapKij#$YH8L=wB+otyoFHK;hSXPAcvBQTbu2NGpS}Qo>g{Ff zXR62FTc`Yt6y+|BXw=2xlKw6{xlK&!?lP}EZG6u8^@a|kmAmcNzTI<)@9-@ zOn>ih-=74X#f+c6NMd4aD2Dx2V%QMFh}E~#K&7ipFOMx!xj#`3655MsF6v=vswv1< z)l>E!X+qbJ*=Vc%wVEM$mh2RjpP-snuW_`nA%hhtEzNfGV==SafE6XNCplR(Z>Snm zRq5)j?Kr;-!~CyU?dMN9(x#qV?XSUkl(viWwUTzPQ_p+sKBK4NQTqu@5Jwp%7DRL8 z_=SEmnuS$lu9TbBTWsgvuHlH8cvot-5Pw6KXVG5Novc5AkwpiBI9KY6VmdK2?Xh2j zRnPW#P3DCEbO=yP8`KOdGc%%h^1&bxDBPNPto%)I2aAtyWRKs&#sM{yX$}$MheNPU z{n;m`g^i7ZWpWEm?71^0>R)zd_IQ54#lA?)Q1L3hqhhIs2cr^ERbfS*;&+&o?l=OJ z_n(wXoP7HkUDQhUnskzPfjLz08vNz1D7lo)Jx|@gGX}>Qduo$t9bB+lbaP^p54}aM zB0s-WmL%!zUAugQdOJwo>Gs&2{?VrGpA>VtDHkOf{g`8=jV7|H@+8$VO2q(mV93me z_7^3)Wypd-Bk761zZY?9AutoQAWH6RTQ5;q1`3W$cRt2-E0L3J7g3hO6V5?xq-Jx< z9XvimWZNM(@F#>Qbajp3)qIo|=j@7-Q)=ElGot0HCb3ICGTJH9xu|qDL*+eE?385r zBjOGw6nn_SpJD5@12_(28$Qbpe|P{6gD;6ho>H;QC7F#>ndk_f4=%^Wl>7#x=2JMclt71+NMOLMj6?S56c zXh=R{5)9<~6TSPD zSD4qk;bVVi1I~4f((uU|R7OmbMa zPy$lIWNlgiN_o#DC2-Ll^f)C$+08EtGBpI37&F4;R9GsIZT&%bb4FAhD8Qx#z{Jux za5`S9!p6pF|LIIoaUvV0qQYQqSO`%TWkM|g(Sz3v;#$qL&)09cNx1d?tDranKk2=5 zz00!n`nv+TyW?0Ti0CnlBCM{JU<6AkbmAOx|j>6%g7!s4&E}3-W^lNfj~I6jOHR5Z;zZX*DgAGrBE3mYN&=*=Dmk16gZNrW^64#N0eAJJ59*k5A#qHjg5uwl~#ivSKU*wKA`<%d*HF z(8iMJQ+`<8{JaIyBu6{?NG|K{Ta1t`ogE;y-Ny&-mOGXMO6qs7%9f#<8|NNI0dT() zW361<@vVc5Oy;vr^fx?Pw;*|Gc>km1jkDC~M4?3~vKcy5G8kYv79S-ig&fx?!^~D` z&fVrZJm7Huv*k<$25h zI*&y18oA-Ru^17m1Ms?e}X)|DEPp-^0b{giVzbZzQCbT6r0D;aO6_*SP4w`F{9FwD&q8VaKa>XPN3f^tn6T{))e+&0`VafLL+52 zzOG8qlWc5^DkzxXoNf+K{qUn;o3X-0*Q;7_A<9RclK0&tn@ zCM3!25g&AtsTHiO_bNTweIM(fGf{|F4)ENtXCMqWQhq$NiYd*G)b1QCsCv44^nSIuXX26{g|uN z*v^Tq8_kA;ra5N$d!haU-cQlL>b3BBwaT6MxF0hln(H!4(8Y{b$oJTJ{;USSe7EL} zI+&KThh4gQJ57A8^sWuXNMFQCcq{oZEhQp%?*oVoek0;0s`=YHpogfH4&J#4`6-S z2|>#~{K5YDz+Z{~*(S-9B}y*+7CrE=w2##H?+4euT_34azdK$mB@j2&H|JmX41^AN zb)RmYoKw>q1dCzwNwcOAdKBfWC74O|23bb+sjFJEH`7hzvr+#{h`kPRS{{V-@xrg( zA~ClZboC~9g?rEz@Ra)EJvQ#g{B6vARNwYsRJtmI=dL=;C{JN)%ZoRQMA60#-U5ay zRnbA%M;vF#aQ}8KeA<{FXKI4>zGe?4upRqFT38bp=uLB@pU3bSC?$WktB#xI(Y#Wq z3#&Z%9*QrstQ5&Eryh90<7&cgp+3H?rs)VuCl(9I@bnY=bt$xn$;?-$)tSF?!u#Df z!)5=XN&dAY$wgz*1m$95Sfslb8((hD)QAWmIxF_=0a(9*8bqVJPho1Ne%~?qOPy{^ zG)07nc|bR%+cxuUqV)oz%O+T5r--8VB*as>qgS=lHCev`FmYWW`g1zYW7X@3U%2B# zA|F(9ESqgPG4qs1a9i_=4pRZgHn5b}bq>Vsm1rdq`6nSh7?37-Dr~TTKlVp6gm*uP zfUu@B*yI{a>4nFTc+tlq%NZ^h&9ag_>BFH%wUr8f|^zgtAxm8}2r| z(wd+kvrX=1yed7=Us*%UQ)d$8LMK7^VJP6K5jD4FJmL(IAwYFb9lg%ua-*FwzuNoxb>*LCM zzfgMLZw9v*%r?g*NKha+saG->ZLK5^2hO?5FujMHhMI|Wfgk906g2j~;=^}YLzfW+ z&pIiF3Xlj`U#wdJ?M@PE+KrJC;8bpvAW?6U73#MZF%-_WkU6sZxvH;88Nkw(h79YZ zTHN2}_~6G=2o_7Uf;EFfV|9aTo1q+A0Caf5wViGFkZ{+oMem~ z@xxizD{z-=q!TOil5-bhJme>_m;m%+JG*`kZSb0w&rq%07X&y@-M_-Wj6CYjRg>Gv z8Z3wo>E{re2MJaS?rd*z$hiC$svylN5l3CS#Dlhr@=JDo5kCKey|)gkD{J~j5ANa}+F z>fdVHd-Xos#7Mm|Oil?8RUFNkn0>_gx|lESKH19_{P+vbO{*}-H`XI-Q>lBMYOG8E zcO+~7k;Fkyeb|WT%T0@T9qg@CsJjFxe1F)XjjpkvD@^)A4 zk)x5(s@iR~=-H9EO)BHvUmS<pB#tZafe4bQ2RsG_>FU1VOlqVLeHTF% z@+5G3m4~U@CxgP8UC)EkOMOUYuTdPzz%k%Br=cg(0tR_TGgF7HVR9^1*s(h%j8s4# zh`;(qru_;bns?52ey`b$5Xq4CkzLHRgpo)!5eHF^5kp=--2_kheY8IXL?z@Iy*0t; zQQxtk(z1mOCH>ne(ymBM?6>O1n`H8AMZV!Y2{QW}36_LN)w?iqceUJDx}EjI{tktw z$tBjVno4M6j&f&5)lKiVV$2et>+;52O4Bl;U+H4QEh%$9Oa>HK1|nRuM6a-(`{&xK zOP^NZu$niPYtJwA9nFdz46a?U)E|5l^=_5gmA-Mxm86I5i>2zKC%+T3Iwu+7=1E7fH_ zg2%@^-XKzE06R;I1zgvsDcBQ-km1kYn%|sYzbA+G>cTyP%7LyBxJqP$3P)M3RF1m` zlbWTL%$FvT`Uau(h8MnO0(@C>0n2q}pV_H9TbLk8>R5rz<(9=ZJ}=*0bpbmE1WliBNhJ>rb51$llXEoZEenPH0$H3zzD8Q;#NgPn zchbCQCQcu+EsMA>L(CpjG@CxNl9W}7pw6 zQQIyys5lra5q7GD1fI%(VS{^D$pI3WaM+XX09iXf&G)L(dH`wdu^5p- zQaQ2mqHKmUmPH3+!&4V%p|3%nxN?t-F-l1{&U(}*X7o|D!on*3&hBksQ{ij+)(RgeEWJ_+X;q z?IWJ09Qh<1k*vA`U7-`4(A>Zj+$&XSvSjyz>S{E8SxsA5|vUK44OyC_Hut$-^~y9-GmN!R)f-EQ|mdVHvp6RZKJZLSr=c4cd*L> zvyxh*T#p}T&pU>Nv(#y5c)A_UYt<^wLq>ACD4{2md<$+LNpg7?D{N$FQyaMra^{5h zhh7+xn-5-gM@Yd2S}4WTJ#uT^UGj}@j#L@pGZHql%nM@;F(+*r)0b897n&Lg_-LQP z<%DmqaoXPtP!YSsga`&>-ZH&dg=ZoTjuvs7P2d;`S&-{Y5pY-hbO5QoI^rMtaF{UW z4W{|H3_m{ka&B(MJmYdqaM{yI?$_hwTmi*bL5Jp_ zLBO%O%VjCRaHM`~ZL{4lJ1bTWf%+6zqUv6Cf4@1sluL3VORji@3Xx_I&0KHINwG61 zc3Wdi3l5e@lHKL?)@hhKes`&zI)`4G;xjMnSx4Z8ngtymxo~ZVV&E7)y#3tqB@FAq zl_ctgIn-ucgf!i!5H^xj0R?-PM;B)~|7r?-W5%jj^^%(6)8*)Z+!*E);nX~l&*^j# zT%R~*qN_1wA)^DcY?h+8Uj^5z8Ob5=JdbO70-3uFb0pwNl^B@-yzogYXCE~enm#Q>>A z!m9t6>*oucJ1dY@#wzUt0PubRti0C{Vv=>n`rL(>vUS5QX{XukZ`oyq%fq8KtRs+r zQ#~InH!LnMxV}&`zK%fGt&5UjG!TB9%)U*=PMMPR4o0sOLO;{zqa-gy()J4u=CcQ;%v$XP9M*Ni6L{E6AehF3qlpUQW||&a z7H%47K3#KQ59rJKeMn5mF`t6g8j#BPn!~Hzdj{rm5;|PE1hGG}hCOYN%cyjeBK_VO zN8t#fJ=EIlGu-W4F~!9MpkhF9hD0#vvj3s5UguA64ut;=vLoTOf6TRdo;xa#cFHQP z3(~lK?1y;fw>g{HGZl~@JyWn;U+)w7*ov1c9mfXvZs|pp<7zd?t<1N2UJYVUy4wrT zA>C#LU`|shs*x;jhuU~M!w@h1 zwN+B*JrE@*Yq^rBG=i0$jn2xjpE8qxCgVfT!sC`G?UheaWSfOGs*{e>;6#f_4bNa@ zmBGm0ggn6;nroqVfwX>+##g?J!4EGuB_V1H@u__+#%xoh>h8t{2R;h=2PoNyA{g|* z?f%8K#t_J1w}NOctZ=Ujp3J*yE&cV(59d)k(W&P4xo zYy=xHeKszu5B(L&lD$~OISA4GjGU*HLh8fP)0&Z=1pjPfjs3^j{3O#jg4$eUxxfl^ zD^JpuLN#`wNZp(HBOC7|_69PbnE|ENVom zK(#`E<@jjCgeH)D?L6PgUFBB09uQ}<+`y|({DceY=;*Z!#`Q1^O~f9n1NrvicWmLIxrkU~<920_Cu zS-4GBy>s4=33b|fFxZlyqWJPOk8@igDX{L|(CU`wNWOrCJlM4Xb6jSjE}3tUw)-gE zBB5o^4ZaEKfE6}jgv(cecX~Q@WH70G9~2yZpq?F}HEDGST?TwENj;=0g9o|mxw{f0 zg_xMiVYYb-18SZ&or{=DpT#vvw!SHz2G!;zl1)O?|2jz0t-ldW(Ai6O{-?4_|E(-B zkPcMq_II^@QSW}I0)YWR5=dWXl@@+FCvIcL-U+D-FQ*w2!lC(uuvuUE-ePb)Yw<97 zJ>DzKOrxqsUX+r@2*c92@aN}O(dIIDb&^&`q$rW=yRuEBSPdF*38Fu3hnJ0a zYbFpFJJqaQe%$LF0?7E=frkEn=xxWuz{ICRD1mFf)a9o3rMcK#dTK^!?_p z(TALcj>6(Fm0pWQg9r6Jn)v17T07U`-8FKrFAzQ~fh@vbu!17QOiM#VTc_v&AoG79 zo5lMFhR>OT?@uZ*Fs1%P7PLwq-c!<}QV}*rjQ20gL^%WU1BO>Yps0VEAbrkHIr_hI zB>qV?6#m1siGHNV=N$yfLHN?UoiY_$?E>WTBRGMq05ANJ;{IJs!JiC&q`2S2JPQYk z0j9WLV&L7@p*n09(%Z1Z@;aU+Q9V1^uVnF?Hn~7Lkm14aVu*iIkA9~<^T7L&EdJ8w za2?cwzh~-)F0;PCVPI?nhTh)+`zZn#dVgE#X0%{>3r1+Z% zVEFu35%zyFdk&w!Q-5ml96tYVT0BRoe*r4H_D^QdQR+`BPzzv``d2OdeggFz8-5d! z1EfF4hToYH|D@jiPW`3Duh{TxS^u&ZKm6ohL}c;)$?Vxl{-l!p<|JN5a@|hvr)rSG z|4yu2`oQJ=-`wPPoEm~!{r~;qe<5xBZBf2JFaB9|{~mCEdUy8!AZ`4YMP>hg!7qsZ zE-C*?8$Yzbw9!!=YsII^0fL3`v&8y46oNOf$8=)?2Y`X~UvdZ9Z@B{^VpXq51~`}P zhj;h@@4C+{m&ZJidAnwBY)w3gR-KT()ruE6o0+ad>t=tu z-6^qoi);UwU3|FkAp*B<<$P>`c+UM!5JF<<1=$2PYx7Pw4)v7bIEUd7EQs(;<)SBg z;ujik_9;)}Og${?Uhb44oQY|Y$-&6@V{3rWq)XeRAJ4LH-Glp*HtC7NR{BdfE9eGn zcsnnTcv#hL%ul?j_2!>WK^b`uIt4S(BBdEXaA_$xKNr8F?a8O5LMmXWX;R;^uRqSG z>n(t3x~4wGM=}Xpq$Os(FNEy5a$bfn!OBko!)g;rV+g$-H|=f9*S~R4M(JLUUjCqC zZ*BE0$M2TXbj8p5n>@;;>dd91%+tpJ>PW2d@5S*~1uR+$mRxE@SPGOyP%r9uF3vP) zmF>Mo#7)v7kDK;QK)*BGs5)eR`YmpgGZ1W zy^_zWSGH`H=DM}C8*>(3vo7Or!Y0yt{k!=(2TIYdghjO@OtAFr$|?M+o2?fr#X;CT zU>enk_}{GN_4VjV#XC@asIptgD<|XFh_A|h5!P|56Ek18ce&qT*N)bNti>0VaTcp- zq7@cc#%E}9`ksRxC?Tb+!>u=dJ19q?M_wab5R)k{LfaMiY^_nn8i zM-A&XH;x~g9?|caWs@wkGij=SbLAJ^493)k7T#C=QXj{cI{sS#K92FI7OtOrxXj^EI#j<87u$JIwmztye zxJs{Q4qZ(`O!CN{SjJ>-s7?@F&7%RJ1L}2ss1deRA^H)Z@mH_LIaI2+2t+joBgJE% zMmdKiVbRGZF+5BigCMW<{2&x9FgY96=4Rq|aIH`_T@n3czB@PBSn1pA*_vh=nTny6 z&@{Ec^;#1S>_(iQtw}XlF$q*_tq&AyCyQk`RpUm)mqx|OduV=5ALxhgziuz1Gom^tOT(;Ppzw*#g3UT@6AdEr_uy z$AB+_cim?h^hnlj3iO*qL=QUVWa z>BmgN=)uQ%!)=Wx-!Fk1?P?*`< zB*JU?^``jZFUV{$71nRi9_Y=-jM(qL&?3Z+w|ME^W9Bp+)+AC-b_I2PLJ4&o$g&r- zG597I=?9grxLWS=%KSd*OIr-AtwAlZ0oq5RVRIW7_1<=8)IjYw)9kBw#9+DK4#z-T zEp&?v;@mm1GD8#%o9SlE4*Zk1k|HIeffGG z@DAfpFW=zRMLUa>J;XI%MQ#%#HxV?6j zyL;>;a;&=4`9)8siP-`=VAYbyu1_wow$mWsaft}MI;uxlHptU*xGQ|p!E#=*Vd8c! z!H788fFZ*$bA?wwj@$f+=(2EvF>2LQEb~*{jzOY&wnL7Uhh7BXv?wQO*qR|cJU8I7 z)yn%=2T^tDB?L|=j&fqw>b93^(o5a$*sDt?r4DTQiGZUr=>`t;Vc$Fy;w3}@?KYnQ z$E&;~{a3HWfIrh?BunN$I%V|X8}z+!9V(+Bf4GJf{jhYS226qn$9_s;J=*-|H0#hT zin9G+!ZNq;m9v5rC|oL-b!=nAhr)DMRC!OC4mX#FFXV;|C-&Pie#&rPvoC4w#i|>>fCR_?Ah6fuimnsCT^wkD8Zl-e2cd*(; z=uCA?1PUt;V3=@m!&3yACy%vk!Q%k1aTP1l#^S`-{xqp5wii#-O~mJYvht>Y4)9iqlqZRsBuXM_VqmN!s8$z9aEEEQ#X)EthCoqyOX}vs*`0i>02uW>n0mBlpy#FeTHNrt&X!*4cVsEa% z@%5`HRz1V9k%P;&o_Q^!ggQ}?cBJXUw?SZdw<5TAmY6ayIgq#1zPl9^>y_I=lmn@>9yO>qnsCajXo`Hts~K$DoQ zs(+pb4;c>+)d==(VcJ{_oWw@qylS75b0vj6v$~~^zriE^@>mF?0d2RBvjZ+$M9l(p zgGJ?CSRgNAGV9X`i!z;Eh$e-`b*9fr6-CX<&yIG4TYP6!Q1Uzpm>Ng02mtndO z2n1G5bHmo=pD{~zu^r6E3K#u6OwItR*5(hX%W;{ zOUj}(s&vlK!=O)>oWpJ97tXBa^y|K~uLWu>er62RovZrYg=hOAK z)1r6VYmda?&6wl+!Ijj5;`$8PS7yWE)}QCQNphTSSuVF9FK|_)*E%?52>g9doN`{1xS0~Tfc%i|a>M;wKNz8V0-Fro@;-X0U@q6)L z3i4g<3c8x63gYn|n`VG|YgNk)8dyPfZIMX=^JGWb4Wqv> zij-=zRX!zJ#~b<}@wEWCO(qINvXt`bOv;XVKBbQ}ePv=*?&`=*<;JGL@kE}v{DH$e zHkXAdLj3ZlU!Nv|DHdU7(JHxARJwfKQp;W|%S> zt>&B!@?tB|zp9STzfjv(EyiPZ;O}`jk9)0I!nwb&ckr5J9sUWCaD{}0SIv+u1%A<8 z;xM^s9@1bb;K}-Wn#4^HN8!`m++{(&VH_uV+kxkb-#QC2?s<`FKp8q_NhRKw3H?3L z8fx7InQ4*z(KC2Z+H*>iMY$o&qqLpz+)U8IJBRZT677tM%g0IlJ;V}CjyHU&n0vjh zENyGG6KYnmDzP#Sq2DE^B69b~`{R|gc8Zs`2KD{oFw8Rn&A4V=LtirRbYSd*j#CNY zNss7YwjfB3+RMBSP z!+%a_o(;BwGAK>*)jrp`8GEg#6kbe`8H+BuwuzEBxk^>c)k@3oF$CUqi|8-J~ zu62h&jE$0{7w572S$p-PH~&KY_;=S{o)MUk+Ts?_FF4@Gn_y|vm)CiRIh%Q3A!i4J zS*f7LXobMs#eg3M@5OpD3QRaV*n!EUEOsIYdvBCcbvE`U8ZIG;LfSpox!4guG2e+0 zYQ=W~IW|x;lI0EETzqd^Frf)xLxK<3UZ&;cfN|ML5F_)ZrVK(ifOr#ZhYI0MeIpTs z3{3{1>G6XM{SmI;!%GN|xB^(pZ`Vcq-ajvO;A zzngP?eK+?w{%t?8*m4hgS~|3xaQ5J|j#H}>?Jh%>;MG3x)9vz$rKM5>keP2^fwSld z(;P%Ogm}S;0}#y%bOo6W@Igc(oq3=STR+fk&`@`FEGcM;P+fs4t~&WZaf}iFdjPJ(1t7DZj@hoB?_d|QUu$Uu&rR6;<^?jpH`C@9nkB2C69-8OE8Xd zS9wroBFma4n0=2(|C?q84d2xtgfALJ7)O02GIbq2nTxB)?_Isp>C9_u}4Bw z?j1%zl(&=zC&yvPRSU*tNiLjI1;HT5#IW6wbDVQ2R%%mt9aB^!0H?|pK?uGYb|baS z+43yoRqX?4$tR8MRApP@RC*3N9~n`Tr9Xbeh6h-nMH2T z)+wt}T-`w2^Z}XohI7eA(0(`n>&FVhWziZqp1bO^^p!8K=ZyC}G7bR>Mvl#vueaKF z&R^U++O}oU9tDp;zvgzPu>Teg=me3-mB=h zu-h~+Qv%aEPE09VR_IV{VI#VjGqN&ybto<#1QEQBc+`)}06kmQ>Q9T%YghGYKugWY z#Aa6npK>17IL9yKv*1?9^fLHdR=h}_kmm=%COHDU!ox(5G!UNH9sK#1qp?G?#NVkU zo9@crm#3ZAvKHkU2ETt1W^W{GRoz+j5FHDzC{?jSdLU?&3lRx5PDNY#*{aGq1*caY zssTIR_=U%}?=W4x(7_`rZBcHfd0l?1{vRKf0T3v(=tl_ZEeiH*8+{5R`S!=rIy+Ue z&Lx4Z$C+{iK($Ak}jX@VCE2Myr~rUTjrdJ0ww84AM;NopjVnnXI$4FJ%r zL*9UP0=r#6@O~V-0Z+*9EF!k^>bEhul{x^(FQBOlaSxKUOtxFfXI6Tx19jR}jY1|f z=dd_&3KA&p(xbF&64XfMI5-g*2sR%-ZJh#Q;_n6!V80D|7I3kv!0#NWx$nOZCBA0v z4y!$hZk_vT$l2eXauWY-y^^=?c&ZD9Wjja9;6;`XjaYCr3Zq=QM9IFaB1V5G-*ZeziIvFTAaB4=gi3l4WfUd8Y4rqpd_`YdiW7*{kKvxn~n;QW>gcAj}=>Sh3?<{4*VMMIsnJ8eb2-g&hO+`DRkDx04OGcd?$t+%?3GCZ(l8N$V3jo_2TPC7#aC zO80kZ@tCi<`<4f*AfN@ekd57@9(8Vbv0o#SY~OXY{p{-4*-rzP*-EaXuHtY)E$EMB_0HYhdjh;4a|LiLM?jW^E%z67URhs>FRcP z@_U5d-Niim_;qWTt0hik(ALuEH!{QDnl-qumhKnD$L6v9oY{6Q z!^tR|7`@)Ck2u&<5Br56CS!h;&SsGz~vrTFwYKPe|{lr~66O{)qr*}_`C`btq z>O;>oDofH;prpE}<6G+I3k@$Bs8Z#PEV0KsKD4J!I7Wff+LW!MKql+l89rQ0Ryj?Q zejyXlcTj`$aix>(#R%^@Zpk8&g=iGhVyogAzchbm$EkYxtqXVDaI#26zUo?fE07|84U zMcbb1r7r%bE%iHeYhLr~1(h!EmFwj@52+({1|D>DVU z_kF;ZWD#+6z?3Jx^V}ivVGK4;bi%e+y?t6rhC+FV*o946?+cfM2jZ94)>+@9`@lG| zCvxP{01;GI-q4)qy(8TWP^dp4ZYFn9zo{<>TvSB36BN)Gu;Rkdam5CA!)&|a|HSMh zwTp^b${`^{qX=_poNUquS{(J6G+*@q^!wsEZdsKyKeS^W|1b4jfPVn6e{^RtK7qh; zI^i53{52-~!-9TxXhm&*vM~R34ahX`8Xz!^f5N5pqelzaLI!|5Ll^DZ@E0$WQBoA#m&BUUGZ3Z&9 zayHV-p$di3oL^F*o||1T1)h(afLSu#^hN%=UnAh?r=6m$DKL;j!CyWgqLjst9m0QM?8iviai z>7GY9|M*J+;Dax47#L}RJw5*>0@%>w^Vd{haQ@ZEm&NyIx0wHrKX3?`HuQg2=9!BAGY9`+RG2@K@UuGqaZWJM z=R>$(Y3ZL{%S#NTKc}VN`9C8Mq!#^78 z`zTO7Le^h&a4R4k2-LqseBd?!yJP=-8-BEz{cJJT3Z;vl^?>(u0 z^ijL?3Fug;6*SYKfvg^blKwEsj`M*b`q2$>GOtE(*vbd_+ksEyh1V-jqSzMBirthU z)6?74wGjtBgr-|8N1C=VAJ@>vGxQodAQG5v{a9l_ioO3MMEFKJ2&bXE*nPEcwHwR_hvE#gQN=!R0-=KIg)I%9zis< zadCzb*dzO68xi(@Y*w}caI?bxxmi&_`o2K=n^(+?K-lDagN;h73leJ1G!%z8C$OF# zlEAlp(-`@d!5|>nzmI*(vzNB1toRgI*-Tud|MH}&YJ`nNFF7H%`Rd+TDM>!nXxFb%~+j4n)fcWf++WFG+kT>S0ipb{xD&XM@dzZtUT36$gFQ0 zS;3R&mOO6Vny6>1;M?Med|&RZ$|RiEi0FbGDpFabf2Xw=yN>b#1$Nv2G-X1duJ{7L z^uj9h1kmfp=oGnZL-Qj2H4Na+{b_KCe|R_ugg|=gPs0Th@H-Og0+l_x(~yRt8{40; zNG8X9T?&(H-CPCy=HNjB8|?PC5j1yIx7q=M@O~-}Z1D&TidZWN=_qQ!hF;sg_V@HP zCOe8W4WmRhd-Ps0ujgxDUwIm7lxF>{XVa>e>v-+e@A+T2y|0%7%HgqE$*RjQ*|taL>x1l zey*AAtyO&X1Y!ZP;T@ikvk=iQe87Nz00;ztc@G5`33SAWpVs>3Ze&ix9simT1Dt>k zl065+FX*2(_A8Ap{Eq8$JY5z@U-^YAB@7)HPrI$=aZICVMxa*;^;85!^Iow}s^;ZR zt@Dv}Ch_N%)<&-=IiD4+VRhD^3bi3=g#L>s`b|C&Mq{Np)- z;sSy3`)3_=4x|HbC-H%FA4lfDrh@=OF$k7G8pz*>{fKdEMqWd#+oZ>hvcMNR*La2Q zht?|SKU8R19YC(^d>KBr@Oa{N{bE$tOa~F)N>4UJPC4avkKYSOM)(2(<}d{obSEAs zAA(g0lT0&4BSL_j291Y>)G$&WmWSCdW;Im(GP|BzY(wPf3%_>A7}C;OOneoJGhQz8 zHtq(e_?2p~bzb^z$8uzD;k34Va$fW3_mR|z8tf7Y_(qjkmNF$@*8`v1sj9`t9*$B0 zr5DsC{)lbz5W=0GXqnRXUDni-?z@_#-JtrF52*6E@Q$89anrtxpeE-%e)oONL9eG* z@9!AdZnUd&|6N<~LpKG4hH~42V!kEb1euQrrSC5!#X5k9(F*`ulb@>v%_oHM9jv(< zS?)LiBzR#8>?A|z$i>to?zsKoUsr%B0WSbTuk&xv1Ctm3pSH>>kS6jIdB9g!UBrBl z={JQ24zoE|LL!YaXPIRF!^{GlGVhrAi~J{kE$eyfo+}K)|3f+E|ECn7?7-it{6HSS zT@U*ud+Uw-3*VpoL4cv_nSIfJvws1k0~z)G$p}at__Nw;6i6HWWmIS|bSn-It+qY7 z=%49b4o;Zt-Nep`iZ&LFsU&*0uj^OXJByglLLRGLk|8J=4z7Q*z)Ij;>ek@Kcm8sZ z=%B{+#onp)s(1%slzQP{6D#(k;eoIjN`+m`ISdB5mB?3fM#mgQ{7Jk{Bx?ENQug2n z!8sSofG`Mn`y+w(r%3K~ISv*L9=70V0yHfTd~pG0Hh>^_zelLL-mjk_`*gSMPHQ%nko9)P98{_&?AAZ5BvJ z0lvKh06<)dy}lA1ASjPucGf!Hh9D&ziuL2s=uJn;I7OXrE+keUO9LA-=|dNQ1`P{n zcudzIrc4H_-!2IC){I^wY7+%16kzw9d$1##1{0ws-a)b_DH;>ve@}t#i%rtQ5G&LQ z^6E2S{8gcyl@_QlX>GkX%nOyVZ-`{v5Rp9!aWQNBpxTJif}5KwYTl4HJU2dbG%ZT& zC~i+isZ7;AwemvbU$Ng-w*Fr7!yXYy-2 z=FVkIxS}@eZ?)3A)Io=$158kfsrZ6v`*WnQ_n2uXM zJjp+sRdkJ-HB@Zztk%X!QU*C383C7|e5#5^GR(c-VO0>S;VTP| zIh(4bo@B3_yLc#a0TZ1D94F#ps!f6>Ug^}B28Nf#3+6gl1|E=R_FK zW!Upl-)LIE{?Y*w_>c*h_Oj!F3$i^O{fi8x4I~3s|7TeSVEnr*1FW*L&pXs))~kOv z&wmUSScQ@i1Cu?S=g=W+-TuWNE)2*Bc>i7h@8R-C-SV?ieE#>Zx7_}vYQg-wYWdIf zzwRb~<@^5({B<|^oaFyQ{p;2n|My_r0bC(4&-}{pkks%(XAs;)cXTqW=5G{mSGFj3 zvh6r2=igj7Gt@K64c`3X2;TBTvtQ}&KT>|Z3YVqxyOd7g?B^W!CzV1VP4L&AkJl=( zMtJ6V21UjcU5<@LS=ek?3caeYj_8@%E z-#?-^>rOHZf!tK-X=z>%9Z4xU8dJsCTb3t8XQT1sD=sSF*K%m~G#uJkA`%fD9HWqk zY~dC8SR028tUI@kMcYYo+aRPeGv#CwtD3j`k|o7P~YNpLFnty26b}dR7(mWP4m&^l9)p7BeXL-F3r>_ zbiLDOm?4W_VfI6zSsckMF}|B(S^{gDS#f24C_PC$dYIIu8XGCVST(%KQ%0>yZfZ)| zA}rU9EP&~|1iyqRcs1&P@^I7b5?1ChQxKzF5kl&j*Ui6LO2NOp;L#z{Br2U z?sN>-%5@y-47+ydTkMF>S2CsobIVZb`FmQOs?blk`rWc%NNeyG>?P@LTUl))dc2lh zTgeZVj(rd;^e`p?B$kp!Q*Td@X^G$DuoBx>c;+ai;-kD_>Hbt7Z1k&MPa zTCblPhRBNMBeC<*LCz#==jy?>$&}0?iE%^Cs5)eD5s`wT>E#@lP4LPK)CTBkua^k` zZdRgW8J$>)*2*C~f7|fpMzlrc$ayBVtTR;s>KQc&L%Ww<4}p7y1tcB{L1^-52a0kE z{la5DZc|W%OC(IVx3BwHP?OKV5n};y+f@t@6VhBMsrro@lkJ-*XL|#Pz9=tN5#AG+ zetjitUhI-)d?~LkFaE+0V<;&9Ef_MA(VCv|9S9C0#a%eN7k7V$@HXF6MKgt8rpjwg zo~KobM9H`+D1M_cn(vs{BYf5gPG}HvBg_iLygi>T3(FM}@Fyuh$V@bMI!>v8Uk(U| z5F95~IKTgzI)I_X)*5ivz0~g@@$&U?vVpHpDou9JvFx-d#TZ@*vpVlyyh=ukBBKh5 zIJU&B3*DWj`|(@jr;PUuW&x?TKEifgPOOwozFXn%(P7}4z~9To>2g~6Gy2#MqO@J-@qJ_F3jSQ^(kX>T}Qw8|V(kH{t1oE4-5ZaaJ&MSnKSvhw`(p z43`uhD{iQZ)-$fN!;C&)JQViVbtKAoj5rmL2m{=tly``x^p7U zP;L*aQvKp@YsD}D=HFWM7e4aGAh4D;^S%BY+C5#^_u*}mUI!nRs`NpI?qbij;SB#Eszx=&C|(8LCDZ{?HF$RpF*Dx}k(o}M<_liQ!><({snpO%Lo3)^Gv zp;maN;4?0;%-*kEScw=+T6yBo5t(c7S&n9W6}0k2vuHCV0VO8HJugiU#Fb~EGEa}l z0*lnw-C!}CuU`WVn;jtwxzFHee0T6^x)+h)9Lbt3!K$6jw^&paAAMgF(bMCYvD?t& zg~dCM+IG#lY{v`;Z{nx?YX9P;ln%)0hSqoRy;L?NaC>V7j&D~Az9?OCIyhMFT9_sd zY1q{n;DI4>C}hM5RtslF09zhQl$K`pY6WrVdvn$hM_fw1z%YmTB!mfbO@Pu!9!Y!;SlB;BgF%0CpgE|yxUJ5=S1wfe5M12%)svk3)YDkyaH+G z*u+`UGnnECDR;imcoZzEKCI0$W7bZ?MItl-69JjrpWf7oC4nW4oyZo_vQ&~DJ(v0J zb~u!&y8sbeFsm~3X%6^1w)5X`!uY6d~k_2)X){H#vB zQ(Tk)aDgzYh%oCe7S{aMO#q*#;fo-c$nEs^kKj zfY48X0>L$c8pt=E&e5%oRW@I3^$9P}Bc2;I&T3>jdc_r)>dP?1+r@mR`2!!>Nk zRBi649=32$4L>4EWT7PUd%(QR2bbKdM5-9hB5rA3!Zk2h;C-<9=2sW zt^;PUYj#(5Tr=Rk<)*u!dyPC9c1f-4vYmWCP5%vwT}4CjNd*}u+?%JmM&G&b-%T~` zM`gOdGEX=hpzrY-iaX~p=MFD}_I%M8b@Pfkv=&~$Rk!Hre=Lk zlzi@MgR(^1x9H4kJ&r=~#anaiLnqV8d$lE8F1wIXsvanY4!XX))DL=|+~#g#J4=1k zuA5Awc;6GEL&O~NiRad1MpIrdhcw(b6n-I67O8U#RXB@ydf|)N{zPztGN}9-0?~{P zDR=Mg<#G&(%pOydBcQhjk9hU_Eo#$OP7#kZXa%2XEhS`<^0k8UflIUYg}yj)5kge$ zhZ;4#-F+it^wsi!MaLL!86#F)@xg%?6CbEH7hG&q3giktg{UwzIN!A}C)Hze!wv_+mVi^OP*;kYHSx*Mv3zz_suI)fp*Fhmjymn@ z9x6(Ds#c&Pfr=2VwSBSx%OY5u1RC)uT0@TUT+TIn^o$Bd|;Vz z!s&3B@jF5%(Em6kN%#&oS7E4t$i*il3cFpSDIr|F<-xwF$mgEa+z?jRJ3SZ=rF%_S$S|mc-Y0D> zA--`I8T#H;ep-fyYJ8mzCYGEdvC4N`q0X(wP??xp8hXBNaHn;|H^(ym9$sA1d=sN3 zHWp1yMup)>q&t^8HkXrT}&Pn^cc-2|6o=W_&<_9Dw`C1mN>O~baRohd8o`}S= z7ux%(XzHg9R%TF@Vi7stn9jS6F({y=LsFoJLGAjBeEblRVIb^F6V{Ma=ivXP|NQHM2pFTG_eeGcw3-$e%IL+bEJ{GUpIL((FPLfU%cJq}DUia-I*i4pn#bYvI zc5&Cx@j8uo?mf0r)T7pdMuKuk%Hzu2&S1O-3AUNgz(Z7;6O%iKmKMAFo(tD5(Ug6* zr*m`k-1z%g+5uNTNRf?&fZ=JzFEXJa?J}HZ<)Os!U7=(`cl=El;PwaKI+}L4d6`i^ z)Hd62fJjf4`fT_!qE0$-=kzU!U)9g=3#{E{4O(dvv7U?uiGK?g3I?Nh)Y*wpG~yO~ zh!noK8+_@t6%y(f44()CJ<8#sY=}&6viN~rQS<8L7Dk!RNwJdKJbIc%c}*C%sQq$h zJRaP=j{HKqV(!vQhxIIoJMnu-*0Ec@^St&Ak=!emSZN*#;wfaeB4-(Hs-6WkB5{Or zNmcY$sHRVLoR;OHOC(O!wDbWQ=K{8$t9@Uq)6xjHlJOku-G~%K>^m3F+P}?Wnf5>9 z8od;7Fq}l?To32@EnocbT?_Z@$-%^ay1*Jb_)RJ2H}a9p6OP3j7u;?E8R;d3z!qU;A84 zi!k@foq(0X5BGd#yUEAZW6iT*=I6K(U}cCx1d3TnWYC97>$M-K!brhdQ@cf<>I#pU z=1z8nx*i%o2#WS#zND35Kr`!sKAk&ECF!sc=Lt}F)UKH}_&!0FQzB@TLGBPmkvgvl zzi^C?+bAO#ejo2mW?}!8nTT0W*b<$_*bU4)%X^JG3u(cxiStWmrMlq8Hd$vc!1(LN z5Hjtn0_Wu-Da@iRdDaU8#6-}-uf7y+Gt>e#q@v)EUfrnpD?*$@Td#!-CQsL0v>%Pd zP-`)~(wv}~ux%tb*JWf3p4g3deU3%BdsSeY{8QNsnvm-Cvna1mS#3Yv2;s8(h1l^p zR5%^VT}#X8G{uK?yDKCFn_NL8Pu?J#%D43zsjO@x4);&f!zqanDpF*nf_@0Jrb=^I z%E0ap3tn^0(c|t<7I=yI_%<0&#xG=+Fxwh(e{=f)f6lf6U5~9h!?1Dn$?~kl`Mm^X zB)UH#)-XVUA+5t&k7`sPvMifSl^p5tg6wmA8u^~b5KKZPOURmOS2D13K#F(oBgw92 zKq{B)f^di!G$C9@rvT39DoU{nuk*lRn*RqyK)S!#luQX+p`f-#Js*&D#-5h#;GU;d zkKOlKlpcXp==9$qilqnS;@D`)`vkBhaXb83*M75K%>?L~EI`AL|ND2r`XZ4PPp)q< zTkOB|Lo$zdSYV@RY~!Z0dJORoI7Hx^#JMpNZ14?t!TQSO{%aH2xwq&itc;~a%+MHi zQ)B+7obwbR?$Hl6S%PeREkai7KmJers0jtpV!2ixzWjd9)PqOk0Z%S6E7+K1pu#3W zIWC7Jb2SJLj)k;$^TXuKn7<}qOn4Zq5PTZ`T3UFdi-HT?San3^g`u-Wz>bYexya~> zoX&!W*%>JaimyC&(8|3xkGGnj2- zh6`wM;JKcmEpuVn7phxPn=u%;Yy0neAr^Vc07-O&N;8TIo6Sx6PKCm?k5^0?zSRZ0M@jMgRtqRC!-om`pO}>Or`05$w?-i z7V1hbf^@&RVfUVS2C&nvh(IS}Dn8c|>ZX!acD1fB000C-0=tJ)SNG*bSu^rm>9wsE zZj@;+!qm317OT2j-HL~s-vnw!yXi!6oa(L&05oBgHzZ73@B14?5RP4_D_y$+xl27J7ZQb@X1(U*(`9=gc2X@Z*L0n$! zh2Q`G|MRC~p4dy~LD}dPaZZ7n`tCh&&Ji6LRSbGgB6KkYs~a!x9jW?aipOCnTVy|$ z@!6bd*+DEj5}Aa$W!ENHV2=p!V)y?AKWqQ&3!qZ#5K4d65(Y7C3bV8s%D;J4A+}F; z=GEbd#E9f#i?On$n#+dcT}*1ATcWB(;TC;9(G7v|>c>BVr#4Baaue z*#!>HJ>!FCGW$E8{M}X-&+Peq;;kLW1-Yf&Pu`X%|Nm$dulbsKa$!GVH)@p{FGdG0 zI{`N}awh7z@Q8GV5fkFfA%4JEFz;+w^|ve{x2RH7Hb6(OqXl{;#G)u}l2_7;XG88X z1b(#A%%kEFf+j`HZBm2gD+y4my+6{$g$|cv%rsDf^cFd`XTfpmdc3p!@&pazt%uX$ zw+!e7Zh!yh0N8X^X)6G)gmLDn{BD%jxakS{J=4w0Vo2{WH`5Kwwl3SQ8KcP!Ti--*cJ0!Bfw-eULXR^sWRO4i|yQq0;&c85;t0WuD zgZQw|TPCQSbTyL7;0%1qCw&3a0&?SJX2wb(CIpBxLC+H#Z=^VRZUmncrfh!iYuDM# zzUe-&dyeNZ+BG}lq4Jx?TvdRSZ$kVz3fj+PXi0VjhTl9wr)WxyqHII0eyMzL)*Ur! zYEZ(J)-EN}-H)j=Q=U*r)MP}axk%&b8Xz0lE0qtk`JAxM#;oNw->U6(mV>w(ep=E5 zJgIjzv9<8JTSq)7CENDWsS44a@M*g`S*|&Q^_}noMST*IyuCv4zN1PAdV-*BHfxgRYllKfpzUV}9~W)Y$!?Nfe1%^-z(RTbBOZ?pwKkX_q2^fFez5 z3*fvPLXB$Hs?UJ>@3ttb;OMSIvfmr^O^m=>ypmY#fY{p!V@>eK| z7^N@JOqf5MYdF{2+A4%eqRQLW{((SMMUPP39NO|P+jxD3-$lcSq%9H3zSboOd0RSU zrRqV^VYY%FnuC0lifA4OX7Yz;UdpT0=f{=V!(6YJub9ITV^L^2kwX$WBD1Q{MmH9? z-#jGInOMEEGObbQ9JGhDuAy50h^YIxq!L?A9}^8|AFG$(@9=-2F}HPHJ;zW|>uYe; zed_lTBT#XYS00A3D_WITYSPGnW-~X%TVCVz|Uf!!<C$IPY?VhZWopUScKOqeR`gzqAoPhT0vZw&0t#rXw((kB zaAv>@MdmEZk?h~}_Ll4c_R3(;5ooeh#CLjnIp*j~c1B##hKpVCV0f%>*E zaHfpn5{JeE-c-kjN5p8Q|2XX;93(2w$3K9y`v8w1z=vO@(Kzn$LM?kV!j6lrUQ zFkj9M%TGFj2H}hS-!Xh3wSD%-57Ps|JE#|-QNI0$+5lg)M3Dc~PFKT^04~Q7dZ-+4 zSmkl#a{Pbo7}0M6Ky$Jb-@h_cvJ@CMZbqc^MsH|XL()^Y(Y_s^)X{L#aUKj`|K9-} zm781KEY*dvL z|BTU}ZCF_XUlBcWs1>l+hGzOd{^-#QBG6S3y<6svT}*&s=@%gE=pp~-307v?`EF4| zOf3dFszaemF8daLz=lt4vhY9Dh&*@6mbn2U!)SP_MrufFmt%**x#-%xt3c8^(n__D zJbh?vb)MJk7f896FOK8tAGnb!W-^Z%t_yoxv|jzz?{Cv!GhGVgMgeIOWYU|W$-T#0^+bk#rZK_m5B(*6HIz5-SB<3P|lD&HCC}V!xAMbV1Dtb zh)4k!svoir==9CyMic+FS7$|PVI?=C1TG#y%s+g1nC=^%s2=I|o=Ja(d)-wgqeXkx z!#7+C8JyEC;*F2Tz3)f1FOhx>NY%;+s9MK^062<-IIv5uI4na0>2)J6UShx1U*!xb zW(E!njByvt_z=;6eaKr|DR8^Hqno>tMfmx_ME+XbmfgkIKta;M*R~h_A|H{M-?|^2 zOi)`A#RYGDFagv>f`+**R>?PonGgE?33+`k_B8#1x(<_PT3~|TzOog|LmKBcHAV_H zV0W){Ks4KrhN`;6mu=tra~*64|Af0!q5XXy0KqGaz(5Z-+{}TSr=AdL$ixz~4jyV}cq$B$$UjWW>}9(nS(3l{6c8 zv#LhuA=7G_4_|K?w_Ufk{^%2l-l}& zIk6d(yy`Y3_>`>Nw-eTO?(qBG;U5{(2Ui);KcfZ_yMN{n_xeDkWDDeE|U;JSh++np=vCpuk@9}4I4QV0_Gq95Z8$Ns%}KUuuO-s|HHcltXprFANKc(HDz zNfJr~@?vc53BrV4A+&KL89ZrT<-yyW?{ip5CIRPO>QFiE1}34 z&AD>-xej3I8%Jw8>m6hH*w|ysG_7oLn7fp^*mkxA{=2&bYe1OE<*Q3`_JVXC`nahB zAG<2Swau>`P0`)qfr3aI+vi}Q6IBx~saWQanjKXRG$FmEUt%ei;W!A%js6*MDfI>L z%PAe^o@1HxU%%S%ESp^7QP@{Tn;t`8;_KMk$r}Ee;_yylSZf8H0{bfva?@d$4J^b2 zvETq{hCaz65cY;C-eNfWxR$@HG)N@jfB?$ac=KQc<>a2-<}KU3-lGR<1!nLr6RZj3 z%Sfc4uU`G#I9ZhgC7+G)PI0QpFX-%Ji4rW{=S5haGXVmo5*(1C1wDj8!oIYn*2UL;QPkRkCi&_ejQ$-l6Zg3mZ73t9u%kw93{V|VY_Ct^wXBO#V{uDuiiafH6ZpO!F}q-_T%Z6mM%kYkSlb=k}%J-u~|PV_)B_4-r;L= z2ZE%CTGpf8>aJ*T&~IkRn?gOaR3Y%4;oZZkTz$YV9E{6ar#Lgp)3hYbmtiMYW2Y#H z!@jlOh(r1AQffYIKx%zJ5rm|+y{$q%p z-i;f9A5c^{kG~#$@xIdpir)v!q#~lt6{2_}PtXNPBV(GI`q>UTRRP*RJ+iETihlu0 zPuY<#dD>k5H;Ow~*9>=?IttMUL8)GIKnZzdcol$$cq>uwQUbu);&ItqUw2KIlIjzB zO}&#R*0{H@$k@r{_>m4uJxRUTvCS3;hHJvK2q3U?M@5i2<0t=CqtCqp_f^n?cYLY| z`mQ0&+5hasC?=1>p4El{1=Fp9Ie(oU939c!p8eA=D_h~CJyCaq)ef%eRO-t7T{H%9 z2S>1Z^VDtXLbClTps0Kl1>uJwtqQ>4Hidk-_>gnBHydT$_0AGHh?@6@1lGUE_JI`o zdKvqdf(V7CLVJeen;$HN4{?rr`Rp(UNf<)FiO^Z5z2P`Ww%Hhhu35LPjDPYe@u)v> zxab4f5HaTVN;lfn*nB)**@c#8joiIX!u0=uvHmx|(}o;y{u2^89}<-M(If$u8pDx= zEpPK<`2VJU4JMoZ`J830ffLzlF<+9BpZgDDl;TfzSYQ9eTUqb&!^K!8E`eI+p_cI6mlN@w-JPzX@INHX2W$5EBSWSOy?#He z&F_$hYCtA=zB@ji{d4jsc?JU(KjzGYqjb;OhB&4yo^`H8C!{1 z*_1UL-oT#O>Izzzq_5`y=-1$8JrFGUNcG{ZoX;E_?@BD2&{^4bt;``H6!};%TW&C$?hnQ2=+JGhbQY@ zXFRYjB~XbvDNUjQ)b4ZONSB{Y>xaFge18Ck0_=z0j=}FA!Gu*n?9i+<)CcVRX3;rV zdk6I1$3-0^RUr@d1?zf;6K025aJ>t3PP?Y16`OJgBnlyt$YPi1z>MM(5(MW&`##3cE1PHhw?#19{3_XWOe_Lp$2D#Exg#rBDVo*Scd@>ZYuk98r|pD+LYQ<5U< zg(Ia?N*^qif`NgSZmcv`3&(zF0RMlKPxRD*K6>coRHJhgv@I@M32v_QXiq#q4r@*6 zcsF31YmGWqHKu5qvZ+fj6GnkHsfhn2*^lVtoCv`QB>^G-aXvRK7Q-Ntw%h{qwV(u4 zQ>-O=zY*6FuHCa}PSNRRcjdcAodiaI?TcmJbzOJ!mkW>9af^GuV~hrPVM5a&zSjBX zF<}>BTXUW{JiSe|&x1gYOn0H}Ww1kp0k=-#dn?+)+$(?(@lEG>@{!ZhhT-~SF>gLb zs)=gxpE1jF{nAZe&AlV-o`!13Xh^N~n&&r3r6J(dE+*%z0=boo^}D=BUQp_DMjn23 zuHe!DfZolwnB2|U;au{jsIjzTjPHdF>!V9Dy+AXh-y;T%MZPI=`ixpuO?pEE_iT|b z5fMB2NdNy|Ns3|(>q(RGh_E2UscL^|hOCtsjo%1ddK_Dlk&riBKapFZEU9%;O#n5&+o+Q~sSQB~e) zWp6;y*b$! zyDzo(y&|Le-`M?6iIh|YNCd%^XfS};|FuJiAPuq zlK^U(O%H?Bl0~4c_1iHp;o@EOwcYdl!`y(8S){N%)3#&(|KTHS0z!}a9}Tu2#Tcgl za3V<*0@BOD-bpEW$mI$(EdTxZ7VW^!Sz zFBPUf1<-6od;S}vK`~G;uIL+7qmDuxh4|4qWMuk|Cgt};y~^RgS^|yO6vV$6j4`BK zIIIPze5cdP6ozlUuIeW%Heapg<7aCt&qY!A6gCPLs{AE~aF!ALjoUsPo-CzqO|-S$ zOVinE~G5-bSLrL z^5(>j4)xt{efg@!jn*|Q-9R)gi6+g#?~Li{`lT;_Yhkb!*MG7|FM{0O0e>-XYgq`1 z=z6?RoA)`izZG8d8v0<%%cZbZTDPuTJ#2L&{kxxP3SRMl-00d5^2e!ozH5Vd?c z(ii*2KJyVHKnxv&r}5<$&TfDAb+RfEyO+nHZR9#HZxvO*lDW_9WfT3D(bLfyJ>x3C zg#>cV7HJ=|b0w$L1t>aP6Mk7-oq#~*ePnGFU$k7!Bgw{JJ6+?Wew`h)y(7NZ z6)d@k@xRJk+s6LD5fl?N_Vym6EOH1d=DyP{D^;qHx%aqPJo+F>m6g6Nflc0{0?`3w z79xrHYvNkP5w`#gfhos(ogX__4D~e+1(&gW;SZ*%T_d0Y9U1cAM-Q!D zQ9hz=)>f~PVu?@A=l)=Xb!WDY{Up=!|I=LD6TwwNeS(vD__?M!{1u&??Dh3Uu%t2V_&qDnP)OCpr9?W{m@c1B;P9MuE}nZ373PH1Ls-mF*0JcBDjA0s-~}Xc4?tX z^AQ?HZwLlA*#`^tVGqcVhzOa_NGkV10k)k^J^vG|3Xh>@s^n-l3)B7TF54V{UXK{M zzNzdRF38}xG~rq#q|TJrxHYKpVbeU|39I+>Cr)Zl-j>esoHSsAQE%s2XI$B<7%Bo;>AZL;^Ne*P}en-5Y5UKcmRC=l@QkZ}OK<(Xom$Y9a%%iJi5fk&77q zFmrvr%eK4G9?k^N`z~%e@+5bhPrC*N?gHRidC|Vcm|GgId@mqpVCxdzTy7qmztKagbv@-lbD;WskTR2%U2u8Y zR|+#FqO3ipYhAi5I3VgBTXB+x3z+a2*WYczqcnJ_^6mNR3g&8?F5qA~>}Wt?)GPnQ zU0S0gl6;GqY&ak?UHQ#1#|^<;Q=E^Xujg;14b4T9{lyDIfB)ROLYgMdbbS4JsUVP8 z+pOl!KWS@`zeEnQ$f-1qbs2m`>1o&fimoq0=pob~l3UGLx{sL70p(#Y`|NPDm|Eu-=FFa|hzKn$HI?=4W8IY6*;qTWQ(xggDlKoF32XTqO zO3goi92Ym=nKt;TF&K}dRxP-&#}~pzci2+gFFC}}IQ|LcugAMZeD(_9pGV0D4z)39 z0;%-g+-pO-6)f`2Sz||tX)T={b{RUqv8jp_Iijx9HDU{t^0a#*ZJra@@9|&H3EbO> zq(^ri;_RS{ht~_L02B{SdK6Q%B2^^A(S`jJCA47@{*3V6k1c#DMjxW6=0^zvc9}($ z^qt36O#Ni`pyiXt5y(~XNHC|qizzxjymlrXmygoYnf?T-IYObHT2&-+S5BKa;kc~} zsX|da*bUe%(+UL6PTgvo1zbw_L`c9x@x>J0?1ic9(;yvT^ftpR;D7mxBRw( zZkd;mv=r?1_AeC`K_PKoaxZBd;)y20Bc550O)FM?L}-^BZ9>F(S+)*Ox7ot|KNOFS zBsfvbF4wiechc`Gka@23b{UGa+cO$Da2L0{YnJz*a;*3_Rh4b;N#*4c$vquwv#aKh|@ItCVryhH$k71R*neQgxw;@-iNLmdQt8skMe6{_0P<8+CP9z_J^#7VqN&_%*>Q!qp zLh%Fwb#}jcJ1Q(C2I?eEVKpo}g?B?{fP^4=&Yt~+mrdTBHX1POzm3b4a?F|iHV8vj z|I)=4+lAm*MvluP3JM(a+EOFTeAIo2hl&+``6nH||3IAwIaGW~Yg*>9FUHWv@^Q-p zm>qdhaudc)c-GYIa9%BS2#dvTZyjlo=c#RO)$r>)+iE`Yo4G0pzLT$&}bZjRwP$L$d(a1M*PjEWqlT;KRbd=K~xb@L0);zC( zbbt2|6&FD1=SnVCXE%0YZq*rOLX~h;x#N7p1l(8QBPZW})T289SGxFzmuKV+Mps>v zBBba>HX!dREJ1G+W%EP#I&sYW(@i)f(3`NsiNLB!aa2;sl^-ciH+u82JDE__=ACvk z)3mOwsjFgjzx7XC?-^^aG7>vti-LEnt6Lv{Wxd7KAuK{uG=`%vPvqBKrzKdo z|NqRYV4p&i0`B^uI1v;YTLOG#LBQiYsQB<8CM^AOBcI0wFRW1+F98=d~ynKpv+P~xTH z70tnBg7$J^yIdYb!YjP{^dp%SD4SvT<^WAurM7KSU`jg5{Mn_SQx`te2Hp*bN=F}!X zC3kV+|CrYO_Uja4B#MKgg-k?+nd<%^(*b$xo03-8Q za-j{)q0`i9LCg&`+0x?Yiv5-*$HIi{Urp{rEMrfoZkS}qp}DTv>Jodjr8m=;CaK@R zm9%h=JV8!-g4mKZlX;HgE2SI>1H(Xp=sTVlTXR3_2N5pbNo8ICu?Wk%sXzrCY5u6m zc}nN2jbk8@QH8|X?=u~P{yNJ;Q9msYBUk%zvKMI3@9urlGs@Cc#C`D5u4}wY*KD8; z8viYYU>=U`wtBTk?Dnh}u&&=-d16-0d(9wu?cxmk$`NhHQ){`+jeG^(hf9r-H7+ywiBZ(e;<{7X-+SRroUXo-KL`#<|$D>vgLGaCm{ZGLb3_H^Q8M08dsN|iJX1q-R2Be7E9<}>HmF+5zdt#wf z!W~{q>;os!>pWjL9UgL$f63L@MxU(#X|#Uo`CG)ZS!|Ss4RDFKKjwZM-Rc9lQ&kvl zchqi3kE1S@SdTA=wLg?iIv8tFmA%`TsgPI;Z|I#4x{>@w!hUa5(z0;}h)s$zA)UZK ztgRVbexRX@uw~z}t`cf3;k~m>cq(GRarjpEV)-QN2@|Gn1*CU`j!05JtUHBz?dBbv zc7GP^Pnyr)=Zp^lGS_RXqz|dzr@E)yvTEy|prD&v#%uktPRw%L?t5o%0h1HG1 z+BAJMOxp{k)VZ1`1T)|^={OtEIk5X%CeG|;7h0|AsE`?82D&$1aLHbe@kKW`wDUGjujLOmRwy zW3JPfq**blodh&BgY_h>!#ZQFHU%Tn3YxWA%SBz9m0oT#wuUikPyDa^6|0uZ+`x{n z^aRA2dm+Vem>_wisF5Gho{B(Gl$} zJm{g`dKiGW_J_8YcKc#bD9bW(zvmvCy$g&;2;# zi>TY=W3kMZ$~8~ig3G$8NOOHFTXq>&D3~vN|M+?>70WHUz`LJig;oUvOXzIM$Y(3| zo^5{=tXLw^a{Zu|rl~QcbK!i>xj-xC$bcIKd3catsymmfh}L4qJDt|JQoM5;gH%N+ z&OIdiibHZbLN?NR@}_Ja25o)byjQw`M1&+i5ap6LQ|uFQB5z)%NR=FWZDWXSG~}=W zCtcNnJuU;Ok7=gq1!yNk;Nh�M{Jz2Dqk61y}h-^M!O9Ag?c$l;55$CH9RaO`VQq zqtzvcB4)bC^uLxeqb zd2H2Ncvt#CS5e~vj{pO_g)|iS!N!Qlx-YJ+T?=v2;xn9Guq~r_p~Mf-s-c&< z_UZa(_F-R?25=%*_xfjI6}+MqqwrsD}qt+XV8s9 zZXEc^yfP|_h$5JZaeCQ3D5<5f7U&|+rcGltIT+4QBo!VXD?{u%o7j0XZ>8(9Io0*W z3{gYEUsv~_cxiUra-YptuFaA9HP|XuFPcfUcRl!VruK}jVsF(V1eCugcr)+?kqlZg z2vhts7c>1|wI@wUjr|np6^4&vF7k;7;*yU+r~kt{n3!;)J76@?YD!^!xr_VaIR`}J!SZQ;ejdt@(M@{pJrQ>yg(YR_sIQsioX((*JH{Q(3~)lN0+F9XAc zDwWL1*_DBrOd_NF_2IA9EUHu4)v^v}_eQb7HOEMF`2pZ`b<Mx5s>6%- zR#-K6A0>hlnq)iS?iLgm)c?}g=PJZlEx5}h(ZfW40@*jHQlZP0aW`%ol7hA(h!-b#kVSJI)|M~#V#LT z|MNq%)H0&qi?(o+Th2HX+wf+&?sD42@p3XWMl@$|2rd;pSAr0pwWe(J*LeOpyhQ0k z>AAjGa(x1A;d`HU58+NRioeO<<@HJA$HwzpHJqiXNO71*+ZZ;+DaeJSM<&Rm#wb$z=(j1v#O1AvrMr*l0!b;JRMh6Ng~ZxQj1P&b zDIk9;k_av~7LZeycUIO#>Em-UB6>%JEZxl1X$|@8WCB%4&668nLydl7M+A$^1$y)| zX-cf85;IF50-Cn8@Se0-EX-2)@}!mBY|?;MHBFwJ+W~F-gy%$}>$P8x|4bV$PLWXh zHRK%W-j?pu;4zA;OhnA|a3zfTVR&pCh=mxSZq}{nQ}xT0F-7f2zRltv(|zfuf7)|; zIe>*=w30(}X?lXvHk5zt+la<E6N_P!AkUNAro&^?Zn?hzV7b zkH>en1jEwYVy5=ut8kQ)> zTRwYu2>~3@46nr{6nuYg=w-1lXg)LKfa=vYb4Q>&sGbgVFFzeQNHg3jG4yCyi^$Xs zdvR0p%{svbk_NsOq|Wm7QZbZJCZS0)EA0rp7$Y~xk590(jct?dWWTuEyxd zfW})^w+Qy|Jr$L0-@)r-uHJ`1EJRBgyPe?_N8R?`^1R)U%AIp7;R)3}nv9EG=??G9 zLj}k82cNh%)OE6>f86Qh(Hq})23qsv@IloFOc{xJT30{+3LDLw*x<|d6eUPb%)wS| zS2<8kzvWr1wN{!(I2&K+Hu(N;t)z$*5ifiex+l0?;Qs0~vQ-9E^Uiy&gAIb{ zNzpG=UCKwA&uhF$h%R`x`@*aNCp?Le84>9T=SeX9<8LHh^agm4lvKoetQtvh<><^T ztEwkHw`9I!Y2S%Qf{MZJfPii<#B7Z;ah(RBYM>_$2Vcp8_AUDIA-pTU3)2nt)q103}(^t7MQ&FJE-D@BP3>H)R0(8Grx> z#yr=-D%1^{K0T6}-7@C}+|F^Zu&LmbbK1!6M8>^0&Iv<$aQ_yG7 z0T5TcF(X|N?Ezs`f@J$>0f=$1vB__d>$4)!6ZUA7Cj#t{hiOv2PO3>{6VXlBll*@k z4Nct`j0WURlQzY+*HE}zz6%fdB1Mj4kqFbdj>FeVt^olf5X)e1ty3orZzTJLZ#$gn zyNHMUFw=^ki&q&njyx4;Dz1YpLLkxTk`h%F&=f9A0FtR6aZL(${lm!C-JgL1;ld-w zx@K~#O*m7A$jJ-xB;^cO9$Eoa0J>pwvdNIcnlQtO80@;OcHT->wEn{uv zTdz*OG%{9vN4IsQ3ZF|=o~;qfG^;I*KKOgqSG!rKk^bt6SyQ_^jIj(;WdwY+T5Htt zbf;QcEF%p?Osa>LyBS>|t6_R6Zd3Y$MzjW9G-WsKl0X<*6ouYRBX1@lCBlk zFAs$pRG^n6?BxWdB2#UEla zW)TOX4gEa<5`GlXPl=l&&hj%*=zCIvz<>bw1k_`olmo|bOmg!DiDpLD>iZjsAyD!J zxa;dgU-g?BX@UB9V+%btcciV=cT|WGAiJ(NYb4Ts z6h-uLD!08(WQ}9pG+Tb4c(@SxnX=b7Lr&womR>@?60} zP_UMLX?Xck5`c6mXu+bx(G(^WFXK-uS8EilFg?6PFj~A z3ZC=VF}v%6%!G3d4gf1|1=%4XRx}isl9RkvfC^A6LNx>Xlo0jL2skKB9*Ec9qwvtR zfGGjV&kX8w2nhX9SxYR!fM8x@LohD9sg z?m{yq&$~aiwy9`7&0MbOIL&+o2Nly>X34H<{=+O1%nyDS3GspOPloFm=@8Jyf<0Bf z<|d5ji3jtc^BbXKlB=f5Gbnddc0Pg(&rEI_vY_n)_T2&}u5L&o816P{)8CmveE&5( zatabO&Z~VIMAP8K8C$L9a1NXpR4ENA+IJZq%`APJQfhE=Hgyr4QPVBmKAOGcm18tz z2Hb75Nrbt|AHWXKLh5uwzPxJJo%uZwr5*Jiy$o(^-AZ*7!U+JtiiP*v=^U~g?q`V~ z;op~@lHs7L9tQ`+v)cR+cd`@R{fBUBuF$OM67ijPX#%Q_kc`&LVq_EP8g1)X@0=(&?_JzZASh2jGXBXWde^ACjQUlNAsSR4|7wmS9$&%BL#2U$ z$jPi7rY61&pg`$PWUUTbd3)L=%je5Yj}_HcSX!$}RXRfLWw+CwyQ?BiKh*&!gWUX$ zatN|N`s#^5*_%7dCjq-gw4R{r(M`Gn$9PJzHs?E%ci^4wxE-wGZgzaO|AIMET>cs7 zpTiUEcwRR9GsDKUg?9;fu|iNE%OX&docz8{b*| z(3Sd1e|uSKm|p~ji+t>04gRSGT@n_V88TZSTXE4U%-j*Vuh(c} z{x=zncvQ74po5+3o&rH|bi2C_7N>vz;`ijH{zOIvo1cI@Q1eRR(>Xp0aR(T|?{-hl zC2#{5H}lvcE;>#UC_`}qhP zVld@%f8C-Ak$B_U18_#HV`en4k3mmIu1>Q`I%mXk&HzC5sjO^j39@4&sF%0%Yb5VuFD%U@*C=%i-r)H*eqp$7qfcg2wf#$+AVV4?w%wH3YMj(3j*oMJB z8Oz{j-#6K*^acrb4q2GS0x?x$O;!b(-*J7L=6Wtra|v5i4%fY-)F6f~)u41C@Zlsw44RjoB?m+S}4gTG`PXiK0Be?d|1pq|r zhz<9SdH?r$+g=m;;*_a_SmdB`7oIOEhQ0gssui?_M7mQ09&Pc$Y$IypzqQR7*<~F^ zJ_S*rNCDh~=zHsn)l;@Z&HOS9& zlCo)gJ#B&RBc4tfBu&S_AMabIv*YGQiBtH;8v!U01Wgs7w_B-f6f1;sY(}%r?j!mG z#5}L*oG`xh7!Z@zve-*@n^QBr!aDhGXBbZt6vre<6RJ zrA$FqoiM%b*T6lkBAs{=45kQRfo7#8EH^{cPQ3nR!j?^DmYJ||Rw6Ihq)#sFCnn;>a zC~-*XC{&8=oko5xO}dl!I;)Fp|P^6prZE`^S`GK7Kd`U~6a&oQ5~EOz*&{z(^KBrGo#IRGr*a{~oS7uC1M+&z&Y zKJi&L{}1}E@TU!1_u~;GNKGTe?t*YV)EfIz5X3z{jxz)!6L41bOdrJjOwLt^DRxA; z;tV>SVJXodR+tI){i;l5HQ(xBk|maw`ErI8E|s@#WL*sw&%bbE4WIAcN$V2&ZqJ>0 z542Gqq}mf55hX|d#RGyX2X=c*1SAeMYZW5Ilgp@|8 ziY`cNP=mlKWg^?U-5y4KP?&r`09i*Bf5K+cCD&hOG4T!OAJS_qd?D%iHa3?dN^d!u zMcOJ0`9o1+$!-9=1`!!q!bfU4l61bt8S9AAL^PiVcy|za{Ymw8DaV8lJ~=`CTehZQ zn!&S}$9%NJo8TPR{y*@cj#@w}O1o99#39#SL>F>?Ni&TC{sPqY&^Di*AN9 zt%66DwR|RAmyvx(+Nen06IlQ7v8CV;t>muov}T_*Qf+sH;{>kZn~QyDI{{Y_S4B=exvP!oD>=|E+F%=`@h#Q>dsx0 zRd1de@11~=Ubk#IF2qr3IhyrswEL>el%8MoII>s16;3S*%6Q=XlZrfgj+F;A&Sls)TN^8mfAkf%}&Fi9a2nBOr0z11BqAv>n*;k)FqCO;BS*7!3eTk9A0{e z^-}k;5p7<2OqrtQQA84QJAp!9LV~+Tv+5_U0!%D>zt3__-pC84*P8h8ds)O(Icfj9 z>ojuj@>W(0PR0U&j8%__DRoZsEMg4jO2fwHQfmNEqCJoxuheN)2Jnm5I<)cRyqsqC zdVYD)G2!-VsKkR}uw})TWPNXQKtx5m!CHfe)(%gEmJT{S8|TeW&P(a82jonXz&uxY z)7?SGZ6T8y=j)N&iq!Y)BVM`>|omf za$8Gz8Wns_3eY`bAGmptq`g$oaulepQGI`wsxj^)oduNSSJp!=I}K=ttB%65kn1=F zV^Agz@4`nr5%fC$7sLQY4^+8j^I2snJn^$7D!Ino(x|JLt}&3c?-~Zj`huk{2bt$< zw~v8A|CFB}RPvV)PUabcnQ%h)xNjlSV-2j<33a2e%8u$BGu+xrZsegz^)NBF1&KSz z;E%0oY_K&NypQt7{fEaQA!yc~asHni`?Rgs7}{T>dZ(QaMl_!~y{r-(59rr0Bm6{{ z6C6^SB_mJTZxb(16fco=WJ=6^e>^Tm=c}Gv0CX6vtZXv2eG+LZmDZ4@ZWey@lV9~2 z*RfECuAG2ERvOd3_xS8AbF5U!yC)A@`f-Je%wF=Pb8b2lOjW0cQf3w}DBg4C(cB_J z0AN6$zvyeKZf{Gc?Ca_(Oj~n2VpT9TC?x5Y;E7=*74=wURFviR$?g?|L)guB0!+qarv3a^e2G0HDpZ*(V zUe1U4$m6@TFibK{=i&74ccUI}MH6)fgD_)f(WP^tk1<9BLe8u9V5TaqYkKqjDCIJ0WXV*j zHehsMP&N*3Oz6WZlV2`rR^!4)EpYDvqy~t-Y1kvobLjKbRO9P?AuQ8S=i(K+WjLVg3ewoRd^Kn-wZCp5!$M6G=i z`Q&C=bw1L+g#XnBqt_DDUTt)dtXgq2oH<_keLRqa(K-Hd9zYsZD&tpiO z-n?E3e=?&qOC=u3bt&QLs!r-QewUA?7_GL+ZGw$Ss`xO=Jd~1`0@i(VOzH{nvsZ^G zOE)AT&Bxe&(B@@yCmUg2QZoG&E14>3JW$sdm@f32+d`>-{h^p#e3S9nlGN~b=*7&S zKByT0aiG~ArTyXPE?n{9y=2(kn`>Q!t(PR8nr%CYv*k+YYnz7Dg|;yCB(e(sF7~An zjb9Ik<0bKH!?Y#i6*#6;1ILf`URNKT{8G%_4>7ZolCtzUZhXR6)7OddCl37ZV6wEqPA}>oek9Nr-K{(>oDz%m4rE@q6e} z#A*dqce}Sudt#GF`TX>c=8K{}@!^k1WDba_1Ge|O#pn45((_T?CBzv;)dWP4%S(X$ ziV*C&GnWj;_!)5XCEFU1kz%y3{0JySh4TC|n#79{eOfu=gf&c5T03m02Jcd#=S^mu zX0Wo}<}Y^|9+yq@e3H zf&sJA2({+m_$AT_^6_`{bOB)x?nT&Q>SjBe(p`eF5mwmyVV3IRj_L@~y~NiIR-PE* zI?3q6pK8|`R*c|-Jqr?G(2(1x)%6??|FzrRsO(Y#e&d0%4F$REB4?n|;275?Ut7GR zDGcLIzafZuLyh(BmJX!QXrLl)$gu}fjIrqGJ%ghJIr)h?tQ&y&6+iNU{19NSY)u{+d!|aviiX^ho+%#UA zisq%tLNvYgeu$KV-XXP=^-t{gh#AyDg-Ll(z3bN-r9gC1pIk#rb(M*$g<^yVBczt| zR!B%P;mXW?7Vy)^E*BPbru!wwdG3s_SZq-lBxQG46jrPv?#@NzUAhx+bUe5W4n|0c zE#;{TO@~u)@}E&H7RK}l^#H90mk8vRd4I_h34%qMVQ^uAIPOhm3BVLP+PRv}ac#yX zaQj*}a0rlMl$savVJZ<_Pg_C1cWOEUbb3BDl+DtFV6ImvNjX-8CreU$Ae<1D{$O3} z`r4AJ#y-dhboTf0-BG4C!Ij(m0M=u?$6_3^ckj@M&#vH)nX zo~{OWC5u}|qjjDHU6K2ud)k-)C;&8ePQYvd_&}3W33{`IJHAeD_X~-kR93JYnZMp+ z)m(6us-t&bXh(m^5LNIhh-)x1T_aHc|M2T<`1kDfQUBGAWj!SL0Dq1>H_~O6l|-wG zhK#EJeqM}?3dGG#_JCTF@^ZK!o**#2Ez^dO|EE4|u>=T}+xn#dgmJt4QIg`)(t~a{ za(7fd!rPEiO5t=0P9*^APMQQBoYqo6h%aPlwfN^##)#?OII!ry_+c*S9vx?1CjPOs zvBDj3)VkL*iYc{ieZ#X-Yf0ygUF`B4k94dga=6Er2#@`6dk#f#<@#Sy*Ov0|^*F}M z|5&az5&Rq4t$prHM4T_4F=_1SROsafiF#$(%|wUL9Q>N;=yo zdSvXwR(Y>tXq7+&;XC0B^j>h`ewd*@Nv4GPno#c1$?aiMvxr^RD5KzE_)$Cd6~aPP z-UW@rjQ@xm_LsjyGH?=p74nCc+;);qwzAK3{82}|3I;`~g-i+&2zOULSU^16q7hRk3`cIc z&?bY=_jr-L8<1##qO67S6^fI5(zsB{q~OmsJ@BX#^d#LAP10W0dNdCw6d3h1HolL3 zyM{yX|KfO%o92BZn{&G=hzk3$CYMkzb}DsBK?{RfDBTUJQnAhui1sZ z^?Ay4#qU9KW7K))#!c_7tCJTid!PoEMfvS4H;7jo-1LR>?3$(gJNeK1LEkrnO)dVo z%kIn9pTrgYzSiMY!#to>-p*Pl2KkSRenoMNef50$fn26XQqVSswf~PDCcl5N8q!eD zi$YQ9_5lC-7~&�KL@2fIP4k~jajiBKk|m)|~S zR9zGojwJXOIJJh!Prd%4Ka zR-T6n4w^3uuH3HXE;)=5eF3bck6EnEj0|VOUe@R9Fo|w2f1YqVFu1+IE;OkgeqN+k zzI@5_3QNoxUoLE^QZz@4K7QPK6WOv zdCAYd@TxS3y&F*q5C8x!${wqlpIL!3wts~-G#IX~h4Z3=)C@n{L=wS7P~+}!h{kRH7Bor!D3 z8F&^oAGvxG9!j>-^0O2ZFp=tgBZpDoQ0|yILz*q3VH?nVX6|%eOaG7@37|;hJ&S#6 zhG7us-aJcX>G*W0!6?Px*!aGKlX$EdkL`OXZs)>vH7l|@_;2i%dMB7n$Oig2eDcBA z2X?S?;?O+_*UD(EZDfK)YL6y0qAUwEB77bU56B=cau&N3X%lf zLmnyb^-ePa1-aml%ea@D{&W^OZqz^Cta8u@kXq~iC*6>p3rtAe8Lf%NMsSXlqo3Rd z7aXz@-*0w$fXcOHwm;I~F?orIG+Vqxe6amoEO=Xt4r|^Ug=P6?!NBV&W--oC^is&k zZFJ5aXkS!}W?PzKv%tIDFgJf1-KOpo2CquQhrv8X%t-`-eG|a7@W{lsc(IlfbfU^g zv{)&<$~#GV&`!-dhidrd39yfUAUWZ4tb!(9;bWN+0@ha%9egxPTGsb2=Ey*TiN7k( zzdc6Ts-}IuaVz|WgS(Ncn=s+O@^IFDE4Wit-I3efvzZ@3ZrO5tNm5Xa%adkIOywO{ z|1ltWC-#HH-lIaQ`%=~^q;EOyLrowk1Bg<_L(AD#&QcgZH)aE-!8ioOL0_ffW1`05 zPLmU%Mw^+xg^&h#-GYo@OUtd5L7$p?{Z~+x$ zoj&%w1p$W%)g``n8(rM`DI;7Z5|(-=GHQl2>Bg&>lD77w0qso%lxfmTR#uxL_C~~3 zYm6&&fB)#N7n9*_^s*RozBQwhK#8?3*B`T`kttwlt|*n(fJ<>>Sg83-K7VA2=ei;X zO=H$)VHIx4BF-3BQe65GaEPidq{GFtt%Gaq1qkc{!v)=hKVSCsn|jGj-$+1m#}Qv> z@BZ?~NiJvsdJ7D#q~Qg|&f(6GOMLHy2~1K$b$v3I^+D_^?`yV1lt@RJD5Q45gA9Jd zLIwv@8e1I6_i$(jy}USH7Y$1Uk<1>gffS`cK^5;}zyZDA=#<}UeHO6khmKIqItb&i zp^<|y>}1TA?KiLLDmtp^8>gfDKB{?mm`2&n#D&$?DOba9p64+A;u-3N>-OQyDciklucx@c++4x}IkwR)F~jTE^2FBHn?Q%#;2K(@@O=LldGpGA zF8`ZB$~4g;LZww{!cySP3vr>TlY{;s;S2Ye2-`L0S-04iA1D~z3zQya*c$SGrc9yD zSst5aR8c?^45pUASy^LkYVOTj1TGptcnB4=Te@EoG%^hHtKQ8mAP6%>NGuRGWeC_x zNb0s)vONIuasMR0g zKp)liCWen1-8DdgqE9rzVxx_(kwl|pyjFQ`teUh_!c_THX6}K%svCieuAtWi=ToMA zs0s9OYWZwFFKk%;JP-xmV^;>(bfmf-z9md>Zq?v-$NeeE>$Xa`WTxU?S$MCGP>Wnq z(vm3%eu8_2yo={#y;OYqnE~A>y1&5GBL+MUMUwz}#BhcqlIa+=t@8^$B8ri()R(=AMuMB5SoC&uZlZqfw~uG(MYE7<-rGku7pnq}kPATNS_T*!wg$NjQhf`>JI_68 z<*~By!0-7r1}>BQ&ICqj(a7^+ik!W>`#D2w*6s7*Wl zsN0%V6;Po{8ZCJp>9da$?l=Hw?mGGLKs_3W7%XC88$;#@L~M=y^l^#711u=TZWjhl z60<-<2A~(z$77|-Aeue?eVh2MiuoqYP>|w^xsBSaaVfuq6j+gH(88QOkkwEa8-*xb z;T0|d9y?e7In@KlvKi+giEI&m8QFHV?LRj$f#115?&?t(%xQ*#E$;<64XT1 ze(Ev2m$*5#r3PiXomWSuv48QnX%@QfNh^|*9qC2BT}y$$C<5+cwJypl6mW2%6QbTF)iSCEx&JPA#{B+!Un@Z|R2N+31iFxTNen~(h z;Y}$J@WMW@_GzM!Cr!e`{m@73Vzcs8of%;e*>=9!P$<_G;7bHAMwm8otXTdMs|4Ooebtq4(O&>R19&NXWTJ$CS^$}sTKi$~$ zKndGc`04OHe|2)*#;v`URJLcg@2y`2!XV7SXllGe4hMMrBB;+91f-jT53ihhNHIFq z9kS#8#_G-~q!IxP;kin!4yIw*9`@w7iHg1L#si}BC*NE;dO@MWrtQ5T=Y3anPl^q2 zy?#cPRf($oB?-annJC0LH}A&<3Tk+jpY0AS>L(%-=|1RU;z7yG$gx|C0>oGdH=4a= z?5U~VepOUJFz4#9hhsZdPZbTkYCH(2m<>*CzEKywHFu81GE69hx*pWe-Mz>E6yKAx zS~ESeKk#Lvy{DB+K6TlkgL+1N9oQKg@G>or%1i=yK9^)keBLi|I_Y!C0#t@xjIX|e z7L=e0?i{|dG$u%jMeN6TC3x_b|*6$OAyrQl}r_A!_jV09{+~W zu)W4&d4LEpx+b9=QC@gS&3txcyaDGdg;8S4j`l6WP=Rm82}7YnAmNxYeY{S_5!BEjsd(@JF-f#op4 zpsP&=X-1qO4ZJr_HYhg;@}-}d)A7%kFMpE!q9GlQ0Iqf{ex3iR%A=mCelibEm^)H# zdOq>0C&uYmX&|b_KpCUsd(~5ZY(J83?#=&^h=42{G+}!g{b%9(RBKT23i~Dz<2ql@Qjl zr`lZ9mu$&K)6DJ6?>HDxIQ4aCZ_=h(a7K0XbRIayNmB_69XCS@ITyL<@=y-&;{3B^ z&8|d%(WpQGS5HZWlg;?5@L+x~MCe^A7i-HA4{l9p48B(4R={%#fm_5zQh4E`yss5E zYN}yPfYIu3jPV?0zZmu^-r~utpAK5(NtaCPhHGQQMc7@2*sfYi`PI+=Rc63x9>%J1 z^)^JKmJM(`5wuDMkUVIkJ%20c?AAr@1kW{7%0_EfntCd$mLY+IzR%HwX+sc*&>j52 zbow)s72@PFA^jlUkEeo@a6Flu@8;2hZU*n;{dzzJyXrk}8q@3~1Z&;S{tkxaKr#{W zfi+(01kg@xWp7uSc78`-_mALf-v9l&kL4ona%YdD9|I5bk(#Xrqs;VtZERkn4Gu5^ z@6>zG5Hwk9KaF@d(Y6Iu*iyQaULGl=o5|Y`|l$E z3Dp5#3;?I$`)Ms8r*uvbzohXM{`=>WwSkaXjyVnJ=SYJkeITJThm&eUP8ySbApiYi z!a#IIV4{g-*UpZ8B23xHlk%2K!BQMfkDnqfCEluHvj^ZcM10Bg79(wJtbd~LSMFV! zt&~QEWtr>S1-Obro` z;K-UKq2RmbXj(FEtM`cI<-V5~!G3z5J_xnchTSLGCjZ3^K~^tu=~=EJ2VhmFYq}L8 zXFvpNOFp%GryNvJSZP`hPr`J~X~HCoI3i1;_5b~5(XYlsoeEV;VvyT^DG%%& z9(xJm28YUn|2;70V=vyO1%-BXv7BsFvUl!A6QZV{Z);nOB1eVLg?(?s|NkE@+BN2_ zKCtg!@nZor9~yxKQ`AUeD%go zx~nd=8EJS__PDOGJsSXz!47F}WnYh9O9vKN7jbIY)WNN}K8NWUSHDzj?);=FZ;bgX zx{QeDMBYwW<|4~SYXkaaj_+9k2sd_aa;VqzaaoQAJHBPjVgg~(T`h$OH+lHNpZMzH zG}jl*OuN_}xw&h+!kC))D?+!A4z2$ zY|)Mts}WDT=r&-k^o5Tm?}*0$Aw2h@6Lb|V{KiIcNsxF~ve zezrmEO!BIY9$%3YE`ewQLd-u0#BIS=j|D2XKG$bE+ zulGp_k=i;Au6p0i`;nMyg#^_lV7fIQYqBXN1vDcO#Jh| zbU>7U8?6sjEyTDD>Mx6J>n>6__QI=&Fv=$7bT{jh*byg2`XU9TJAIw#B+7QoG!O2! zkT_m5OBk=w!<(l=yW~nw}`XRCj&$&U;4o$ zjANc}5gwurPrqNu%~Q@$It_%ceO$H*BRd4+?pv45Gs1&`xpB5KM#$HLI%0t8>x9lz zrB3$OmA?cXDU57-Vaht=0%x!>$I<)WeKw1JYRQ>Z^PCLGx5s`gP zBCk33?iE)iTic6frNqCnU+=D~KF%PU{hDwUH}LO))6-0V+vjYqj`{m5v#*K zzBhx1_5zI+7Kz-y2n%DwJ8dm0HLei;(a8K1E;B99u&X=%gg0Ne`y^d;97ZeW1n!t|3vj%8caANd-aRL>kmjJX7tnfJ zZ#^TM@_gYo1wZo=Et(>%Tfat5X!2OG&gXTm6AoO!l!Qifg3ZrqW50`$(hZ^~ zN=Y7I*9nbu27gH?yccAbvSrQkad<-ms`{-2K`|EIkWF--!48 z|K=Le#2ulv@ubmC+$~!ZDlN)F|G~C&yEJ?4Y2YSZ<-Tofoq6o|1{JFYgn9r2tcJ-P z>`I`6w1VJ2vaTg}PjIOSgSURk7?-;uGNLEdhbS}3-zNID6lQVQm)#;0JWs+F`HJX3X;3dGu(A~oJZq8jH?OF?QDt-&@%uZ6SJQxG zV@}c~&W4EM%Qzd|cJQ9CnkGR;d`{u11|u_^ss#XlI%uCssx2f*bNs1pQ(2-jfa~C{ zq}dtmWgPFbxT`vi(Wj9#IaqtqVwS|aX9ch9GFp?6l0%7+^LRcM-Flcr+ZmAB>2c?q zl_~J~-bY?WmzLq32?h%^*(ko$otD5*6pY+= zBntr*X6=sI@-M@XbK3ng?q%eVZzfIJ&)ESm^j`t$aISn@Z*TU_?H5xlS36zBzQ@~t zqk!o*AA4JSjuP}kHYsaekngY;Em_Y3kc937CrSX-BE%+ZXnKbOxHRqO8TatWKFB9^AHd;d_v^u+ptCC8c#AuPS(N%)&deh{fLmEW5r{5w1^MFX!w2u?3rg| zQ>xNm?O{*~DZ6K3>7*nufbMpqd|Apj>Lbdn;9DLBUw?&8-S7P(#%j98Pi zFxvoloO%KFrFD&6LvjQKh=Mm)FAp1Vc3d^aJAJ>uQ(GGuw;=Nfrw_3-loB!iKh$k} zKMs#6IBg99zJ5Q|*F>2JZB5_#OwbKdU0ryzwKS}}rf(dT|FMSJ_TBTBG;TMSUuB4d zh~<`pRvzYka|Ap9T$-N2kexBJ*c^X$U^O7^1WX7NdvShQKOEt)WBHS(?DmX`453DB zHkU#;{+Msn%|9g)BVp1U{q~Ja#7h$;9+rJhGZ7>nB-(thELQB# z@YQ#4%17&baKX4+!lFLLjk?{PxVJH2!%Z+IRUxcW_2STqC!N5CY|#FYR|C)LCnR_D zK%fFgqBwyX_5j+;JMI4&LH}f!E3uL>H!%n8L>?x$FTV>Vc*wPzqzu3PWFE~{oTqfo z(jzB#f)RnSg*-DEqO7+}?9;@(*aZLmy zNOr7fy9Orv+7OZjRD1Y$Xd`9{V-^3Hb=dH<=(r;1HBo?N5&SK#=g@+UyhrB%p`{YC z94W92SgCHkd4O*ic&e#pP0sZo#B1{#)}ae{FsFKdompJ_ci96i>bZIms^{8D1fbO- zUcJfMmL5z#rCazv?v(FHFi#?kv>+oxI>O4XU2P>uOScV%v!_79{kgW|6rcrqzq9UW zY>|?dIOGvTVw;Hs-**}&u3k|HGu&^*5AXl@&)7$Y|4cRa$n2d>^BJY59Jk**Pmp*j z>G9m^n;6s7fF)8^5A*?`P^Y!ckS^pvP~1p)8h#s5j&S>2atBul=l){ECoz9Om}=8? zuvrP@dsi&hfql@ePLi9Ok(B~%;NcoS?nAxLr%LxLw3{53TTZnts&t1VFcQj!t+IkVJ@gmy7 zoAP>^HWZf0BHi!dp7l;On_?Yo;HXKKi4_@VPrG!O{RKrjq)U;FES~HIde&T_G7o^G zBj82x-0r4KPv{d)E)O~u3K{#0DaT&IXF8!A+?SW`kVxfk=Ocxr^uHVHW`^DW|&8T95^;Ya@+) z!J1I+az<>*K7GP8Gp*`&ek?dfv9&|eP1J~B@MnifYi4T>yjPD&Qg9R}Yw@KFvAmzd z*d*KMv=g%_=&!2Rc*~su6Va2nKpC_q+4`C)_p( zPoPVJPo}htjXLJaP|175qqqk~%%<>~!{6Y5g*~B!pPwoi5w^cO&EX0M$Pf_{pF75J zV;pl}#g4z>f71q4u%O;}#=m9LT@?rU3?mT=;n! z$S|H8G<%JM5W~S$4!>fobB3k`v;Y5%<~Nv$^4NbGhuNW5CzCP2%E#Ab>*ac32>l9HGNwgR#{RN#S952lVgZo+z>Rxf?q&of%&(F# zT|L7wgt{Abaz%Mp(m?_x0QhcwKBsOe%^DG&;r^#Q5>gCey~`)yCEm=bwODWp!T%~- z6(rQ|+R7EvoT)vB)vYTJZc@AxlLMoCO z_N6UbL=-c^tL8B@O3^VNu|5P5*O;@9+hvrFLPS=1F;FxQUm_tBl!)yA^nN#TLc`x` zKAs}20xWr7CtGCzcBw%ean*r;bLW?b8CV#2&g7AE)`*%IkdoS;Bt>!x0_g`q4o|&fKkP@@Z-HEt1Y9C}^8dO^@{KQKZG3+c5tsWD zS00TmFpwbXIF`jO6+j3XDmpEUD`ad_3-*4hlwh47TAQqG1_)AR^5;G5^vQyBP*9Ug zrR!$DbSeMJ2Ct(<*CJu_WmjvMEEuP~T{XvwSqRimEoU*fR(qQsc zN;7AES_Df< zSBHjzGlEpmD!i3(xBK><&HEsFxjQV9-90O9Yq7d)_+0HYs=5w!Dvz(>eRF$ckS8*U zl(LVL-kymM1pGUnjQ6mqI_)v zz+O+jRqk9PT~p_Kt!Pl+kJGsaAEJE%j4rB~T&?jZEzD`*vpCeEDo4=_P(q~SfY5S9!Zvrq_|y$T`=~z) z83U(Ng#8E0s-4Em=eKZ|(&f8LqKTptY<>_zVkgM;r|8rO#OmL*|!p|B=$=-BaUNX^yPx6kU$zRB4fy(IT9r8=3@TY8$BJE+Hc>6pEI|ro%(e+Hdd|aP$u-ga89N!O+aH~ zlbYFJ>ZTU1ZOw)d7O!G_#m&WDJDJWFex&5B1%N2@wC&K^mQV8W>3cxuw3f zRXagK=vmcRR8w)&+^VZSgg_&7fuhC|m&>V|!HwoCH06v7cQ~V;4z(y-N0-1+$Iz10 zLrefmDejyAX1UO%RJJly#|r4(iVhV*mn~^-oiCbeEoiW+R)W&*sF;h2-(BLWuI{6Z zK2FqQJ?T6|i#+R(d0Q*f+PgqV1&;t71RUSRgTCn6TpES;Z!J^bX%KthCWsV)CBZP< z+OeT;we@Ua7f>@>m9Xva_ZBTfjQ;Q_(j4T`O9r%DjOd;tIbv5>!tRcup$&y7*EzQ&hKEp>B+>XML zyi~EfmRadXK|4JaE6BX0$lfQqMldYUA306$q#t^0SEADf z-h(zXQ00A>7*?3*k)RUTUHB=rPW9v7_5DhuO^(p)$p~l~n;EgQTRE2@I77m%p`dw| zPIHgii_~#`0QBF1#0}LS^Os9A!8*wTRlEz+A6!lqd zL~nzMo5U~!7H1@P0U7)}{l7-!TbWv6Rt~3s93t7CtGqrU&Rf~pX%*&Qb}Y~=?QVvZ zMC7u$vjI#X3nrVz%=zS*bCq#1V?L{X@#eE|3DrM+j(a0BMD7x!{!%Q(#wb9)*!2^+ z=-aNM`@t?`E3zk&0Df_l3o|s5P>f^JAbLt1=kdZl2t9XQVrAhi8q!1H^|e~{NKUU` zn!#WIlJ|yuP>N|aNSCWMRPcsi3vcv)My8nM9WA(?t%h?5b8BQA@sr2baZVXHWX+oH zkET>xY17s8?$HGeIp5m$=Qv)1 zVbwZ6X{8$z#!FW?NXEO1W=-ml0{T$DvR2Yx+%9$*j)zlggG>#wUKM#*W%%lQ&F;mY zLH^;1y((R$WExwqA@QeJa%Hl=-D9(xW*5<4^^IQKI2IvqHj#@hy^XAuj!CWoSdwY` z-uS_fwTSE@;mK^9j`a9s>U3}}@X3!;t{R}W8AYM>wwGQqMGX+kf0*FK?zq|uZhz#rRb zCv@okymS$;ud@cpnOXF&xttJDhbn}^i?C&n1CK@eS}8_I(9=!9({n-1B&w83Lq&rp z(g|X~Ou-Z~Hi>f@CT8Z7Wrp0DR+9{NF#2nk$c#!?V?K^ub{nv$-U_#Nq~yrfRkD{v z2GTpqEG#8AD+Ftz$!v`5UO}qSel#dc zcroFub~3kZ20OF>m%4j_VESMG>bOjdy|caS5Mc=)K|2hr96G*3omPG7fQT=A7O1OE zrBqnta!>!i75AP`ZLuowjVAQ78s>eYPJVqF4mC`dRheLoJ6=5)OC*Ib>!Zug#luJNFm8Euh%V%M^9CaBKTz+J@a@+%S zMLB_)Ac!MN@e*3`@oE8V!Me>5twVY7(N{kA)}35?U%kFQBtCK;{KYG)<=H+c83H^n z&(~)N#jnI-WSZoC*5;9?-;gS87y)EXVi%&WKfnL;qNt>6mw1Q&hEfWUIrs_VY-XQ` z^TCFNIYcE>1T}8f=wJk^{cqSOZocfUY%|ZuL z`$MOHX-m9JjskZ_mRDdvJoEw`8S^x6SFqrZD9dq)&pZibHRXmosl!ni-<|dABARe4 z@gOD8Wuo71IW@<|MSujZu>jSifi%i&cv#tKr_O{DlXFyGEAT+ImlUQM3q>X=S2cb0 zsE`e0A((6b2f7lF+5S+%YFJL@PUOOEV>G#lrtY>v-PTH^?~Sa;UNc^^oiZdB!)rJE zM)o-8u7G|nIvn%bQaCiD+AC)&NJXh_r1nDQ&9sMeu&Mq(O((Zt7xA3=@$G|{9eG&_ z{5)jWjbbtWaOu*TSw(uEo1TUHcQ%ZivrQ``p2na?$XPsVhMgJ$QD3KPhAK-+{M|;I z|D_t!&Jvh5r~qG&N{2vn{fkGu|An<-3Po|3>mJlcCV7RO;lwN7_W6khl@kYyP|tk6 zk9A6q|A1IF#pll^s;pY-(CIWGNBs2zp+MrnC}LhoPR_g@h5?E8lL5yi4(RGkQ}(jDbR zh%MrXjkdJR!D}t}w0twex+lzMgqt4a+EFE{n!9<}oy@3ezaFa@>DpIT)YYE4-}=<1Az!VXP!lPOBK3yea(NDl+=~sNfHt8iUwt@xN+8%Iu^TEcZd> zi9TZ{gux%eA!jM>AwTPm^>t_gpHMG^qx>+emEu;U?%AFRx#?8<|NrMnjZdOyl3wNr z3p2m4PWa*|(Ieg+CJGqYXq-Y8oWO|1eRE*ID;l&wRM#dQAsVJ>=MndKBgWv(1wm|7=6%px??KijDXCuaiI3Re4M~N{IFmMKFFJVBgRZgj#-nM6T zVYV*kG0{$O_aJ2z`v;SR6efUspw6lLWj{P=SwR&!;O*tPa9CIcAFT`E_b0|otis`p z9wR~_R4z7ODZmNBz8U>H;0vniU_DV!E<4rtbS*fwFdkMAuo0R3w|z=v8f`5Z*K~Tb zpJ;EX`%D8cOA^*L`Wx@Z{DunDf?ra^9J|YAzTmjp%|P?;t0EJKy%`eVQoDvzA^mOB z{F=q;_bFo9K7>;Pi~4nM0?p$C$Y_=7HtWL-N%gp1SMqd_sN-+JtKrV@*zC#0Lc0}T7ncQPj{jPW zus1v-h(|qC%pWrNL$3qzbV_XoapEK;6PB=J%L(gWc>rC1HK}BgwA3Lip0J$c8A~U} zck*@$wUKSn|209T)o8~YL-b5ZFNN!RGI~9RcBG&kGaNoFk{`x%<4bo4@BNjk%fAw5 zkmunpw~~^vBT*D1i`N?qf4FtKSuoV7Hx21#MTv4$w}|@n*DR~2eAG)wr5VlkIUN>xks4Th}bQG}}xU$FX@$&16Upi6JB6rh&A(irCw^ zYv1hRRiS52ACFES^$kr69;8NHP>NGm@zQ_hyS}*~xHOF%;s1(hlUAa>AyRRe0N-+153)VR=8MHi87}%ItU_C6uq;|2 z!mTbbm7675b^{ZrC=8{I8|6n~MD`BSxObK_CvAJ~ufO zp_j~LvG?hG2GtFCTbEj2xZEX(AS}8~+m?dkrgMUAT{68fR>Z?ezEGi4Mrlfa-GV(SCx$B}=kBJv3oNy^}T zNEAIQ+R8(qUDE3(LpnZw^WA@{k&r8^PGE(dEYdb>*s3<3jlJXyTnNbxGc;rM38gTFpSQ7x1~xhp`wSyHYcJs=E@VN)K{ zP0|X?SQ*lCibOEi9PjEtZG@Xf}B%i24F!9(Xvzg|nLQ-e)W3xnqP3aDs>>?HimYnhaLL=hW*! z05ImETe)qxxUGx?EjX+DnSHwGQ=_Ga-+v&qYY^+P-6a#o6VtI$LW_e0T=-$rE|3ls zqrHTuAOFOxuBt|N=Fhkv3TGSU(!@JAcG`KTo8@@W$~9N|=^1syA?n1jVWoG$D5?+I1~J^@?R^j8ZVxS;vbUNSQgW3gbRSMMS}(nbUJz@(r0`r zK7?r$m6jPdoP*n@C~>!1B#1TEN(WY*m7AI#Vs@o9nVp4Tm4_`;7sLHtM#*}pg@c}NR?Lin7jf;i;?XF3AusWH8^mo-SdMC!RrEPg2{^csKs zGr8%93L~}yO%|k;4~fXNiaqz{5dTuE_rxak?PXd|dA{nP39EYLkofj7^NS7^Ch0vK zFE+$uen&~2Gvgz55VpejqyCp9I4f>W14p-;dthDDSfg(aE)&~fJOijqLiV*=rehRg zhV-)}Q~sBcpuguw8MX13Aqj%rd$%UQq84@OIr4zmJ03%geya2|{heDN=6`f*>jRlIpBDzjbASw(;^LWF?~<>1)C_AP)C;Ls$Lg0 zcXZtYmmtWtE$Xba?MmA=D{b4hZQHhO+h(P0+csYH?(Tiw9p~O35o1KGSo52@D$;yE zx+`k}8n9gKz@Zg4+%fkT9^2n=?)^nmAj4ePADQt3g62I4j5wy7%CwI4Iqg7+3Nb_5k$8G=iF^wwRu5ACq&4j#CGm&7dLftDi(v2ses#?0 zu&z!I?RFuIFcMwzN+&&6KY{pvyCB%6Sdqe0JDa+c!F_p3iS zFEcEo7XN~LJlCZG6V-nyT0gG&GgTTnuhx}_J?)U~ZYOyEA}-OB8_#ZRw`%i zbs7a|h_!?6>y@(N_MyXF1@y*-_2cSuPAXaMYKB_;_UTDE;!Q+f^V{F)ET*DatN=hN zj>eGEbs>08grf4&P(E($+qs$bAg_=Y3msvQy64+qGXY8d|e^L_*_=v1PcCGnAWPb1Up<09;$X^nz< z>FY=lZE38F(p1mnFTLp(742zt+gaGgJSM@6IBa zW4}>|&{N-i*98OE%`*abWH}%!)p6lPXaEoy9|{pB<{!HX1>$H91T|sdHI8+H`Mv`T z8jW#ZurL9CuxNJve*Y{k$l_38qnBdbRk@KUsNn;vTQ8QNZJSZB$qm{4pLXaEjJ22B zjofA0EMed+&pTYL+2tIFsMI%5SJy76T@zFMa9-U>_1;$NpXAx@+Vy;I%p5=lHbq}1 z-&dc&*uN4+3vFbcue~9fKCvbR<4q;Ucm~FrHe9im5q8b&uqig`9(NdMoR=3+j<$h^ zJ!SGn3cwcmuOI;20io8sy zsnpiyn3+B;i!>Fl_d2{KiWeWFGn;GA(0OJx&4*rocj6u^?PWdYIXvHk1POu?u=xXE zLnnT3;cq-Obx-@NRRZKfL_X2h_F-PGIj3E7gVfgERq2o(i_EUg?% z83{QvK(kWM(0F$-#hCE=^(~#G5vua$35=`X2jFs_P{*{F+})c@fWiyfRCt4QsHT@m z1Sq%t_YjkZ_rc$CD&aV1Kh?yJE!uzNROx-itqa)9N*A|8w>Lkf73Q5LDfM#BVSs$n zYc!ZKRTh^BX<7(r%H>bF^3V*>Gas*)PF6t}*))0M^`es@w*ohY(WqJ@EC;Mm;jF2x zH6}|aQ3yQ0&>9b;U!EZ8_^ zp1&ge1*b+fi~k2sP4noL17lG&7<$-RWEy#%a=B!6`2>wJg>E+w;aMm0rR(hG8d9oS zC*dhwjq1QQq^#D)CEzUMqY>MZ#;x#;$xCSTHrj+&I&|ar`JfciFAOmj1Q%+)J}&wF zbq*-$IaS28!=}12*_*cO*P*?9&h1FI8o%2}|F)cnu&Nix0^561I^Q?yA8f3qMGKH7 z8*^n%S6h24vI?CR$afOpBlAlzrie*l&v^8{gU~(tv!=|;dYBt%x1}bI%z$>9aJWw3 zo>j=%ULBWbArdEa*oV&HEi$)>VZGKeP|sN} z5u99nkalaEqXUt2Iz#|{E+Q|=O|&GFC6ys$wd0UJ;iKj^Yxo4~m>X3QrWoL+#7TWt z7DfX|$&ISBhQVR4z`*%>Il`B2e{vmk>>!z6upa}FMPSdbanEw?2~m`}f!0s_Fu?8) zg7>FXYc>amWp+1Z*W3<2yIZM7Md)UB0GoHT;t^2{_{7}EIfqOEl>O8ZN^v)GLn7;I zz%Vg$pj!9S+}J1a@gw07BW?sZ5Vnm)je5>mGzCTE(qI+ zNVYh>nLo!XrTg{3w5k&*TFu~Zj&Ku0KQzJszE)_v?7a^5NH+B$nCqD`rY07{i-H0x z(spl)9>yL!aEX4yesn&hz<|i!u<;OQFYg3&#b(!o!TBc&@;4Mp3_EQWLY8yzGiuO| zgbKlbWJWobJ(_5_f7EB<5BeTZPt@O+ZDy4&F-tRA&st~z;_SH`*Uh3jhcCl^0ty~+lI*SLmwpfyU~oM}D~ z@QT(d_aR%`OwhFdcHqs;jDj5j1}w%eaon;nz=(5-T64WL{arrwTX8Fvh|Rr9h&s3p zOeyslXgV2WunWIFmbRF9W8*}`1U!>*WX7td>XKMfav%s!3P*IDrX0WslbrYEx_v@H z(k|mkmJ&3%aJ)j#kxxuD^lhg4wNuSHuep7(%;8E~J~GcsS6n&EGJjb;3Crhx5N%CB z93{34fePg`T)!!n)%~Mr(>ApByHO%#Iyq%HhCb9HT{FByR8)&6N`TwRP^=XANv(8v z$dKi#>KDBJr-qilWNn^hxX~m_Q4Gk}q7Bd)N7iD~?p|~Ht^_`>?^36_bdy~-s1aVQ zILp%FZbf~sDpj3uiRCQBA{$qE-BzRnrY!6NIWwCM?Me9A%iSOS{>1(*XhjTfwBjbm^iBuG*Agb|=@`5B; zohN$-*r7$!WKznzW1gUo$XabTy_iLCN!IWu`~ByBGHQ@Lwkdy{nS&2ix#9yH3&uO2 z6e@^G-FHYdntW5EN!Nf#8|8jOV zF=yX=mP<-1-k0Pb6)bg{b6MQJ)Yd=!QwgySlwQ5t2^W98Nkg8}*_}d8%d^LJU^{()c}dvZjk3G~&UAFXFUKSHl}kUH*&*A6-M!`1pV z;^wNyvQ?l|5_;70A+=XS>O3Ruk|JxmdzkjR6+r(qM9>lY(UjU0c2eaBxW)ya@XG}E zS6JOty!gGOr}Z;hk6f@GK~l$utAWM%nS& zo=Qsa`8NR&hrr=`S;`N@pQAI?`uxAL>At6AD!1mli zv<3_qci+^IXI9WVb(N|#QtYg`F!c+~VP4Jdhh%zbbhWY(N`;74pP1r?ID(DdR={e` zj<*5cbn~GH4ly;es_$Q5>L?;n|96EhRy>1nI%&=>qZ#6P@`s|Q*22baq08y~Fs(hL z*YCNEDdRW~ZT~OX1=V^DUy&byVk+{Eq3=Fn`AMm^!yQ;uPCqF7;-0?^)fOiOL9{zj zg6H4q%%f7&FS4_89{vVXD{V4HC;tPcdI-BI@+TuhQV{-**DM^bdGHp_k`3e*5Me@F zX8KwY=UY1jlM79d$?@M_@@>vvR0T!*p1+L~6HS)6jNQwsBAY{z&3R7TaG*{r$FZmo z_dsz2)=X}pw4kvpVH}Ulv2ueIf!~mVI{=cf^LTnezGrJ9s>b;TOci77{})U(^NECE zCUPKV3n9lvc6aM>y zml!NHvqGds^o{s^_N zwEqE9ccBj0e>lsfz`LtG>zt=Pn$V1+228`aO!bP^Xf$KpTdOx_PP#X%yE7Y$%h0}I zsd>|e)FWdI0|$JbZB@aY2_fHF)^+)Ch7%b&%vVxd-ASp>la>a69)T1fJwQ@eb8A!H zB+-Gruuo)-Z!tUa9s0=}aY-^84{m(Bj%hYI+*r$qXG_6VSoNc^u4&0$uON;UOs!_G zc2J)jhsyehN<rrou0{hK`T?{6xZCQwQ7x5hTqL$;Gol`PzWJXvq zqVK+)!@$^EeFQA3eXdofWd_$RNxlgZD2fE$rLIFESr(P~e_4N3{}EGREz;d8t*W$E zD|DOjgLY**YH)u6^zTYQjPvG8u&?@ZXviID`#_+Bt&ja%S>~SaCJ{Ap~t2gL$}sX#8h3GLgcLz*#ZD#q>HlpBZ!Kf&g3wduX&7r49U}H#-kfR5p37oAu?833QxZONq zO3kWs!0o0@WhsLyVi-rj34Z(}DHw?9hCbl4eZJTOT$d*b5)1~*xivOutiMG+=`t*g zC+yO{%fRN0pEkPJz~3;huwt<)^q8bI1NX;-d$QZmQcR9rea53_z4#d=k3o6U_Gt?M z)Nc$n2>7s4SeCG#u}D$wKuv^M_A+yiy(s23%vU|iVTw}+x4|_kuU!_)4ymX@*4^`4 z3H=#S+JD@E@*F<}JGfCmX+%#=)F~6Np$H5AnvWPI8H~S+{&Nj4#j#yVSW1*VO<%`Gt%i4!!zA= zABY4q9b+#%S&eK>f7JMgew}KSMDJxu;XawRjc>yh7i=mRCw-Cpf}1gUPH+#c(JB%_ zkO^pJt;RYs z8bnpy@l*O)z1;BZbbQzgO2LjqrFqSh-z#%o&wo9ymyppf&b$063lJ?X-aM@rdY!*G z>DB2j0cb$Vv>^SM4!5~x%tA*Oqts4Jv-N7+0iwT$Wal*bsQi_37$6-m3ttb()T z>U+=6_f*#a_d#^u1)a0fIa>+(naS0M1UJ*ftYYDBDXIYu8B}*pl$JIm5DiS&t!#>*$`{~jX2&YL# zwg62Xn{%xe&V^7tBH#0c20}3Ru^+@i4YGqCSvjw_`m~7>Gz}j~^$;vyAs@(~kvI!l+ zBg6x|<>iA4Hu23)ZMQJ2c6OBg!jFX9fls1^ZOifzd= zSuSqM4XMjd>{OVPE9tAcJ37@gxks-AUx_h-dFUh#$e*Rw4}3g$brGvv?0vu&nZYG( zkVeUSwd~|Xy6-gz4E>012FpMZ@*ll;CN)<;48}d|Sw;(T3<7+=6@7-|9$+h&(-6lr z(Wg=K)p!d6_H|jN3vTW1-aGnPK_bR0pM`2@$GD5iZ-{vhWCD z5#`*?Gexe`;(_=+(3=1Pc9cxuR8KwxDzl$uOSCD5-*QYH5L0R~$2oUXsMcQ3{lGgt zE>mY1XqetSJKlk7mwTvXEM#+FUR8gftsLo%^Ek9Nf!8|JMB(>0f+O~~ZjPq%&o$(} z_>58G7&5^8ubqi|C9Xo-7W{IG)A?mk#Z(EVFDt%vzgcW|EQs0cs)kXpb}zkj#W=+q znM1;}xAjN6O4gTxLSBw>IdkSrP2gBmC+VyV8)Hxt(1{GXTf1VW$6cs>qk3T4-X@k{ zYz=-f-;+08p8i#SG`N$79pG_N5mTSDrfAUiyLd(wif1@=M`J|(RuO-D0_ z*mf^pSmVT?hbcXP)l*;%0E3QtbBf3*zS@PqnN;u3cy|+MB zdltcU)QEl9h7bC@MLQLD?<+`4%pZsJYLMg1ULru>*ZI%ooXEa8tvBXcOIIG?Y1gT( zpv+?_iy36&0&Md&qxv{?HY%J&0p(1XWZ-M?K|G1Co4*7^Z}z~0!k2}xjSIKDiI5=y z;~Xv%difekr3Bq}y-Ezo{A3~r`-%4)V1EVVe8sVg^%1#zYj_hw-j1kTeUa}SSCwUh zCZl$f1iCF)?O-zFZ@n!7pb^RhEeZoOF~v_2oFhbB2%&KXYGWX6%rgK`O*(e=&R+iicX;xV~Br z#7Zn)$WM(%wa_J)%2dU%6hE`64!(HdhrdAb2LAbqx0KFC)%rk6iiC5w8+tsVT^+=( zAfu+U3V!L#s(}X@0dcmIPslA0o|E>v!?TLpPTE!G3+M}EV|W4DiyH{REXHZF$Bh52 zaMaW$51LTF=*XFTk5hYGSf%u{{hgolOEkd7Pfq3>}6Ihq8S^$7?KAM_n)16h}DN zh8iRv)iu>!*w!D2Yyo%+FxyA z2K$*D2bt>^bJ%DB>>{ich)_~C^C6%5uW(ZSTw)T;t$MEjXMj@+z-k18sKaTt9<3oO z>bL@J7x_nAkcC(;6TjR=$Crt*4GTI>cZ`NAue!8Sc_sV5dQIbGb-MV5(hdqk4?DA>80dOxNb<+)JMeT=UC}m!+=!c3qda zToaaz5XiU(Suxe&vCxR9brUv_`-%PCA9fv}aB=x*RP)^$As>~HitF$$+1=R%I|9NG z!{<)MVYODD7|B;&j1m!@jSZGWMSn-FSNb8My4^-R#PdltIoY_*3&%dbCJXEY`kLnB z27>~!t50Ok-gy)bJhNlpYgH-91I2`vxq@|w#FFb7r9rLJ1N#fJ?*raUK$4q-=9Wg;;ASX zw$z)00%8>@P9}LN?#F)ZmRkm6$D0_r7t_TfgxC#zCua?qpVTQr0|X8YmekARZV^07^G6?$D&b?izLQuYm~Oh^2)=7fzwd{8byWp9$?Y6SopT9s=5T>0t1J&4 zE!Zujjvn9Uf7BA1N)Gb3bK2-wjmzYQQ5HguSi}cKT48`af1Ta@EV|Ju1W3%AhwKwa zelUCJwH{6>1U!zRlnxEDXsj?(d&r+%Q41o{laZo6U4c>$Gp4B1q+nVJ4`EgBX;|l) zna5!xLhnFto$l%}<~Yt;a2I&p^U>DCl}vB|Dx6WhQCSDf*%Yiu>KeT8O!~Ad zsge42Mg4S%>bwIXCE#&{eoLbQTOr)MR@QELL{0bLjKufJKdt(4(&gf2+Cj(zNT6aw z#2I~wz^sJZ*nyP~y|7x|Os3~5BucB7LmwX3|o?hA^Q2=7;081G%Ud!tyPW} zy_j!rGeY5hy^ zk~Y?^@}@%X=n*<$5s_f6OsDY*H zkEGpI>_~VdxzqdiXn-}jmlqM;sZ3Ka8KU_M9*~%2+s_Od%Zovn{qK|VC$D6hCEU|E#4D^ zf{*)mB!m^ZX3faR)FX=M*kyze_ba*6_QVK{Tvpesry}vfI$jq*{5HYIKYoL+AiQR8WS@$!+MnGNP_$Bt?IbM5AJ#@-AT z3*Ls}f%PNkRYwM6u3_v*Q~*YIV&5Z~g6d+bY7JpfY(y}T{*`u)Q}6HqANbxeF2qw|YGtl|$`~%*SOyMk{T5!5 z`3uh7w1gfl4)V6b$e|B9(Y9`j58 z5mRgaM@*$Z|BsluX@`680T&=C#nXfp(TW#}`pe7BwxGIhPX8gItsN@4yczniLF6N_4m** zNbj16&QC+Aqu6X;0B@Qj#d0qC-r`PuXXJe zS)4_p&m{S5tU`#3QYJ~+`sC+ZURw&w8H`Qs)9Z>)eZNri@^5`R5B-tb9bcNK+W?`@ zrNB7|c83HaAQ67!@$~7p+uS;`cFC>(0aMxk0#k##B>n+Yf&K+kIYH+e{svS1Pth0u z0aLI43#Rh_3#KOj519J?511m@v<}EHL3Bs_=Qp?olsZwH#fA83G0rz~`2kd9yixow3q-N0sN15J3NEf}3>w zr@F!x2&1%5DHibc2C-|01+w>dJvBksYlZ69^q1o$(I$0e@4)`)(EE}Orpvp_hxF%Q4#}KNI zD2dCFgzv%Wd7q$Kk7*M%vOeNcDynTucd>OG@o3#~WJjp8yzQJ_Cb`Y0#`ZuQ?kfms%FXCCa_3+0Uj>wfyT5rcyg!%TBrjwBn1Mhmd$Z@! zVCAGGNfD#W(OiQtuY8uDKhM@&Jy@GzA^4mNbqj21`U1oqH9<1Rd5*QkhIL4&*dm4` zLDiIF`hoNkNWNC-6H4vZFytMgf^3VGyTpp1$MnQxhO?Vb?4J6lm7$)7c@JR~Ra@5~ z`DllPU5M^@8>lZ(vx?BI`yLAqXsHer(Grmsetww}0ke53W?#9JV_xAKY5qkQm0~J` zST97!xTO^yti{*X`EiP(p&j-R?IpU(t#ixWzD0 zlBrr%OC^x79n$~{GpwsFX0zabd&W9XLXMgY?zRxQ$4L|%Scxx!m${;1Xf6mvT^%;} z138Q8#bt6CR?YsJwS@(Tizoon0VI>2n?QJ6W*?e*B*22k^rn&N)U}*bx=R;Uki<)p z?yb=XSvwb8RPJ+p2Ga?YJ??aXV0Zc1bSF!ej&sdCm8-hTEMwsNw17~mdFDq)#GW#) zqW2^9?c~+Qnu13a``|CE)oMoHIZmPbx7tIkC(*4RI6KTL0Sf905ESNMGb4hl7(9u4 zKbk*ACI=Lcc}E~Mn@e+wjAIk8e@qe1QpMm^k(GE=^$nTWNJ^QHUL}Z~>&#!Znx~c) z4dbksl4w?IIud0RGO}dB!4pe3wL#dR95;<30KPU*sE2{?PSY$_e8puqD}kB$JakBU z#|*1Z+YGB#OsQUD-#Z(E)vvaRwZU{lA<_}J+E&Uu-sKrSV)v&Q$E_M6y0_E(GH{h~ zk1SkVAYn}{ICh^6#pd@YXb1P%(Ua}unu=d)6ahDt-`u49bGWE}=}`vmX7pXrw6z1D z2g8QDADEY*Gpc8E&$mZ`VjGk?s1t^FY888$=v>TJ~+`nZ%JaY-52I1xC(~9D}*wrpncTyPwRq_ zA|F3$3L4bVT9N*$S;EMU6ok1fGfV}*V@KFH;qp%&?&b^!A}K{5;k50~IfstW={zB4 z1xzbMtq}-k|7_~=8YFvw-^^kSWlS@wiY55Ea=G!+@x2?zsrg*I%9R2>T2g_{V4davbu2jkFv@z3oObcGYz7N_Ubk=A75*TY7i~p>QSj2do4;P zxqGnOQ@c9P70O@}dJ~I{ph}iE531bAj!n^L60Q+HmP#QI)^~LvRM@d7sjT|}+mOxR z1rl0e28DaliL&lvrKfA35x~jvPz|Vs1b_k(YAJ~x#KpofV|Ye#JK0udnz_fT*&O`h zPh|KoZf>EF>p$@Is$mZfrx;k-DrQKFb4(TckY9|A!zln~50j_$^2K^>pCroRwzz*a z{*n=a^^i1S^Ni%j1IEhMJxpF40ALLPVq;t24jH9SGua?5gd8Bd`oSfR1B=umm*1c! zL#w8R6*ddJxw8dkCjYU#n#?cDf^4n2+Y7%tT{>N4utEB+f2TwS`|uzV0oYq!YxcPI zUu9KX2|;QLy-O4BFJ)EXf0WfqH68{}1dB45wwZjX?{G~23f=)x*=l!*z)LZLui3M-nwW62^5ry_@*aJNd3bUuDrh0Oos$@}>r4QckQ-dibQl*k5 z?DH=wT}n8ul=L+teBJ`pNegw)7rcptKQx4DJ}Q89M?s?uu&n+HkuD()RN;#ViTz9Y?wUl-#g=c z?piy$RpA@BB}`6Q8fc9%@pfyJT=;E4q~AzYpPpcBzpMT>%x+gc5S1glSc@sdg$(Wn zcPV=Q6YdDY;7tT!H{Pa3pZ5a8D_w zCTeH*W5AARLl_-CK6=W?&ICXr&ypW9iQ04y#LdReqqqJ|=0rvt{0Lx@mA7u=VHnY! zC`K}`yvV7@Fpd-KvHObQr@YVUS@5uR#vQ{DNt~A1k2MJbj_u2PO%v_9X!5K)%MkzI zdM1j&UZhIgtxgUbwfNUJaG}=T!-AhcZ;SF9be2(gAqN!VXnT>4{z8T^n8eF7#@UlaR1hi zC0=t^LZBY!)8$AmBzEo=exD3ovly$UM>~HQA@I^}`@ZBNtTm)wkZMg6=ESyF676Jh?I z&p-GJjVvQ!=AIy%&)XwMwP&6=#K9dOiT1Z2UjA_Z#5b*eMrDg~%gDS+`6lY=DJX}= zqs!+*hC(!is4YknmSVU4vhWMXN}xZLuJrZ#K7!Cr+;Vt+&q0}y0O%nWkC8Vdl{40}?YKwQIr=k?SLDtl{Cb30_ym%#<=`v1t&dgz_M9iR5!N9sz zo07!lkDNI%(Pp7=vIL;wh$Wx5_6!=7QQT-1#bO+El}d`AExgWgbhF#=uKj2i1)h-1 zt|6vYo@Pu6El`vjo0?kP)J}|I!F=y0jOAD+aqgbM5QZuu9KMuBA7B8trw6>lzQkw} zCW8GCj7@0BD&!U0T@H9;5->VA9&XT}d z?3K(N&L_ijOJg4S`(TXk1wZ}uWQE{9fw^n)I)_K|1d|L0m%|)skE9Ca7YbPvDY_^n zbuLZ5?q z+UFOHP?@IqH9X$NKiu>kkUN6;1&Xp0lR15l#_f5GA0N@YGpHH9cuj22-fS${<{QHt z^73Ik<*lRntoiPI93ybZH?jgR=8}bThV1o_pghNJghE$XcTE zX(dSDQ>ZJ-4z;7^!Zi>tGf{hLXT_!Y#b8N9Cbxw^QovPf@BULB!%?0Iy=OHj1I%njWfDByAC+RD%;}tj;TU8! zcY2eg_duRLolq<&270HZRrwi<1SfRC113c}^(^phc{S_!LA0|+)0*68F`tP|vVU!1 zV>h7{YCJ@3kzP#CxWE*}u(=wNRJOd&6xb3m5Goa9Ct$Y#Dk;y-dAHxzHA~6BIyGdj zA3m46D63>nej%8|8{O5N#yK;dN+Ii~UvJ!GgMMK|id(wSwNy+i`o23eMM<#Jj>UWF zG#z26*6JFPV!|IW^Q=*dNW5_8b>tx9*T{azGKmy2k-%foFxOdr-xiqPo2A`Fujf`l zJMrt+>@8G6iG%n}0C)R>YdnOg9Zn(??A9WGetV-0sxfGL@A?nuM+PpHr}>ATwfzdVT4M_KP2Tb|+wK zNlQsiFr)CO1mK&Bo|I%SZMMtk=k*F(Pf6ti@fwo3?JyRDshLZgG(;|tPEWy6p zoVaJ_`I3Pw#g`w&rl1-TxSMBoQk1l086(6#7kbTIEuM#ykbpMXr=HkK;+={Xm|P_t z!(hJ9U~pq1(graeKrvSnpoQ397BfpKQH6dO$!0QpGV+@bj)d>VlDS*ky>|V7`Kr57 z|JzqB`)ozLXAL_R`^Q(s4juo;SDi-tudnLEVAQcbK`%Wr#iakWf+v169r748n9+R| zhD#AR^EHR|fAv*AqyFE%YG>E~@>Mwl{`FNmo5=s)zG}O}3OF8M^nf`M2Q&$AjZa)a zT_S==ut4m8eAUY06SjT-FFVtY-5qsL39HS2d{wOC|Lv=Slq+NX*H_*A$5$!X zS>M<~Zs0|W_|jm1H1@hgl7Lw&U54$3#@hez^GX+b)qyNU(@bhu2~1wBPci#bn4;~V zWC!qr7B_v>xpGA@oKbVISZond!SE|L1lSzdG`Y_vNSi-eAb2?0fT4mL0-% zbAiTYF6wwB_0|KBN?N$FSaWV8$KGY?rjVD`i}NI?21P+ZXcomVTrnp^LF8Mq74gP#m8D7UQEw}! zu=X1I;*yF!ID|pvct&w58)}lt6ble9l0lKdfzRw7xh!+X+Mk2x>F6PK9rwhM+i$@GV!zsMY0uUC&CRw z-1o8cV`ru-@)|4=$sGx~$$E?#zff5{v$v)X`UQl~-=)Q!5$|KK;}|JfqoALy_ogTZ z(tA)}1|hV(_PRX+Xpf1ezDQS5f~W`bP~-XxXF}kh!GHLG6J!bNSV|1wdwK*9{h)On>hdPj zYKfT3OoaNy=JD)ZZ-W-cT_v1VYJ|GRmU3}-pRo@^jwo`WK>M_O?5_1qO8+iJs1Bv+fmma4OfU2zZZ zvc&1Y^st`#CmXN4EyI3p5lVzy-{p5<=Zci@n!ObwCaASqL>kv)rqc#y!!l`=#?f++ zVBbC1u8cRe{)B0u;&zqJ8j05JfQ0mskrtAY#LpnR5S5)3L%wjg=G%2^!H-tP?eVul`gjrg3z2tTOj)2%PYI`Mn{ zz3CWSr-2kshRPSMeA0fd(-KYR&I^8iLaGE^IexaAfDo51aJks0#<#T63h>Rci{sWY z1nL);s?LOQAfV*m6Ov#69|vo1&`&cCn)2Q-1(xm}CJ2yB zXWEs~j!OEIkfs-_B)ohf;fnz3lWA05S(awbfLH@0G410_GU=6oooxCtTXdl?j$gGga>^1kQ)_h9mM$u(NzZ2)tL%kabge9Vx zQXA@j9O|_cI(JOK6+*rWvGqC@6HRqZD~gLIibN62S2asbu8n<))d8XKtNc!>A6~o* zkM$y;u+|JD0kL&-h4E!P%>`x193)9p@!xofbdjjD!>IFveKlJMDAZUBZ)U*0bUf;GKEAZozn>by2 zxseU3Pzd0kz>Fyv(ojysg6%eKj3^J&`&G>%#dX!PKSNIBF*3Zo`=VZX`sF7zJaJ?; zR1t#QV}!4!TkXlbDLFBei6?K=uZ3Uj0XKEA98PR9Gd@p@B%yAfdtWS&!g6%`({+8} z;p32bv_`=m8o^J#v-_%3LAO3`gsogoTha5IC?hi+a@2l4Gt^2a=LrTOmPXF zC#}8ESr`;!f77cT!19mDeKPD4!`g8X<&5J%C6uR4?^}UqTYxtwxK-}OiDd3}K{KrR zco4moMsxbu3m}5Q^DS zhoitPXw+AL%osThL%jj`bo+TEmnIyCF;D&W{R{1F5->74C`< zUA&n{Wf2Lom~ID0&8i$_K^2~L?iM~=?F)_yi?Re#ejT-hd7;W+)iKgCwpUX0-;#it z>rJJON!++&tnnKQ!r=bA`~-jGRUqeo<<(>I?!V>L++u@&^P_k{Xpj%5dBun0xa! zH;)n=RTER2gkIz24JU&9tfH7ydgQmy@LQ0Avfpp{~v4jz#~}LZ2`J$ z+cvvw+qP}nW|!4v+qP}nw(Xk!c<)RynPg^u!%22>_Pf`!LK;21>5{4-X@!}4LF#iR zG|?+J;f==}Yd23?hepaiU)yi>YFpaNVXIx54hg5X7#L&I7N{7AX z-6POEM)2;N)k>ON{o&#xiHEMw(u~Zb5LRwlE-AjNUZD(D;mR1m3GzxOa5~u9<}y5Eu@7aThVEO}s|`-G zp_pZ^>jyeFGSvwwC4)I}H}HEOv31A!oR5h@Seq{3k}$NH;#sa-_&UIg+r$Ii7 zTk*9=35Tvpy64SfO0cRs;jUhK3`CN>tH0BK_&4j>PZ8}|y-i+0$~9h@^ctME!jbUV zVKWqFy{x~8Lge*j;q-VV*qpM>L$mR77ZRKwvmSLp$|VXWJ8l8al-WOvyCdLcFro}p zfvbW!il}V-gxtF}3M!w9O$i3VdSj1-gkbA0wUkSiq2M>R(X~qiDq>-QrzrXi!=jXDF2E%G3$HfI{uf@=`VYK{mGwXH zYWM$wS2z9(uX2~(Hsb0h7Q5(;?|C*2WAWsq?k&(cR;zJdZ0xX6sbwwlj=Zd%)H5;5 z?on|a5lw0v219?v3UFmdx1ZB@A{`5M5P1-QpI~M;FiDU?4D%3y7vxR*;SkRTt++mu z=_1Wlk?_K6jlA5ddX5htXd;kr4mE)Aeqo<6`Y3%1M4AFLKM~D!4K24AnX`?yqS^sx zXc3%5W%G7K+K&y8S+6+zFy?Q_X4jOshErHff3N&_)4B1zRiA>9E!`zOF8GG!Zw{n? zIC4kL2IY6ql1?Xa^gklQmCb!fWiGqG%`eIS{Stc$ZLJ+uA&nMh^?o<#TreX-Wp#bU zU~BYHot2EAEx|o~kOQt0oM^)lPD_QoM-B=50Bk^+ zIj;}q;J1xAVx>_Cry#6ZSS5VlV({(d)?hMN)sW~5ToL3SQ09`4xXTqsqK4FuLD--M zA^Xr|5n0hIZ7^CXAgF*VDH|2l&N;)ScVhkP(}1))+4@wGON`%E=K4w(c)DT)fv1@5 zY$xhR$%2xh8QOQ;94-S;$Z#H=s+@mJNF|GmC13m5nWFk3XZEF3)$%@1h8v-MTN=hS zt3OD2N`WH3%zQEN1rZw+NwQ3LRdT}ttgZ%|A>*H2*Fepp9*PLOw*9_yO?`!G&Pu@D zBQxN&55vM0Ji}?$EJDmcNwn5Sdwx@4E3EIx!`@zg__7E@I#tc!-hb)Z>z7VAHm>0a zTxW5xhziZoQq{zCiakY#f6O{!Bnj=;TTqj9b4rRBBOta~!^y#8B>Tdi0|1PJloV8| zE`n0p!Ud_CdnLeSlGeWtn7Y>teN{7Yl!*t#&A5YF0k_ANV-E||lu&5B%3{`*_$lBC z58~yzjV)05vrGNf8oE1!KYYgDE26P#mGeaHU%|3kV7(#J-1qmR7vg}}1?Oo&`>`g= zsjlun z_0lpj7z*&M#si+q0zs=vQl+K1Ww8P6(Z1`va1MxF&dxJF+!wb94!9sa7j4h?6Z`X6 zOWb&3WZ$ndKnY5M^9gd-%p^BV;U-(%|M)L`^-L64?R}?KcFV_WF+(8==zSNmWi`a$ z1V)Qg^s<4QGLnl77(b39@jv=%DlBjvGRdor#s=LbrxNVXE9z@$_G)LSKR3Pz&D*?G zA=tEvhK|m^%!<9U=ENBsQbp%-Df8^XV*7 zMD)|GTFBR+T%L;Yd1!9Ff91G+4o;he{3%@j9F0#uJ?^QCK9KwSNE2dNwt<{H{mTbY#E*fl|$HQ282(goK`0q@h?|p~aTm$>!Dj3SVw{!t=p{Y6D z1MBG0ang-|LX%N7Z3?98)sdmz*~epG{$99pI8I@-~gkt+j{_WfS9bl|I#z=m!Ymc)j4L9G?%lk5!DWl|k+f-uY-G z2kSIcazSd)-uOn2MB9vt875QN>U(aT5)qa(@&_1krr$XlkCzCRAl~lWyv>bI;lJ^!i|G-yWO?k3^v0US$l3ov9 zA_B9mSKX_`Y@;T+TG;WKb%rpH9{@R|Fv8a^BT%rTA8JAr_v?W~e}JD`}y-*6^^!dN%T5<<)B3mbN~)#{^0YZ6&nCBnr;D=|NW ze{?b)*mX{z5t)iN=l>~f_k{1hy7MtURN5b1U+F4#)s6l6K#qRRkhdzhX(MU4k$-T2 zw6VdB^UWB{76GjBT^&VY%}kNL`RS4McWw>viD~R@uDu6E7%AR^Nvi)-x)~*nn zedV>Cz^#>oMcLq4v-XRCe}Mfb5+gAu>zB1R*1Voz5a^R-_g^w|7bV2g+Ih~;Wu%l|_Qhb;hiXUSF4=UtHri1JBLOUhB7fj)|F zBYn_j4klv*bm%YlXowK`)-~^9U0uLqwnUlFQ3S=8rKXR~Vo|BUXk5=^JIbR5BGY%v z)}7I*E0_2M^&fe)pfUspxu1@>1Y!3sng(gd+9YX*Sfx!ELr{b5scY84oh&}tUks{% zG0Q#_HY_DSHF+pMB2lvQDil~k7yIAx4B8~}Gl!@bj(LxYWP!8Shr1#zb-$I_W?8CG z$DvhJ{9`NY(+@*_hsoP(w>n-Ktxa5w? z%7I%WwF0&EiA}Pm<>{JNFf7H_LJ`F@C7zr_%2|Nmp8T0bLdCvuYx(Nb$;!p(AYa|9 zl#PL3diy6RtEg;igYs{fv~&Rs-HY5*f|Hari2V);DPlsM;VAg2rqiFUCw;MAeBBZu zMNVDT5vC~dpyQ1TRCBcX^d~)c!LrdPhVY$?^K0C8e0#^lnCEOXJl0?SMpe2mDratT>(QaeuJ4Wl zOPkl4kKg(Td+ND$b&|i^Ug3=z`NI8SfTt7oZVe!=$qK)$sDYQG>Jw(f3c{%7JdxQB zB%`+yhQRP8=-}CCouG4}B^F0{k&aHck0WFDs>kgy6EYOiGX-6xpI!-XRkmIQK@SI^ z_O97@Zpio=4k!HPht(`I%*<`Z9UgFwXI*pNEFd@9O)0-==1`Hvr*sESmrQcq4RXHn zSY$(i_c!WSf?4)mynYJLE;%gCVvU2js`$K?d4rsJ%{`~Cg6Eq5z)eJVPz3jZX39#o zuRfsa`kYE(WVgtX935l#7YMl8+;Jpv5Ar$M`~sM;+(GTb^tDy*b@f+ z^a-|f9vCowY>h^GfTv{XB_n9rn+5dtDMgV8fv|VJS{9;S%)Vi?@I}hJ*YVGUZvsKX zFUlYq_we_CZvenukY6n@A#6j>?!l@ozv2}Rb4)u>K~!mxHa;*)6p1@G=_zQ(a_P%c z#qOX8C!)XEqp&IHb2Ih61~MC;tMDamJXqd2H29i8Jb|&SvQ|DD*>Oe;*$hiQ<>m6U zx7*qPXQXDn*bmf$+hV7yE>p&t%@>)Wp6laIQ5dgs<)>qFI^Xmj_l&7=`b}=h#fDy5 zTcRh`{E_<^WBh(W@D1t6WIYiZ2<&lU8e%Tp;!L;kQy-5O&q94`#p#uEr9Kyf4=IlS zeJ`ancirptgIGMlOYkYo6E11=EeNC5W6f}U`M%Mm-V&&73CtPfFpjzHUcOB3FEN2;&!~kPORQc(!AH-E9dA$Ajhk8PA0NB&9bU#Oj*VnahD{ z{sBTf-6#v`DR__-H;5i=6k^&KcetR28JW zhlxbOl1VFS*oXMQI{IqUXLfSeVi0}D;xrWxyuO_5RdO52&q!4U^zc9*M^3pvVl zuoGrMmb#o2w_Ho#hQgqcqp!yZ_CZvJwFf)d_8~`D{-v-6E!NmN;kn@tvf@quobIrN zp+jE9H8_n6>YK<`EHIA$8t~MJFZ+>(vF{5R=dV#=U#V?tYv)4}iLU*!)-nQ0BdjI+ ztFYd$iB$=+*)QPe86+95)gZu@rjI~fyEVcP~36=qIGQV{`dbbZ_V zlb zrJo@*<5$T0Gd{;H9Tr6IYcaGL+ddaA+eXiLs0Skkcz!Z2f5Dd`xzk+h0pW8EDk;UDz%I{K=z#e)2o9x;fk(-C+NPCXq@&JTC3;3Ip9KZ=A2_c? zALt_3J|8vg=-Ul@jd?KRArcY#4VgqD!fnH?;Y0yk5z4Oa9bkAJ- zg47}8QxzVa3G^zpv9SPjt*vRn>i*0LNO`!S55)^OeKaU zZwa2r0=*)TMf5*G5a|4}4wsBCm34uf!g4s~HMq^M4enQ+42v!$lbH4*un)BG;mmV0 z`PK914tKXmiI4y-bVSBTZz26V0zy7e@6d08Qc%y6K7W`wHa^z_6SqO6(R*>U#>_M) zmUrjV2WJ&*_mM)AD-9=@&hHyGf-(4XO$Q-lpmWXIwtS7}DQPx#?!tVg$~tTancAX` zFq9V;q0rp2b@?lD3!^nTq-J@`FiE0mliK4CP;&KQ`m#9BojK5+&Nm1dgZk=MgSZ!#WH~oK9%+YS zY%6ndsW9uXW8s~PkK*$0du$&=59QhSSfGk77g>2D7t`!_i6=NP73`^KbCo=q2v{GjJ%ahw9Z$S`<-P*pqPeqD7Y z{V;z-KfN_mzBM*4`quN~q8;66Rrkc3UK+yoP*o~kkH_B|(iYY07@McLNRVY4in}hab{c&Q*n~{VmiIP=1g+> zr@Z<|qR6ain?x9$TSufM-r-zIkbZlcq*e7bV!o~wO+=nqrW+!L>+=s?%#wYXCg}){ zvr++ySt<_RzP`bCOfVl8T4w)#dvNw1zx+hbGCbYH7I+! z{L{^>Lgnn(-y8;b#NVDCeKM@V)WSueHTJARkKFU@J4k@MI1IysxxE^>(OC?LXQFzXq(y-~N=Zg;qzJ^Xs#~d-=Oj@v@tn!K3-{@#A$PoxE zf+i9f4h|Oen&|X_cT?+K2dRgG%-2!EH`Yjhsn8wkeE4?QXmH1H!MUpwrz|!Hgr89C zS#1W(1G08jS3VPqbWB4;uvm$B(|KeihLCRm%`CsuRn?>AuMIK$ zu?^sv7{%YQ2m(Qi$E!f@0slVLV>-_yxCun4S~dNsPBi_CWzFh-@%|^v%JLtUwN5iM ztfhzXHkazYGmr0E6@Hc+F@J7^NkQlcj!c5EaG2LjG2I?V#@KXM`nGqg#_1`$9iiUD zRZ+Ht{GQa@@EVB(Lkj|!v+qG8&BVDAq>i7jt+l^@U8b*r1j!LIPNI}%Oc?2-B^l; z)vd5<$xV54LTP+ar`j%$Oi(#rqmPyn>42eM)^*;vbomRbdxGp`y^1%dAx`;87s-}> zb>i24J1|3rJve@3Lc9D!TGW7pBCJRLdkhc1AasZJ&eUiuvpxyXpu70HT00}vOl3_Z zMa2w!VDyyD<0c{N7XEH+j0N{m6lD6Kt+kQ#=8u@E(>wDjYpL!b;K|v@U@k6{rka@$ z4*=H#9Agsx&av2*=(#L&bs%EL8U!=q#T@cXVS`0aVoK3Se@W-lr0x4|10l|UkU!K$ zfUCH;N;D|xVc`vGE}$l;xoEDRV<29d_HiUMDj{Hvu;rgs7lLn{v3u~t{murZ7|j38 zvho%FzhGJ6=>4L&u}xM;{aaq@+oXK2KQpj|jRf$@x3sS?=aAq}gpSz+NB)M=lT78W zOD}yuFtbxPSxf}h!LQmuAgc&xi7fN~<1K++a-49VnEV5MJnIlU2A{kq>CU1Mv|wQoG1-_MS2<)zUr@kG~1L6{J&*c zp};IJ*6U^m{a&;3!!N-66i z5VwCagVKU^gsWh<2G5~^j_?#RA<&bSYHOQ~nMPzci_P88(^{8oO$&pbvXH8E#*Whe=Cc8ex5%ODdqyQ%6cJ(Q+ez zSTB`QalL5!st+-y5|#q>G)%2BhTZO=bkioH;k!aQdN?Y&E0{FII{rgcHjjiZS0F#5 zqk&`z$dh8pP^SUgQ6Ue4(WAPepGc#xMbsQ7Q%ZxH&*0Vj9#gLv?e0F5UMX_sI`Yf`-I%q!``QgVfsp=Cm0B5ARYeQ0`8a_=O_AnSnIL2>BT8+j>n2^btI# zUU8Bg1?~dDgOI9K{Fh~|VoUh{#w@ZRNM7`V%5IU zprk+t;2FtA3l@&Rv25>OzxmrA8YCL%>@LCA3r$x+0s#Zd^`FO6Yjt`8CQ{nx9meq| zCN{^1^g+=>b^C8Q18;Tmft9E~SnvkQL-d8&-<8@_mq;oJkJ<%JLJmT~1(NwQOug-> zTh@hY1BTw}vc1WnuQuWFYN};$G^*-BDy6s4iAe0^4^0oAaWgO7dA|@UZ?-2(P5s34Dp8`a93oN6|I703H_eM$LvELp1O7ON}{*O5Neb>qb$0~0=yq}7Q)Q}Q*mw+< zsEc;es$2r}B1`vlOe*}o_5gtVZJ_k=N#LKVx6@pGLbQ&eD(vkj&FrwU3P+~QPmQvZ z3|`;L23Eaf=o+ddu?nX|Cr?-|c;bu~h%CXg{+40%6c@nrMzleQom@o};K)p!8W$&m zv(pypId#Q#gas8e24U4$qnQ}{Gt14@u~iINQ^;_LQ)+^# z0tLCd72C^e!~3O*8&EpGp5@0JZY7g&H^mM1VD${}?S8^U4 zKbq4PrKMvcg&X^Vt|+oH1`RzV&&;}RgOE4MA7$h1+dt}$=vWn58zK6Ol=w~scLa!9 zT!wh?I?&-NRRY&%*cRsxh^RRgkX#;G2#)}Sq$boLN(Yhl9eA&7ZPIBRwKT{_pVORJ zC6Grqjnc0=N42JN>iod{qX-nwogH#hEwhi81kZy_fp6AOp(_-z)7=$6cdY^SmfkZp zHmkN#0?PF=@Nq!0(hz}72>j5>8w95l?ti=bO0+G;)2bC8 zEr28Nw=B@vCd-)bg`>HN3bHlNn3$$F@%#A zQgKVqCFVbw@S?2h`bXsX_MM3M3||>qyGsnZn*!uHJjjhqmOIF>tv~}0 zxujswT@hmqQA_cElKKG*wV0%JrOUt73N4l(gcg~d1PodH&i&9Ls=-_^BADM^X}>IL z^%>kSAt`;~=mQ`Oq`KFjLloSNz=Dtq)r`)+(`EUYh{iVDApfGQDUD3ECA=OAiB~nO zu)_0T{cMn1h3sG5pxo2664V}Ty$tCsm>)>uB-w0+8V79bok)D!VLj`tccK?;Wzy{e zznMQ11D(+|AZ7jS4>sr3x8yhrB#kUzg zey$mccE+L)t8W`kb66&(9gZhyp3ORBI5XC7KV5~fZ%wwZmDQa-{%x{C@)P4MoBTCd zVar1PZL&h8)##4{c}!|a{4bOB@s`vnwTnR$Z9xBAWV2R@bUWluiTx7~GWm~|#bGU< z1L--Ae+R`xIL`#$&C{f3!yn^lt&`A>6MYi3$_+RVH55%*(=IJq(sv_msc81EkS0fm z3@VrdAOYSdJJql!qDc2iPyBiP7c-DzfL&KKZ5U z+SwJdoslY)oUQV+v{5T;CJDJ;n1%fQ?(9KbKBW7oWKiQQ31A1SCCt$6c2XG!`O zJG@^=wl0OAFS6~4pN!Mumo)G^!O{`5o-J`=L;Dp~=^ z=kvr7)+}16g5CaJ;cUD;?94QM_Vo3bqu+bBEFBEauQeG;G4`=@;+FwiBMzp{DB|t` zr4I9f4H&jDLC1+@5ia=riIpqCAW1!V%4Z@+4(O@*@E& zQGII1AfbLT+)}Qhe5@(Xp>&sb%vGN75EY~o2QbTHh~MfFSJxfcXt>ELAQqFKq zk_DP{sJ1Lb#|3L1S`pJX^%=qwC0)h2F(X-U*9!3$I`YD{mncYGEb)6*;i2JI|B^Yn;|r8Va2h1}yo z?f-!LkbyM8^wa_eS<}T)L8)u3WJ$LNyQk;ewY`Y5LI$%>y`dEap_a@T!;@B<`(Kq+ z_J34X)FRn`sjOSF|590<{!c0^sqw#6*7E&2M`f+=4M-Kg*)P?pTcqb(5q2Ml zI4yxZ{)ftH^S@M9{P%yWtdaktvg+6TUscwS^Z%%mW!KA+k1kxrMAd1TP@5fVEG z$BMd>zg+!>Gw>#Ug&Uj~zpzw)JFKl}svkUb@Ih2>(1t$*9&}qgv-KDNQ zgd(`jW$Iy|_MjhCtux8mCXImr6KPNm4rv89**sb ztt|X@gYvwonvLvSOQT_uif>|&Q$AM)G;K}nr|fR&TiTn#@uEoYN1lf-J3%WiVK%#r znA~6RT=o}j5U&9gb0P2UK&f*m(m;b3H$_P-bz*WXpd1MVCP97LQeUed$QVh+Q6sV( zDqnly48jR|H9hz9^WrvuTaLv2e{h0+?ZOf{Un$XRb+f`5d<>TAbM;N#e`VYLVQK)L zo&;9&XgWSJj7KsjI(l2&&E=Nx_stzcdKiU+t5DjcklLtcc;^nch|10^;#x`9om({O zGaf~CDfAEVwQCx)p?=`)p_JR+x$9qgM#d}ud1fGo->z-e;!yCz5S{yVWPVr;V)1oUr zVuHwFUT{8f%|b*W_@Y<}p~bE$;G`xHxlfiUKL5poC42SaaW$81Yq0>UEiHW}TC=jX z`MP7d%OIKE&nWRy8$)NI)cW=d!`WzKn-F$8$^g?Zt)@F~rTKG<(U#Tv? zTau*B1CX;!tCoCwc?EJiEnwgrgT#r*J2v{}{aW0O&sjV+WQ73>=xXHFaE2!Vfc*1H z8)Ov8Bb|GV>ca6ePhDRnwOEwT--gY_AswFD6sUoK7s$SrvvO()Cyw14du$mPv7Y#c z_gTOix(E?$UEKJRTN~Wif(bq^_b1nk&f3Pd7MO*}_-AMF99c;B@>XrR1 zEiINA$inExjuL~*>(WrrM2WN6g_MUx3bw}iZJ(&{ocB-}^n=_5;&CEp599tNx0VB# zRgZn=Teu=;PPsz!9c9vNe%wTu*TAy||CL*D+JyltlQU&gYPOxcho@We3XVSBHV&Vq zjF?cQrhK-@-YbXnY@5zs&zCD+W5<&Yw}qHJ1o?plFEq$W#>Jo)uKg|q2ACkaL z7jav05m)8`vM|p#xc$9K^|RRPqh4U2VCmYfDoo}SRFLl#9x98_3N(g#j?|4d>Tbl4 z@NP+kG!K<#L#dOkvR-h{eB zXu!C60UzYdOKo!$qAkOzsu|<#Oc1kC!&XC1?5^%t;e)AF#EDi(*Or~{luaGsGIF6I z{2b|q059Gmkulchxe0OfD`Ix!xBA2>Fj-TpBQXob`;_J)cr2i5CT{fQ)K^}ThK#8x zmY#6nf4bhjOD`3Hd=KVY3#m7s5t;5@hZQdi=qrmb+-$bU_2LG33J9$W%+FR&>E#g@ z_n>?zAKC-W*-{s`T@q1nUmhDXE-k-%)5#?{X-et2krnXVp?vj<5Ge0bQ-wR_^F|Sz ze&)$3*-0{sF=UMfwz(3`cZRsNpPrfd=lfR%XXCm296Fmc>wOc&muw(!+e>@fLlZOx zbqq;c0+OE$j6&_D`!?wgi+jALatlPO{V7MX^FQe~@|@M$j~}o1hoxx0N}@g)us%FoF?8FLy47vMPEF z!kiQI7k1IqlXGZw*$^0`YaoGpFk^n%>ayFOeV7JeBP(7g1&<0@A zc^3GeAGqe3Sl<~H{4e!orFl7j@YjO{A2JOKWy#i3^YNOOqtnsZO6lbT3aAyyS$|Is6S{aN!Sh@iS2pMXq$lvYS6ig4itY6jAjWQ zkLwda1iXkvYDPG-nZ;!9hQdUC1|Z$|Z!b9S*q)+`Vh}E3ik90l6=W)`u5r^7HRZT1 zZ_MHjy^0KolZUxmMbRd~rxzl$>`4W4N*lk(j4NBACRv7leZzXLW><>Svh@7z1~xwA zVTHIOrCDAII|MF;=8{J=wg|(bC#}_d7fjg;{O1-6ubK3V^;-wMex;B2r9jtO?FM zk&6dz_2PQTY?(2I{C4)GL-sn9x;J>EPA1Nk&`aQxb3j3IgPY?*6e-_>5?#-Owd3F= zgvvM);9}3WCALJ7P;^zN=Om!d@@@4Gy7ij8V9-CR3+{XTqcZW;a&X8HB3NS)Ek5-( z&yjZcE8Nh@s$9)miA&x~9t9OM8tqZ1P0{leF&S;%)LY;sGkp$A)zB(;0fT#V%+H?i zOJCWu8(RGznLz4$!@JC35`9?NseN!f80P@hU`9|A1}4CA1NGLky;%>%0lfWXtiSR6 z=#K<#*_-*v%?+7`+uO{lA^x2}!2b zY%si{*pR#SAlDh_?(|w^(^ag{-!J=MQGLCk$$RzK9dx>-qCRy70DE~%NyXBdOhC+a zUo6~HTvHEHSr9|XO^cTKX>p(ZnPEzBYjA*!$o2c&St|}QXmn^pfog6W4Q}qp55q>L zOfz+HM%}`OI56b*$%wIDH#7o-o;@6KvLiaVZg-NIH}d-1kceb&Si;&gl~KO81r$Ts zkHr%s07V%d+@&~l=0Ljmec^3~1?Ln(gyBa9FPhX9sI2kA5|TdYKCL0p80~BB&3aX< z(IkI*xWk}yIU;Kypj2T&LW|*uz=q?_=?sWcHCTxg8wU_H41ROl2W(!Trfnm%6y0e@l^dq417TOgri0by>%G2l-QLjk;TpKsy;jICY9iC^R6F6)pe%VgxAcx2vnojlv@? z9cN2JjOacd(*V=y0X8v=HWi)d*zM%QFh{6(%eku-R1YywDiB0!e_>h#u;~gRbYGw{ z(9Q-eps&s;zPe}MAREntepU+;WpAv=69_i>Rl2U>X@Ru_m^jFoGB>e|J_c{S#D~ZE zdp9OpqRM+ZwmNz*_GmXKs5m)Ia+X{qXEb6CC+iM|3wOU7WK?|+pafyOJ+PwcY}%$us1BZ_{zW*cy{vLdwd$f}*1uQ`v3h)irHx7v(29DSxelCgH*C&5U_DxmFaqjRKH94VDOSJ2gH>j?nTwWW*d%fex96(ZLaS}k>T!A zy=hXvxLLKP6=~stY~FTctF+gI0AJYdp_=j)u}F6$t8{{nL?7aN&7duUg=lNFU7=)7 zMPX~>GlFU5rOK)n6qGf0S%D7tnJaKIQ`?j_3aHLp1;^?2M3nw{0Ig8#KU6@JwNP(MDVV62>tlSiWY~{<_`tC)gRh% z)=(-fnqU9|MV7s#vyE^oO7WAJaL%1a5WB9hRi>{U)}IY>CrIL&)~SJn-DcVVsN;rj z(K+6ACe8>sU~31wBCCKmCWbZi{3->Pq~usEZnfB}mI=)6$-pg6z206U(g7#P*xrT_ z(kiJ9_?mO)d^C4VMY|4hn)GA89z2B8T4}0$1Dw%<+x!j}uRnsTdA*<`QTn_t=B|0{ zvSqXnReNR%znzLj@_|)ljEx1uX|A8MbG6$xrUdX^_r8;ntY+?|;FqSINPXun0v14J+&gYTQL;p?Ktibm)N$ z{xKuK>7U7+D8N&?aDcG}@QZ%zn>DM2bn0mO+7O+aSwGwAPa;zQ^a2KdU@{3>*ETuk z5p^v74rWbp+Zt6>K1}KU>ZfduJ>g)Fgh;WVun}+;@IX0(rmn+i4MEixmG5yAj?mvA z@spT(btpyr0;o5JbvZa2_tvL0$8$e{P7~ODoDc`$>pXK5u8gKqu0<47xb`eNSGmo}8w$j>lHr{TZlANWAw8IiuN^mXE3BOISqBsM1 z6Tx^=*Dl$ysltBV{A09L2O=@YthaDLSD>#-k-Jqgn3@PDA=Xy*y8~xFtX`|Bf&$ zb)qA1mYk9rgbBqDy|C4&U!E0g$N5cgO!0=RlMAeh6afuAmMosw9YrxU-{l>~#}_!r zAN|>R>318sRp?C!hq!xAUMe|v4Y*<8QmBg6*w+-zB<$yPCcWbeO#4O6F(9u)zAU+; zn3I+&F(k_MQG*cp3q@6jpRDQ#&(PHSwrq$*(ME!xm={K5CKAr&ba24_80BiaS#4oy z*Otxz5NE?YCH3y<;?2;?YVs}a41WtE^u%wbbE&B6@&M}6raqckJg!Vd(;=yqNpREL z(s*}WY>{fD!HbEDBh==ZbYvWi7X>!`DGF8Bcf|`b23vKP#8#{q8K&6fRzt(c#`1bf z3xwJclQ0-+opy_M1`89+V{wI=705hGZ!B_eC0&peDS@*pr84$!1krCy5Yqp#Fb0UC zxx)>u`t5m2w6qbab%=k?z&nSBJ7LI`oPW1cg#DKlnF8yiH)LMkS&NK3fqCN8FZI9! zt3w5fC3?_otqQU#l-p!p6^)KuyYtXp?Tu2F?ty9FsXHU>+2t@-eDr1-KRgJa8}{5( z4bxVQT<&grhC%3e!EtG8Q1@B&;cD;}50m|F4nbN6F-h@4!gt7Ptb6*bgeQfEb7OGl z{PQ1R`6!G_4m4@N3&ehm80bR7<(5gB*GMYS9u4UIhB6j2w9! zH}B#A3|szEVR{BeA{QZd<$fJQ`bKLhGwloL-xc6UmEE#Y;mj5=Vl^f)g}eWeA3<}l zj968a>-c9W$_n3zYq(Dx+YH`1_PA94f@^tl8)a$h1+O;@#-kAL&sQ}=gs%>rt;rE9 z&}_=SY>i2|-wa(5e;z#w1ku9jS@yZ$s?lwY=Oi>6m*J$N(t3-o{@24!RgA83Ka#~zs(;a~*y6c) zL2(6jn-z`d4y1s=%)U(ts~S@5L%$-?d(qY+Bqf(8;6T}`62Wux%RSBpYK>JdENZ?x zpfv_;oP)HgWe$XS0s*tFxx(PBQnDo_A4AGO>%ly3#rAH;PL{LU)5pwT?8IfjF1XgT z*i*!MfUUviTZqGrz5yEKiJPWsANK5)LwipHbc3$OMsRY)D@xjFkjSonRdhj{ zTMx>`*tS|!5#$4M&jkqfAM8j^y@%I(L7MUo!Vf0#7+P}6d=)yS+A-_DrbZ*ZrU+@w zH)}kgY5l#)*-u7SUqf(0oyRoQubs5a4eP+6_lGqzZ@`LP6mp~NFO-%nO~G^Iugsmx z^BGGp-nOCDw#ynmHS40ani8~%HD8(D5LGwJ=#P`@tpUtiw-q6s*xm7pLwpwD7np-9!6f}<2?~+;c_&WoI3H1)cvTxh8*lm z5%rzv5~XxW!U?=VEI9Lb$TCKBu|kb)ALSnPfj*5%m>eKidqw?_3r5rrz$|1`kHa9K?77f>!#yXvBs5T}2f`>I zgwMYbvT9s;*xS}jX-ejuKhBRouw>0Pvo*6{MaBl&jKGryO}Wr_-}S8e@DUA`|7Ep< z??}|@{<=Sws)|hS+syiFRkQZ5x;ERdcb~AHIX@*v-n+L6Awn}`bRwMYWVV5lWK}P5 zW|o;zl7MHqu6exZ9);eC*(^BUaO6P?Xb9=IcQRy4$Wb4lxn2A-mpdYM`X8VvwckLXitQ- zI-6U*%BiafgEja)?g{?Ds0vJW2Yz`(nI%y#<055t2mUZBJ55H$(iuU+@1WY&2Jk#C z`41!#=)vYu0$!5xK*Wf-!L>jm^*~mIb6@mgP)U})0Qez}IaFXqn!CuW$Xc_-Xnve2HeXnTP+z}`FSDu@<E`sR7=x!?VMdnfhR zS*t3mRw}8a)|ubY+8W5a5u%S%8}|c30GdgDK%7l=qWYJ`A+zw3JOL+Px$cD|DU!_m zzf7xgzis7n*x_M!DrWq@Ol!N$KTK;*<*@^MGPI3yXz8NQr!KaRT*&-PZ6oCf8Y()L zYS6;5fQl9ISWF(s?|C5rz%8tBFho-+e*5$|#5MN-Fl#%6QPmt&-T`&pGzX)pSE(1n z+txS5m$5p{Zd@bo-vB+QB-heZT_^EqT`$<(vI_t>XF-&6R`dS4*1I(V7W2I5T>cZR z_=z=ot`QEV4=6RG1Pu-UvZ#u~E)&$K25(pNw{lBvh-xfpa9}RyCLY3f@DWo+%hi{G z==jHJ9Z6OB>$D#JkJCz6GcZ!>zPAdx>)Y`O^~MHx8#UxZFk&{Tb%;{OuW+Y(*=IDR z&vzasDUOEFp+JvZaFiv(LEcKZAoX$3_BT`msx%T|1t+4h>ic;K&_2f-hN5bJq5F7Z z>^|n;k@)n!5_D1ohkUTpPr)0~3zO*?U;u2PADd;&qcb6KZ!8b9ZX^mhh_w5T;_jr^ zf~{S32V?`9qM9Yni#vpWBIit%y$RfuS?z>+Dmg=05fLY81vRVkMp@uJRL0gEJAJs4 zNhPUUUCRu>KKFajNuITj=%CWbxKUq1Zukcc3B zD$7#*eTnNs2Lt9VdMXt+nfY^>wl*AL?F9;_466@I(@i2nNl(WfK zPv;R0B`b?JU$nHajoQ#mLB1`P{OW1Vs1ZI`iLZyK%#u3HN_bR|=u|#-UHqyA}))8%o3YP|QkzW%tF!7*ZXQ;-D^*Arx zJ*9P>Foch1W$H>~MW2S};Wjj1`pZyqV~@3S^ci-Ti|`=Ialc^1+9uz6UxPmiL{dN@8mdN{I?I50r+sdJcW91R}y)|NRI4gHRA!JbHI+?=0mGC$r>5jskL}1nOQE)1c6k2gOz88(hBq&b(|N8Fbp63SF24 zNU_PdCxL`&b|;!Lyq6^?>}K7;Da-%`SX!jxbseW?rUSoPA9|835#Ksi-|PDZ-JLR! zYCWYP92r-$3p1Ajx^z|(8726KNbvz;{dL_9^yTMsRaK‘)YIbQgyT@by!bJ&Ve zA(Rw`Myo7&yS4K*BNR16z1C+$vcGqK)*kj*J#c|B)l`WTbpBh{maF<{_uhAPvYE(i zF@O(XDyB36r7W>O*r*t_e&MtJ=3}V@ywty7q1-vZj~nLzt%%Xie|ZzSk@p9PtfLUi zp-h%7x*TS!oAD`n(8R!!9s8%#B%op2B-u$=zXg%I>^ z6kiF-J2pS6heqOWNKArDWJMfc8!aq!dbqf*8HqPD}`4oHEqw{roG|Ovz z+MG-HCI;~S3Q%bqgyS9_;>uj@`F-fMtgBp;W z)=Xe~qOn<1vd-=tMsXsP)G4zqq;UTWYccpd$Vxw=va`xgGeTq7RksVHJ}oQdPrXo1{@Ign6L z+IJcl?U|`V_n|Q&o?dl$!V*evS6UXRW`57sc|I^4@xxs*s6-X*KVp$#Ee@UHdvgj$ zv1wxng?`qw-5mB2ZKaa_o-Gr!6Fmb9cj3wPKYBlPfci=HyTJZ6NuSo$Q!QE7jiE{% zrE;Z&hF*pBH4F-im(bDqDr#g7@H0Z#rOuyNVKs-~my`a?kdb=>z3Vc>DwJ7y{9aFU zZt>SL8c;zQ_#9@SJ6NlFPl8<}hong~m@(}mzp`zDIIsvg<{r<6=Kg>hb-zO-va2gw zM#}-L*jQczNwxe&0I(rJ^wN+i>o?p~IER=CE7$%hNXJru?w4XLv>>b5^6w|%LF#if zpMI*8VRZ(urK}Fbx4WhveutDmIzQ?@w@Ojx>&J?5<4b5cy#URZu`|MIH1cnHkSdC` zXjtuEkB(hFdV=h0&l6Ne2PTxD?+w7^kU^N;!MvR&bnGw*S~yZ_2S?!`!VN(b(qcC_ z_Az`V*iX!IW5Qvpo?h~MTNX_0APpO5Wfy)vg+7eP!xCb}xk^!k5|B|$xzrPA9n9}v za~n+YZ`(Kww&?pe?h8&P93AkC2#Gz*@?+FIVA-a{K51{hkmLC*e09n7>~G;?xSxm= zKO}P!)r{ky8Fu0(HootQUO(F9u*5oSLth4 zK6+uvp^LkE-= zB4}!mbHW;+QTX*E*WBajtwb~bK30%5(Uh5W7y{z$(}MK&x8#;Xw@oef)dA5bwO@d`^5VOu4=32Q8=qW4bqP zLj2Uz*f%f2wGv7{9&gwn$R7Zv@9-x*)VnGm=Lr>71PN=+ikHl>mITw5H3UGU`}bP( zkJ&KsqGvC?yaD4Q{)bHQ%g$3NG^w+V-y(Hz6;lQ0!Sa^Js|S8L?z+X)AoZSR((}s3 zwohKPPd9>m5cU=ZxsF5JYBNj0zQDR9T9FBDHGOv85C#^Tb*@#wwL-%(%=9nTN38}g z*Khz^!4BLRYtCrsFi_=~blU(v+0xq50!+zp02y>!6HEy0DI-^p?%HYE4g%xfQA~tJ zXx;9<-=ntx@r_j(3vE`GNYm^U!otw4NMm{6&q}~4b>^#)Oc84+P#tu;)Xn1@G!G`_ zm3?uG!7B4l5?wEwe8bvysZBfx;N>l)-l&3%$B7y;Pbn8r8Qx2r?V2mc z5CD(Sr!i`h$@K9)H>szC#ReVMPW=%&UKxnR^u?~?=kp#~zRa(}daEhQu(&fGDzhE- zdzNPr5gTVl&t{kbdk7y^V?l?flI*jX2S!u>|WaK2*JT4 zgAF5P5`3SH-1kwbty8nN*vl5jq>Cj{=<-?W+_w6yhjf0fb02R32spQsHf|E;;c zJ2JI)P$z?a|A_#roUyY(Pusxh-I%gUei05;an9o3sju`av}8h72Je7Sp5Oa)aMvxL zRj6W4cUn9rh&iwu7S@8v{K54~%(8NC7LW8CJizvXhhva1=BRED>s7Xd*NuZ%VPj6u z1VJ^w;c-v`glb*+dhTSX5j=*9dZftUJaR#`|EqK-+HU&+9L(TGZ4$>k&Cr5We*YT` z@FBQYz2m6dK-=+GmF-!U{L_ns$pLpia86{`WlmPC6eE~@152V%U+-l6d}INAKyY8= z=Grx@SQ|0#2m4PJp{3)+9yzZz3Upzk`Ec*75kMh3#{G$YGc4?y-=sHGuBsCDAH_R& zTT_u}#qU?kZ+N2mVO5{omo^#M6@M>fP+jU)RB|uveBg#6D|}eR0QP{?P{>J0rIqt_ z2>Zp}NWWWW6sMM)J#?VY?7;u zgt86rxf6Kyfj|on9p+*bPZTC0%F-Wa=N9yfs^xBqW~AC*FxqK-2OB_UP8!2U z)1;F@g{cWF2G_2!keg4jScAxB8Xg@lG=ZlEB9t(*Zs?kd+yjbxl^yxDfAqAi zGsMzi(qji}MzjhipqmOkc@u(}pebP-oC!<_{PN7_otANTK$5hNMM>I0mr44s z<|_I^^TYc1i;&UDv6TFe=Gw~mL%m?FL0upf=ZwwP^6sE;kTp%O;ZeB|o#(ISx}AVc z`j6&X^{?i-4bUbQ75}Tb>K6RfToVY7BgU|l#q3dzjRG7D`u%^hxhg|3!&d@>#7$!=2XB@c`MZm z{w>tU2Y!;O3IEHvcKBHXS;X0Y zgZU5VYG{?asx*h@XTTnl$kq&kD(*EO_xK;qby=$D_8-pm`y7}ZLo1^uvc^JT(qsDY zAI?=VIO~f_Rvg|=2WNTu#Sbf>tk4B=*NDLR%sw~o%W^=luL%Fd+g6xi3uRc5<;uQ=#GoNN03;auNx6E?%rX>NZNA0YjgbA`v+=|RuI>?ZCo@=UP| zBF3~=a4T|F(_UkqI2XeHT$8R5G*^bHSR3GCO@VilWeg#Z7QAChLCaV!y}_T#fKq`o z=8auhaE*`3=n!n8ND2Do@!PS+OkH{w7Bsa}VdpA=lJ&oyD_r*FU(Xfw|9GxVr`QC3 zKN!$9s+-ZwW*bAI?n$-#j-HUhw;L_5TD5MPC=D%OMA8@kdahu$|Ci^=Ea^@UQPspb z*RVMKjm~%Rs8#dkEJ{dP-gBvo3T&%v8hUYPtPGC(&Pj^~SGj+QO|Sm;+LJ@^F|P~K zG&fxCZGtmIviEWBbgW0pRDepuzm)CL5|>m?>`vyOg%v4~Aa*val`NQlGnLIFV0S;Z z^mWg!;BaEQERTXRZOTFz{SodMCi%nzLQLSxJw1)97bE=l0*A*ns07|te0(XOTj4aI z`5pvwl`idi;?!lgvE+E&O*I*Vf>uv7!mh2>+}T?2b8Q0<0ga#fJdrB`h6ZHH2m5he_T*^(Hgw689e3rns4L}Ll}^OwWIMnxrWurRT6 zK*2C_oM3rIU-S_*%VE?vevmRh_$CT1vD5)t$=QTOA!#5f%CE4mQ;(832i?%rc4NsPB{ zkk;CHZ!iuJsb>B!Wz+8kM_~U0;yiHD# zBoSjigyH3~b9~sx3L@yNsd%JGi8jW)@Yu|4^r|n657+!O{ON7QC>B^bv=HS<+6Fbm z45Z~}jKRt>LUC#{_-J|GD)bk0-T8?72Xv*S`Y-636m{|s=<3YSnH|hC`)9{tpYpVL z3PGeTl=bPr-G~iR#8p!&n_w;5ssa|%y+`mjaY>DqJ)AU*8fi3wKVJ{)At|=Dn{=i@ z+KCIhLSyeb>8@IGh5DsYq91mlb;}3jUFUtY7 z%TFFsD%-}TjW>S+9Igk5PXyV*g%hhbU>Xr`;C%ihz%cPnuVq!;<~SE2c+CJ-zs+3G z>9FivD<~P9XT{yZ&?}&2(lS)-6cu`DVBDGrS#oKezVUr;OsBIti#xY`Le;fGS`Dnu zs(hF$!7>RYD;xDBEmpf-3Hz$6!}o+2LK*c|l_51w9gz^P1_5D*3mDtoN3I1i4^W2Ho7`hE>etM4X%Hxi@S`G;f!;f}LL zJwpxRTPxWIxfH+3z5MtUa_eoW^vV3QX^B=?0kTb0e3V+fv%;1~6BjuqZ#r8cdD9Wq3?6TSY|J0j>KO5thP^$R#& ztPqQsiIYx!^A9e#$TR|`bwz6lg5G?^S25vlV_*VUb}^PKv437HQ*hFKn3AtMJwBMfHk>f zSfpc2iW|lSdvb4YZ`q-kI_TG1JK~zvd-F83%`Q+I&leM?BnbCfuG>sm3gS@9MSh*n z@3Aq?(_-kU`6gI9cz`Iwlu4&x9U-#+&|Z%WV<+%}$6!mQ^zCOsB5K7^6x;V~(R##5 z)<575w74~Z!hn?qbE}Wt2|YAg)t>b)@k$J{WBo7jihjHFAL5lGB3YLytmO~!`b+OQ z{y)Sk&1Upp;?h%)f1{Pwq^Yu?INqk$qu*fu6kJyhB zd0Hb$EO32>k12w)&yjW-kxk_&lEPb3u#snk!FK zjF&4l^H$+MVFepzJx`LY@YK5FizW-H%I?0)ZD3ZYWOgvJTSjH?qwLhq9ILi~n|}!N zNFO0synB8DmoD{x4)*M5wJsLP{YlK^_L@w!MW z)cIfI6)9HbukkwQ^N;bW9{I2F8V&W=c*PEB{jc#FF7RLDHG<}^@k-nLkMa7g>wk>b znSYH}f8MTuA~wxV6ucQstY?IXv}Z$CsDR8%)kCVx%qbzZ{}8XumYd({K^&4C|0P}} zP5&WYd6n&9DF26e1y)kXOD}u-+6@ct2NJsp(-`*(6Cy(C($QoXBscU*RzpZ*M=7&1 z(*8Xpw2-6+_&giNbaUNp8oiZL&{>Dx#u33Hab_;+6T+rN3F%)*L&B`BvBm^9QuTWd zSP&{AR-WSC;~fWcU!QgpbP9ch=cuZkB=Zoq4@qpUGJf9yL9kumqUQsAh7Z3@{luMn z-bm1RF7x;i+}s>9$|tiYN90~XZEXyVEh|Ol2G}m;=hWu!9?;a+QuhD}Gg@%YbdXyZ z|2?J@mFN3^3$K%je}&h#e}z{Tz>XmA_pTJ9NkoZhqreyl(w|OE*Pi0Hw%+EZGG{%; zy#b)#4q%5i>3p60>Tawgd|W10mq7sTYVNc9( zXkc!{ks!ZOc-NzjMN!J#es1inWnWUzJDfFwBpD(SsNQJY1_U~D2XGg>+VsDJ@s=Pc z@>gu*MM#epI>s6!ty-USfOl+cT*d_YEpTH>qDc`A%~w8|)`gg=M`Hz-`vLH7GTuAz zp0B~lK_}KP(ag!y$XpL#F>B926zCRc`r7+?Rn3qenEr{r}Z6`iaIt*LA=cpag# zFT{fIrAp%v2^7=c_y>Bln-vg5kdBTzjWMcvDn2kRDEKklS;UbdPcyn?!Y`S5yYBSf zGL;atYf{!;pq{Pq9bB!-hG(Upduhk;4vp@GvR}4bum2<)1XNu42lp zCYxjqq|_C|sDyn#9@nTsWKF-vwDF*5hj(!-9~x)cRe1+-d!P37In;v=e}#>saR^oP zWcLqj&o;5P?KHDQOkr?EQhsYiWFZSu7^pLKMoe0O>K4PoF8kP(-L#4?K(1lI|x(|abj z-a>`kykQ{H?maIt4Ym*|XubSvwzFwz9EG*~@oE=^#mOrV@=$Md>LTv!q+D^-pA9BN z!Ftw$l0H~n-evn;pT!7ePX;d4J$(hSK>HF(+e0q*u9K(iEw! z;N2t=QPra!{5Gvu3sb3{`;>iy{SZtG++T@*uryGeZnGjU?Jz7#Nn{jv@Gz&VS_NQC<-p;k5WE_kOwJ?i@Z4R@gp?f)+la|7h!y9Rp9m4Cvd|Pw%gji5yMB& zT_6G++ZQTaIiK#HHtgWfO7%}Q-?#K3u7<)o;lR6n>*9JLU~ZT`addijUOrPEYxznW z3DO}M!M!8v92+7;@cH66n|`)jn~btnx%5I|AIfez2|y*99kHnlj%yL?jB`Bx`I?TH z=NH4X{|zq6W_i_vI~LT63nv%yg*W-HIL_e|d@RR>R@r3JTrKoqD(!pV6LD(~bZDb3 z5U&0y$!GMR#t~8Gw>&j30OI1^Ruk17TuA=H9Y$>U1%sz_Yapt1O{&ItwQCz;j~f?1 zxCXX0Ll6l^Ym?qauv8_6*lF!wIyP({{TwHV3t2r10UuX#^=u@7N;7mjT0c$-x113E zCVHC)CPe=0u2X{=O_Rgu{5k&lj(*=Z8}e=&XHce~oT>`IBzSq{2Eq-HAT$wo^)J+I zjNdyBGBEujVhKJO7s^i%o4L#^#(}))GapJhi5zP=54O8;}rZ@6Y3LKqVFKvpr|Aq(Ig#f;QXb)VM#PpP_gIP|%0U;=;Bf z8!8@3zD_d(0C@5|38dRP6!1OqunqjJur0De-&=*I>Z++f&}&ur3D z?4tdl9@&DeE@1O~$g7MU?MCS(lqR0#+}3?#P9q-I&d?=Ath+#QWAnefYs6pPwFu~c z@vc(;hj%^v%e$tc{>!^Y{=dBI=)b%xx$g2myld&N+$r{)xU6|Mo_iWFcC3odl_^`G z_arK!BzCDY$M>zTj%(teBb(g8^i(CVjkl)MFz;0F4sX6x!AJj7k2RTuW0E*piwN!{ zn%+R&xdyBfTVr~+P_sE<2m79J%of`K~%~nVqV&Jl}GLS2Y z-g^o8AM&6z9GCl=mV`<~Mi(nXykMR^!@3!(eB-irJ$3;23+`;R?77g<$9 z24;{jR!3-Kcp&1&2OCPP)GzX zAk&(3cz8RI({En~l~Mi~5N zJ)-AU9Yh3uZLeu;=+}q#P(j5mbs5cp(F?8f_=C90m^lZdC@#kQa;AUqxH>eojb)uW zeD86?4{WTG-(G1rMYO6)f-fC(-&Qce)bXV&n!SvNuNGu>#cMr2tuf?z5;3MWaaepm z`c^3db)lQ2cNSRCl};_v79gWaG*#BEv&+4InbOI$!{HH$TgnCh?qeF0iDEwyYn~Ha zid3mZuECNfNEBGjl~NxwQcY6`JObpTtDU*VTm514y<+`Oiw^s-rhV$t=LsH(p}XGV zoD|m4sRKKqh-2}+1Y6A>|Fo^IjzJqiH>v2u{=qebFHk-08M1$SVQ70kcE3Xt;fXRF z9G#?PynFbPV@YeqnZgMR;Kj_I4Yh#gBkU@5CvXNO-U`+0dXfNrptg$P^L%Z3jq?>j zpRL#RR7JsMt?(EfhejIKYr*^MtFB9(%IJL>RcP+$Aky3{*h^lf-krtEqowJ@+2l3+ zYKH_N8afYG&=8}kf*f{4ujw15!{GLz!`te|3z))^Eb9f`5w1M&AUOZ+5Z)IFZ@%@; zY!Bu5y^MY<9myoi<_xRgw8K0uFTXo3S)6hcSs2svr*8rI2Bp*; zoM}_k9Tm)^-3TvrF^Jg9n5m%_Kgv1@21=aw+`vt3;ByUx)awtnV)j(ptLzd(!+S?+ zBVR=67nGsph=>sLl4458q)`2I7ZHro^TC)YsMmVkX99ZZ{H(=t9X6D#z$@}p2m0Mb z4iR=v@KcT;|I@Nh%bvPB^?u}dC;-CElC3Tb z$w6Ndih`n0+%HQKHd%yC^iT9{78d ziLsMPca176Lk%_1Kxn(tNUYitxeMQR0lF5dA=$pKBYdT;dJvqnR%WKbscc|;!>{eh zQ@;A87hi;>NTB~54bh&!DHeiAaWzL4$S`^UZ}77n4wMnDv#lF z|6w1-XnmT7eZM*ih84^pZQ}#a`Wnt((8qvwK08%1?L4X3D|$3q+@17G8cDx_QR-ls zWAuKX8`qa}NMc~Q2PMKlB+I9$XDFu63lqlh3r#Mi-{d?ros5v{9JJcXKT=aKdt4$= zywR2T#+XFp`bncw^W^4@w|66BIt2Bu^g1mM7-v|g|4232wm-iFA}(lH=Y@SPTLAc{ zNyd8^W?%tlW}<;_Le^KBz0{{|p##Re^m#7f_B?(gghw1R@Vp+@`H<<>G;`na4`y+N zT^Zc>P`Rw_^d+C7OTGC0F>JD$J|u(VhamJrl<(T8B+}hWr_NTZKPC3h9+qo8WnTfm z*L1mz$=q=nSm_yA(Nhl=`Oa5|&r~S6R=HjXjS-}mQin#4kU~6p1%b+e`(;K>Cw;kF4vWyU;(-IaXV44Vew7*AsP!!5&u!ED zKZKCk>6}%(wX^~AsC-0rVl4R4_xWCStOCtXLb8t!g)cPeq>f?2(fKezHI@V*Wv@D1 zLrc*ho*+{Xvq)n55zJ_!XhMqO4Qs={tj!}x zjMiC?3TBov(}HRp-uakE7$V=(-8FwlE?P=EeY5!Gng83K87QkAgK*IJ(6i(6XZad| z=j8iZcOnv>>JNEjjxST8<5@f#aTO_qL^co)Kcun~@Mo6`c=Ot599c$KGW!%h0~KEO zhc%6Sa#*~uvh?~?X2AV5H=-Zw%{WJx8U!~&I(hofCI_7ahBPRauyc7dy9bJ}^$?En zmuOMJ0T8uN6Bifx4)}^l>C*g#IgX&Sd^a$EE;XPlLco~tYQ5`1qHAtudn6ohMYY>h zIE~ZxEwkB#MrVWPlOK|O`#^rl(t}xz6JALNf+&;!5qd@6RiXHuyonz7aVJ0P8sG~x zMpVaPwdQU5BBuS%HlJ`gBqHHIxNUCmy*3crAKX@GntnX)@Qrgh(D(5$^DR12%xZ4C zE=8DZBg09U-wa#!Ds|Vx1_m@0x{Y8vzuRh3@#XZokdLRqkM|tv@DdMM%VMMOA^IGNRm3H&U*P!E?ItebtRJnH>dzUz zmGWh5Atyf`>VW23>5(H`+|D60k=r~$_9!C7$Wa^tnvp6#V*ETnK=rlb4it1gtQ6dQRX5bJj_l%7YrhUcB z;F2Zx?2%yORPU%e`yTMMuAQ_4#9BYxnCh6~wVw6K;aoGD>j98KnzLfPwXvD8(+1S{ zfCfsTtTvDM7w?Rl@0kdu*Ob%@{^;nGUt^zhNSvc4mr{0e7yLeJz)^TUoZx5hQ%a%C z0h@>CO|H=Q%I33<{NPRwq4pzmds?&<+enJB?9mp7S)vsj@7PbdynOTp?|RmO{1jI@ z9RldN0N{6CmnEu~nS?e*Z@S6_Ue&Zw9lOwZ7tjtr4XrwQhWykVyAj%oo4}y#Y2<0W zp0!g@umfdtpVTWMLIaP5Fy_niNmD_mF&Qq7OEtZ4(5E4P?@n6hV+7SN#h*faQA`R!f^une7JS)AAS~=Wt@~@#lafF@IPtt}wQkOWvPwSpPg{ZY z35JzP`H-zm?FaiAF@-Jt;Rg9WHtcOFnY-u`WBJzv4Y1pe{WY@07zbP`N#HvoaC5yu zrGwo2^`h3*u5O#~)vIA^+X7i`9JvhWMP%0(O?8QX5y!2r^#0pubh-!Z5L zEGsibj#a{zamXRM+AjRK2v|VF~ILOn&acPz45jP4sXZW3^+Mx$bfa zd$nHIuwzbs@jR?8q>g|#XbX}wr?K6B?Ch)hZIo(x&E}jpf{B#(A5FgRB`c6`vh(7_ z?;3l-G5CDt^`Hqaq+*m28YTy$lTb8$&bCLDTeq@{d`w>lt@cH_*Z`%0pV;%W!aHW^ zS|{+1t2L$8d;H*AQ~n*QUeqtaWO%bWeWF7%k?g~v9&N%K@Mp?rQNDc6_$}D$B7?Gm0RLs&&YZE z3Cl%l%?IevfjoZ zJ)0;0Xm9J3F`H#;{aV$vX7koY3uSn@H_te}h;0Ff_!jTSa$PuyIsjH*8Ok~@alGB4 z=s#Gb*CRssXJj5Bl7)mAH4i#+FirLC$hE8nl!^26blpHz=e&Gs}#aG~7CUA0_ zV-CKV_m;srqNUc}}3i>{x_WwirQwNTE|Z z;&R>zVr#sXw|9_6SV`#!mvxI1NJUm2(D)E;3h)TTs=AX2lZYZq!^DuGV;R=1X2I2f zW=^J{GF_bVXKOu*XB~1$3QD_zG_X7}FI|ZTTm6kts|dh_u_*f{330e9(Tu7QGE5=*10Jg~mY%?{6vEJ>tH;Bf=-+PAl2awCNiGF;wLbttx#XKg0;o`;J?- zhoM#B1mnJv@@7Tfu5(A?p5g#xp|b5Mg-&{P!xURa>OX^lE&HB>(9(c}p#p4ZX(bPj zUz^rri~AA#ndi3u2q3GOFYht6BS}A%kECs=LVrHw2XV+6DkZbx=N_$BZG9LI$Po{{ zH<}d6lC@AO&H;p?!UF^Qo@WQ-9W_TRX=UldO5Z|p^eU!le+>sMtbZY3&EP#j4%B(GPtNtefKQBhf; z=BTF;CH?bz=h90T^FUR%u;zzx1JtGByK_hZ1Oc13aC7f@2zD|PWTHkORtEv6)8#ZC z*lZW(pCgf^WPzbn z(?Bxr>Bd5PnVYi^rAS;{k?SwZVCEZzk&|RpW(De_?lM8h>;FuPpH?O2f38Rvzo=xX zYbRdnEzoy@2IApivayV13|a}JdGJ!l+c3kkowm`OEHYU?Z}P4SP@D<3)h8|bQkg0H#iz`ipeUbOPt49LNTz$|h<_GKY&#Mg|#?|HOo=3h=E z=*3OyRGAr29uBNDvg9O_vYU*0v?1!XO#yMYL@ExW#TI$k(zs%*q&p7b2XrGUq zhiI{9w5%W`?X1WBUHrzuI9mDo${AW*B+0D*E-!qgQ8BT(eOl?MS>qn?u=3nkJUe5~ z|8w6|b`y~0P7n63;x@8~v;Cr#-kK;&Iix`_3Z0x)!T`$sft(tc0*U+((4+AIUOkjO zozBToGx)Ndsq7SBwS0si<$ic}AZGxaDVB)?OezssmV52j zg6sLs9lab%dX{+wHu)XX7o)J}JAe`yd;3YcE{sx=5&e9c zTJR@CAD~sX^z2R4VOB$Q8A1{^HupkG1ZeWeUr+;uA5qoGJmqP@J*A93whfQue&!3i z&qj@Gy%i-<6~%;x7qyjLaY zYgKZni{&_zzmP6eIZ8GH6l|AmvN~w$2qg5a2>)a@LfF~0ZQYC+gNizN%uZ$ zlSWT6XpM2FKTavZzH#ksM{i=c___RYW$#*qO1La&UZDTB!+`^Ynr(Yo(4N@UH@=fR&=N1v^ z)Wz|=Qw%L8BS!@29H(aM=o^0h+11O+5_T@wLWE?T!97Ypx_4u0IZT)dS28|25>ms_ zZ2ciyNl2?Wms`+vzQ+yL3%d!aaq1^}(7pO-{9d?=un=)x*#X&q5{hQN zq+{@OVl-`HX*hv5R!UL}`aB7m_#C5s6i1>qd0Qp=aW_5P_B01v7$k)~U4P1}a%LIN zmlL%!jL2tQ)ry-mIM?;~WoY7e6BD~HY%n0U0h3{tA4h*+2bA~Bc_*tpp-s^%+37JA zkz~e(>OsB5@8z(2{AH@ zG=#t(4BpbJtr#o47M%8}_DNglQZ`#rWR##}k?Kv}{bwn~^zmoBxP>lPuXduSM3e1csg zeit8nFfb#?UMSP18UO%$dPS4TN{Ya=uYq<49k>oJm)~8AIWXX!1e}wc=$AeA%qen!#6%LuH)1=67JQp@oDa`i8`dg4y))u6saY&VCFq$J2T9IK{bqJTVwNO* zT?tS9!vYRc-$F^6K824GwA}dNJr>?g`{jDrezl-|)rOr!Wd7Qf0NsP1iDxyk4K7K< zivI5Z=XZJ%g68o$#$-U8ncxCYGHZ<0kH;F*3Bu4=gtfOPKAd5Dmx`*&Q?#W=+w^xT z+=-EQy5H-4lpvm2{+aB4lkgIGwl>7E!T4XHsdg{myZhpoU)FM!8?03%b*ZHo!}6_u%YRT-<6a#Hg_yn4PO~ zYYC#GV!&|My+E&m#jy(nJF-~tSy?0CE78&U*(*Wdc%^UD@FY8Ps)zjZ`f7=Bqk&7Xh{lCHKz$|6=Y3)LI?W}ib zLk$J=#v{>hvoEKhg@R#{Sq6cwX5=?l<+xVh#TFBQBk6)HMjWDl!}PgH18!c_)ah=^ zu_x4c?la_v&q!N7p#8v4FSJEot$64PIZEq#{hiZl~kk%S$iP3Sn8j38px{XHejI$FM~5 z$eO{ZOJz#Vlb)*Ka{7}Lq+0UDC0qMSG1pLOyIMTKhoTsDL6Jai4r?P7FNmDGuC%mY zEBhmYsP#mXX77MfR%w7;nEYb9PqPU}1QHtMpYjtvjNa|gr0$~x##i1K^#LM1#yMds zxq*J_yjN|5`&QD@WI# zfnabJH8^^*e-74sHG;cM6hc->Y$yy7mFe#kB8+j7wEPw3gBSJl=m`I~a2l9c8GC_w z{Oort0n|BZU&r=_%qd^BY;=U}$6-EM0*LE!BGazhHSav{q8Ovpa3R*-jHiRMjg`32 zcz=gdrm=)C5YQiMD}w|x3;+b`>%`rq_#lGofvcNMl6C#pbBhzJsm*#DY=r@){3pLrGkzcct#EfrS# zUt|CC48TwV8C5LOen9A{b_=N(hc&l*U|84bomiaM_$t8IPEI%~UunB$FpbLfzj8~k zFdS=T%X@4E4v3iM(6|QwWMVNPQmWYH8j(EQ@U1V8IcJ95nM*9pQMJM6l9JVOKTBm# zDix@JQ`ACXb%Lcm_fsHi9cl1f4jCrn{j3eg3UVw7qLfMe_`)VGwZw6~5)P*}xM`T1 z0`YplIffb9`81YKskP2Lxiqidg(}cPqIz>|6BHR)3axx`685!V!N~S==}OL9zscjg zV8YTR_@Pl!8UVr!>D|+D?^1ESC4y)dkpqCb@r)#7Y+8{@xY9Dtimb<=T}+2=%g?xX zx^2(k@hZzg5uYOcXFbP7&}ef1*Ba^f{(t1XWmKKX)~=1advJGmcX!v|Zo%E%-QC@S z26sYm2*KSoxCQ-Ix_h79-8;R1o$noIoHGW$m_^N5vua*-SFOeK{GQJv(O+fxM0Dd% zZEgAhZMlUqFIZ*uf!lWPycq9Tzv%cHZD3@ z=vw~O0p$2^5#%9=q0{;O>z9Bvr6u@V1bK9#e~Ig-FBITB2C@HWdmxm>$|@`K76w+h z%J*`m#8ME^?@CKD*@67LC}eD0GEdvgx~)_h zeduLYRkPgS{edp1(RG(WC0^2r!pv~QN8B&{u0x|&Rk#}OCW6potmmWybZq@-MVr>8#!k8maW*lgr4y5={|v^vnow=W)2atYK`4&o z>kPUyr43bg<9J8acl5BI=;DB`*5LdC-7_xDkmUmhzf1JrT=y@2<23LeDry3z0nrMv z9TZh`muWV-QznIp{FwlJp*&?ky57LNI1Pv$h&l(0{zx1MG~m@qxquevz7bHg?@H;B$VaODy#6eD~Mqr?qh_KcC2Hl6uv#Wo{hN6KM9^loeUAiB_EZWAz0c)XPx-C!#gr zM(G@qbY07y;2~mCmUalb>wA1qaW`%~T-#?p@l}ikt3kJT%4{21!WzdFFAQ$H09$Tz zNL=TfI-4`9V);GE`8L|r8o+xVpL_`fhh$1&2|rC?tT25iqPERg8(jem7EdTI^H|v-2JdOKMJ04kpmOP^7Fdu=473-xrT?NQ+0PK9aZk70^WbwI;y||Izib zqxo`(cVMv#m>eOmwNJetR!c+%A^r1gXW~dmat1D_SFtG@)aK@`?*dH(6Bxzb4_3u& z3K(nI?G~KKD@b`X8B$*=h>B-=D@Ys)s20+=@msd(>IN)^FJxUiszM)@@dP)=nH{FM zRqItmcX0~ZL&9D@feS@MPWNflIJvQMnqO%7?7mF26q@>Ob~#YwN^kkQTBKxA&pgkw z!`)ixeris{!gF&IB!gnLNLi-c$i0W32_PXdCwb3->SieL)!`Mo)~~N|yjry`K?F5Y zBs&a=alyGS?rg{mRzUi@4ukOP0^so-h|?z2se^>l(F06|>_aE7UX-&QF*nZgFhYqa zgpG<-r)yvdq^rYjsuj#G&y=aBN^@V%t=c}{;=21>(gQ<4EnAWUFu)@TznkXP^co? zbkXX8yh-<5yXXDp1$d-f4_>&8sqIsk#I4u|)m)3}n|9sxd%RuYmWQAcF88seiLbcl zGf$;bRfKze3!mVbIluDP7K{o9PC$@b+>yVjaXIcN-FTI0Z&B;5LvM?s$EkpNrP}k4 zM8r+ohhNAav$~fMvZs3q>aM87s>9FEe-U`^6XIgtHZA*cRp!;>1J1D~A_0ibz!Iexo0S!3LBHQ%PT@;cOM5 zIazp$tV04)rhP0tU;Nr;baJe6!9wEfXW3TXWXpZPil?y5i+D&*1PB&K(3-&1MvE?wcs>8H%Mh z-KG|U4+9a_7m;|o*V|Jvh1D=Q?l~;Sn|to$qvBdvLHhD-f3ErdbzKc{vRDSf^B&(a zq**+H#LKNB@VTC7BMFTW{5}>HEeS{|^$CNZxQAR%4+N#y%y2$sOP6^$c9T@ry~IT~ zx7MT^Ys)3%VT(-VZ@~tN_9RPKV^;0C_f9SRmkvutIJso*wy8t*eiVm-;rgSPn@F4L z1iDDZ{nGf~T!6tsQdO9a`?q{SUk1ou=w>!6CqbO{9( zR$`Oz0e8)Mqwn?Qyy#DpP6!r(nfY#_d*COD3Wu6sB^z_RL9+jEZ*p0>7L7 zM=4+-19}IP$4_sJo!f>#&25hXGni4Il6qnpP>o;)N!C54l-TgkUJg0v&s{W>e{^|?lZIB9x zxGq}t6T0DE0r(F|1WSs2r1y)lVij8D;czHr`bQF2uwjxV-INALWxJ21iG!R!0;~r? zi`9-ze265pU=<4h2XQ_udw&U|<_K*S)EL%yo?iPg&&vevdJ7N%!JjemTjl=- zdMIH7knFq%Gt=LP_cw(6L5QCtp#C*Je&;=tb_-~XvlW|;es8N>1)w#}|KiEN#|yO3 z)R@HEfl+AMy!E-~TDAL{Aw&@JAOg@F^FQfv|81V+=N5_!ocl|F$ncnx*8}W;wEw@y z5I~s#PEx;Kx__s@@1+W;x?d6C-=~d#EPnv6{-gZ=H}UFk@c5lqf`CcI1J3&uK!729 zT{jXof1CCH2O$Cg7T}ia@3Wo{NXKt?ReuB4A8`EVivF*H001n&&DCFh{m%jmpiKX! zD1HN$+t2X=LjNTceq${_3H^!)zb~GjCaEtWUvHce~Vf-#Pdj3SR`)`}TfR2d% zL2$_M*jX^Hx|VbNWZVBS!sCAu8vm1;0RX7~&Yoewzi#aSK>bG%|4#$zw`0hkxbSB{{gllpnn7Em#37!1L~hoEC07b12C@tfX4q?sy{D!{<2j6*h_y^ z^8Zp$|E1hje{s;DD~xwo+_ zzhT}Ykq30d_q5G!!-sPFiX?Au$2-V4GC)WRAnY%tgI}-$!YGz}^e7DCV0a#Liym6? z$zfsr7&mOSoMNEU1HMUk+sW?Hw?1bPO6$+N;nEB}yB&8FbIt^X2f0?hyh&dv5o_yf zvI{ynMbqNaktiRv>kbi!xu|x5ykG}4j=Cl?Q+d+wOjIL_;3O|rH6J0?ONa_aNA}1x zKJCsa=L_1Y%1*r>P0zO2 zXI1wP>iL-4NUAul<1gVe$GHSdgeW#FwurWE>sVJ~FGQ>+lh z=*0upc(+ieR(7Ati*Gf+`j(O~I51OusUI&n(6>rb^_fVtSk*KW6qq=tuxW;A87S{g z4dwLFdZ}|UE{o}q+=$k8DMZfr5tZJ!#mxm9A)CXk6!SWr(K9>ua^EC2=pM*|ef;*g z-Y5F>HRfrv6=c{CoZt{-<`^`XJ${fOgzrOBlndlJ6nMrWpJZ0``v{D+9@mj!gwQ4x z*#IR3vOWs47tPsHsbt^$!oX?iqNRX)lYp^8oDEFsZ~Q9^ej3T9 z<2hxvMsV}OXcE$2EI1;k(6G}lKaXwRiU-j%CUm8jRX#?p89swZZLqT&G+hlR5hGQt!FqO2kjd|NXSo29NA-lc z(xFno(5gZ(8ue+p|fS1=*h{}Kv( zSUtdnt*h@%Gu@;V-fmN+N!FEMOjmSFCAjKvNsxaD-ju|G@9>kWr`p|VfzL41UTVcU z90?R`w2vAjy|FHB8LsA8&jX}7Ax**B-5UnF6Afp@JiQWpc1p50{VEO1O~JwL*eo1KL#zNZ$@e-G!#C?&b4br6B=D9J%nDny#k7qPJx?7^K-aRD`-7GC zw2$v#Qt8C?_l+96VaYj>5Ti0Tq{1x*VaD5=Dq=*_q+N@F$Md(SYCzz!o48VF939PI zx&0QRtSQYTY3YBMf+Gi}}Q^PSy`aIkeoVELKC@D5qYSvK11l)@_%%Y7k4Af6GR;PA>qFCQI2IG%>pE9g%t~9 zBX_f^XU-7D7~a${5XSGv99LWUAO-|>cNB~4Vz-?p$Py$=g1(?bd=oH;B;#OFguw-; zvMoA+5Cq)xy6m}0y>Wcn+_6ze?_eyrnTb+0Mpk&Bhwk3AD{VNDR`L2-c^)?QLjpA7 zyN&)Ccy4&Up|Rtp@$lAc=cmQ`7D6GugR%-BLP)E=0yw)H5ySaU@R5tW@hCit4#MN_ zEyf(Eu~ zCNn9jHMq^vu5;wcZ!_5#uDS&Z^#fMubnW&m3$8x<1IuCZ@oB;GYCJ&$-^H}7XplMX4QdmS zHrQysJzP(|CDDY+FJ`n zO45BI1LBkuQffzgO=lfYSAJ_%aET~7c*~2v^KEvD$8;V4N{7q5)CXpd+wrPyB=Ru< z=_GZ-DR8l|U}aw;BD#G4MVvPoQ2wN_tfh)U{xqzsI*&T@B%-Pa(F0Lu4@Yx{3xDWx zLrGvqY$g%8VYz&Rz$;8lB_gl;oyJf8V#f+3v#wJQ71ATRb!Qa>rxe)WL4{y8<)o4g z5t4`Jc8Ggx%i%#Qv?}B_Hn#Z;EFxg3)p^^-lr;ye)jQJ}*p=WKOH|z4)mD=ir3jYE zU7DTv2Oeg}u2v-vgu0G7xUE@8Ks#CK(%bjmu-Wq(CwX`iH*S1m>K!5{b(|coH&<%s zzVUJ5h;@Vtj`}|q1FD0s1^Nj=4>{=^Af}6jUS-(RDhThZj?X*u=!_y@AiZ7*zT(^) z6L_%VA}7bWO(VnDs~)%RTRUs&>UkuqIBZr0oZ^0z?z0D0QLWRXogzTO&cgo&r}WJD z?bRqaiRQ@eK{>9+c_!9V5czt;^lO~3%B3IdiFt-R;_8R;_(*VF(lIkFq6>I~*O6jI z_eX7#yi9EoSpCWvyp0>@EG4U-y*8Wth=eElX&~iPHgZ5_Xb`y`F?MqTiagR)mzMrVRfi+o)7 zZo7_>wb41(fzY%sQo-{`C3@J4-+>+s>I{4{=vwEWgYr9NRM46@%M9>{iEXC7cli$_ z7s%O1AO**dC>9PC_UDIdKdfV%(L@VQzbnaH|IDiZ^o^=OQ^kpr?CYrXW_j3AG3a;J z{1P=e=+)`>YCzfQ@PRRLFwiU8bXhm*daU7z(zD%`qJq14@zxjk8fyCtVH5KFZA<}7*kqXp!L^f%{YB-KUx~RtZuU};D-AgmNAi$|mEI+LYM;pIWAsF2Mj1fzU0(Qzb zc(b5|8$c~SOgX}`qPN;Y*Q|lBA+b+Xw6^+01n1s8#5gp3p&jP5ZWmH4jm&x4hIon; zI#9z%m&HQv@s(cq#TNsiouhk2H8Oy+C8mIucy72RE>^glcEInxhgy+wQxF_HWh!iu zU5)AGvyPR`Py&zJs9hftme#n?bWH&Gbuse3WS~o;fOEUhmSirnxOD|A%WFEx;X-ZJ zkFE%!wHxqR!Q$t%vupOPyEDD$l2!}db(d>+N zDQR0IG~Nu+uz8IzBO)D~LGPZpxq~i2GOTu{^)+xCV4sc-C{ZcFOizbnN8M%_W3q`T zm>=-xpXHTqp?~PzB26atY;^2b$59!!D+IBUyvHdo4neme$#NL;Jo%iO;4)zfAtB=L zGaIvf=bgBdwTp#jl{J>Li~{ECZC~BqgE@RJXVy+@WOk5HL7N+FemhdMx!Zo1wqiXO zbk|jytP_t`9{^VJP-FtMQfSnY<8-G>ldLYSqW?+?2fAa4(a-(`&a&3uwG<~T*UO1C zaHq1lVkw5UKQY(Ov=tl6OpgM%_M}$Y+=ULu(qf7ZG~#-^R=6jz95=g_3!KNpl3)N5 z^ZvX*++SU)H;?Mu;=cC+Pp%{$vH|l&PfKbWcZpZHRJJ4=YwC9MvbU&L<2k%8C|K{d z>9Mq-E9WC-m((~6U2>7Q)epE8yPV@CasQ|wffE9Yop3_$a}E#iunW>=b8mb#Zq{+` zp&#NP+wW-N)LlpFX%uoB&v+cyDmqITRk?o8QZPolWngw1b}Utbz#2oSvr$XsSy&j*FFq zeWs*#f@hDdfUnQ7bg7hBI-=_zSMm`maezo|P6_sVDsxl18u%~rLT2X$oUzwzZa-r( zOii7FP@Z;vU&7^w{V>6}wtMzvX=}oljHk4Y1oi$MbuWp2d&hv_gPy|#3_fIsPtiN3 zeCk=YDLs6vqVNpMINJEDu)d%n^02RlsV-?VTDTF;tOE%tDK7m_H^wY+(dCCrRL$;_ zJ?yJB7>?;NGg(`s1xNx1DIxI=1{YvdksW7w8Hw$z2iuw1E&xecucQaC`66@s@-y+?^#%4aN=R}g!E7;-S7>iVY$2}|UHOZx_pv98?hP+sg z&ikPV4JlZ$UFv&zf}1f+MjPY0$hro&c0FG4w5WbF_?a4rps2u>g6qy`sGMdadOC8v z7r2q}P%08+Y!!bINzVwHI0byT4TCYMJj1Pl(+Epa&GxWFps%gDQw)1AUswjl~ zJizWB@OsJ_yNNL7QeHS=VtNkuVn>B_nWK+C=*#TKlcTQ}vybQ&uz`-PtNsa%Mq-8ky(OBH;|CMBR$FBqMY=(ZO!zm zAndJzAA8XsvIaAJEp;fmhzDJ9|G?h06aI@?R>J_!^;6YrNe6P?Xr)EskwDMA^kf1@jp23$o7Sgu z9Q%U_E+W_I;*-;fnODysjAyjLkpf^@$VXO;vf=ZMeY;YQ3kY-4C2Y&jw{y`vp7A|9 zVhTDz@$0?tu?vH)hsBB)A6R?y2$3)2>zl_5tKVnJG)!8-*R0?Z%GjNK!`ny7i#<{Ac z@Ng$xt=f&p3ypTu7>&j%^}^mtPhi@;5ZJ}O@cfS$K&fTR&QpWD4GKZz7VB?`QD?4Z z_rod5TE5f-pTys$f`+A4fnTiXr5s|~RgF3n0vN;t>LyyZ!V}PckY0}DkC`Ipt}p>tHZeR0tZvC%)wtyb>Z8)g0g2}uoMpD-eUUfl8XkV-nKd4Z znmTEV))v<}mgfCVhnqWxPp$Omw&9o5=Y+~nILVAy*N|3#L5nsmL3+DnR7FQNtuC{XCQPmM!3HEl8OLpu&66X)KC2wD*Sa|Y^~O9%umHl2 z_{A}@{Si$6h8^b$Vy&v-S%C*dQ8U?~l&vH&k($GjDFJ*`W zs$xA~*@-EaKL(}Meh8EDTExK~Pkl;Y)LuWGpdqFjL?{Ghg9_kTqJly_=Pc#*X6y}< zknyE>Y88XlZ=;Ina$D;1N19J%W;>|;ijxJQ{Ps3$3v+D+R_aGNg5-d9L`HfIL@90@ zNFaN&nOPsqXSEenYx(Ajd;)j@yghPXw#p-YOaenn?PIm#LX2#du!*We7O=3%lCf(# zljVs;@Qi9$Ny%7K!^##qAF&vX1Ttc4($zD*-J94)YIm(eOka|)X!G>Xtb#EV=~uIN zgafh-nW$b$3a!bBUtLhGZW&Gr?7rHTaKl_QzS|S`OeQMLH7|I=Tu%d|PuqT_2-nSy zKsPSQ-PS+=VPk8z=JdBm4=r73486S0cqvKP49|^&7s%kF8HT`H7qzSm7dn&Bi*bXj z`C8NgF}rfDL83$j9=HO$dHmq@UAnP5c+D#_K)Qy5gDsB#$16Tqw-gQf|)XrT^6uKhDKfFka&&6&#c`rRW=KYZ>q@RFf2oE_G{3Oe6o%^I3u6EQ}=l zC~VL5fqC;QO3(t0U);<16&lG$welWK&SfcTlI*=rHg7b|IHLmQOw5FY<}3G}&t4LnsnMqFCe3dt3Zwn zc=S}{!pJ&~o2rcLN;2Dkd?VjC(Mom0d+^cou5N_#vUbU09bX21PsfV9**hQg1HFI6 zkvd>UJ9buo=j$ko>I3*B!!UOjae7lv(x)#rA!wb?DN+=1iRgx>;_t&;{b+HQcJ zj<&&i?(aV1dKC%}oQTEg5KKQ!(j(}m2Aud-&JJ@jT5;nZD{$Vl$S{O{7kdN8X){$V z5KwtgM-jFQdXV~(W_}$}(KlwE zByx=lG8Da^x|}JW!FYtxNHt9-}8BE$)LkSp#pn(qYTCZK@Qpz6ME zY%ma9fYciLGPxHq$`bBq;x)KA&(KV`Z}Ji;olXyr5dhgK&P`!6j!h3vre>xm^D`Tu zjx4RSng-jo;3DjPKkd-ZFFbu2o}7~wO(eC523E1@vhm*tT9YgignK#;T5}3O>Ej}K zw$uZrIw*bO_jd1jo7rL=nd7Z-Nd2J>H+o71=Wp&rcw>YW79yHMuYo>Z1oBMTY z<$GmlL7dGQ7Dh^Fj?gO<@nK@`L~Ssip3MD53nH1zVabiI__we)X&@rMERZceiqOn4 zF29#Y1k-$NHvJm2c?j+shg;9Uy>dseCQUc-r12f50qiGNi{7Y zDqy2i*K)^o5lBWx_r8QoM6+oyUK=BjsmhCcLiqiLGp1b zlB1I!2pq(KQ^Tr=Np_&awQ02=8pv_Q6?Dm=F+&{#VbnvpQ0Fu@&aCRuru&%t>QHwZ zs-P$MI1jZT#K646KTFE`${|L8UO62Fq9|;9!N5D0@e&5AJPzR!(wT)|Ga)@kOm8;J zEX-j8esG5NT|(?DD>{1OHq==RTI#3t@U#H)X&41tx_Ei;274b?9=!|iPwxk@N=WI| zL(C|B?P5eFFK}bY!_8cP#Y&3t4rC*KN!4~QU*o=+OQI>eEDa%mtco*0~Mzk|OjE zlTivy3D$bJ1-wf2kXCBPwwJNw!?$SJlFyB(isFp$Dqd0!L(wifN)}F(bFOe~4A6%T zyZQ+bQeAM)7~p;SL7pX_OkwudDx`#ExMwsHS}Mm7zI!g}QSaTd^KgpsS4yHm2Xw?8j+dP)GtV8)=np=fB%ofAnyeeNlG4aqL69srchESx&2)mc|Zzg zAJ^QN&J#ivYTse|D?jA)q(d@YZkNnkRDZ}>Xyy=!F;c40VG~-(ccj@CL-w-DFFWEI zBdp}FvDuRgLKPgj(`hVIh8k0er z)Z?uX`UW*xzHDSt)?&G~jXS}2ZMc++XJlBG_XQ#`e~~ygI`$c{qzqf9r+jcF<+OM4 z$tQX;$p1~QO2*1MIoFhMeT>6`V1292Vbhx^WVKemb zo@*k|NY-5n0lvgz+?PfH<56*tMinlcsEKUO*|GR7nzxyK6caMGNJqlykN6pgd17WI z?~cD#zF+^K5KD2&g{G!TTkwL$oZ>b<-W}i@BVYrWLW_yW^SVrH@qH?G>#&(o5@;qq z%*QWFB#CVPp2h~0EJvq+6qeqTOF|r%#v(}yx_pDrB)_>#@2+=2Yc#dE=O~uXIjcVxgkpHG{s5j$fcN1b zDbVvk3+9Pa!ta0|q?w&zZ9Q4&cFUwy_(;D(S|iHnxh`_liF}RsbTgS(BcLl%$%N(D ztTCb8Y%WNTWmeLp!luFRY&PBw><{XSvJMkX_$C4(ezQ-SFUnr*)>16x@m#MQ?DC;Z z=KS+Mw1;2}lfYp^4V<>yllhn~g6j{YCu`(RAI=V*7FZ_Af-*c;*Y*ja4okKioz$lD z;Y{+p^9VBAuQG$Rw(B=#-&b_flY_>v_CodNK2^+g;3OE$BJGvMkDuNdJuBX@NNdVW zFIAL*)SR7$Ztw`L@e>&;27#`i&8E*RSMdjBySpV;M3i>Vy36WlP%>Lb{vgUhLF|%* z6?T*#_W$I0O437SHCW)NU4X>Z6Sp|OHV=B_tR#4zE>vRkm0(2GaIALDpajN9OyD@t zFnXvgeD5tBMnVLpjh{d;2Pwe8;e#|oI>Z+*No351ObOPwNWS;h_HD()1(Gh&O5P7! zMn*KoG?H-|=4govn;REGyofd+X;+`XC>O!;6%S>jYURCGg%bv|+hDewCA1}8!F%FP z6S+SE^(>G!Bt$nz(~k{6cj#rK%W|I*4YwCFH5@~h&frjrU9rzQx~>X?8&TtR_qH{* zak#;@eO>)X)<7@HthC>NLb3d)kNJ5>QmanaO-}>KN=pV_-I zFC2B69)I@UwJ-!<9nT~Q=YAxvaM(g|$_Kd>3FQ{dl^bGWebRZe_S5}>zd&BZ;W>wr zAk<90R^VH_=(?5Qkn}$H-``T>KzOON}?4aeXM-ZC0ww;QjwBf zKU-;8{FeW1os98Q){Q9?c^WlkzE=35$@L1RR!`UmqZOff;PJAlbf!7dLMbqJ!WFt4)#h2dej&5kyO z=^;!TR$d5)W<*VGZM)!`tChk3wXmLbdsqc#LL@E!*_qvI^^_3t(yi^?CMcq|05F3? z@SW5ur3}rg_vHBGjCxC_j)F-yMovB{ zZyWa>EB^;Jkbv1#J8T=?fRbGy=^JQ+3p<_Vc2v0QfbF^^ZG~F)Pa7;$E|3NdsMQe z?33MnIs!4re2OGLcmV=b*rW>zvm>&^r^4mjF_ULzzqCRKkgMrRiCNG1Op7sL`Xggh znTBtub_OwD-s-~- zWj161se@Y82BGZim$0g7aOGR&p|B}>0px|7T7XQ%RthhQ3S9k-KJ}9?=(k$oi&gf{ zkkGqLQu@stzPYOy-IsEvUZf(K*r*uIL>Tl#Yb0p10PQg9PLJe?QwdD=WmcmMq}=<9 z%B&I*mg#hOY3puw_lL{;Y`ot1gL%!$DGbzZ{J~fQ}_dw&tKKx3Rql*-B(kX z>@EdiM(55F@!P1<=FO9mhW#RXufHk8S_O#A`Y@S5KHK$K+a=rMH z(-BG+^69~IT2h)GJoQa@HCR|Ena{pbMRi`XPb#ED0#Wu6Zx{%8T5`}{sP@!KwMY8? zFh4S4_b5|dFtPcu9i84^q{8reDQ{fR^j-EsYMDZ-vSU!%^deCeb_pjCO!$EN4B~sN z_2e=T!r0A|Xm13`W}V%$E-xKn5${``kSfJ-U#?!#QD9}{)Li2oT4Aef%ZItdy+;cj zq86GsFu=pI)GR!jD-nf^*Egb16yv_}UAjbUV1Km*<}Yw?AehqI4wDG&v(+4IGKLo+ zVCGH|MSFp!j!<$oNG7U1r#{bxgWPevpji=e&`EsfyLoeuDjmnn-t@tnz*Buv0r}g! zls=k7{wRF80{P8OxsB?WS`jlCPt=gMv!p0h~|E^3#vQ)hkA!8GSKD!qrm?LD6@=k^K{B&Y^-J*W~F-twv| z5$;dF-VTcIZ9E@+hKNGoq~h|uuDA)AA53~)Y`$9;e)rZDz0&5ACBx#4Vr6e(2R$4( zkG=%`e)aX^$Bw4fdV};IrsJ4GDWC>4=a>v8{x>I8o}1N+In+BRG~C>%!CQptF4Y(F zq8hq8NmmV$dxuW=6X%_VT1yJ1jJ7f>TS`dRc-dt-?3b6mMx27k(vkFuWW7mg2j2>^G?$YiCczX75Tm46l=H@X+yBEw*|WTM9V9g68@2Q>CSM zxFGx&G6|B_j`8TN6Zk&dL+iCF$u1AdrG9RrCs%_+NA6q*$%d<~!ps4@wDgNp(je6u z%>gOiw}U>$31m$OJ$hfP{e(FrB;=W^Fvd{!)&S#Opo123@abS^W~*5A zjEr6Z6G_e{4ZfR=WquhGMlKTiv&Od(XETX=UzDUC*Vq@)1yYU3LR9Q`1l->(QafpWn?8I%Ey4_6&BKzVRhAF)*utP!-&-xIqiz9@@7B%3DOO>bco*%Bat-&?P| zt;V}+UyM%uHZ12nmeSi67EqXzo96%;de)0$r$&4o$hh$ArPuSEyOa?w1Fmiu!~`Y} z@{+Be1^A?af0fgPZy#UpalTNBiL$vmf(Y)m&UZm##*!c;>iU~U(H2H#q*j?0wKSv$ z%yA3IqbKaC_N$*{wWL~zK+@U zk-X=GUWN#G_TbQlOGAxVJp6lriV=zXU=gGks?aasdlVti;UbFmz1W#6*+4SvPG!sI zc(S;<>P$p+E)o1~galGL)T1)4m{0k59RA8j++zhQtIT3yiY)i6;=>MC{^X?c`wLs6 z0Q0Ksxm_gDiO~JC`sleLRqR&H1x0be)Ipyzran)ImB{x6ghh&N#lr8@K;!whr6|#D zigT`%aafo?ahp6AP{6Mm$i7qY`Z#`e{^Tg>-9o(cM1_PT`OYP3w^*GUljczfyXDvoJ3O)*j!`~|Yq&^TdgW`PsRL`L>qfOaG9A<= z4iO-3(VZ8&_p|zB2fV!;;fa!9usQK|T7=57SNig48}^!y#e?1Z#6Uf<6=xR$L}{>dqLg@FdoB_!=9KRwLLL#Q1;b+v zV>t!m++?(H)PcrWTyFp$KQusc&8|qi3S=3$hp{k!kAtf4%3U}6!FrMwFMu~qu)d^L z5jgj@heoz}bk;|9bZ>85ucGSkjJnepceh~~Rg6a)13pE^;5sp|#er1hpHu&FS-E76 zdZ68uo2RYg#@>X-ax(HOK3qsHB9un$mz&6pbThZ4`rQR49RIsARTi#qxpCU`z{^=H zDGjV$(OgOxa0A$x6Z1#mhIHf)FxFOeC}s#IyHRx_?`6UboXtp|D6#cJh0q_}Ev`aj zk#7dhS@FfW#j$1R3}yp+UCdzkDyf-NE(V$tGf4BKho>FX`dG=*i*+5HAJ}ar5bA9+ zv1rhfZfM+G#U=b_wH2y#reVmg3F|?tTlb5EcT~IwOeDY9Rg~IW-e`qlcE^<(n2E1^ zi(e`Ar6a@gZy6>}hS9vz!NYioukZ4T_iB9iL#yj6^>@$4O1T`4eup;x=qb0iCSLb$ zDbyB;!&J0plyyi*Hs7kHsP`Zbq6QuM6+9C1N9I%2)7a*9b{MnGh#IvDv?HoUBa&C` zV3y(hxCeEIe*6^dRvP_uRv6goNklXF(I`n06ptV1Cs>+UL z%jhw=5;H+S!Mjh)R`xT#K_ zwIpbYsxBL>a*7_g3IeE>o!3v~Yf)&3+R$GFlWy)Me0+ojg_9T-xW*ut{U)>tUd@SS zfU1#RZFle70go)hID$=F!?#g?vty=_7kS{22xH)L_jZBHjmy3?;DBEAb!dpnOZXc0 z1wq(!g2M>Zc*F@)Y`uhCQhcvsKmLHdi|Q%c!>;1+=rM}!_4C1?m_u66~4&o{YJ(A?YbVKH11{{wkWPRkZ454=uGUQ@*);Ma-3i{z

lU0%;hLz%@Dfc}!=7j-?Ih=mf%dFltw<1DS$`jmFdHZF@`ux#Qh?clc59x!T; zNO_7yq!fIJ3|5oyLAetcLrRv$hOW09#>V;1>Um8O$T7-`W;n2c8kTSsS4GQFsHVxz zK#DGFh(F_yttwcTc>c_aRAH4LrrO|9;JI0bRNjQY9L)em31j|!CU2d-sn!Gn>NG{b z{h333a&Mx+<_+c~r*auLm~?@NcP5?{F6K)e^S5^{?NK!il?KL_3Z13hKH6%oP|)m+ z-)cTID}I?TvZ2f@HCutogyjHDZu7D8Fa8qUfgyz>{$;P*OP4;LwcHQ^`x1W$$6Sg7 zE%IEv13YH{i;rrLCsjDN>p@P9GmmT)Jcg%&DNen zWk?|5`5Y(O#emj;N`q8=itq#W-97pAmnq!#aoSqoBb%GB0Q$0hA=pQ72e#$RHDl;!#YC@F(c_ECx0+1AVU|Ncbb5(<#QBoy9?_4rw}mAWyQDOI=cXLB_}|w5RCn?_h^Dv?f{DHo3X*Od7U9xrDsY z5iuBW;)^BF&^uPqf!beL?5M9c;gQ=8AF9(Ml-tGT_t=i2-R;oqxnFgixsUnEZd_?# zQgf7zbL0xvnMB|P`*k83=e3)LI3WL)VFcHVH=A+oIczGIWhGuX@Uo84IasMZ4SwJ< z1>TQ7qnGL$mZmH`wY=J%?Dk!oXdw~&dVhubBl`7tMY5hJ6c^F2Bl`fFOJXa?Z$EMp0Y}{(R~PGl&1ODJd_>k zIqI|9wbt*`$fh6@ly$;v>(CQ0J3bw)VX(45%#{@=%^xMqIJ2Z2KS;HGPq5h6>vL>b zm})xu=&(KagRY;~xT$B~AhR+qe-z_Uj1k5}Zd}I&^yuY%r9@S;>#UQI7qf{K zcfAj|oq{=~N3T!9*2jJY?_RpjMx+W|O-e3`TM!0ePGq~tq-BfF@%=J=!_?}Ul=;a7 za|(fa;Z9`QLHW0sN4)VDJRfiYSqg5Q*Zy#p4%$>*NLfJ?##9G?Xm>J)B;!ly_m%e{ zf&;sk&DgPXJf3d(+y2;r&@|*}EOij#pE)*9Y>B@;n6!VtcooA~{CZ#3_Ti~9xmwEW9!`22!L`aTN>YTGe)VfKp?}d&w^(&mui^d7SSK`lSX9@QSjV-rqRI ztg{?;$c>XI>yOfshP#UDWyStT;?vM^?1f;u55Cmya0Vzr8hPRf=*=+B5Z=ZYj zdGFrueXfteoWD6@jyY!j7wgZ`3ens8;woHyuty)+(WwUWG;p{WT~u=o);)COCb&QpnzRpOQ_hhxeFjt;XcwkSAsZU41 z{e))4g|zc^Jw-&83?XX@Z8qyDEz*?V4rNXlj#HxeVc>epU{nJKb1&!Gh6T&~k|L)& z%;AqGR5e8CrO)-9sRUd!oO09%3r3AK={hosox}>mMzuMG36~q@RiC^-w}q5&TdD11 zdr3stfkodOKze;{*P>f_D+!YiGHozNGZ5 z(s9)j!za&UK0?Ys?#KPGjw>>sT+i(6&XdJ3o9vRKk(3)g5)LK3?%i49X?h9 ze0>i^UMj*Nb4d1=m}Yg1A`%j2z?@vgOfi3mhrmQ>6>+oouNAy(IyqAUB#B0tnZo<%jhvscqzuOb@PgxU>Il@s)iO$|i zc%KsLN7hee$_^MqSy*>&Z24E$ z4i$5!zB80i53Uro<6ZYEHR&G2&686bBrjDmq?omxBCZ!)kbHNhd6rtJbC^=!8ihN0 zd{!_7bAUA2nzbMN#v#W}fQ6?fp)rfWG^RRb2d0EPcQn=i?2CK&u;V#*N39LPy3h?R zRTsDZCYF+Idu;jYse8X^%U&+BJw8e?-6nbX`Ke^>96xergFETkcRFUi?m&+1N%<(` zJy&g$2VM^3RxV2pr^Ye}fmYE9ZGjua9Z~4SBRPkm8(tk~sXDVVM*Ru)!rvupY8v7*tcvgy}Gr5ViXOZY->x{GhmVWq3!&YUp zZeN!_v{I$?6s{r(<EcU%G8FV zhvFq`)X`7H1_hnth&vBD%H$MQtqpbZ6>?BR0;S$Rd>qRj`*grSpf6ot{ZqU3YR5~o zax=$hQDs8^#mO@r3IUu%7|9m%P-Y?i3l#QH~1)}DIeGNI<~%i!ps5N9>({%_NJ|~ z`{g%{HnT&PaG!D$zXri?>r^)v6uoIJ4~5dx`#+b622A$h-Y06KC*b!hUG;y*_l5Bt zgN>`2Eo5MuJfS;F^rpOT$bb57?4Y^*sgpILct+%e#X!`0tWlC;oaJ z?GuE1Y|60RlsF#vU1%343JFUjCHU1r^w7wIuY|Da3%fdLtObY&xybzcQQpW5Jj?np z!;wAe{Gty9p`C^3%w@V8SJ#vE21!G6!Y35p_?nY%%g(F(MDYME#AMO$11K1Qr ztLAh}i63vdIq%tekuZPgF31SP!0OZ!Y_UJ(%;6hHD3Fk#sa; zVX>0$@%jX(frv&SKb-L};>gE$kBSE?$K@aLU_JjzsMsQ@56{ebox0?AgQF&5^-fi3 zgs&Zm>_jlC*k!Y^$}5oS1ub!0d)&iKb)^&Kv~3$3q0nfmcM$%P&CL;UAxtC6&7R%_ z$n)P)Eq3C!$L_oHi6*un2W7k*mA-=Vw0ou(FGBk@3qrDE(aKEku)&DbqihnU^+jq) z6Sk$yQmk3P01Uk4jYBMxOlNZM8{BM#vXjDx;mGyhy+$fLlSW8BXU3a!ws{@rY3iO7 z!`+v)H?w2P-S8X>6`#jYX50Qz9wHp(X!@pHS+PP2s%zxwX|RE4SIquLYFGJwPa)YF6m{4+?uu6AY6h0MwtU;$ng!V(j8L7j zqr`+a*hd_jQtE^W4T!1HdeS752xQNPH7+kwqoaO=Noj7(dDKR)tAwviDNYDn9O}#{ z)MJo;SCNu_*DqX7k#u3ntIU=311?12{wIZo?;Pz>IIRwFYpgpu!=uDJ(-f)*t?-DJ zswYQ3UJU9EYcYJPc%CusW~F^GlwLy*sRPBxFjfpd5q9`Rgo@N8tf6&7%Jz+d-CmjY zw;Rp|PYy|=!_H8=cEj$Lb;0#7qWp)1732$zWkitB+X}mV{bbt!?-ti%eN~d5H%cKxIXn~tGh(IY%nTVR zlsbXOs_bZ;$Lf+y*?RkY0hrFX@Y>4zRJ>^TUPHR7Z?YU-t zxKrip<9-}y(CGndjcYZ^!0A0g(?7OAaSFdzt`JoYs~c;Ibs_NDtLHHeB@q8M*a`Wfe22?wBn$O9G#aqTpr19^K zvTMm3PLWqN;g#Lvr$y+8-jFjaEZwANV3lW89A%~KGUJ}fEt=G*pcgu&Nfe2Izu<(g z(eu9fzVdN!mT3Ll z-TiZrl2UC*5qNuD-(zWBeSCWyPT|z_T%#&`6!xTHDf5XU60)rBv@GUjNfa~*hOo@5 zg$J*_ACB~HFdZQ;EMzm_cd_7Wtdf3v-ixp;!(LU?QBRxVgA{tr>8J1E+-AYT>Veft z##mmoVtpn3(eAY_hL_+w3<@NhugW1yqXzEq^>Ni6tj4dKKMy<-@u`yRB!^TlR)gzF zer(mMscEQMKUvB(-HcVx=uVHS;XVONUvV&-5tgHva4#We4=qGc^QnL>?s`s?w2&or zmOlzxq`XNMRy+dQK{Nz}z+0_3<5!Mz_pd#Y!#b43p2=t+EjURnI%%NnsTO$pQ)v{Y zmF=8zT;0yaYZfAGr~bzoAr#+PfG2-a@nao(EBVPAvXQ z{D?~FcC`L164`PUPUt6%0DkX)8`4`7cd zi|itAN+U%ayN+|FpVQ2E@t&0j+%tIa=*ON*Yy}0nm4vsQMV-PZ2XeLyUuCec>>w)F zC$D>tM#E5Em^uV8$2!w&w>??vj<;b?v&=t!SFs*ilZX)@Hg27Wk>CfsJ+3N#sB=S} zs8Y6vWX$G%V9J@sK&y^t?yCr?`VreI1>vN#qKCV^6bE%KhuFC9Y>u%h5od|r?jE?LqzAc$zEzwF zDbN?D0lZ#rGL^f2hw+1BZJLgSEeV@#j_t~3jgb&a@UDm;a`H3e{N!Fg<3N&!L1P8Q z(o-eouQ!BN1GlNwS!tN>>Fs)4i)&WVZhx75<*?l48WDGdTad#4wY2DlOVJ*&$RukA z?|ff?no6Awl|)Xm0RcLFFs;%PL-rOg(OczP5T6%_8f`o?aGxeIl2-ZIH(!lVl{aOWgz@JAII}7bUhk&cu=lNx2nv=D zsj0o&G?S{1&zi~6MMyHF@$0)HWV^9#3(P9O$Y8oL5X1YNWTTNo_<)&~DqSB+7g5`I z%>PY{h3=0yUGGfJJjJ;}JGq1E4PUGE6BFpPZ+5Qj>o03Gu`%WEW9%O*kZj~|Ta|PU zLL1&F_tpu>BJgXcO;kvi<6vYDIIn2#H@;1LX(BiHAgZ+aN=Bh2{rGZgea3gD7Qusc zM{cT9K2Y>c|6s7M46>1oxO+CXNrKq1PWjTyVAWdXK?@xD=TO!XxS3-QN)%Fql{Eri zCi-X1s8)YjOTaO~Y$GIM`ScdjB5g!Uj%(PP&*}L(mY~HfIrI*70t^A-N0E#piC41x z4edpkCFsQsJvXC#`r09F%Pbbp7gfZJz6O;7Zz=FJqjGYJ>sahlsR+^#Fs^#~xIVLO z$F@f~Yve;&vte@Id27Y7W<0k0oOUe!yiefTT1zDEy~Q|8Cz9uA z`Y^c@Sft1Yqi+yl~sQ-)c%k?|Zx);ehB0MYpA z7Fz!4G6U4&)frm2gp)66&#tT>rBATH&B6hTmh@FkYQl9?*#7c#ld5+Pt%uhv=`*7r z?5Og~4Tw{r3Y2fWbu}+x$87d*bzi?Z z#IVOMkVrJOcJf=KKxFBB}At?bY^YLzsBWw&Y$b zVs3*KZks2A9oZ8lx@@`0&F+Vm@eBt+mkmuffnXa zT>(|hvx~4$x%)0Gt1jpQ-nq+=oO}-pLkvB#0#BG}`0@+K2b&ikOpJgKN)<$aa#}uKzDh`M zOnWnky<8h!6qzFXBXA;B8?vJd_LB~2K!8vEYl#YP@ApAA?Xur3&_LmM87kpN~1&wtN(mreNwoC`cWIpWW8-Z9S?hDX6WZ@_yuIPWJr= zN78!advV@IS+1u-se|}+*`5*Cmf;L-=Onnkz0KG0C)J-VWs+c`n2Qr4-KK)wF0f=a z`zszTcMq;a7vdA9ls+^m^w~8Q!YDOO{j?c=&K!rj1?z+Cm}U3SmjNe< zwIioV#ch*rs5Q&RPW59hQ|9leHm+nUT5*h@2DrOjHBd#;4_+MM3hSr6UWS&d3O;?0 z@Y(X{LARn8G;6S>`H4YG0L3^I`*;OeZY_fllfVw)!IfT714I)`q;4cRP2A$&|bBI&Nidy?-Mxc%-WIM4PjOvg^hL*tL1Rq~&_$`5PmIkENfjdJOJ(XoMeuu=5m zsr$&ACo>jrXPFs?ix2k#(NNeW7RU3&UnPF0Yg$^*@t4RVDzom+$ciit<(pP@UQEwV|^t(7o4G=qKyu0W4~iUxFo~-d|3Ph zE3^Kvmu9n?=0mKKI33@JU6lL#fE2X{$!ey)h!f+X%{sYF9<-=I(vPtHa+%n!@2!ZV zw_J^4Da|VTx1{F`_x3bPWrvZWz(iAF(eR_vkF=}$wtAj?ehb{HX@XAfOs>VIgnTGk%M0#38NO;@Rk6sGu*V7z*b}4F@kkCyLax^onK&vVD zHkV{I2sWm_mMcRV#UdQJju-cpBT`+cm6anpZ z`+2S9$k-O2)pNA5ZZ5u!KDQ3G2kwWpO%N1_EzfDeKH!mjxpfv%sXFJj@VTtL9j7zp z4I(UD&4ohZqiO0SynK64eJ?pAyTP43S!8l;2SnTAtL*IzqALd`FoK7Rqwk@=S5waVa3X0ZsSqDOX-$jlg|4CIRP@}P zR9ED6EKPO6IkG!VJZUStC^2xeMwAZQU3oOAZSAeq%IJU?H6|B%t6>aqvj!`XyOEhw zOfoMfIBbGUQY(>gCIT{9XJx}Fu@8AG2UlT-bcJngFQ((PEYY1b+RUBL8U+P{<9?bQ zmc^iah4_w5f(GI^G`8`spm^fB_4}o#W2qlJc=KgTDE0eRJ{mJE)md>9c4`!%dL_2) z$Uljqi(D)f92gBk)XXy}8I%8NQ}zJm%J}M!0+uK8+m9Fi*}pT|>dl(3po`RvAVx2cWSOxx&yX7zfy57c>LIOyXhi~>X6@Qqi1)Ra6R&jS5T+Ks0XcEH ze7$m~KI~iaQ1S|92KqZ_wVB5@)F%?uJh51mjx=PNUsa$${E!fU43*mSsR@l7{?9K~ImucEpl@S7WTK$ITchtWt6tD1}E9jnD2#CL@ zq*<#V*~6JFzMl7xK2!<1QTe7iOrE6v0*5LR`9?J)sDY=&s5$5@cVMVRc#Qt+i!;6t z<@MYRhg!KCwc1OWeoT7SUdjdd<$c@ijEir3AAfr~ci-go2HnnO@eOsF0F3vrie1yU zhr~*O8EE4#5#a28^bo*V8@%2iK~nKYW>gU$L&!~ZBgyFAd>~T%|;l$jgBeN@bKYE~O;>YGh$J-e)xRI3J(v>ZY%Vqvr5k z6Lo$keSU85Ofyb#(|!I`?~v?RT~vVioy9?I;YFUKL4;baBj zdU#?t*2)5c2^kkbtkpMdtHd%Vl4LxVH?OJfR@#~lo2C!eOBi3(nZl?w-&~eP66=^B z-50G|HROluf7Kzolm_3#c?kc22Y%MnpyD*hpP*v&`XM7-oxy{9^w7{lr+%z!nJY%Q z*}IzTLhKGjsB*8<@t(d@@p+-+ZNUFB2I;hrnR03;rsPu;8#(nu$42+*r>+nXb@tGf zZIE5-Gf7;zQ(f&HS6OKj5Wxln{Sso%k_1h9Rxjk`-Kod!&q=P+7k6*R@8>r=51MP3 zi|RvuylTH$$lYAm)*N(XN_T?A{OT)I`UDSJS^c#aS4GAA@TiA>e@%ZyMYEbRZobzO zuj6LSITw+8o@V7C`qs&OXGHz@I`FEF&!Y0##>#Ly&k8pg!m~T=LU3E#Q>45H6>&Ph z-cM2pdcJld&%>xh#c3F2aExj>$~lHI$*uHbn@uyms1;fMT%uKLQPG8%Ka!~OzUbmN zn1i6bFD@6o$h0_PsVh<5{amRENzjE2LQ>(hFAY5}97or9Yo62gvQd4SL)g@#tzo4e zUg98Ul+Uge&NgidgeY(AJ1fmpZLUE0V5#hFGs^TJDrf>v#bs2t!tW4G&5G`^L9O45 z_cPEFMuS$HB$dfOw%6E@LWhGcjq#(sK3pF|_hAJY81x>GN~EySH=fB{cj1ZTpqVY>1Y4QQ z)A$*;cGq3KHnX6^s6U3O-j2Yx?ECF8lEgRlyUs66AyzhBoU z39E`cFpRZu`MIu0AeiTYr{4FNjF&u>355yUEjX}Cxg4e2BcC6fz4U`1h5U@novJY} zV{i_I=DHaRGurVYQHrSfSgjy)&lk%H9Rt8LjiUlHH!z{IPa?ZZU4Gq=e=u@#y+O+7bN3piDs z9&8(|cS;|=I8POEkmd~-yqv&4RE%#lEm>!`LgLV?r1~;yBy9Yu+))^! zI179?0oKpgjIrG8C{AYIzHmUO6JP)@80G)xS1NV@rF@W?f?{8{RKupOWL=Ddfv?M~ zDpeOi3Gy69i+#xK-(=CJo|XQR#5$l5nx#uE0C#H=wN!Ux1_A=DLiiOK`;%u481BtM zd?+f9&8n@Syq`AB;?13id=yv@zuz2Ub8_-IKId$Z)UlQoz6+ZkJ1YOG>V;Xt&iSjS zO7LtgO8dbhtjtUPTxZLSIzQI;CEnmtc|V}PXbV=MTC<^Q&LfyDhe#jj(0hW4aCXMd ze5!X)=5zKXZgo-Q>bV$YCX)2jLyIY4D%VLH*F6NR8nf`M?2py+pmVQ z)|YigTr%;BV?Tl{c*owwF?g&UFFk01RhJqyY$rP9lVMGscCDE?DNds4l#@O}$RmGU z#bK+{PO>sEWHldQECe>2qT#G887xUD&9Fa7K4x??{~!OptL;=*7}E157^ za?EtL*~L=D=UG9uk=S14GFKMOP~)W~J6h8YR8mu#pJ3n}^}O8hVjU5YUrmz*V$Ye3 zwmS|ey+DkxgSh7tWKMi=$^?~x_x2u(_sUrGYo)7#H)kbCUiglp5R z*|{{&aS_j>9J@C5X`_3ATUtT8Veu9@j?o$AP|L!0uR7?Tv( z9b@|Eg>dM@VEePK$t08TM}K8TNx}Gf?^Es9OyY2dlbis9(xaHvDgn&|+Cbqn&xLtu zV}e=H${@UOPL*x`HPeUF`^Uw=f6i4Kkmnm;CymsKH+lQxtJ9JK!8tJ&ZtpXitmuK@ zT>m)@$DYcuXirTN_`TX)iFV;3I8}(#=Jt$QV``))4)NIDF}nT1N%(Me$j`rpeN|7( zH#PBno@PVN19N+bVbx!_#u&5MhXGy*S?xK^yKomH7l zJ8kXB31$wi^N1uZkHs4f7%PFVo2C7FUk``^i5vvTQOu<>RtDp?A4WfcPu!$xi5kvR zQ798-pJFV=*&E7$S7&gKsX4RPl%IL$)I_mhIDG8ckWdKg5$+0?_C9&}9$T`kxy9+s zn3m1nQ$?>!X+i~}dm?=$XeMmmUcjQm>CK8@A|=dpUcYfxX1joD*<88!Akn(^HMB`2 zPYhDbl%5=SC53%A*K4V1MAjr)s{AsnnT=J4dJbcgt1_OBuF^BTG5C92KXQLFqV~u& z;WvJ7zktI;dtFVz>CTQA%&w9g+;+E|9t zXqh~pgm)!H@yO)Mbf?^~IigDll_Shys>{i1|IXMTQ9V#aZ(c-?nj=)%KEGVrme2S@E;=;88vG+@3YG+3@P^=~`l zZQ<)0!fcn0`H{4)i+^yV6VXH|IC@xu#}tI5)}bM&WZoWEq44Tnzu6wX!){H&cP)s> zS{pwcH2jHV%m%TT;FEytPjOS}vRBMPpKzHTh#InndKGuqp_X^&uUL-HKg9&Z%(s}S|Kezvr4 zz}gQpC03`bXBL<~Z`lSX;V-zVw;t35N8h|{5@*(cp}GG#9f6WkNh14eNLe5&TqnLR zWkzsHVJ>%?07D6rDl<{hkX!&$=V_1d@H}EmVit(Qq#lGvdO5?*2ZiN2?%J_p^kr8IC+b-R_39A{cH(A7y11{Ve!*jP zNh*TaK*G7xHj^XXd=qlyA#K(d2`ENge)`3^24XCFds!p7m7n4EP>0b6j%yKuIyxUK zOKqYfyl<9OBhzclfasD#nO*Q19?Tl=3a4*@V2>?K%oC&?)4n`Ji5MmvHh-o$Xry%9}HqVm$GDQgJVot(>LA>r?mOG)^Pc z^%Bi#+cBfZ;Z6n(jRoQRQxP1k#(VUsS6x|)#o4vW(qgVHOxUkhU$G^>QV7;*u9_xy z=@K1$g9G#;+L3s-j<`h!@|ba7^Ar+0C1LR^>>Zc|6pN&RUTe`p9JF#hLYe`RhnP$q zJ8+UUW$DsQLbNZqi?dv8om)fROMaH#KB4o9A6Q%9?tZ^GvoWIZEj&dg@Dj^XLi*za z2*3KkX$mw;YLk#QKB-Z&MWoh|25WZWoCJ8 zsM0^n7Z>9r`}7Z-7Q)zTiFe0Ag3olg=W%v5$9ri?2dP)O5ouF6m!%J9mQOK zc(d8NsT@cj*u>NkZhVy2_{9E+bM#XQk>;L%Qy*aqRnMxLCT}wWhOtJp)2G4?uSM7; zGV*}&2NA8Z>~3-0&&_K?c=huhFBdWinq9D0ZVsHjCp1uIrY(MQ?knX>^YTNth?PgO z%#m}n#EI1o3`_X+0qYJc>2zy{vnn`xbMJ>LJ@IhA$rfzI{^TXULA>#-*Vz7X6 zjw<8OpQD$i;p(PlW@EBa@yAYvB`ASh8|hSRu6DTgReHOKXo@8D%7kt0tR#p~w6t}E^BIim5FJmZ z+FU**q8dC*5;K8*gT5%$4wJfwaG0yj=wmtiaTF2iy);MpagbV#lJe^TnyF`K3g4*K zF0@PMeweW^(JD724JCY)&cf(gt(p&Z_vYJ$B7AgyuYf0Tr>Sd}$6>j~>irW|`~0jx zq_b3Ut-q?6Fi6f2BNdwcWzQ`_>CZv6Td`>nF`}Qmnch`rDNr=?)>^?K0cr4}P_Q&tp z(g-wKs0;}%@DwDAUBq9sN~^Gb%T-3S(Nu0L>oKU;RL4&k@81e|3@xa$9m?%eZDe&L zuov{m=o#!IF=#{kNv%Xpxnv&EB7Ae?%mucsI=qqi$#SOHC<3H)MttgzkKR`=7XFBC zMPSzwxT5QwBt#gyihr_fZ9$T7X@)>T7mq_41DjK<&fNRLM}U5_ZIAl1`(WQkZ^A~3 zae1f_IGQV+w|>#FPMjVrEh6%!mEk=dTs_Om(sgJo#zjYnKhh==8*y!f6mA5!WERiq zBHXJBs4L%-uf5pimmYW)+rkiACK+FCz##CD0r9+oa4X{xj!v(?qkkyJQs?EM-PqhE z`Y1Ee+xk<63`NSk@lrgyY>|kDYW4|@cQk?WX>0|IUH0~0G>H?694((()W9!@@0b!C zrh8i(&#W6#yQ(&{x43n1G_n*&nRiK$6%yz)+6P2u+zdfEX38qN)X`ruu-G^59Vkzy ze4p~%eM)=)rIE=TGJ?@kmII|ThwH#$689LbEOI8uLNw$?N%`BcOcFn&usRJ?y1rOk zD?{}A#khF8DJ0~tnsd9}zWPmaH7Dt7C|D&Q6W#swTe<>{T^V{!vkSYVw7r2hJQ%Md zEo#F1?+QzF+Vw%K5aKCrP&j>3smm9ZV@vDT@S$}49wNu14qFO4K!6vHDX+`WRpmiE zrYhl5`P^ksnlmUi(@i`*|J8cVeA%(mccf#qkv4+1QR-=2Ri>afjPQExhH1v6JARGr zU0nL?g=kF8;~s}gzK5uoyKTz;>t*?rPhLxZnP%%VRSHY}P$?!rEYggaM`0-7i(rzN3NZwrRJRte0jiWD!!N9 ztshVxD=OGd&w9>pIm@0nSBrEM@nJnnsY14-~DGzD44qU(VJ{Oe4F z<&SVA91)5UVaaQ0yO9-A12isXvQl+$JULLC7w5H9{%w=NTuKm6)do$oY8dK>aSACB zq?>XUbEZk7dXIuX7E*UnJ%h66lX0FB4HHL-Sf31NqaLsZ0T1^cfH9&E}76=mmpCm<#ccW^B38|z9VT(@kL()n zTd=jMz4zX{-}`t@?46BgOzcj8(xF2@)w-bu2)l9-AAnMmWnHz%>`stbD zd7olI>TTe)*_KuYwkZ-S1d~3C3N{;=tAa{*+m_a4UW9&prMZ1vEfq(OHL!^i4XMFX zQc8c+F}8&@#Rr>f8@s+^-O1(9pWhUUi7)ICr*vhafE(?xU-MMGINg|RTzwF^A^$Nx zG^OdNL90mo_9%lzc<3uBj+)cM{YOvu6`9JcJ+i-kkSXZy+vwFc8B@tvd;XGnf1Stc zhiUdVd@p4D@Wj;d2PLGtKgzIY&Zn5%gr=-uNvYm%V7JvO1`?XGzs+g;)M^l) zvftQ)$SQTLj<~Yg_ObyHv06k;9i7ogR`0TyDnnV~kX9(xL8Af|ia3i&PXe}tf#KoM z4VrG7H-YDcn5D!gdyciaue(ul=00GpKPhw2|441Fl#&RE`{Ss2a1J#$Xgw!Y3pY}V zLxWnx#2o&Ur0DSEtPcJFtwx8@-rIsV;TERTOHrsMs9R1P(~hG^eVDWXt(r8&nP`x% zzD!uIA`CMF{LgTzbA6pd(%EVwsi&}%UiRVFyw$*@v4;riX0e0$Oiq$X*bnqEbOfZ#c|v9kkifkIf@xSAUS z>75ID9Rean9RheYCGhi)>z@En{0A2Lhva{jg97TLbaphb0+`y)RzK?m-V6L6*Kcb; zy?g{>)&!F09xY4on! zl*Ye!gvO30pbU6{d}J3#YtmnNZg?kWLu(*k>g4Qn+aaJ#nt`hk8<2w6U7J4(pizNl zO95Gs!0UgI_*H!8H|`DaPC5tVrP?*(t`K75P)Bh z3+|l}m5>lH=DX2DfD)>`ffM*LWv~*ENS&O2#u~^%0R0OS_cQs26O=$xz`g)4Sb#vC z3m`cH{^g^;s8#I zzw_ho`tWys{522$u8+Us@V{k!1kVG%*Q3Av@V~Ji{tM>>;HdX=(fqq^{OYH_+k2Szvrf3^Wg9L z@GA~~*N0zm0Dk{nAO9Qo<$r5_{rx=t_wNS3=i|RMj{Xbx6aL!&weJ1h2Y$r?9Cm-t z$^SSf|M~gq@BO#`568#feemx-_pzs3Q&KEU(*%>xn`pqw!X$VdZ(eTT|{JpMm0B>0RQ-W@y!pS?AP@N(z@&G| zEbrt&zas&|096G`Z@su?TG*>!LR(!dJg^>LoxxF6rful?zR=I?;AjO^dZRs zOn67W6vz_+blXNS9#nU*9gx4H|5Nt1F3^7EAAC9h-{k`j_5Bkr05DkBt<2p#Xs-$& z&_6H__6r!_yY;&P81xt9gEs!qhtvhi?&^b&@7>k~>ii)OvGUJlkl@4v^>4?-AM%ip z0Pk*$|7h<|{X2ZfRY0BspxgF<@^|}R0Km6(fihrQ@A|6*V9*DU2a*p!pgb^Ee_~P~ zy(UJ*noTj;JfktqrLw_ye@v*`&|d5{~!8)j_27w0Rl1DAE1mWKx6>@ZW{!!Hs6g6 z1j8Q~^zBZ2e%b`}L0g~=&O3at4siVe>9)Q<_5Z}Wfb3m={^b8FO!`~@)}MbR|F8Ie z{rTtq{xe>BK)iu|*YyL^+w~2U0pkyjh1+ojV!1ysI0wM>`L?fkf&A^f2g@G+fkC@> z`F~=tufYA}w$4BKAim{+_W#7Bzsqj@`IG-Yi$QfFu$XZ8Qd|3A&2|2zL~WBMom zU*X&M{4d5k0z40Zdm^Y0tly8p^PLzFa&V2q0=A-jAO(E@^58hb0>>J-w)`G*G{tu? zaP~rJ128>6;64DXso3E8lMf(bfB+o~&<;01V7&m{s|He_zMp#@U>6#E?jGcU`rtTq z2k3WQKYaxE#@kr^SNi|Y_<^?m9sNJ-p@4pZdpzh1xPQ0;1g`Di90GaZ`4!v;!8}N& z5Rev%Kq?Q=?S2C4{$2xq+5zz_KzIEd`vYtJfgAq7V87hahr|Hz-FXl0jd%Dz_u~I2 z47TYm|KG*ne*52P@89+3|80HntONEx*tbBxqw@gg4zNy{Ulm7kYWFfAx8fb ze0MDC1AK67g7!fI>$_v`=a{^Ug8}~ScmT`)7}pSsf0X^fhrB&sYyonl00DJEA_D1c zIq1UzK(~GXZH5Hv1LyXwAKZ8HpghRG<$)MHciq{GpxS@qTUi|dgE0l?5m@#Jpu75i z`22I-xyz@AfK(a!t#@k!v;&?e@5n(S|1b`24JknXEB0>vxoywCs{c{_76}#Q$V`)Qo_* z-L6GKz`x7__h3vXXCpfx1usZ|fX`SEhAzg=20*H5WAZZvvJhl Date: Thu, 13 Oct 2022 12:26:28 +0000 Subject: [PATCH 36/41] Bump geekyeggo/delete-artifact from 1 to 2 Bumps [geekyeggo/delete-artifact](https://github.com/geekyeggo/delete-artifact) from 1 to 2. - [Release notes](https://github.com/geekyeggo/delete-artifact/releases) - [Commits](https://github.com/geekyeggo/delete-artifact/compare/v1...v2) --- updated-dependencies: - dependency-name: geekyeggo/delete-artifact dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] --- .github/workflows/sync-labels.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/sync-labels.yml b/.github/workflows/sync-labels.yml index 986bda6..10abaea 100644 --- a/.github/workflows/sync-labels.yml +++ b/.github/workflows/sync-labels.yml @@ -114,7 +114,7 @@ jobs: path: ${{ env.CONFIGURATIONS_FOLDER }} - name: Remove unneeded artifact - uses: geekyeggo/delete-artifact@v1 + uses: geekyeggo/delete-artifact@v2 with: name: ${{ env.CONFIGURATIONS_ARTIFACT }} From c254dbadc8d661c31c02993970b67b057f1e0051 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Mon, 24 Oct 2022 12:31:53 +0000 Subject: [PATCH 37/41] Bump carlosperate/download-file-action from 1 to 2 Bumps [carlosperate/download-file-action](https://github.com/carlosperate/download-file-action) from 1 to 2. - [Release notes](https://github.com/carlosperate/download-file-action/releases) - [Commits](https://github.com/carlosperate/download-file-action/compare/v1...v2) --- updated-dependencies: - dependency-name: carlosperate/download-file-action dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] --- .github/workflows/sync-labels.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/sync-labels.yml b/.github/workflows/sync-labels.yml index 10abaea..94938f3 100644 --- a/.github/workflows/sync-labels.yml +++ b/.github/workflows/sync-labels.yml @@ -31,7 +31,7 @@ jobs: - name: Download JSON schema for labels configuration file id: download-schema - uses: carlosperate/download-file-action@v1 + uses: carlosperate/download-file-action@v2 with: file-url: https://raw.githubusercontent.com/arduino/tooling-project-assets/main/workflow-templates/assets/sync-labels/arduino-tooling-gh-label-configuration-schema.json location: ${{ runner.temp }}/label-configuration-schema @@ -65,7 +65,7 @@ jobs: steps: - name: Download - uses: carlosperate/download-file-action@v1 + uses: carlosperate/download-file-action@v2 with: file-url: https://raw.githubusercontent.com/arduino/tooling-project-assets/main/workflow-templates/assets/sync-labels/${{ matrix.filename }} From 1bc38c5faf41e1098e8bf5bad19093fa42d817ec Mon Sep 17 00:00:00 2001 From: Naveen Date: Wed, 22 Feb 2023 13:00:00 +0900 Subject: [PATCH 38/41] Fix: SmartServoClass::getPosition return value This PR fixes the issue #97. --- src/lib/motors/SmartServo.cpp | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/src/lib/motors/SmartServo.cpp b/src/lib/motors/SmartServo.cpp index 84efd23..1d5f031 100644 --- a/src/lib/motors/SmartServo.cpp +++ b/src/lib/motors/SmartServo.cpp @@ -235,7 +235,18 @@ float SmartServoClass::getPosition(uint8_t const id) return -1.0f; mbed::ScopedLock lock(_mtx); - return positionToAngle(readWordCmd(id, REG(SmartServoRegister::POSITION_H))); + int position = readWordCmd(id, REG(SmartServoRegister::POSITION_H)); + + // retry one more time + if (position < 0) { + delay(1); + position = readWordCmd(id, REG(SmartServoRegister::POSITION_H)); + } + + if (position < 0) + return -1.0f; + + return positionToAngle(position); } void SmartServoClass::center(uint8_t const id, uint16_t const position) From 1217b070f1c67a077dcc000ddf64b9c0d4688d00 Mon Sep 17 00:00:00 2001 From: Naveen Date: Wed, 22 Feb 2023 14:51:31 +0900 Subject: [PATCH 39/41] Update src/lib/motors/SmartServo.cpp Co-authored-by: Alexander Entinger --- src/lib/motors/SmartServo.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/lib/motors/SmartServo.cpp b/src/lib/motors/SmartServo.cpp index 1d5f031..c3cd566 100644 --- a/src/lib/motors/SmartServo.cpp +++ b/src/lib/motors/SmartServo.cpp @@ -235,7 +235,7 @@ float SmartServoClass::getPosition(uint8_t const id) return -1.0f; mbed::ScopedLock lock(_mtx); - int position = readWordCmd(id, REG(SmartServoRegister::POSITION_H)); + int const position = readWordCmd(id, REG(SmartServoRegister::POSITION_H)); // retry one more time if (position < 0) { From e1e6612534cc531cb7e03a7684b0826c942f8fdb Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Wed, 22 Feb 2023 07:08:46 +0100 Subject: [PATCH 40/41] Revert "Update src/lib/motors/SmartServo.cpp" - previous commit causes build error a couple of lines down - my bad. This reverts commit 1217b070f1c67a077dcc000ddf64b9c0d4688d00. --- src/lib/motors/SmartServo.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/lib/motors/SmartServo.cpp b/src/lib/motors/SmartServo.cpp index c3cd566..1d5f031 100644 --- a/src/lib/motors/SmartServo.cpp +++ b/src/lib/motors/SmartServo.cpp @@ -235,7 +235,7 @@ float SmartServoClass::getPosition(uint8_t const id) return -1.0f; mbed::ScopedLock lock(_mtx); - int const position = readWordCmd(id, REG(SmartServoRegister::POSITION_H)); + int position = readWordCmd(id, REG(SmartServoRegister::POSITION_H)); // retry one more time if (position < 0) { From 978b76af7ec608fdc9df1caeeb4580256a836de3 Mon Sep 17 00:00:00 2001 From: Martino Facchin Date: Wed, 31 May 2023 10:28:18 +0200 Subject: [PATCH 41/41] Release v1.3.3 --- library.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/library.properties b/library.properties index b33976a..52628ed 100644 --- a/library.properties +++ b/library.properties @@ -1,5 +1,5 @@ name=Arduino_Braccio_plusplus -version=1.3.2 +version=1.3.3 author=Arduino maintainer=Arduino sentence=Board support library for the Arduino Braccio++ 6-DOF robot arm.