From e7467b56fda1eb2d6bdcaa44fddd7338175f24e8 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Sun, 1 May 2022 10:30:32 -1000 Subject: [PATCH 01/22] Motor bit number functions --- FluidNC/src/Kinematics/CoreXY.cpp | 4 ++-- FluidNC/src/Machine/Axes.cpp | 2 +- FluidNC/src/Machine/Axes.h | 4 ++++ FluidNC/src/Machine/Homing.cpp | 8 +++++--- FluidNC/src/Machine/LimitPin.cpp | 12 ++++-------- FluidNC/src/Machine/Motor.cpp | 2 +- FluidNC/src/ProcessSettings.cpp | 8 ++++---- FluidNC/src/Report.cpp | 7 ++++--- 8 files changed, 25 insertions(+), 22 deletions(-) diff --git a/FluidNC/src/Kinematics/CoreXY.cpp b/FluidNC/src/Kinematics/CoreXY.cpp index be85322d3..89ec1c198 100644 --- a/FluidNC/src/Kinematics/CoreXY.cpp +++ b/FluidNC/src/Kinematics/CoreXY.cpp @@ -171,8 +171,8 @@ namespace Kinematics { AxisMask axisMask = Machine::Homing::axis_mask_from_cycle(cycle); uint8_t count = 0; - for (int i = 0; i < 16; i++) { - if (bitnum_is_true(axisMask, i)) { + for (int axis = 0; axis < MAX_N_AXIS; axis++) { + if (bitnum_is_true(axisMask, axis)) { if (++count > 1) { // Error with any axis with more than one axis per cycle log_error("CoreXY cannot multi-axis home. Check homing cycle:" << cycle); // TODO: Set some Kinematics error or alarm diff --git a/FluidNC/src/Machine/Axes.cpp b/FluidNC/src/Machine/Axes.cpp index f405bceb9..a30399f5a 100644 --- a/FluidNC/src/Machine/Axes.cpp +++ b/FluidNC/src/Machine/Axes.cpp @@ -79,7 +79,7 @@ namespace Machine { for (size_t motor = 0; motor < Axis::MAX_MOTORS_PER_AXIS; motor++) { auto m = _axis[axis]->_motors[motor]; if (m && m->_driver->set_homing_mode(isHoming)) { - set_bitnum(motorsCanHome, motor * 16 + axis); + set_bitnum(motorsCanHome, motor_bit(axis, motor)); } } } diff --git a/FluidNC/src/Machine/Axes.h b/FluidNC/src/Machine/Axes.h index d4577782b..6341d80e9 100644 --- a/FluidNC/src/Machine/Axes.h +++ b/FluidNC/src/Machine/Axes.h @@ -33,6 +33,10 @@ namespace Machine { inline char axisName(int index) { return index < MAX_N_AXIS ? _names[index] : '?'; } // returns axis letter + static inline size_t motor_bit(size_t axis, size_t motor) { return motor ? axis + 16 : axis; } + static inline AxisMask motors_to_axes(MotorMask motors) { return (motors & 0xffff) | (motors >> 16); } + static inline MotorMask axes_to_motors(AxisMask axes) { return axes | (axes << 16); } + Pin _sharedStepperDisable; Pin _sharedStepperReset; diff --git a/FluidNC/src/Machine/Homing.cpp b/FluidNC/src/Machine/Homing.cpp index d7ba19dc8..1f983cf06 100644 --- a/FluidNC/src/Machine/Homing.cpp +++ b/FluidNC/src/Machine/Homing.cpp @@ -51,7 +51,7 @@ namespace Machine { AxisMask axesMask = 0; // Find the axis that will take the longest for (int axis = 0; axis < n_axis; axis++) { - if (bitnum_is_false(motors, axis) && bitnum_is_false(motors, axis + 16)) { + if (bitnum_is_false(motors, Machine::Axes::motor_bit(axis, 0)) && bitnum_is_false(motors, Machine::Axes::motor_bit(axis, 1))) { continue; } @@ -77,13 +77,15 @@ namespace Machine { travel = axisConfig->_maxTravel; } else { // see if which pull off we use // If both motors are running use the first pull off - if (bitnum_is_true(motors, axis) && bitnum_is_true(motors, axis + 16)) { + if (bitnum_is_true(motors, Axes::motor_bit(axis, 0)) && bitnum_is_true(motors, Axes::motor_bit(axis, 1))) { travel = axisConfig->_motors[0]->_pulloff; } else { if (customPulloff != 0) { travel = customPulloff; } else { - bitnum_is_true(motors, axis) ? travel = axisConfig->_motors[0]->_pulloff : travel = axisConfig->_motors[1]->_pulloff; + // If motor 0 is not running, use the pulloff for motor 1 + int motor = bitnum_is_false(motors, Axes::motor_bit(axis, 0)); + travel = axisConfig->_motors[motor]->_pulloff; } } } diff --git a/FluidNC/src/Machine/LimitPin.cpp b/FluidNC/src/Machine/LimitPin.cpp index 804b65baa..5128860e1 100644 --- a/FluidNC/src/Machine/LimitPin.cpp +++ b/FluidNC/src/Machine/LimitPin.cpp @@ -38,10 +38,9 @@ namespace Machine { } // Set a bitmap with bits to represent the axis and which motors are affected - // The bitmap looks like CBAZYXcbazyx where motor0 motors are in the lower bits - motor == 0 ? _bitmask = 1 : _bitmask = 1 << 16; - _bitmask <<= axis; // Shift the bits into position - _legend = String(" " + sDir + " Limit"); + // The bitmap looks like CBAZYX..cbazyx where motor0 motors are in the lower bits + _bitmask = 1 << Axes::motor_bit(axis, motor); + _legend = String(" " + sDir + " Limit"); } void IRAM_ATTR LimitPin::handleISR() { @@ -103,10 +102,7 @@ namespace Machine { // Make this switch act like an axis level switch. Both motors will report the same // This should be called from a higher level object, that has the logic to figure out // if this belongs to a dual motor, single switch axis - void LimitPin::makeDualMask() { - uint32_t both = ((_bitmask >> 16) | (_bitmask & 0xffff)); - _bitmask = (both << 16) | both; - } + void LimitPin::makeDualMask() { _bitmask = Axes::axes_to_motors(Axes::motors_to_axes(_bitmask)); } LimitPin::~LimitPin() { _pin.detachInterrupt(); } } diff --git a/FluidNC/src/Machine/Motor.cpp b/FluidNC/src/Machine/Motor.cpp index 5ca3ee21f..d43e98909 100644 --- a/FluidNC/src/Machine/Motor.cpp +++ b/FluidNC/src/Machine/Motor.cpp @@ -27,7 +27,7 @@ namespace Machine { void Motor::init() { if (strcmp(_driver->name(), "null_motor") != 0) { - set_bitnum(Machine::Axes::motorMask, _axis + 16 * _motorNum); + set_bitnum(Machine::Axes::motorMask, Machine::Axes::motor_bit(_axis, _motorNum)); } _driver->init(); diff --git a/FluidNC/src/ProcessSettings.cpp b/FluidNC/src/ProcessSettings.cpp index 5f38d3dae..258b99d76 100644 --- a/FluidNC/src/ProcessSettings.cpp +++ b/FluidNC/src/ProcessSettings.cpp @@ -357,12 +357,12 @@ static Error home_c(const char* value, WebUI::AuthenticationLevel auth_level, Ch } static void write_limit_set(uint32_t mask, Channel& out) { const char* motor0AxisName = "xyzabc"; - for (int i = 0; i < MAX_N_AXIS; i++) { - out << (bitnum_is_true(mask, i) ? char(motor0AxisName[i]) : ' '); + for (int axis = 0; axis < MAX_N_AXIS; axis++) { + out << (bitnum_is_true(mask, Machine::Axes::motor_bit(axis, 0)) ? char(motor0AxisName[axis]) : ' '); } const char* motor1AxisName = "XYZABC"; - for (int i = 0; i < MAX_N_AXIS; i++) { - out << (bitnum_is_true(mask, i + 16) ? char(motor1AxisName[i]) : ' '); + for (int axis = 0; axis < MAX_N_AXIS; axis++) { + out << (bitnum_is_true(mask, Machine::Axes::motor_bit(axis, 1)) ? char(motor1AxisName[axis]) : ' '); } } static Error show_limits(const char* value, WebUI::AuthenticationLevel auth_level, Channel& out) { diff --git a/FluidNC/src/Report.cpp b/FluidNC/src/Report.cpp index 655a2d840..4b5a76266 100644 --- a/FluidNC/src/Report.cpp +++ b/FluidNC/src/Report.cpp @@ -504,13 +504,14 @@ static void pinString(Print& channel) { MotorMask lim_pin_state = limits_get_state(); if (lim_pin_state) { auto n_axis = config->_axes->_numberAxis; - for (int i = 0; i < n_axis; i++) { - if (bitnum_is_true(lim_pin_state, i) || bitnum_is_true(lim_pin_state, i + 16)) { + for (size_t axis = 0; axis < n_axis; axis++) { + if (bitnum_is_true(lim_pin_state, Machine::Axes::motor_bit(axis, 0)) || + bitnum_is_true(lim_pin_state, Machine::Axes::motor_bit(axis, 1))) { if (prefixNeeded) { prefixNeeded = false; channel << "|Pn:"; } - channel << config->_axes->axisName(i); + channel << config->_axes->axisName(axis); } } } From 8c198dd403b445a373dc7f16306884432e7688c2 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Sun, 1 May 2022 16:59:35 -1000 Subject: [PATCH 02/22] Simplified homing cases --- FluidNC/src/Config.h | 5 ---- FluidNC/src/Machine/Homing.cpp | 49 ++++------------------------------ 2 files changed, 5 insertions(+), 49 deletions(-) diff --git a/FluidNC/src/Config.h b/FluidNC/src/Config.h index 84fccfed3..a9d1aaed3 100644 --- a/FluidNC/src/Config.h +++ b/FluidNC/src/Config.h @@ -57,11 +57,6 @@ const char* const DEFAULT_ADMIN_LOGIN = "admin"; const char* const DEFAULT_USER_LOGIN = "user"; #endif -// Number of homing cycles performed after when the machine initially jogs to limit switches. -// This help in preventing overshoot and should improve repeatability. This value should be one or -// greater. -static const uint8_t NHomingLocateCycle = 1; // Integer (1-128) - // Upon a successful probe cycle, this option provides immediately feedback of the probe coordinates // through an automatically generated message. If disabled, users can still access the last probe // coordinates through the '$#' print parameters command. diff --git a/FluidNC/src/Machine/Homing.cpp b/FluidNC/src/Machine/Homing.cpp index 1f983cf06..3e5152a92 100644 --- a/FluidNC/src/Machine/Homing.cpp +++ b/FluidNC/src/Machine/Homing.cpp @@ -191,31 +191,6 @@ namespace Machine { delay_ms(settling_ms); // Delay to allow transient dynamics to dissipate. } - // This homing mode is the POG style squaring - // For this you can only have switches defined at the axis level - bool Homing::squaredOneSwitch(MotorMask motors) { - AxisMask squaredAxes = motors & (motors >> 16); - if (squaredAxes == 0) { - // No axis has multiple motors - return false; - } - - auto axes = config->_axes; - auto n_axis = axes->_numberAxis; - for (int axis = 0; axis < n_axis; axis++) { - if (bitnum_is_false(squaredAxes, axis)) { - continue; - } - - if (axes->_axis[axis]->motorsWithSwitches() == 1) { - return true; - } - } - // If we get here, all of the squared axes in this cycle have separate - // limit switches. - return false; - } - // This homing mode never forces the machine out of square // This requires independent switches on each motor. bool Homing::squaredStressfree(MotorMask motors) { @@ -278,18 +253,12 @@ namespace Machine { MotorMask motors = config->_axes->set_homing_mode(axisMask, true); try { - if (squaredOneSwitch(motors)) { - //log_info("POG Squaring"); - run(motors, true, true); // Approach slowly - run(motors, false, false); // Pulloff - run(motors, true, false); // Approach slowly - run(motors, false, false); // Pulloff - } else if (squaredStressfree(motors)) { + run(motors, true, true); // Approach slowly + run(motors, false, false); // Pulloff + run(motors, true, false); // Approach slowly + run(motors, false, false); // Pulloff + if (squaredStressfree(motors)) { //log_info("Stress Free Squaring 0x" << String(motors, 16)); - run(motors, true, true); // Approach fast - run(motors, false, false); // Pulloff - run(motors, true, false); // Approach fast - run(motors, false, false); // Pulloff // TODO See if we need to do a nudge for asymmetric pulloffs. auto n_axis = config->_axes->_numberAxis; float pulloffOffset; @@ -306,14 +275,6 @@ namespace Machine { } } } - } else { - //log_info("Single Axis Homing"); - for (int i = 0; i < NHomingLocateCycle; i++) { - run(motors, true, true); // Approach fast - run(motors, false, false); // Pulloff - run(motors, true, false); // Approach slowly - run(motors, false, false); // Pulloff - } } } catch (ExecAlarm alarm) { rtAlarm = alarm; From baaf32c1b42ca7e09d81a5b894f6233294f3c809 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Sun, 1 May 2022 18:09:33 -1000 Subject: [PATCH 03/22] Stop stepping directly when limits are hit --- FluidNC/src/Machine/Axes.cpp | 28 +++++++++++++--------------- FluidNC/src/Machine/Axes.h | 7 ------- FluidNC/src/Machine/Homing.cpp | 22 +++++++++++++--------- FluidNC/src/Machine/Homing.h | 2 ++ FluidNC/src/Machine/Motor.h | 2 ++ 5 files changed, 30 insertions(+), 31 deletions(-) diff --git a/FluidNC/src/Machine/Axes.cpp b/FluidNC/src/Machine/Axes.cpp index a30399f5a..437ad988f 100644 --- a/FluidNC/src/Machine/Axes.cpp +++ b/FluidNC/src/Machine/Axes.cpp @@ -35,8 +35,6 @@ namespace Machine { _sharedStepperReset.report("Shared stepper reset"); } - unlock_all_motors(); - // certain motors need features to be turned on. Check them here for (size_t axis = X_AXIS; axis < _numberAxis; axis++) { auto a = _axis[axis]; @@ -69,7 +67,6 @@ namespace Machine { // Put the motors in the given axes into homing mode, returning a // mask of which motors can do homing. MotorMask Axes::set_homing_mode(AxisMask axisMask, bool isHoming) { - unlock_all_motors(); // On homing transitions, cancel all motor lockouts MotorMask motorsCanHome = 0; for (size_t axis = X_AXIS; axis < _numberAxis; axis++) { @@ -89,10 +86,6 @@ namespace Machine { return motorsCanHome; } - void Axes::unlock_all_motors() { _motorLockoutMask = 0; } - void Axes::lock_motors(MotorMask mask) { set_bits(_motorLockoutMask, mask); } - void Axes::unlock_motors(MotorMask mask) { clear_bits(_motorLockoutMask, mask); } - void IRAM_ATTR Axes::step(uint8_t step_mask, uint8_t dir_mask) { auto n_axis = _numberAxis; //log_info("motors_set_direction_pins:0x%02X", onMask); @@ -116,21 +109,26 @@ namespace Machine { config->_stepping->waitDirection(); } + auto limitedMotors = posLimitMask | negLimitMask; + bool isHomingApproach = Homing::_approach; + // Turn on step pulses for motors that are supposed to step now for (size_t axis = X_AXIS; axis < n_axis; axis++) { if (bitnum_is_true(step_mask, axis)) { + int stepIncrement = bitnum_is_true(dir_mask, axis) ? 1 : -1; + auto a = _axis[axis]; - if (bitnum_is_false(_motorLockoutMask, axis)) { + // Skip steps based on limit pins if: + // (Homing approach or axis hard limits) & limit pin is true + + for (size_t motor = 0; motor < Axis::MAX_MOTORS_PER_AXIS; motor++) { auto m = a->_motors[0]; if (m) { - m->_driver->step(); - } - } - if (bitnum_is_false(_motorLockoutMask, axis + 16)) { - auto m = a->_motors[1]; - if (m) { - m->_driver->step(); + if (!((isHomingApproach || m->_hardLimits) && bitnum_is_true(limitedMotors, motor_bit(axis, motor)))) { + m->_driver->step(); + m->_steps += stepIncrement; + } } } } diff --git a/FluidNC/src/Machine/Axes.h b/FluidNC/src/Machine/Axes.h index 6341d80e9..ec0a1ac96 100644 --- a/FluidNC/src/Machine/Axes.h +++ b/FluidNC/src/Machine/Axes.h @@ -15,10 +15,6 @@ namespace Machine { class Axes : public Configuration::Configurable { bool _switchedStepper = false; - // During homing, this is used to stop stepping on motors that have - // reached their limit switches, by clearing bits in the mask. - MotorMask _motorLockoutMask = 0; - public: static constexpr const char* _names = "XYZABC"; @@ -67,9 +63,6 @@ namespace Machine { // These are used during homing cycles. // The return value is a bitmask of axes that can home MotorMask set_homing_mode(AxisMask homing_mask, bool isHoming); - void unlock_all_motors(); - void lock_motors(MotorMask motor_mask); - void unlock_motors(MotorMask motor_mask); void set_disable(int axis, bool disable); void set_disable(bool disable); diff --git a/FluidNC/src/Machine/Homing.cpp b/FluidNC/src/Machine/Homing.cpp index 3e5152a92..1eaf7438e 100644 --- a/FluidNC/src/Machine/Homing.cpp +++ b/FluidNC/src/Machine/Homing.cpp @@ -34,6 +34,8 @@ namespace Machine { // Then we scale the travel distances for the other axes so they would complete // at the same time. + bool Homing::_approach = false; + const uint32_t MOTOR0 = 0xffff; const uint32_t MOTOR1 = 0xffff0000; @@ -141,18 +143,15 @@ namespace Machine { return; } - uint32_t settling_ms = plan_move(remainingMotors, approach, seek, customPulloff); + _approach = approach; - config->_axes->lock_motors(0xffffffff); - config->_axes->unlock_motors(remainingMotors); + uint32_t settling_ms = plan_move(remainingMotors, approach, seek, customPulloff); do { if (approach) { - // Check limit state. Lock out cycle axes when they change. - // XXX do we check only the switch in the direction of motion? + // As limit bits are set, remove the corresponding bits from remaingMotors. + // The stepping ISR code takes care of stopping the motors when limit bits are set MotorMask limitedMotors = Machine::Axes::posLimitMask | Machine::Axes::negLimitMask; - - config->_axes->lock_motors(limitedMotors); clear_bits(remainingMotors, limitedMotors); } @@ -189,6 +188,7 @@ namespace Machine { Stepper::reset(); // Immediately force kill steppers and reset step segment buffer. delay_ms(settling_ms); // Delay to allow transient dynamics to dissipate. + _approach = false; } // This homing mode never forces the machine out of square @@ -253,9 +253,13 @@ namespace Machine { MotorMask motors = config->_axes->set_homing_mode(axisMask, true); try { - run(motors, true, true); // Approach slowly + log_debug("Fast approach"); + run(motors, true, true); // Approach slowly + log_debug("Pulloff"); run(motors, false, false); // Pulloff - run(motors, true, false); // Approach slowly + log_debug("Slow approach"); + run(motors, true, false); // Approach slowly + log_debug("Pulloff"); run(motors, false, false); // Pulloff if (squaredStressfree(motors)) { //log_info("Stress Free Squaring 0x" << String(motors, 16)); diff --git a/FluidNC/src/Machine/Homing.h b/FluidNC/src/Machine/Homing.h index 23e4aca66..07ad73dd6 100644 --- a/FluidNC/src/Machine/Homing.h +++ b/FluidNC/src/Machine/Homing.h @@ -23,6 +23,8 @@ namespace Machine { static const int AllCycles = 0; // Must be zero. + static bool _approach; + static void run_cycles(AxisMask axisMask); static void run_one_cycle(AxisMask axisMask); diff --git a/FluidNC/src/Machine/Motor.h b/FluidNC/src/Machine/Motor.h index 7fc1fed69..342a8299f 100644 --- a/FluidNC/src/Machine/Motor.h +++ b/FluidNC/src/Machine/Motor.h @@ -35,6 +35,8 @@ namespace Machine { Pin _allPin; bool _hardLimits = false; + int32_t _steps = 0; + // Configuration system helpers: void group(Configuration::HandlerBase& handler) override; void afterParse() override; From 1ccd2fcd40239b724296374d8d3a9e1d3d54c58e Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Mon, 2 May 2022 14:57:31 -1000 Subject: [PATCH 04/22] Limit pin ISR quickly stops stepping --- FluidNC/src/Config.h | 2 - FluidNC/src/GCode.cpp | 2 +- FluidNC/src/Kinematics/CoreXY.cpp | 8 ++-- FluidNC/src/Machine/Axes.cpp | 16 ++------ FluidNC/src/Machine/Homing.cpp | 6 +-- FluidNC/src/Machine/Homing.h | 2 +- FluidNC/src/Machine/LimitPin.cpp | 7 ++-- FluidNC/src/Machine/LimitPin.h | 11 ++++- FluidNC/src/Machine/Motor.cpp | 17 ++++++-- FluidNC/src/Machine/Motor.h | 5 ++- FluidNC/src/Main.cpp | 15 ++----- FluidNC/src/MotionControl.cpp | 3 +- FluidNC/src/Motors/Dynamixel2.cpp | 6 +-- FluidNC/src/Motors/RcServo.cpp | 8 ++-- FluidNC/src/Motors/Solenoid.cpp | 2 +- FluidNC/src/Planner.cpp | 22 +++------- FluidNC/src/Planner.h | 9 ---- FluidNC/src/Protocol.cpp | 37 ----------------- FluidNC/src/Protocol.h | 9 ---- FluidNC/src/Serial.cpp | 14 +------ FluidNC/src/Serial.h | 4 -- FluidNC/src/Stepper.cpp | 68 +++---------------------------- FluidNC/src/Stepper.h | 10 ----- FluidNC/src/System.cpp | 31 +++++++++++++- FluidNC/src/System.h | 4 ++ 25 files changed, 101 insertions(+), 217 deletions(-) diff --git a/FluidNC/src/Config.h b/FluidNC/src/Config.h index a9d1aaed3..978fe20ca 100644 --- a/FluidNC/src/Config.h +++ b/FluidNC/src/Config.h @@ -215,5 +215,3 @@ const double PARKING_PULLOUT_INCREMENT = 5.0; // Spindle pull-out and plunge // INCLUDE_OLED_BASIC includes a driver for a modest sized OLED display // #define INCLUDE_OLED_BASIC - -// #define DEBUG_STEPPING diff --git a/FluidNC/src/GCode.cpp b/FluidNC/src/GCode.cpp index 7faf3b302..cfa5eec88 100644 --- a/FluidNC/src/GCode.cpp +++ b/FluidNC/src/GCode.cpp @@ -52,7 +52,7 @@ void gc_init() { // Sets g-code parser position in mm. Input in steps. Called by the system abort and hard // limit pull-off routines. void gc_sync_position() { - motor_steps_to_mpos(gc_state.position, motor_steps); + motor_steps_to_mpos(gc_state.position, get_motor_steps()); } static void gcode_comment_msg(char* comment) { diff --git a/FluidNC/src/Kinematics/CoreXY.cpp b/FluidNC/src/Kinematics/CoreXY.cpp index 89ec1c198..274c919e8 100644 --- a/FluidNC/src/Kinematics/CoreXY.cpp +++ b/FluidNC/src/Kinematics/CoreXY.cpp @@ -68,8 +68,8 @@ namespace Kinematics { // leave other axes unchanged for (int axis = X_AXIS; axis <= config->_axes->_numberAxis; axis++) { if (axis < Z_AXIS) { - motor_steps[axis] = 0.0; - target[axis] = 0.0; + set_motor_steps(axis, 0); + target[axis] = 0.0; } else { move_to[axis] = target[axis]; } @@ -235,13 +235,13 @@ namespace Kinematics { for (int axis = Z_AXIS; axis < n_axis; axis++) { if (bitnum_is_true(cycle_mask, axis)) { // set the Z motor position - motor_steps[axis] = mpos_to_steps(motors_mm[axis], axis); + set_motor_steps(axis, mpos_to_steps(motors_mm[axis], axis)); } } } else { // set all of them for (int axis = X_AXIS; axis < n_axis; axis++) { - motor_steps[axis] = mpos_to_steps(motors_mm[axis], axis); + set_motor_steps(axis, mpos_to_steps(motors_mm[axis], axis)); } } diff --git a/FluidNC/src/Machine/Axes.cpp b/FluidNC/src/Machine/Axes.cpp index 437ad988f..6991c1ee7 100644 --- a/FluidNC/src/Machine/Axes.cpp +++ b/FluidNC/src/Machine/Axes.cpp @@ -109,26 +109,16 @@ namespace Machine { config->_stepping->waitDirection(); } - auto limitedMotors = posLimitMask | negLimitMask; - bool isHomingApproach = Homing::_approach; - // Turn on step pulses for motors that are supposed to step now for (size_t axis = X_AXIS; axis < n_axis; axis++) { if (bitnum_is_true(step_mask, axis)) { - int stepIncrement = bitnum_is_true(dir_mask, axis) ? 1 : -1; + bool dir = bitnum_is_true(dir_mask, axis); auto a = _axis[axis]; - - // Skip steps based on limit pins if: - // (Homing approach or axis hard limits) & limit pin is true - for (size_t motor = 0; motor < Axis::MAX_MOTORS_PER_AXIS; motor++) { - auto m = a->_motors[0]; + auto m = a->_motors[motor]; if (m) { - if (!((isHomingApproach || m->_hardLimits) && bitnum_is_true(limitedMotors, motor_bit(axis, motor)))) { - m->_driver->step(); - m->_steps += stepIncrement; - } + m->step(dir); } } } diff --git a/FluidNC/src/Machine/Homing.cpp b/FluidNC/src/Machine/Homing.cpp index 1eaf7438e..91b1e51c0 100644 --- a/FluidNC/src/Machine/Homing.cpp +++ b/FluidNC/src/Machine/Homing.cpp @@ -34,7 +34,7 @@ namespace Machine { // Then we scale the travel distances for the other axes so they would complete // at the same time. - bool Homing::_approach = false; + volatile bool Homing::_approach = false; const uint32_t MOTOR0 = 0xffff; const uint32_t MOTOR1 = 0xffff0000; @@ -61,7 +61,7 @@ namespace Machine { set_bitnum(axesMask, axis); // Set target location for active axes and setup computation for homing rate. - motor_steps[axis] = 0; + set_motor_steps(axis, 0); auto axisConfig = axes->_axis[axis]; auto homing = axisConfig->_homing; @@ -241,7 +241,7 @@ namespace Machine { // Set machine positions for homed limit switches. Don't update non-homed axes. for (int axis = 0; axis < n_axis; axis++) { if (bitnum_is_true(axisMask, axis)) { - motor_steps[axis] = mpos_to_steps(axes->_axis[axis]->_homing->_mpos, axis); + set_motor_steps(axis, mpos_to_steps(axes->_axis[axis]->_homing->_mpos, axis)); } } sys.step_control = {}; // Return step control to normal operation. diff --git a/FluidNC/src/Machine/Homing.h b/FluidNC/src/Machine/Homing.h index 07ad73dd6..2c4d023e9 100644 --- a/FluidNC/src/Machine/Homing.h +++ b/FluidNC/src/Machine/Homing.h @@ -23,7 +23,7 @@ namespace Machine { static const int AllCycles = 0; // Must be zero. - static bool _approach; + static volatile bool _approach; static void run_cycles(AxisMask axisMask); static void run_one_cycle(AxisMask axisMask); diff --git a/FluidNC/src/Machine/LimitPin.cpp b/FluidNC/src/Machine/LimitPin.cpp index 5128860e1..7edada9f7 100644 --- a/FluidNC/src/Machine/LimitPin.cpp +++ b/FluidNC/src/Machine/LimitPin.cpp @@ -10,8 +10,8 @@ #include // CHANGE namespace Machine { - LimitPin::LimitPin(Pin& pin, int axis, int motor, int direction, bool& pHardLimits) : - _axis(axis), _motorNum(motor), _value(false), _pHardLimits(pHardLimits), _pin(pin) { + LimitPin::LimitPin(Pin& pin, int axis, int motor, int direction, bool& pHardLimits, bool& pLimited) : + _axis(axis), _motorNum(motor), _value(false), _pHardLimits(pHardLimits), _pLimited(pLimited), _pin(pin) { String sDir; // Select one or two bitmask variables to receive the switch data switch (direction) { @@ -65,7 +65,8 @@ namespace Machine { } void IRAM_ATTR LimitPin::read() { - _value = _pin.read(); + _value = _pin.read(); + _pLimited = _value; if (_value) { if (_posLimits != nullptr) { set_bits(*_posLimits, _bitmask); diff --git a/FluidNC/src/Machine/LimitPin.h b/FluidNC/src/Machine/LimitPin.h index d0a6631df..76996777a 100644 --- a/FluidNC/src/Machine/LimitPin.h +++ b/FluidNC/src/Machine/LimitPin.h @@ -16,7 +16,14 @@ namespace Machine { // _pHardLimits is a reference so the shared variable at the // Endstops level can be changed at runtime to control the // limit behavior dynamically. - bool& _pHardLimits; + bool& _pHardLimits; + + // _pHardLimits is a reference to the _limited member of + // the Motor class. Setting it when the Limit ISR fires + // lets the motor driver respond rapidly to a limit switch + // touch, increasing the accuracy of homing + volatile bool& _pLimited; + volatile uint32_t* _posLimits = nullptr; volatile uint32_t* _negLimits = nullptr; @@ -27,7 +34,7 @@ namespace Machine { void read(); public: - LimitPin(Pin& pin, int axis, int motorNum, int direction, bool& phardLimits); + LimitPin(Pin& pin, int axis, int motorNum, int direction, bool& phardLimits, bool& pLimited); Pin& _pin; diff --git a/FluidNC/src/Machine/Motor.cpp b/FluidNC/src/Machine/Motor.cpp index d43e98909..49dbdf7ee 100644 --- a/FluidNC/src/Machine/Motor.cpp +++ b/FluidNC/src/Machine/Motor.cpp @@ -31,9 +31,9 @@ namespace Machine { } _driver->init(); - _negLimitPin = new LimitPin(_negPin, _axis, _motorNum, -1, _hardLimits); - _posLimitPin = new LimitPin(_posPin, _axis, _motorNum, 1, _hardLimits); - _allLimitPin = new LimitPin(_allPin, _axis, _motorNum, 0, _hardLimits); + _negLimitPin = new LimitPin(_negPin, _axis, _motorNum, -1, _hardLimits, _limited); + _posLimitPin = new LimitPin(_posPin, _axis, _motorNum, 1, _hardLimits, _limited); + _allLimitPin = new LimitPin(_allPin, _axis, _motorNum, 0, _hardLimits, _limited); _negLimitPin->init(); _posLimitPin->init(); @@ -58,5 +58,16 @@ namespace Machine { bool Motor::isReal() { return _driver->isReal(); } + void Motor::step(bool reverse) { + // Skip steps based on limit pins + if (_limited && (Homing::_approach || (sys.state != State::Homing && _hardLimits))) { + return; + } + _driver->step(); + _steps += reverse ? -1 : 1; + } + + void Motor::unstep() { _driver->unstep(); } + Motor::~Motor() { delete _driver; } } diff --git a/FluidNC/src/Machine/Motor.h b/FluidNC/src/Machine/Motor.h index 342a8299f..7ec1160ef 100644 --- a/FluidNC/src/Machine/Motor.h +++ b/FluidNC/src/Machine/Motor.h @@ -35,7 +35,8 @@ namespace Machine { Pin _allPin; bool _hardLimits = false; - int32_t _steps = 0; + int32_t _steps = 0; + bool _limited = false; // _limited is set by the LimitPin ISR // Configuration system helpers: void group(Configuration::HandlerBase& handler) override; @@ -45,6 +46,8 @@ namespace Machine { void makeDualSwitches(); void init(); void config_motor(); + void step(bool reverse); + void unstep(); ~Motor(); }; } diff --git a/FluidNC/src/Main.cpp b/FluidNC/src/Main.cpp index 94db30bbb..71eccd8fc 100644 --- a/FluidNC/src/Main.cpp +++ b/FluidNC/src/Main.cpp @@ -82,7 +82,10 @@ void setup() { config->_kinematics->init(); - memset(motor_steps, 0, sizeof(motor_steps)); // Clear machine position. + auto n_axis = config->_axes->_numberAxis; + for (size_t axis = 0; axis < n_axis; axis++) { + set_motor_steps(axis, 0); // Clear machine position. + } machine_init(); // user supplied function for special initialization } @@ -132,16 +135,6 @@ void setup() { } static void reset_variables() { -# ifdef DEBUG_STEPPING - rtTestPl = false; - rtTestSt = false; - st_seq = 0; - st_seq0 = 0; - pl_seq0 = 0; - seg_seq0 = 0; - seg_seq1 = 0; - planner_seq = 0; -# endif // Reset primary systems. system_reset(); protocol_reset(); diff --git a/FluidNC/src/MotionControl.cpp b/FluidNC/src/MotionControl.cpp index ba52be4a1..83bdbf4e3 100644 --- a/FluidNC/src/MotionControl.cpp +++ b/FluidNC/src/MotionControl.cpp @@ -342,7 +342,8 @@ GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t par // Set state variables and error out, if the probe failed and cycle with error is enabled. if (probeState == ProbeState::Active) { if (is_no_error) { - memcpy(probe_steps, motor_steps, sizeof(motor_steps)); + auto n_axis = config->_axes->_numberAxis; + memcpy(probe_steps, get_motor_steps(), n_axis * sizeof(probe_steps[0])); } else { rtAlarm = ExecAlarm::ProbeFailContact; } diff --git a/FluidNC/src/Motors/Dynamixel2.cpp b/FluidNC/src/Motors/Dynamixel2.cpp index 4c37fe8a8..dba104188 100644 --- a/FluidNC/src/Motors/Dynamixel2.cpp +++ b/FluidNC/src/Motors/Dynamixel2.cpp @@ -155,8 +155,8 @@ namespace MotorDrivers { return false; } - auto axis = config->_axes->_axis[_axis_index]; - motor_steps[_axis_index] = mpos_to_steps(axis->_homing->_mpos, _axis_index); + auto axis = config->_axes->_axis[_axis_index]; + set_motor_steps(_axis_index, mpos_to_steps(axis->_homing->_mpos, _axis_index)); set_disable(false); set_location(); // force the PWM to update now @@ -192,7 +192,7 @@ namespace MotorDrivers { uint32_t temp = myMap(dxl_position, _countMin, _countMax, pos_min_steps, pos_max_steps); - motor_steps[_axis_index] = temp; + set_motor_steps(_axis_index, temp); plan_sync_position(); diff --git a/FluidNC/src/Motors/RcServo.cpp b/FluidNC/src/Motors/RcServo.cpp index 9be3fe26b..51e53b3ff 100644 --- a/FluidNC/src/Motors/RcServo.cpp +++ b/FluidNC/src/Motors/RcServo.cpp @@ -84,8 +84,8 @@ namespace MotorDrivers { return false; if (isHoming) { - auto axis = config->_axes->_axis[_axis_index]; - motor_steps[_axis_index] = mpos_to_steps(axis->_homing->_mpos, _axis_index); + auto axis = config->_axes->_axis[_axis_index]; + set_motor_steps(_axis_index, mpos_to_steps(axis->_homing->_mpos, _axis_index)); float home_time_sec = (axis->_maxTravel / axis->_maxRate * 60 * 1.1); // 1.1 fudge factor for accell time. @@ -108,8 +108,8 @@ namespace MotorDrivers { read_settings(); - float mpos = steps_to_mpos(motor_steps[_axis_index], _axis_index); // get the axis machine position in mm - servo_pos = mpos; // determine the current work position + float mpos = steps_to_mpos(get_axis_motor_steps(_axis_index), _axis_index); // get the axis machine position in mm + servo_pos = mpos; // determine the current work position // determine the pulse length servo_pulse_len = static_cast(mapConstrain( diff --git a/FluidNC/src/Motors/Solenoid.cpp b/FluidNC/src/Motors/Solenoid.cpp index 57ab0f241..5758c7d83 100644 --- a/FluidNC/src/Motors/Solenoid.cpp +++ b/FluidNC/src/Motors/Solenoid.cpp @@ -82,7 +82,7 @@ namespace MotorDrivers { return; } - float mpos = steps_to_mpos(motor_steps[_axis_index], _axis_index); // get the axis machine position in mm + float mpos = steps_to_mpos(get_axis_motor_steps(_axis_index), _axis_index); // get the axis machine position in mm _dir_invert ? is_solenoid_on = (mpos < 0.0) : is_solenoid_on = (mpos > 0.0); diff --git a/FluidNC/src/Planner.cpp b/FluidNC/src/Planner.cpp index 1b447b6cc..eb6896ad9 100644 --- a/FluidNC/src/Planner.cpp +++ b/FluidNC/src/Planner.cpp @@ -293,9 +293,6 @@ void plan_update_velocity_profile_parameters() { pl.previous_nominal_speed = prev_nominal_speed; // Update prev nominal speed for next incoming block. } -#ifdef DEBUG_STEPPING -uint32_t planner_seq = 0; -#endif bool plan_buffer_line(float* target, plan_line_data_t* pl_data) { // Prepare and initialize new block. Copy relevant pl_data for block execution. plan_block_t* block = &block_buffer[block_buffer_head]; @@ -310,21 +307,17 @@ bool plan_buffer_line(float* target, plan_line_data_t* pl_data) { int32_t target_steps[MAX_N_AXIS], position_steps[MAX_N_AXIS]; float unit_vec[MAX_N_AXIS], delta_mm; // Copy position data based on type of motion being planned. + auto n_axis = config->_axes->_numberAxis; if (block->motion.systemMotion) { - memcpy(position_steps, motor_steps, sizeof(motor_steps)); + memcpy(position_steps, get_motor_steps(), n_axis * sizeof(position_steps[0])); } else { - memcpy(position_steps, pl.position, sizeof(pl.position)); + memcpy(position_steps, pl.position, n_axis * sizeof(position_steps[0])); } - auto n_axis = config->_axes->_numberAxis; for (size_t idx = 0; idx < n_axis; idx++) { // Calculate target position in absolute steps, number of steps for each axis, and determine max step events. // Also, compute individual axes distance for move and prep unit vector calculations. // NOTE: Computes true distance from converted step values. - target_steps[idx] = lround(mpos_to_steps(target[idx], idx)); -#ifdef DEBUG_STEPPING - block->entry_pos[idx] = position_steps[idx]; - block->exit_pos[idx] = target_steps[idx]; -#endif + target_steps[idx] = lround(mpos_to_steps(target[idx], idx)); block->steps[idx] = labs(target_steps[idx] - position_steps[idx]); block->step_event_count = MAX(block->step_event_count, block->steps[idx]); delta_mm = steps_to_mpos((target_steps[idx] - position_steps[idx]), idx); @@ -334,9 +327,6 @@ bool plan_buffer_line(float* target, plan_line_data_t* pl_data) { block->direction_bits |= bitnum_to_mask(idx); } } -#ifdef DEBUG_STEPPING - block->seq = planner_seq++; -#endif // Bail if this is a zero-length block. Highly unlikely to occur. if (block->step_event_count == 0) { return false; @@ -433,9 +423,7 @@ void plan_sync_position() { // this function needs to be updated to accomodate the difference. auto a = config->_axes; auto n_axis = a ? a->_numberAxis : 0; - for (size_t idx = 0; idx < n_axis; idx++) { - pl.position[idx] = motor_steps[idx]; - } + memcpy(pl.position, get_motor_steps(), n_axis * sizeof(pl.position[0])); } // Returns the number of available blocks are in the planner buffer. diff --git a/FluidNC/src/Planner.h b/FluidNC/src/Planner.h index 09e76998b..a283de67b 100644 --- a/FluidNC/src/Planner.h +++ b/FluidNC/src/Planner.h @@ -25,19 +25,10 @@ struct PlMotion { // This struct stores a linear movement of a g-code block motion with its critical "nominal" values // are as specified in the source g-code. -#ifdef DEBUG_STEPPING -extern uint32_t planner_seq; -#endif struct plan_block_t { // Fields used by the bresenham algorithm for tracing the line // NOTE: Used by stepper algorithm to execute the block correctly. Do not alter these values. -#ifdef DEBUG_STEPPING - uint32_t entry_pos[MAX_N_AXIS]; // Expected mpos when this block starts execution - uint32_t exit_pos[MAX_N_AXIS]; // Expected mpos when this block finishes execution - uint32_t seq; // Sequence number -#endif - uint32_t steps[MAX_N_AXIS]; // Step count along each axis uint32_t step_event_count; // The maximum step axis count and number of steps required to complete this block. uint8_t direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h) diff --git a/FluidNC/src/Protocol.cpp b/FluidNC/src/Protocol.cpp index 78d413584..68069101e 100644 --- a/FluidNC/src/Protocol.cpp +++ b/FluidNC/src/Protocol.cpp @@ -17,15 +17,6 @@ #include "Settings.h" // settings_execute_startup #include "InputFile.h" // infile -#ifdef DEBUG_STEPPING -volatile bool rtCrash; -volatile bool rtSeq; -volatile bool rtSegSeq; -volatile bool rtTestPl; -volatile bool rtTestSt; -uint32_t expected_steps[MAX_N_AXIS]; -#endif - #ifdef DEBUG_REPORT_REALTIME volatile bool rtExecDebug; #endif @@ -736,34 +727,6 @@ void protocol_do_macro(int macro_num) { void protocol_exec_rt_system() { protocol_do_alarm(); // If there is a hard or soft limit, this will block until rtReset is set -#ifdef DEBUG_STEPPING - if (rtSegSeq) { - rtSegSeq = false; - log_error("segment exp " << seg_seq_exp << " actual " << seg_seq_act); - rtReset = true; - } - if (rtSeq) { - rtSeq = false; - log_error("planner " << pl_seq0 << " stepper " << st_seq0); - rtReset = true; - } - if (rtCrash) { - rtCrash = false; - log_error("Stepper exp,actual " << expected_steps[0] << "," << motor_steps[0] << " " << expected_steps[1] << "," << motor_steps[1] - << " " << expected_steps[2] << "," << motor_steps[2]); - rtReset = true; - } - if (rtTestPl) { - rtTestPl = false; - log_info("Poisoned planner_seq"); - planner_seq += 20; - } - if (rtTestSt) { - rtTestSt = false; - log_info("Poisoned stepper"); - --motor_steps[0]; - } -#endif if (rtReset) { if (sys.state == State::Homing) { rtAlarm = ExecAlarm::HomingFailReset; diff --git a/FluidNC/src/Protocol.h b/FluidNC/src/Protocol.h index 4d1c7cbff..af4e93bd1 100644 --- a/FluidNC/src/Protocol.h +++ b/FluidNC/src/Protocol.h @@ -51,15 +51,6 @@ extern volatile bool rtButtonMacro1; extern volatile bool rtButtonMacro2; extern volatile bool rtButtonMacro3; -#ifdef DEBUG_STEPPING -extern volatile bool rtCrash; -extern volatile bool rtSeq; -extern volatile bool rtSegSeq; -extern volatile bool rtTestPl; -extern volatile bool rtTestSt; -extern uint32_t expected_steps[MAX_N_AXIS]; -#endif - #ifdef DEBUG_REPORT_REALTIME extern volatile bool rtExecDebug; #endif diff --git a/FluidNC/src/Serial.cpp b/FluidNC/src/Serial.cpp index d89b0bb32..c53d6fb82 100644 --- a/FluidNC/src/Serial.cpp +++ b/FluidNC/src/Serial.cpp @@ -184,14 +184,6 @@ void execute_realtime_command(Cmd command, Channel& channel) { case Cmd::CoolantMistOvrToggle: rtAccessoryOverride.bit.coolantMistOvrToggle = 1; break; -#ifdef DEBUG_STEPPING - case Cmd::TestPl: - rtTestPl = true; - break; - case Cmd::TestSt: - rtTestSt = true; - break; -#endif } } @@ -201,11 +193,7 @@ bool is_realtime_command(uint8_t data) { return true; } auto cmd = static_cast(data); - return cmd == Cmd::Reset || cmd == Cmd::StatusReport || cmd == Cmd::CycleStart || cmd == Cmd::FeedHold -#ifdef DEBUG_STEPPING - || cmd == Cmd::TestPl || cmd == Cmd::TestSt -#endif - ; + return cmd == Cmd::Reset || cmd == Cmd::StatusReport || cmd == Cmd::CycleStart || cmd == Cmd::FeedHold; } void AllChannels::init() { diff --git a/FluidNC/src/Serial.h b/FluidNC/src/Serial.h index e2e8c9578..cb550b6d3 100644 --- a/FluidNC/src/Serial.h +++ b/FluidNC/src/Serial.h @@ -55,10 +55,6 @@ enum class Cmd : uint8_t { SpindleOvrStop = 0x9E, CoolantFloodOvrToggle = 0xA0, CoolantMistOvrToggle = 0xA1, -#ifdef DEBUG_STEPPING - TestPl = '^', - TestSt = '%', -#endif }; bool is_realtime_command(uint8_t data); diff --git a/FluidNC/src/Stepper.cpp b/FluidNC/src/Stepper.cpp index de87012f5..4c0244871 100644 --- a/FluidNC/src/Stepper.cpp +++ b/FluidNC/src/Stepper.cpp @@ -20,16 +20,6 @@ using namespace Stepper; -#ifdef DEBUG_STEPPING -uint32_t st_seq = 0; -uint32_t st_seq0; -uint32_t seg_seq0 = 0; -uint32_t seg_seq1 = 0; -uint32_t seg_seq_act; -uint32_t seg_seq_exp; -uint32_t pl_seq0; -#endif - // Stores the planner block Bresenham algorithm execution data for the segments in the segment // buffer. Normally, this buffer is partially in-use, but, for the worst case scenario, it will // never exceed the number of accessible stepper buffer segments (config->_stepping->_segments-1). @@ -41,10 +31,6 @@ struct st_block_t { uint32_t step_event_count; uint8_t direction_bits; bool is_pwm_rate_adjusted; // Tracks motions that require constant laser power/rate -#ifdef DEBUG_STEPPING - uint32_t entry[MAX_N_AXIS]; - // uint32_t exit[MAX_N_AXIS]; -#endif }; static volatile st_block_t* st_block_buffer = nullptr; @@ -53,9 +39,6 @@ static volatile st_block_t* st_block_buffer = nullptr; // planner buffer. Once "checked-out", the steps in the segments buffer cannot be modified by // the planner, where the remaining planner block steps still can. struct segment_t { -#ifdef DEBUG_STEPPING - uint32_t seq; -#endif uint16_t n_step; // Number of step events to be executed for this segment uint16_t isrPeriod; // Time to next ISR tick, in units of timer ticks uint8_t st_block_index; // Stepper block data index. Uses this information to execute this segment. @@ -216,14 +199,6 @@ void IRAM_ATTR Stepper::pulse_func() { if (segment_buffer_head != segment_buffer_tail) { // Initialize new step segment and load number of steps to execute st.exec_segment = &segment_buffer[segment_buffer_tail]; -#ifdef DEBUG_STEPPING - if (st.exec_segment->seq != seg_seq1) { - seg_seq_act = st.exec_segment->seq; - seg_seq_exp = seg_seq1; - rtSegSeq = true; - } - seg_seq1++; -#endif // Initialize step segment timing per step and load number of steps to execute. config->_stepping->setTimerPeriod(st.exec_segment->isrPeriod); st.step_count = st.exec_segment->n_step; // NOTE: Can sometimes be zero when moving slow. @@ -232,26 +207,10 @@ void IRAM_ATTR Stepper::pulse_func() { if (st.exec_block_index != st.exec_segment->st_block_index) { st.exec_block_index = st.exec_segment->st_block_index; st.exec_block = &st_block_buffer[st.exec_block_index]; -#ifdef DEBUG_STEPPING - bool offstep = false; -#endif // Initialize Bresenham line and distance counters for (int axis = 0; axis < n_axis; axis++) { -#ifdef DEBUG_STEPPING - if (st.exec_block->entry[axis] != motor_steps[axis]) { - offstep = true; - } -#endif st.counter[axis] = st.exec_block->step_event_count >> 1; } -#ifdef DEBUG_STEPPING - if (offstep) { - for (int axis = 0; axis < n_axis; axis++) { - expected_steps[axis] = st.exec_block->entry[axis]; - } - rtCrash = true; - } -#endif } st.dir_outbits = st.exec_block->direction_bits; @@ -279,7 +238,11 @@ void IRAM_ATTR Stepper::pulse_func() { if (probeState == ProbeState::Active && config->_probe->tripped()) { probeState = ProbeState::Off; // Memcpy is not IRAM_ATTR, but: most compilers optimize memcpy away. - memcpy(probe_steps, motor_steps, sizeof(motor_steps)); + auto axes = config->_axes; + for (int axis = 0; axis < n_axis; axis++) { + auto m = axes->_axis[axis]->_motors[0]; + probe_steps[axis] = m ? m->_steps : 0; + } rtMotionCancel = true; } @@ -292,11 +255,6 @@ void IRAM_ATTR Stepper::pulse_func() { if (st.counter[axis] > st.exec_block->step_event_count) { set_bitnum(st.step_outbits, axis); st.counter[axis] -= st.exec_block->step_event_count; - if (bitnum_is_true(st.exec_block->direction_bits, axis)) { - motor_steps[axis]--; - } else { - motor_steps[axis]++; - } } } @@ -452,19 +410,7 @@ void Stepper::prep_buffer() { // If the original data is divided, we can lose a step from integer roundoff. for (idx = 0; idx < n_axis; idx++) { st_prep_block->steps[idx] = pl_block->steps[idx] << maxAmassLevel; -#ifdef DEBUG_STEPPING - st_prep_block->entry[idx] = pl_block->entry_pos[idx]; - // st_prep_block->exit[idx] = pl_block->exit_pos[idx]; -#endif } -#ifdef DEBUG_STEPPING - if (pl_block->seq != st_seq && !rtSeq) { - rtSeq = true; - st_seq0 = st_seq; - pl_seq0 = pl_block->seq; - } - ++st_seq; -#endif st_prep_block->step_event_count = pl_block->step_event_count << maxAmassLevel; // Initialize segment buffer data for generating the segments. @@ -583,10 +529,6 @@ void Stepper::prep_buffer() { // Initialize new segment volatile segment_t* prep_segment = &segment_buffer[segment_buffer_head]; -#ifdef DEBUG_STEPPING - prep_segment->seq = seg_seq0++; -#endif - // Set new segment to point to the current segment data block. prep_segment->st_block_index = prep.st_block_index; diff --git a/FluidNC/src/Stepper.h b/FluidNC/src/Stepper.h index 59977a422..274087577 100644 --- a/FluidNC/src/Stepper.h +++ b/FluidNC/src/Stepper.h @@ -47,13 +47,3 @@ namespace Stepper { extern uint32_t isr_count; // for debugging only } -#ifdef DEBUG_STEPPING -extern uint32_t st_seq; -extern uint32_t st_seq0; -extern uint32_t pl_seq0; -extern uint32_t seg_seq0; -extern uint32_t seg_seq1; -extern uint32_t seg_seq_act; -extern uint32_t seg_seq_exp; - -#endif diff --git a/FluidNC/src/System.cpp b/FluidNC/src/System.cpp index 80b6c32d9..cf567d4b1 100644 --- a/FluidNC/src/System.cpp +++ b/FluidNC/src/System.cpp @@ -15,7 +15,6 @@ // Declare system global variable structure system_t sys; -int32_t motor_steps[MAX_N_AXIS]; // Real-time position in steps. int32_t probe_steps[MAX_N_AXIS]; // Last probe position in steps. void system_reset() { @@ -48,9 +47,37 @@ void motor_steps_to_mpos(float* position, int32_t* steps) { config->_kinematics->motors_to_cartesian(position, motor_mpos, n_axis); } +void set_motor_steps(size_t axis, int32_t steps) { + auto a = config->_axes->_axis[axis]; + for (size_t motor = 0; motor < Machine::Axis::MAX_MOTORS_PER_AXIS; motor++) { + auto m = a->_motors[motor]; + if (m) { + m->_steps = steps; + } + } +} + +int32_t get_axis_motor_steps(size_t axis) { + auto m = config->_axes->_axis[axis]->_motors[0]; + return m ? m->_steps : 0; +} + +int32_t* get_motor_steps() { + static int32_t motor_steps[MAX_N_AXIS]; + + auto axes = config->_axes; + auto n_axis = axes->_numberAxis; + for (size_t axis = 0; axis < n_axis; axis++) { + auto m = axes->_axis[axis]->_motors[0]; + motor_steps[axis] = m ? m->_steps : 0; + } + return motor_steps; +} + float* get_mpos() { static float position[MAX_N_AXIS]; - motor_steps_to_mpos(position, motor_steps); + + motor_steps_to_mpos(position, get_motor_steps()); return position; }; diff --git a/FluidNC/src/System.h b/FluidNC/src/System.h index f6f09d64a..6845c57f2 100644 --- a/FluidNC/src/System.h +++ b/FluidNC/src/System.h @@ -81,6 +81,10 @@ void system_reset(); float steps_to_mpos(int32_t steps, size_t axis); int32_t mpos_to_steps(float mpos, size_t axis); +int32_t get_axis_motor_steps(size_t axis); +void set_motor_steps(size_t axis, int32_t steps); +int32_t* get_motor_steps(); + // Updates a machine position array from a steps array void motor_steps_to_mpos(float* position, int32_t* steps); float* get_mpos(); From 751cc12ac3f7d9f7cc4961397cef3b2dab46e4c3 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Mon, 2 May 2022 15:41:37 -1000 Subject: [PATCH 05/22] Replaced memcpy for axis arrays with copyAxes --- FluidNC/src/GCode.cpp | 14 +++++++------- FluidNC/src/Kinematics/Cartesian.cpp | 2 +- FluidNC/src/Machine/MachineConfig.h | 8 ++++++++ FluidNC/src/MotionControl.cpp | 5 ++--- FluidNC/src/Planner.cpp | 17 +++++++---------- FluidNC/src/Protocol.cpp | 2 +- FluidNC/src/Stepper.cpp | 3 +-- 7 files changed, 27 insertions(+), 24 deletions(-) diff --git a/FluidNC/src/GCode.cpp b/FluidNC/src/GCode.cpp index cfa5eec88..18b7fbdd3 100644 --- a/FluidNC/src/GCode.cpp +++ b/FluidNC/src/GCode.cpp @@ -906,7 +906,7 @@ Error gc_execute_line(char* line, Channel& channel) { // future versions on processors with enough memory, all coordinate data should be stored // in memory and written to non-volatile storage only when there is not a cycle active. float block_coord_system[MAX_N_AXIS]; - memcpy(block_coord_system, gc_state.coord_system, sizeof(gc_state.coord_system)); + copyAxes(block_coord_system, gc_state.coord_system); if (bitnum_is_true(command_words, ModalGroup::MG12)) { // Check if called in block // This error probably cannot happen because preceding code sets // gc_block.modal.coord_select only to specific supported values @@ -1324,7 +1324,7 @@ Error gc_execute_line(char* line, Channel& channel) { bool cancelledInflight = false; Error status = jog_execute(pl_data, &gc_block, &cancelledInflight); if (status == Error::Ok && !cancelledInflight) { - memcpy(gc_state.position, gc_block.values.xyz, sizeof(gc_block.values.xyz)); + copyAxes(gc_state.position, gc_block.values.xyz); } // JogCancelled is not reported as a GCode error return status == Error::JogCancelled ? Error::Ok : status; @@ -1510,7 +1510,7 @@ Error gc_execute_line(char* line, Channel& channel) { // [15. Coordinate system selection ]: if (gc_state.modal.coord_select != gc_block.modal.coord_select) { gc_state.modal.coord_select = gc_block.modal.coord_select; - memcpy(gc_state.coord_system, block_coord_system, sizeof(gc_state.coord_system)); + copyAxes(gc_state.coord_system, block_coord_system); gc_wco_changed(); } // [16. Set path control mode ]: G61.1/G64 NOT SUPPORTED @@ -1524,7 +1524,7 @@ Error gc_execute_line(char* line, Channel& channel) { coords[coord_select]->set(coord_data); // Update system coordinate system if currently active. if (gc_state.modal.coord_select == coord_select) { - memcpy(gc_state.coord_system, coord_data, sizeof(gc_state.coord_system)); + copyAxes(gc_state.coord_system, coord_data); gc_wco_changed(); } break; @@ -1537,7 +1537,7 @@ Error gc_execute_line(char* line, Channel& channel) { mc_linear(gc_block.values.xyz, pl_data, gc_state.position); } mc_linear(coord_data, pl_data, gc_state.position); - memcpy(gc_state.position, coord_data, sizeof(gc_state.position)); + copyAxes(gc_state.position, coord_data); break; case NonModal::SetHome0: coords[CoordIndex::G28]->set(gc_state.position); @@ -1546,7 +1546,7 @@ Error gc_execute_line(char* line, Channel& channel) { coords[CoordIndex::G30]->set(gc_state.position); break; case NonModal::SetCoordinateOffset: - memcpy(gc_state.coord_offset, gc_block.values.xyz, sizeof(gc_block.values.xyz)); + copyAxes(gc_state.coord_offset, gc_block.values.xyz); gc_wco_changed(); break; case NonModal::ResetCoordinateOffset: @@ -1590,7 +1590,7 @@ Error gc_execute_line(char* line, Channel& channel) { // motion control system might still be processing the action and the real tool position // in any intermediate location. if (gc_update_pos == GCUpdatePos::Target) { - memcpy(gc_state.position, gc_block.values.xyz, sizeof(gc_block.values.xyz)); // gc_state.position[] = gc_block.values.xyz[] + copyAxes(gc_state.position, gc_block.values.xyz); } else if (gc_update_pos == GCUpdatePos::System) { gc_sync_position(); } // == GCUpdatePos::None diff --git a/FluidNC/src/Kinematics/Cartesian.cpp b/FluidNC/src/Kinematics/Cartesian.cpp index 612748859..1a9fbc0e6 100644 --- a/FluidNC/src/Kinematics/Cartesian.cpp +++ b/FluidNC/src/Kinematics/Cartesian.cpp @@ -21,7 +21,7 @@ namespace Kinematics { void Cartesian::motors_to_cartesian(float* cartesian, float* motors, int n_axis) { // Motor space is cartesian space, so we do no transform. - memcpy(cartesian, motors, n_axis * sizeof(motors[0])); + copyAxes(cartesian, motors); } // Configuration registration diff --git a/FluidNC/src/Machine/MachineConfig.h b/FluidNC/src/Machine/MachineConfig.h index d87181eb1..49e0819db 100644 --- a/FluidNC/src/Machine/MachineConfig.h +++ b/FluidNC/src/Machine/MachineConfig.h @@ -107,3 +107,11 @@ namespace Machine { } extern Machine::MachineConfig* config; + +template +void copyAxes(T* dest, T* src) { + auto n_axis = config->_axes->_numberAxis; + for (size_t axis = 0; axis < n_axis; axis++) { + dest[axis] = src[axis]; + } +} diff --git a/FluidNC/src/MotionControl.cpp b/FluidNC/src/MotionControl.cpp index 83bdbf4e3..7c9524f07 100644 --- a/FluidNC/src/MotionControl.cpp +++ b/FluidNC/src/MotionControl.cpp @@ -342,8 +342,7 @@ GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t par // Set state variables and error out, if the probe failed and cycle with error is enabled. if (probeState == ProbeState::Active) { if (is_no_error) { - auto n_axis = config->_axes->_numberAxis; - memcpy(probe_steps, get_motor_steps(), n_axis * sizeof(probe_steps[0])); + copyAxes(probe_steps, get_motor_steps()); } else { rtAlarm = ExecAlarm::ProbeFailContact; } @@ -376,7 +375,7 @@ GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t par } log_info("Probe offset applied:"); coords[gc_state.modal.coord_select]->set(coord_data); // save it - memcpy(gc_state.coord_system, coord_data, sizeof(gc_state.coord_system)); + copyAxes(gc_state.coord_system, coord_data); report_wco_counter = 0; } diff --git a/FluidNC/src/Planner.cpp b/FluidNC/src/Planner.cpp index eb6896ad9..0adb95586 100644 --- a/FluidNC/src/Planner.cpp +++ b/FluidNC/src/Planner.cpp @@ -307,12 +307,9 @@ bool plan_buffer_line(float* target, plan_line_data_t* pl_data) { int32_t target_steps[MAX_N_AXIS], position_steps[MAX_N_AXIS]; float unit_vec[MAX_N_AXIS], delta_mm; // Copy position data based on type of motion being planned. + copyAxes(position_steps, block->motion.systemMotion ? get_motor_steps() : pl.position); + auto n_axis = config->_axes->_numberAxis; - if (block->motion.systemMotion) { - memcpy(position_steps, get_motor_steps(), n_axis * sizeof(position_steps[0])); - } else { - memcpy(position_steps, pl.position, n_axis * sizeof(position_steps[0])); - } for (size_t idx = 0; idx < n_axis; idx++) { // Calculate target position in absolute steps, number of steps for each axis, and determine max step events. // Also, compute individual axes distance for move and prep unit vector calculations. @@ -406,8 +403,8 @@ bool plan_buffer_line(float* target, plan_line_data_t* pl_data) { plan_compute_profile_parameters(block, nominal_speed, pl.previous_nominal_speed); pl.previous_nominal_speed = nominal_speed; // Update previous path unit_vector and planner position. - memcpy(pl.previous_unit_vec, unit_vec, sizeof(unit_vec)); // pl.previous_unit_vec[] = unit_vec[] - memcpy(pl.position, target_steps, sizeof(target_steps)); // pl.position[] = target_steps[] + copyAxes(pl.previous_unit_vec, unit_vec); + copyAxes(pl.position, target_steps); // New block is all set. Update buffer head and next buffer head indices. block_buffer_head = next_buffer_head; next_buffer_head = plan_next_block_index(block_buffer_head); @@ -421,9 +418,9 @@ bool plan_buffer_line(float* target, plan_line_data_t* pl_data) { void plan_sync_position() { // TODO: For motor configurations not in the same coordinate frame as the machine position, // this function needs to be updated to accomodate the difference. - auto a = config->_axes; - auto n_axis = a ? a->_numberAxis : 0; - memcpy(pl.position, get_motor_steps(), n_axis * sizeof(pl.position[0])); + if (config->_axes) { + copyAxes(pl.position, get_motor_steps()); + } } // Returns the number of available blocks are in the planner buffer. diff --git a/FluidNC/src/Protocol.cpp b/FluidNC/src/Protocol.cpp index 68069101e..552e1a2b2 100644 --- a/FluidNC/src/Protocol.cpp +++ b/FluidNC/src/Protocol.cpp @@ -866,7 +866,7 @@ static void protocol_exec_rt_suspend() { // Get current position and store restore location and spindle retract waypoint. if (!sys.suspend.bit.restartRetract) { - memcpy(restore_target, parking_target, sizeof(restore_target[0]) * config->_axes->_numberAxis); + copyAxes(restore_target, parking_target); retract_waypoint += restore_target[PARKING_AXIS]; retract_waypoint = MIN(retract_waypoint, PARKING_TARGET); } diff --git a/FluidNC/src/Stepper.cpp b/FluidNC/src/Stepper.cpp index 4c0244871..cfdc2e026 100644 --- a/FluidNC/src/Stepper.cpp +++ b/FluidNC/src/Stepper.cpp @@ -237,8 +237,7 @@ void IRAM_ATTR Stepper::pulse_func() { // Check probing state. if (probeState == ProbeState::Active && config->_probe->tripped()) { probeState = ProbeState::Off; - // Memcpy is not IRAM_ATTR, but: most compilers optimize memcpy away. - auto axes = config->_axes; + auto axes = config->_axes; for (int axis = 0; axis < n_axis; axis++) { auto m = axes->_axis[axis]->_motors[0]; probe_steps[axis] = m ? m->_steps : 0; From a7cb7189cfff609ffcb3ad6a19cd74316de2cad5 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 3 May 2022 10:50:39 -1000 Subject: [PATCH 06/22] Multiple axis limits for CoreXY --- FluidNC/src/Kinematics/CoreXY.cpp | 8 +++++++- FluidNC/src/Machine/LimitPin.cpp | 5 +++++ FluidNC/src/Machine/LimitPin.h | 2 ++ FluidNC/src/Machine/Motor.cpp | 7 +++++++ FluidNC/src/Machine/Motor.h | 1 + 5 files changed, 22 insertions(+), 1 deletion(-) diff --git a/FluidNC/src/Kinematics/CoreXY.cpp b/FluidNC/src/Kinematics/CoreXY.cpp index 274c919e8..ac614a915 100644 --- a/FluidNC/src/Kinematics/CoreXY.cpp +++ b/FluidNC/src/Kinematics/CoreXY.cpp @@ -29,7 +29,13 @@ TODO: If touching back off namespace Kinematics { void CoreXY::group(Configuration::HandlerBase& handler) {} - void CoreXY::init() { log_info("Kinematic system: " << name()); } + void CoreXY::init() { + log_info("Kinematic system: " << name()); + + // A limit switch on either axis stops both motors + config->_axes->_axis[X_AXIS]->_motors[0]->limitOtherAxis(Y_AXIS); + config->_axes->_axis[Y_AXIS]->_motors[0]->limitOtherAxis(X_AXIS); + } // plan a homing mve in motor space for the homing sequence void CoreXY::plan_homing_move(AxisMask axisMask, bool approach, bool seek) { diff --git a/FluidNC/src/Machine/LimitPin.cpp b/FluidNC/src/Machine/LimitPin.cpp index 7edada9f7..89182dee3 100644 --- a/FluidNC/src/Machine/LimitPin.cpp +++ b/FluidNC/src/Machine/LimitPin.cpp @@ -67,6 +67,9 @@ namespace Machine { void IRAM_ATTR LimitPin::read() { _value = _pin.read(); _pLimited = _value; + if (_pExtraLimited != nullptr) { + *_pExtraLimited = _value; + } if (_value) { if (_posLimits != nullptr) { set_bits(*_posLimits, _bitmask); @@ -105,5 +108,7 @@ namespace Machine { // if this belongs to a dual motor, single switch axis void LimitPin::makeDualMask() { _bitmask = Axes::axes_to_motors(Axes::motors_to_axes(_bitmask)); } + void LimitPin::setExtraMotorLimit(int axis, int motorNum) { _pExtraLimited = &config->_axes->_axis[axis]->_motors[motorNum]->_limited; } + LimitPin::~LimitPin() { _pin.detachInterrupt(); } } diff --git a/FluidNC/src/Machine/LimitPin.h b/FluidNC/src/Machine/LimitPin.h index 76996777a..509907c25 100644 --- a/FluidNC/src/Machine/LimitPin.h +++ b/FluidNC/src/Machine/LimitPin.h @@ -23,6 +23,7 @@ namespace Machine { // lets the motor driver respond rapidly to a limit switch // touch, increasing the accuracy of homing volatile bool& _pLimited; + volatile bool* _pExtraLimited = nullptr; volatile uint32_t* _posLimits = nullptr; volatile uint32_t* _negLimits = nullptr; @@ -43,6 +44,7 @@ namespace Machine { void init(); bool get() { return _value; } void makeDualMask(); // makes this a mask for motor0 and motor1 + void setExtraMotorLimit(int axis, int motorNum); ~LimitPin(); }; diff --git a/FluidNC/src/Machine/Motor.cpp b/FluidNC/src/Machine/Motor.cpp index 49dbdf7ee..07c252994 100644 --- a/FluidNC/src/Machine/Motor.cpp +++ b/FluidNC/src/Machine/Motor.cpp @@ -56,6 +56,13 @@ namespace Machine { _allLimitPin->makeDualMask(); } + // Used for CoreXY when one limit switch should stop multiple motors + void Motor::limitOtherAxis(int axis) { + _negLimitPin->setExtraMotorLimit(axis, _motorNum); + _posLimitPin->setExtraMotorLimit(axis, _motorNum); + _allLimitPin->setExtraMotorLimit(axis, _motorNum); + } + bool Motor::isReal() { return _driver->isReal(); } void Motor::step(bool reverse) { diff --git a/FluidNC/src/Machine/Motor.h b/FluidNC/src/Machine/Motor.h index 7ec1160ef..af544e246 100644 --- a/FluidNC/src/Machine/Motor.h +++ b/FluidNC/src/Machine/Motor.h @@ -44,6 +44,7 @@ namespace Machine { bool hasSwitches(); bool isReal(); void makeDualSwitches(); + void limitOtherAxis(int axis); void init(); void config_motor(); void step(bool reverse); From 66db1409e44a6c94b51776bfe5876c54d8489727 Mon Sep 17 00:00:00 2001 From: bdring Date: Tue, 3 May 2022 17:18:42 -0500 Subject: [PATCH 07/22] Update fysetc_corexy.yaml --- example_configs/fysetc_corexy.yaml | 25 ++++++++++++++----------- 1 file changed, 14 insertions(+), 11 deletions(-) diff --git a/example_configs/fysetc_corexy.yaml b/example_configs/fysetc_corexy.yaml index 2d9fab2f7..eada3667d 100644 --- a/example_configs/fysetc_corexy.yaml +++ b/example_configs/fysetc_corexy.yaml @@ -7,6 +7,9 @@ stepping: dir_delay_us: 1 pulse_us: 2 disable_delay_us: 0 + +kinematics: + corexy: axes: shared_stepper_disable_pin: gpio.25:high @@ -21,15 +24,15 @@ axes: cycle: 1 positive_direction: true mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 + feed_mm_per_min: 200.000 + seek_mm_per_min: 400.000 settle_ms: 500 seek_scaler: 1.100 feed_scaler: 1.100 motor0: limit_all_pin: gpio.34:low - hard_limits: false + hard_limits: true pulloff_mm: 1.000 tmc_2209: uart: @@ -39,7 +42,7 @@ axes: mode: 8N1 addr: 1 r_sense_ohms: 0.110 - run_amps: 1.200 + run_amps: 1.500 hold_amps: 0.500 microsteps: 16 stallguard: 0 @@ -47,8 +50,8 @@ axes: toff_disable: 0 toff_stealthchop: 5 toff_coolstep: 3 - run_mode: StallGuard - homing_mode: StallGuard + run_mode: CoolStep + homing_mode: CoolStep use_enable: false step_pin: gpio.27 direction_pin: gpio.26 @@ -64,8 +67,8 @@ axes: cycle: 2 positive_direction: true mpos_mm: 150.000 - feed_mm_per_min: 100.000 - seek_mm_per_min: 200.000 + feed_mm_per_min: 200.000 + seek_mm_per_min: 400.000 settle_ms: 500 seek_scaler: 1.100 feed_scaler: 1.100 @@ -77,7 +80,7 @@ axes: tmc_2209: addr: 3 r_sense_ohms: 0.110 - run_amps: 1.200 + run_amps: 1.5200 hold_amps: 0.500 microsteps: 16 stallguard: 0 @@ -85,8 +88,8 @@ axes: toff_disable: 0 toff_stealthchop: 5 toff_coolstep: 3 - run_mode: StallGuard - homing_mode: StallGuard + run_mode: CoolStep + homing_mode: CoolStep use_enable: false step_pin: gpio.33 direction_pin: gpio.32:low From 25c11158bc464594c7192709d070bfb6f5692ae2 Mon Sep 17 00:00:00 2001 From: bdring Date: Tue, 3 May 2022 20:35:26 -0500 Subject: [PATCH 08/22] Update RuntimeSetting.cpp Get rid of an old debug message. --- FluidNC/src/Configuration/RuntimeSetting.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/FluidNC/src/Configuration/RuntimeSetting.cpp b/FluidNC/src/Configuration/RuntimeSetting.cpp index f9052a5d6..5e7ab0076 100644 --- a/FluidNC/src/Configuration/RuntimeSetting.cpp +++ b/FluidNC/src/Configuration/RuntimeSetting.cpp @@ -57,7 +57,6 @@ namespace Configuration { out_ << "$/" << setting_ << "=" << (value ? "true" : "false") << '\n'; } else { value = (!strcasecmp(newValue_, "true") || !strcasecmp(newValue_, "yes") || !strcasecmp(newValue_, "1")); - log_info("Bool value:" << value); } } } From 67dff435c2ef7928517805998b331aa7ee55f7d5 Mon Sep 17 00:00:00 2001 From: bdring Date: Tue, 10 May 2022 16:11:39 -0500 Subject: [PATCH 09/22] Update TrinamicSpiDriver.h This prevents the SPI from getting setup multiple times.. This was seen when axis config items were changed. --- FluidNC/src/Motors/TrinamicSpiDriver.h | 42 ++++++++++++++------------ 1 file changed, 23 insertions(+), 19 deletions(-) diff --git a/FluidNC/src/Motors/TrinamicSpiDriver.h b/FluidNC/src/Motors/TrinamicSpiDriver.h index f7ff43a4c..dd55b81fc 100644 --- a/FluidNC/src/Motors/TrinamicSpiDriver.h +++ b/FluidNC/src/Motors/TrinamicSpiDriver.h @@ -24,26 +24,29 @@ namespace MotorDrivers { // Configuration handlers: void afterParse() override { - if (daisy_chain_cs_id == 255) { - // Either it is not a daisy chain or this is the first daisy-chained TMC in the config file - Assert(_cs_pin.defined(), "TMC cs_pin: pin must be configured"); - if (_spi_index != -1) { - // This is the first daisy-chained TMC in the config file - // Do the cs pin mapping now and record the ID in daisy_chain_cs_id - _cs_pin.setAttr(Pin::Attr::Output | Pin::Attr::InitialOn); - _cs_mapping = PinMapper(_cs_pin); - daisy_chain_cs_id = _cs_mapping.pinId(); - set_bitnum(spi_index_mask, _spi_index); + if (!_spi_setup_done) { + if (daisy_chain_cs_id == 255) { + // Either it is not a daisy chain or this is the first daisy-chained TMC in the config file + Assert(_cs_pin.defined(), "TMC cs_pin: pin must be configured"); + if (_spi_index != -1) { + // This is the first daisy-chained TMC in the config file + // Do the cs pin mapping now and record the ID in daisy_chain_cs_id + _cs_pin.setAttr(Pin::Attr::Output | Pin::Attr::InitialOn); + _cs_mapping = PinMapper(_cs_pin); + daisy_chain_cs_id = _cs_mapping.pinId(); + set_bitnum(spi_index_mask, _spi_index); + } else { + // The TMC SPI is not daisy-chained + } } else { - // The TMC SPI is not daisy-chained + // This is another - not the first - daisy-chained TMC + Assert(_cs_pin.undefined(), "For daisy-chained TMC, cs_pin: pin must be configured only once"); + Assert(_spi_index != -1, "spi_index: must be configured on all daisy-chained TMCs"); + Assert(bitnum_is_false(spi_index_mask, _spi_index), "spi_index: must be unique among all daisy-chained TMCs"); + set_bitnum(spi_index_mask, _spi_index); } - } else { - // This is another - not the first - daisy-chained TMC - Assert(_cs_pin.undefined(), "For daisy-chained TMC, cs_pin: pin must be configured only once"); - Assert(_spi_index != -1, "spi_index: must be configured on all daisy-chained TMCs"); - Assert(bitnum_is_false(spi_index_mask, _spi_index), "spi_index: must be unique among all daisy-chained TMCs"); - set_bitnum(spi_index_mask, _spi_index); } + _spi_setup_done = true; } void validate() const override { StandardStepper::validate(); } @@ -63,8 +66,9 @@ namespace MotorDrivers { protected: Pin _cs_pin; // The chip select pin (can be the same for daisy chain) - int32_t _spi_index = -1; - const int _spi_freq = 100000; + int32_t _spi_index = -1; + const int _spi_freq = 100000; + bool _spi_setup_done = false; void config_message() override; From a00c3a874d0f98ee440c87007162be91c0e293f9 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Wed, 11 May 2022 08:10:31 -1000 Subject: [PATCH 10/22] Fixed #415 - equals character in setting value fails with WebUI --- FluidNC/src/WebUI/WebSettings.cpp | 28 ++++++++++++++++++++++------ 1 file changed, 22 insertions(+), 6 deletions(-) diff --git a/FluidNC/src/WebUI/WebSettings.cpp b/FluidNC/src/WebUI/WebSettings.cpp index f24d33f79..5d929b159 100644 --- a/FluidNC/src/WebUI/WebSettings.cpp +++ b/FluidNC/src/WebUI/WebSettings.cpp @@ -195,17 +195,33 @@ namespace WebUI { } static Error setWebSetting(char* parameter, AuthenticationLevel auth_level, Channel& out) { // ESP401 + // The string is of the form "P=name T=type V=value // We do not need the "T=" (type) parameter because the - // Setting objects know their own type - if (!split_params(parameter)) { + // Setting objects know their own type. We do not use + // split_params because if fails if the value string + // contains '=' + if (strncmp(parameter, "P=", strlen("P="))) { return Error::InvalidValue; } - char* sval = get_param("V", true); - const char* spos = get_param("P", false); - if (*spos == '\0') { - out << "Missing parameter" << '\n'; + char* spos = ¶meter[2]; + char* scan; + for (scan = spos; *scan != ' ' && *scan != '\0'; ++scan) {} + if (*scan == '\0') { return Error::InvalidValue; } + // *scan is ' ' so we have found the end of the spos string + *scan++ = '\0'; + + if (strncmp(scan, "T=", strlen("T="))) { + return Error::InvalidValue; + } + // Find the end of the T=type string + for (scan += strlen("T="); *scan != ' ' && *scan != '\0'; ++scan) {} + if (strncmp(scan, " V=", strlen(" V="))) { + return Error::InvalidValue; + } + char* sval = scan + strlen(" V="); + Error ret = do_command_or_setting(spos, sval, auth_level, out); return ret; } From fa63fd7effd240a873f266811a4c634e4435e964 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Sun, 15 May 2022 08:42:29 -1000 Subject: [PATCH 11/22] Create form-based issue template (#425) --- ISSUE_TEMPLATE/problem.yml | 63 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 63 insertions(+) create mode 100644 ISSUE_TEMPLATE/problem.yml diff --git a/ISSUE_TEMPLATE/problem.yml b/ISSUE_TEMPLATE/problem.yml new file mode 100644 index 000000000..528b90ef5 --- /dev/null +++ b/ISSUE_TEMPLATE/problem.yml @@ -0,0 +1,63 @@ +name: Problem Report +blank_issues_enabled: true +description: Report a problem with FluidNC +title: "[Problem]: " +labels: ["triage"] +body: + - type: markdown + attributes: + value: | + Please fill in the forms below. The better the information you provide, the better we can help you. + Information that you might think is irrelevant is often the key to solving the problem. + - type: textarea + id: controller-board + attributes: + label: Controller Board + description: | + Tell us which controller board you are using, for example 6-pack, MPCNC, MKS DLC32, XPro V5, etc. + If it is a custom board of your own design, tell us all about it and, if possible, provide a + photograph and a link to schematics. + required: true + - type: textarea + id: machine-description + attributes: + label: Machine Description + description: Tell us about your machine - is it a mill, router, laser engraver, or what? + validations: + required: true + - type: textarea + id: configuration-file + attributes: + label: Configuration file + description: Paste the contents of your machine configuration file (.yaml) here + render: yaml + validations: + required: true + - type: textarea + id: boot-messages + attributes: + label: Startup Messages + description: Paste the startup messages here. You can see them by sending "$ss" from FluidTerm, WebUI Console, or any sender's console. + render: shell + validations: + required: true + - type: input + id: user-interface + attributes: + label: User Interface Software + description: What user interface software are you using? + placeholder: E.g. WebUI, FluidTerm, UGS, Candle, ... + - type: textarea + id: what-happened + attributes: + label: What happened? + description: Also tell us, what did you expect to happen? The more detail, the better. + placeholder: Tell us what you did, what you expected to happen, what happened, and any other information that might help us understand your situation. + validations: + required: true + - type: textarea + id: logs + attributes: + label: Relevant log output + description: Please copy and paste any relevant log output. + render: shell From ff3f55a44940b6af5717ff8ffe5f2520eba3612f Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Mon, 16 May 2022 10:01:42 -1000 Subject: [PATCH 12/22] Forms-based issue submission (#430) * Create form-based issue template (#426) * Added config.yml file for issues (#427) * Rename ISSUE_TEMPLATE/config.yml to .github/ISSUE_TEMPLATE/config.yml * Update and rename ISSUE_TEMPLATE/problem.yml to .github/ISSUE_TEMPLATE/problem.yml * Update problem.yml * Update problem.yml * Update problem.yml * Update problem.yml * Update problem.yml * Update problem.yml * Update problem.yml * Update problem.yml * Update problem.yml * Update problem.yml * Allow images in Other Information box * Update problem.yml * Update problem.yml * Update problem.yml * Update problem.yml * Create feature.yml * Update feature.yml * Update feature.yml * Update feature.yml * Update config.yml * Delete bug-report.md * Delete feature_request.md * Delete general-discussion.md * Delete help_request.md * Delete problem-compiling-firmware.md --- .github/ISSUE_TEMPLATE/bug-report.md | 28 ------- .github/ISSUE_TEMPLATE/config.yml | 8 ++ .github/ISSUE_TEMPLATE/feature.yml | 63 +++++++++++++++ .github/ISSUE_TEMPLATE/feature_request.md | 18 ----- .github/ISSUE_TEMPLATE/general-discussion.md | 10 --- .github/ISSUE_TEMPLATE/help_request.md | 21 ----- .../problem-compiling-firmware.md | 18 ----- .github/ISSUE_TEMPLATE/problem.yml | 78 +++++++++++++++++++ 8 files changed, 149 insertions(+), 95 deletions(-) delete mode 100644 .github/ISSUE_TEMPLATE/bug-report.md create mode 100644 .github/ISSUE_TEMPLATE/config.yml create mode 100644 .github/ISSUE_TEMPLATE/feature.yml delete mode 100644 .github/ISSUE_TEMPLATE/feature_request.md delete mode 100644 .github/ISSUE_TEMPLATE/general-discussion.md delete mode 100644 .github/ISSUE_TEMPLATE/help_request.md delete mode 100644 .github/ISSUE_TEMPLATE/problem-compiling-firmware.md create mode 100644 .github/ISSUE_TEMPLATE/problem.yml diff --git a/.github/ISSUE_TEMPLATE/bug-report.md b/.github/ISSUE_TEMPLATE/bug-report.md deleted file mode 100644 index 967d7995c..000000000 --- a/.github/ISSUE_TEMPLATE/bug-report.md +++ /dev/null @@ -1,28 +0,0 @@ ---- -name: Bug Report -about: Use this template to report bugs. -title: '' -labels: -assignees: '' - ---- - -Please only submit bugs for the **latest** version of the code. You can check the version number in the startup messages. - -**Do not add the bug label**. The developers of this repo will do that after confirming the issue. - -Please provide the [FluidNC boot messages per this page](https://github.com/bdring/FluidNC/wiki/Requesting-Help#fluidnc-boot-messages). - -Please answer the following questions. - -What version of the firmware are you using? - -Is the problem repeatable? - -Under what conditions does the bug occur? - -**Important** If you paste firmware code, please use [Markdown Code and Syntax Highlighting](https://github.com/adam-p/markdown-here/wiki/Markdown-Cheatsheet#code) with language C++. Use the three back tick method. - -```C++ - #define EASIER_TO_READ true -``` diff --git a/.github/ISSUE_TEMPLATE/config.yml b/.github/ISSUE_TEMPLATE/config.yml new file mode 100644 index 000000000..32ca30b55 --- /dev/null +++ b/.github/ISSUE_TEMPLATE/config.yml @@ -0,0 +1,8 @@ +blank_issues_enabled: false +contact_links: + - name: General Questions + url: https://github.com/bdring/FluidNC/wiki/General-Questions + about: Please read our documentation which answers many questions + - name: Discord server + url: https://discord.com/invite/vGhne3QmFZ + about: Please ask and answer questions on our Discord server. diff --git a/.github/ISSUE_TEMPLATE/feature.yml b/.github/ISSUE_TEMPLATE/feature.yml new file mode 100644 index 000000000..7600b0d46 --- /dev/null +++ b/.github/ISSUE_TEMPLATE/feature.yml @@ -0,0 +1,63 @@ +name: Feature Request +description: Report a new FluidNC feature +title: "Feature: " +labels: ["enhancement"] +body: +- type: markdown + attributes: + value: Please describe the desired new capability in the forms below. +- type: textarea + id: context + attributes: + label: Machine Context + description: | + Tell us about the kind of machine or system context where the feature would be useful. + New features are often tied to machines with capabilities beyond the ordinary, widely-used setups. + We need to understand the big picture of what you are thinking. + placeholder: | + I am building a machine that can melt adamantium using a phaser powered + by dilithium crystals. Dilithium crystals can overheat if Klingons are nearby. + validations: + required: true +- type: textarea + id: feature-description + attributes: + label: Feature Description + description: | + Tell us, in great detail, how they new feature should work. If there is an existing system + that has something similar, you may reference it as supporting information, but please note + that we have little interest in adding features just because Marlin (for example) has them. + placeholder: | + FluidNC needs a way to sense that the dilithium crystals are too hot, in which + case it should send a text message to Starfleet Command over subspace radio. + validations: + required: true +- type: textarea + id: other-approaches + attributes: + label: Other Approaches + description: | + Tell us about other ways of solving the problem and why adding the feature directly + in FluidNC is better. + placeholder: | + I tried adding a Arduino-based heat sensor to the dilithium crystal stack. It correctly + identified the problem, but it needed to integrate with FluidNC more closely in order + to reconfigure the ESP32 radio to subspace mode. + validations: + required: true +- type: textarea + id: incentives + attributes: + label: How I Can Help + description: | + Developer time and money is quite limited and there are many competing demands on our time. + New features require design effort to ensure that they work well with existing features, + coding, testing on hardware, documentation, and long term support. Tell us how you can + contribute to the overall effort. + placeholder: | + I can provide the team with hardware to test the new feature. I will write the documentation + and support it in the long term by answering questions on Discord. I plan to sell my machine + to superheros with adamantium implants. I will sponsor FluidNC using whatever proceeds that + Wolverine does not slash to bits. + validations: + required: true diff --git a/.github/ISSUE_TEMPLATE/feature_request.md b/.github/ISSUE_TEMPLATE/feature_request.md deleted file mode 100644 index 6a2c7838f..000000000 --- a/.github/ISSUE_TEMPLATE/feature_request.md +++ /dev/null @@ -1,18 +0,0 @@ ---- -name: Feature request -about: Suggest an idea for this project -title: '' -labels: enhancement -assignees: '' - ---- - -**First:** Pleas consider discussing this on [Discord](https://discord.gg/MDsRDeNsTE) as a new thread on the fluidnc_help channel rather than posting as a Github issue - -**Please describe the feature you would like implemented** - -**Why do you think this would improve FluidNC?** - -**What do you need the feature for?** - -**Do you know of other users who need this feature?** diff --git a/.github/ISSUE_TEMPLATE/general-discussion.md b/.github/ISSUE_TEMPLATE/general-discussion.md deleted file mode 100644 index 6e1a4886a..000000000 --- a/.github/ISSUE_TEMPLATE/general-discussion.md +++ /dev/null @@ -1,10 +0,0 @@ ---- -name: General Discussion -about: A general topic of interest to the group -title: '' -labels: '' -assignees: '' - ---- - - diff --git a/.github/ISSUE_TEMPLATE/help_request.md b/.github/ISSUE_TEMPLATE/help_request.md deleted file mode 100644 index 8234032df..000000000 --- a/.github/ISSUE_TEMPLATE/help_request.md +++ /dev/null @@ -1,21 +0,0 @@ ---- -name: Help Request -about: Use this template to request help. -title: '' -labels: 'help wanted' -assignees: '' - ---- - -Please only request help for the **latest** version of the code. You can check the version number in the startup messages. - -Please read the entire [wiki section about requesting help](https://github.com/bdring/FluidNC/wiki/Requesting-Help). - -Please read the entire [FAQ section](https://github.com/bdring/FluidNC/wiki/FluidNC-FAQ). - -Please provide the [FluidNC boot messages per this page](https://github.com/bdring/FluidNC/wiki/Requesting-Help#fluidnc-boot-messages). - -What version of the firmware are you using? - -Insert boot messages below. - diff --git a/.github/ISSUE_TEMPLATE/problem-compiling-firmware.md b/.github/ISSUE_TEMPLATE/problem-compiling-firmware.md deleted file mode 100644 index bb150e1b6..000000000 --- a/.github/ISSUE_TEMPLATE/problem-compiling-firmware.md +++ /dev/null @@ -1,18 +0,0 @@ ---- -name: Problem Compiling Firmware -about: Use this template to submit compiling issues -title: Problems Compiling Firmware -labels: help wanted -assignees: '' - ---- - -Please answer the following questions: - -Have you read the [wiki regarding how to compile](https://github.com/bdring/FluidNC/wiki/Compiling-the-firmware)? - -Are you using the main or Devt branches of FluidNC? - -Have you made any edits or configuration changes (list them) to the firmware? - -Please paste the complete output from the PlatformIO compilation here: diff --git a/.github/ISSUE_TEMPLATE/problem.yml b/.github/ISSUE_TEMPLATE/problem.yml new file mode 100644 index 000000000..b2f0eb762 --- /dev/null +++ b/.github/ISSUE_TEMPLATE/problem.yml @@ -0,0 +1,78 @@ +name: Problem Report +description: Report a problem with FluidNC +title: "Problem: " +labels: ["triage"] +body: +- type: markdown + attributes: + value: Please fill in the forms below. The better the information you provide, the better we can help you. Information that you might think is irrelevant is often the key to solving the problem. +- type: textarea + id: controller-board + attributes: + label: Controller Board + description: | + Tell us which controller board you are using, for example 6-pack, MPCNC, MKS DLC32, XPro V5, etc. + If it listed at https://github.com/bdring/FluidNC/wiki/Hardware-that-Runs-FluidNC , just give + the name. If it is not, provide a photo and a link to documentation. If it a custom board of + your own design, tell us all about it and, if possible, provide a photo and a link to schematics. + value: 6-pack + validations: + required: true +- type: checkboxes + id: vendor-help + attributes: + label: Help From Board Vendor + description: If the board is not one of Bart Dring's designs, have you asked the board vendor for help? + options: + - label: "Yes" + - label: "No" + - label: "Not Applicable" +- type: textarea + id: machine-description + attributes: + label: Machine Description + description: Tell us about your machine - is it a mill, router, laser engraver, or what? + placeholder: Gantry router with external DM542 stepper drivers, dual Y motors, optical endstops on all axes. Spindle is a DeWalt DW618M router. + validations: + required: true +- type: textarea + id: configuration-file + attributes: + label: Configuration file + description: Paste the contents of your machine configuration file (.yaml) here + placeholder: + render: yaml + validations: + required: true +- type: textarea + id: boot-messages + attributes: + label: Startup Messages + description: | + Paste the startup messages here. You can see them by sending "$ss" from FluidTerm, WebUI Console, or any sender's console. + Look through the messages for any MSG:ERR or MSG:WARN lines. They indicate problems in your config file. You might be able + to solve the problem yourself. + placeholder: + render: text + validations: + required: true +- type: input + id: user-interface + attributes: + label: User Interface Software + description: What user interface software are you using when the problem happens? List all that you have tried. + placeholder: E.g. WebUI, FluidTerm, UGS, Candle, ... +- type: textarea + id: what-happened + attributes: + label: What happened? + description: Tell use exactly what you did, what you expected to happen, and what happened instead. The more detail, the better. + placeholder: I did something, expected this, and that happened + validations: + required: true +- type: textarea + id: other-info + attributes: + label: Other Information + description: Please add any other information that might help us understand your situation. Context is crucial! + placeholder: Log messages from the console, screenshots, or anything else of interest. From ec29ec0189b921e08972503e88daeddf28ec3b67 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Mon, 16 May 2022 10:08:39 -1000 Subject: [PATCH 13/22] Make it work with platformio version 6 --- platformio.ini | 16 ++++++++++++++-- 1 file changed, 14 insertions(+), 2 deletions(-) diff --git a/platformio.ini b/platformio.ini index 5bd2b7d36..8ae84bbae 100644 --- a/platformio.ini +++ b/platformio.ini @@ -65,10 +65,14 @@ monitor_flags = monitor_filters=esp32_exception_decoder board_build.f_flash = 80000000L build_flags = ${common.build_flags} +# src_filter is deprecated in platformio version 6 +# It is included here so we can still compile with version 5 +# We should remove it at some point src_filter = +<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> + - -<.git/> - - - -test_build_project_src = true + - - +build_src_filter = + +<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> + lib_extra_dirs = libraries @@ -98,11 +102,19 @@ build_flags = ${common.build_flags} -DENABLE_BLUETOOTH -DENABLE_WIFI [env:native] platform = native +# src_filter and test_build_project_src are deprecated in platformio version 6 +# They are included here so we can still compile with version 5 +# We should remove them at some point test_build_project_src = true src_filter = +<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> + -<.git/> - - - + - - - +test_build_src = true +build_src_filter = + +<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> + + + + - - build_flags = -IX86TestSupport -std=c++17 -limagehlp lib_compat_mode = off lib_deps = From 1bac1124332481c03e2844ecbcb1d1d060706683 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 17 May 2022 06:58:15 -1000 Subject: [PATCH 14/22] FluidTerm refresh (#432) * Make it work with platformio version 6 * fluidterm with Ctrl-Q, macro overrides, error -5 handling --- fluidterm/fluidterm.exe | Bin 2361105 -> 2362930 bytes platformio.ini | 16 ++++++++++++++-- 2 files changed, 14 insertions(+), 2 deletions(-) diff --git a/fluidterm/fluidterm.exe b/fluidterm/fluidterm.exe index 8ed54dbf53add42bc5b76e600fbd7d640ce01e69..e8f945a48b32492ecbdb5cfb32cce6e0d978dd09 100644 GIT binary patch delta 364062 zcmb?^d3;P)8}OWSXXegCHY5=d1S4V(f~YN##2O@$kdj1H5E>elkk*orXfqvYQx`{D zOM;fR+9J4=5`>_Z*kh}-;x%bhLoKo9d!BP=VkrIo_`d#rujia+KhJs2a?d%F_w!G4 z$(9wlBsbgR@X5?~RDaf0eLYsCDpQH14xtTI*>zN^xX;&gqx~;_eyI&jsmGeFuk)4^ zK-{&SlCx?D{k)k6>$9?fj;gYy1;o4C98Z->l?PHy04@S(^Iw1}zOcjl3FA`6sZ{aj zflvtaQh?t{zY!0|dxr!NwO6SQ16&|!X+Ou5dO*!}R;gS74wgpJRwPcE2mi)P-@w1` zNGIUm1nB|%>mxN0T9LP;{_t<4G!6b8DJ_G4qoqCY?{Cuogf!nzuMt(T+E4@kncu&o zQkh%_ei)`&dn*h6F~dLkOO}MGjLzo%w^gdl-iPz0Pt_hY_?q;c`fV|u1ggxzRg#@1 zwBDlpA*jbQ8MuQD_U2E2lM*$Z>6Rzb3QauGNzXJB=*DMKg0@9F4VVE|Uu~eO##IgK zGjFNahJsZIABdRZoVwF z*Ll$am!;u4Z;~a=)V1vT2vk?Be^yh|sj%Yi^O_paH8Iz0LW3#Zs+`@eAlBffeX+(L z{3K8@JN_w^=$g>m6;hS15lNBk_07eNQWykqj?`5@jHd0D7V3Sx<^U@5md?0;;pr4T zG%#)V5LL}-Y^fWxw3Asnu5TzN4+vE4^$L;x()S<(rB-%c30^ygsLb(y+NpAn9EdXB z$h_rl3eiDe)gZ}fkri*I9j>&}A~J6!n1<@iAI%h03ky@c&@TLks524L_jX-qhZL#I zt_A%dLekXfHtxX=81xD;EbjmI`Cxd_SUAy7FXML=E|F6Gy0 zPp73yC3W2B$Z*MAr;~q+aJ|Y{ij4Y3L}fgnusYOY|M5_;S3tqTFe~p>4=LQlRGI%)Q2{r{e+YNi6$QiINbkqZi(w^!DQa7iTbljXek&|RHd~?AF%1*sL2W1 z1|fqi8=_ZLPQgCIP+p&`wZwa;>x=yP1$ij&SevjB5zf|*UNuBN+(NggZx8CZ05_2i z+)5`-0Hvnbrts93uad?vXiKk2-u04(e3FP= z{m?Qf|0*0}Y24i)47?6W`^-y$3FQ7jxgOW7DT$QXKv6sicPY49FNsj$S80gLTeSG7 z^s!4D`s;D2z-59<$#RN$inc{%;BI%5+PTi9eV0q$yEdX8Zqi}bCX_Ch%&uL$k25Q` zJ7f_K^IiYKe9NRjw?x|ARr=oTsdwPAS0y_B3)6U+bi6@>5Vb<6te*?sxLWl8y_CyW z+<`%7iJTAGmFmMt{4Uu}WehPJqi*HEzc9|WwUk=BH?mX1+J#I>^`&9%{b*QyX|a0< z)z_DrHEKfdERi0$8@zvA@~UGy|AkqNIqX79)1Iu2Jg(puX;HBUzo9rB~v4VOOINDwHKQ@O9vWtqu)D8PZ~99+8Ne!bnZ(h zfFbv4Q!oRQa?m6x*V{uH?x}H18_UzMl@FxTigVKD7LBC8yNObkr*nFl3@b*93!Gkf zdaw#Yk$SPVZOsnw<(V@*KX1zvrZAZgAA&{qDomizUcSJM0>rCJ50~HblDxAbpKb|L zz77`jni2@9`Ex}XL{(+3qbP&*$WIv^ z?Nw|Ig58xe-0ndTUNi<;hwV_947E(yoB2A)tBGg23hZ0@&E5Pi;CEDm^Ds?j6{dCv zajcogXzRc_?6kBnt1zYcPE{(P65rwr4kssxbuj$CZJ>LT&p=l|Rt{Hsj{ENk{^P31 zcLGKigSiei2$RUUNVypK%((g?gq_6A4mj?4cT4)h> zVsX4+b>7FU(!)3ixtBTjp6Ua8P~v(JltjV;V$DqGMFUzj00HRSwPY}C-UTa()1E?b zB!9(HOoQx@znr$i{{RR47T$ETAGmG)?BC3{f%*2!%x0aXiCz$XY+*GRIu!CZuAl*V zLvXa1Fr--$(0K(d<%Il&ypj6}&{E$Aywmmob#}-t)tsMu8Ivzo2ey$L~n1 z)!RkU3)7*!rt(`@_$0@s?&+peFg8sZaJPy;N@8!vU~i9tosU`j5`G5a`|^EK9t^P0 zyX#fv1T{t=4_mPx#{^eW*SrYOpy?Boa6nD75dk4z0T>|gQ22s->Bjvi4irr0pI!>| z^s}{rUS}ir_>^s{LKUW*kkjB&-?wo}LFcx`3NV-CgzU(PI*rqd(H?h1tNr-Y0**NA zu+hG~fIMeKuS?%cbu`7ktR4+_C1Y7?yb3=$oMGHWgyDY0$s&@((F6*nRCKnBCU1XTcx1f|B1DwJ<-Bfkseal*J~jq!J= z5SXk9^JPi8!ck@AFur8+@@Z}|C*%x75U(e#HHxm%fYZ>c`$j-lyi z6Tf*UmFVCgH=Z)@RXPA=PY=e1>^Y@`M==QXjyjAGP>TFvISK~OP*7(cTMb_l-Jte1 z*21yoV_pW?Q`s!ty!=m?CBU#UpRBHJ{t8D-N0?7m!Q5-j$f>9o_rE;l-x~>QU~jBp z=*MBLBi1lrLC9GjYF6i(gL8@~I%u#c>Y@x8H>fHL=2K!>_jNn-aLwu!XR{~fF}o#A zZQ<48?U6h;{W`&7HTRfxZR`S*2DGz3Vkb$PS~Rz}>>*tJVM&sjc)LjtTGS=wlFnd| z+Is7yu7>&m>q>7M>X9%h$1N0TegKmjJI31AZBT9%a+L1 z4CehMxRi=Jpz~Fg4Ka$FY`V`uI@YoU*H_&Vt>`5e?*<^>&btRGk|uilP`fd(w`%Ix zBZ9YOq91r2d&IJ@(n)3BO~@Ll#=8gIeMow%Rj&@7@HNjjH`Ya5+>r;(s?_ZG1I*U$ ze_?@!OwEzjwHiV0N)KBFk}|1>Ph$tO;+s$mNzh*!@6!d2XxJ-wv$W5rrAOhgP(H++ zVeB3XaK>_Gp(k|Pqs6Tg>)TQl^l#Ga){RJWiM4J;9!q;$FNF4mv>8Y0N$cBmC%)1( z__tJQ(Dr2?5~aYl!BV@H?$XM(^Cf?ux>Cn>4lj8bFAZupy@>`K2HOwe!xc71rjYWS zFi+ft@Ilc`Ds2}++DT2?`@+A&+qZR1>m9%+8SE6u1qAuY(r4|P58lO{$rY)*!$>Ii?1<&8j_n&)SvwDc3EKf@NSylMUIMzOlTLK(m0o1w zaIqwoQ|Y-1@RI zs149aFv6F-_xABDv&}uhRDo%gF8uAh=Q&_=oQ-GfmCrcgz3OeQ_d}Aw% z?~4X4v2avgF(198_%hkXm-0eeU%GJv>1y*Qz-rzN6H;YQjQo5Xi2{(owZt+P8V+*z zp>3A-{Ij1Uaw|!$Da4G?84I&86mezAS(pfWAsiJCp}7?yK*{A3L$q<|S<7KavGhSF zHzG*6omxO5ZSCYwdP#qE@~Z1+X$o$Cl*Tvd+=w)j-s;?U)Sb8RU}On6oU_yqEkqjl z<}Mo?M{9KtA)Qn9nb-N?u>&$=G7pA5!hUF^E*ti3ISV&d0vbGp^&)?VRMNR+f2G?q zt3OmG8AoU;PSN?nJRNEkbpWmSm08gl?Bk|6)e|@ufdlwOmn`+{(jlF2H$#CTXKBJ~ z+-!Cb-9$P#jbc@;lvPu~?K9^=J!c^o-Dj4d!VkDAPQo?<`zgn!pYH!++p_}-p;shx z7e6vgYV6mbuQf2!iqPU5w7Abqxb`_pU?K(QOkO=Sh1J(4Ib`(65^=l8VY z_k!-dVo5{Q?IEg4ea?1>348#%`=3ea4Xae|qT2;O^tPi^^+&By32aQn&u$D+?PWKljDGXPcGscY>AIu|+Di|YONWAd>7jC|I%tN-%7L=E zTzWtF12F?7KD{B`g>nj(=iHFq5BWeGh2(8$NzYh+XK)oJF?LtGu9jJRxxs(>VKy*Ss8s8`& zLmyCjyIguSyaT;oF0~Gur!RqqS9<5nRB;=>UzZMsjTXPfXzaW$d55RcpRaSDPF|O` zhmRJQA!WmLslkYQbeiIAdb#8sG1_?q`qds3S?(}UpW`GzW=pu=bjtc!FP#b-M*S73 z@N&r`aR`DPHF2C>dr)bE?Q}yr zH}OllMG2T(E`2g-6Scb`^-63=uarxp68-44aw#XVG5w>wU}NIf#Hlkjzn$@cO{Y=6 z>jkM(5`=nPfo7ifE3B*o_(})OsGM3t2V5`sWtvIA(KPsdncgUugc*zIkn7UtGg{CQ z5Y-u}%@6+%&ZuFKoDrvsY5Do09vS_nOqZ2^uaKkHZPvzRW^m%*2F;R2%X7BUAPv) zC4KNwBRcqc!LpC0l4i%SHODJk=VDj>yFn*z78tTm)xkmf5N=lgD3|_TvayXBg18fQ ze5!xGamrc&5j3S3y!M_1RTgZD8^@f!S#WS^a{;6aDwfY72q%4cpP-t!6&DfoSSfqg zYBQckeGZ`bg)YRUxau9)bazgAgp* zJOmpxZbw^5z2zrl-?rr`@xTVcmcgsy&|O%E&E`6t`QF6<62ES3f)bTmS6BtNZtIPz z{@K>~)yC$)(dz3OJ7l{HRiq~&h+ENCy1yg$MJE~0!zHl+Lwgj?OkSfw`f2B!SB<&D z*X(Op3&MYnCg|VyyFNqEYxkH}C3n7FQu<~0XRor}ffJ0^8F~K~S1o8SFdjI8$s@g8 z`~+H7F!J!!e`Nq%rM^~0#Ss&wS8f)}JQhW%uA<=hi5Y}u+?V>5?4Y+EN>59=)1rq` z*HhhT_CskJfK3mj^`|mv=|idA=@_c2mOeS%ovwH&9RP6dX2H|b$y66#1uLL2zN#SQ z+-*vaRTLzY4kfgtLMphpfSM}`x?j2>&^mt>H2LjwLZ4O?Y`#`asPmuF_rJHMWq(TN ze;-9RR2FpnBT@?+hk}LX3=ORsS|HxOOUNea@!#FOGT@re$z@@DUn#%J7tRt+SNYK7-O|%4kNzoeE1xsr-k7+tv9O)OOY0ifMX=2`rIwoJ zUg`84zItn1V*p`1P~)0_Fyw5F>vCQw$q6ar0=uP{JI%#pP_;G%F8}Y0>4jxDmCHx< zaH3xO+5!Aq_Y4jLT@CPQ!*xf4s$$r+>eZ@3uFP5TygS8d3ACGp&|g(=~#5At%Pb&*~vTa3fv* z9E1x4kl9>#3#Kd>kZ@qkFBCw!&%Gbv)9bH$QEoomGiNwG-%{g>UqT=pStCW?Z|UY$ z!>y^!Gx3xyMY)@=k)-?a@$t(-RqgSg%xcl;)33m0W_2B>PouzkKBD2PaA6K$^AjwU z45*lTCqivk5~6CHvf2alE@UEIUHX<<1aG7s3#e-gh;ig*z0u?g&(akcNA+al5CE+; z^$vrF9;U8I(oc`viMw?8Q5&*B`sdNRBtRPbxG|LHJ`RQQ(Z{|}e)8A=|9U;iC;rm@ zC*8@4g2zufYU!04xh*AUiQudXm8qKO9EB1nIn*PLYPv`*H+CcG0xeU^s~VDgO1&D& zfu1DIfmW;KU9HKxdY8Q3fvQy3i4TLEtHm8&T?17=Z}OMl>O$rSbW=BZM>pa{pujG5 zC+85c*`L5<4Ta-9$SOirgV@xbWEKq=B>%4`afLhLeDqnXr8n0nB zL8LiN(6AQ4WHFthk>z00LetJu8wzh{3`u*Pp%Q_7u^_?PtUeOa~1ehXr0WxAJY3YbV z1s@OL*elb@9}Oj8g!r=y!$=@Bx#4gU3Qe6joD4IO^pfHylT15gK5}7QaKfBI3w9#0UsS7MVcSQZGmLD1lr; z!np~gH?`kn7pl4%YzQcAxz0{*l1QdgnrA0}K7|m0uCrrHrb3`L*s))xLbtE5lNU`R z=Ltx&gk)%n%8@NfCM#%}18Xy#{8-1!Ayn0R-xd4gz;Jy!5aRW0{`y?c{cO5Mo+wCx4hv{(xo9PLBJU6v8K^o$R%NoYc@Xdv@ms z@;{nt&o2H*y3y(OtnN>wGflK-AwQ8AzeV=o?5X(`U11enc;t#hF4V7Rmczf7gALJF z9P*&_+rD|u@HQ-3!ECT+=YAr?F?ima$OJ-*>{-rc(pi5DMg5MuJFvr>$w<1xo_TE{ zE$Z(EbYmY2*%ZhQv$4kztB4^m3Ae4RKrTFKTw% zv$EY}7(He$`~E_HrS9kgaE3wl)_@U*La3K&itOe3g`|%Iy=KoMj+16}N&)?|2WZS&|pM7s6)65)HW3dTP&FULbRTYt04XrL!-Bi{ISb znwEtC*`8}8nAw$)0FuInl)GWia}X_lgCUTHrAYELy_6)>D@j zH7z$fq88u47;c3*NuBI-lkLLEH!bOVap~q%TO;%G`s+{76k1 zeq!WTL%F7`_6slnUOp49lf?8Dww^33G#*G9VCsrapjTTgy3cc!DGqC&;E-BEWKFH zo?Iu5AWs^U!;HIu^(iMIbr17E+2c@0YpxsEl5$9<4QyLEOoZ#$-Ez`_B(P>Th+HyfJF0SUsjM-0QOgqg`|WH{F4}npFH(X z(v|@Bi%Rl7G{^oHcewp6m`Y+Pc5z`xU`y1E_fX<5@Sx9mfmVM)jQwXcR;0I2hKf(>F}0QP!<6N`IDS~=Q-QA=Xv+pl5LLs)+k z*tv%!wCxJuHsAdb^@idG{U6H~9Ci}%Cj7!qfNg{h-22ptg;qnW53`@DNgEKqR886e z5Fe3)(DTP15qEU<<|ERk9d}j>cgC=XG{OLaeLrs?G`$Mn?!Zd`RYhZ*Ze5dD@5iJa zbzZ~XeN1{G{PrqCE*VEK;>23?Q@zu3nCgAlfakDxa9JbIdroSI>k1{m(a$_5a0&C|*3!i^2lT)`(g#+7 zL4-!xVO~K}!T4kw2<;EU<8MOIrjF8{0D>tzE#JW4*mpQ}U&DT(G!~(!Kt~`<7N|eM z?*!UK*Mx)O@uLg5NOm`R z1w|%yr#q0t%O8xP@}qCj-x2=MldeID@LqHpm)O^bUPp;<`qD2@A~1k%;u8P#qyM0U zIfzEHy}?vu1A=K9Im-%zX@&(6LT3VEPY6wc>AFjQIuB}F`qK=o4WJ)F?Z*Lh0jlpj zknSfX^8JA{4r9oo2Gb|xtQU-Nw_8IM1Gmv@Q?KsYH4TJzF=KE=P_&Q)o9Hn3+km91$^7K|3nx^B$eA#Bw@4 zh9aN6Pgf#GhZ&S{k>XV7NpSevnKTMRr(wb@ItAJ{Z5Ew@64z(ZmC*e8X*8F&tp0~k zKPzwkka|&9Pn@r2ro((yYJTryKD)s9`rjOyL%r6p)VVYq;o-S7-3hZ9Mrg_<%TO6P zkG6;DWZp9B!B)+qzV(m+hZPPHCFNP!JnBu3F)^LC16IFu+Q%K2Zd?dk!7Ms4*JkUwnDfeg9d=5 ziVWHfW;`!g$LjMYwwP5@1GbdKG>r|IPrJO%-$nE3Xc+!C=Tjd#*_qW{KwbI4j&(bN zO#}DhoLSEWw7ok{4LR_b2(FiN;AN9_=E-0g3upvQ;}y#sv^JA=qN;lAd?uZa(H@iqi39M9EXX8)OBd3C2(K+v+Uoof9qGthb!R&7 zF`%V<1QS*gTk#R?L+-K5A5mYZ*?&xf$UQmiV|tO;PI6t0)SLH1_=6z$G7iF5;i^<; zzR^fy(~Z>K2YYEm=B`b=!9jf1O9{?@O%HE2(uTxG{?$mk<3>s_(Jx?xt~AjwsNFVE zKj?-Qiy#a-)_)Q03dlK1ZS^7$)Uln5=opg7Tyy9+QpINFK-{X>uKhl_LNQil(uoh*B&FFq2}F_ z;VQtQ^ep?~Qy2`8J|{n=EfC)O6qYMkc{+SXy9wasgvGQUtOpww(@s#kw3yCwtjgh; ziUF!|O=c4%m^ggc4-$RHSp`m-2Dn3t@?lWInl7R4-Ohq(+_d4&&oT%gl@xg$Nbvok z_3+9#%Y`$-G_`~#Lx6r;LdQ8^>rD|ZpxD&ahlMVs>FDh7rPQZGBG(SzA*t@5m1jrf zJMfDayopdg1`c3nrzlj`Vj1o4it6x-0FK`>fepfeYGFW!q1uvV)ZLvcdT$&kLQgB) zAmUv8G6pjiF!?j;<@~~SV@_m=40_s!tztAvnPC#(%`5zf3er^(XS(I|9DEb}wj2_* zPn1NU(xOeE5D-65IU}) zw-G*HL0fchhx6G3coC8L>UPry{D*9^&u~_@n?(RE+fA3cEP5p!2m?QVCH40StqWUA zc;X3rF<<^=qI~1qe45}3zCLwjvWohX`aWo~1H?MBXH7~&p!lp|p{rp!0+_m*wnpFb zR@24^_pXKw4B%^4Q&)hpTORGNriI_haqA$#u(0N9no8XL@k6VoWu*1189EBTzjnwS z*VDHIdZk!?_d8e$$!vD(d)TlHU|t((wrBY;aJ*@?h+li=oA1HfMm*)t%`GP7!&uQq z>X&X94jg-N*Z>E!cs*FfQ)dJ)E7;m2jgBn>bR9i0E9+JiIwIeE;1iMiHs4NNFu-Z+G3h9WRihm)*xPrxVi zdyZ%I7C9qsm6O-9Uw)vCJm;WqPJ!^EAAFOi*|c`faCYwp8tuAd9cXwm6lZ>?g$FUi z9hR?S<9>vl)sl5=$B(pGx8=Z6c{bM+Z15C_aX^(RP;DG=&)A;hcMG8gPorJs)=q`S zqkA}Nxv>Na%;_iUUC%RI$)xzRFcZMK=ip{=uY~H8Yu8B{)sln`u3k_a9gh6 zjJZ)mzJ}m3Y5r*{G*$H)MJ+ec_Pzm|-~$}~E7l}H32V@qwf_}smP2@9vIBY|(3Y=d z3pT+*GiUvQO_aROyK|fAOnPrP8@h$AMtFM*{S0Ax0gNnwKNKkVVOtgawXL+Fdv+Xz zx#lmmDrbnnJZl+3&tf5A9CO}AeOx(puZ7wjsGKx(8*QYJKC_TSD{1aF8b|%Y*wt-d z3*fx%U<;s=3_bwtEi3rnWChQCIE+5@t)t;S++1w&Vcj^Ew*!3O)EYa5x*n*-0+6om z03SH%q=hugN^;l<%e!Hl+4U)V$aZ1H{e zD)?D@X-m$x7y3D2oLmGq(r`L?QvP8-Y*gviFxI|^_NCy)v?7pz`uZZ!WP@*VP{EHn z2%3Oz-a*g=aNR)~nSL(}+WXTLWgxSWHmQx2ilsn#X_)FD6V2%s{z@7IN(Hi|eE@4Qp!nCqK-!nRDPk6t7iMdf}K&w31-(z|W%j^o-9>aPU7n z%#Ie*mY}f;G}4WSneH%5w(D5nVe01H;m8XEMt6$=Pzg3ry?G_avAKt7GZ0w~B2;yR z$%koRx-T~Ur;C=*M%aWFDHThB!b6*R3*YPULHco;4|j6?OZ0HWJ~p^X$`7 z+J&Ax&kmHrl97Cw2^VQxzr@Qg%>g@{A<{N;!j9}$>VB`(V-Cw}FVcJsO*p~&U!zC# z8&2@orR`40?q#&ST7TrEwLYvIK6v!ItaR4we{{c1_16FB7dF*TZ_*nrYnfr%jl~d$ z!ampXonK31%guBs1%o%ubcKdS9%Bn{(_i$kY5SOc2s*3kM(6NG*=&q-0V$w^U^=e+bEA(NIkD|*VD z6+Kn(O-Tf}kgCgqs1QNJ>ayijs9=Fqs4p)Ogn3$8xShG!34yfg9X7m<(3u(Sgb!%Z zcBZZ)45F&>h+IqCZDaT90FzGw*4XuorDUwz511XQdd|-4X5Qc^@JuIF}S|44iK!Wz5wg;X_oII z{0NM4xT~;)AmXN*umchK4TLg1ie@$w98gqV+#CXcm^5EwqN$iVN7jHi9e5 z^%0iR!ufKm)&iXEBy;Rm>bpRm)mCUj=w;d_4&N+f%O!qS4@MYrBmU=`Hxj< zr-ksffnNz-Mj?45lJSNM6;Q+kBc_kSysU;dLV(|f{NHfdcD(!vERpk{J9C~y_^g}%+>@7cdHEjK@6YuZIKHSm z92(Dm?#C0gTvWspyLqtHHa?k>Ik7XEtjL7aW%&fg>e`-9Zk|NY*$?=Pv*(&_b8z`O&Y;8BZbZ$DM}k0553ZcIpHjP zq|n6KehMgv)+sGhZ5_eVM+%`}8I3?g(~aB)A%FX+(oj!W8Npi!E%( zR*Vwr(#RHD?NZg8KE2D+Z&VDcH(?zgr(O{+gCF~*?!EXcB zw-~2)1_| zSV?;cyDoxNB6h<|Sal?8@D3!Q=NWn7JHkF#17|S*M4>5}!J-p|ws6D0Bth6h%Tk#C zWWc7d=*hwmlFGJD5T?~wl+96D8cUoY45n3SaE1U=paQ zn!{3(gc{e-GcdES3stuICSnTk>K!mw+2n-HWgDh~=J>hn-c(#f=dzS(0z7}7C!41U z@F=C^L)I->$gj(F1Pl^YDDTrdIm5CE%TP>hn$P^ETTPV@ur&pH2fiFhy@kWWL;$X}!i+3+CpB5N^QSgAjAiEoZ~T$GQ@7Je7> zVenZ1Gb7Xs(uD>@|3538oyiaqY^nkCg()`Gg84#5%UWiL$;!SjZ^lY)Vz z3xw5LdiW~qW)!~FfBzddoO@L^8--xC-UoKk;0V;aeku^E-(#h-zPZ9yo9feCLAI&x z{#>}(vX&VfY2OhXiFvVWucfiWi-jQ+47f@{a2-0agpFAxq|&O5^66E=QGw1p!&a>k z7SpiJa_6;zj?jPt)@z;67UAS|f-em#U|+2h{OO{{^0{?_D@1v#!T^vnXdB@Ql;ulfjXz{Z1Z=58`;K6*F$P-+R6+YAn8=w*b;IGkc<4?z|=|}n&n-kLMMVd$=er&#_-xK zLUywX|H#p0^b37|o+z0pdjg@+Xv+@VkLVu$7R_cw< zGN4b9J3r=~xn1t{MEK5udU?raow~P(g;vh$n`)Z3ojJRz&D8m{{Mc0uj}U#f$&DJQ zAKAkOLv}N$2NJq&JBx1#EKg6#gS{;*@3uk~{{(rWpZXGoy|CP`yZUWHH*9As{neG! z>zw>a5B1MlRM$U1{XZ=(w;p$km5xke%#HrzKw!B2{7q9+?;=F}ED~9>X6vfijGW%JFJ%93Ax&)C-~E@|Ovyy`)6m zG7+`IwruodtM+$BywE-p%5T#C3H*p((LQDh*DhyHQEw$wcb4@?Qbz%lbCcAqFnIFL zseqvO&dAQmYIqC)K_efk;o@zEIu*z0o*C+dZZmNjo-mLr<>j|+%0r=S>xcx*V0^_L{8@ZB{D@)&}-}VeM9cr7V9t zTb)MhM&oseKY`zMI&CjJkeeUPI?q#IfR~FWL(n!H#Zk)`gVrkj?@i?h|u)2Oq@ z((Rg6G~R=aBmg&gum=cLjo2~@Fsu>lCIHN9B%c>F^I$Fcij7==3@g|JgkdY#vP@)H z!MbGutXjd&BMew6&s?ZU@Wh$sO1@?ut=h_B)@X9@ySQ?VW*W`dCXZRGacV&0kF%to zfg$fWyY(|LlpSZYcL9U%3Au8Y<{LE)yT+tK&3d8mWC-iMPH4jmQ`QL`X~{|U)jrKN zL3PSP!2+i^pJJEyYbu2*KVU=#?w+d;0>AGW7IX;s;?J`Zg**XZ4c zEwmpYqy}v?a>f|6=Lk)zmb-Xs_3$|Og50N-wkMzMX8UO2?d`1#@{e6Cm`XowM@JfV zRrUHAFqu9D96WZ7YKCs1-X2@wu6RlxFEYs z*49_k&?~Iq2Ydxv{yt4hcby@B=Lwga9OMo!*6+)WUU7%Sf zS#+Cs@%u?O8mY{4!lDBOxL~JDt!|C*(u( zwSN+Qh4nyE-kGU|-Wh#TKAWWtBl^+SlS|hABW)$(JwDb>BQ)eB`y^X?N*`jS%Lzv9 zuhiAUT8CL7AD#)r+~RSP1uxQmrmrQjD~q%-Hr2o!?RNU!N%>KZwuib&M?6}HYNJ-p zIW0diMR;Gfm_2Q}N@#XtNAF9dW06?zN+AQj9})urZM3p%L{qCPP!`=oXp%2uA#ChA?300BCtMB4(<^Gmev z*`OblXj`HMuTxr2;?LOwpYo#zvK+qC&5m2)xAAbH(SNYoa^+e~6fPdg%ze6IV3bo% zYkN4MJ3sxdy~ih*udi$W;)NwQv~YF_r1YCwct!+;_bM!fv6Wg!-kSIRQVJ~nZ|z>% zD~1JBX?xMI7&fm;I}E)(QKfxH--|a!4d@Zm+IX9)_g!rhY+L`k zS}p0wrIki$B&AWkTU#4txp^!moGVZbQnUZjo>bG6z`^jaKck+!z)s77l?=-}hBhKPNL zez5f(fQ3@=H^jFS#3(|$9%q?qu~^^LN|z%v;(F?8XRX87JP*IPgxs<_&YX0jq^~8h z?{#9VO|`CG+)l?HmyhVhBSMp=puv3qM`-<=7uOev1XXZbu*pIES^uIs!%>X3sh)Kd z57{(ktrKX}uc{SJtuIb`QI&7h7jM!Rb#~6}C2~juF+$xo9(vU5^s&+#4^_3jQB06h zasMMhxv|PGtH%yB5)A=maG-2z>;q?dhXU%gGxgUM2k6co1^)x^{VD(#rN*EA6bE=J zH7|u`ID3?}@)RR%kLBj$iCq20VjRL578qQpYsT(17JDPIOB01CSs*96G!>(e_-<1% z^#9$dhfTpL>uF+!mwo~K#OAsen1%Dipk@l>W{aAEPkMqg`r4^HP{!ae$YC;1gAGfY14(>_`i-F?lS2?w+*q#8=L}SqgMaloI2bJoPtjfFCYD4 z63f>5fH^pp6k02g`;^rhd;;VF3$jHU8{)b);1dv^v=IlS?|96!M*+_Jc+Eut?nime zQvqJT@|xiU2R;h2-6>x4E#<)P8VCM2Ip}qVgMh~z1d}IdXrLVjp^hAc)l26v(v5>? z4-R6Qa1h^|g9L955<75^)SZLm-W;R^aga8EgE^rHGBTiF!+9wSO3}QO4W)N@X%UpB z@KP?6W^nr%OQ1N1Bk>X>gO^r7DT|l#pp?x^>!8FC5IP|D+_LMW|+5*+F~<;mr=>C4>h$Le~Lo z;j7?3_EqrXJBc44{5I={5ge(pc zmvE5u4F}0vI7r#ULE0e>=9D1dy?Ke3us6-TguVHcm#{bO;kU5G8Q7am(s>bk)0da9 zH~o1DdozHS@}M-3m#{avN#2`b9EZIb%}dyu@w|k+naE4no5{R{y_v>Kg;2_X67S8L zF3_8P*4~VS-s=jz2C!8(=rw>scj!%k}F@}_iRG`>CG*KI#!k3l#(>jE23x!3o>|0Rdxd_#Cw5TaAvr)4s zRxa-;hU0Z5>)u<;wy)+hZC$7Bu8-@bh58r9zK81V4eFP2^wM#wPU>D^Vgc zNbEc|8()^CI>YLVC3AQ9WQFHs_$RFb!Un*fliT=6`8BulsLUB~Kti47q<|-QVZ_CJ z!7C_d^aQ*gh*a+7kIAyv$~S^=KLNL>y+XtuyfCZ3_!;~lzAn=Z6ix5~amhe&9)S9T z#IFJD93;jf(S5M^2U#vZ87xM_-$ppeqK1j>>*qlv_@B*y->AbMXK>#8=SjA7n7B3; z3FhHnE0G>`+$Kawsptw69_gr2d&}S}Ksg!ogp)x(Q# z9Mb&e5gQBfaja;B*p~MCRlYMqgwOt@)0V;#E2ikQoIgs0Uo^lqf8EjIC-4*M1@g)< zVrzo;{D)&ie(^8A6DPLd4+K6QD>~t;0(p77*q&pG$BB*jJA?9fL_Z1_ryk>B28d2% z-NuWZDcoT3de~_85!P+!=f{i9ZRu_aP=`xP&YzOVMkWA1+#m6J(rES#)@|qykl%*h zZ35J{hO^NVV8SQ~XI~hv;X@o0;Oru&(cdpKs7pET9&PpLv^K`1uBv#R6VhTKJQ#{NU%J zH@krM-R#1<;ODwGGo_7Tu1VnM8}t+lsKsKpaMKGv-=MNszza?bf3B4u{M`L!7x4C< z$w}bn**7!gj$!xF&o}5P7Ep`DZrM*S{CtDTVgavvE&Q9T{NU%UH@ko@1sIzuHluJs zJ9@I{LB_CiQ^gh&-XK#fpoGPS%4!3~j5_kQW1v{TYhVk1$&Z#cxSIlT)?sLxFXJk*aPgqIPGrvn}@rx8N^>U6+E zz5V+D;YG#V_W=)=+E)=mz4r{jXGh67GsM;KjDEh{AytI8UvSepY$luX# zXvw3~!~`|4u);awZseFZSIhv8W%I=SNH3ZvIyUm$9R;o1r>>}11snHVm_Tv{sqsyF z;M3hv?DiL;!OhC?2mBd6<@slz+IIu<`BMDZCwbRERjMCMXq8t?T2p|ow~7IxaaHCt z9ZB6~ax>mB^|SAtyi2zGN(@!gfb(+nYSB$k{m#kB8$?HY>U^GMY!%NqmY##{O0b%5 zT@uc*aoa?Hns<(UwGI9sYqI0yquWFS!FR}2+hLQJ9mhJ#;$B{tfzg&BY^TET*-nKa z>}SzOdD@*03okzHewd3;dD@)|ROS74Ukg)W z3&p{_F$qUREpJTHIdK#%J;x57gU?cEh{JiMAp_2fo#^2>`NQ+r5P1HacLDr79LKI* z06(!_3XC=k%PuMOzLz+C*=1-3f8@Q|;?00$OEW+?0I13n@Ua%E2vq($eC}mv1{dsT zAzgS+A;~{n7S#gX*nk!MCJv;94cN2a#CM(T$KnBLiXR6$udyuc8f;A9cx~l1F)3;z zKORjfd~tjVdrjE$tKbhG@xNAG9Hcv|@R$+Q9(W!Fa?Wi0xi+j?ubPM}6SL4nd6}5{ zA11!o@}DL?1o9hA{P?@L5KVObLrnP(6N5JYr-?Q|exr%!f8ZtsZg8)Qf2w=&Mg}JG zI0ioT!X}e!+@2Nxj2-7|?mHf#4;&mPj03c)JN&;b4M~B}gO|}}(a__K8YWpZT!Y`@ z*l5V>2HRUMzRfK5_C#aGz^7(v;r`HuTXw7vf28zj1GcA998R6xnbR#X$$22}n6zZ2 z?_DecMaN6QO=H-Fr4@Q!^d>5_^igrJ2ry_;Ysag~0|``pxskQ~oKk z{Skzge{mNRg^TA8zc2uCbqk%lC*3%fHR-DhpoL>ud|%yg^kQ>g-E{p%?u8oAZ3A?k zh#nN6i?u=j6rhW@sk#Tk|1lY8^$*mkNk=YCxHqoBiZ??qS-s&OPx!kr&K0NzsdxM7 z#tYPNf|Z2mvKm+68F|466u((VjWnKs=km^`7=sri_vPbkdVgJ8yAycm4bKyronYVe z*EMT{b@Qf;k85DAgJ0qv0oLn)GF~))Rg2sT$g1P)PJf8%iQ~*|fUZ3)8OuTj=-_i@ zEL%802cIcp*|q_?Xn?ZQKMFnPtlhiU79n87+e2fq-m9-{jMg|k9+ssADTsQ>GPeTFK+TZjIq@R5+$2}cjp z@d_+pK2tsq!;Ecbp84oGKm#l-e5UMv9DeCJB)K>!8N6;bLf5wQ zzeQJBMBQE%y>JXBEiN~2gsu~ABsP!Gx#AC-4v)}ng+Ef{&gMly>J_=OlTo^)dd~4U z*TG-ffFZOGUS-zJVDqoRCoSaQ7sml?EnZyNU^)nf6RnVmUTx(c*m=Yn1ym7Ge#1oqe$o>viMg(pVk*b+1x)7Cu%t zl-_b@d1H0a-u^t+_VFC(LIM2y78jH?iPueyE#(2Xzx5*Sc#Auxr*#5X!EcseVRgZu zF7aF303a0$HYSu?+*hpNjVqWi$Lo^ywIIG|E5*B#f7-< z8mFs*_d-+H594*-*b(Q(>vqHAr-n?Ls0*RJ8nR0hb z@F~jhT{uNIKS6)DV0Q zv)j`lnh<@@_jT|2gz;!5C)h+Y&ZdPgqzc~GeTGuOGjy|FC)L5{MON)($Icv|okgA`m4A23ox)7l&#|I{D;?d*-v;+Kb7(;UYv^AQ1fU<9_lOg!IFAbvk zZ_yKj715b5i*^T5m<&O#$p^{+4gY`-P?q?CZdd137v69>tAhV;uwtPQT(cYiE2p!0 z7g*GXx;Q$!gl+p!*R=k>80MC+n;+_8=&B1WWcKSAK*Oxrx|lax4!ip%%bGcg)^+rK8X0rgxOXYjJh$Hldgxr9uM~zGbk~?^nGz%sz4X4dDs{ zppUB{!`^r=rXkNWj1$~5Kv%7quM5Xh<@@t> z1AO?;b^_IA9sD1M8iRDj!keTL7Qn&|Qri~j{1N`W;6F?>&s0pLX4;s@h8wj1G*OxL$#X2CuV;7SWTo~84paGYI}1*ZM5b=Xt3t%EprUI?avY2iXJ&417XtxH>G zG5sc~dkeudNQHa^tpk|;(SMlO@{wXf^RbPIYPc!nt$UM+l#dk?2S0|^fr)1yL+b#x z&sJb;w(cz&HjaIPb%6ZNBMiT9oc3DoJn;XN(t7b0HcnO>bsxi7)hd?riH>P=SHanl zH~ah(otqqB(rttv6Xvnoi*&=N?`qa3N9Tj}#2j6?eb`sPS=SU`=na^IIl7eQ9Meg` z0IfS5*zJIy!PSg8U=l2RV?NczD3V<)m;;~crYV>~7EJHYbOmVb?q|9bn(-w|%+<}J zn^v>m{|{~70vAQq{y!|N?#yE1UCYa=cnuYAWu>-UMa9HhUh=XkAo`*pqEVTs-IIM9<{|=@}E+(AGM`gs-ISmKWa-MeavI%Slpgk{Fn{DLC#dSJ!ZR| z@Na@2@Hnp9!7sympPJHHaK#60t6o@3H`IJVWdAtI!A&*R4oO9UcJObYb_jb#efSA9 zesz(0@(Eiv;%zG0p}J6S2S`#>+XJ1LWFXZh>=o$R*KP;c$(w9LxhHD}NXBilWpYU( z_f$XGWZOffZFti5n8i_un|;VH^JVqYx6Lt7!H*4Y%4S z9_zD+yKb&J`dM3S{r=Tjeg6A|f8*yc|02$`=P-nU*9-jKbGEMa&#I9uFKJe-yl^bH z$VXm9bJZF7$gAF2Ig{m8m;Yhm-{E=Wg*fw{M_$0s2>kEoZ3Ag7V#o`&PB*kg0)gog z7lxQGo2*@IqbW1$1>37+_|prvcJ&!nl3~{Z+h#J{TX2ntL4`cx>xI{d_-&!>u|&#E z%fOra=!eNxcbldG(o{`=Mw}NIAE)yZupI=e>$GuySo0Dp5OrNIO zqS=F9L~byA{YB(fk74EeF#PsK)E0&-U%E!b4_@LC7ZhD1;)_ML$D*l7?dNZKZ6_`= z)s{3>hoKR*W&A#!UyEmJ`<7xxn5EwPGHznjfxmz}ntt}vIxNC`jn-7LX3LmVNmFHo zM#N|QZ&`xZ%c5N{amNbfEUF-vd|QtG*xkWJYNvw2kN{Yf18N^H!v%2Dl2cH zC@<4g9%-uLpb_<9{6L-8%iAx?`x}_bi^ycwxusN_@i~7_Xwi_&t?OyL2wqJs1!RIS);^GWgdCT?y z;fLSCNfG#~w`{Z7>Vvlt7^@H7f7>>vVcutP*ssL-#2dD@>hNv0Q8&=Cg~qEKLD&{3 z-qzUb3{TCC38&v>!Yb7_x7j*&2*)!d_-cWlYZ9@)TS7QJgpr8d9DlhyHsX2Y@yj+_ zL+k`FTm8>F$OCwa*S3oA*IwiS+;@lVPD|KqHFpP^2$-6vUlQet}+&kxM@zVa@J=x~bgiHmpBFqbI;X{xqEBf5$4TXbHJ zh)0ijL=Y^ZdjLfoJ&i~7;SCQ)PNbabECGGuztxJ7|Y@S~50lx6UFyup9&-x76 z%s>1?9`UCSuMx5L9@|5Sl$-Y4UA)tdOfoePX{uI1BN~YDi*^3W3gg++kiE!l-BoHk zd@pi?;ZJ*!TRn!Xw!QbEwlLhg?-~*1G9K~uvTH>AsSLHHBDFU}ZCgz+)s{3>8}-`Z z7yTNwzp}P?sCBOoxs_6FO=l&eZ*j7b_aiqLzP=y1)nmxcNL*TiD`iCCeF*m18FL7y zdOTmf@DMIWuzybDPi-yQvZ7W_$F66&zo4Yc6_}m%qP)&eZP<+%3nxcZ+8!qSMWyX6 z!Ve$D1P%PtVOypJ8|$$8R4et>CzEOFs!xSYef@LP2b=ZuJc9aQQ=SKppg!27=gbk* zCrPfSKG^MN=22dsI0JF4gFj zNE!fAsP`Mctt^NhkbmVH^a}8;r%(&vpH86`z;~QRE&O4;7D-L&sYOLteYJ>etcIRJ zE%L+EHD^!@M-%mzGpGgjDVp{zYJu&HSS_%<(YN37S~U0$wE)j*f&GhEEm#S4)*`a8 zx1UC}m?UZe{LuHP1@O=xPz&H^f3SV;4oSt)^++T?kv5Dp9bKfUS_}<4Pv|GkNV1E~<(1NO6aUP4 z+X+kB9Chh$xCa3I-f#Gk6OZbi{ms_FcvSaTS5%%qs@v{&Ti{XMCn5LY!CvoOzvITe zyR^Y@`r%^}_D#`B9{S_*^J_ri$JG$rHl?jHF(XSQNwf>*jZLwgDSi{Nk_Ab8*3E(< zTkKxP?1YbYsmWE%X}3F6S#9u#t%*fDptkt~hugLT>Z(6%J>6-zY{rC+5|Tmfor~X^ zMx8DpIydfkK{~M3Gmkw$UcJJ~jMt6}DWScRawqt;(PRE|dF=$hFXRF8@L5meKab`I zMRzr|!JQhl^0C~~R&`3!CjmT#$hL8s(E4l{F9kLCS zHmf7H8$FBXQn?8Qrp=cqus4Y%RF-50+ zuW~0;YTa1$O60?Rt0|hBHQZT{bdy+X?!aI<4-U0rdI~_BWl@0d?x41)EZGY^qL9OXDQyCYzSi9_p2>QTpY2QO#G&D#4ywN^}YIyZDR8xkZ6 zVWOiX8URNU{gOzIeu&oI70TLC`wF7m0V_;Dr0-!9l(wZkKk2;J^&*y{l%R>-lJ=+& zzRZPt5m&ok$To5rjT~*RkS*u3Op;9yviV%LgJe-cHkr$|lB}1I#c`RRWNk>M+AiDr z(4EIyF55a-T6@(gmu)>9?AM(*|N1yTZc1ohwuRv^%v!@jSc_J_qZYu5z6XDN8TZAp z(c%T-@l6qYtBtqFVc1Gy<4Cz%V?Mb!xnHDr<8sLO%pqihyc@lc@p(bW9NvvT%5j!3 zuR0(|?m;&SX9UR|EN#82hj{$<@oJFV)^h$G^+1r^i@vg543fLh-i;kB;PIvA4hwkf z-MH9-*!0wP^$Lm|g9FH`zDhzqB!zIWSN)oVe8dT1xL0izj5M%e-Sl92sxyby39Zcz zkHmvW0~)WyFGDoy5_e%V#fG;ftYuuh$o7J6i=%mMBS$m5TJS*Ql_juz*U?PHuA}KU zQ50=vdkapZjaTAvH1^hT80fLI?dLDjq9SHDw*ww@z#~hys+&XPyF1snMQmRO9l z=8Ll7vPQ}c+TnQvRiqTLpLxhFA1*$JM+!)`!}Iz`>D@t~ur#WsK9p2GYc~GV$7jva zshF^2rb^QV)^tYUoQuiX5R#GeWi-{^Fl++LDQ; zoLKoG;k1*U_UA=b0VHcpK%cMxsADW>)aN2hd{$!e==4)T#%{a_0M?UC*5kRgM01^$ z7#q%cS^*F3vra|h@XRKGqP_35n;Ro#ltTiPLmTUpYF*(Rq%36WxY7;N;ahAy%CA>&=Hj-Pp9SAvyH9~g^j*rh8A*eEIBvED7z8v)<JVz5ax|5@c9L*+#L)B;ms?cE82sxmr zLfXjYbh$1XfmIlHVVKlj?hpcU@(Yi*GHd~7+SHTwFp?ZCTnUP7&qs} zv@N91N(?PW(X`)KXt=+qcaH>$ZaMp`Hc-5ALj_e5PEpk6t>xuz93O^0!JrZiD#@V6 z8`LC&nrcukgGx52G=oYvs7!;(CQ5yzk=&^fD#j{^x#Y!>>Kl#Z4#+Fdu-sr!n+$5R zLFF4%p+OZH)K-HkHmGd|wZoux8B{4z)H!9=y+mrSwq;j zK7FAom7vj~`&l0mLrdDUjR9lLWPF+%cW09iG4%71mL_xSlFbF`(55(6HghxD>QlQ- z=sd5oa;W9Bn@>?Hv}g|r2*pY=zD^h?@~Mg$KQz@eoeITSGX5Ix{iau+*h==JywrkZ z%+06?UNlGVn!`{5&pOKLq*nCw#vQX#~YPb#0a98tMH z#Xrp^`3g`JO*=HslojbwGHqw7bw^hGh_WV`rtL&NZC`>3$_7(Tll*^wF^pZsxc+Cw zp-rZ8>k!t?#0;WI{$p;9mo}hzcxK6~BBtR;(n<^&xba0x=-TEHr`+I6` zqsMUAQ?pYmlq}^3C~pz>N~m~P52yq-*{uP^)$0URX3ZliHFw|!V7yDhu-I%+`36;J zP(=o{)u4(6Rc75*gbQZ0{dSU+S>NHv%h3*wN;rC#qn#XmN(f&@Q4^j!)hUzBaw|bm zO|*&Z9)_6ZM4gMMvzAq}_U~KT_fuc2dSeUuI`sdkJ z3`JCG!LLB6xh>8E`K%X()@QwBP!g_VxNnF-*$gVwpu*gOEVDKzs?6Ggqm~@C;;1!8 zZ8*A~qZ>HtN62SgXEX@asE{>C9w@4h)}e)I+GjNm38(#ZwN&@d#)u5lBVe?Ig2u3- zy?A|AVrT)Rc1yt6VKQ#ZjcK!9pOqL|@u!7yW3(;iDbco|2C(B&qqz$opWAv?kR^jC zjI~Hx!c$YN|oGbPBD@S|cRfkILZQm#(m;8C1GKWg1krLFE|KQiE#ZG02si zQj=Q9Et=s>WhgcXMNSKx!pf|L#A=P(na&@q3$R@Roj< z&q@p}HP%W3#?>a{v)nj>&1=N42M5-{*iG~JR<5Sz(AEq$O|U|-i-zcoK%xf9vr>l8i-04!Z3%)G-;xq>x-*IQ@ z1mKISrm4jjcb*+kJ5S=JV2fxqUJ1L@zpL+mE|<{Nq%Y(_3Im-sjAV3iMKZ)BS$~qz z={Xrf3QxigB&3rGWVpm&GCRp=&Vr1}C%X%gkkMfa86`uqQzWDQf{Zf5oeS*~$b2Cy z{4c6Yu9rKq8BX)y4sY(!++TnAGIvkz=OuLMr={yMACo1M48K@&ySJH)zC&nO^}}V) zG1)G(pN3y7xNI%=CA+plR+Wu!!%R#k$`+bcmrv8>OAEa>-XOOOip_6c<0d)18wF#m zxF@??y#ZC#s#0;cIu8`xeeR3hHqD=jcfMbJQC-y*_Xy5kRJXR3JIfRiGgsa_>e06H zgWc%f_1fU-6}W>Gyna*#p2sO5k@jsbw!R1=7|%PXu4*SQs^i_5*NP6 z(mfP<=PLSrhwF7Uv%MUnP`KRS+i<^JeXqUT+D<%`_x$E}RDXMUL|st_caWd1bEB(@ z8oO_Ct~Cn8mN{)X=ipp;#X+@|L$0;^7PcY}?kG>EEy-sK%r~>@C=VfF=T2O?LSUv0 z=`3SM);ra^I?HwMzV(li`mQsQ8Wh;6e>v@-{#iK61@7O4V^;3AE=UT(b3!<-t4Uee z6-hyPV>fxs5K5rF?YBOyz5Ny!@Y}}D?w-#Xe&4s5@Lea+wQj`Dz;_28H#wV?-+ zg77mT?BCO*+}0CGL21A7f0opa8<7-#6l8mXVJG&-BTydjIe}SH*}aeygm3ra%4WSe z<{9@!QiXSVf9Ngu3by2Z;k~|}+!sqzzfeaFkRP@Tu24@9c7CeP9|)X%O#O49{F$ZL zr+#{qTxH4m()-@ca=yiq@P#_#RvC{+9rK>LRSpi82Yf-Z3ib+De;y)Fwd_W~q4H3| z>xatg<=uw5^X>8=h`rNpmlK2Jmvy=KEvI~QkbJMstG`CcCr#`Z(eh*yJ2*z3YGR*{ zk>_2 z{+Ef3A10@p*qy`V1tzv%f}CPv^AqH`CbsGD8d}eAIX94p+H{1RX=2xoKx89J)iM&k z0XB1_Jm18AJ5ru)V#g+;3IXE}6Xl0YX-pU;k2A4vj*^p2Z2LRpWnGN6L%R-Ggm$G3 z48?m!4ISQHB2Nl%IR@`DU~Fy~#Dy zy{5=mIgL?tVye7=hRvvH^6p?u+E?C2Gv&q>OXXK;``Pldz~0@nb$ygf&8P1y*C2`GoU@5f$qUL22;5c?!~wa zWcB8~7?%OI{e7~#i@~B<`^RHkn%;kF=+qDIlP3l|y`7fIGlDHSC%h}%@~L3?FTHEj zj1@?yjq##^lPly47L)qqgEiEnSIb*1Y!KyQTw*ZIe@M==V6Uai56Nv?9mN-__wTEy zx!45DqWZ0s$B@ygweqm;?A0T**d!0vKeUvlKCkm@<P9x2e@1tno-S4AlxL$Z)4kcHw^@Dn2T=^$JX!fsMmj^kNcnW$%z!F*M1BO;AsM{-!FIVN8`NCyj(2q*4laDI5@K( zaSNxYeGVY6dj0dCqv&LYyH7kr(iMfuA`j52SYyRUVW(-LM}C1g08% z)zBYrMgukZNPd+JcYh?etIx3VeHi}!k&I^{r>GmsuMzQ3IghyP-`9xv&cEfy5-2zA zIa~Ro9q%Ow~oZ zANm-{;q^$%K0$Kz7*@Uy!*@QBH>)4?Y1m9nsklbWM=N;Dp@*&!bIBq3v1lq(>mVw; zdW5OMq^Yv%6~rD}#Q&y>2GCblgiYcrQR={Kkn zyXd?gf3S#O2d4Om?C#7X!+HFM=J=$kS`3Yd&-fIbuiatTI^iZwv0cl^HS7_!>#K8o7HaQv}rM11lX zk2v&;YeZc31!_x0YK;?lZC6K`YD=1`-}Kt~f*5bq{>s{BBDXJ*TLsnDbSxTui$mEuay7 z%Xq8KUs+pxlWu+zxrI!wzqXT4A~zWRbrQMNW5{Yd)Q{T2u+o2xh;6>+5qE!mjfj7J zEk6`NMQWo(Z5!Tdsx4`%2I{rLzI&6s+rE)At(L+TYFAAjZrRa7U8u?LgbjwFFD4^qLC^nC1^Mjl@v#p8rLTrmMw4zslvrH#jFhNBE_4^nlYu^`~=k z{$SP&QM}2c(Bx>YD8vq2{{7gEuAhuO%O37Y8%reciXS{Lhu?C|26z1wf{ zt?j9-+$g+?EK|wI^x_^@g*(~Q(I)M^hpb8y3te)bZm2|4%H3^BCGmgR6qT?l zD^Vo>LRJa~vl63t`$pN;@v)I)8XJE$(Z>d>^|Q_Ov4M)et0>{OTrd}sjQk~;}(;>H^Z(Bv{^hY)fby7!z~+Hs=qW--jTPlu8Q41SuJj^u-W6577B&~ z4%8=GDw#t)tgmA?Tsa=9mg3R5xX|_E!r8%S1ftHiipL$ zpRz46FSk=#sUNjfx>643+A1sQu)e1q$567vKBm2L*FaW>C^QBg*EaKUefm$92P+pN zc9leZ7t5>gS$pNie)YSqtm)bXuG}xOgVMLPxsX04OYc1$l=e1DQA_p7ZptXju9m9S zO?kiZaiqo$WlU8WJNMZDACG~he~npIh2LqE_WkOQ6I(ORnIH6a$n1|UGMD(X7AVnM z(qFOLEEO%)vfEJA(=FBO1}huo5PGmA#@Tv`x^=MfEXJHSafmXN9Z|0gRWfd_V4dSU zO-P)G{o}=<qpVeCn--Sj-vKX<-R_31a_eb zu(MR{s660P_!lJOACU9(NUB5 z(Y1e)vJOWkTKU|*zf^ZS^x?wE%1p!Z#%53NrBQ&(g9!HPBg?n>6lGpCD?G~SI1bn9>-q&aSA`E5ho6Dc-w^CRqNOrZL;)EzDs!% z`C~u5E`s5N=FX+F=g_bwsk#A?z5lYfY0h zen|f6pn6X-qG1CB{Os6VeJ>e@HSQG!rzm$29w%^tz~=;xN#**-Q z9_*m!%S&i%q~=D4`=V_}52};qC=pctgL6>+X(~UOmml5sr-SPDIZB@f^oU;Whx~2q zt<#hqbf+gKO}T^L$SF)yhH&aUDAM(xtLrw*)pe)mDicU|+dSA{yZ?LVDeVbA1su(8 zuFQB#EXIEm7l$=&uEarOzPU0`=Z*ajM7#ka9=n-x@=YF(w&644v70CRpfTS}*{<_? zJZzuO@&ji1v1e&#hi~P*-NK>^B z8j&C4x9hwf58KhRc)%hX}J_H4yx3&S28`@`5scjeF;0GSHKL_mf`yq~m=D!CUfet2o{gYJi4qkWX~6F7?VVg2iqh( zqg5ikjS_LJVWkdM2svo5e|GCdvcmh0&xV#rZ!tYHCOaGK$mn&mkw+bqqg?NP5Hj)! zFM$uPV-Z?=0qfLotyz*l&jUh+aN5H{cACpPB)eD0R_gTr6r%>))b)2OZAOiO6=herlb3*a+K*j$cKdn89?JNbkR`v%GbX!z zLKeb(rET6FIZEFkw+%JGlIoy66H2I0bI)L}>*g%wGAs3JP@tE6)(}|G2P+^9DpXMG zCpmo9Fhktjpjrz`ODGiMBe$IcG8Wh^Whdbc9POy8K5IC{c-roAU;z27D=}<%nQIJc zok8Up)CPmvBq;4@0UInyQf|9^$iz6Lu}OvctcAsRoST=Y4^FHv65i`4IkA*TFg|O! zK~)%3r9mAPl$MGj`RK7yNGd0{ogWmQD8_#(Oq->k1u>9N*%CJ!Y1R$sJ^GYcHxX54 zeUcDXIt#hanr~2r232HG4p8j1rB;fUgeAP%sMdjDt5wUaNUAy?$JQO_TYTIoYZsAa z*7pcu)fiWR+G|kz4XWIroS@iSV6AjubVrd`%pkPdp;o+bIzF^)UO2T!2|Hk{<8g@4 zr_Ab}L}ZzDG9fGs6AGWzWl+fmm1a>`6HgHG>-1$Y)DhHQfDl0R1HdUP^GB0BtzT6 zhNe4qtn3BD7R6wg5s43mnL$+;RHZ>36_gh8JWe9*{9xInxs%3KYHqvJ5b#pAnT{$a zq*N;UNBCoDpP=vrc%mUpGN|zeHAzs~WBGqw-a+N$wsS#NvKjxdoCW_`6ZouD3>Axm z7ZfjWB`998HG*P?)jC7$&NIjj2DM30S_i#MKIO5%R77e)Axv;oyF}4JseABzrl4mFC(~Y)-G8$0}qx4bViZ zz0?3@(jNa*X{?;XM9YfHZ8R7pvnjIlY-z)9ymqcSH&F=fj|D6(YUZw3N&&>w7w}D&vi^jtsYP(gWuaBia-~f)Re8ll3r^Ow zp$SbXnt$S@%Ox}$YM&EDlay9Y6t$9;RrKfO66#l6hk=rIs$VWwmRTn4^4|4;Qi50h z-KDl%rOYAhUZsq%ES<|A)%j+X@*pwu9#qC!q-N^w2XU2-jZuGm5Le^Cy;gHPU*OjS z{&6*~(xGp+hT~C$i{`5LuYo=AdjkI{@Q_?Czdx7Ty(aL9T-+wO^fzx4{8{5Rf#oCh zo`(>v#%%)ZFA%&Iw*i3130xrXIe}x=asA`#aGL;j|6Nz#ZGua+ZWGu(LO&U|37USS zZeL&5Z31ns8uKv90DfHHQv&yYgv(b5{MjSO0d}|L;mZ(S7t7-Uh=*Uo*= zi2NA8UFY>LIV-7teQ>Q!hgK`I|H^sZ4UZ{P*!$?KA6JTkETKo#r#33T1A8BPLOD$u zHD?pPX##KAq+~RpDIoWly8KC{uR8Kch2CSLx}Q`g)KJ);;)>g!QieycN#m0r#G@<^ zn3{t$RokHv>EmafZBHrZEtJJ8&+sf>cvitv@wlgYIA6J!@R;XuL;`Plp7R}FP=-aY z+2dy{SEVX;yVq0(X{ruGBg%m1h8L6pmU7X^z^v2CsgWAr%Nu$1J*Ehxsrv06qmdbZ zM(6cTJ1yb?vv{=Uh4u)nD5Hkvc%-RXto!?d7@wl^db~@B_o&h#2;qRDSau@X>Ks#c zmsoZ=Ms|!pqw{*S=KtbD3YfBspv^b5M_|RWGsh!M)neV>7X*)Oh4_VHLxK1ALS=Gt$79BNkz)oU<;P@Y<*S9ac2H8QaX0v%c>K{?p97%bHJUfT2glG zr(*|BR-HJyr0oeSS)7xNzD-yJpcP31r&W*ozq7DqHJ(&|+K`goH=l2AwtP_sh(K)<&^$ zDgHg5h_zfM$xz<90V%$kwx)0JnPb>Xkf);5wRkI&cK)*qm+@X@ToK}HeYYbQF6Rc* zYnB(hp>(15Qfzz!Kk3|8;k}_)k%K$rkBgBOCzQoiI(~S3?Wjtv=#h)~m7sF1wAR^r zNd7o)%-hO!Ax-Jl2;E`uKQMybTo}|<#kR7`n$m1Sa!)>&U+U^T=T-2oTvv(OzC`KY z)J0!}V36MfIU?7K4s~{k@|fa!oI7lGsFzEWkxFI)*Kh5pj(=B)S2Bllen&^OkoXG0 z@9n6bCq8lp*H?E`V|OakEjgd7g*%l6&0Io$sUv2lw&A{DyoR{TE@h)qEfls+>fT)l z;BoN)%{!^h-&3-i6${?cNjSQud!K$!xzo}#8?O$dD!5+e9ub|?;8NvgrFudFt5SX^ zHMSHHtDoR}L}ztFsq(qv!fPR^%0->k><^&#mvO$lv%2>KWu-ZTu^%dZn$qUER8H8( z+^)K_`Z(m4>M`EEA1X5}n038f_9;Wz1f5c*;KezE52&3FD1Opd4=TeNK;XTjLTMRd z$$v*ptyChE#P%#`NNjs`bEVR{0b4=6LY-HsbXV2|bZ1FNn~Z4vxo%en!*B3mrFBDE zo35Q&tiF0u=`II!>qy7840wF8`rn$mNty)t#t@9MH8r0v#=C)q;g%VnCTrO41aPIZBdq}BL*dn z2z16JQqrDPTIVeFE(#jZB_4y0ZU6AuLiN9gYv?wUjxFt7v5*JN4>+DBrH8WVFC4oV z1rGiKx|O6mm8p*W96la=FUF)^T=N=n+COxrV`M@*`1XAh4OSjIrt=$v?5zO^)J!x0p&VUMw0Sz zq3qtxXxihX96-t#DCwvS=py{k4I{@`%IL?nQ z;I?dAwvt+lnWx_HjS?;grkd_wD-jK8MYVPcUn~4dXC*zLTtiAeM+v2AlF~@Il{`BO z<<@{_!Z%Q|8Ej7)4{Msjib%<(u-Q=ljC=x9nC%pFYzhlbQ}6n&hAxeCYzixwqwcJ! z+fO<+g~iNKZ_wZum`=K%hK|i(r&4(`rWtGvDcKCRB30e_bqz<2bmgpysl4F=K@-kE z$0o2nDWc&5$|6$o2@J}r8bNK}LdPbs;1u<)?`!DNNXI6yf@F1PP2GOdu?Z|Dnb$Bd z)pY+3x=5P8PR&;DquK{_Ye>iDwiUD0rzw|!P9xnQHt)?=Z#z{(m!Lt%=Dj_$)Te9e zib%)iz1g#P!srg<;n2PoORw`T?qYnu0pNXh2C*)w>H2aamn zS?Jib7c3l2(_R`W*|b+MosX%2<9^byX)k6vA5#Hc_aC8Sv)-v`JR8%jw}zB#)>|Qz zrddxTC7<<#(lqNO`~)SN_4Z8VVNJ7M5h>ZMH(Mx8v!3l|DA}wRER?2MFO8IJ)+@M+ zhpi4&Wj`s|tQRAcrdh9hHI!`DJ2iz5*TCephIDM!TQNobl7@0Xr;(1$dYz~6wlj3z zgkO}4?4m6CywcA~i(r@hp=1WrT2<|mvcpDKWiMFm2ZHIUY`$z?VGm2ky%|k?>GI_t z+Trp){op$-?7eMuT|_(E*@J?jue|EUwJB!UVBF%xmjwO=gT5_kV{jwdCtZ25?OoB{ zj&Jn1WIfrz-lncgS;b*bv24AlE_B$pg>9x?FJi+Tw^S@?7ThAgP#xIO?rf$@S7r4W^fM_?*#Fvk>Vzq52d;4%FS2#)0fE3C2(SvI6 zNBQsAnsIRySx)a{?^M_R3XgTN&#DnR(ZxeI>}>Bg%v@$uDCoM%RNUGjX(&p&I72UV zDPHA)f-mrbM|*CQvR|jt7k9Qh>MH%E&i2ktZDZJZ(-v8Y3Zekp_3H7?_Fk<_g|ly5 z{izrPbA;R5)TnerqkNS8pM$K@J;-uexILk+V!h$^?v}iZ>eu1+{T4rV$LwOisVVK7 zP2UV6FY#{%h2h?FUF>+3e0CdeR8RXjycM^N`b301(~`JLwe_;M?-olfeyHO2%eB8$ z=9SQwQ=gUoFCDFp>Sga?*-)tF^s=|L;5*_Iz3jc+)N<5Tc`V=Tp6FUO$o$w0$S1WG zZQ>Gb()@ZpC}+_QeC#W1YF^;aGsN`*z7#KRSY{<6$TK8O=ZOGcs`EsEuW;*v3NFak zc_Ls?tn);G&(nD#zgd%l45kVgJkU_eD2n0x?`wG;AM1XhcJQ3g>I!^@nYTcg* z@RF`40(_FLCjz`v*Ao#G=@}BK3y6S0n9dUc-meEBB1m=hvbS_6(ansY(%)#i)O@0U zd;d2+AW(pAPXzoEbe;(Cll1sRfKStTBEWaoc_P4H)cuJ7Zz~u%iMJ3a5=_z!hyb6U z2Ot9cAe|=yd~2O20=%aCYcHrLBJCaB8)#phTlW7>wUb8Bk2?8~5T!l+1|8M~G)rc8 zD%b?%V+x;>jvAU6UDO=qyLod6PtsV)m_9#zk(W0i_sq1amkyuj_a^hO`uy_c)9szo zobFC(bCBRv~>7!VuBn`%%i~z?F{O|(^8#+?*1Cnl6U+8Q9;I;yrwA^C-qM@|S zVl8hd`7PfELG*oyRck1%wnl8UNgr6Pzc-XlTKj?C(ja=JO?s%|EwI_oxOjIv3Co$;I2@o3HJCP5)Ykjk0<=#bUU78YNP&or@bHHt`qII5}q}Y>t7N4 zw-dQt*Gb%N$|TM|CGZ!MxL?c3T;6jg$Ma@#`HM5{(G>T4fu~I26}oOVFXw-aKb&U2 zm&&VM&$8(}AIl70kDF%jJeSPi`Mo=X>wgzmuVP%n6?WSjN{@D!P3_9+b z$@$l7;a>%>+v#}sLf)PAmH$o_FTeewn&m$s_|F&dVR7pc-fTMFoy~b=aZUV!;C~WW z*n1ybV*mX*8t}_j*{@>*{^19C>A9tV8^xZ&QB5?-7tDZn=XHiB*s z907O&bRXcM04%JQqJT#MHi1q8o(aI3dnp+>8-OKd(%r!808fK{1b7QzGw7ndeMd?= z!8`+IH}I!`XF(qZJ`KnR{T=Y1fagI=`$noAU$S?!Y`$IXx6VGVX;^iXSWrXhaI{qM(+KaIpEnsD{0oo)SOmBma38=8SOFm2YJmPZi(uygmjDeQzYfq6 z&>qkg&>L_QU??CSK)O2s;-mI>$-dsZ^?7@&)v|Q7_tzIOY^fso?-beR1iO=^aWhj> zvhQ)kW@KbZ^JYsUGUmk0TrfK&T}sZ9VpC=cjbMN;ZuE_5%+;?hxb z7m)Zy-8O#i0%6(9EaGNaS<={QyjeMBw@rkDNk%)eGaQRj79=||mY~47$tmjBuiD$F4Yt}HYWJ=7?jz!I z=4PiPJ7(SEm_7!{JQeAbo(HT0Z0yZx;-53o#Mg#pkxuXEt@c}j`nz^S;}O?rDH1?* z9>59O48@S;1B70E|Ac*%*Y>)7T~N!+hQp;WfD4cWZ~`J5dS7|NJ~YT3IdhnlH0$cH z_$oG~CY@EpIfY-9l9Go>nJHI?jmg9M)NAB71?VCI1t)u-c+>uENVjoIVkHOQ>&3BB zDWEVrRyvgtD-{D40+Ij&7R0I-KEPFM(vcWx-{&!s10VsGe;k0)!!eQvV3s*+@uYJ= z=C6#A-UgU$3&B&|;!kVJO*U>R63V8BVx(Yzrvga;bOVy>w2ob$#7L0<3xFSd^Ki68*U(t0x=XCI50DqGe(bf6aF?Q^{IjnP)~o1~OuCJN zUPLj`Ptu&LLzh%^dVNNjsR8Hhf_^+jE!$x)>-PAnSjhzl2S|W?;@ubr0ROUBDH7mx zi#{)vVx_l(U>F=LeE>LnImUqOkXWgiwWjQ?T0Gg0X%H)gG(8nwqgbiabw~oB8<1S5b)452BiWRsE+?E6R?|Kbm7|I!PDKAsj+Lq=AwIwd ze(A7S$uk@Uv>6^N{gMzXT^Q#5>Ro(&nYbY*UdjYS0UUs^yW^$gMe&jo&;(GO6)*W0 z#!Fp#_e@O1ymj}$cqtN)ax-iI)u6wNikI>MhhyTUVt^|;Uj6d}dmFdsY@Cz=DE%Q$ z$_E@e9RL@2M=hEE`+#1zErrYj7*|Ud3!dU8X;=CP-`P^dcX3iQpg*Aa+c+r_pa&+o zPU|@DOq>*DN>Y~-c0p(6{g9RZ;C*qoy=QROg)8HwBtRq}4B!DQbVCM+1cU)RZuR#M z?48`D_IT;-(0FNfqj)L&x_GHAcpd!UJ&glA$sJ)ed6Jbvwx|i>Hm#{E1y6C4n$?u+ z@qyh^af^7Vpk=%?u2sBr2C%Yqz?kGFV@8i{gML=7l#^YP>ubs*A)^H5jER@712h{K zFP$HYF#@{P^mu9aG${AXh?fch>hyT;$oK6Bg4DBn?E`9D&)*g2l#*%z$;=Q2o`CFh z`tM?j)4V3QYYXZPOwLpg1sD&Y1V~0$4@z=9Sv@Jz*9OvYnLALM+KyzT%Lo&%19x^x zt%fu2YH?uqVwa{W!;o$CjN^ zcfc|ryIi+mC zQpC_93$zK`W=1MYb~4ZnhJc>|ht<Fs1GI)Yhpg)04;hnLV1SUW^9vDzL4j52{+EDiuvme=;d4qOS!EpLJKu)#oj6fz`EDEb_ zNBn>MS0>>$2dIxuL-6`^^~rae3R?ww?n$&3fb1_IncV=;n0!pZ6NOVZlk-n-(i3Bc6L2mo^Bc))>SULvDJ~Qz@=Pd3Un(%7yGWc15M?p6+;R5iX;1>akLEC|M0mlRD zIvgNU@Q>Us47jf(-6lnYXaogKn@K|H;!5c;p~I0Os>Oc`z6zi~2Yb95 z6amjepeJwv^nU<)0+&Ev7Cgy0Cf9?pcMc$E$N$sZUvy`B%5&1-2luNd=JnO zfQF!hXl>*GFgFAAfS-IfQo0qqp1@$xx10DV(6IpBei-NxCVe94(I)*^&=XAjNmRJs zDelkSCN~Mny8wEDKfqwDFrY%FLFWR{KqEdG^c;YmKzY?jX&!hQG!$bA=zC21rJ&sa zJ^pggD}~-oK~{r#NC=2u4>}K^J3IzjZ$i><1iuMDG}$~2`dNS#G$mOG`X!+!n^!>V z@yPx)@WlYoZWiDzFxvs-Oi%)P7l51z-Ut1miQfl$KR{3LAn1Ra^cA2#GwBb5J_^uV z@Hps`01Nd$1^EVy?m+yf7z1aR0Z-s3bcqI@bQI)!&_9~=)u7J-^a3t`{tqAwwp0Oo zHRb|&+~vfCc{L?LV(8rQ*eUGLN;Ash@{z|8<;R1&+{Oo1a(ZZC6G}PIwsjt z$Z&i|>jaw&RzpZLm5xD58zG}6(=j#AlaSG|`y#MS4SLyr!|*piQqDRimu-+yI31Jz zLvk@;kkUtx(M-!Q{cIJ};RHmKvX05@6l6461FK_Zw`%riq~iV+G776>nqe+LW^OWw zq|1hA}0r(H#{|lg`Ujht8e8~|d z9b({)lEON1Mgp$x7$x}u6#z0Ka0-Yd9q6}!^8w2NEGC!0sa3^0xm}a)X(DqdVdp655Pur@7~o^T9wB=R z_<2B9SM>i(I3@vZ2YlKsN;=gYGa?`iupN9RaPiHs85AXX07Ux%d7#Z8fv<*K*N;t% zl9B;=fENHxKp24J38SKBrC5x@>i@cn@4 zBryoM734#K=?Wtjcp~@_z;v0C1WYH6JAomVrZ)6u{b+wG$nBVi>ip~KFai47a4ny| zsUO4w|4n15SR|Y9uPFA6ihBBI`!;vC?NL(BHV$Ee-XgHmq}vYqqOkiKc)y@C1=eHy zL+oaSJ4KKN0)PH?l=LEC34j7_c{7k?o{6qqSkOBGJ6+f1D)u?sFkZ=USTV=Jz+Qj{ zaPh4u=>tGMfMm;o$#w#giX;F}!7EG!l)iz%05BJ-(C2gyzj&ELbpu*=)?SNrcF?(&NxnTP)GV-tS}^k*jibI`|3{0Y!z|C8X&{@;K% z`=0@C_D7j&ub1pYrcfaBhXR>DRkirDwRp1af@g(#18xCC0TKa|{!nkaXn)Y{X__d} zq7PcyL@QiqO%*NWpcPBByn7qnN>;I^VR6SI!Ija}t zO!-o-$djelQfr3U2rsG(0hEJw0!K7gZ~Bk@;}%6&nWcZ6ATHuz-XitU|Js|?P$dYP z{Y(|KU;P>uZokR76pjRDneLT_rONt;wjv@h%XGWFCOan_C>gU%_Z2dH&&0>c{-cde z&U!LtS*)3Lr4cbUSl`x}90(ly2Y=%{A5w_VWfZm#?eLGWt$NA9MNVkq?1c zM&}y(n2Wju8v?T|o0~~RypAInn~wj~l0wL2>%bG3WxBJuVBK!N`sQD?I(!4%3C!i^ zi1N+tv<5Z=W|?kh?%Yg~rdg)@*646Dq>s5F=^=CivrM-$*GIQA%k+Ai6V&T%mW4|H z;su+9dT*I!dT*JN(R<4*qmH4Exdn|@Rhv+Qo6Ysy&9c*XBuZ)B5+%YO;BY+CnGfs| zGQW^Hx+h9Y+i<FgbU7`^{=pDTR37oIP-(}L%(na0hZ3z_#m<(tG z0^LB@`%QXU-dJ1j=p9JFQHQ_Fq^A{-!rv`faQVu*z+@0%4j}Y?lb%*d8VLx!qfa0K z+UuaU-euC$a!9UsgU}N&8PI+RwFCG~`T<6OfWIR$kU&ly{w|Z=sr$QW6zU0>3|7_= zz;Dviiu2kDI{F3@$g9KOWzsjtI%M*9^TR-Nfyp3|5;G1HuJ@bt14IC`zoTCu0b0pk z+uvoty>oww8iXi!Thf$0h-P+kh>)h7;0)V+9YUd>SECJp+3~RViTN* zCw=)<^b|`o#SOWYm%+LaG<|qnHxD>T98P55sbNr4Pl5d+7}3t#0?Fr_XlZaj?gC9G zD~g>1nhGYMR*a(F)e}JfJHY6NmJ76gk&zF&NQ_uNXd2wLlUDVvvMXoyJRFQnhDamcX`bCQ$G&@S%6wt{J6AJDEtq%}7bcm)yg~kU3$%kG) zjQpU*VT7C4n8ZZO3<6CXG?0A~Xu9GdIt?^kyb$dHO|9W(8Il7s^#haA5skS3r&yu~ zfu;)%qLV<=#RJi4py@h*Xb)&QrxWc5O{Zs~oiT_j=zP$$MFGjBSfeZO&?OlC_>VBr zv7q(-oobTjnCK0l^(Ng4n$BueKsjhSK@oixG@WdS4vkBc=)6I61nAiIZq6h!hSTXL zdYy^h3c9olx7iQ6T+pXM>&-322W%XmbsHyW-DWE2OI`U`%5j6CkNFS`L59TBc-V9e zeQ6!~3X{Jy?8^9Nz1w*W1J70T)QqLj>#ZUsm}(4~YD|^zfUc*K{Q7?#3@XBT({2J? zE$FSF!$dQef{qk)1?VI}`$6mDr`kkI!vk`siT0T2(&6ZT-B}vJ2NN9$p`a=A*1)wh zH=l&MUqw%?GYEP;euALcVXphp{7VMZ-{zB0zHU&5o&x(#fgK|Qg}6ZLM}&vu7-+1U z1WlEb61mI)e3PD?3ye8))`T%ABhuiB$G>e1`;VgZo=dPyI>L5|)kMlVOB*RRoA$>7>V)lHjpht5cpGNIoJC5CB7nbxTWGAAf($n0w2)2IM zl>$6xqNSueVx&Ca($O(eCLjqwpKX-DE|dei>TkK7^c}Nv*Dx%Fp#z3tfFu}DKw((J zuAJ=lAn6YQZw`}+-^PNp9mAyjcR?2qlPY!(lft%PvD*89rxT>S_lDv2Dr|NRV+kFF ze{mUFt;`*bC0{{n8Ya1pz~(p)aGC=A8?^@H zKb0U=qY&po)Ck}?fLcD6Ae91#l|v6)@eyd~@_^}64gb8)u&U3Ee@+yTwmUmQWC|JWXF_|MH~}6Z zb3i6x{P;hQmfU$l7y)7aLevi6X^&>_fIfVT-{(w(&JTGKpcJ}%=&HB!zDUxA@=}W zB!ez2oa@d)m!FLS0o7d~14MS^y3iXixj^m$6hrQWk4xwxpz|z71p(EE;_#>uRxcfL zWBCyn4+-!|gi$FBoB;oJ)Dlp<4Z(qv0Q558jK3ge{`)&jQRCI?yHyl35HmpaCQ~?Nsj6UTsEQXB}Pz_lz?5bgx z37g2Cz>t+{-1aPNT{%deVn!h5jfe@GuwIA>2!o71p=~h$Vdr+>Up0iqFs!CvFpBIA z44K2h`!NE>&U?`Juq};5z&<=kBIKEnO8{42$l*tybjTg|qFW*N3_!g8T)qzSB*^`c zI|oA6FNS@2k+wo1-3MbRJvXB^H*tq@$Ri;yB`3%wAwLVbA95F<;uh2jK%dZdn4*`W zV8|nHMN<#r@(9SK`%x%#NevMnkZ*-wLpQPp;{rGVjs_3{=#vPiBsk^6sX7}Di_wo+ zum_z4S|T2_XAxQpK%aE@xbP~xeE4}3v?!p$hS{K3ZGIpd;rCbkoa|whr$MQHJ}ub5Acu-K%a8>gn7_v z@JYHKvSl%nyW(CrEJgoA-~u=SrT2jc(B~|i9LwPZM}HVHZ-V}8jNqUhpsRr^0L3H& z&?gjELz(a?g-_T6hzH0+OBXLkGN2s*3E=Ud|1&+@DFROV8IMK5Kf3Fze@I8?1H!dW zFm%-ucH?kKBETmRytD6c$pN@}*C8vT?9_KhI|^O?bHk-ffaf&~%Gc3NVwyb- zU9lHB0G+5DMOY{PGWb_v3*PN|12x`^6A&<+D#L(_p8!LAf=_xWLCW-T|4Z<9evX;~oNr@{yoKa|>0|4F>%XL< z2n5L61_dA=K%eFvaQGd^igrMKQ?Ua!VSW^R5?!zZH3!t5W+Pxz0h?li-LTn-)_WIa zdc&SvNWnlH7WwQ+9Bx1F~|lPdXRmxsW8h3DHGs?gnkqx zSyDIrVhzxLUL{#r4_u%EbYBl-rL9Nc@;cy4vP}57Oui(GgrB1ac3|PB7@RU8^hb=4 zJOKTtRFWmZ&&I~*~)Zz=ycg|u)K*M z+w1H#xQ`9Td@cG$xrbg1qCz;1kbi8SOZJ5l0q5G4WmpAhO5ym|f^U8ZJ{zvoYzQsb zZR|IK53a4Eff?|>=^3p5u$jviiMbr^e^MI2!{#ub5tx#r{`dKx&1N;x$Sj;|D&P43 zn#=RSR5~6S4IKaYp<17*h+vBRX8RsLcW;M_xJlMR3B#rV2Iqp60mjeX7kj~~`a%B3 zEQT%*S8RvuhKqo!n2mX09t0Cy4O}rC|7sCQ_7doEaLEgRn-8%JT*NI<+u%wQzz1iC zYXH8KT_Skd;nx6uerrDvPG$`C&yVZ#L;Eps>Adp6&+j_S>-es46JkOFjNjQ$hI5t5 z1{lA!pXUV&2aI3Wx5MQ@3FRN}j2D)J7p~2Mb>q7z`TwwD+FJ^ zGuDh|gG)oEcm!-@U;~Ct4V>#hgMguz*TA_>VI+Yr+XMvyjt@;RGs6OTG{Ct|VF*|l zU~sNs$5!x~h&Z2OI63U(Nsovy$bTCMUBiw|;dVO`fpZNz0Rv48M~WYty!oFMRKRgF zaAx?oAMl7|z?VXqLFU*oEFFBwaIRV?0W4+}R@*D%P~eU7hzkSrK$H!q%J{@)LFrmV z2Imqqynzsb(%Rr$f`(zm;46gVYUN)oV1ZdE@q=+buG1O}s{lOgqhY4$15UsKz)O2$d$A)@B`r@*lmyX zvBBqG5NJ1MKN06+hid>LI}dW%So7O}48;F{sM&?t{YfO2k3@}ieK>IZ{~;>iTqA+E zU-I@s|ATW`MAG-5P;jhhvPFdTOnV_5^vq&>L(jw`ItcKO_iXI1q3z*Z7Lka3AckW_ zlPw~wXa>HDi13|`Z&oxLfahNv_|snpFI?%#$v%Z}6>$7Z051C==;3^@)UT<)vRy3s zG5(Vo`6hA>=P?YlwF{(yCgyEq1n&Q|=FbF;PYG%aG}%>?ebP@&_DTL0nfMWghMLJf zG2h9|YzAE^=nC0w)REIGAaufbpy1YFN4)%TRTAbg;X5FL3k>HQiI^1`_AX%ThDz8z z!1&*D#K5_l<1k?9r6@5R|4NzfWAMQ7?>N5sUwCXR#UB?_6@d27@eRknT6|Z0iK>U= zUjx4R|9LdvJK|<3*_?oteuaqP{-+ra@%UkHAp2X?__t{P|8>R-0#nTQXaczZb;WA~ zkIzqNl4`g>%nScmyh8tPzj_S^Q~Iwc4IKZXIk$fzw{ZN6#dpO8WCD(Vc6{3$2(!a4 z3Ez3G=%8?gsHNf=SXINXfZqUT8;1#Ns;s@#jUX;%LO9!aNn8v97jYh7HDKaj251{V zR{<9hBWX*4chMFC=88BQw1t<^5#eekNm?6xH*Ktpm-P>yTo6})uo$jkvOx?#5RP-~ zgWS3@Q2<&WCn9Bfz>9&8f$xgg7U#)C5or09=Ri0+;QT9Qe&dIw{6@K+=QaKR;Fym$ znOwjBg~ywQ`FLZ>^(!5Qe^Ka7;2mZn-nnx9ym9TrOv5`{u3vk+_czn<&X@Rc{d*(Z zhnXlH#L1|_7`WnTvdWWDovtd+o9=0zEYRkGE*;K>rs3u(1>QxQjc->|=74r%DF_SU zVrEKWpLh?kZI*|a_wTcnX+Ftt|BI@|d;Ae*taMG_`9G^_SpWYYbT!_QEXA6j5YA^S zCLiRy@G;DG@EhRlfVp}*@6k4Zt^zI)vmw(K1Mi|u2Fz7z-eNDz!cq;ccpKgrYhVUr z3T;1~^7d!mdaQ=w{$JB+17~6b7BO(`XH(v@PtKn169Ly|Hs$u`f0e73dAkgBG0$V63Rn1l znYL>=KBj?lP1}5IBBl_$aIR^a4-jN;1Rxo%G(yhhd|)VVAKDU*e|$P6y%@~{$3NZ} zE<`vF&K4zk_$XxHA=CoX%*M)iriAke$2`E(*{#AWW-BE;hUwn`J>cW>?g9die|#b_ z4~TTQ;&o6&;P{secqzl+Tzi7)*oe&AGKDV>guLxLN7V}6pRyMe*pgppA>W9V;?q|j{1K55vald zZh+hN&_#VTc+7DzG-``_ttAZ%1$5|9wT~qi!L1_LVLyUdTj-fBYH!PNgbV4yqw1)Q zo3~ul$0HVZ3J=O0a1O`9y$JjSZ~S@>J_+zL;P3LrD|ZS4=Ffub^5{jq8cMhF$AZO)==qTjPx7ApCjlJ)*hL-x zUEG78BU1MX1}FU${6lT<8(jD}pCdq=2EjOQf_0t*ssVQb&rR*l zV2TIt1lYXwBKP%f8-ww|1#bbvKyQW>9)_{p5?e3ocX;C!+3A=+3HUhR2Yci1@bG5= zp8)(19FMC(OsBX->C$6rkZU;mpWAj({|!Xu{1_U%RlQc(|2R$Gs)i`x+i4|y%l_>b z^)vMNR<(z6cOJb2kbke87xk6gk&ndCN#DI^!Z-+Y>%>&1|B*s0&n4E-k1^SNM%dy=e=tKF$S zSG6gD#2=pMoliJ*KCWqwnm`L42X#ev+Wt7A?HNIzJPsi;wi_wiAsZ5WuCfdop&ai| zcW+k*49XwStasz8#4iwzJ4$KCX5F6w_;Hn|!R28+Q4aK-wFAbuhYVv>UB!7FKyVV4zh&$H0x(+*%4&?r+ptHp_0H@0949pHL@qLvDIP?dl)5;i~?T1vQ<7c6mabqpB#?aU^cenlOV( z@78)!(35IcrvGZ9*44jIY1T(Fx?loLeNv6w7&Pjt&J~T~*x2Wy=YdF-ut0{z!Z};7 zw4vjMiMx8m-7rkY4HF7j2l)JBSTlBi&4pB_rJ8$XPRcfXDkV{z7MMppxB_JL*U!)9}*`zp6LGF&RFI z&QQ^tu97-Psg!SI3gaHnrHZ=RM14u^M%e|Jp+m3b?()@ZY7p%$KtIn6Zq^s` zcUP(}P(zj6Yw4P&)w%O~HeJybaPyCwgJY^KcjzVt;Kwj--crEOjl_?8H#hI`#w&UN zLr`HeP+>L%)8P)6)4NZj>)Old^wVUTjCq()R}ZoCrlDUI6=Nr;wTdl3U9 z_|q%;!H&pO(nNZ2x7u%L;fX6!l9f!H;WOWA+lYT)JHemJ2mKl@11{^MEBY;{HuLd` z^u=y-J^Do%z*%EFIF;v_gQK1A;`_g;;;Hnr{2lk z<=1jnbDnC}Q#lV!lW4~tb+o_vK(pSHn@5eMZ}zB@mHbK6`*}5FRN3uL-G)fGos&=x zB2p0U2HZ82Im2eaa&B|#4i1OK(wgVd`1yCzGtZ;zM&C)FATs}+^PKu7P9-6h&Ofh? zww2{K>)eO=XNRi>GH^Ds%Xv$Wok4ly0(;T2LUpL+_#CGmPn)g}>`MCz)t;7md{3eY zI;NQ)3)O4=Q{tWa8IHRumP~tPvrO2FvbH#y^f`#zTsw)D?!|=U8u!r{%3OzLb+Q=u zES|Y2F>vusO?npN0w>dZd(mq9<~sFc6y6*$na=N3Z&vIvG~@-$qBY}b)(h%&{?#b_ z>&&r#GClZ$I%04<00RKvnpOY>U}uFm6Pem7a%xda+`HO?*4r# z=0yzrvN1IMMF_rFmDat86p`;aWhjs>@v6RzE66;BzI#!fpj6&Wy^BDYat%!{g8WZ@ zh_)B0Q!H^0IrRuydlquwY>_%tsn|jx|H8!DlH;WF#{(u%O_u6sQnxs1=;(l(spemh z9kDx{`dxIPzjiHken}l;$=vSL?~t-1=_NHniFus1zoafv@^;WU;7u9Zoz!!#)Va>O*wRE9!K`c9535f|8_` zIQ6x(>9QJ3AHSlGHx<0?q}g8tOjeTLqFJvZJEbLb;8o}jMQ_uI*VI9j{2Inz-K%Q6 zlH~*jiy?xdzKcfH*|~#v=)n#9mQ%i*Szm^OpuK$ zoN|IppF$@Osr@=02UXDuCj}fr53F2jV6zQuFj{x>Qbc%2?bUHCJ~Hlb(ngSW;Py{n zL3>_D$2pE6D`wq1gY7VoSt~`Py(sVv)$GrMO^_5yk`89bpZMEp&q35xSr0mQ07Xyj zA-`h+<#%m>{Lbnxzis{HcgeNl+mv*zlg6*Hj_4kGORIY*hoeB;K^qcjNin)qLjr9t zR!6&Qz$d9y=A_ujNezgL7m@W4hIh>Z16gVyBT$mO1+)Z6C3`7tIHX=@%39P)&%dtr z^RHTNP*(`*{z}erj;6OP^1dYowq^?TeM9YUN?ZcIgII)eM^hr6r44U*<*VYkD>7dV zM$)^Huk7dO>KjP9^f?N76E(fN&>-@eDw{75`HL^SBID)7t+Kg}UVRfoB)smj7c}K8 z^*#)!de(r7JcNGGHVrLPMTOF~nY$a41M8ZGF9-qx{6=`i@1%QoR+pP05T>N9Y{cv%BK}d)n!%E>2 z+QBLTivY|!jXJ=>_X^#O*`!wOgx`XS(%({hQSn=9 zg0%Q;)vsGoyUaxapDr@jD*?fXc9}~B%*p5;+E^4c2cNljHbXrZEit}C?Pm!_%e+N9 zUxEg{zC`WQEvQ`%f>70XVF0LJQ3y7)L&pJjL}suCwbzU1-mG?+%mOS<QwS^q+QH!(i!-c~)0B0tx< z(U5nc=4PbQ^mj1|GVY|6>>pl3Ti;d3bAs)Z9fO@38^q zURv^=x=_i_pm*O>2lZ}2hrERuCRuwbm@io^NkQ+aSwdIeQ@i)BTH35Hcj2KfFg_pn zm^*055#V!Py(Fy0P<6EnNiYQlY4gT}{gS z>M%>{ax770nQwU?Wv)wa)qj#Jpq=llD|%;wf4Nn{l zt2qInFyOOpZ`D7hO+i{Po%ui=rI=r)-lb?m^BpvX{l?p9A^RzJ(mME-!>d~LDp?Qz zE(Lvh5uGblyDKdVsKYU}pIe3Sxz4F?RGNAW>P`GWr~WkSu6IqP2N_UxAJz;Q z2<9)R(!pcuoQ-3noAuG0)k)Tfd!Wd0(?-G7j{YZ{C(rPkn{|GImFd$A`V@SojQ=M* z3-Ga^?GPS>d z_9z3;HI6!d3_#vZ&H4eR7!XIJ7!Zg~AOK_H2==Z1N^${h{}{`_a9^;nK`RvevQuXXE~1)|+MB?o1HqMCi9$?>t; zhYAr^GIuds$RHNhL5~`&bK~$P5s#$FR$G?UZvsYAFrxHBPfvf0&VgP@hfVWS_|RX6 zuwRi&vxL8mRhRP zz4CCE9L=1E{g86ubf{eI)A2Zh$G5f8!HrtCPK>K(0ONXewc)cE1y9>-M7J=GE|;sl zOmVrAfxG9 zqY#l~?r7Ehxq8Mdu3_n5__1VQABP|65 zAQxs4Q*J>kt=Xd8paiDT>I(H4C4V*h>!|oqP1x~7u>zs2+`$R2oKF5<%L>}G2Q_+6 zt9~29*L&a-zD5&NL1h@oh`i~v^lR15g%pT=_Zx^8P|B~>#g>{*&?=>gCc)MUv%=12 z)i7T_X^Gpfx{yjtCp!HN8?F4QbEP`WWcO{R@s(<%Wxqe$-_Cra4pa)S(jMR}`$Jmw zFd1i!Cm0pVP+`llw(5fRq!>`PhZw&4IK^<(_+}Z@a)wf6BKua|2gr8EEAgvF@ z{)j~^V%+c}24U(II&nrFCzkt4@>RO}BNVS7Se&cX4eSe|;HykDMJc;V3x86__(fl8 z($g>?sPGBsFK_;&&Q!);lB5aEOgdF*ZlWD=0i%_gMml<0U8&SIO1$%;j4HoTL}f`t zR7U(|3*PbV@hO+*KOQAb#!@%=K_NHAG`g?7~7pmD#db1mVh zvw69h>%nc2Q4lgeedK{XeiDWnFdXq4a%EZMc%)PwRe%C8)Fy9sL~( z*AjzRDb{I79T4gjx*NWwN_Xf3Y15DDU`mJ0$&~EVO6Tj;Y074u#{7W}kfqZ@f2i{< z`K=CUyjTGBp_V_?1f{}Ev;O3md$v-aVC`npzK+OGur|SxVa9Ask)xp-hyI0Ds8(C` zMbd)g4Avq{Wu1`3OKPMLc#5f&`u+>6`j`QlpVH7m)_Qfhr5;uC19f@L+MW7_XuYVY zUX3zEb%*Q=(QdZnqwW^UM%g$4y+|y^OLba(R-Iz%*$q@@)tf2(0E#2(<}4~SNNLsY zqrLS3y=lQYb*(8M8QQzReI!xH4dX)wQk#;qpj}+YIF0`@%Jv$AIU*{lI>>zwk|s0j)Ij zI*w-}HrG|pho2Ip(YqHwn$?MYxdUK{z39-b+*$fk_Bv}P--|T=Z*_%{kZS{thMAm`txyCh31eGsZiTQyt0_aXBmc!EouK|3y@f*PA0`lGUa z>n^HeO(n?V&tF)3QA{ItnCgLjla8H6>t{D&ijHZbqmAlv({U^GkOA6gCB0ErzaIeZ z>Q`*dbgl^lGZgGk%E;rIu>nyynpQWXbCpEXTg@2I!A+!G!g90vGEKY$c*bQ~Jt_b~ zkH=t=sa3c0W)}>-moNtF{af|9a(z3f1yvP)j+VEeONVu&b1f{_*glkP;*TkcUlWaV zsMAeZXgU-pTuk3=L@oI9ivA>5K5y}zm^@Sdx}xVX;(-}-eXB$W<6j;)?qkH( z8FYWEdb6eEKMp>HBLA9L5EYb5! zkTA4J(MBjmS7_l?x&6}RD_AZ=FFEv5p5dRGK`&lamnoSo)Imq>Ww+2cU7f4cH_;P1 zDy*!LLVUGhWd9Gek;Yx!A#|$HnI?(`*tG^xCqfkaYGah$7o~3#9AlI+`R$uYxB6rES^~lF>U^`iTt6ND0!tcj@6N*FPmH%O3nMU!J-YbIM+J#!BSdB+|5Cj z)=K03)VTvHVqY>HWk1~Tiw!?Y_`|4lo7TykWDL-Orm;&M9>v7ulkK3Tr%;l@jSkwu zfeHjZIE9X$`H?%n`%5{$tk+lqKW@^y%3$S(O;9`Le5Zz)%iN@6J)}02(jZL{q^yC^ zp-$Rh)A5gFrI>s^Gis--ya_sri0l|P7-b5(0aT@q5_6QccScrmwIgz)GwsA=yEzeo#mFR@1T0+F(n?`!04%#yf_t5@rVQB+dB-0yIO_ zq7_7ZK-I8OaiocU{sw0LhWBZRrY*PZKH8)g(fd~DG{u@0uhd9FrR067W8@vB4OTQo z=v(xzRa>b0F?;(iHnv6OFG5xW$x)XwD;`Y<`P6U!#rjt3pf}kPWOJb)#k1Xj7F&8JXgI zLuRe$O&Ziy8)Hd)uSuUu%Ps|6N87q;{S=?~=|ER)i4yZZS%b9IO7T0ifqmP%bdLS( zcWFsCZMCIlrmF{8ibRmdg)&d{r5h|q-f*iPg$NpbC1suix`)uAMM!j@a0GkE<}ID; zFjNnvXdW%>f$Z(O-Jw5DJNv_u_3s|qD5YYC)I3U;It!-XLuR+)MpXa_7>y zI!p+KbLd2GZHiJbhr0LC<}2Cpw7QRWw<&&sgJ%DUBOwWC)H_%kr^GI#g~1Ri5esNf zur|d~hirN&8%l8!4Y`&(#C%$Ltv1q9J>4OXfCSUAYqd$1I8??3x27>uskoC?hald- z1Ue9+%~gWuig`^roXY+rXY|*`nvzyHJbHo>F^$gk*A`kb zraEAg7TRL!04-KYUrq-Gpc#sg474<5|1z)Y%!p$x;U;sOL*FZHmtPIk#w+zxrBdLW zC6$8wSzbzkbG`#dcSODY6{d}_sL2j}j#LtEx&ifA9V3(iQ}iMSoo|6U$XbEPj_!l6 z$%5Wn{P=>WHpj?gQsrPqAaNiu1~V# zTL~+aszL1nh6|0ZmgySNagFb&AzGBF3~z8_<{V+FM?Vu&sMHQdaw<|gP{MDab;Hpg z66Vm#p)ev~l`oWoA`FTORu1ZC(D8bo1pl`OAR3~o@Pa0D5Oo38iF~F{)|9d z)=i}Wkx&o((AHCA)o+YM)fY^qw*Xhlr%*HdnNw-xFwmf)G|V`#`ANt@?n*sdHXKwqqrBu#Ty32IIHb;Y0R?$ z9tRiv>Sb||&>SC6KaS9P`LmK2#!U8j(nn~KruvsJi>=>)azK+_xvb+~nc?U|JS`dt z@*L=T0+1L_8v(EsVaeNty4+;#N&gLfjlvw7bcv=%yCgwvGk=T>smHRk7f7X*bS~_pK0ZD1 z84YK@NPD8S-rXBtyzJf(WLzp-VG*4GPN{s6{)BJwLp;gGf@!qY-xBw?`+MnV?dBfI zSXO#(;qm@WxbC2X+o6x4+bt`GPO4(P`V0`}ERpYC6f{N~8^SC9$>@x*!i(cKlMoME z;_Km(n`!kJt-GZKRWn5{M_R^cL6rWhYVH>Urrkhv2O%?K+eefu5%8!s48az^mL@$( z&is)#VU~-!L@RGXAN6abt2b%0Iwv5CELaR1#P|H}Y_pKNp*}t~;MkfN1fH?lbxOk} z+CEkrWHE#0Eooi&eyrBlvU%@iJzu8L?Pg3h30?VkhtOt4NKD4{*EAa@1K(sibh9?t zH&l3*)b7S%kb#zZPtXTJmxUpSgBQlb=p{lTI_D;AjLNw^?-6$}YA(kW`6@_7NRY;7 zy7AcyU1lUp?JVB+1VNY?A(K@7#>UZs+pNQUtLUp3sBrtcVSiR8lHJuEOnH#w<4MX? zuo0&~2(rlbun{QedPPE#gN#7Qy#}hGi-aiU572?_QYwiPV^w}v^y^U9=Dc`1KT!+i zej^YmKn!L?emuQ5$qQk(7#sy2j-9u|R% zj(r{uk;E{AVShY*5vxTi>EF}USZ$0c<)VWP4ZSq(K3Q3xZiz1Y!5U=_Mu1LRaIpg_vWm#A}O`Qbl|!jlQ&f4%Cup*jI(sO`fna zh5IzqqIK3AP1Sl6ZChuxxeI1?m3VBsg5|qP9M=v}1cWGYLc4-Rxk{Ye4w2$2aay|) zHy$-goN1J}8dhVY#1*c>8zrtaa}gKG@@5(3#kpZo-bUDmjq)bHqjgeH${*JT3}N3@ zTCpKfoaWSj;JV*DlZHNM6&pFn=3~PEN0S7+zylWy_p{EE$5jX^* zbSAC2MVn*kiIL>*?(Tx-Fh-q-wX$8Td9G~Kc@STnP=h*yK}70om)bs8HUekK)PmQz zg_>P=8p|BTj1$BQuue_vggV8M8|Y-JtvTJEItd}4OuzzG8$eidPPXg zcDqqhW6^8(1T(O)eGTzme}@7?uwvYqwg85akNmbSNO0Zdj&`x0E4cJ>*7!2#MU}dV)4ja5I9Qp&}O- ze>nBATy2L?JFj~Q#fUls@qRmm&4u`^9m4**!SU^E+Hn8|`@})$)CaW5O3WZSu>#hX zf*YD?_Ca7;5ZG~0cI7jZ(3Qa|X5urmNq^EBX(W``D|b5ky(#N<*~DTF&OtOH)sA-e{4b&j)m!zg z9KXMvjxaTz z76I5Kc}HP?U)0Uh*3n9FUm9{JI*d=ATgt@fv-HWYVK$siD$Uuo9ov!=Ch4$Zb=W&PrPT97*(pAMIFJ_TmJYYu(qVGHWq z%Ybj6Lxb=4iZ1bTv)2r_Bt@L-*`#S zVtB{7^kAkoVWQ7(4$*f|3UP##S8PdMFkXVi!WC@79xHr4*5x_|mW0okhv{mj*1fmi zmZpCk`^sfJ?hifyd=BvaB)|KZ*AaY|=Fk$xM{jHT$EmJ*;B7l-JLAhAYx>8DDn4i3 zkV8iqp9uc;C$8dw_sOMmj1SxTPka{e_Qxq?9q^gC|HSVHzGgekVtmeyf8wiwFMgah z0I%dcK~JrNjV0nKIeTohU`1f=|_*HaH_}`IrBk=ZbXbAfaCutV@fnU>V_VX%eyMaFde`v!Ahdi+L z(Ol1=G2_6N4aIk&eEYvNXg-}wmp5v?lzo*1=I#`pjos=v`&BX+WMjXBRF@cX>dF+o-e>n7&+<(59 zOHX%Z#`zbclX$d`PsnEYlmI?h}NUyFI<=v33SsVUMbc6=+MtG zVqF65cm%alk6!rmN!Lz(qx>3S$@&F`Dxt|J>A%qGEm$RFyp0umh5EFqnEt!8qAvr0C-bnj@G%7_DHXFiw7jW7TcklMO`BuoC6_2rH4r z{+T<@(9cCe*n~BI>IMdjD21UY@FtgiXq*uUEH?sGu0Z;Y1|;lU}7DD=_APA82FNH3J@ZR0uP56W)ZMSUeA4C_bt?8Cl1mahP7h1G$7u)69&XeZ1Q@4M`3%{ z_#W{DrW{N)%f7^F8SxC_(N}y6ZF>UNotls7#1k+lC4M6Pz|Vzm@`Lr`*&iTpjH)sCJB2Ae}H=>Cp74u8x50B{Vi=xKKs@ih?aJU5+HvL!_Rh1~BHwsgyBoHk zh7TyDK*LG559q{h*n$$VmF#T`s>fclum$Z#z-1i~B`(@v6fA0f+Y(2)N*vP;5$h^( ze7k~GK4_FUu^qzfDsf7?66b?MlsMfe@o`UyYm5>%wkvUoEOAn)DDhMK1I$#hTT8T* zd5TM?}EOG^N;~*o}_KKh-^LzP^KP>q!*_~< z7tpgW$|)(*f_2`T%{m|SHs^TYV%!%TYSvl9G}kYn^DpvLRs3J=K?e-8k8ff-d(i6! zLi;ZWVcqGK*v=lb-!S|1Z-+=gRDvV29U{oZadV=y2i2c-kGq<)a@;in%&9@NssF#AkPY-rSZH6^S`uK0V0FRIqZ^^Z)e;Ug-x4BoCYxXII)#uB^ zw&tKzUjuO(@vu3_u1IrGg71GZ2iXygNcB9ZS7|p$b4>oDUfU}%$du3RZMIi3o@tn?s6;yy@2B) zO26eA;hTzjT%jF>)?vN|{zx|g$N7J-4HhTuP5Bnw)O;G73>~h}`Dfsp4U18zp9l<5 zI$oiri~zw&CIkaaO8uqnC^neheb>u&R6M##=k>pN^Q~+cMu)} zNPkbWD@T^ohws6V=+h1N5OEA>Uj(a8htgqCT6_d&No?29o+CIvw!dey{yXhG0$XF> z_qE9#qVX2TtRPywR_p!t=J&M>U(06bzIa26&p-A00H&l`oYFVGAK>rMvCVuVkL|nP zf1pk6kQUjjU&MPeV{l}ALaBDrl7)M6xW-w9B!(W7Ry*HFbS2!WDZ`5n=KZMZV_qwj z=wt)Y&<>G;3pd|z$)gt1ybrxN8aCpB8&4P$7t+fHLYSv+zN81Ub?BCbblIC>-|S1e z#)xeTY4%56F$G0k(p5$rTS%9@5e<_K#HBWfpw0^bXS30bi)cofS4^49F6q-4@xUT_ zz6^3Mx31@yi$LLeqlf346b%*W3;-{jq+AA zHuGokV>;I>ezmma6K#kk?&n7R9(e}%#3wkExErZ?z6Xh;hf4CVxY~tu<9=<#nXk2d zU}Y%!6o&?P|3-fUu9$zLLFG7aQiFwGIS!fm{Y0OXYeU$=(OizRP=2Rr%4eWU|CKhd zUtUc^KG)_`%zhlvVB^2iaE2jwvgXa>sdGeSqtxw-Y0uv{q2YpOeP_TAw}Jb&oNCmg zxQR;^(fBVsJK5bszcCO;7I};lX*7iJnp^qTbf5y+iTH}nec^SAr}(QzX$&e|L_@#Q z5;%2nyr=r4f%w{k@cj~kF|49df0~o8T||Aq)MA)JAW}~lh-ME$2#jc?Ar>!wN%ZrV zIOB5U%SQL{FH{Pj+D-nl(Y26_6+v-WHu?v8=>$e-()aYs2|2!n_LKR2qkMruO`@SE zy?WH=(FJSssL_vbcov|DjPnRg@wsr5oi{ zYJIsd!t8>InaCBB+72nzOt6ZlF49D`O|Tq6jlJitv1yiAe4AN4>Pxnd13LM>Loa=c zQ4j|U6?{uvnM1!{p3zM?rP(b7up>Pnzbo;r^gKlazC*Y4`G%H!hx}I_rf2YN$vWoH zBdN;|FqHlE9af|1RWzhZd&=VXwgXpdASZ+Aw<_&^rKSXTpkVV){obM9K+C>I8-Dpc zM0a2fS%1K~t*8`tp0sC_@*3*!qjt9?|5ZLZDlU>0yh<$7#f$@G@5h zo)zdxBYxKIv6Q{(&<{z`RQ@w6G3agFiPF|t3IM-RP9ksCXtyb`|EAt&wCR@U{SN(0 zuFS5Kbw*265?`cKXXNISXynlOt@=ss0^5^l_%B|gDSHldU#^n9N%W|J*qMke4STEH zt1C{TAAf<|t{L7Wd%-|U5paI;L^yz+BXT08BHXw?#wi_6qBno_O38+21v+y|pC(bq zT8TL1fLUT?tDegYr;=zisuw6=(zdQ76Il>=Mrr$g%g_Oc} z7s80MNkT}97au1*YT9Cc*n)dIdoJR1HIH*X$Z*CXi|I6qnH=FxycRg)bQFMw2`m_v zI-_^lO6kOZyn0uDwb6-u7IW{qmLh(~rV3ujpa{2DbQjv}@WAG^ zQ)&dxPu$Hk1K6%_HNvVcy3k6LslhuXNH@`p>ro~H(FJ>VoqsjXEan_znDf{lw}ec=!#Z-GsDj=W*fU_ zYhmBgR{4UR?-Kgi3(=W-dLwgmqtzC#6tcf_=ocA2dV`;Z$1E!5U7pn&gZxkZC_TB+~w0kQsOsNbFABDv{%wc`AI8)-~h)Mb(pHu@^~! zXK~gm>n2*_XPv7g;(;OdLr>D@mvBxwa14dCz=wTO_~l>HCoMSUfQsH(h!(^K6rV3O zFIz%`9bPv0u&;2AnGyFcp&ed`&QX;(YtD$rXo$a6L?rB1wr>si%S&iMtBk3OKbmr3 ztA2{B=i?>xo&gsObwE@xqIwDSz3i3rVZ6X3M$pA2^spDAb2`SHxSHRQj;ijYgE~hW z;66)fhSMveeWMM;(4}r~%4 z>`gJ{e})Se0oMMMebwt|M#jG!Qg2n**4{ zKj~|S&Kt(&2bR(*9ZH&0xq`tW%rX_G_T-&&Z!%(BFJr83Ln8F6L_9kstX7+r?%Igc zDgTAU53vZ6MCVEmeNvRtLMB`!59PaxCbFh5{8~6OtU+elJ0B8 zg)JXfNnmvD=W7k&J|`lt!^S8-K5pK%l%7|tH!D6Sw^-Oa7hML*jF1Yum%62bC|fbK zCm|Nf!DxsDAue3-;~uz}ms=(nQlVlg^)*{Pqdat+p&IS&#AN_){;SlCBMA#of+hlNGU=TcbI4wphAdA9U-f94hza*Q80gu-3P zZlNGd(AXJ{W0|linZD>OPfQAip6C=pSnNusq5fV7GsKHPyqWBl7J{Q;o*^#2N_LA2 zAx07mX;GKlR$7G3HU>G4;D4ZcCDG_YbX`W*YhH-rVFt&*WgfBMfGiwtz;9Yce|a<1 zjWEQ;>}7mz#dE$hW2Aw&eVLROB}0XvP$FhXfsy)gJAomFN(tD+;99?o&Ie$q^lWr` z2?o*CGY%Uyw|6`utp=zTav&RN*)F!B;RE3y z5#r$SWkO<^W=O;$NqR*SS(=sbKAla z0V~*Uz-Z2RtJqr?wa)K7+JQFjL$-pf-2&q95twHH4;#QV0MlR$6_lkCNDV<&oafkS zK#vP(FaHb|pvvIo8P5)0p`g_oKqr7n`37sF5n*;WM9BFR$@na%9o?+G{8LT;RG zRE#?tYC=%;G=RAPCZQ@GM8xLM<#d@@%TbO)42W1xeY;zGO{zrXLwVRvT<(!+Q{<8% z5QNDJP9k|#vJEg5FehRb$t_w=4|cak4vtZ9TNX(EF=GUr`Xt_IVE}%?aNH7APvCt6 za$RUHhUAhD*p4^9+W3zM?AeX(2sl!XAQ#7ygW&UzBju*_%Wjk}@#XcfntSA2-}bIe zE+`VNmv?P!wh=S%-!1S!d=5&@H+e$gQeJ7)lerdBQ7vX1i|f+UI%!f^wo@G5@tJ3} zrQ_}l=YXH`3tWZUhY0hJVf>WeST7joDig4lmAIPqF^*#v_q3WrdxFAs6K5`Bivg7% zsBD1ugm1ooxp;!Q7hULS?Q01>)95-<(6FB0xDa*-ev(3|T~8}}S*KeHR=W3e;_v35 zI6`2k4Fs_a_T*MJNsZ>;opm-eyA+t0Y1gFrf>#f6-xI1WMAL|&!iM!hP zw(Prb$#t@|y1^Yqg(sMSpmFU6A^C2Hf=T#9sCA5`@D6ttE6)oo-?>S4;+D41Z-NDj zeEeoPz1!b9NUjLSo~IYCwN6*;OX=LT*4r(aVBR2~ZpjF-CMZSc=<^WkETt@kdiS-C z#A2>jU+Yk5ZVSSjq@87TC8xn`gFBxCG0kEY6%(_4sZ&3Qx;N)8C;u?(1WU?dr#^$` zgjst~hRrIBM?ys@Tkh1;neh4L^rp>A|2e$OK)kk`O#N^cJQy+9`PuYq>6z=S11ReT zoP$2H#HshEGxxw^b+DgRoNg87vfL!&ZTPp**9KYpQT%n*a6EG~p`UfCEI?yD*Rwcc zB0{33vJft`2Uy1`8Flpe0Cb{~6zVY0 zI>vWDSq55%%hJ`LT8-x6JLigdvAcc5lT5DWc~3TvlDwE^h2eOyOLHs)|J~dyCzjL8 zVP4IWjb;&uAC}XlFsPJai)r;B>lE1>RcMZ{*k*-`^8KtG>9rfsjW|xW`|d-Vuq-hD zN3_XIC2tY4&QgkF>F6M9@9v>E7Ssg<{Nv%xb7f#Oof~8omqvMiO3lVis4YB@>oJhC zqj2YW_F(I1|DaJ$dDtUp1wA>~8mVNCqE7}}2Pwg^^!H%v0HtygKSSG{BEr#YqGFu- zhy18>5X}j<_E9QgXmz-CrKNURiyk1yOwPBiY0?yY3hx$ohRHi(87;XH%Zs{77tWFe zGEvV1EqQ%gUCfn|0KGvmcumzIt+ez;s31`uW=_LkK7tvdgL}myhEVj97JUn9z#O%L zug7{+>ik75@-6tuDC#v`i~bmM&Rao!B4pzUD*_llXL!mA zS`~rO3LE!<2$-yH`-(NSP$t^3@_&jGI=>pyHolN3@Tz-o$*u)L*>7 z$m%02Xy^#*VA>Oj#{X%I6(_UVHotk>KT22J3r`JkQjd8`*KafO-lJ9jjN#9$pdW`J zkLh@nemLIaclFE^Fp9$M^At|hml>SLne&|$^yYAgoE!jNr$Z5Ve4<|zx&UGjgxNu@ z`V}VpbOqfJr(C6suzQs<46h^QF!~2k%4L?UEiHN<(Opc%UmAU+@e%rS z1p3I>FWqfxKjkpUEExj2c4Aj*)H+0gf8eMU|Mg}w`^M`%MbEhH>Ouk(tfQx*G1$r< zqW?t8L_}@aHnr$GIhC_3Xw+z=k^#UvdCB(4(X#Uh!p03P^8Qro3i@@lSGC!YPthWs zQvO@#sK3+b99l}-&M{Oey^pLnS?^ZrGuWR?l{d*v2f09bxJ6&hBRwdEI*yf#fqt#B zTCQVwQVOjy;KIh0nvK!Rh@uoaIo2v{Tte`qrL^e2jHpean{LJ{n_R*8_Zyv;x9F@K zn0wwv&${52z^-a8hTb!bNVshV*(%W8gT`TUf$Qf4gsAD{6)pPjjKEvlL+8ty z7H<{?-`^r_(z&E!-(#Wzr!5B}_ z>bI49Tx+CZ(ICkyMZ^alo_aM7lC<>K@e{c#I++Rnr0B>8wC6A zX`4jZ6oa68rL2Ry+u~!V8u-vvGK=l;lMH;?Dp|y}%-@?T;;lB5`hkP|M|lYp^ZO1x zpS$4URWxZPBv14Q4sZEpIs%T3M{!S<0|$@dm`jQbNNrn5E2oeu%<=Yr(}r2F8fL!l zpx>jtQmA;(I9q;f74?{n6hg6a@u2K3_ssSpEPBTwPw<^sMIX)fl5G`W5L3cWs|?xJ zW=c3xgl9>(2xnHYY`c~6p2cbV>_c?UZe53Wv(DPBi>UEwRcxh-Zj^^D6(QB?P=zk( z#g|QykQhY~X>FyNAIc!4T4tJCs)-S-K5uZ8q|xAc#t3G)viUiO-it?SV;YOK-t_uB zIs5stY}@>_L*K>Nu)AhF^#MeingG#uxPYs00OcikiMAqa8oa`!sdv#w2`t*4rtY^G zS|X=Z0{h{4F8=J`we2dEoC)5JYR|( zQDM==*puW;6s@M8=S#UGq6&J^A$MhJR@0;fUZO1qX$a94yr!*ai`#3QgHKxH7Hwm!V#HBwP~;zImrBe- z21ScOQTcj1ic%Lv%snz6vHzghV8oGQP-N^EarENH342mZvD(QD(}|yKu_K;fAcDpc zuxx`nnBxf^f5^=i_^>;e0%%7$cWrWWReR!!nC5zr*HRYGL2;F0ntKgeALk0Ntjl8x*`WopQ-Fx2gyl7bvp*ZHQ zDGhRy=6B`bg&D9t3~}SL!Z|2xCJmE?QEG%KbD9yT2sNxI1^tac#Q*~p-FR6VSbUm{ zK+9MI6>*J0+!AO6N(URL@*7%d$FhJCiv51FuEZKSJ5&0lhHp3g><1*gc%Aec3_n}? zriz$LIR1$HxTQuwDUPA-X;N<%7R)-cae}hq9`^}KX;21YFbjmrd)i+Au%9)KJyv-* z#3LT{#?_4Kb_{WSTID&(8V`d=qOy0ZOro|OM};o0Q=02M9O5c9;37};9tL54$=Tnc z$8lyG?je0Omh-m#G;R%ar7GN+GTJTol0zC3#rvb1?{3jE<=K&zHF&zB>?rk4w~jQW zmA8l&M<^{FE9_J#SRcA|Kq0U5@l39mO&af^H`A?A{n{7_*#^W$!eac}qbwy{L#++aY{h<$bGN zdGlQ5{m>|HT$;PQ?xGvzt+-2;w_&B>%W^9*t7L)mR<n--n*a zmZrD8Y*lJ99s*l^ulpv*gc*Q08t`@hgtGMtM|%VAZ3FtVZ4Y_JR&44B0OA7#|K@a^O@F}rfOH9UIy?Vg&+3PY*RY5 z%6CEDy0`5;keH4J;&U$qZ&|t+PNN~cp9K-UD$&LDx4_P^90$2ES2mpDcR{$8O+}|L zl`ViF(Qk#k*HL2lRmhI^u^`PPW0R-w-yMT5fcoFo0|!uO@E z@GYT&-PKb?UHV`wF5pJ#a36JiOs;?gA~4TDT+cx4y#|>nnKu)j}FK^U)O0iueg5u7M2N;Z?aRD?r#Z6kf zqEVkLJM1zJiC*jk5GN-2xmq7^J>?#xqWdCOVy4Tyk7qi$wb>ybHo|A{uJN<#fDYx| z++m9fQ=rj+KIhyGco_eP3k^8P_W^q9aa3>#W^{wf*};9wC*2dQ6+v;r&;zVS(BMk` z%N4gJ$Q2AT_q$}=2QoRQUZR0Zae*TZfsR|y#-W#Js^NdSK46@}1j%@vs{RjmR`T$y zxN*TJR0Ku(9$-Bl?lbUqKs~bT0`DXLd|5vIl69Z^?ui(krww?H2ab*t)Y%2k_rQe> z`X__F@ILwOOJk2q;@uZhH3x9f#}tKtc=#nB0oTJXLceJN^L5;V_M@%%<(Kg8yy+s0 zIf312NxqayV*OQ!YvKh=TYO*Jdp^m38;E0w1owPQaTmqWjM1j}zeS)|+lOC(mWh6S zpIf05DTLw_%~np~RJ#-!v9~S|zqdogx;R<{qRrJG+@!%F4#C#xetGxDN!A353LZ~W zh%s4$3p8Un;okSV+d?4t{WF0WaKE?*q%`2p<3wT@)l6- zH|=f#Wg{L@&%^F_7g^i_s>i93_c`T}_qV+T)PP(H#I$yZ!!C{_G9UjRzsL zUNDHXAG%+@8WT7YH)OFFdi;({`oCz?zhJoN`<(SwOK6WvUQZp(d8$(N!&cXsJ=Wo- z=#fr3nWjZ5=FzlpkK7~>BB-asq3`BLICGHb9&C{~4N8-ri{)@+Tb5KC4iMuZ2y?^z zwBvc$Z;wZ`C8+3W5M*Ww0+V?RQZLblDWhdBOi7Uq;f4lE(ZC8;GAK- z25^;zJwU5oHY_y!e_-oo8VpGu2GMSfFBlw~JsfgQDZHc~;blR|19bmBv`$nZy}J(@ zaDGKIUWxzeMf@j(ey>=ED#5?g(ZYa{O6?i4zJ@*R;M!*W9a^>*_)f0^fA}jJ^Qv`< z68;}Lw>MyGRfhGkA>4PL7% z3b@mvRyM=R4T7$exgQg0eyt>M{`~(@_wI2~Rox%(%$XTP7&vFR-x&}U6%iE?5p__+ z8!DRRB~vOhGgC4uOHwLSyrih;vNENzA~VCpFf&D^vLwZ_9-lI!GNVEr1i9zD-@W&l zVeol=?;r2;*E=6JXP>p!zO8*dd+oKCAdsxz(WLj0QsS?){eARJ1viJVch_IZZ$I8M zf@#uz&wC6tu1&U8!bZfY{bJ*b7nv!OX}Y4w&CgKy2ZDPXk?PuL+sjmayFE)!e1Kie z)59B~0vnO6K-sfccBLObz){Qg(G*sSWD1jL@j=gttg?9MIKM{QD=ah&T7OZ3u2DL= zk&YM33EDddm)*W)TgM0=dX_#o0G3}GC1Q+9>>Ohi?C)^G)hZ#3__Cx8?MaQ;oHq@G zQd|FnOpw+oppRQnqwNh>B=F9&^y5L#6s?u&4tOTw+Ne$$&Wmic?$-EYVf5G4`EV{(KXpVr2hNmZnUpnoF3)ZUCwN>J#0iYe?E%= z%88w)A5sz0atDGp>kCg{yM(p5;N?{Rk<-qjWoeVRGNJEsnqGzqNYyuC4Z?3@D=P!< z<6P)=nP;mZzNOJtDHss=u_tb2YwC1Cl))#Y$(AIvbpQ1+!f7DuJmUF)OO6**>blUJ zkMZ5Q`-o?@qo-vLf#E)uCChSZ`^4#XI-cPYT#?7IQ}4vG6)bLuF87JBC>+l*Hs(%~@r{8KR{^Cp%b z(kynxmn|px82D2g)>&|w87>5ucyhs|D}M^Z8&Z)Qg&kMrXUzKTX>tvs$S zS(&72tV^@4kxf$N%jw*4(R2890SMsBnAE(S`jk6Ks`B;Cwwo+Kd=70Y$M$7ya5MG$ z*2z4_jG$)Q8b*c2$wPJdL(($X_LO%)+EloY|5dgljxr_43u^XgKM##wx1Hw^BA%W z&9+Py!`2*{TOnfLh+>q6Bd7zxg@L(&&9=d;{5x~#iweOPj>v9r5{QdA)a^4T#13t< zIPV?s9IgD!bDUwGheLQ=QVi2CHPrZ-=Omr$pKa_mn?VLMR-5WQ?(9&!p~0`S7_Q3K zv6Fp;d->9>*;j03X9A>dWoL7*{S$?^;<#_xZ24^N&UlWRzQFc)ln;$RjZF>vv(TIN zviCh+^uuYKhuJ5dINj6#OV7bn{-x80-jy!Rwm%s!3ZA3-FA-U>uMkOPeg%=#2H$3y zdDS2JA6d2+%pKa&j(vwKS2(n;ZS=pA2-zLHI`Vw3hGnoIfaVO zc!p5(8Id1;VF2Ro%C`Pzub?xakSyL5_O)Hgh)(LJ;)_&#iI)S44iRUfIcL!_eN6PqS<01lb}% zCe6Twzf5drJ%_^1##Q!TeCo;X&*oRS%~V&fB`fLPDs+*8dpk?*U~@!B?U;v4?e-xG zcwnf5eWOQ>!*=3vRanG2c+AKa(ZS1CcJAQ&Qd>j^Z(ix>;G&5j1n=Q-xsD#r*#kK5 z;EQs32bT(FQ0%vYz1&nEuJ0FTM{;TTx5#_-be4DCy`%1-zrMv`I$W1;n@>NTz%jG5 z3t|gR%$v9&|0L^&hjQ6XYWz43?}s^v<5`9{g+xz6hNk__Gm;qAlN{vl~azuirU!_J&a{qEDa6b?)pwZg%*&4mj`9QOGUt>lbnzeVw!D zaFTjbTzQ_B{7VdiJVe8Y7SY!;p67jCDjzPSsHNZ2_=}LDUcxQ~@8nmo<)C(Qej;+L zs}NJgba8ZU3-|KQJ*|uA+(%s;ox6&A9i5v^Lbxly!q?@`)6gH#{!0wB@dxzfY8N{8 z1D2SJbhPeEv9#pp)O79Q`mxi`)1yB+tst96x7gm`UF`+d5vJ%Wr>e3U*0H6MsWj=5 z=SW?QfQsA3*vc~>HZ6F#c_N(lD48y?Lv!qd3AY$7{s{-^q8Kcg3eubgk|NaOhb+O8 z7pUnc^zB7IIrVMM@?6Ayl99B(Ky=x23NF6fe96;~Y?ooRm`w;Q10^t9z=_7b$cc0p zU|JyjYcU6jXpj=mV&RMQub)x0X_H{9=d9-tT_QZMo)uk@lg>b0a?4R#pbHhYt zA_RBCIrr}!LsY7mJkBd^4rzZuzQVut=`ns_V`3$(2 zQRMZj=kUl&U)S^g!|w54C5`bgsA`YVph}EjA6##usa7uQx z6~0(;e{Om?eRBniKI4&A+bBmgQw+7AFk@}@7^X-$?^ExqIJ(0vTvmL+USMr~NGpw) zDvzV;IH)R)qjfdt|LI|D@xzA%jR%GO0Z>ISJMYJKQ6w0z=SKl^-lM<%aK!f+dr6RH z$MYz(xQ^zkXCJBXUh%p^yrzeX1ga35NI-X?0dlK9aBO8kp#4Olu02RiqF@%3Es@Ky z!73mmO#mwF6ww0&z+wmFg>nEI^@%^3_>VPeO;=j+HwuyM&ywJ#m>fu5&P^Da`x_Z3 z#{@0}nNSm-@;7oH@HV|&i%G@!2K`!VpP|rzT?-m)HK=R-vOMZ{4aa@~%GG~TZz4PI>97bO`_AQQ0F*Iy!g}EPIPsKav`y0sW?AK|r701Z-Jg6Gc1B=}HOv`%d{udbpItr)7Jw6ww~^JO$IMPi%nJ68C; ztEf*?N8Ikq2DFKzZJ(~9mClH$gf`m{R=o48=vx)R%bgL|W?Rk>f32dP&8Wi+d{H(# zDUwb@l;5**=vULJW~a0)F>SU$R&xK<Cp~2miIl{Y)4qZhpwjM zEm%;rulYT)d?@=L3@tas*Whjy_j$B(T-W%TjYG^Pzb z%N`>C=T_V6tbnUl)9yBrO&+4*Vyl=B-ds)fZ76x^uawm8RPq^!axg34r>kjGyQ6^K z?iVh=iVQ@)iWSEscqp$m)W?XynMs{>rMp^b^0#s*72Cjw z+8ttuY1m;OVtCNg7(sqxe2G}IZHYWZig|6@Ntqv~68u3vZN>DpB;z{6LYkw) z>qWXxC-)f_@U6($iHj_d5teH%a z0(6e?gqJ@qsZE>$OU)<$t|E5UaKqx;Y~idN)AKuYu^jrPf6|f}9%ef?+!HY>r7+@0 z^Xa%63Fk%>hLBYZk(W>2Zs0~XcF&y0m_#Jw!b-g>pFVJND%_R6ZMF#vaUh>`?oNp6 zA#Jwj7&|`Cr|Bw!uYsf6Y^NAEzRMRqO+nE+&e!tqo~Ko2Tv3@}?%A0cHNUsoX0Ytm z=hM$dk*FvKhLUj%;l7pzddPf?5f=`$io+V=YiYfQQ-IT#TE(@2!`9Nz9w_+XtBxUt z&nk#;9xLATwY1#1wwGaS;>}>;+Rn`&^(s!?vvRLo+qoH7ziAcCVB=cR3{oF=E;w%n z<}9`3udNl$V9$9r#-xcOA+Qh$*&!Dw&Tp|FeM)`=$0Nl`l%JxHdxXMFa;(8Rj}i05 zYWzaxWha>=XqRy-o;wjrJ?Uj#;P75}j1e+(pZdj)1QtEsIf2Z_MFJX5%oCWml!ap# z?@3G51S%0qO~BmYEkv@g!OISBJz=-Tr!zjnRo=KEUsqirVt@i1zOG@4#!!n=6bc=# zA|E+fid#&VedIY()}u7s7yH|V_tUd@8k!$y!8JVGO!oy})H{xydiu%t7@EN-Plw=C zjGKsZ9-Er?t)(x*+7j9vEazL6va+9~S(VN?XV+Tpq4#fB{qo`=yvUwAf#Mz%X`BXZ|mE(9VCU_CZ<Y$pMn+KQme~aqS+aI`^Sl_8TdBbTzup4R%xtUP zj1DL>&D~p&T05+EvN0w^Znb^D#2PSH-v?uiRi>~QFwWvZD`MnHhFlz~Fo~%5KxfJ% z7zY-rR)IH|n3wMw75UMMzGzE_z1Y((0q~~lebGFNWEvhTPtp~@1pDM@xvymLqhqn) zRf!*6kClfTEXb`oWH*4rI(~Rox+O+bT?}Idv%p+++ffl$z(lo9@=;N$(q&~rgWYT4 zT;?^I8V_A*G4>91gqqz!s)1KjI%K;I6#g4-PD)af+?UiKSP;&I!IIU5uJ@N8Vhal{ z!Jh_}j%H(O#adcfE)O$Q;`D)C1r+J3W^M}6uF!5^KUoh(3e(Ys^!^Q~7>^6aeuj&P zhI>^-yDNxA%q#kVj&`~MM5>x$QCx%Y3L{E}LNtd(RM!_>`=66?SK1YiuCoK}exVbv z6+mfU0}VfgW_ziQR-BT@>#D41rhAN|4TlkX96f#wHg>P=G4_+HbTlaevEN-Z1X4vs_i|qtEGyqZd5P5_l8o5#p+};=> z50Ub2(EihCU+mDFZnitD#h;dkNtGN58R>QUAxTb?YTGFGOFSF8!Y(6wx6-jMQIX;RJK zG=GFVUK>Iwh>~9bd<9(rvu>La7l>NG0R6QV+Zvj3Mjp!dGYmUhT5LqxOV}Lz!~%xQ z_=CdEf$doaicLWg1908hETI{*G6nc)SLsL!s-xm}T3jWIE5vlJdN8g^9;Zu&=aVXM z(0G+vt3cKsL0+R!581!43!>fU4*EpkIiEO6q7iQD=^5U?1N;zH4c=5!ZHzG-MgmLezBG*YM<$?K;a!xj+*i%Y0zX=v zj;t6%S;)FdoHtnTt1(8`9NIu5Y|ujppD5#ElduNcZngT$vDNjH2L@+;UsY8w?VpG? zX#`7QWRW$Hh)GyS#fQ+WNvN?!IE|!^HgVi*->>Jw&8=;=x7jdtVJ*#_EJNP(jnHM{ z3&RD4ZQ`c2UpW?cJ0gOom{DOgvdP%{%W0rpmr>b;R`wL5J9eL6pDaTOA3afuxk(>p zpj9Ma7tfqJ@!W8YmQHc{bT8c8W?RJaVO>k7rpPI{PqS{a+)tFS=nM^?Do>SithDhi zc|4UjVK=u{_&EzwRRn*ra15xgQ_$TkZ+}tHG(3-9qgSS>P)ZgNn zenS*!-ru4?T=<#n-GK43|5vyZ^oP4qQ#0jeTdAMJEZcC>e#2`CLF0Gg$`}Gb0&iR&; z8Nm5C!D5iWBEYKF(6JeEtY5+9Cda)2QNWb|SNju5GvyxAo}Z}qOgYlM>Zc}KZ)%^(W|R0EAgR`_^$7vXcZ_FnRCAC@Tpp-;Tn7o1R5gG$-j8Z(UR5vD zcWUxgPjPyqfE2H`qwJn#c2B@s6*a@|aRd*Tpayq^XVW5a3Wc9lEoa;EtQ`fcbDW`! zI0I29;9TVE=rH^6xkF?R$gc2@($ zbqe6^9uEW$5#JGluSb=mP2zNP;ySJeq$~cUiAF5J{RHJYM+Ii0095<1jMI+?+U`^UigLYW`pCj{#lNW{KDq-j4ee;gODfUv|z5`*gm)dQ8=TcYMOYOH_lsdYj)D8xyr7p=) z%UFdXaD|R4d-2WoQfEEmC^g&1(-kgLi=7IOz1Y|!^l`Ja2<@E6^_{hI4nxw;)pio@ zKr|o(*UlNgzO!~t6+&>tob{?QPzviE_9YYFlB~ud6dvo+J7PU*&&TRJ5X}g|V}0e0 z?p^;I@{l_I-pbhF%CknM3;9?wJdYxtZG^20`}O2K9IhH-e{*UxvW~2 zF~h?x4Oek`@%h`U#Wq9CPtnZBzt@lUBClmKzmA9N{%BR*pOfnyIze2=2lK{6)>+Q} zCp?|Oe^~F(3F2A@x7B;^u6DqAi`{^Tcz~N72!0KoJ;3etLMLe2AZ96;Pk-EpBB*U? z_Mk@5gcjL7Il^;?PS76T7NHa5wxP35P_DO%2)hGu)E;8MhX0}zw8I`Ojbo=6jDC*F zvtpOrt`zh$COTGm(bsMXU5|@)PjjsbakWD({tXCI_b9&Xn3!Wa;;O!^#?{ab^}hz{ ztIXq`uX-kMPbAt1JccM9g}v!=ZkNB_B(#HOZRo5WRJB`0%)bLs4FuN?TDqaLc98Wo z6|tfN!9N;`5aI%B0vk4T)(+xAbA;l^eH@u$$XHx&*A7bU@aA`Tk3Lp!-vZKPIcW2i z)Z3MU@x}j453u%TZu!Pu-7`9o~5y%5Nd-0L})`zQAj+M{e-pUf#l| zI1C1*KPNQDj^>ExzPo7tT#pf2VMj>92~ci6y7s0cA5~ZasQH-3z1;jy2Qa3?TL5pz z;I^6R`u*7|6i=$q6;wk&yua6|@Jk(Vt~F$b*L1+AFfF4$RQiSuLOZB5LbVFLGeTH} zZZP8*J+lfu4VX^KL9U3CFSs->3FV;LaAp>oFEOiNCV6h5I3dM#cj9h03+*8NOP#fY ztnDho7qKwypo{--{pBILOYN#6b0@RVK#Np+yyRHs@f1>jY!=!)z3)iD=ie$~=pBf8 z_7LeDaffzLygk@`Dwb;p#UM;aRq)PQd`9Kr;+GtC!4WlIsfcG^5>|q$zrwJ>*&Xwv&R;X%vmC6rJio@bz#lLh!`DM-{=YG`7Od?~wZl1L&36jkb>{;s`eUUN4lV z8!FPA4PXu7T0(mm{XkvZh&HYzq;01Ygzb|>yTrLZJ{(oKVB?Ux1FJ@&HPPs;5lz$LN#iQ6GKxI_(At%gEu`(H)uMNM@1RfqyFLILEk*vq5HSF(Q!TU|I?bK_R z%q^hsRZ`)sdU4%S?j~ViX~J%qUtlLVd<+)2_26*vCg@rT@iPy0bcP!2%6|)1d{_-; zEN}$l@fCj5DAb423b^`^uI3Oob~n+mpzfA!nyTkh1YTvj3jHBh9oGYrEC!nMI@@5r ziJMo2y3f(q8k;Gzf%QMd*B*ZqelTaX$0>9)!!$aqS^PeCsV-X)xt|Ph45}7U1bRu0>>M$Y`{k zr78OXKmQi?eUo7aY8$JZ0P6d;(7z?!$6IGPQUulzj32L<%rJ95XJ z%T<*s;zS4H1T$*!wF>{X1J0T3S^$&IOkwEv0+NeyY~#`ww`@N+^pYm(H0N$ncqzuA z9jBm(cu?HX#)C%fx@G%`1r6Rz559{Yb@;4GYIP#zW=3Jidmp2mvY96A1!Z-mN*R6P zj!5?us-$aF(j9`duh=%!RM7tSSJ z=Qf^!PL&ZE>b-?_e<-S%bGT-eiWt>_;5{m}uu+_)pS^|ZKNR)PLlkXkv?Z|5^~GCg z`ax7@6t<20#hKc≧w79!s|mA}c##T}ItOE-7`0n&MBfg&7xJz3h;awjXu~a*MV( zNDFr`2{pgmqYRs$;!DGLkWL=LzU-dOLQXnuGn13{5F(S(LS_|+3tpCeBq!^dUv?In z?n8pASg-&Is#{&tKC7o!d&&KEn#1*U4jx0uXZ4UnGKs3Ls$3BeKOXdmpn#gmPdOJ0cG@6n@l#9PwiYA2J{R5X%8m)oY=uOPH50bxLu; z(@G{f{g6LZ<%&|g-RKLMo9|J~d=0o3iN8IBH)+oy&Pm-ggghQA_tjOvgU!rghCI}T z5T5Eezj(5qjd?hvaM4$a2RUdUk`B;g-3?r~t{7KiZC`cb`Ij=6`&#YsyY;WvEh z2$kDG8U?SOtC^AMklaVN=+k;3x;2BGi;{&L)o|sl7F(-B&XMMjrxxS>D=tsX+alzt z3bLeL5Fh()5f2wD^QPKo_zJYT+m3Uc$a6!mDlQ=t0LPMir7# zMX7sA>N|;2ix04>w2M+bX#YtF=4;V49&rF+Rcfn{qFM^L6xHCf$ysnk=0VjxiEsmdA1Q?s_xq%+9(;ms|!$3?9lI)gJaHIz~*kK&31I^z}`f_cx_ zi!$Fc2Cz;iSvJ$gN*qV9uA}Rfkg3I^UhNcSUGZk8H$x?2&Z6hf3Mr~o4vwBh(A@R3 z;w%KbdypYjYWmw*NJWcQajB_p!JZcCmjVe_<|^8F4zj16c|u%j%%XlgN zO*+Daq|@?*u=L97lyn}&+PSg?AE6FmsgzelKb!~Mo);3<28oQn5{{S&t?Q8X@n_rH= z^xp9waL#Ps?t0rnv0Ux{qdZyHz8kywJ|1E8I^GOMuxTCJt%g|i5|~i6ljdBK7fVnR zIE$yD{4vL9m&d*KjS)TuSN&0Ef509)R(wGk|&Z(Km9CE7d>nCMmqZ|WTJ6*;g0ro!q3H^ zQ7VGJWOB?@Y4!#he+Bs}&8Jzv;kk1?ZTSriv33o8!=CLbe%e|=m&{Xz40WxOICR67 zdURqg4t4t-^)&YEO}jYs(${uxpXwfson(A*;Nk|HxOUb>V&c#l+qoP_-1ynY0$cRX zl0hD7*?$SO%sG^~_2z$sstxNb&17jE4r>w@ot1cE7_knaV^=XKg(O+A1qD?itf>FM z>BTEawD1o|G+l?%+kb#baYN}c-VJ#}tr$wUqDlW6*-PM$yBl$Di^&l4b<0_*3rTH+F>8HU+t2zj(L+e5DqS zpd){>Qxm`)6Q?!Y|H8qjcnc-{g-^Ci&suHqRM*?n+jAO%DENeG2WS&4#a5x^pZ^PM zjQAIPhf2P}3aICnR?y19Zu#3N2Z7FO#4W`mMIo)*hs?|1_v2T>8GSAIZKaQRc z_UvYG#SwP{TeyUaK9U|v58RZedMt=)vv~`0^JF?dR#oGM)}B%G)=irqTML(OnLtI? zq0R9Cb^jEgf(0aL-JBxZg1GsLbCG~P>zXI&KPhx1Y^P5aaV(L z$781wW<+$HXz;=NBDhq<=X`j8!Smp1H#K#Fv$S??BQAlfMuWN~`}sxR zfx85p{&jlx7G(bOo@;i5ivgUKJ99T31Mcn;;P8pae=MPFxY>Yt2@o%6KKzM*IUlt^ zhBVUvWBFh|7MA5l1DJQwQD*P9qa64EwPsyC0>( z36>046=3CiX-*S5wskMv ze;@it#w*6I0lsZE)?A%iS+)r<((W)u`|Y~fY21zjVZ&=Txeh7i?trW~?~9wZ<5YJM z$1DO{a5($)r#Efs!feNbE%N;?JC5J9d8rp({MI5rBUSIFIjwS%UtSVyNVA0Tv%s-7 zR+LElThaZIZ+=E8u}K&t%-%}DZIDgPNT9Sfxp(-!+czD&Wp%Ox?&2U^-GQe*e=BWj zlYRYa0I*k1JP^ykuz3k|q)ko;Odf&@KmcRE47dv5mL)(EBCfxTYM0|f^Y9+b2r$On zjRPZz@W!D>RSs^lO=92Y-jv@iN4aN!j&&sc&aG6|E^~VZm)m7O!wwL>B&JKxe}rU> zeU}?G(3j-*K9_8rK-IA@aC7J%IapbMIC9X*_+81TolxQKGoV<=!PQ&o=YOCQ)82&! z+?IRywYXv*AK}=KHI&(K`?}!!h5_(nuq?P}(1~xJM~*IN=yc*J4(J_#Ik!PpoKnD? zy9*l^GVh>cb+!*M=Qf=S*hRo}j&8-bu6<^<+ERehH*cl8Y~WJG4Dvi+40A8FBU}sV zO@^2^lOclS3PwGnRg9Mbg={B0qDvksYR`1O>Fv8MPH}bLW2cBxDK3B_bq1$Uk24sN z8%&)sO31bo3M>OX++cf0%u!mc65e;;{01?AAw9;g61ZZ(?46g@JIl)+M6*V;^hdPH zKq>1*+ND+ebj5jCF-wZCWWh8GfJc6QJ@0L-OU>nG#&ru8;PkK-G}Vt#ERGoJa8V|m zV}SCruqMwpZECEowqH_$VRWM#U9&~#1Hu^)Sz|!W!)LXB_ z8m2wmY8xXO>r%Zk(ohVu_4YH=Zp>?6HM6V6-FNJ7w0*}imAH+<4a$ASxOW6(^&f(>W}9Y;M^y$bs6QNj5U`0(`5UbQJc4`)CDez#kird$#$H9v+Upo z7iF1bZKuUulr%#zlmOSL8_->pFpu_^TWzeo;Iq#Hn)038&5*ph-u8+x+?VL8L`fxU zV4Y9F3g`{m<*M}1U3~Kv-xu+(@xZnO3yYtfXFkC==Au)udlJ+{yFb8pN@iEZ)i1Aq z=k;VEf@Jik6Nm$z|`N*jEPaM!W z`Z%;-{Q$mP^`$sB#Z{Nx6Jje=Viz`rMB#dJNh-8xz=*?c1!DZm8DW2tcqCXTR)V&!1PMOFlBiv(fodfcCJ+BAeJH`=Mm^R`k-0Nb2DYJ}y8gwye}oBbw~3gc_>>;73ho5Ibs$ z2JEf4O7kM=6_Cf};kwWMjC{7>E^9Y&kBEdAXP2QHWY}ZK6ftb~!K9Y$S1+#Fnn&dA zqugQ4Tphel3iTox({A)BvvXoMYj=)frZ{D^eZg>u%&e66fN{u z21u3)+U2i=Nm&(i%pcQLd4*LhXvFo{v3u}70jZ!{SfnwYdX`s~>LtMKwg!FhJ{Im` z1*HWb4%g4rIC=)wg3P`iv=_66!T3IMSS7stgPpe)^gP7EI$a{1@)_MmY?AqNiValK zq-Ce+sX%3_A^S@!b~d5d;zPd#D&ErRFR3w5fi}!n6dMHkg0E;!kdoFr`i#{Uig?)1 zo^(85_BE9ma8@stGjuix{F@EjPAJ4-wDbs8CP;;6XjU-zfA|co4pt(iiZiq~SV@wa z&(Kx&uCFAw5GBYkw$f^Qm0s_y;5x(*E8KFv! zRQ)xb4OON}N6%7Z7~;2{rAc8*Y)Iz!C>Qd>eyqz@!&L(2h6SY9-FrVwxyxnIC9ACw z2^jl4M}tsS@^N%L z8lzxwIq;QEVHn#l0CpNM)=1co!D;}z0GN?O1gssfs?K2_;JY!-5wd|j3aPOOSt~>) z;vPUICSa}3BDMfm+c^@=G{9<{V5y*60N544z8B1hi&Wx*a{jW~(7XAM(NutD8DO)t zbUPCJEL$Q`Sp|R7u}B44E`PKAmlKhwbgyoTpER$QdUsQjf-crtZQ(2mwB>uj7uJv~ z(E+M!X+<|>YM}9&iU&LyE)FgLurI}_U_%tv(ZzV*O!pr}LrlSYkny_J{=H6ZG#>DQEFj=ZRQ|*OKD(8E?WrUU zQQA7j3)bRtfHMNtT@5plx46j&iG2sSo$!PJpDJWMk4Gz$4efXzDpuS-L@PlNuI*ME zs|TJY4==*9P8I{48&iS{rnp{8qIBgSTG$J`s`-cB?gifMxlKQ?r^ZH}z1ix95Oy=iA=OBRY$=jz;uRQe0+h>ujI6a)CAN?t{g`#jdccsEm}ZbS1YK z439qUb+}%Ks};?R!Lnbj z8^HLA9~-m}!&P`w@BSEseSBzEe+-8EV(Zvo&Gr|o`h&k0`jOiJ@Ha7z(guL8CXSvO zfOgZ)pOJ2?PgKJx{psuglo{Fyo&)jB97vM}A`iLov}>RO8N?v+j7R(z6Y6jiEaDHM z7vq&75^P@{i&qvJvXfXD`Ob36AgIJO;C;H-!Cf;5E7~i==!ZdQ)40j)_8?4;4a4hf zH^ksSIsqf*o)NS#fz_3z&bCSL>f;3T&3SnLQJBH3OHg`B`VF5anU&1lBf)DU65X9bHzA8*4bS&3YER@-J!1$JPFTF5C=^a=EIy2tc zkHhiY2Ur_B`vv{uA*hFG_fb%ivP&v_oQ~j$^YC>zPr&*3^ic58xST#5igFp3*FhS~ z+d|RL*x}DuPGQO5f7J@wn2bqx!Akl(nT-uA>91szH!7EchM~V?=F+5LD7WT$+Bi({ zGXy+e2RRwG3WBL(7#eEy3w3OaV|NVyGYs{U|6(0<_>q1HjUJ9RIU|qe567gOmj@<@ z_ES6@`QEpRejSds8n>DzjbQb^x(;$)ru8UYT20@KK$08Qke3ClzOtsyHcp7x9^Jq5Q8ZWmk$+*fdy;A-Jqb|{)4xY!-aO3iS1X2C6ndjakhxV>=YaNon# zz)3G7V{m4;c({Au=D}sdy#TibZV%i?a8+>E;acI`UO{2t65-O}7Q!usdjW1c+#9c~ zMDE}@26qvz0nX)BMdJq-2bTsn8;<=J;Q16>9$X<@5nKseIb0>&Ww@Jg?Qm{8Q8{ou z;1b|0aAV=7!p(zQ47UvKg$4Mx5pDty9X{4ZUNjZU9^|TpHX|xY=;?;g-VXz_H(I_4&Uw*OmWsd;Q;<>q@lA|E<0LZ_Rb(|J+{D z1pkNT+WY@!?KSEDdwVVWY@9NxYu6w3*-I8JdHSKH)a5QEr)7P2QU6ismzkg&&~ZK1WepGdxl>&%$kYH$~Bic$0hCm^sQy zkFd-U6Etpf=cZ1ZJaumRxVxs!ovV@Dy8eyNGlOo&h_Wk>DnVML_R(X?d5NX^?Gntl zYdolZiLyzudX&ACrNnEIjj~gZGYaHqd$!VFD)Xc-vz6_VMJ~JlNhLyy43_0RrBwH2 zIi0^pIU1I$r0|VETR)Aad-h{l8g2E@_-0RBg*8pCLYB7_e+kc-Z($i-rBLo$N(g)I zVsJdm-cph!gNbgvg(alfL=kT*{lb$?DH?o{XtddX#c4E234Ju01U7nDM!}b9q9t!D z!AV(mqNS18NJ=pPrJbr7aUa0p_knoiL(3j|@X73l<~}(8{<&F8mpr`m{>L=Z+qzs6 zRlKeIES)mZTkj~bp?`X%X!4NE5-fx#Xfvdz@PDdqbE=Cby~&HL??3>NU)cke>|TlR-(;W-mHo>8tH~^K0b+tOh%cL((tbp+SEg{yy*m}qylgHn}x!&>$?bb z9-;hMs5V_=r%)$@5bC@)O#zhzEA7kQMJPO9W}z~CQuxtW3HLYRySXE+b=YGZnt`2^ zcd@Cz)Q7t4Rm|+!YcE3MIc6`*gAYBvR|#Ox^?Q{Er6^yrGCZE1?*TvDmlEGY30L`2 z?t6gaxr@Qeed#oN$MY(Cukj^iALt_eXvRLk@qB6@;1m6*XdlwW^CWwJ!jEbh9#6OT zk^2I_6wMG;=7;o6IGix#9mc6$_;()s8(QE;Q$ZzF`BBdM2!-b>?ENo4s(2r%jrJ$w ze!%hUy`RPAukt-t?~hnJcu^e5V)Lh^ppr`bX(tPX=Mfglicp;IJM`~#3iVt!gtGdR z^Z`Nz2T;rhC<&gE*!#!;TJ`~A!E-x%&kUe)_KxRe_Wou7xt8D^&mJXsFNc+Q_KxS` z5+%xXJ3wuZnv9fKtT6-W%@XA&sVIm)uh`N2K%r$3#if8?hcFZv60{h_<#L$c&dgDVR{a6rHeyF6GOYGF2YX8-V`YsIlBo@+?IG@r)@|q5@-)S}%0C2~xI3dV-Nn3_t-a!SqO}GEVv;gi1@5W$SfMT+nF79||V#kI;=r zhfu;t$_l9@oId(Uu?AbrVwjQclctSCmKK4T#bDS_iv zrijDX1}HMqLx+`NW-B5JhwqccXmv{$Mxy;)pU-Qo57= z6NRLR?)2Ixh!@XKK2cI)Hgy*jCb{X7Qc)C_vB-oSm^@L1AiINibf@T}O8B51_7F`{ z(o3l2SQf$#K4;C1s=Ph~J|q=ctk|mGmH&PnBn-b3N#VPmy_R4|@Ak4B_2- z(l?(f{iI$!Nq0;c8FpXK6b&j4bu~q|xq1a_BwAGBM87fE`RPdy9z%gjaQOI`5+i-m zlg=Jf9+oP4(%|D@(9&pn_&6KPqG|1M3~u|P>4W3g)%q3piXKOOD$#V~IKq2HQ%pJN z@SIc*hNnl@l{T59DC-AQ6MPpAOES?J?0hfC8 zqV*>bc2+McJApLu{ON=;DB=*xA*PilpPu{3;zzRQKDcCY_Cw3E=l0h~9xm2iH1MQy zQ0mj0YECNVgb}?{G>g?vVbEnio57o-L1#t-)o5n1k)RwTPvS+2bP?=G?~P;9D9$6j zY56H7x<^kC{DEFF0(-S=VtPVMOhqd+BW3}`a+AKdH+^|Z=_6VCP~$0VM%>$nqAQSX zJSSCvRd_yHp#*w9-^V@*Y0@Y4p)C~{0E+t1*A>cq>DN9q=rgdStq;xqObHBii4p0V zGCHMOf^#s{S1NVuSlq+viHEl-ZY3zEEaLkMyOTUmzXJjFn3I(F87tTOkfoJtIiasBCwN+nZzr$6=j8e`ze{xs=pB`EmY{-O#{?Ybw6pJNM> zCyT+*!IlB^;@4p4lmWCKgg%cBNYPwHvOG&{@Et#=KVAA7!|2cf)c7@$Di}b$&MFI} z+5xonEJC&npkrs1z*vugcZU2JalMuf8Q@H(dY7Jb)udkGjZd#Ia|JMl*aC521UqhGmsa0wapm=r!Z-gO5e~fFKgQaSwjVpJ7Hv{V6qB9q zm(;f)fE&FN{{}vUI6$zp7UM@|BE4Lzgal`T(2Ue{|4yCA2vhNIKO+P|RV|kL+Y-t1 z8g|V~5^2mejQ3{~spJ}(>>r8r)isRYU4~Et!^aJwzSpr+c>fT3`8p~G&$8?2_E|&d z-|QXFCiecq5DL73cRUB*z1gx4gll9(U$xuqD!x)n}lxEf`tEHl$^h+Ib{QgkV-Bh}V z{5Uj4gDqr@_FbtrWKcZuIg0=oWk{yfo2ZrWWP1Fj(&L^U$s%5s5jKk?TtiTnyFCb} z0tdGM#&XB<^fZVju{<0D&=mug_BH8SmPR08n^+oyUmQx;Zep~`N~W-Sj7+zbwbH?1wDXn{-1{J+;U9}5 zv>!*Rxm(9V3_Au4OH?zV8)E)x82tiz3D4WNlz<*Jc5K2|YDOaQ9l%)EQHh{UZbaW` z7)JLsqJ?%DUiNgO^0iKi8%}AhVAY)A^mHp)4}=hZwkrL*Xhx)HM*T3HBHEP5{%ylk zH1DxC$HxccV-!QP#&A!xMst@H$r*G7=&70sp;6fUw@`MQVouJnq-e&0Xv|aqP1&g1 zR{=SL2K*+1v2g-psAlj-D$ou<^ye&8)u#A_UI%I*&R&Rw9kri{_!=yvZO81El0w7V zmFN5}q@;)_pFoOeA(OgeAv}uCw<}XumW)c#@C7zYLcjU&N*8!sd2`bw3;=STA3n1& z&2^;1T7DfcSCHEo48un?d`l-hk}Bw*xr08QEeyxHXofupf_D)NG0Z~#-wTP#r-$Y(I%qymNEP!l^}qy14gUD0Un26*tq z5!C(<7TyITDB!m8+?*zmE$hm9o$eTB@6jn}E%!Z(TKSRneIV85RmzZTJYY!8FbTQj z%`3qdKGu@|4FblCC-EO!2q;xTw1w(#qsJ#%$j^oqP)iCW*_0QgM7;qP zon{5GBzYp6E;=?<>`r3W#JT8p@G0R_$~Bn$dou+4&3q1#e2QR3ylCe(<0BzyH$e6o z>8EFPX2YbqscP5lCcMyF^Z5mP+YLAuSDEz#aF zJDEpQp4Jp8MUSRpt*Ot5c#z2mn=}PTX|sNG8lJ^JqkQIjgII|VbYQ``T=FgO;9`&&10Ne?4guY1z#Tkm zES+;T4Gb&!%bT?Ic!b4MnOli}*V|V#GFfVMV z>e1-+pL=LDfe$_QWcH#b_;)TgRV~1>(-+#E|3>b^7kFaS1&BAOyH^2Z-UN_~u9S^1 z5!1)f^&nH|*y(nX>E{^9R8FD+aJM;?`%5_aqkwet)o5_|1zcq?`1A%Hqr?W-vT<}* zuxXx@JB~gMHcbxN0&o@M^{d5bn9+}60D0^M(Cr>aks+p@Qq?$`5Mm1Neg$+dI-)Ih zM9a#8GQ5EtTp353LQH=BtN^|5AZ3NnX!-;q;x-@v*JyV{55sFa(uwFYo-Tx7+!-*Q zTtZFZ!_vm5Xj(*IJ!f}J4?v>)u#!OyvO-BuMX(ZS<29k{CZuTYVlnn)jGQu_9tcHG zUOb*QhnoESUqQfo5ikj@f(JzH#l%gZW1*(N;9LY<4y20UF~%XLekJ4SW~iy(APor2 zEVBo`LHOwRk>SWZcy_}x2%ZQN2s-EV+wpWy82XZC0zDmON|OpElpPNGGl5ZICq2SiCiS$dUel-`R~%I>j}Ml&A{2+O##*DshR znxxG4$@;sgNLm&`TdtZ~r6T?w4 z&Fe?GE#A;We4h&bHs$DQ-<7C;vtMYJWUOS_i>aSiC}q^5clz8Sw`-=bfLDO=x#fy@ z%zWchqxk`leB9<+Yl`&AZ*a!+XKU1PWMSd5xnJiL?n6K_d90B>nVn+njxP%z9xl?? zXPk4GLSS|@xKiCKKB0jFT=|PrlxG0R1p0m-zfhOQF%@SvP}Mcl_qw7yHMB6@_;eqf+Pz`YOBH$4A-c9Z{Se$8v(TQXgwggh~-*D%?Mqcwl&X3NeQz~=FD+0j z-@KnSpRh7(ooR!l4W#E9OoMao3 zfHVh$#r%mL>*P)l_G!P<0g0u-jV6;J9uww-bd-_eiQKM zUg_gU<6BHdDNE&1(SC|s=haQ?PDL%INbLkV1ybL`oyz+h(x`|M6D>w5dY!s8v13tf2jN?UNRqLeV+9NY!Kb{@iSmA0=i9m+e~4TqTsJ~ zWClcm*f=mVEN+-yYl>nvVJGdjUjesoc1bH8jslAq8 zNE{%`@Y&K4^JG9~^>c zm&J<{x+gkM)hQfbJ?0e}yhXe?p_>6IYDD$Y=KFlSx8F9o2Bf1aagfG70>27K=G|nz zjST$B{au}+7=VtJ8Q+zjzm0iijd*cF|BFEq1vDmbuZ;FTkP? z#fwv53H4v~h8yj!HH8K|Dqft>=KxtWld2H6%OCJBczC;uSI{<3FW1rQ<3&Anj32Lc zg4jTQ#sRVSRP-%G&x+d*bJrfazZIV!7)w~U-B#!oC0%i$*zNvdV%RN=+jiLtt1&U6 zXdyU^#DKDg#%aC6U6{BuU#9ACuQ0G3FQ6JlABfVI`|<|0NBt3?*e*>c^6>cp@c(SUWK>DM41@QUH*VS%8RGtVnI`% z&HX`LW9L7z=pmG_l2UYDgM3239~V|&jhzKG@l@b~QlZq=KK>)~A(B?ROm-ms4+|y$9)w>2SSzkK$mN<03lD*E5 z8Gu~cNaf4C!ZKI=2ljnH3Odn$2Z-gga|}IWp-|TevXw!;aHjbeAaO6D;e@%|fH(7D z(Vn`X?-#+J4R}2KIWsA43>KA6B}S_l>2g1Cxu>a}g?}CXtS`yj#Vf4Kb@)*n(k}N3 z?GlVp19_$M_hJ<~7B9#qJ>TeumD}$oSC`#@SWi<4!pTa1dj?rEoJa?LH~ErT>!sIb ziuP4V!LDFzK@eG7QBQZ~XC}e}R|OpGZm||AU4#vpFfTtU8R)OaIiXqe7G*rOu;~8? zKOfLl4giu_X7BX>rI|4{ zcBxdO#bD@5)u~>t@?Va)86%dE_FZ@1F46!VJ>9$CH`FBnFPUYu&>d_rm$0>dH#Z;5 zqPzo_(l4@?ZSl&jh8J%I(ltSRvpkAIq6K&r#-+5JB<=dy!GLbolb;}RZ%@h8mX zYaSn2*I*UNsz}N#VT;a4!xfeddVQL=H^q5)xw>>2h&EPC)#LrcGW#?CTcQPu(dk}5 zvfgoqtOG=O+Zpl|ASInb;iFQc=@iNWNVYm0J_>)n@b`WNeslN#hpuyhv#DzT_?h9H zgJi~B%sDROj7v#kNGX>bkt8%qC6^p>tCW#TTb9_qEsFv-diCCmN}nT?7f&lVm%j*$`FoM|!sJ zAUZlig?>k;TtxU>b99`G3^_+fM|AaRDs(@WRa@%N!U2Hz2(_=q|Co|<@X`8FDfssJ zRbdL#{58!?d-Ujzv!i<$NJpsYB}{^!Q^>a7#kwO@8A*IY&_&OxP%6ovMBB#eszq0E1PJ_esR1r8iW(O#_Nv1kQKK>y0bV3}MdNvnyz$n?D zn5nv-dO;$tHD)X%{^S zsPtG%J}Xg@kvYG46<hmwL1CeM5r6N~(BJEsnl*=8rAkS(j4k zb7r15y%wF}H8R{Zay&zr=S{O*n4y-j=o*?%@c1JlQe3>z&Y z?|^vb+sLQT5hwC9qh)0BW!wvKA}>aJw%gM0Fj_`F1!>|$eu0j^t%|5gph`!rW#mPW z)NR%~!f5H$8_)Q)tV#Qx(bD?|B>t}PHfdJw?0upwSyC79;4o#P%OUuu4I)_&^$&q>PfJAOnMS9Wy2OYmnUE*-aaENi#M%R`>xkIM@`XsG&;(cyfNTG`~>rSc<%`Jz_wt6aYpHsFe&V-H=jda?l%CiIfI+)A3LzHdNpKZA=mn&_K)1sjc)XWWk< zu?arW^j|8FT0JSv6*B-*cK%&g++3#0<-n+{p^e0OPMg4#i}uMnL-L6tV5h=|h> zvsIhMY4!b^aq-gub5#>Kg3+gZY4{&!U328FuA=^FOs?l%qm!xz=WxN1+v+TR>mXDA z;ZVib4^N-EDzZAmx!8@pr1Ia-YM7kuQAz)B8+MwX;aNgd_-<8vE(gV0qkX0tzBe#J z))6c*S`Nj2NbcP}HN6-20Zv*&jFdNzB^Gy1om$yhRts-4NW^9x=xDUex+f&h@kWf6 z-a8>N$2;9<>3tXybt?U|(b8K4DNI!QU2BMH?S|w#?!Yl?2=_mbVyEPqy|tEk*M}52 z-d08@y#H$iXR`Lj%^b+~g^8Y$ZP$|<(JLK&CwiBoXQMs5YecV0PotYTdK0>@qf5{; z9Q`Ajozo`%AM`#)2d?EL6SBM&y0xRPLPw0|d5v>x_P>|55n?>tz-~qzW}^8_u+h(J z?eLGauBl3N%%AA6qZ?jFe_36%7do28$xwA#lU1kcU6`IT=A+t7Pk6nXFpJeE%~;95 zLq?7CRqsQPll8?~*HNVxP~?^9NNub8qGOh)+=?y^I_KY{LVkhin*@pmZ0G~%c$U%L z$I&5PNu5?d<#}W{OQtes8GYaAc~-BDxJ&Lft5>g`M$6Uf2qan{Nu}%mOX_MeE)nzp z^?OI6DCZEjw2}w3Qq^;5=s=T~%0;J7F3&};Lf0pA4pk{hX_@-|!}HwV;yX3DtTE3J zR#eH}2WaZQfs(f+N~Qxn;~?P=6Xbu?MXx&E_EjlEjb50Q#SJ3g0n!vzQjfLNi)Jge zxg|C0exuG=#nI`T(Kb(0vr2l*OwG8@LCumc$x%I8rDZ2~ZmWvAr#C3jSLgO$$U`&u z*Ss(5NF8~Tvug!%GsNSHnE)xOok-<8%*icnDlZ6Q#Pld%Wp!C=d$!mA(f<;~>uXl~ zFG2K`v76{?Q#bjJtP9tweiw3Dt9Fyt^1Ry&60Mu4oKD%P0=WT_?~1vr0+|QNb3K(@ z1xXz&pHprv0G0kOpA;T~gv`{RXh2+zsA-S%Woq!ZplBq7}&(ZCZWC*0xMV9pUoa>1t$)FN~^xKN`?BYNC%N)R? zg|XtsNGm{>o9#WtYtW^S@+76UDr%fjMgC2y4~Mh*=)*y0mBj7Y#@xLcMFQrlxm55! zfWgGHR{|?A_%%=DVvdo|b+%3Q?WqRI2YJ&%>#S`5cQB@fzH@GF7@Wq=ud7OlZ<;+Y zG1R)Kk(5|hSKak5Oib!vbx9lY?~gA1T@BEB7CKy8MbZA3(Tudcm+-YVg6cgSRsTYp z!Bo9xW@V}T25FUj88_>(Q>mBm=fU|}n^Dshn6B#oS~Jt%6UZ>Bmc`usF}FoWLAb*( zg(SW;=$KE%(EcCM42}Babf%5;pEC$=QdM>M5}xhy^GAIlZ2kmz4n3FOr|CZjK145c z^f8^FkGeU`Upr|LigEa*=*Jv=J$i|w$D(IDdI7rlI+fR!JXfPv_p$l|bdjSEq2Ies z<*v=B?;XsO1P9kguXJ>K^b$wkh~DO8IR-tklFC1sUd!AFwI>N~#j?bmSGhsr{-*v$ zYaP#j|GiG){Kop`1*~4d z5XO6zUA63C(gl)_JX6>o;Y3>!h3U1<{!5Ulq$;T*55Pwu(G;1_%bL`XWap3q{@!z; zp9u2Yro8>1ti}Ub1fuPMaE2qRCdKIffVR>_nfKq8z7HQl7kTaVx}`O-eLCL zPiIJD$iYf7<_gFX7a0bLo+V?ZLwXdr+WHjeJy)_fAz`mf_PtK#>a$A2d5GmAIgp{Q zoI66IuKpManNpeYKhusmpxLgrz6goClI@06cg387)OC^I2vYfE&SA(Uu9(4)eU%vh zGsRB_9d)&S8AQK?=}gR4$VnIZ7E)fU&1uV9 z{UR==)E!xYI=+*-tW~OOCqhEE>PD*DwC;c|{$0&Orwm8iR_GH*p4!cnqdk;-u;C5OhbGaOFNJLk?4PYkCqX*K=HSZ!ow2Jz;Gv#d4 zPODRXL6;vANh|piqiVfT&S9HKdljIVcSv_3?cL}QudPB?eO7Zl56xdhz7otbaYFI^ z4mc@6-8=LQG|#boozO?6b2wn109EGz%rsYnXJpjzt;4Ka`ONvsw;NDhg42L0l~r^$ z^=y2nKKiWgiSChNbv}APs>o%5b_(F#0C-OwxRO7WzCsSQ2~+<;moGUxId-rwjU^sJ`!3z%Bu*&I6dm&$eehW`?Z(UO;6Dc)bIQwXJs(biSkW&|#-NW6^y? z^?i!~T?FuM0&KSJ*^lh&BupB^fmKz#){T7w4bV~E`9hPg&@x5s2m3~%!&OcBRcE8k zxlN7fnwhR5S21^AfJJJUi=L`G(0U2rd5RvalbHFU@rl1cTV|*8#>gLQR!%BXrzy|h z>MkyjI#)8AQ~cLChItAy8YAzQYHIXUZg)q!bG!RXOFUY{q9^Er%|uBtRdVNOk;()YEdt$waiGFH81w@6m~Pt8AeLy zuaLa%#yKLYrF4D)iCw9k!9LTql+KSJg(Iq}`JboN3tW7!F+`OXLyAYJ=?<% z;yWPGQ7YUR@0UhPZ+He{G+OP^1;1jn^fsPJZlkKI!OLsa3l>^K6#P3RZvr3r>Yi3F zc6$#M8sB`WX*W7ms(dkDVm+H%yynlc!6pOsT5ookM3i1R{F^}GbJ-$RQY*VM znon9?%OcWa9_ujpz~^jxc@yIhMow{hJ%6)@`7LS_j~bkwQO~~^V-!a38W{RJfJIF_ zk9I=egFa=o?+BVt2kQM){(kfM6X`rB-_J0%oo5qV{s^a@rXDptIisF;6UIoj?m8;c zVgZ@LPkhHM_vIK|cj#?W-oQf6GOAM_?gthk7g|~6QBHYQMv;xwP92cENH@&L(MaA; z2=#q~EaRu`x?a~PZh>Cl)ayNr=mn-;-ZqcvbJyVOsmhDUCe3Yi8$He-H>VeZS=nB6 zNpn*x|JjRaMhhpOnHYT&#%YY@31j>djHF|z)JTR`zdMw*o+UAC9=ZAdAR?Mm)oyRN zbP1i{x}h=|lG<2Kj%5|dc1UR>8FLI0&XFX2>3_+kkdP~8Pys0SJeh16B+pg+caV~1 zGN$U2|0OLTMXs3ZA*D@Zs>v0|vL|biQF+k+H|bAn;r^tU=>m0H=h_W} z)*Hk3Fh)r;o8mQeQ8Sy<_vq3lmZvV$Eil}kwqxetQ}K~mUNxv6bFm!}(Ylkau-PjbzpbAw6cQyqlTA zXFtaU|4_R(>|%5?hY!-);j__m9lj2o=kUGgQ4X)Pl1t#B|8pCqzZpKpNZ(5gsuu^P zRY~4u4@KY2cna$+icpcI$l{=u{(VSBN3H9dmcx&U>~W}?kIky;!^4=UPB(FoHF(~P zh7POezXF49Hy+6Dmb5bKxNjMHPb>R4zXY9npi#}!J zeXpZiw^k)X(i)sIs&!(GZ=Gx&bWth!?+CG_gY84`&}u3#G+cp8A>R%zLWoEw!~&C^=BYm%7H(HGd=ndNrE5ngR8e zUaW5i?3~8_$>X1&RmDFVCzZ4#w*VtFY|*VG`dG`6CQ&{AFBsI|%#b99UNQRvl4BRE z&~1d*dXd$wsES%Q$l0mmZ|4yGmyNGK#-XRpDme|A$No3HNTu|PI6u+W!hvPkD zwDeY4%gEVm&PT?m1lbhi87%|zA*Hiqw>}ApKPbs7703=qu`A{~NNA2sRkH{(Pm(6* zRX`mf9#_x}kc=5BZv=mPPC~C&IUShNOOVYR{3g0s<2wKA5yq8Ca(KTbwse*o3?ua-`LOGKNNyWR{;oh8y!_voJ{8DJ zNKreP&)XHqiGm8K{`&tW>sx`$uRz|fKq|fR-+Ve$AQN6G_;1iF6@pGeN?h$YZ^M5{ zuL@*r1@cS<^4SLNkh-%@e)YduUs!?MQh_{PfqVifbyd3R#{ZHFAqDQBffa%tsX(?@ zAb(dNEjRtQun`r=5={zRb=+McDD5>pSLGzSsshQcK%TBZKCeKkysmS;SY{nINRo+= zQu9-@#1+(hNRt&Rw7yn$!Ilc%-H;Mjd?}>(h+O?LHvgAg0*Sd|20%)FlBuRwAS(ue zid;b-LJE({WWQA)_21xJ;EK5lQtYbq5J(w2&UGUnuHan>iMispLJD0C_`U+Ex`lFG zF&98$uKHhFf!tjHin@Z9Kq9UNyjy{kLc*??+HW$Fu63>-ZR<0Z_fmD9ZfrMP0SOkf7 zmiZhh0C`;JkI>sByF_MmJtTUWO!f#Q=Bm)wkW;SFI1MSfROWN}HpaPwBr~@a&|6(( z*1r-|=py~zp+c@z&Tb#i6TnLc~yU6%CR%VqIj6BN5Z zW>j}OJ#>#umIsM;l&O|O;;!L12#L9J?*1MXa^*7>Qc&Dh7PeIfHJ9XHNU^J}?cS#w zT`ijk$#Z4>G$iE8XE(&tUgjM9fJ3vuHPQn?rLGCG2vX=O{zFL2)z$w(qHSe=wEd8* zU0ppC5_JzEq_Ay2S);w6&}EWj>>wyCvmOA6O_Ia$FeL06vX3C6rYe3;o$Wh}E*Wfh zws=3H60=lT|5~mkI&YXN9+#e7bs)NAHj9gzzAmkfZzATwVfHV{1!&JK{ntRYuNa+b zllYFISI@RZRQ;GMJ14#|y7+z@e=WLns42o%fPT!0e?rGN@voxao2g32lmCA7Nart7 z?>4!<7lnQimG7d^$vXDxcQlg}6E0Z#mB9q;7RxP<0AyeGQYY1cjI zd?%mh&F zYnNW%DOkkO^*^Ow?SksN5`EC&qtSa-m}Szp1ijkm+G^TG{NXMBWYhbVQ{E?l>tv2@ zeP=PQlK4@qzuIT!dRYx#&u*Rk>$9r(!w{~Q&k*0;kfL@f{~rGIdJWAbo*LYUKg3UB zaKUAb3wP=4WxCOj(%TnJCfP$sE+p&^Cs$!`4Pm#A@510>!Fo>Xu%8^yxt~)khWW8& zZwxL4Y?>$r=X~Swt;Hy|rF?|sOm0*Bq*EkH$@s#Yt*xg61}AEp*9Z(w$ksC-Ba$ek z7$cl0W#qTZE>b&4 z-&cNj*|DPN-P8A)fo$7G$-@GJVk zoRrQ$-|fJ77j;zUupeF6MWsg3-S<&QJ2grdxKQgBDyI1!G;dNhy7t$U(#Gn6=+wz7 zcRG_~5t?(2n%|i%@;_n3E>P8R_*(3z5%-v&l#ytAYSFcsLFcDz1=(|pMqA7+bD!@U z(qFEY==5XIMfa#;t)E91x3v}gMf2viA{WKsPGu*c!?uF{jcCpsD(53-JDdMU2xks8 zunqSbat?SnX{gQjlJ!V5@5hXzQ`VvFc|zCeaa*V3z`_=01kU@G>g5_a1Q~6s^6#Sy zo~p-gYLi=657-Yh-U^=rS!+3N;NU4(mO(q_2UoNw&qA2Wia(w#9wX zacBSA1oT0xy$jJN)irH-JhBB@W~A?XAMF-?!M8r709qaY;#N!DvpSCX;G&xKSMn*1ACpCg0*gm_XU>GC@mOnW+x=Wl~L+nWHe01bcfV+Rp>rQBwxn74e9YHmls2yaSt3qQTv7s_%4dkFJ=7$O~p)!W-7MZFaWc7T;|4i`@XVmqXk!Qz4O&GS#a(#+9nni7C*3yxP_`{f8MlLM9suS?%h^r4?d!LqfO7 zRB8XRin@G+jSE|(&Vt#}~UGpO+ zDM1Pnt?v&CxyJQT9pswlpHv`Klc|tvTsuRGU2|wk1@a2SV|&_;zsGZ22f4AU+=n(`|TBo-%Cb!%8ah8KxRQg zt`%i_1>*P7)Wq7*g^9^~pCvM679_W!T)!IllRSm>C3y)Fk3dxK4q0phoX@7b?-GnT zqpz=6I;)V=R27}iQ>%GK+a_3Vm8wae{HWT1H#o~^=}oFelPCFA{ma+|)aztgm0-Rl z%&0{Edm(Wd6S(RuLqyEWkjOo1-XqkZWp%A(DK9``ldZSO*;-5QGDyj6^_Nb2K@F{? zcReIB!+OIhT1)SCNc0hvyMVOUrD`p`dm-V6tao@#t)=%EgrDdx(P?i;(^`68gYYv> z?agYKuC?^eg2YsZg=zHzNf}7zv}3z`f+pkCWedr;)M%M>SSFn}Q5CN?fqQ8M0bwDjIrhlA%vwNZP!*40{iE7wc%6y2nL#+$X>Xz87q&HPh0EuyE|)JG1G z&V!Jmn^nI>{Ca6oNNefsoI_t+V-E=1v!fyH?T@Ys7NDE;mnVuHkjNd9cpDJYPm&Ih z$nBDhhm0C1$$Ch9j3mG6d|WZD3L27;D`*U)*#Mbrm5v!L$@h@eu9*6bh{=~RH$hgr zD*cF#86{&rY{YqOl&kfX8&hjn>pMV3xiT8BV_dCY13Bty*-;&Hmn`i3bEuFj=C*S< zuSHxz&l5Dt)w1s(aaZf>ol9Y^m>VH+SL^5N7+0k~&@ryoS89^vN!~nG75WcXk5-*SWfBxL^o^>8eiuzGCG#7_CL#k(YdvZ_8&&`hl1)f!r5!-zxaGeT|vC}LGo126WkW6$NNC} z;aaKA=2diR(CR)HkjT-$qWSu{j`2R!Tqj+plb+jxr2Mj3C*6upt!MSkxg>S;X>=+- z8PqYVB`ZNlWiR2z!TGIdthvOe>ykFu_YJ+N;kl~%%LI44kW9|A`b~7|dFsU_{2_X< z{0~vSDg8oLrmtsfay>^oYpc|y+Ht5mn<|oPi4y^~P zxaO$yGEz(L zT4YqUjPbLWpD$IR4e1Sh&D%05Y~Y>9@U14zi^%9ORjAV+Lx+Z{GOe4ngAcd-c69g_ z!&6>B+p8`;IDBG+m!SC$0X-vB=v7KSw><&sz%sgF1d?}lX`HeGZ7-=rx`P_tY65(X zI#BuBtsaVw-e&V#j%Fv*)4E%A$ek*@k@_{ijJl37+B+6qtU7K?ub;9JX|HBg!a03A&jYyn^EPYJ9tjYyt;5 zv8t#y$E9bf$TR!|Vjy;Wj4IW>r_p?~s@(S@cEs^DyIlKD97&`bg&i5KqOXx|HF~x1 z9o4>k<4bPVS>Ere2qZa>)j9ct$)h&s?CGF3k#-Q8J7e9kq3z)J{#ou7;Pogs%ed$&D z&yq!Nf+r!@Te%6jS|&dQ80zHRrh5{9YKpwa1A07a^L`C|(8>E>^bDI}$E(3s7HBDx zZvm`+M1}t5U3G=eGdWHJJPXbMdvhqXL6vsRYRH?Ce|Vm?pnZ=d&yHT^)fWCS=u^Ge zKK@pEJ?}}30jl>4blTlLnb_CZ%|=Jir>yo4?8Pis2MFF<0!W%eQW7(3xgSM#Q`Q;=rY3*udK139XkHQcow zcOyf8gROeic73@#yMgEIYH&2OPSq2b@p3ciI@NMsMnnH|H*u~x!K?iA3thHY!;|Dm z{H;&|DfP3L@*uyi_|Y1|{U@ZTR7KYF$4E*)t>r5ZLXg-=n|I(+Yly@>A(0a%abT#? zGVugR=%gxsk!#fXMoaH=kdnhH^*0Ls&}ivB0*O%Yfl)N7Qh#HJg0mpeA9?LgE#8EC zku`+77lfbdeY}>EZ#7z8#1=sK0iW?MHd=a%AhENp_d}zl_W&gRhsrM^=W_>Wop@P{ z{=07^q{#8EHClR4K*FbN+Vp{1OK&bD)p~<{jF#T9km8d*Gm61^)({O|4vGEYJM%id zK(QqvW;Z0&+y>?vsB2~w|Gzq{$3GSTN)9Phi zX$|4-0|}{hOzFU_S{|39I|&j!YUj;dqosE-BwnhDUZRhSjF#T55YO>Ne===8H&Qwe zLW)bB`TCbNM5WFegxe{%zR@yqb4cn*TkaJ`OYe=4uqih%%1G&)qQj5d1{E4Dy-z_( z>@gO2#c1h$7gBiArrmF}^qzo3tv6UTqP6tah2$OQFj>eit6Ew^w6_zah@(g!`@w6i zA>21Z@{aP`RX$CSk#7y*o*Gdvu1RYUd<0L#HGWS+ib%NZdwwitwMh34Bsa;!i#T4nuXwDi^-LJz6I8=34)v^*xA zZ6UFr^?TK_bFML3dIv#@Of&RlT7jB=by{X%VmVB#;&UOnrFOM^)@Yf@CP+ThVEzXF znu)#2J)@nLi1raJpE!}Ur2Lx0j3L~uAn~7U`F)Lcl@AG%xV-$pla`1a zwm?#ks?h6<{sE(94*%--BbtcOZ!|ms6Qkb+QhdZ#<5r_(CJ#V7M?^J(Yb+7f*a0ae z=FL6)nDu9C2=`edD1d8-oon?3YE`RBu(2f~rY)rO7Y?ryeqDNlHH7;PNaR30SB?Z)XoG(7+nP-4PPQZ7#J2TSK^~ zL5luT(Jk~)%xJl^y#Xn<-rxbFrPp&Cm8W**dZ>jpMAkP!3UTl3m{G6JL~985BaqnN zo*Uer3xx*O5V>Cp@l^4vq|RL7 zrWSKY{2EI{OaxL?rgDoZV4Tsib@xH?%6NU@Z=A*!SwkdV4)M^s^53ZkH&`NK-iD-d znQK14u*Vw0eF##V#gB+ibDW>DhHzIJMGH^c>SY-%t9K40MD>>Sqk;3Trh%7QB67GA zQv9cSVJm~%*Jzo;P)JFcifivgqosEiq>$39aEEz`(bBsb;yJB)yp@(+=b+Kjn{@|^ z#c7Bdd_1jAoof?j`OwaW6zMBXHNT7}7C-l*`p+j=dDJ_QNG0_%g#^DcT26qYkSM*k z^>@an%o?KY{yQnc$ImaA>6r;;!3LUZSua&Xqop@ko@W-=J)-`_JVqB;^wT))g%r}Ne z+z66Kt9zeh+IP2xaNiCoO~&1nAHC1ChHx*2?Y`&6%Y znU%Hf(pnBoGe}-#ecy{6Ncx(hivcp^Mo20HuaDb6zBNStGjxKpRVn%BJYlp2F-Dk9H{$WT_iuL|&wDeXP zhxboa{e9B5GFndD8zFgrsR1eJ*}*ABOYag$F3Y7J_25=(h-w{xL~-l0RE}r7F@(D| zB&5$3W>}`$Vd+o~6T{LUQo>=oj`vNg+z(h(##kbsu!e9ihlFwK_mkAwWDVhdUnfYRICI_z97vd+ zL|2^DNdhYL5i_vzM6KogOo5dCrSj7`WnE~r?1^h3sTpR)4-7L}rX33@N;Te``;C^~ zg^*~nCVE*IZKuWRa+s*zn~*S_ZKlPi))38$Lt>}&&oXr`3sk4O(lZ0~CM94Zm+K*% zwHJR(BMXg|zvO%u!r7w)Z%)!ZT1#&mNKyIv#p^Hla$g`;4iiOGp3DlAsR}=*h^|J< z*4_t+rWtR}J4Q=y@)YL2xx=JeF;N}p#UF>=%3-322OyCQ6)mBNCykbwya?g-t=b!W z+i2ymfj(dFgJpA%cmPHy-z^m zPRn02T6%XuLcb@DSEuE*rzK#b<^3T%_S2Uwf$>JmOdf>rfY5lC8!f$?Af9UKubrgb zWwi7jffVz_Iu`Gsw?J#@tpo9}`fY8+5_^d?M6c!P1YES#yq~L*+pHnn1rXjo7XOUA zi;b3fmq9!v9&@>KwHfRXHALhv36jqx_s-3ncsE%?xKBcOZB>t5G_B2atz`k@A;nd! zccanL`#U6B)l@Ff{a&r5_i+gC%rZIeGg^9U-^Z$Ea}EwST6))LqR+*b&}r{lLsWV% zq%_641HW2BxcxI|2j8mEL*3eFnfCxlyr%U&V6^nEgQPk$ai`JJdlbUsO*2oc&(vCa z&xI6kw|50c8ZG~FT@Hy_Z}11BrMKbzcwH~>8gGec*ISU-cJl(ScEMR%%SGmPNM0AY zD|sHIsIw%SAS+eN>FISA?M|y)>C0J3YD`f^Q00zKuj2g^=W4xIJWGXkr@21PV%`!^ zx4K%qo6X~W+o>(PdE{JucH%T-7f$_DGo>le)F(*ai^ORT&FS!QJcvWc4hH35$y`xxn8 zgNzR3l^10^PJ0_;y$#uij9YmUSzXoK&$FkLhp7C`_B~2X(Q^&;^*=KmPIXOMjb(_wTd;=C~`d7hpZEx#eYKC&!gs|>zB**EeR*n>26MjCj$1OHI z4?W`+8$J%b;}-jpkVWV!Lp>@f&O57$G5Eol$^Qs?^-z;QjXIE4L-nnZQ7ffwAsMs&s6BCd_ydjiKdO($=}3PLa^;=23I2;P4q=$8 z=3z8bHGd?29&((KzE#N0qfKA)Ct;QUIPDhTi zaw&4Tm79?JjP!ki%$Q(G^nQ=-p^|>0)#;D3SWR$N%Jvv59m6{egCDBtpxMaEciU;~ zUyIQP!@RTZeT*2!I^J35J%Yiu2vYcbi&_=KjybH(5fa z)9eF({|JoP7=x2&;R=jB7-lM`FJ-c+6QuCogdAz4|0!gwz&SJzW1Pa!Yl=VlN%}2n z4R0Nc$JF%W6n8OlpTqq(U^JWV1Wmx0qH2~>!sE#GM*24+j}oFQ;qyI3H{WX~TO;%o ztG$<_*Q;eD^$$iixzD4vHqOe{;Ssc6%>2uA%zdU`yltI$<2|*NAm1)z<(c*fsk4mhKu3>7PjU2X=#5tMYMe2@q&4)P`!spq?+j5Fj4A5C zFEnpFl8;tuxdM6ANZ$v@Mzidp{WE&NERR}NomWLY!s$Ni(cj-O%sX6XVT9(|yDfo@*6@Iwo#F=}u>yJ&M@TLYxXjj$ zyR0D+#~=|(HP0J%T0^)`LyCT|`!8Cp&|2m_1XB8?eWnyMT6(|K%oS(U^c9%7T`&pe}4i60UUAMi~5bkO#=`H$1y8|7qA>5-O;YU>V?_B9GH(K6X z*agX*tctbw;^(!N-UX0Sen+akzZosP*Sl zkGF=X^s|uoJ>v0E;44c+O!d`V>&hJ%y#OUo@Z3Z1z?f(a5x*1?OSrdNL%5GZJWIIG z#}15OaE&p9yAve-jWc=jts&ftA>psh6n|qj zVN5hq&YfkDBGQ^!yVDvXZ5bqL3$7Pzy4D!NeI2BbnP*C#VGZFff_UP(JPqFjiVa zRQFRzm?Kz!vO9R%8p7T1B~sHDKWXOXjsUe#K9TR=hwZ0WZcExnIGav8Yt z(u3P95v8AiSIh<*H z?(2q#!iPZ$si1Cr&Qfa#cL^l2PiLy9zz8!1f;BfMU}6gNgv7r}R!Nn!>IEONhREeT zodEY6KXQEd-!O)7cY>7cOIBY`;MV6fYY6uSonWuZPvRE$Z$`^Tw%9_^d+qp-Hd=aL zfQ0tSE;wX~$Uo;z4iaiN`gO*Cpf!YhA;j~Y-LVmP-x|XGC#3YCnwHEXpxk1uW%)xO zh2JNudcLge+E$CSpFr}zC0-r>s#cvq@>a+6B>FWMlJ}hoRZ7p!8D_N1{832A6sHI0 zZ8i8!c58fC4ilM_K}r)R%(ibCLsVicB%W}uvxaaVfrO`t^J%d0+lGjk{*XM@KeHV} zSwpx#hD30i%cE-Bj3L~eAbHd5c8sY;%N1_DjNUyPRC^WUM%rfH(PAj{6rapf@4 z1sfr`G(vC7$T?vRQG>?s(xQSyF87*_3=AoUiCh*#_(k1HFGKyY(XuM1A)bj`OzF)T z7j8F(C}Sujmusyvn==+#B4XZzM51>0!!e^}0kz&EFGqq8+c;@csysXl&^!&Qi~ zhH!6zgt-*tbs6=7$E+dTS?@D1xP~d;+7akviHI2vDVlDpx6o)=y*D5w1wQkXKIe!v zMB=m$80D#nKJH}uxI;Ni^zki_Xw+`dm~XT!<24;m4fF<$!$wPQ`iImns(RI6e1;n> zz3U;RbRTagsTZua!x*A|{UNzid}_`{HfAldhH&qIL@B%E|l)x)S%cgt}iOe)lbpy3N)mnNlhlH0{@0~_V@1r_?)}kF; zBkVO&I%|K%p)p&Pokb7!G+KHmLyG8~!5Ovc<@{g`QRg1J82JZv0^Rak)YiAsY6Z$! zqTw$?B8=ggbM5z*h@8?srv*#{y-Oq5)f&P*9#T4=mG)hx*a~Y1_otA&i7I?Hji~X3 z*0K>-Kw^venk-u&g5#|r62~AOW!-@iYY6w>knmKy%b~+=t!3W#KuQ*y<0`P+Xz6_) zlB?`d_p8y;8`#6te~ix6U!>@24N>rDNcd6f4lK2XaK8)ThDj+$bl_K`W!`nZq|X;x zZ#Sc*Hy=_u)$Yw$W3=>s4=G`_G@|icxF00M3B#PS7Fa{Lw?m4jsekmokL0hk zmU&+S$!8$TkEg&$OGFL}Af=PdmW;p$M#~(^ASL&zSSsyqu}^F19SF%=YUcVJBc*da zByyjsUXx3P!$wPQ@M}8MWTq$chvqO2TwM+mvw0#UVoTU)q|D=2NXc}2AU4{swe;pe zLQAc8iqX>h3?z4ku6ol$MoMRsZ|Jufme`#a{UPBQc6Y-Zqh8%+j zw>j$LG&&+|wDjHvNnNOk?uee|*+FngIZSlK`#RxLpQ^`p-N3KbAWgy@I6w`infe9$ z7%j_~1Ic}yHQ{ZJ_f6IiiNDnenETqDllrYOg!@uW?oZUv?!O3(Du;%0`lyn7N|@POTR;r}rK z6BUd=qK~VRS{yBfM$0O^4v9Z%yuqK0mfl*2I1c&a&uqK6(i)-$V>NNIUTL&Uya$rE z$Yy=^VXdXN10+Au_Hot_S+9VUB-;M9HH16m2$N@$&QA}HZF}&Ja+qlQyO0>`tKN4R zJY@}$OXHtN&m7b4oExnn+%q7B^Ad%WsOg`veQ{GcOcZh$5-DWg?R%V=>K`?R$R!UF zD^$?{{Xg4i*$uBl^5&`3`!llx$BmZW>|-?ZA$3%zy~k+j-3iHi$ZWaIY5ud;(tAIo zXs#x@i@Ms4KL^TTqV{c$(@0)*QJW$jHCkr!GsNR~dz5M|z0X2QAF`LD87H)s-f56x zC+$9?rT3y=n3i)*xxuAIORwiwn!~{9og=}P))0L<5K^?zanG}caK8qLaJo0c{;xHJ zyW>eJw#c}%16B*~Hb^)zG0UtW+%0}%IGu?Z7-0?JUJQvl`!IepTK-LX_3tEhyw4de zz5i&Eu6opEvAE_Bt>tIXo`6JLpFulji7378DN=o$ShMVB&;s+zVPed`gDkmL{Y*jL zdVlJNE@tP2*@W5HL}wi zB*&b67Mo$YYAfHu@SZ>pu=1S0^dn(I`ytm`IUmWFZS^Ol-bGe_fX5&))S3nuv@g_uh3 z9mu+K>?54D=)QBz6BYj<^o%(?M#;#^uKW*^PbKA$G7lLy(l-s6I@dmLT#N3e=Ie-W zk>jjP|5x{{p;sbzSUCxK%E~p!Mk=QP$-Y7IQU@(Fcm^}Y$}5p8t(=71Wu$Kn(lgIK z-u@2V%+bN5WKUm5_dw6E+B+Ftq&hXE`&J;7j&LF zq2n7@PWG&y&oegmH~0r&gdX7;+v|K01>N@%8~*`1rlvP0{vYH%Ld<@M%e={+ZVPPw z1?cDk8@~npo~n5c@qZ&LFSL*C{B3>7o<118Un76?+=VuNBYKxwrsGc{Qy;bY`!Dq~ z3K(X0!BmW0j^QiDXtu~q8GllhWY5S&_Gz!L3&xH`wo0?nm6a{x19T6y^<0XmRyCP} zz+iu8bcvz_K1t@ChLNj!H=##gN5+iw|AI_?oacSJc~W_PHCpKy-eDM}>VS@a4p~=? zIS+Xl+0Du(XX#NibR;rn6YJ=xRf36E;IBBMTiocDx%s<<9JMI|+* z-oGI?5@CAdg0rdB68cH+wHSes$DjJyd@0 zvNiR#Nlj*BL#Jj;<;7(Q}uXjJ(&UC9`W`@CAe`WRs^kvYzHC_eU6o7-p+Q&2+{Y!#r;8j?w5DTh#*e zD64&I(d(ZvC3sJvOVz;UbW4j2##~KD`kzE@UhZVG2P5@ala04VCPxcj`69e4vd~EX zWaN9#+R5*G9V4*9)Y*3&ooBVTVJ$r!myy(eD{}n`;!An7j6Ujwyn}9}TIQ1bAIJe# zo|l!(wh}}8A$J(*pM$Kt(%EaV1EaNL_|6U_dxowwv&7#WU5LZ%2Y3J@j$y{}4UA^b z+szjKQy3F5^sWkDiy#N!^Y)kRW=b{zW_7AEQfEPHW;*>XGSMXVXP5 zjK?s{ri+I#4q=%64(Zv+o^X*J&b!bPt@iIk7Zo{k|HAsrU)AX%25tnhuaW*IkSo_Y zH7&t7YI)TVhr~;^Io``L=Bk}K=~U!4BmEnZWrXM|cx&g-scP`WgybRT8tK0ux$R}D z{4HblCdMV}?Gg7UI)A;Lyxxl%=sZu5)^`W8`YW~{K0)7#Jw%^NZ=UvX;l5XK(E zy~mLORr3;3_HIO*HrSNg&m27Ht8cWu`T@F&)n4DZdR1$ADbd4_Y-vUM-$Cx$=nPfuCLH{moQa>0(HBEchQ!M- zK7_@ckLfo3*&5<9uKIZ#=D*0zvmr?Cb1Hg8dUn$`6}(q#?@1Xy2oiZtm9|UIE|^fk z`=HLDm)t(Qq5^qK=isWt7m(6lWhqA>VOKuBrcAlc`ps+lkB$rY|0FdvJ-ucyx7?Aq z2)!PXPao*tjTB6^hUkMBB-%;7!|iQINm!EaAu(5t{;WXGKA(2DVj5N;mu7+Tddd#z z3wdv;>A=9<6}*ce3#X{uA}$_^(3PF99(;g~&Q^D}=Ti89j&VL=a0>mH^J#!kGnz5f zeyX4wdae^c2)*8UrT+x`c)8-^9G_Ddh(pXol$w^!qO`<7+>$6~ZX}RlP_S{!7ses#<$ldcD+s7-GGoMGtepQ#D)89hdzShz0^c+yj2Bl?s<0)Duoy8X)z9uHG zr+PuBO=`~Zd!6~frmqothVw%44(O<(Z$NLnR^1#Xegb-%qZgrz9K8X(&(XWlC64|B zUF_(r7Id$p+o0cb^o{5}j=mec+0hEU!_lvzcUf(>kjL$xHY)G(^vad^UX%ShgGv9M zYI!+p$3G-!z1glE&2l*pBF(&OXU&vDkQRs&eMI#|9D-t z&fa@PcD_YK6@^tvX9naobgrZKqf1Lw z=>UDf-bzQ6+$Ab)Q&Fc4U$4?`a>D^ zJLJ`uZ%*uGuA8*zzKjfKEj7!h=^0OAW%-aC!mgwFN62GK&GK2`yYRo>29S^|UawZ} zJoN(QCYR}addM|nU4uHx6|AXi53LyBGGs3zTH*3~YeKU|~*q}X-BxB(KK>P+6G z4BLHbYBVFoJ08~_wQNd8#jghH*VTI$;t#7%b294tUO|R>s*?V-YMbwXo^?nsCS+DA zskeT8{TDj4hicX>y+NfZ?axwU?n$fH^e>?8cpY~IM`pklFaH1Bi}gsTcsCZktI>>s z`sAs^=Mu(3VqL6Pq3QiI-l}gxOz*4t*QKS~&tUI|#k;B=S25`;wb4DV^0mGIoqL7R z{=S-DSxK#XiQl89Hs>oTlOS}qI(|;3`E2kqZFgJLoyB|`()O`##0K*bjjBIuzwTx= zy-#Mkn&wZdV%DUjh&@*F7xD4mhr6fOcaD#szPzyi5|g0zB~)T4U*Oro&9xh>ANk-a|Z#7!x{UjuRg!S$=T6)iF&v06Au#3^sI}wuiIUlSK zaD(>+Ylwn(>jaOfct7S*)eg+5FP+eK))1j1Aq$<*#pw96PHR80h6w!^QkrnLzRVcH zJrt6+!zrlH8p8c5q*$r=yUf4u&_yq*XfFn=Q%9|3;}%20QB@t!tXdi#ed<{6VV zILm11eGyW+q>@@YC&PIO^w*Y%n)o|WlUu9V&g*Lp;a(2u`-F-NtCj8lO?z*1Lc3mW z3=#SWWVQ|Uey6=^-8H&9J;A<~Y4 z}HRci=$wQlrDq?#IhC+}EjZVln?35hP& zuUO3Xk3p9Vs-{kS$S<}ZwT1{?uM-b+a@uVT;rvRQ5bo8GRCWAA`f`t!@5&Fl|EtMdn>Nt2yD>!CJV<+FM>oz zTJLD1rFS_be5>`wjh5c5o^<4J>+NN<^hP0hw%n|BMoaJ4khnT zv5@E*Rf;#~38Upvv;`8oT*vF7y2n2D{H`1(hN@C;mW7Zi`jjG?8!cx*ABcy0v#i;^ z0(7jtiOhPzXc<|eBh~2s^ic3xWJo#(LgLvfzduiGRv0b4M<9_TX$f*HH13`$-8CIPU`=qk+O@>R_bfYnZ`+7)WBRiT=qh&|0fV6f-b0<2#p^YpvT1GbL%fxGF1}t#9 z(bBsXQq;f>=P9G5xBX4js*y9CqpTsSs355go#EVW4dMO;5*}ej?EHRO%FY=C;YHAT ztRFK{I(I;L>9QHle~p&j3;L6Exb+S-T6z~jN=I1lCq_$er2!mhj<>zh(wh$njj-eS zoYB(zB_urD8PAk~#t_X7LqZAn1ZxQQbCCScs;Xs^I5hTIL%6Ho%s}k4?m#DN2=^FB z-YymUg8tfRv>c~qgP1Fy8gFo}(bD@PB;s7m1%nY|h^)Ipa(6own`{l?UIob~wXSzo z+#152I+!`2p8A5dHebsX97L^(Z-pv4#8 zqP1KS?}bDh?`K9!Z~dVxQWvUdM9(gx4YQj=BT z%32wLTkc5E#ChjkNd8SK^c7|IxKnGH<42kdRe87IJz=!$lGM@M>soBD+FPUfL&`+< zHCjgA4JqOG;yRy~jh5ackT^d+*WPpTwU*w2kPtr|*WUY#mfqzMR&nF~z-a0H2@-qO zEL8QzXepP3?vP^ZoMNPOJ`eG%uq)B$MoVuQB;WBixl3#5y#^Au-mED`OYd?Wuafq2 zTz#hH2lBW&4JmrBsv48Q4xnaZjUi^r4UoJKtvjp88p7=zr_XmShm-XnE#H?}uZKjO zKf!`=YlyV|@wlJok;@4EyA5jycPYg4yh{Bhy?(6;TFP5`UqYfPXE5u?d3PgSf8LCP zM2s`AO-q+EWg<;{VNvI-TIL;x!P|^2yQ>&dytk6t8t3xS% zMM&gDCw1;*V+i*eNU?Qi2c{S;yhV`IuWaIs=2ML!+|Nx_FJ6=0AovHK5?8A(pGNH3 zN~*vccV=G=jg3^gv`iV-1n`PY9!w$3vXn)0z8D zWN@`LL}c>4Oo4=Zk~M_;CrDnxJ>))P2=^{X9JjfP&}@b=gu4JzI7sE*&QbY{(ek)^ z3zF)1e=u5ly)!Ay@isSFdas3)+-!0VPBvP4pMr#*u4G>y_^&lYwffyp*0}W#BeLGG zhH%%JMLX2l2e}};OUq@l zR2BTla_D~;*%r}Mzy#W%M| ziy%Fm$gj|$gEq43BCTcQYRH~iD!jN>{mRH0wjR9{E&k4?*<`d#Q~xo>#i@KgniqQL z%5O!+zO{+Ye_U&ss1Wj=lPHdErUq{!QSM@DEh%&edFxR$%5^Akv(Ng1fQ1nElI3zGVUDt@w7{VXG8%HUE~ zhtF011dg%kMoaHO2yZE;(7@GCB3*^9ffRmbk_HYLEt6(H#dX9_Y9ATr^fg*83lC{h zMK6^40`_~Ab38pW=i_pixPGk`qtM($nEhFEuxB|;gw27(TG~^2gAc7CX1Z?~g{@EI z@Op55S8qoudaa%#FUQO4_B zk^fyYBe12MCdvpuOQ*fA=8{YB6QgA=H?3g)uj1KGmKn*`qi^(Oh#b}w!C99Zw z4ONNuer>e;i(=|(>Yrx44c2Hay>CHc7peC5P`}Gw)LMF9frMLYqNl_SJl($|JtNR_ zZGtB17l-g0yZz)67+IvX%;hIY=vnI>yH0EA{T-4zOLd=2+G#IoExk!E6aR$uK47%; zR$ouc*Q%&ayU=Lq&3c8_Zc-cYp7)f|(%WDIbElczKyB~w-Uo@OWtV5x_ZA^XTKP4y z*vi~j8EY%=L&mIp9$94N-^fBMb2jQLbe);6D>C%ZA|Kz`xf$7)=Sct7WU~T#xwA*4 z5MABbBk}?|R-i)n^Yx)Eb@=+wcEDppY@&nc=p>alg3SDz(Bo9-ch;#^=pCxlIQA9{ zL>`)CK4IsZjxHXr!sFO&xdxqKPZ?h#LpG(a@@w>iqg$YhoTS%jezz*pxz9v*u}NP= zh8=tuoo8{K*Xiqf)XxQ+F-D>JD5ueHphNel@E<&`JbN=qCoq%DZ0f1j)nVtyFkmyA z#~a%3RQ52s%(f@<4SKzgikwQXtzQi2>yEuc*ag@dg}nxQy|EjJEisF}$>>_Wuzljg z=8t(*{)w7_5Z|nK3 zssAD5!fk9n)9=iz#`m~+m!#0)d$9L$(O5z>fCE;UM}Qby^UyHSc5 z3`r_7N>QXyvLtjwa{FqC+!;c0sZo*;qljuSqNv3Gy)Jux&;0uT=JoROem>8-ueI0S zXYaN4-fn{=Y+?1H!9ag7WvgBJy#a1-*n7Sf}_83>lCBDWB@wD z-x8yb8Zwc%{Xt$PrSTmwT1CAM{seZi*tCF&&SGEiyurY`VB5WRQ0<4aE&CJp=*5G!|eGBKn z=5uddztIQZ9)bsQ!Po<~j>q9vmi;aE>5g+5lZxEV~?| zkBWPf(1$?YmZmZKknYFX8ry=MERF@|T3iC2HyGFtwmo9oztZ>g;}P0_4=_!j7G;Pzuu8i^SGXgqoxw~d2p4*1K=@(fro!$Fz_BThE$*c zZe=;x=mdk|Cz97M%j<-(${GHV7%?hUk>mofv%%m#aQ+FiNIcNuBo#ej*G$ib>z|}( zY_srR!r)!rL=9g1Gvh?-m#ZcPI${)`w1rp=*ZkQw%>}rfYBP8f14jSK6vyi2;Czg+&hQ6|^dRc}PSrY5to(k5f=N-E}Z)oT7MWG{eg}54SnD@^#y9E&kX>y$zy+8b(~4V)ICpd!svHK1_xlYJ8!!^_z}kV^S-y+Fa%ot zu1_IHb%d|L`oFsf-Tt8P&hY<)QLOHtMIoNOU@kkr;1#gd1v{{VFJGjQF?4Q$;GdjI zFRH_{xGH=F9;>3>BSN{qI1K-^r`zB%j3Q_FyZx;X+sOp-9|WgZeCCqAMlfpGf5=Ov zMhNf*m}{}dW!)lL4SonVzvR+xdWFJ!#?T8~N%9fjqxU8zjlK~h+kGwFUe7Q7#plbf zWPd4H zqEsfIB21}-t~pIL!ZOSTl(gzn>3oJTrSdv;W;99Hkbzz-Ch1bq63-GXNrw3dB`sMh z_xwhfQiVQ@l9?*Q3_R!arC%+TO}?_^Ut3C-2vk^4D$krJvj$Qb7FE`l-qhYTwH0vl}kPLJNDQ}7l)c7LNo{(Ysp^Pt;(BwaVvYEyhi^|?PvZg(5Qc?Sw9(VB})CbWL=B@73OA&oBgDWH54VQRIJ5bn9;rz*ZAYE zFkO`D#my*}N=3W$uQ0o*YuW&rSquf*RVvo)D5b-EOI0)a>sX_`?5mLUj8f6squ4-R zn75g!W>44eO?Wk&%NdD6P^@`{JC3%6p=h z(Jrk_P_YZRpVzs9W|_zlltMO1Y43oFnx*$Qle23%<)}D>AhN#;S^rq^_pSnjpAY^ z#d${=mfrIy84s%VZxiHN5R~@arLste87!6KD7#99sa2OS*)mL*x}ynHs?=}lKv^=-PLzqIY9Dv*+Fb<5}A?2uvq>y35Pr8;W8>xt@uY=X0sZ1A3GL`}B* z51d`ovT8ypQ&sW|D$?)||90sMOnZo?m)ZBiL-3!|*e%-1*vzISW(2Sm}tZto2t`k$qp^BQJ z6G^#|(!{BJxNX19g$DOd|Wl5@+*k;B43N^%!b!MqdJ7FuNo~Uh2op3!{aJL z^IYA_gH+F1bF%r=T)g4c%m&@mML#wE?m*9n&5EP z1^!t(pR$E&d}oweKg=uCQ+JYstI8^PqA1iw>=ak1=68{#sOAXllp&_TWmes#Ce5J; z7qsSD@}|3WB}{3b1|zn#{^f8*k;OUel)hR!93llsa0gN>Xqn##m?g&tR-m9}zw45$SyCRJkG(Lf+|JxOWXpP zZ#h_%I}4YBB=kcK$nJS#~ijFW)AiizH^5X zn;Ap6A3*U9wKD`TzFo`#&ft-iFT)ts&g!v_g$c?6$WV zL%4HMiodjpC$6)GaQ~*dlOX+4fouDSAuGSDiN1$Y|Qs3-Qoofx@ z-iea3-R$TLUob3}<0juh@4w+9-(w9Cc`!=$8zyqFtVAI7{{4P0DW=mfnph z#aSw%y?+{(-o|$^LI+xJf5Xx{TPs7X_n=|vjlG+cKeXO-!_qqdC4Ij2&M+*!+fg!I zzR~S8OK(e*?4dU9Glr#i2@2P5x<(CtF)Y1$%cuSGT0Zq2Qmb$G^tCrEyKg8;KezjD zCY({vhTLvghCGduSI_SLyZK(t()&D0?ls1nxW%ya#@xp|sg8cl+UMpP>r3ZjD8<*f zy?<|6LkzzSD7gd7u9*u4Wpx|2XW(QRXCH&oISnOtkZSNfYejb&mfk;6GSuunERs*V zAM7ukk7^}L74K!(ylYr`zeFh*V7)O9XqMhqDA@z-*1x9=OYa9LY5m>Szk}8gwXN8J zGCOzZc54XtQz#jYY!}TkEL(C5$_&?;XW+DkHe~e-%`#*QHW#f!O$sJ;xpBR+RUr-8$ z+U`txNVD|bhr)*Uy>#b`8V5_~a;@;YMtA2a!_u4DiCnX-x2s|4orIE>ZM$=;Vd=eq zQp^=yR3o+%JZxB0wkJvfUbAm^iZz6LtB!EM?U($^8p7S+Kjh4|M!jD$)XN&e{RT?G zLA#OjjA7YJ_dY_E57>>I3k^%JpBsaP?z$^{vo%E0eNgfayMn!A4dMPArI^^JV3(~S z+>N`?o=0rKCK;Al|BO=by)D>1T{TPZT$G4+mAB6tBI&Z-xDs`{B0CwDYq%pQ{OmS6 zD$g30-qzh2$^TJiE9WPM<&xJ1J!miM4R16oy&Zb$8NyvZMXVu;RfOUjU^8yrOS8=Q zRg^+k=mUnO_nJ&He$sB`oM2dH{3}X+Kf9H4P;brBTZEF~UDmaJ)EJ^zucBlQRW}`A z*jIl{vy40sWwBe?XHOq!*jB?0r;Cv9~_Kn%VIoz-e`8G;yU%Sn6k74PJ>BkB33F~cZ zSbCpF;cYc$i{@;@(z_WY+r>R;SbEDn$-tg(rl*z$Sc9xhr(e zu=G~v+>^J!PC$1VmfnFVX$y@vJl(MLZq~{dZja_!YltCGgHuyB`z*~C&U>vP+`~{} zxlA_hFRUTlb+Q;zyPbQKHH7;sloa<%DSX))!hQ8XntCDI1KB$me$N`h9Y2Tz#koV1 ztRdWGnZbSbU`~9}|^2XAKdu(Q}l~B@~`#4dJfwJY&mqzikcSEN27G!jgs&E ztQ=qsk@9OOnR8SgDW{$`EF<4PhJi81>w5dKve38^(d+tkD4Czx-JQQ0mgnAt7xgVZ zySuXu9NA_W(#raNmdG zEA?X3ng3GGpzsAAy@@mN-j_AY-C7ZpbT#BBt_A3QR&SnIk|zSxsO{zxNmulQSCAcziAEO{t2bPyU`Fg!5G4QGfKYO;W^B(Y{11R z%k4#o|4Vqg-5B#5nC|vFrcKl=BRz?-#YK7@PO+OLmx7!=%nr{#49iG2z0QS^+qc;p zj<~&`^9;+7KcP%?A>$^|gKmfCNW(JZ4=9IRL7Kjy$C%lzITp-!TRhJgmXRLLE$iFs zBF%$G*hm*ZpNrIcvSt}+8_F&hsoI;|CAV8Vp8#{*7SFkcWu)&>*4apbsJFP;ZMS#^ zu7=a?p2@^shGncNDD275dpy6?SZceae+n&U_jul|vD6;Vu_&4Q>|V?w!!q3tZ__Gv zlV@n9Vd2{ZAXp&($HGGOv9HT;Kn7yN?X_j+r zx>lN~2k@r8WLSDPq2%A-&A?sk7j2{7@kDP1ZiSM5T&*FI@K(bzk$a|d{6s~ovuCO% z)jntqae(xDS9i9T$IWij=BX0Z%VgjTO8T?vUR*W#f%ArCCc|gaDn(u@5AbTytKBUl zpL-7B^Z93aVZ1coK*>L(E|X>`?mf*i%}FRZ2aPv1HlkU2Uq?xa)z>-t!epztFbP$d z?TKC%V^IqHs{dKCDEq!ne8<_jrG1(k7*Jn{|8RPIQ2Mb`@mwVo#y4i z^Umj~#=a8K%c9GFxoT^n){(`vM-9tF`Yd5?Dz)=-D@wNAxA_}5!eXtD^bBnFgAN6G z9j)FPx)q#n@mFw_#nyRc*@t2RJO;8AOz-?0uT{5Oa}gYIyEXU0`|a+=sHJ6n(a+i4 znpeZV;dZxXM>xe!|D(W6w?lJ2obLE*c$eF)c>&IG+cK|RR+jHBn0Eto1M{8yI^567 z8^Lt9Lo@bcG977mYxah7+-}XKaO8jQ)-1QYtgpFEqc@o2c5A*4$5?qaxL@qXJdM5A z+Nv<8s^7nY5($4t>~+Sj{l9i=mKk}cD!$0dlJ-^29?jrrf^yMh_hs(G$aVWNN7{Xv zWl~nD;^T42!M309koKx56}N*8J8&MXABhIHU>tHrpv+1NT}h=B@^S#MStS=}Bt|C2 zn3cqaCwh)c7^|ESXt9b%WR+AJpFjzKv6bCZ*X0&t`i~?sw z-KuI`u39JX#0JjCRi|FAnyj9^#%npy3XE7B03NeA9ju>Vo^}Vn zg-0gvbefG-!3z0wnrGaF(W;vD1jb;@sAeCKuYrrJy`9e2NG^iS-@YxLjij5Xt)b!2 zc1?kWP;5vC3>*PFTdcL2GFj{eo;2ux4@^_NqDblsFvsFQV1dEFy`OTFR#%x(q^96( z$2;MC%fTyfYz@~Lt+r5pX9S+b=vPCfMH4#@K2}5Jl%WE@!s%*s8M3XvRd=_>;N#%M zno(v`rys7Hq%x}#^8nn*ar`z$KCH`g2fWwuP`GZg)i=V!99R5|Ye&cFFz-^=af8F) zKDFGCUW$=hOXWv1`oMMSdMI%9c3L^b6gZFxPjNgGF18#z0Jl$d$s~Nv%$jP;+yS2N z_*Hm+s##VL*bKL-ZTW9F;<(oiX308s>A|OPzdA0_KQX3QN8pB?G?3!~aQC`4p)cWl z%fY6*Xo#z6#MK;za0YCSk_{Lmo#C&#ThH-V0(3wwc+z0-+AkQP*F>qMmGsV78XY!q zzsAUMMxg$eTv=Z;HAoLk28#>^Lj^oiuICCp5TkQFJ8sMDA-H1&`|4Z0>{nz^UuDlH zo!8;H^=H5;{c}Qc;CtEyUb>CK!DGEZaffM1ZEUWV z?1z0f*e>Y}XE>e&M;xz(i*L{~P_Wh!4x*+}YR?Zug|nOL+W3!xd8$Jt4zo&y^mkJ| zZw7Ayn>TYMn}yNG8U8~Ux$1}xU->A#bfYS)MC!N0xi?0s-WTGMf)R{e&Inw_h`C8+ zSB|e;p*;&7qs=uN?{ZjBAtBKC2j-lcOcH_D;hHyFF4FqVwr*8_WN2Fswt!nTcPER- zFjxv{PcRcP7GvlF1h!(FY_97U{0ppq3xV{`&gyaTZf9r5WBPikRvguM32fFvrNlA( zSHO9Ws~o38T3UTDJinzmrOX10TB?jooL-K=DXlE0{=`w_xIaAJ@yGBw$F)z;9gZi% zbz9rGSK!W;{cTQi9iVzuWkMJYuCurSEHW5~{+V{V)lP2NaC^sx;E|5+{)N`C9DD^n zbgOHbEf}HO?2%ROS0db|(%+|vkxj<7eQqs+NE47Hhp00|2CCo}VKb>nGy%#k7 z6vc024gXGz@v3qHr;eVdDcv1z=pVxv>5M@CGnC^Flbyc^ZmZrSLSS$)&Cli69Gd?$ zyzWjrD@{Mk=(@}DUB58`9dCnKWoVYOJ$kOJuj1X7Ps5pxpF7W7;yCa-L;Mbzi<0}Pi5EU@Sbjq@^&%zu z)J6_JY7G&27D{Aw8J^>_SnEe?2zQ-7ssB2a9g0s5XBn1h=b;qvo}mtvco^`fHALjr ze^GAIj=F1)&r;rQgxBEzx}l`iqKcBAoz zhZ~mO?@)?Kf3k{CN=^R97$WJOD6t!L1pOQCY4cs@(7Y1S`+fB@O2H>1IAGTVrF1=p|D23jL(>QfJ>ysF~sYbCiM17k^Mf=ipQB}v66ZuTX>A0BC^PW~xk_{;N zYg9oE8oX8+&9WrVqh#h=?;*p|+q`VFFXdy^swQ!V8J6BfD0!b4Z}@~^=}nG~_GN!k zMvc0UuhMt5hA8}Gl)`1!9olUT;g06kLjE#!Sm&H>Sf>39N)aobS~6pP3}-GiArsFS zmLabRPy;n4HNIBjFpbNkb3IDF8kiJcD^wu}=1FHKl$@n1HklGEFf6@)qNLrS~98 z{(4nCg}Ak@(k#6_wX#ZO;0=FZSb9&OfvFQ8CZ3jQl-H zBfdp_mKzfkphP})!(z2HMBV>D$@$oJeAB9$W#j=U zxz<}_p<(GghT{7aMQvJGrADYxyfaHCiNPp~?Z_yX2WM<934GBrO9Hn{ppu(a!8&%` zjW#Uv+JNG--qbSHG)r$Al!z{gnWJyDbM(t4qBrwxL5ba<8rP+zDkN%_iQJFk<2+zS z$z*GYmMTDDl?huRs;RuX@iBq8P_*w@7gfM}yaErxDgA}>Erep{+zYchqQTW%ImCve zeY>3A9*#JDJiNb)O1qnzJ13i|+(4DuWpbkQ8@ejw-RJEX%IDin_G4<9?zYYrqD9|h zuYdjJsxxz|)OuXqJOK7Xk2=M-oZ%@(_U{LG*$}BUh?~+3d3BKuEiK}uf1+7 zTQk}>-?INcc)wbzlV1tez0Y2(`s*YyC95{|(X+t$=;m|8t1#l*+Z+P^ouy3u?x+;z@#7~DD4VYY$M z582iZR=Jv44`WCXJ0RdG57|q=_u-R{e}P+dvKPQNUK8z`+sXan8HG`RVQyWm$B22@ z8i9W>(jQityhbR{pT=L=PAqaUgN>neEB`7)b z)Jaka{bE?AlA6XW^qER-LLNN~OYan|eBtF$-<7nWMD_9rHsOH#NWDfXp*sxARGvf8 zFI>~!PYg@%DII>g%5Q-;?FP-#I|zl(DK)wQ?=r*Edln^arCO)GS2xuxy`4~UX4y-S zSKxx>CS>Xw!!qR0D85g$q6fou=9yG#N;6ONs`(&FsX3%`hHS~)$guB^I^vKMq&8YB;24&JaQHtN4 z+8Sr#%^Ib%r&iukSwu~pZCHAbpyZjB*DcV*w!k&bJ<+RLKdpSIBkEvF)sQV!swI|a zUZ_7&vKOgJH=(nV-Rj-ctq7aqsIdIOA?rK;oerTWgky4?sz8s0wb=SEPpJqtOE>Y3+E8 zr5+jyw;DtA{e37I4eiKD9cK;U-hh(Z&nx&Q`#GmSN<^>V*WShm>Z1P|)^TmA1wZaqmVc zaL0S-MQaH6Diq&ZJN^A_SeEyeI~fFP&50y5%CPjVLn-{$PJhLQrMK2yl+;as9pRjB zY{-`l%aF@a^7g59E#s3De>E(4vXAR2~n%>74*sc{j(Jeh4mk@fPMD#}67L<%#YQLUxuNanz z+}IxP=c*FZP-?DW>HP^MXQ!9N=jQHDsKx!B=w?XRsa4R>_1^z?9PX^Vy-1JCHw}#03X_P`c(Jj$fYNGoACFf^1(bas! z7$R;*lwxn9n`jN;-i(qTRyFt29dVsC+gFO)Eo$9RiX$rj4vy!y49iMyLn&AlRIO`r zV*JY*BI#?pP$}mQ^{|F;Pee)Ypi(ku&`pNrKsbw%f1lUmyH!+AR?1w{)f2r2{SQjY z0QE&%5}9CFCbCwC@9QP9%_dS@B6^9WbYmV$2E8cXU8>UEl>QyVGLN#E z9JYM?@b36p)eTDLA(XU(6hJk(F1|+S-rmkExdQnZCHpRwr_;V{SVnLACwUwp z^nQa})c zuG-v7;Ww0sUg4wqF}XaU@*gIPfre!wdr>m)vEG_bYL?z!D7p7)Z>>aw(s@IFg5R$O z-AlsH8J6DlC>ak}@3jLoOK&bp@!cx+KH`3ESbG0KiS1*&;hVBFOK*RaG_K9!crXxp z-x^{heuKhIvynRKasxHX25*kSTNLu!>(($Vlb(r^A5z(m;5}ei&SzByaR~gRl8GC> z%dkxOX_Ufh70e}L;u33!V*Q{Mb#?_`E=e8?Cd!l_Mk(lEOZA#zS*kTCnXXh949mFJ zXVXAgs?q(FxsPEPcM3{@i@V3Lj9YF9O_^ci-fCFJ9fZO=lT2$YGA!f%h?1G5T0B6$ zp`n^(+;%8A8P+?>u=M^{hyO`s6E}R+ux!cLrx+YwOWtD*(UPOIVq0>x#!@X=jFSJ8 zD(Fh7>JHN^Q+^1A6-(xP^}b!QcXIOflLFweK8#lvw-`VrkpN3_~hR@P7 z-P8us2|s377Ii90=J}x7*pWkcw>3m#T|r?zXM+bR#LdrXmXZ6T6l_qLc*DyL%Z&fj z%0_pd>i@hkMAG|EiaXl#RJ)OyWzs89@&_7kje4UrOYanv^pj*}PgMRFoLO?B8iJD3 z(VmLd8J5w@jAjT7wBGv-OYd7Kg(u93D)hZ!S*zMP6y_Im21u=FlMi7nEK9zN~t zX)HX(6TO~)5hdr0Jr#X!SSC{8McS&^dY?5cy+5F&46`Sy1}|xrg&&CGd)l0+LWc}X z?_FaFpKZ@ElMGAm9+ZqB)|>vaX6apslHJLAe={t-H@?F8`(f*yYgl?KjU#SndkXrG zVd;GbC9{k5#*Ei2y+cua57`scBE!;q1SOxBMsbb_hhEhzz3oxbxu!NJsIk@%LvSTZ zVOKlZ7a5k3YraM&xk?5R4CUP zqF7tB;xhJ4)GRZ;86|tTEp(P)S?C!kg)Z)QhGpEi*BM#E?OEn7!!qu0lwue6W5Y7; zuPEu=Y}}Mdnq}M!lw240b;C05R+N-y>^bN!!!mAzH;CKKdV3j`-ZxNk&e=26r-o%y z{)Q6kHD$wGV~D2gr4?7KcMZ#8eT7nZ&Yq$IlQqkvZ$wFX!F+ir&=+pbw~zF5$9Htd z(dvP2+?(75FLwGBIFe)a8{XtOrPCjWBQ6~U^Tl72&gXEZ)BlFsI{mu0$k(Nl39oYc zTX3P%x533u|5NKOorY7QechejL-QonzX#>ag{L|G6z=ngnxyqV;Y+Wp%x}22+VE}G z6u2-w;rWgy!y!I#tiyi~*PWz_ze$jfOjYFiDz{gzJe7KyyGVNOYp6P$hznO}mVjX< z!#h;eU)(QBzotrbne6tedawA}Wg_;Gs{bjXZdbi~@kntQ80u;tNS=lJb>+d{w+TtX zCW>c>&hQVxXs6Ehimy{Pr<-}IXJ1e0UyNg&cGL=-0MB=`OPT9Uqute*Om0U!0iHA% z_yEl5VIPVfhxa?a`W-IDdYYKQ$Ki=RSsYaI&aw|s>i3FLy?$aT|8a~N7<$d7ztME_ zysV0ihji26OTFC_z;7|? zKWd*a`Wwt($f!*^!bot&qqgk3;Pa1~m7G;)ayQ~J3fGv=DD}kHr8+)F@c(MPk6Bq8 zEP_|{iBd;q@wu7%X5o0;6=)6ypCchc@MrL%r#F6&;i-o7q51lQ(=5&diwp*jgXw); zk?TYlNS^U1#x!U6-^bXZq8_I}hrv)k``oqqY$90pcY*WOWP&g zxt4=3X+6ufQE&rBwle~MVyw%u>lSbRfKX~rU(z2AW*7{94vrk?9`o0jN6Qbioi+fD z9i%(WzYOfGdiSH*{{c@9aznoThvSz^ml{#)DE(L3OK{!ZjdkL z>cD}IDA@>Gr(5A^j)%iVBg`__rC>8&dVQSv?-ab)as52{`#GZr`@l1vbBi#RVZ=Od z%j&PYR9AiSAWERXX%@>b(^c1Ma3q*Ml6^i$nB;b1O!18BA2Sx5;qQmR_elnm&c|TH zV(sPJGFD5qIuPVjI~osxy9@^EuV5-0ZP)ZpgQqw?24A%7@AL^L3e_f?m=Q4FU?6rS z)f;1Dc8AAX_V0p=)E+_y%B`YhUNnt#7dX=5i{O?Q%_5C8V2nCDgp|*LtQyhSY&Bu6 zngwpL>H@IXVDM+K=GZ9pMj2+<+G{vnVVD{AF$_MIHk5Xo0q%8r;Cl?;%R0|swY4<( z%Qk%A5sd7Y?OO3%INx&cb2#=DmqXM#4l@k1?*3Mcu^4)XfFI6#Mdig%SI{@kjlXj1 z>5Fk@`~~iW=a17l2S$NK7FU32^J#;LZUnBu$Wcdi z+_X(Paf9=~`fA8<)Eb+0e;Di!78ne!2J23;KQ^m2p%#R*aD`rc#}7A z1}bl1zO?Kg19N{~hu#flSxn!m)7ENWBG_!Qjd%r~Hd$qsC-gQ>d{*{vfHPI<2-NbQ z=|N&}6j)y^)#@5B+u{XqmBpsp=_l3ZSu)82dHrj~PXq>sO;Nd*tJaDJ`E(iq{7Ikd zuzNIi1sfR*P6s=`ZHI>cYmA7|1MxdJsNOci`hGB0^?r^_CV{P{8uc?U$Eqv!qH%R~+Kg$ve~S7ScqwQ6ww3c11hJ(NpN zm}|+6OHKG%yVgk8Z@A)yS4mB%^aYhF<+|>RXtn8?Dya?b(XLVn4n*;7 zkm)8)kXgi%qSH#`b*u(sjc~la&0iJR8DPC=3D1uU~Z}A z8iO*!G*`m=V9HuqqK#iht0ojb@gS~@QjK*H<&rHwc@}( z3XgT)kNq3I=<-PXieisc8B5uw)Eu5N)^Znkoefj&X}G(WZKBFZsv09!Vw#^7!Cb=V zgJ8%liAlkaF*pjW@f8Mx-WtW)SZNJ^?AQ7LZT%Aa2+i+}`5o1g7b$mBbe`Nol_$5bpOiXT#it5jx(#5&hZ^Y%_n;elUmes7ij>qNA)>&lv?eWBqPu^Z%1 z>?tU%=BSi#mE;C1{^k7|rFgv;{{Qo3g5rjWca@pQ2H00v>v5LQI;*qY*$5QcXR=aJ z&vPPgi9tGQPd9d3>C#7~sM$*r>Xa#%uGdELP4Rwox^7_ za`<|seu=YP2w3M^P63PfQsQ$}_+j~7e9Y)URuOjqmZKCdlCge38TJNEOdHvBD({zJ zdiClx?6D_$rKL5r_X=#7)`ZEZ=`*iwu*z_h{8A~;O+?DH0|i`{^k7* zCB0Pm3g0nUN>%c1l>EhV;^>8vLmBk5U0amtI*gL}Zbn(|eIP4}7f<-gsJCy5k9+dW zzk((npv9-j$hZAV>5EcODuXvrVoSx^fs(sOj}wX&)!nSPXq9l#6TN$%-B8j>MN}x+ zmEA+B`xtwCtcgfx(C|gSOl^e5At+1hsTgLRA$zAwDKp{d?2#W*`Ue$Dqqi=)eFB zo`n~5W6paO&izKcHi09&--Bw&1SaVnI;QDM-9-E{V=4%q(4q>ej*0OJDs3Ve#2+?2 zB9t~Lw7=eKmY`k;^5*nGD73#iQj=Jf7F39-yadHItWG?nYMqNq2%bTtZPlI_Ud0}F zM2}&W-;3gPfajaV@6}9#ffo@X{ZyKEu7HQVp;G?lsLWl!YxPee9?E z*yA@-AHTJN^$W@P-6)lMh=uR;es}fx>s+9ZK+c@W1teeajfN+xxJmJ~q8?IBCdJnY zpRRA0Cipm-Emb>8gH3ZUe!SBf;y@m(m4#EwCL{-EfY}ija;G&!$lp;SHe~G|2uYge z{n8z+AwoWnl0ib+ow(2%!o3$IPmP(%)r9{?uy#N=o1o+yXSlbw2DaK0!m)4%2lM0eq6ImVJu2+YCtVL zRy8Scr8Pw4<0!>y(;L()@h31v)~hW_tZFhXzE=1djj7W40ZL&C^=i-7!f&l15{^E> zFx76>zl3kKhHyWHlFPRM^oq3bT5AaRWt4~;0O9LS8bi1rLGe*3llZIF5bjS7ZQWK2;-Z_=LI49oVs>KD$|L~hchYEo*tHALh=C^?gL z1byUuW)taGB6^7^l$2>IZ3<81 zwi%WMEk?;y#v86xq*;3JK`CTl&1REs=pAc_Y8*o;$W=3R(v41OmXQaeMBY-{-=*}6 z4NLDa6yKX#(WSr7F1Ne>v?qF{e;OrEsaxMBi}i+OBEB;W#;MlZ&am`OK#9Dm+D|2J zzG3MtM#<%4AEX?*Edm)O?HEQ^fHH5p|1-kzo zGZQ3-EDP@xlx(j@wp&BEFQ8=3FcU%Q9Tzpr_IwQ`rH*a~JJ#hdIxI7bd&Cs zJ$BLNyb{stlmjTfcU8riWKsEwW|_!sDCstf&@jW&I~S#*`@y>wZp)pOD{;wzui%^s z_JZ^Z9Mji6+iT?W`|_RM1&;6gzqc7G^Q)<1qW<+>ZF1un`$Ki&gQ{>=eC?=+y|Q|R zsQbBuGIu6dV?@t#MiE9DhS`NyE6VTd=NS)TL|m}IIE-Dh%p02m;6+dW9i#4h=BY=p zWf{M(^Ly^r=2(m=&ansHj>F_0Q`YZ0?-{pZq(q$OX^i%su?S;?XZ(yY7ejAx4Bi;+ z_Z51cei#*J+XMo$Fq+S{UkC#Gc=}a-zb|*TEo2XP3l9C-XYzI8zefu;n z5FPOQir%*m4_m>l=C~Fbj4{kJ-p5#sq3ad+17rUj`+}R>gMMHAx%OeeOYq3K=HB*K z;Fh`eZeDT>o%w;~{&1fUOjQ3Ic)2<=hg*V$V5@m{yI;7R-#25PEzpB-(L9&!IE>JT zwqwAyA3FVajO-6x$CRh}aF`vUV=)SyV-FlZ-^K{WRPgip3uoMlk>wdrV@&gmMHpK= z<7bRw4BIgk{k}#ETmte>B`#4W3U&tODo%*S3`Z!-T5P&_kut0;O=cRQjRh zl!}$x3n^o)3^ey&$|{t!Qek$X9-^}JxAri z!Iqkz;r8<%{OBCCtZGH|!oGy^YTLI}ss*0GS3FeJT*R;2q6by_BEru?qiWnIsUk^q);ln>XQtM7z%hwd{|)v%tTI{<=BfmyyiS(u!{;5}0oQb4GU1AjpNCJn zFmJ7TqaC+| z;~jT~FS#V2g4;i=3iCKw6`I?4{8w)&N8J=WzB#J>Qo47pVXkAie;51+qrh8Cy2Tpe z%407|u3b!8q_Nau(knXn`%{;3abG#CQC^BxN6GgRzTO%l;oDGhOv2$uG?q%ZzYg9z zM%}-ZU##z0L&W_OCCyu2RIa))g!@*MJiELo{Jdegyy#<;T+)uB*dfazZm0$W!%O-> zYY6u^l!!}ui(#4cB^2LRe9me)FCM8|(-}P6n zHp^3gDG|NvrKBXf-ffAv9&Y8h4ZQ1JyR)wY96KkVMy+J|XfJDsa`Z<@e_u6NK?6Kz zSeD~ul(dM-#GCrIVd;&a_-1>hTx@?)E-MkeQf@@aoTYZ@EcO_di5y1Bm}3i2Y*>2# zK`EGNnu%NAnx(fkN~~++@V(X$bsLD1of)H&mQ(e$))4OKT6Awub>I`q^`K$z4mv*_ zeD9*{a?5v5z~>z|P2nhKvlJZ{cmgiytwye7(7$U~rmz#m$KYzXf;TAnQjH<9PeUp0 z>D`Rw3!A!+A1@KT)_WTzzn4m0MHlQgEc5WyrVc&4ME+5!XGo-ZiRdLV044TO^%{wU z<`|ZV>_f@zuJW}vu8wBuy&Gl3NR{$(m1=53jVdwzhY{x6_h>%`X4(aB{;BX5wWl3# zv;7<_cwH@A9ba8VR>wyNzC{>0NegmOntqQ*nPv~E7Hg2%#HU}$>MviHDNK!7!-SU% z)>m6tRdWaC~2O1k2Qq*l#X!1zSk$UY-3{xcRWh= zXI=${*?pjmN<^;$x1kh&snV+R8u$)|Wd*vT%8f`gbJNHt? zSwj?M3QFv5mHjEx(>%j6kB?Du3+(x0t6}N=3Z-C`J7$pdA*%KUN;ZA; z(bt@zKC^~!|AkV>bg`AWzhatZnRXbZV7XU%E@Jdf*hVFySNawx`FU!hPNaijnMf~` z^gJ&S*UwLth+ZNuq7*Ju7fB?%-mpyM97^W0fSP?T1NFKl#t_wb6ea)DfI79EMtH^= z!aWY9_!EXXZ4{br4dI@TQn*qTY|~jAmRaxC;dchq&TokPlQl%-zfcNxs8*j5Iraw4 zGIAjubCYlu92O(}wRl!mP#+}EKLn31osw_Q#hCSwRGujuPtynRFj-r2N(@B248Qxy13p^gNhQ zE@TA}WGqVYKQ1SoOlXr;M3_HO(#xv9KBvp>zDcv3cXLs)%T!=#C^xkaTSG*ycQePQ zbBCU>hH!62DK4Wnum?L_p}A(6b_bMPB9|;y2+y*LNZ}+(L8&l}Z!wApGZ>|CaX|I{ zj&U>D8p6Eo%D4(8n=yp@Nt8m~-Cn>+e1&288{-m6zVo(8*DSqb zP<-}f6QQ++fWR}&xMsWM6tG^q}1~2{+7K?`>RCs z>VEC*l&O}wOdhG3hGiaaqC}FsM7~!`f8s~j=Ov<-$loX_srEgkiS$9qDQAC# z%`z;#U!&wzQx(6a`Kq+lEWPbfG7^k8Ji)N^Zbiwj8>2>VVLJND8lnjr+{y5-qbhw% z(!C7J$Zw$dYO5t=oO;Nx^wzzL**KsTeg3I!FG0GNh+fSnpk(+}^}Te_X2UX(^C)>y z46MDB@4CBjUn83pybq4JHDZr za}3LZu0qMEF?Aoc_|2en*1M0yDtYC*%3Ml>dXcHynaJNLIakG~ zBcE|MqG@|$h~hngQe584!(Oh0J}eQvJbpyUsAvaE!}~SMJO-h}x&w8QVR@kbh{C&| zpVI@a_5+%|+ur(qOLvsmN-9r#XBn2K=7T7C71U4Ko76$G^maulsBE^XhvyrX-m@sa z%I=ckwhUv4nvX|Gcka-BYY2Cpjx<$ed&!VxSf-tal0xMFxn#Iv6_LU{4>G)Dn9v(m z5n&2Ye3w<`cl2H2Lz?Akzb+_g*KmceUt&DT8Y1!rl*nHua-zSJW*PZzlw7s+Am^)* z8tcj)Ta1$bw~czvu#9@+!z5;+Cid4@D(ZBULe=X#mM9(7cuB^r^B?-iX4+X}shHzY zQvR@&{nD_E8utj^I)Htlu##vp%T9d*zPpY77xM9VPvOjXchhqpC>M{L+kb@*sdh)W{g-KP z{{_Dw{PNZI{#Wn^j6%=2j8Sn7+h^+YQI(!NMuE+9@5UI}p78|649}Q{u^q!afByfvYhlt}`Ep z@`I~*=fD0EOE)-Xy~$uO*lxYaAn+1AW4(O<`wo2G>i&;(7}e_seWwrPvk_qMFqpQ{ z?PI-!G1nP^>b<$Ymv6V{Tn~?Q+!ij(H~XIaIdFS5`bW~73NAJn_%B#-vl_|Hyudbi z%4S>O!|<`qHpQezDb1&@BJi|N?PJ+t@I}kP32^5vyx!p#mXyMa)qBTywzLV1*{UMP zNd6$)XRB@5bMUII?0_7Xm@su_LQJ6iV+@{cHehXd-QZZ;|fz?dCw7+t_unhf4XGQi08P zI(;CmbSOZ`59A9EI`_ejoho^n%Vw8W9S~y1<+`Pa!?!*{YF!dz0gZ4W) z_##I9o+#DkC-%|7o%YzyuiKv|2IyuvM|X_9d+cE~6OR7M9ag6>T6xAz1IPixL>Yz= z`N}LRSPq{2${bfkVEwO64*t4Xj39O9R|?b%+-v2)bh!Rrd%OD^c!uMu1DW)`v0pLz z4?NNFJ8;ZC(-MKN;H-VB(9g%L2626%Dxczz><+g2R*d7R2y?%+V{s20z26>Nl?IdS zepBXq!M*!!sKVnDd=m@Q}@@cl;!re!$Kb^WZ55>``(8EZI+nmAkGdEqFjhIo4bM=LADm+VM&}=Fj8EWop5qM0 zMdxTS!td+;ql@tr#ZGzxYcpzxPmd_ zxOLq79M$j~FJXj!vW_p|kw4iO|M!~va?f)maiNSFvw?f7t*s%>&siw>o;zX<;r_)y7 z&e`gM_Opfv`Z~&37jy+&yvc9-;sJET75Ku zZ7C0&uM*Sx2CIlLP2Sf($@HK1!|#dN*8U%*6R~1vyDc6wts#;)in3*)%6z<9aY{CPC{Wxo!*%j+^fBlT+o{1 zj3I*dLWw5m->kd&KzkS1{KLOnLj+A9Pf_Pvck5hh2=}6Y^-tly`sX0AA{+u{V~zh+ zV~8Xgpky-ajk}XIg!@^PVz=)myxAJU9e52lov&jz>|hPyp7XC>e2Xxd41SZ{N^6J+ z`%rvzvT-L(FotmV(h41G-1Dp<+$T}e=uG3TG|?EseLYHq9@Or{XRIOIYqX+{Hb_iV zx#21?iDh2Lo+R&0+^H2cJKGEKwze0@-_eCAg(~WDe64HKCV?MH=coo{+@SW3rsoO6 z`ysCIn|z_h-{luq_M*gIFrTvu1>Vpsy-iVaowu)H>79y_X}$3~3`_5yZ>an$@wF4{ z=Q2ZFl%5As($$#$)oLY<)%cfmE=6GImJ&Tu=8rJT>8r05CrGPlg$ zvxaE-%_te3`xk2n_f>B)^Lg%@tRdW8QGBnk!fFtEWrkZrxL-$MX>7p`j`k1Xf|tvy zvpbm*KedJkdH|((kW1-zYY2CRwG5RrSJ5E-Rzl;DEnQMax)^tcB`j64m?%&oXb!O>zLRbSvirBg0(vvC0<+H=<9;Dn?x!9 zmG^XaFznLj2~qjBwF;M)Vh?vj*^i@?aqYTrK9k30N0hxEB}U?6pE_TNvOA#^k+|5m zJEH7`DEYqqfg{TP8>NiIzei*!MgDd zqU5qW0}UU|EVfv?t*pZJx3t|Yj;N$(TZM~zvEOn;*}tF!{`4BB?m{8Tz6ho8sArFK zMA`FEO37QA_FYGm{Rc{cZ#P{eMA_G%1hA!P?{`GmFQCN9TblNBN0c3UihkqS*)1JW zc0ZJ)*?2NTX_|!_^nhN4lDpm%-$jjnDOkJV#T->>s#*9kZF#OED&_ttfeoHL-4SKK zgi_}H;K}~d5oK3-nm%P_j>)PQX<^};I_KUf$&IdDlLc#c1xjL*m+>A)RLa3;DE1qk zeU2l_?u%07|GJv&h_atUDJwRyLHy1+B3NH{wR)Cm&AHKug0;IDrLb*?jRL8#^Oguv zNiRZ4^X-hKLXj**R=ms+W#5WY zO*KiI&Jw}e-G!2z;@p#7uvohnpyW<-ZZE;w9f6YXQjR_>Si4J5O1Ny4x#t5%)ZzV( zQs&!vB|?;a2}&A2;$?EV)e&V+MJe>{=N(b@c9b&D&OYRbveQ=v?N5yf48v9yF4P0< zI+WxBQ<%YZ#zeu|eF`PPi*wf9CRn>ap_CSj8_il}v36Ud6!|L;{TxxH8i$fBbbb9z z!MZwwFOr<+b``AMhfv~wnbIVUd|a@;g1c!oXPCd8`=Ma%wt0yv@Zv5Ltle5K)6qS5 zqG0X*h!SvawD%f|wfiPYzQ1NrZLJV>z+F+2BisQ$B3K{NM<}JvtzG98i?!PyrJOS@ zOPt5}5R_d&iLCXtish1%UnS24=FDtbYmi`KRJiL<3OzULHH)=71ceuEZQSS4cdMLfz98G|I_oXgZX1+R^SO;Wz`_%vPDJ4bLLy3uR}0n;4Sa=C?%eFm z4Hj$nA{4fuJC%g*wy=^mSD=&<)vlo>1#9=@QtGja%eIwZ?e<4WRyGfvN};9**6#Bt zX_dsy+b3ANSsNJ=RjgtkI+qI_ANy~RX=YA8c zD>VHL2J~7p-~QM;U$7qTy->aYWhQ zpe$eH7TnHxi)Lb(%m$54c0>i;iIVVAiZ(u6|uLeDCb6}2-fa4l-OoYQ57F}&v{1_mHtqa;{8FhG0Cxg<%qI-Y@?U? z_S=pq`-1IsZ&r{c_G(9z-Q-<5kZ(Wjh_dUvM-TE7pXG?ME5A?8c0lJM=!4}>UtAWE9Ih#Fb# zh_e4dDZ1a}4`F_&{h`IWiOxnz^W1KNwR;mv+;b-j*6t#dvPqJ1^i9Fq{SqaY_4)2c zc#!hsokCQx&O?b~w>X+rH#*1>Wj}(FTpu(w*f=P<))8gzMoAD`E`I)SMA?}i(Jj0+ zvuF!Pl-&iTn8fX7B+;>sDEnEI66_JRus?A`*`bfgdp?`J4P)RocSPA&qU>4dmeEFl zOXqn(=Q^T-zKW9jgvl-9O!SptJ%a^z(P>P*BCevETR2~vag<`W0@r4=VC_DF61YN7 zr7!-E@*zs;U8aQ0BYz6kDdg;?UyKnq^Af?@y=8aMTsboX|(szSP;B!;`bdZS?7qwYdU^V~-TYj+t+e7H$`M?c>pSi4`MB!`I` zJuX7 zyj9nX&x9zuDN0$w6rIjFE-qNt*9ep}*O@}I!0`z#Ua6P+8_W3hJYqojGc zTq;<*Lr_ZGifrT|!P;GplKY)W8^y~{p9|JiSM_sJj`}CVr`=~>hgXRH$?!dt$IeYId+_US0eeNv9>ErNBDf1xyU zN#=gTy;?8H4&dB(U6S_*)=92LDgMbFTIRPF>m)~@wDPL>RdCGPoF?Tv3UbiJxE;L3laU>$2cO0E|x zbb!Z7_~IIk6YL63x~`M3@Pw}O0!o?}X&bn!ixm0>T)xW`-oflv>!8Itt2QV_yPZ2+ zuy*I6ZfRY$!4iNc__XO)v)N8?iZ&989 z2OYesm)v+qRC1*#@#`hI$eG71*2x)^qJF0MTuS=8VC`P@C;g{i$mD%it8UYm98pQX z_djK+b)2%yFgfRu+yue8(!ND0SsXMwUSQ9d;))8gLQbKk&3n}H}f_3Ddtuo8JcfOqmD_N}FH>|?0Qj1x;uUFY(?cRw}QXDjS znPj}f5tZ?2Rj?m5g{??>mS7$E50r$L^ff_?wYvf(mt(R?cS{WkQAzhhNf;Z!*4`X$ ztMWM?@6YdZ+bhEOm3dw`6i8#gERH7fh+v)New5sKW_)XkdtIu<+TDaw;NrH)t7@@! zuPF9&_4C^HKgwOi;t|7BE}%bDu4b`LVG2qazh~VM-S5709z4kx{bcV!2^=wFNhESi zu)g#hS)IPI&6MEQKP*_gx1AgclveVyD6MRY{!Gt^Br8-ukFKY1c-2fn8?JO-7px1~ zqz2uoNo$AuhhQD|hRjf)_(PZS z*MhZseHOjgrJPqLSf|`3I~0gl)aekJzOz?Uh<=sUj?j=&X?asEJfYHlu?jo-x~5-b zu56c?85zYjv=jX_enyFVwO4Se#kwHdQPNVp+Pi?&D2S@Pr%)36%_X)58gi+VU_aJ> zo2?k7*h@OSuEjd;Jt!q!(s}zGQIUJ*gaR>^kzDb=aeF4bS0Vbvzo;H<#sy=0O0Y?= z&LhTFzxfT#H0!=0SkLY4^C(lkb2kdsZoB$)rS_(jxb;^F)^1({DzdFr>{QVp#pDjF zl@Xa!q59nv**)fKoXxS_B)=c3UI;Fo zVr#>Gdn0%aG}l}?s3s3>1CM(j-J1_yKFOrr$$nCstnSKw0Jz=Bp^S4vfz*L+pU^ho z-09|vW7%0I(U})l?n5Zn!aE4bX{P)Yc3w~GLWs1Ml<&SdFS1Kwe_)ZzU^%cr2m1vf zajyi6og3ogJyM4c0du{oEdh6N@&`7=WGQv%7`SAh`$1d(yilO$GbVR6Ro)Fe?rC$J zj6-*TtM@PkM{AurXIITCp{L-f|MFlN{Cm@4Vy)VyWI{%;3Ur^P4b;~?{j>TCs0^uGb@*6)D691 z?dGQJrL6ju5@(sjAGP?fpts-C-*|iv=5hwXd97?A1P%wX#d%lM#lSWWegYiq;3=&` z{D74JmjFv091rAsWj5MsV8m>+@CRTg2Xii99&)fNaK3|Mfmi52k*Ux zDi?+VU47CYG6rH_Gzx+j{~+6h+Aw8i?-gYEEwG9i(G7S`8#~GcCV+h%+y0-o zY6oM$q`>fWVD{%rNo&@Hb4&4d616b%_ zxFfyP!S=v%2k!*tn;kanGGL*DNeL@zull23$qhalk?cmjFuyhCZ@k%jMHf zzXDsDLxfGqGzYKBY>?8@r1!{d5bV*(R>i~~Byu;9FFF9txE`5jn`u2VvqFau(+<0x zNi#3DQ(1aXzL?M&IQOut{@@LeO;&Gk((%LocU-ng*AG2ty(7kM4HjMpj{M3S9UJ&` z{N#G`dp|61%ye3NEP>nA15{H8qf>)dF*ATG~m~`-IV0E+Csyl&w z9SmP;i!Ev!;BkTB5x}m;Qp|{VvvR6{$Cwe<67OT+5`m%A%Q!|}Lbe4x3*6YG^diJH zKt4-m;XL40fuSTYa@-ZP`sEC2hl8!aYt2j>dKhq@gNuM^Ca*W@4j?BR3#)Xs{lLOd zYank=+ZQjx!@=>tUBiVILdNl0buB97L-2BkgTX68d?9V6je8z2_K&=g6B-0w>~Q!o za4MfD&exYC2p;1O5S=>*?X9-KZfyP#;Kv*+HP-3?O^q+3*{HjVo1huSy++ z^z_LES2F*5B=`Vixf#%h$j5;P92^-BvE+EjsvCg49IW0w#LjV64fh6?ROUIma7Nwm ztB`V!1aq#kgJ)u2q7DJ}b?{N(6oKK_fvc-jk~g)2-$D+U^nN56>cM;)tYikHkmPBQ z=|1TX+2fJm90;qS#0ahhjuROE6u3R)9c^k)rU;J&&x15HE&3C_KX9~zlYyHYd;yqY zHrfE60>?NQyxO*uRl_ZSv8rB+^n)xm-LEI~{lGE@%YerntbL8`gL`d&8Nk5~{sUa% z;D~GO8PEm@e+_JWlB>nwHN9-;5d}nC2z=DR1He*&;q!Y_SAOW(kY*-j0HF^9hdS8( zI@_974X*?qsP1YccpMTjGi~VHJ~kVHoq+Uu8+sxz^%Sr2*F$2iF2wK}HS#3Y^YE z4ht)1w1nW-K*9|AxB-1B(R}5WYajm zz@BCVJ_O{OlUDr}xWvJB1DO9DoCRbizli`}0Gm13^agv-Rt--CPO9Y%hCd;jJQBS9 zMteF=znQ3qft?&2HPBX)s0V?3%*_U9eUm)_Sr{$?*2(mG^LLOgkh~<5$<6d&-!PD3 zj|BHawwo4%h<(x^VrO}6c?M*tPvVeuKDixIJ-gEE4h*+v!9BCxm<;cMOowdT#`WA_ zk_C4^g-}f)X%UX|Z~Db$ke(2E6*B=zK!IvRx&ECNjWiPN*6x~LzehWH8wia&% zIpULnko;3!!olf~(PqRgRLNQ!NMLxMRcm`GrQeF~kzhN>Xp?d)*$n~~*YS>gGNjxi z!KWcHGm}8Uw}4{=hQ9-r)b&af8Nz^p$dq<5q*)Hx*^e;~gK(8RgdC;=*P-X7XK>$3GC(IAHXRNHXmhsiUha;_`QQ~03&9hjaGlO{UIW-KX8nLrNAX#fZOE?hp^#3 zz|_VxW-a>KI!G&@)V+f#&nH(w=0Xnbrv;}%_}oz;(GLOpHt~9T!JX6=-~g5mJ`;`kY?w4IS!o6)hJ|Q zCF<;BNU0fc2X)rx0b6~CfZ;M=*YjMEaK|ZhEr?AixCL_D1!^;uwmaVovlZMln zHXxGsQb??omv_#C^jL_^J6r_W36Wr#(-|18y~>&f;o^S`ML7;!hc5Lqb_PYfz%{@> z;J#)dVS@KRWCx~&;gcSwEiNQDmx|&0AcG;2!EwksNIIW$sxhI6-;-@B1^BKB>u>CF z%nhz^wV9kG+7kC`+Ik9PoJWG8S@xv6@h&n*0AuaEWPXP%Zs#XcZ1TR!$g1*)J*jmc zOS!%SE)f{+`zU9Ym@Aj}f_Z2MTEQXn_*mAr_6pWZga=Uay^Vd3fy-o5-bl^az!Ns* zZG@74$TYp1mGN^0>ttdmd@T2+%zDvY7M>7w2ueJbYUYh)b$fv$YI*KGlwxlm-@qJ# zdRy?e5v=!K8ikTeLTB7fLeDy)68ab==0&b)EY^`PMJX*0nfG6)SvPN@BP#N0l(L`v zRgNicU$_GmqQ90{Z!YKCLvH`xvjppExBw;h7jOUG?vAKDZbXS=%l^HOJEH9EDEYp9 z&=F-K zdvA~}{A$mu5dB1!pcEe>qG@q^M(xO}KCM_>-eRNdGW`=A$R5EumjfutJ?0(j2IpC< z-6%@JbI%s6-Aho4Kc6#^sQmrF^U4HkxAJ^?`bSo=v(ouy z??mpoWLAj&k=I9we`a=*NVK(Joyg@Vh5k0R107M#I|iln4SP4;<}tzyn8mIAS1Lq5 zk6%%W-gF;IJMRgL^$qxuD9JbZW*D2GMOQnb@;GFbL)FZmZ}VPE`zM7cdkRV#w(J}G zu_MZ^w}8X*?b{qt_NypG*c z!Ze*kBflnCS3tEzoN>xcfpsqttlfK1lAimDVC|NpBs{m-Qx}tE;eH(XV#B=hm-cL?lLJ)Q)fr)zOa#Wf!eHt5S)ewrLg5N_oQ*m{uy!9riAmJxJb~JL2Bqi-`;foFB=xc*s&zJ^ zlK=ZBr3v0`Z`60c><+;rCBzU;c!T>t^oVVfCRb7jwurzQITIqNs>Xo z9Xy42+!1A;_Zr9ii=3+S?h>riUW1Z$*eZ6k-zw**?4uQ;-#{(bQ9$$XBh0O1EId~a zr8OwI7tufMRoH$pEW(q*tsu+E^` zCTh>iAkxke6?qs+?pYE!`$fSz@)48*)8bK{qiebuc*2>o4@yGsKYI&8((ONcrw#4x zKfBb1^Y)+p41C1ffA$A(&;QT@^l&%1#UgQ;IBqRor<;o&R5yalM3od~q%^@436xgPdw>Y&I zQtXqeZ?kN5vA6187ZQWWvQ-PnqYx=dXGkfe`?K8l03Qe29D}1ET}}FYGMNf2zJ!}a z-tMm91qi8~S#$fEfNLRxd7+*<{Rqg@9yZP|Hb@s0=j3;&dL;xKBkVRUo*?i*V9QGh zypJ`!v5+F4%!V9*NLg1wBA0pP`yDdaY_!qaY@>YWHc;qZ$o9)*JvO)#oNKy2NzqQ* zZV$)8@L1rO%e{5MEszoy3vfABW8MNt^e`%Ok;YkmIbG zlEZpn&nt*-S6~D0v!Lvgj*u$dT*ASdAcIXxF){7}E=IR^fPyn1-#dLFu;GJE3G~pIIg=FekLR-dhlsr z9hQs;sVv$!N}<01v(w_C`8svyF!k7PVfc@w-lcu*%yIB zdwLzR$_Mm8h%|B=$N`Ad_C1g~S9=5ET}V%#WPQkO5r~YAUXVSIjVIeD0T{B^czvl1 zG6f=K$=pfGJ{bUsU+an-d?(_6;Ggj_meZ86+1{vDdEoH9)uQnTPgx`S&{4i}lVF>l(@a!G8ham$Q`Sho~ zz#@U+b3dgdHi*5;crWCL(?0^{_IG&&>wRX2(_W&6?*x{hyE{UVBt-6H{sU=vJ+*Id z0$sAl-bfg+gcuJ3%dBo6zW5N*l26T|pY%CXM1eO5E`qFf`rW{CbP4|^q^Frl_~4&F zo{qBcoG_XC%Bdib0#Y1$jTrX2$50+C+wB4oMm?1y~s zIl*(1_Lx`Nw1xnu4D|ZtQ;<@KMBfi-c$3$!8tk>_z7Ee3V;FFgr-z?~l(i1aXIVoV zAd`3-mMtc`ed-K#a{UFRq_uvfwc1zog%gyHCn*1quMCIB63S+payPT2ft0j1WqqbZF>}S}6sZpDKy=G)Tk_ejy2r4V zO1kE{6+FQDp`>WWui(61ASJ4Q(&(H0J0^>zyrD|_sQCrvMQ6wb4X zJ%US8O!Bmv8IkWQRR3!8;_qmXSEP*5BEdS9k5K}zRy6~Ta|5K_~^U_?ZlJ z+fb~k5dA!kTIEHvyo8e8@PoxVk1Z%AFZqdF$8H*rWn||5=!^l=A1vQJ`M#|} z^n+F1&%iUL{K8r}HM)ZH-}q0Ihbu%s%DX6CT$HA12dIv7T=Co!)D!yX9T z?T%8KFNc{iSFkSMr-#h;v6=NldB0FRFMqp4R&YZ8uUe&-q!CFuY_U$`B9z?6<=7K zby@2-`ipsgHG8o42FCnaU+jnq`6EieD{ZUaE!NpgL@DhxXAPCURiG|xwWIW7FKTbW zI_gta=_FBq6sV&%`-5r2i+Zmzo>BUfNm44(_V{G z_KO+2mS3xX3)bDU{ojUrjtlbY#a_3g%WY39l{CgQyv#W@p>SX{*{xjyiEhN7~ zuuh;&FdQgYByQev!P?CZg#*c1RZHLa?}+PxWtOEIbSje@nCT`e4l%`)R`o7^f` zyK7O3XFB(!lPuP5ZOp? zt=7HZWQ(dl+mVpdp;}>sX^a5 z)x_76-gLn_y+2WkGyL@Kb@!KUOY=oPy)RJm>#_rR13vZFC|!u^V1rN!vi(%PHG3Ck zWkyz3h<+-+p%kW@#v3^BSWSy{QSL`6s%!e=M&B2#-Hck4sd_b&zL~}20gk8=EJcaU zF=g#J?fxoQkIgn2)WK{SxRV8Ha~n#2b+h7qN|m2!vCg*$rSKv%ltG{OonY;@&LVs} ztJvnK?V6*gLi7*(E0j&HIhtn^qoX-)(_1K5rV%Hpz z3!*|)WsF0Kw>M92B#*ZQ>pV_kAKs$YejZWNVgq;PudWdNJRV0WxY$&CgKF6)SSQk? zHvP7xiCOm!!P;Gq5}WH=YWL@8+LTH|8YFbZ1ggr7!9J7gkn zlI@>@_0Z{>L!o{&-EgxP3D)jml(}X>Yrb35mKBRqfuRS0+-KfSochNE>o|jRnM;4L zif!LTDW+&iRz}`u6{=rZm*&x`hy8E~ccJ=lh3E$>L&-g0hHoOXXnl)yX8lmgzwr}k zT-lV)teFvgrb6{o`4Oe$a8+~t28O~p4TPxHzY`^QuSwfX9la@7XHu;p&GD!-P4?A- zb?whXiJN~mu+Y5E!bh~(xDi<;tI8dy$aF_kzWY%U8%>Tq#kD)lVx8}Fl;YQ&`=wy* zHb0$Km}R>}bd*4y?`o99s;aXWX4j1b8Vgq0c1B5i-kn*W6RZ=i)`X*Y-kn*82-fZv zl)^Qp87IbQdQ*$Fdksqds;cJDDZKDm?1;+v8Q0_#u{&b^38k2f z66e!l_Qd;@U|ovVXHkk}W{-6r6|CJKQ39TOalXacore-%ZpOb&+@Az%w@nKM*mL6M zJuFzepQDsKZxws=6U?D?%s{7|?Th~5--=T3hWXKEQ6g9;atI}Dy~%wC_xy7#*6tXT z{8yd3Ua)rmK`A@SOeb#MH7zaHlgtv7cvGv`;+^Iu^?xcvzj)ox4YQ6f=h&6N#F?hf zHqvW!p2a%7M^Q=}`{_-0lX~j;zUZfSCrV)pZ&F|Hh-&CSE7Co~thaewCRpe3FiJrq zKaXB+Qvakv^z+DJ`KGLeX}X~(7NVr}_8Q}RM^s}pjWNge zFt@%(J&qQvBfnymD@-wN{mLCI)@~P+!rp%Q?x|$T-p$C&t`Pn5?LvunG1cv5NyCm7 z>qLg4un;8IJ8K2&3jfE3pDV3#=|vW5^C6UEXV)5s1?z-+bfRj*e(8G2#}T4SD@4C^ z$54s_)lBU&epSaW7NY8BA!bBo9&vU`Q;YtS|5cHe^kzJ>jY{u(3Rdv z%J$igyn&9Wl;1=t9nEAU6B4ha)UKHs3|$fCwT%v=c|ZPAU}DU_?~(_L5T=`yzFhwA z0tW6dM2G20%AF*cpJ@=VIHS1SOq!_#QTWNIEBt9mc5rio_ z$K=0QE62o6W4U?EXtVWWA{5IaZ%+6-0z?LRH#^Sj84h&v$^DQ*h}_lK30Y?r>|zzL z} z+=PA`Qhlf+p|tBb)S;$i4@U${pbvP1yHnuh7XO}JH~a_Wdx+dZ>)MChhk1^H#33!X zHx>ks8)lN9kW$}pU@fvlxDT=qvhWzmg42e3<;d+94s?M?s8Nv7zOx>(+;`IZbL_s; z7m{|H7v}{?8;Bg$G014hfc*+NX+tM4z9zV*rkkmpieyakS10uohg%tYE4#<3; zG#Eg8`oYFRs*LdB?101|a&xBk4K%1F_P*>8$Z?1i?L$b*k=}i)RyT$NV<71V2{swB z4OS~AYCSU&aaU9KDl@_vpHnq zVnzkH&b?lJ?S&*DQeT(e&VfLrOBF+^-{+CvAzdI+#~toqSXyFx_)JKZNnQ{C1JVW} z4cq@tl7>i}<&b?4>EXv94e$5LIeZMg%#oZBcstm&>s@qkh(vi1(rU8T!S_QR^~vR9 zIkd^HgD(TOdcfhTcayz`3&2}Fyat>$#ml_PxNu;gPr5hSAgT- z`7=FZ)MP?=#*g4Gv%HeEe1Pj3h(wgCPoosg-d4w32h9U8ITA9F<6x1*F#x9QmxlGo&k_PkXUqW@d$N0h`I zKiK>3!S~aRFZ#i*M=ACzcD5rbv$s%U51Vm+av&$qwOAj>l_-VHDw_^}@wLVW9Z`|r zKq-CL#E(!%l^(NLM{bK!Fva8?$9+<;c8{SXrmlC%Ae9RBW){0zxGC< zl=4|6TgvAJ>qNdnDQA+g8?8rko)Dr+a5YMRSwwCg%G;igI7Nloj#BcFdGD{xoZ6{R zTC6i@j}ow@G>6WwRXci@PXm7WR-nY_O0w1aen(X54HnR?XPQ%frwMus)~QcJDK2tu zsbK9MLdkFDesMP|wpjnDz5yl8bLR`z?hcfgbEDN4TCClUC`DA;LSC?rj&np6dL>Hn zR7OwKE;2Zx>}HGTR$k771nab)K*{yoU4pe+{VBSYSFX;2wR;ariC?ZYj;M?epp;TB z`_fCK$zmbO9)MCb-JF@iX0!7J>)QMPB|&64=8UI>sL0(>iaa~=h$G4_LrE5yGSZGz zd&Xj&c6*cp=SJ@mtlbqTB}@PV+EDE89Z^ZweU{{=nop0}E+SY*Evp`gd-5$tf!L11P10v2#maljTB`JpiS6woTN|9(TC8 zcYcNFkIoNJ@;Q~KwB)3A^7BGeDi@&?JnANwdj#uZu0ko|BqBrmCr4D|Mk^@PV={3> zZWOE|&qv{T2|KMscMH~TjTb0BNngpmm*}OAsHDfEB>kLUb41yPt@5~=Hky=Jtkb>@ zrNDEG1Z#IAN~t$Ij|wi5v<*stEgTIJ>eH7m9CDcLQh1A zJ>pF&8y!*hag=f|=ks5*Sf@P1>XhRE7%HwYkVDM3!UT=ZK1&_cB%D*^wI^QFbv(F%OH`N##?)I_(;3 zNZYy5O9g9pJW3%WUnZ5cj;N#$q9h)1lS-4d7VF3bC`E2kiL4T=CzXFtiYJ=<>$9@V z`r0*9L+8B0Ps|%l*+1zyp+VrJHs>M4#5~m$waHFZ>yUOQ%*xB}I?0|$GEI5qtm>7L zZp|_HKC#xByecdbWWQ<`(*^bdW|)c`!WMquhZZz$sV3vMey)EB4ipB8XiT3C@AAIagI$!*7w7 z*=yBHfL$D%1RU+)n?ODbX#=Eeu|*VkG4QCs@FZZvVtzL-WT5~Y2g@=`%2w6`tYJ4L z126H6U;?t!q*SNq8-Udpx(K1*+l&By(rn18R|PoG%p^!~Dv-~^+R$5odu(XC>)1OK ze35I+@WqgE5b4MBAj?hO$+jkeyU}G8B6k}-?J2LV3LrzDa&5I3%*I?q2vyzAD*a;D zR)fG(7JCQtEMzrAs`7gXw=hm2htuDsx}UCO(raetguvs#b|XrQmw+YwKFB_^!-hZY zJqq!R*H$+}20r83YB6{@hD7)V^1T^QgTt@)z8$THEbI-8IXD+M)WMH|a~;eqvrQ~v zdjQKFG{8D$Vj3xY4D8}y#tz%WqV@n5J2(@#-N6rlM@@P8$1rv|qUP*+A5$@--Sz%3!8-EG zDEax4aWrL@#X958Rv~G5ul`X-RMLA;N=BKIeSCSh@otNC(zl_MU0IbkFxjW$6-QL$ zzftm=S2cS-biTeuXIG&vr!6Z@)0E@e)3)+%1)rfeEX;)${z9+ZSLC}98vZu zU(*D>eS;&)UWt;M@5V>oaYvNhaUb@Twj0<+f5CMByH-|qh32>UM=0^QX%?a5)c?j} z-EnS333T(*=9O>@g@MJw1E9Bg*~F`iCCQML72HjZsK_Y?IkvkhJG+x3%Dxw+yrY}X zqFWqMcK9a-`8}0ox{F@nh_W9-3AC~KWcHGXEW++A7hNDoJpJqsnxo5Xhu z*2fhsr$+sP_j5!=o{th|vau6!^lL|y-RKZi>SukcBg$TelDONQ0)7&#vu^$ib#{-q z(NTi6yBej8oTb8#JED?qf0&%H-;eO~>;XrV{SHd*6;;iGO-%A>M}#Q5J4)bulgOc? zJSkXrly6Z==_t0oBTau5q9Wg7mAmEa6Imfxm-{D_WWt@B&ic(_?G8anT<2z*=yQ&! zq`yTeA5+HPr*;p5PUH!D9LX>?IN}22G zk!6B)8Gp3lTe(wn^FJ)sl`{k-pAI7nPcJy4lKu%L-iKL!Egj~}V?vaD3rYzmfthw4 zR+cbVIz@#!f|A=#MscL=pBC%IA=6Xu~uQxP)^0bHL}#zQHaMb+bw-s` z`&_#uJy)=f90=kzH%~UC&{qo9?qevic5}K>s(k{r*))_IC~s@>j}mpHVC}wy61dL9 z8sVN4wphD;QP_q^;;s>_-IG&s+nRQN5Vxmb?ao1oUv84t-78qTr&mo46m#yujou#E5SOE_{ph(f=;$MvNs9T<~gU(G0Z<# z)T|d-V&TQwjMPXClyx$HpH8hz7p&bsQDPTYHACj}3u0KB5LGLmqLg1`v(4<4ZlR95 zBc1Q$UQshIa!E}p{t|7yj8fEIx^3q9wJg@|i?veCD_v{m<+aYBzjxNwt0=kB$8BZJ zb(?~vX8NLES=~{JJ5)8b?ZW*Nj;LbqLrHWqE1J-lXJuKe^SB+QsEvvJg}Yv`b}MDm znDk!jULsh#_oI}yG4ZCjWrDSv6`_B&G5yb=uKNqt?n0D68%FD$%)CE!tC<@8-YKf& zO{0{Jvr|Qw$WW)KFiTO=`baL3e+27X;-^wsZN<%dPOx@UYE#0y?77C)Z=rkfqDzJ7 z*Y7lxwASVwdmv?kbt36?s8X&0TaFJ0n-z=0OCStKabwt^9>(bG=NIn>0s=dh( zWiLTVaE)s1NVy}*J|~Bk_fDK+1nU#$S`@w+o#@6_NRJEF?uGT}!nd0Xw(z5Ms$lJY zfRZ+rm)qBHRHx<&Q5p9`Nn)q}iv5fu%Kj0hjFa-rm+j{n*VIg{-6BsE6=oDln!Tnq zBfjE|%C$ZX_|<+CC3l<+(4sLn2RqdFXhnegQHsWSg?Qf)l|e=W%E-mwzlG@Q6cuIx zN~z>=XhJRbUVY>nU#rOIw1!Ltx0|MC(E-K?)>X9`rQ~+67?DOoR2Da*1h6ZL5nbaH z6{a%#pCt)nf1l@F<%qK9qXb6VJZ(Q6EJaNk<-U%3k18TkSdXG+IEJ}R5Rcs>c z6UcV9(aja2pU6oq7>DC4o7cNCaIbYl9m|s_ac|`z`impV?r=6`_w2}QN0hw}CHb4V zpe5&n*5_EPZ+uKeVPUZlH*b$%?KW*m&ud{PR$Kl%T&H-gLiEeu`CRIXWdT{1dBqV` zg450;4}SMsJ8!Nd$_}2-9P*z`BBnz0Gilh0VAr~REEqjr=Hr&ay`vy1=z&{rNQFV}iB&DN1n<=jOJxSi1vIO1-$t z1#9;gl(e1_H`=zH#oE0OrI<6J{8ZZJh&q;2+Ea@rrFB-l$Tb#TrQ<$^62Hb2w4%)H z+X>cg{TL}^JEJZ2w+`1QAtljA-n|hk~ z1#E$vyQ^k(b=y#0UpT4QZe2s~sGPFdq#R?B%)Yx2+;kUv9+jmE@ zp)%9qLe}|Dy(E>L!UWz7Y;1N|btSN;gOxf{RSxz9E_d)L;BJB8Bfu)lxe2g?`y^ec z8L&KyI}1{14f}bHB&66UXI@JF5V6{+m{ zBybt9z`;u0Qh5+d)a!t3C1*2P3f%XCcL(whNUX%W7joH^93VuV9-RXzhuFgiehR5$ zHnu0LoOmjCYy{p694#=s0$99~sC?rh1l|pno1Y!KGoDs?X-fVDIEzA?wQJ6T!Gzzy&Rki zoaA5<$lE(MY}2c4oeCTYOf`8Ip}r1m>0sy@Tc@IS15S5vE^w`b`+)ldhV!qb@Gn=A zug!$VLMB0EpTTXAon|FzhimnspliH7(ihUqCkr9HJQDl{GRbu4L}||GZ8NhlTnIcs zkPbDnbE<$NW`_-ta$PE)wGh|^$j1V0;3DAswO(uQgdFurZXX87D_$)RgFI>mTuh9Y zfyq}Y$){Wz_N8OL>hNrE;j6A$gGmS$U8$u{fYTjpG@PQF z4p*QK2Xb#47=9U8=WTD;q~69v1d$oIC!`o6bIwA@?zdej4uEstadlkd+(L@suu+3$5cX8;M!t1M*xAOy@Xf$Y+bFR8#?U%Q{&p{`S|h2K?UGe+Fqp4T z*$A%z4-iHoq>W-ozw2diGlWrbB^kU5+$}I%eKe(f&kH{YGTkQ|AxAwDJoR?lqtfG9 z^=ga&E_wgoLs?lrJ1d0NxXdeA!#kL>%3R6DftQ$t#0!4_+(#IBTO;pIBJA)c=aG;x z5L=(Y&5$zFqB}8aj^X_DfmhE1Amcu8sjdX`Elt7%tKMbX$inadV4V-WCmddd6#686 zEa4$?dU*ztvC}JSox2&cKA8oX1hK(_jmOz;zV|8;z8#qH5p`t0-uMQjr%$Tg!{p_Y zs~|fe@`S}wNaK%PE}=gm1s_XK4-Fen7j`(f2F$a9Jvok)390t0R2Ig8oF9PU1;8r1 zy|V6yw1JHHt5!~xggpVyw88HMu5<8RU=@>hHEOeo1a|O2;AjWG0P;Kt0YWYAr8z!v z^TjwYuff`Qhk*kHhKAh7Slwlkmu2TncoJOxvAdpfd%BgOl(yHux5ASMe}d8hC9qt_ zy6u0ICs1-v2($eJ<@)QdAARHXH(#G0Kf~=lRXHHi&DXamu2Aen{hvfDe@~b6CTzCEKs-|G_f0Z35fnB<6 zCqM9C<+2G#g(uYCRFvca{UF_v|53J}l${XfTa@w>lqyqF14GjS^5J(^#B)#r2X)F< zO`&@go)G9>0+k(crFOgBtwbrkT-V<_|D$}3l7B*&7E}MLOh8FHA^?opAhC^l;mI?W+cj{Mh|PL7-{|q%DX6AXPctle4hKi?_LkC zZE~;6$_XDLOnetpW?#-1O{UABb)*2ocr}O44#&ZaH1lQKY(At0VURhp2EzDqTa$hSDT>>zNpr%7!3-O- zAz2D!;BO2gZ8OY8G6|W1mePvg1Zx91lGS4(u`oeY0|Ed$Wa zo*8cNu#62??9LDdffOP%1X6y$loK`d5IAs9aCnssbc7eEk7jY}_M7z7s^6kWcQ$(` zWYn5@W@@NPk?pD`(T}*-g3~THY5l=tzy(eZKL)1HnFWKh>xN#1Bwe8JZZLhwK4KA_ znO`M*6iyFv0V6YQ=P~2@(|VKS#~Mfd>$BZ*i~DzXo2d&7TmG zgY9FoIib8+beM-t?w=W1rf4ZKuSS@!g((O_(@d!iy$)O`xPD53{T16FrO1Q}IKdpk zDfx?w6kg#9H+sa8l%@QX0_XnijOY|c)KFN1QcS!ZU0J06!4YL=J<9Li2_6sPnx4Eqq;U4lQjwt(Yl(kQpNz!t=iHoV<1i0*VuPL5! zLptuSt+GIf3fdW^8A1Q#qv|uj zrORCY(a#-GK^qriFL8F;F^(v^!{Yze(H;NOUT+dBmjSRc%FsOMh)Sa7LI&%0&u-(0 zvIn3P(zX(NnIp>n$ttv`wVRy3NQkoIFZ{QBcM~R;j|FGci!QM6S$#pX9wjlt%Pjbm z5S3bItI(`cmWLcsb{R?uO)2(ojwm~OG1<|6VqfowvKLu}HWT|tN0i_Khg4ASC|I$jP21SYM*8L&-NShVlT-ehdH6W+pY1|0YA2hi@Wn z9Z@M4pcMWkDMw}r){!@$lzZ-B!P>3AgwEyM=rw}1dp}CCozlrTy2cTe@jjGXJEdDY zvQ&t&JEN5QvF~<7*~?H0yrYVK;E1w+MJe*_oMl3k-O(x!R5JsH^WaB+N0fa#O7T)t z_73CwVQ>LK4{c+De9jRS^bM;NdMSPGh_Vl(3|-<797jX zKl#jyyI(bdiqp|!gki78oDtkL*(6w3-H#|mN#|z1V6k>DM9KfkEDut1Hw)J8bd8?Chi?%C57Dx-;$X;Lc4a3mfXbFbE~kz{Kw0 zd4Y!oYj+h&oa@1q9c28qBP!(@FJg1CDR#^eWe-Kk=Tdbc&nWSkG$G1<9i{kB&pzOY zva?n*w~)8Q?(B%NN1+t?_F_krU51j6U4zPx{^N+Uo4iEZkheVQa;+oEPM{R{_6kRo zy~`?%y_P-Zh_WLuvwHM|YuVP|*y&!&_H{%B9g9+oEiL<+Bg+0AC2^XwBdyj5QTAvQ zZf@Dei_90S8*c+j@-)}9-wD=kwY8+i1+{Iv$c2umqz73gFlPtX>T?C^YxPYi1)LS6 zX?}J@#m#($t1Z9XJ2|54;V8MBG;Hkb1&%0t8%n9!OLvVPxA27XWaC%KnNmx$Uh9a8 zI}xRXoTXV`a75X=QHne}JM@|mWuJvoU>4lPK#WZ}DR|ozte0Tz zCQt%g_({Q5IHHo?g%W$mvxDn}DEmy5H2=3!FGrMp4@!KYi4EeZt+xd0YxQay7=q4? z_7JRHgHqNzWF{6+W2vP=RMMkS3Vr*KBg(#IBdy{87+K|rvVTK~FLDKI|Axgn>-$jh zog3XQSi5O&Qe(G<%)755UiW~7ZkQiiQh2w#ek6;~gBud&0leFnPBUrm1q2x|?ZdFD}?sV<8LMia#UL#n$x1kie zxX~GcwfhW8DVKzDMk#YdRo|~DN#CxwRfw`Xq2%&|T;`?0jwt&9l!R|T=ZLc3K}mXc z|~%HD`l!jD8*ZAdK>qU_613P!r4o+(%# z*M}%E=hi-ThsE0Mi;`FqWQg(fi1#4n%f41I&QAJ(p18)GnQgDP1rwvfeHDe9@8V{B zXt8#0L5aDz(anOjTW2Rn!xS*+dKD6w-* zd{S0Uc2B|Doq|$quAIdAZKH+fX!BRAoNKDn?bh1@Y;*I zWILc_v(oaur7G5nh4O;#TqT>M{u-FbTS{9zLCL1}X_%zFp7ntSMi=@8hFi+&xZL(T zDVzQOPMGAwO55yBC7aqKFrlXMl1`TV3RUvr8@{(myX0?5##$#UKB0k;gG+v(BeIav zL;stcr_vkh8g}qKc;}+0=dv6WqE-KysiF714G^E7wVW*VKqI!rh%bu`785?t^T(LhPuIT)Uh2rrh%bO`<>v{ z>Sb|H4Gi@hm@rFSssVq}z)+vLlRNS>pj_O%AK7o4ex`w8+UUQu*%Fa##JAm)Xm;dx zVS<)#alKs%7``{dRG?PP_nHQV`X3nobP>3N*`fFkDVq%xfQe7j+TKbwwL@T%mUfDg zO>G<|thL4ODcRKiAels_e&M&)ZUu~NwTFqJ=6)70N@!rH=fU_<=l#M_SKc8880y?V zX*bmB6sU~`hWaweSgT^iLo_hd_rWCJ%~anjDBhrfp+0R7Gd1eb^+@|-4Gi@NnAkIH z&peW0`=|zn`VE*vi}XU-*T@x5Tc*b~Fiib>nO>h2{ur00J(O%V`yDV5ZthF%qe?cl zt6<9YB3tKgm27Gc!}$A{Gih<^Wad1W@B^Zp_};-vHX}@dDHpHAI1a9m;{B%bbC~FZ z+VzlLunlv<4btzOgOZc?0JDsO`c+Usg_H885=Wth~Rx<7ubWV28G1QWHiN0e-8 z^Y_#0cZ%rm^z<{8Y-+o~gtWH!W+j{2`(WbS|50DBdQk%-Tc5))5cag-`&5UNY_8Zf z`iqvrxyy&#R|slgI1hq}*(hFySd8){W(ii)>ZlJ>!{{Xq^RsZ4R^4u;KZ8W^?E=5KPaQ>EbxE7?pV2IKm#)_$O5 zQ@ao5Kz)(8neT?zKEz{b!$ig3$fqN_cFzwKHT5dV^qB$E$g6!8BQLl``Q)!d&VN;w zULM-tOBea~)hqNKsATQpoPL-(5fjg1!k!|E|1r5>fI&9-%Ka}G5Pe}fh->e*$-_pLMWK)}wO|-AIZ)YW&+B;#QKWgo#N;b7EawyOb zT02F_ruGMzxD~k|SIVaL5}2U&^**a)Q~S5H*TwB$3(-;B6)@rNRI(*MDA{z)sZC|P zC>c3POt$vc?Oe&)o#}R%&?}F`?uH^pyPI_W0SU78I1oe@tI63sbn*)&UsYwVmrr6^|ji#O41JU3QXX6aekb0 zjz5%a7P};$L{AeDsl83f=9S!Xn8;}H0@~Ki>q=SQ^U}Ae<_dl9%jL4uT7ZqewvP6b zlFew%3WzX5Me{wWWHVZwdO5E0+r{;ZSZE%lWK;VwOo-LVX5ZCo+`40-0#u)!a0WZz z=zlg7$HxDH*e=7>E|RiYcVl3}?_`QCugJGw m7tI&)QvsHbnX0@2rfrI!YC7Thx zhDp99?t6}kYwwk^shtDE$$vT8;zLR{wS#>0O*8f4wVE+fFD$0A-pUkRPUF}*Mgv3r zDNI6Vu35_lQZ^Hq025m#8QBdV(fc*-tR(F^y0Rhpen*5ClgkxKHiKj|qWo(zMYAGu zaFYf`4qk@|u=5(uzNU?(Y&uVq%sL(VXC<533!2c@cId}7FhcKw$uAe13GKbEsgzCU z4`32v&|>B^zaMd}sT>DW{<`S&Jh}Q^$)>h%GlJ;?cYayPrgn0*PL%e<$=%9R!Vw}@ zY?Se1N;Z3GQ7QGlUmQo<=Mg2F@pGHg>~~8>wu(HoHn%#hOFaoI!SqTSyOB=7#Mofq z1yYQhE@d<3_b{OuT6;wcDVy3gFp-&B+q$KcP3?S`P;XKD#rjQ3yse~cY9ED(Op%Pt z?YHS7d}~pW_Y9k~vloHkRfTY8PNR1y*$i?;Yv#jfCU0r6@zL8F7!BRL4efV>oyHI1 z?4|50`g|p6r_rn}6=$XKh?31Tj>F_n(rNfcoT-43##b=$uAhGF%QZ}8xfGMA? zvw!JXQZ}`(zyz%9`x*xnFhWm*;cZD3I*WH!^ZT35lVL(S*Ub(n+0=&5p(9O}jI7@K z^}EquRFZblFa8%5KG7=NOBxtCsNbFf4Vk};vI!-cNz~&Z@RU_;Q;K3M=%v5?EHP6&13iMHQ%G7&Dt4U4-;g=CfWYy^4Xu@LuMk2U_z61_Dk~4Q@}`M z98BPVod_@V_%|08`VLpJb|QD5&vboQ+_#)^9#gWJ$b)>7C;q1>M_YVI$)XM9<& zI+0=;`&|Pg3j;5t3)T^hR&b2{Qpx6k?#73Nf<=;%t+ZOCjjvbKY;`4R=dT5y3kmJ9 z%ke+`m5O*JX`2-V=_5h0jHU2^-K6pSF))+2otzo zgwZy;=Ta$~+I=uCuViE?y!t%()~+^bXK%Y?{uY}Fa>ljYq-@sX7MT2Y_A3uWa=E%w zIbzWz>?U+NVh<&HdLa%-7m)*8vOJDF+>(>X?0G8r%;U(sq=u*GvdeN@*%lo`9-!&h z5PMjj$B;W&a`zrNE}vyS6nUpMpNN>6A#%I2-Pe=I!zYT+tM!{?zK!e`%`W6p>U+c< zvqYer=Z_CclS$%9%rkvGIT6<;=OYGZii9*NLrz%odgO6j&i{|B??mSPMk40a?nQ|n zpi0Gif7Guh!qLKPPiwei6I9}!%aMPv zDrPR?LaSmVJIgRDxq?8GlvxCEiZ)w^*h$w}dXn#?HNCK2GmpDZj%)4n;us-4t&yWI z2>(jtYmf`C65&Jj8qEK?Aj2~moL_}A%fTse_QZM(r8;vPaJPh|#)|~<H{eIocq z{gPUX8&c1z`)(C`C)O*V7m=I z24w88{7bK5tlMA!V4w}6fEfV!0(I7Mz*<{#2(Z%z-TKo||FNRQ06{=qxmz3Z2wRbP zb&hL+4f+Ds+u&(H$_D!YjefR*b-RY~22k%IjsZk%un4f)273T08(eTLb@PkmGXxL@ z^!z4`pp6#1BTn+ ze}E-6XmdS2HW&hE^}FTs6kxawwg8scAm;{rY|sVJYNzEh5-{8bPXd-maGa)k3$WV) zY2S*^->F}kbr^2!e=P&wKx)qdX+d$py82g(Y(6iVwFhrN@Lv3&?AO_H%9{?n6@G&6pKTC5Q5VgU-hB7JuD%vf8V*piz1%S2(EwBkN z5TN$%ItobGpzSc0wEngs zAYy~VfO6Zc`|b1y8{7%V=7C8SU;&^#K+Re20Y(5+WA6a0wSXt>4i3rxh{XFG01yZA zD5x?T4On4=M*+ud@CKkaPvEIkeg=%QLERA?Gytlp&jTE=!C*kw6P9Kc;4y$|wl@HW zY>)&D>uu^m45nL27L2Ag0d+abdXQHjs}w&2?6yJMyXXQL zmSzrM1VCl^Yrq14s_3JDoi=DXhGCRxX$Asj*x(7kc7S>T`h7rKj|QGU08x)f7Lv=c zWCniGY7R5V+mTg@j{`EYEbs{+V1pxofi`G$H!0d+2w){3?N3fbk(0Kf0#KXtTs?CD z1_D$vP42C4va2LRTn&rO%&>NuY_BX&n8+gj- zTQ+C|=v>D#3jyZTNmrltn1s9)g&Os50&3@3**pU14N#v5Xc}cwmYU<79U*T;R{4Jz z;L5lBKLm7=fDd_Or2wmK&~PG}x}+};l$Qa<+F%Tz9H34Bo&p>Ir~n^HvjPkJB{eqi zPeN1A(p&*J0C-QfG_s!&sA}VJK*RQ-IhjERkX`6i$&^ZUUHj*JfT?IWPJ!Ix4|*MFE(gDje}7GJ*cxr0Y(7S zDeo3Q+y?EZ(_A(f1ITV@`MeGo2v9!z0Wn*1&J5DAH3HykWSJcU^tM5#nT!~~px=05 zH4ZpnYcggr${Jff!vOgfChAYp^-*_;jApfkYV#4;NV2-#o@AZmlN=TJK~ z7zs$);B!EJQ!BvP4>23t;C4X72A=@pHfTGSNy7$%0WLqs7CwaGSpXQ|pP!_4Tn{s_ z;pMpS+zH5TCU$>^ViodZ&9ow`VT>sQF!86N##uK2+Lq{0Sx*6`Nbo+L={LYmfSRR; z%%f+OTAG&uae&gad4#&P!NY(a&G{N5U&hEvdz3>%^K>cd7~w#Jx(RHusm)C^Z=+Ve+XCzQ0}GknZ8?0CHX<*!6=yt&2S7E#n}GJM zRisW&Q9G@z+F1iQ08lmBZXqqz#sdEathIsfX}VNf?c;eGFt)9VRqzbe2EXGiCJ`_v8`qULg%O|&dYz1^v_9mWvE4kCF&7}tfwG@?R7pfi{7?-^XVag5MNo`(D?K z5&tMm{zUyT{L5aIvKfD_WF8O=erGXvyOPcLjbEdm@~wEa6U(g{7@=3dByLbUvG@)u z*>t|(bqY2}td*f>DB09jz@&zf^))>4Q@Te_GMFj?35jY>8P zwG<{9qhHAlSPp1lIG?|YY)_`g%56mFYG9~;fXSbyHee}k@url`*tf%^qI9D@MU9JB zYhXC1t)|fQputm6_twBrKLQiA)jw!ps7u!{Fdt;G?;w>jN&`c^5++V_zbDmg-%`L( zKMTXPuvUBDR=`ltg7FWr)IVxqsLxzWrP?V z*e@yBZ0rLtu?P5U_40a+n{`>IfZ;q7#(%$bkc*3V=$kWJDoK06yzpJd_Ec+sl>QnR zQ67c~PO{XWYhb8z6SB+Dmq*Yk`eFa%X``;%d}Xj^44Y?RqGhJde>7v*_&>mAnjVkEVGRuRQ!rsm?fXsxLtTG8 z2a)MQZN757lFc@HLNd2nBkl(c4Ch84GH7P%5jR-L=BQW%6BuUoj-NF!oc$Y6PuE*+ z3{kSf876+GZaCj>8W_$kK0-ZPkH-;8Hl1IB36ZkedL^ZS;oNQ`&NI{XP9b+`V5nb( ziO$v!{{O9HGj^wsiLJBko1kP<`!-C1$KTngso1?q%BHp}OwvwxrUpjBAH$T-)U*C+ zpGets?hO;0tv6nIM9HT1OPJ6+&NJm+Zz0ySr{{p_C27xW zGhp%=`|9bF3Jr`X^|sO-ZdU`>H&DrD7UD3j;d;N7UzKcXPydQ0rpeT{Cl702ggyWh zx>apWQapH@luhT4VPf~|4Mdvdf31Mw+z+OFh+VoC>PBbrzbi?*bbDbcZnLs*?sf%? zDEGi5@60o%1a%KV9#<(o@N1>?tr6 zqjb%EqGVHh+IMIPJ$Nx)ZoCFY=p+n#38<}C&iG!+rt?Uc(AXSt=L2l!5bebW5`NT- z5uw))Og>fuC2wkAsGI&syAG5=W#3`>E&gJ?!s1bttX;jUVajjkxPA`#O#ev%BTP@2 z@a_6z+w+uc=5s3y?>4B-SXw8gY-;b9%pKZyo03g!+Z|}>mU2&&F-kVIZ@`4c={-?g z|Be{srJj(E_o_WxihKSlWi!ZJ7}ppk6uC!5+HVRN`MVP)HabTv z>ct7>&l(u&e!o+1qs6)q+oo(#vKjl_ojKy|5Zk6K+ewtWOjU#blJ~nr`IQCi)uLom zdl<$)f|G+Bp1inkmjXtr2Vu%1Dpl{;Kcs9r{|OTjeM1FJo87z{ag3?_0w$>#S!a4z zkm3P<+N51)-@y3CbM@4OFVpN%vXOoSCOAqwbBx}yR>@`(>3hl1{d!B5K1w#VkHNTZ z)0?jRpk!0qEQNN4(iRU>vZ-AR6JYjH)v{LuBU|V0qazO2d$K&BWYakT6XD2Fx!+20 z)_%np5qiRuPd99Qvo&MbY=jBS(0j5p`Af=XDtE%fZqs?#q-0a;KOpC@bkXJ*z3EmB zjL=IZGfbq8Q?GlKY&r-2$5EAW#)f;oF-kVIufn+Wfu;Dcl1**rgN$0vnAJ`!Q#3FV z{s<6H)vu-fbm4EvBl(At% z6PWRM+}ou1yu(s7l@nm{Iqg#0uzaY2k*S;`oS{&cRhwIcG-KF20uv;}cmHsD^|c0u z+Iy5*nMDf6QHM1!)Qe$Uv#kv5(ZEpu>lpdNyD|g5`!!?Otb+;677g6qCccb+q->V3 z8%%tX2%#+&N;b8>!1%egRpsw^Tmd8WRG9E2Bl+TOnlWrjPRM4r%0F5IL;W^Pcp{76 zCn$eySFQwxdH_rUwaUOU4Gi_)Fn-ik<-aUVF^0_}FsX@RQ#$2OD%nin40kRs+RV>D z8C9aG`~oI1RVs^HrAyINj)w_OWv7qdd13A|4UA-)WZ*C@UHotlllo{44E4J(!6~eP zrlBs(RKQRVg-M`R<$g;8LtV?0>vEy4EO+rB%@{T>!=$je^KEvma%CxCsIP#jm?O$F zDft2=n}z!khIdTYdC<1Wma?fG1Cw}IG(ubazLHIC?Ho!ohpml9a}s;C21de9z(gLB z4s!b6pdYvUrINI#|JJ!gnX7V8e2|fhcS{{=l?!{deadzXjD)-8 z;mno0RQul4z)&~O$9s^Dy-LYu>`UuX%qi@2)qpNDM+3vT0;Yl`2dVZI7bsw;Z-j{r z7Wp~kdy|sQ*yq&Cb>-W!@6o_;egh_M#V$UqfuZhHNDn!hD^9dzD9qNtP=5mxU?D+O zO3NYz40Qx1VOPpJ4GeWweY$Q~W!!hSlFf|&2osqi61g;GbFY+5?JyYEM6F$}WK+8v zCTaP0^hw#&J^&NZzQr4rY-;NilWC4->YdbUG%zy#1WbquQ|cWW80zK?h>drbt7*zR zG%(aJ!MN~N>H``W>JAMFE;||T!+PgwV5onG;ah68yli^e2yvpB?*%X}yDfg#!0HHow}}zA3RS?Gh!MTCYFXwekPj zQDt0X<_k4vd}!>bGG$Wbjw(t0c;NK}n!*#O>hA9IfN~q`1AK3T&dqXN+2>hi4*}ZS z;3q)X2JK36U2|+u23T!_&jG&x)SZgPrMa#~=UX@H?f~?*!5Y8>fV?4-mD@bmwOwlD zUF5-l!VB1IcLTR=kb}r7)48YTx<&xhZO!WdaT~k}*lL>{2e>+0W}z080H6Xq3kXY) z!9xYebC6Y%7q+C5ZLkKAaiOI-w-p(%!9#!vHux2=8XzNk+Mhw8FI0DVJyVdoUZn5% zeucdFBI_1Pv(~w;V*r(xVSrW_TVN@mzYX>QqBc0MO|EMNK-K1Cz%MrV6woMW-7PF^ zOV!xm2EbZ?x)b{>V7Co^1~lrzI-UH+ew#CMT>}9sJ7WMd02AM&(ver%3U@n(iVb=K zYG1Jbs-MqRBN)|uy!K0rMza19^{P}zJ2P`jH2eg|~2LEC>(02@RA zF@Wl5s{re5a1?OJHoLTauB&->E7}}D$Oc~mCfK0ixw)<-0M*k60WvPLz;ZwsAe+N; z2oS$aBzZ72t4jwO?J{*wFY6WL_C2)h??~Jpx;J?40Ickx`&k0Hu&32cayv230O~$+ zf51Xp^E62L&g??u)mQ4VS{Ni$ zNO^naAP=?V%r4B2A#HO%a(-WJuLoTWpeCH5fR#2V2kZu@k#rc~yVe3- zdXh1KdO!?0f~=DH39u2Mg0=0%ygWc<#&a)nj{)j-uqT1MVt~41f7<0lz0R_~0T8-Q zXZ}Ux1t?^tc=iEyU#A={>rMZ<-g0;b5W8L{@E7v->-GKS?pIL08?5p06krZOWoaK^ z{S7*aZhaUI1Fd=&fG|LnVn1ND4SHWmZ@AIYJP#NSkOvXZF~H&*b&^+y=+ie@sk{OR z-lS8>>dQQfqVJ0wf{@oEFZ!D9x&qLCkOlq$EVh6r)Q^rFR>gf9F&egvb^}s2=zJ9! z9!%~R6Bl_7vTCT^fYktX-@aRa%6PK|o`rz$&3e$DeKjKog{qYo0f#K$X?zXmr9-sU z>&USomX+&T+SUS|D*)_hqMmYEha4ViS$PJ~a5m@zr~s(EJP&9-%rg5MFwg>?p4a8N z9%HRVJ~H(-@&OcTG-O^+uerqnR{|E=;2A*527dy&-fBfY?*{s_4WZ) zP3}wKxeO4E&A*=y{|?rH#1=N65dO4+j5NQPcagU=JwZMv{>+!;gKfOoS@%nib-dRm zGy5nYd6${l7iE;C>N`)Z*HzPg0h6e-uOYLwLQURAAyx9Dd%&jm37U~R7tfpN66RotbA;XzrnPIW7YeB=T zS8$N2sa-!l*YWfo9Dk@#Y7Y)wy>Xq}s3W&ogXyE~U1CQsZ{xB;K;&GPx=7HktHe+q=SPA!Gt=RHiKc34(2Xt)5)}%1`~5I3(BA>9Mm$Hzfc;OAO}@?Gi7x!m%)@@WV+n|6Q$17)s9MRytEl_ z+Dw;m9L!_VYoclM!p*ttf-}{m-p8n7y2;ec8C(J+Cnrp*H|uCGjH z9!z|@$-F3S%D%BFk{>mA6fqBf zv5ucraEa%1Vxp^%I{!M6`n7IJ`ha`X>{}$t|K-j0oP$M*?_i(G`x33|)1LIh>qKNB zDM{z;MUCB;o-fLK)hp?_fT&`Ww@KznV22{+ZRuIkF(4HIl=GWo+eS?TC73P2?t zZ@gXyQ(oz2w~*3ovWnPTlWOglW^EfhACf0uTXuhklzfKXjfd2?|BN%2))%@ z-fHBH%+HpUnAf4ODDP*;YO-ITwZ( zjEptbp`$pbsAyyM+Q%^pI|6NxZf#AQ{V+*~SBpC-hJ(2UCg@1)37C+B*?ebiOILW6 zIYfTLsG^cN#k?wyW?7{X-GXvsxSU}C)q-Ntta|nI^zb$u_i#g9=r?~L(^m3H&E;5xYUhV2_toMW)Fu9i4axrKA{%bk& zKa8F#7hAGf%RGa#cy9DZF2V6eWGYn*ZeGwh=TU&FPkSS`tdFH>TTaQ>@nm$eE2$oV zNw%4PDZc+2qbgE9Ku4CYCYfw89u!vtjbBEkE^%#+xvS zt>#Scy@%X>Vloq9;-8vK`n|L)JL~l%kL{5cs%`g5s?EK_(8;W&-A^Z<48 z?r9zy2UlatU}BeDBf=(yC+5J6D!L#T`Z?U@9EU zZ0XkB47403;>h$z)tH}Q5)LoV{T!hjnQnc5Z*twk4Ba22pu=dIWE_E>hpDLaIz^{c zQ`*N^MPFv)j>j0Tb(Yr3&e{t@U5g!EI1m<0kd-Qq^`;g3A*U`A{wo+HV;LmP-YzI& zB_ne-d{P|kEkA34NZnP0t9K1|?b}vTl9#mylAKl372hhcq{p%rdVqrmp zTzNiBW2dJzmuI^7V-oEvI$x=#iT8$kOIt)Aw8!^OhK)Q&asHcwOKiD5b$bsvwA4I$ z9E6E1GnqCV;35soo0d1iBpu8wn6QI+119BQeuatlvpcM6#7uH_(g}a9RAm8I$O3wz zD!1Q;IPK=Cq2nROT@X&^TGm73G!9Y)h57fv>YN*F)=J4X$Pxdn;_bLU0AyT##a1?V zR^y2(+o}<>t^kl@-J+8Kjjj@@xlCN~VcyJ4aI~Lj(vNx$3t7*#hVx_$*Hh$RglPH~ zo0fixP5J#9`lRT%2F83Am_+xv-~2A_bubkUW)e)y!7Qo9Y=%iWYz|jrTAVSN$!vm| z*p)DG&Yr5i^LH!Ep%>Nk+j&wo?UOK3hy80XF;0@IB5Z4zGw=$ za>P8d8q*EN<**r4jTsN)cSN3dK{aYAOv(}H0|!&nH1Y#hvKe2!o-K3hO;wF%oJ@3q zq0y?&c(U$`bp#L}AvTTka^BFQAj5rVvecWMS$&bIMXeYG2#gT-UBk378<~$S@j2)EYPRz%gYb{k%8!s!rt&w4-StJh zF;~v%)43n2W&21idvw}Xard>%eDVwEDKadN(S7;>f{usRbTPw)^IC>)l*j6cl=Hf=zuUHsRuqQ;)32rIm}iH__6oQN^q~3f}F2FjG<0 zv~>Vxwb*h^{ic12=ANuP8z$&5zXB%36k8QwgoCM}Oj)zBlDVk5-YJJ6E8^l&)bGc`RRnb|Y&&+jmS<7RQ1&m(c4d9ghZCSKQO zYRdFHtWqC|<2TcnI!(3v(gd-$gk`*CQkf9lhcJUCkORlX?NW9>A`=sHk@GG_*2&0{ zzAMgt)w=$3hd&UpKkAmI%@jv4%o;BZeOYQoY5lSU>&yadg$ew>U5V%YPY0nTWNJTf z(vx@Aqjo4sO^3?59*S6cYzBsL0T@3|Tr`ZsNOYJt!`-|{ZwCG%W`0Zl6uFg_Gxs7V z#g*q5G|g-L82zrkwGf=viR*Z8QC=TN*GZ&q-1rCc-=q88cni&0hE@DIJ%jqT0z!-b zkJ(XODb6`xZFrt{#^cJ>D&>=Unwtzs2)RDc%$?M|D6{Jv<`AL_RBaCzX-jJrWxa?^faM06MC%VV zFb2*Jm`Eq{qUA8mz^BzMzRrc>WNllRki)(!OyEj0!i_N5dcCmo_-fimVDcUI%VCnM z?5-~l0vlz7f9pK#tftLez=Z0sFM&xpVqO3fu<~$iHEjf@!eKuXCK@tJ@f=K7E5f>J z+OJ{44*L{Ls+(Dg+$UHoWsi^If+n3?B0IHRU@9E;H^4;BGxIP;GFDs6t)_heCgiYR z2a}p+=HVNd9*cAy{;sAic#=Fg?9YS=FE=CfgxRY1A}SkRO*;i9=&+B&HF1`}{J)pOODbuckUV|-VQIrJ1qB)_A+ z>n%K)X$KQ`)M)Q&%Z8WWF-0=RFwzd0M+edXY65A}b@VT2BFe7zs1= za)#ET6|WlTxwnF444!g0>0c{6lW(gt9N+y?UTYswt6JP~UpD76<$;wL>Gd`Av{)pa zMCUQ`v`{Bn>kuz*>qIx|3I9Qi{OQ)Ez)}g$FsGF7VS*m}&?a-3^&E8_ux)C{isyW+ z{OMxUSk62)PqWWF&J^Tu_;xG@sppV`9&udCU#O%M zud6Ppk6PlkyEz2s{+pT&vZU3^TU<71(4etHZW$DaI_~tgz~uWP^G<5@=iIcmsXjX57C;y9pPTa6hDQ*eS|E0Iajv5K3sML(ClJxIg8W-0JN`s z*HAxfk#!FYttlop^)>bgK%%Gk>=m8^h?j9Mb2S7_q_kPz0B8&G>~L~^1Q6^cqBrtv zsqYn8+akUZw?GuPP7qYBvdkI)pjO4%uUj_@-Qf@QHT`0-G|DV89fQ<5>w!`Mi09co zxrR3Ie4<=LWFku%W#W4Am_NT~~x+0x%p{O&NbDj^emPx7SD);JO`dq5$RTW2_ zOIe5D57kBRdy`p%xd5&IC3S|<`dZ}PoLR{Glls7VpY)}nb)HX=2lXu3BRa;91w1AD zy7o}{@KmUPdX_(gJm6~i-S_$;+MXkdIqe6rS?_VV?^%lEh%B`*N z{9d=7cy_KgQ+z+u+k#s>L@7-_@TB#49}6y-;;i55W~JRGE}unJ4J2rVuBv9~Qs7C2 zVo_1AAlvnhRS%VzgYd5K^O{zvocj{**rZCP45ZRo`8nq%XcI zmOn&!a$ctgrPQ;=O)`-qDRJN-Z@_mJaw=sPp|V$`MCZ9WGvT@3x$YGgzR3-@CTa4q zqbI!$=LIrEWWG1kP37@%)FLrwzPEPT2jW_mL*1@@mHCLryxZiH88RPVi>Kz1kItm$ z+NbNa&sBi-VBIBU-P{Zl+Gl4+GWWrR9n2J%%{&L}tUr=%`-skR=n)1|`GsNum|C-Q z>_6(wOj{_Duq}TJxm?Fj@ZqhrOZ)X7bW7yyK)WF_HT&OO(nyd^IdmJNziZf-VPhdq znmwe6qkqL7^R^W)Kk9AZ_J6FVg!Baq%?|d{b9At}k5Lf|NTI^2h~lMyWVPs0&2n>9 z?AJw({F#dNVJ~8`Ls4R^v-$RZp{+s#}O!Pk5{9sp}JDJghRFwp%>(1Vbb!UgeKF|43!Mgt;&m6;FC| zMe7aT1`H+2six4nz53c6SeE0LmAPV3Jyut2-v!oGhi`L+fbGVIcZ#2)S`Lxl{3BMi z)O&->AF(qp!?lD7Ihc+xF$Z&n^g3#K-2oGIFjHX49n1n4|1r~RX$Po~gZfCiRWf#M zl3%MfFQ7}8h`Jwp>!+oO=pyeW`c%OGi5hWv8@Vy4*A!Cp(p=H(H@fGTzT%>cf(CM? z;cD;eg;e)Jag;yqj8($_w6}#j^pEKAG(C%|Q!!I3ycy!Pr@j81rmJXv{+%Z3{#{g0 zG&x$gcG^^N@w48BV)GN;Z1;qJbc0!*X}iSqXH@*<{1Gb77teV8c^SmHmpHZgpPu#_ zHxH~87?p9|=bx2vn`X7eH2RO#=cE6K8P8VbjQD$>^_J!xq?%?Ds+J1ZLcQzF2}8%Y zo#;(*ub+pc%OF(RXHXqF?PS%hSa)1k8{0nZ#V~D+&OnF^#E)AUh#waN7dbNU!6H?_ z-{qf9CqB@uY*g8Y92o%+N@ffPD}C1&JrV0r~gP3pf;6%Hn24W(~x+BAlVS2Ff|kvbtF&sTQZwj%L7 zN9FG?7T-V5iOeo>^m)~To4%lW@TL4wBQz5W!TJyk{!4F1#d}SfF$I1q0f zuYQ2w>1Gw(43po&WbT3~cQ8|7SR6M_nI46yaM&z^3A8lh$N?60Fl)T- zbejjWz+tlxhQ&vtK32e_EHB;BK8Eq1tK(=U`4;^=Ir6mu{|Z_^wdOt*7jf)1t^ zOw_^L2E)3yk)eBGA|1^*F_;!n2elZgyppl|u>W+iWU21MT%DGPJxe)7I@DFf@(N@h z{?{_qhp&}?I*R-GqmMSvEmIT!2N1Fc?_9=I8xXaYds}kGp*rjVaqV)Pt`YYyXZ~G9 z;;!?oez^ebMqi#Z0<5GHnkT{WuI z1#+0FKysvgNUWyzpf7p*k1Jx|S7t6Tj@| zBhTD7TIY(9*Er97`DJf`h`;2`rl-h2>4BHk+tEd$^8&8%7K*!Hr4SFwd=pdN>$qUh z$eZsPd*{7F0vFp2No>~~SrA8KFNTRZY+ez2U-cHXNCZvCk1%7>w|a>^61bde{Td^| z$gI4ES7nWeHLp?R7sLwR7h0BJx*~v(2g+OT{bib6zN4 z3d#&i@5gr(cvXeE{hz7x(^`vPvCmIu=nMEw;`fzg=oc~+=%q7s#-Kri$BY?v*Vx$Q zC#Q#r)rPI@Hq@gKUMZRNI!Hl&xMZsADKNRuA4tsNJus4?kEPI!oNTMs}JjRs3dd|COSAjWbFqLqU0Ve$Bj;SBp-K z#E`de58y6Wio#j%a7K5fT~)I3>cYfACesKeaFxllgh@G=PBKolA_lG$p0}Nu(_O7r zr7fQcO=D2&vy-^Ww|n?&Vr?%Tmu~kPt8=Zz4{y`#-AN$YUl%%E3h!;;_H*a8+@v!4 zQYmwoD!OZ>^^T#M1v-guD>K*bBA`caI zjEerE$vS7*O5I^%bY;6tLh$VxtI2KSvR?eG7J?U0(hkJ_TyObfWi_SxjEfe%% zRwffT~@<|aH2v+@VeM5a)#47w`aTyPNrTg#EBUUhRWt5G) z^Pbxh_t*uKlh@#(Lr2E%HJLGY-#jwuV20jy&q)6`(`Mw|BS!k~Gnlb=4(rf9WirEt zjEuO#6KosV!&eQWV9^ImDj}INllcTDf1=IEERyLvlan3H-6LG_DK=w|YyUlB`1>by z490TWQI79zSBXRD(*7+Pen1UxBN5jORWpsteg#xGj;(v8dZv!A`^X8Hu!AXF$7S0r z)20oA)gncfVO|Cnj>BTT}< zq+o*cO`EKD&*h}^36pC0F1db2GgT)tRF~BckNI7$(^WsrR5=j)`t#^_^bJmE61_xf zJ=Gjmwa&Rk#}Db&E5!{T@=$48;=1^nms%F?+!+*HYNsN*#}zO!2Xh@vc_m}FvummN z_CwlvXVr1Elq0-s=gcYZaPShZF62I?DGNA#UrWi}JmQGi?f2hln5;`VRC(Zac)%jkw*7 zTk>N)`!|~maD8GI-YytwtBP+D^Pc6_hFL;)_zU$EaqheJ;dy~RDcC38{FwOj2pRmu z%2x1``J0@%vL+rroW+cic z|HK)W>E{bIeY=ARQI4`@X@C3LcI0hihS*oMvVrx#)x?W`ZjHSU0IhhzscK<=i!6tO z`3WY%0Ij;*+z(T3G4ceQfAS2{;gt)s(=kAbqz!9eRcV!!K}EON?I7cv1(R|x7r|6~ zVcPVRfxa}Et6@T0ZDvs9+%Ym%60@qrhDon0>;s0>M-pWu_Lc1>sRyOe*CsPlhITNI z!&GcHZQ?MAZ%k&nWWKc-yMs~fRtM`&J+xyq4mnb{p6q7omflTsSPlQ=Q^t$y3X%Gh zhW3A{+Lq%}$Is}|_lX-mqpPhZcngTL-CbMI^~)3P{Z)Qq>*ri0h0%zVRCmu4(JFO&@uSp?`T|Yo zJaN2A!&*KmiGgUuZmB*ePfYmBh}%axek;|te~G$9o;YHvH%s*ZG-9VzH^>tQ4;bDX zrDOlC{QSa?+mk0E2Mu+1>G*|I-~1KoV|B!czYX!m)Y!$m)I;_AFSp&yhhh{GQqc`Yp?J4`4Oowaw_ZiUvz+%zM%tjl7<`Q&p>_( z$DPVrm8i80yGj~%|DK<3rFFDM>lV`RGVZGsk3R8cD+y{IvM2S{gfRbgd)Pcv8By{u$TztGT9Xbe$tzeRzo_ z(sgw;*F!bB=E?-;OV<{^@beZ@q3frbjtVoRb)hs|EPp!jQiX-%Filk zonNE%6lt9=4de2sJwJuMQ&}f}rbXsTnpzv3YM!XfOl`cxLirQmr?6Fx z*2kswENR%_cM_UVEulb-t`lVTvhflNr0ZSPTszh1dPKTTldko5;yS#VYp_PwaWbzN zc!|g4Pb+>3d(>!sP+Cuth6Vp6p=+uo6grh_#qZSqUB~f?Nw4nJyat@gOVxfvru86R zqRuW{J6CfJ*XX)Ox*n6RbENAz)m(?y=(@7CqeiC%GO4?y zz57qnOH@nml&*fX?TR677MCnD_&zl17#XJrR%u8xX!KSx}-+e0n)47Pq7Y4*Kz+pT(?Qr zU+@xRQ@D<*=30KLR5?8_6<6=&Wa(zS#D3{Iw3_ScQ@N_~^o-1FQo2U=;o7g7YvNR{ zoTIlFH{l@mNUt8%yf&W7OC=bRX?-tUN9^|&%;$e$MUBRvN#pCWVV6PD=};}5?KQe? zl1UU^M(KwCg=?c~uE|rma#md`KH5)pwrhs#Z_@P`*VWD;yYp18s&sCd;8wiE&;z*c z|Nr6IReJTqOZ*N6;d7kAL`AuM1$j6&G~YB(Fc<4{Lmz-G%8C$ z>9bj?2OdOSev-Pg)U1%fzm@98PEx-m)f>@>0e@2YymWuNZQj6Vj z65FKbJ=Hw3PvNQ0dY_cpSub5@{Nt^Aeuv>zzPH>qVi>CdbFQ%$qyVm|@3F$-_;-}G zi2S6rOuqV%xBi8GY+zU`@v9rWJQEG$w-~)5Jj`IKR!Lm(sW6fYv zm5jaCLc%VV$GF4$5x@ERzQO^O;S#a>2#*hh`-mTp&~1{|Doj+I&Jt_dD$(;OnLn4P zt{r+AuTKat!;$%6F!?)l73vCm5GLec9)YQ_n5rst?GWD{CD~)vs?>uAE%wgdNv^VkN5f( zr?k^`Qn@^VLxPbdR&S$&b(I&i9!^DCyjJZ}Wv42Kxi)3Hj^)&9zC0(Gf@i%xRi^`1 z_v8_~W0WY-z?Yq#Iz>iH-R*fkE`x_U1{M2GPa7a6o}d*x;`tM_!i!X)bdnGAdfoyg z{v-CB@HQ#igdB6U$k)>JKW3-?87BI($@~KocQAz?5Yxe&4U=*(ySujzH@0~S_eyG)}x>q&mM z$&|tb|1_BkU_yILrVmVXuV!@e17YGRlNk>a*l&8xTc2Cx3RP0}h)eAd&!qWyj!o>C zLW8S!BIt;@Vo#c{fqQG8$`6Cqc89l$ib6~aMPIkCY1SJg5!tU7Tw8AfR8$6+GufXo z`G46tu#=1I7wg=<5_g7MgtB~XMV)j~iCck#;)-+vdp@Lf|FYKNeSktoUAKVoA218s z0VeEVu7F88n87fS|Jm7*8I+x|wj=Ug*hC#RWo1yIgQnZ#FoC~KW~sC}WM*hBOui%Z z7MN@Y^Iw<@2jkvArX6uk+aSBlVKa0qjDknZ$cZFfj)+9_C*O2lW(G zvXZeo6`jR8YIG#!%hgdMjW20kR?twSGJS2`hx!QKRO6swb+oI*Fb^H=9iq98TOI8) zz+;ZN={p$zakCtIU}6@dtI@TQ3^{D-!-P+mUT46RJD7`M@|ix;)S+AzL*9~c9T#o0 z$fi#Xj_z*%S9-vui?_3UO+Eebin#RG9&baATM=|l?t}3;`qOl2<0#QQm{6KdS9?7N z<8qtK8W_LD5RQMJz%+M6{-yvb=x|GkhqHa9Wk*pY918Epl-`kx5||YZCII7SFv$AQ z`RWPN$dTstFl!xN!(b8)CQ>G;Of%3#n25(@;*!ZSnU7#LI|6+RlXBSXg$d+nFI_F} zO^g=@Q?!ZUTH&BtV&u;?-OhuFIG8>#VP+!T8)S_Skv4Tq=3Z&Tlu~6gTiO(u%(I*1 zi^%m%>UE4_4rT+4p9!@p&^IvU4rVWm%WK+XenMi!Cer{W(a>bhf+-6$F{v(4*mDfgxq4KXYjq*NY z2sxP3VagrMg)s3OOs}h9VmF%12$=kvOlGpQQB0X%ofNuU3!#!>)94MD;1HA91e0(u zKS`URrp-ZVbF0am_BqXQhsl(}F%YXlc3R{$B(kjT1gYm(nEJn}y9bo*9Ilm{2Yl04~Z3e+C zaZJ_YWt<1B3^D)lZyr?4F%;#w-eQN_zp;rsY+i*4M$M8{z=RykA28((CU*;76KyY* zz7NVj$);q6+QO`NB!3aiMh6puiBC4YhQdUrn9O*Xl!KWI^J9L!djh=chZChlMk!z3I`!58!fqZp)LDk+CiXPBge=_Q%zmANL1gJHHBfn2V8 zVEi*oo7pfS2lH>3a*I*@qs;XtRQ^oU?Gu=|gZTj_ILoxz50h{(?k@>F$F#|Z2|Z*o z&0)e0rmPcG%t2ialW;JDVNwp}K^XsBGxSq1K?k!2CgNbehKV_tJ!Mb{2bH;%s&+7b zn3RLL0LJyOnfx^{`3`0@jNie`go!(t_*Tw;{4q07xiosjWY)oyKWZ`+F!_(0Oj0uQ zP392HLP!6o`xR+9Y|i*9x0Ng4pe~d~!VY9#FGN@c=~mCzOrB`7#|mF!mR|yxRnOPl zy_pB7>-l)d$2#@S6AcTwQs_&Zq;QMTvv>66fhSF75lqy=vrd#?ps`qI#Lvm@Pm7^G5Y@!aE zmM}?+(MN}ix6yGD&zPaF!6@{s$=n6wikr+Fn3#ik0VcS}w0Q?6>0q|Pq@FWvQrmJb zcSRPPRPC?HwSzewChlOm!cZ=v?f} zX=FcGcCO)Mt>g8R@vU{dlLMUD(3h3wQ>%FHb1TH)VxN4gNG;@rRkp++vWqgGw_C={z)uCdP!wFt3(NskA>9jWD?4+w6HTPlS0a|kr)%2F$4L@Aj?!Xa zwT05cQ@GB**jFl^{(*Y{t>iNk7jbW~Mg9Lzo;p#Fyk&Ziyp6e5y6&!a|EAF?5*5L- zNOfv=UtMuPx}MJs#(G~=xmtDmA2FzjuW6eIb+vkf_2{h}$F4G%agEHS$vH5gvucUH zGri5yn^*OrR1;tKbe!d8pG6dlM=x(5a+mx&&iWeIBIPNfO?^!~uOP?N?o>Q~xlOKc zHxL&+&DS7yHT4z9&%YdR>MLpZSYBnP)sH%!+sN)bB9Hgi-5s`yF5P^k@>xoCYp2&2 zlyTda{M@qDTacD7uH=cyO6|AuHs&qzhT{9&wyfsxf#p)4pm{+D~py(;2ja)Jx=_9Hg^Y zN(s^iIuc7;D+H|QR7yU&J5{SiQ7NibQWbEjR*FZZs(o`*^&KiPpC?8|2@3I=)OwuS zLV}67)CNvRdqBK*dS%Jmizaa5WvSS1DoRAY^jIjhZCjvS=hV)X+6E}ZGN~$r$TDnQ30}urEiL_Wtdr7mc zBK3^sKgZ+PewiKLsMy57WkPoIA6}w0A~1Z1s8@<`@EC+iN*Gu#(n}Boc8YX_mUfG@ zLZq?RBfUgR*NV~J2m(7qdOooC1}E^t16?957imm9(l4}hwHWP*An=4po3!+-NXtYT zeFM@Hjx_ChM*3e7JSKu_M-VD}o#JgBf+$q?<*$K}$PCT8bbLbtBRe zExk{g{YRvmM4F|g?IJBf5a^YFbb*%UNVBg*xIq2e zw6s~ISqK7WMS56E7f7=YMOvJQbf=b{7O4+Gpi`t99BIM?hWalN6ih@=;0QuPZ4!G+ z5d=C!xv?K8I$wr9lMVf{n&??dvN9vixP~Q~6vdIYk=mdezBW;~URh=@KE%tShE|`LJwIdDrtrep)5Cl$()TgC4 zNwZf(dUrC?G%Y-q;;}!(N9YM(DF|n77AkZk%%d~W?G<#8` zw@pRb6}W4<8(qRVYAR!D5K)^F1;$9569@vcrXhV@OKU`$h#*ie(&Jh>Qkp#{(pyuI zR%>asND~kQ>O{IDBIVqa7&t0?>U4NTgxja0pqPtC5I7~$A}t*%%?^w7=39|2)6!ic zjYANq73nN39VE@37U@ktK{{Sbt3)~iLEyMZM`-Dl(rlkd$In2@C!9uj1KULEK@d15 z(%z1=^Hzq+nU~jMXCi2~4>yrhr%&DwTr01@9YNZ2#HIG}B_ht3kKcD935=PA_{s~! zxzeyp{!=63p01cB^W(tWe{(QxmJ`s(*|7usBb_6noZwDzS}WtbdgQjzzQbyV)I4dD z(an5&*$$K30jUa~*X&kVkd)=7&H+eG_}0YMc^;DFf6!EF0yU+Z+0E_(9aDWwhm>cU9XbSw zxyp1_2eCL5y6*o4DLG`e`Vw+PxwqcIj@R-Vp&kipf52=u1ER;V7}65H-L^Yj0%@FY zw%QNreBb;a@p(wmZ%myAh_9Mszdh6ZUTSf1L7`>8kLF=4{5in+Kb@CnHTWXUge;hs zWi>wKkQLc0_;uE7`^|r8CD$k7eqlsM$k=xoz3SpDNL>Xw^4!sGb`PjQHQNH|P|bpn zS{24)5V_o$J_V`rn(n`Yc-EU_bPM0wc~}VkZTESgpijw9|!7eMX2xp1WW7p8dy=-DI2qi6&eobsNZ|vU=3N_!9(bWV0ddYC7(LH1ep*&LN4+UdXm=lROuA z{Px&^{-|9hd-+7ay0 z%1a^6yi4Z>LZY&quHf0m)o5o!lJ`V(yg9|$ zOuA+No`g)GT`LN$1U2m|#q_~QD;ZchL@syyyCJQIRIi@{RjV}Xg2ZH)hA#V%5BXIW zheFyiO`T*&<2sWpgygDvk^|vy3;T^sC<7%a)4zh~ULS_oZyHC^_eDs)%BUttmU7k( zN#U#P+zA@>f0?o^PFWTw%R#w8Q)wF{^4Fa0pAt}&JQE;AN@qHxM3FQ|ZP0YK0@7M$lARE_+(1!jz=U-`}BcP7*2=RJX<(Cw)Cv&+$ zdlQ`)HPfw-BWihF{P~5U9t@G+(Pt##xt}CDSFlmp=^$BMnp3>OQdzwKrMeQc*{>l< zn@w^MvWWW!_vrUBq{)egbpO&Xm=1M-9|>U;eq&@)K)EVEGaVeCOUbL z7?oC~kS=F}yg51ft5)V(3CjJ$=k}Pmm4MZ$jD~L*lFj(xB4w>Q0hK zxgQDHs#+yN8dUJ-N~_SchUee1ia{yP!Bd<)2a(H7y+1&rR3W|k-{`C{V>S~~9WcrL zqNDbVfDqeqVs0}I^$3nt}h#TMcy{d%iidLbXCOUjv;SOUV zBx#@>>CpUJ)+$i5n(1FdJl@DSyxuj%c_rDFPnrH-blOy?UxQdyis9_9kYqJMt&q;` zVaqcAmURwPp%%=5ukF8sU@t1KS3dqKC_JXzk3uJ2xt}UT56YR?}JqQI`GIGoV}**ncRcP*zj%qSV}f zicV{u*`e#sk=6T5G97Z)2Xe}(o)Sg>Jf4xPQ(=4nrQ`#qp`8%bYwI~kwHjG7 zBwod%6EZ`^taleVRBl?1^MkbMiIB2~BTBNFX69O!{VSiIaH8FV&J1-%+6#%@9BCyM zUl7aWreuPh4c|gqmCodEIse2gG@H%*mY}I|WI&EMTc@3RSyriv*&1}t;>_IxABB{v zb^jE^qb#5Jmh(?hw(0&ol;m<#?@P!GBV#S=n)4J8wO$rM(v-6tNb`HO zx>H^b(WW;+VpJISLgs8XO}_wXU2l>PeqiStNSr)BWpLpHx%fL$Z-d!vE+i($B$W^k zGwr6;0mxugKVF3#Qx8HvfV8OmI0q?T$N2|}F>f*7{l~w`)GF`$UxKeT+)0r9$IK38 zL29c_QV!v_X^bxJhQz4d^@I@o`Q40t3p69cH1r)LP0jS^?=PH=WJt4Gip7xpji#OL zkS4V+)I;i|Fb{Qu&zFIvV%?pNVOHP3a&PRl{!&CuYNOi>*`>U`0BKe}+8}bdS@}I= zsj5Fidi1r*I2^dMIUUmMR5tIbg5}x%k~NvFYArpAQl(lHPeCH@3yCqys)N+=D8!y$ zA!i_ov~oxI4WyH4aLJ`T`-Yy8y3;bGr@yb2=I)pnNIH!BEkJ+TUp6 z35||@4xOdS&Iw2ty>&-_96dzA^tWMqJM(sE2YmNLAAR2^y+IhsD(2D(kV~u>8?FNvmjQh zSt9R-99Pqt4yp8Knav&o)j6S-(eHqys=)pa#52$g>|Y_f_L_FAi~CyjY8d??Y4p#X zj)jn|S5l)~^Z=+%IeQ7xnQ5AChV)aWzl5yIHg&G--PdYSh2$1UlxmdMRdjea3Ikw>WEd$b2YjVg@w5RWrf>Fq^*3EBeF{k@QND$h4VmS&hb zCmLYAuP`E!U*o!k#XEGxyx zm=lmvCxt`)UjZFcqi+>Ms>b!Zl;C5k4?p%eh6+)e>KI7wgXS=1LXK}YNj{{*Jq3#Y zN|0P`R_}q#appC&V0c^|RI_+gOso8O8{*kuI{QkWmrhVam1Sq)6RGJ1!U2c*x zNHSe?x6UUoFl1SWAcN6yXZm?a$FEE~pFqmYNc*ktK&`6mTz@&qsLtSNkQ7xJS3}Cy znx^X@9ps1G#g8DT+)zt|AwgA!{n61nAjAWba#dsr(aIVN@no6K(jZIsnq)o1mur$k zkam^AJ^Qm>l>2BusII^1>?TNxnzMzFRJHJqLF95Xrd~*;>HclVQWcM{A-T>l_`d1V zd~cv6FE)Bi%m6l{fo3npLy}eNR7iDB;Amd#&?%Mt+fscz3R$X3!Ml)CDnBo}g5zJH z&wa7OM#u8clxnlPQy{0!%&;DYj0oI`x_>+W4DK=2Uxu`)+r$<~i}Lp^B!0iy>Z%yr zI^zr-KzXRut_t{gbVfX5wwmDw#gv;U9a5*lvsRj^x!nb+y3zi-+IGcw2I5gU@^^@y z$WI`Nj%C@t^0WN~R;*h4y#|u~yUh+IKw{LAT?jeyw5hWma*UoxXY3CB38LM<59yU| zw)%P?hg2VRf=-2-4ZD)VREa{fUfCf9E_U7;yqo{CYoYI+yPMR9)-O|dbsba?msqA6KV+Eu`b$TOYt6v?qp9R&b zRDT%~rGnoMsdl<3&dx&msjA|Mr9+BLf|RR-T@3NPt%83)s7}p&01_22gLWFSOI3`q zSF?gvn>uBXHYd@fi&c;W)u9&1G5sRakU`AZHD=I8LmH^M#5SBC$&g(t)VD*9++w=V zf*j8_$tp;{^(Lu=L~}cEi<^4SgJ!6}z7CPgt%d&x6Eel>*<)Sk@4ER@uAv+qFs)}m z&Z>g31`?-2QVB`RFk96^wyE3ww;;L$AN+uv^Mm5m31`w^=20d8GDww5tSykZ%@OzV zDn;l)hLh>?WFwzn0`sZru!mOpTO+NcYwrx^KDSzp>>HH$o_nJhTsDN$ty1;bhPe%>JAE$QWI#9eiyZuv|sp@p)Fg6QS3~q%i{f+5$;q^x{633K1TC;0K1D36W@H4c9{woim`ERWiM6 zL!;{B*!l1WcD{ndsr0;LI5oan-RE8pic;B-0%=tBY5~Mj4>Xpu;kmKqIQUfVd z#pwkh(u(+pM_&&r-D4(Erzm+%lJH}6)O3_W7O7SK5G3D;ki@zMQmcy9-yvn8jS2sf zewK9}B$rz*`;UM)TZ7!y%4gN~H_&^+ttO$9uPVXqkh*S-rn?}ytRNYbJ+J_zQ?02(kY3^G=w~av392g%JY5ny z)PMO%mXmsWDIOA~MtMKPjg~iuw-GsN*k2bMiOnz2Nl;y>gVd?E&uWl?cnK}k-E%8WF0POC`dK;o1y|EQZu7NztgN^NTK zJPYZ!(RBY7q_I5Ey^8pK&A(e!ee4&IkAcK0$I~Fe3{z(Tq%77Pb~>a=&BH2) zZ0By){>l$(C9N4lI0H^W;?<+5-lG|kIvK@7dL1-d-3_t7^fEG`%OIty)5VaE9cHV* zXg_BYbyzxzQp;ge=}U9Qze)P~<55zE;vvo1rqXoCaVIt9 zZ{@ zGSzi929m7G_ZqvI`3&*PO~D_1S;WjFL4Wwod|T}QJ{l~RvGw)z4c5AaH5f@G{y9i4cNISZ znXit#FF^V!_kV<>DAFbbJ8q#o2Z_%zJ2Z$p@3TB!Hk1-UB}!>N^=!Zq2&+Wqb5 zMC~@am=0+qS7ZXDC9e%Z>Q<>^&u>7rDjN<$1+@rU#*UKNHuBiF56^CQl{DJKFAEEQwkYu zpVK49o_(OQ60_MKASG(_fh>$zc;{PsCmU6!WQm;rEq%1sV5=zT@ z8B(XR;U5sW+!X#ClAmdI=tq-SK~6Gyy?&XGEUQU{aUe=utFGTq+?=|M|3JvU6@u}`9Ewg)Bs!srW- za@x5;dlRx~mudP#NSxX!&O^%B7u;5Zl3ASJM1{H_l-ps5Ke*X6)DG%;(j=pAVZqEb z$wWxKS{=7RPOD+u3#nA8R{%-%nRaR+z5Hr-5G9Z?U*-A*GIwL(QcGQyI z1L4$SEWG~_JNmItBdAp^ysJ{U&*M}iX=BgXb&&e<$a|jhuFaZE%W6=C=r`yjWtand z0}`*6Vke}VNi<$>=slfVFEx&vA#%AHyA%?oOcz7C)O0)%ZskTXD6P1qHCWDGp7#Bda z`vS-=b!$@zDH~u9!5+plkZ83FoP>0$ft`b#4%d(H`DefkPO-{;9K@rXnodT*pdA^+JRxuW>7os~dRRnRIRZE6pE8q&HUVo2J50rA~ul0ma^uUbum zR60ZT`gs9GR&bG8!9J8ccbJ9>Ar($Dakdds=4>!tuYA>=Wo=c-cn}>+otn--;*F0! z82^wtJoDINI!lD)?>5QpkV;kImq4t?O`T1Ua&?k;3KE@d>bwGpah|X6DAm6*voJru zNuA+8L8(Rs&H5?Xpen(YkVI!wmUt|Ic&;|*J{uA&iMS8{7K2rzB6P=Qlxh%8ZxUuu&D@a;(#I(2{cpK#_GZ4F(X9_iHGRGm2%T3c1(S6!%odfAs2fQaB zL3P5ag~U6RMJzT!;44yn)|rCfSDrv-W~9k)9_1`^~9Lpp_t4`Qi%#yyZ!HJK+x zC)~oe^A;pa1*#R&xR{)BO<$SH(sst-wI4KD_Ls(a!tN)cQ|0K0lT?Vjt?EX6ndror zd-KmBa=D{l4~e>%n(8*&BF!#04IPAZXP8~AhsUMBBBtD2`;veqy zHc+zKFAqU#m7#jbSryoKA#%Ba{RC2{_SB2+vQGf*i5C7}--QYj>;M*k|rr;c+M-F0Dy z216QD?VSW!=RAdyF3y1T3MXuMPrVD|2^}&b@hE__sj9IRqVr=9Bq}q~X>X4Gt6#0E zqMSmfZcRi-+_ys#BPULof6E$uH%C|JRP4>-*jZH~I*v2% z%Dm+T>G{?iH$vk7L6p+Ivy7ATV~~_pW`~YLtH!?c&AuZ1FMY=y55;RX8erqL2 z9_Y9;^b{m*ziIjH!DBi>%Bmy6dhk?#Iy*v3E5(jry(Y1LyP%glZR z87@|1Aac2#z8O-t$#kC%X;(4Z00}w+llFTT`Z?pMlhI#LN>PD*4>CgCw)|)j+fuga zY%nB6t@1gLm?fspYDk@Ozk3nS6yk|3-3*Vc6QwS7!a5IWS98{HF=?f?;6;#DWqK7P zdZ3wARgeUAP&^9px2sUU3G!f?0E9dA4y09u@oPv>)yiv^u$%eJVcZXC%P>h5WS7!; z9#ZR9?*9x*Q7@2w1zD$#e7)`=8(PiZ#^?`Os^_15q>nJRF$UNA<=FQiT`YnymR9Q{}&Ls+y%1*(#eoy zRQAaJ0_j%I3BQ5(l+KVWR=Mkpw&NhDjhc)9+d*=<&Xz!8vLYc8**ei-ow+*OA#>=o z+o5+LXVpx1LXwpG%d$CJn8a@l0R`2eU>qbR({%5J$mP0U1M!rZI@OS^DvG~@l}v z&6y$jbs65%vMSsoGwMB-6Kd7z%OPzW&9UAHY4DmP72;8L7A*JE>n*0zFHwqDhJp~e zqWF=RSk@6pn|cCrCamM8aL-&eZdDtiA;+>zU*mH*|7=q!b0d-GNR?)l!i^S6bIu5^>m-iOXuRd!~8x~ok0MWV!I8>%|_>aN~!UZUUbscr$a; zi_`eunTfl%HYzc=);Y z`|shIxqK6XjoifnIY;ffXM1z9Uk7XInS`=G|J4PsI0RivJW1NtuV9i z%%b?XZ9?QOWOCbbn-gZaO|Jdk@8@&MVeI$E@8|V$-p}*CKkw)LTt3h9Ij7Alv&fO4=LOT4;zG|*@?*&yTra6Uk*fBu^2f_775#wCmcWC{E)06N0; z^6#X+W9|U~MC~=2g8-9cJ?-TfT^p!b&Kiviz(9F8Z9yXB+3-0^UI(9J~XgtXv~fO(r9vG&h2JPij6VzYyEfJ?G@Mk|!N;P97|Ikra8l z)Vzxg=qvyJc~w=1g7SMWs;WTO#4PjIXfVM`lewz}#2VbRFVgvfp9CuAMrOHKYD8b$ zkSnAHBwn_+X)3OlLm_}O?cGKE36?Y`T*`xrMD~Oo1{$V~#i5YO)UP8)m$odfVL;Btc-cAjxSl zH{MPwEw82xO}!ms8Yr2UCJ37Jf&@>r3;z&xHBA1|wiA7Ks$6E)_jIu#Lu8ij4K@5sh)5%G$67D_F1>L4jC<{mWervv+Ou>uC_#YYMW5HcQ5E-tKD8 z&rg%n>}OK1(_cAwP@k!CBL}zE?t^SFeQdF3Za=H4+J=2}%MGof{>KBWefgtq-dKm_ zE&VYTXqbX3-_DF7WSEuImIPmpL`;@knorS)k%<+k%Op2iTm<^otP0)Pg_|-B(AiNh@$l zTfy;#n1y@HFZ#$8PK|2M-fH^_@9(u`PiNO5$^hPoTkTVW9uSCc<`OREVgSjfftCjH zz6yfeRy*Koe;ZI`QU4oM$_GI=tDb#7S^mPgp?k(;=;lh25N1gim3V4^yvw;>LyJwP zts1}42~A(&SUEtx=j@Z*s@gISZI8#*p{)(ZR8<+R(FbfgIQq2%v<*TAS=P@+bL&Iw zGYsYZNqS4X57l{@KgW=V0#9`lb|J#Kx}!Jtvl(omTh#Xi^<03PSP0x|CnkbYQ{*$t z@RGLsVt3_EvDMUIcn3!HlPhX@I~Go|#r!I62!qyqN%pE8H(EfC=QTpj^L8)hUS-6Hru7#?{WdR6CB)I)~%|F7ME@2jwqZTG0zfPF|OmRCBvS7U3{I@-NKx zC31jUEFD@${?YB3SJ>j$CEoiNrtM<+SlzloE-K+xohqH(q4uiS%Z^ICF~28}3@ z<;U&@uM1zj?%1J!VU(}r-t|J9BD3`vahxsomW44l@~J@;r+qIcuvi1(lK@bNRcFpH_mG9Jzbjv*dsV1}{15 zb@%4{3o|84HZ?G~^s6CMcVQ1ld0&IBw8%kz+Mq$>L5`|tTfqlY(1V)%OTmmBIYI8? z(bzE~lILFwZ^)w!r{x^)rgEBxb8^a7SSC81QFF7nzXsZ$ezvAfP4@9MnKL=Q!W6AC znM(^{rF|^%^_Z_}lK}Dhdc)<9mslI|ROOQ`;mOg$Dqd9#p)~)bDuZZh%nej!un2Wl zN5jq0IAktn4tr#o(tCo3;Pa4fmLY>P#`b~)X!qa+Jih9re5xnR7koUGf`(g$>d{_* z2N2Z3jYDb|5Y-{|l_+m$=st#bvha%M!+ul4qcvcARa+BaH>HlT2Y`Ip7-$`~LuK-> zVZvU_(aN5UJd&NkzNNq1&0pv=nr)TfJj{)01&Q529Bbx}w05xgIxQ(kD@bU%U6Tl? z8NPg#;p8Np9ZnHGt)OdDPC{2eHV#&Mj{D!{Gz=nG3iMzu9CTE5(NqRHe)A#Y=f{EgC3;LdZ76X1NH>T6|jeZL7frwwbRz1 zul*bnwFiQ}w#Bm3uLY@vp$0&4W{Z3bcR>cEB9e0I)f9kum5t%Gb4$UkUPk+92AzQD{5%3jcuMB56P6L~jY{^I>vpn?aAew{GMR?m zhTetxO$cu4?PS=Dr9jwl4+qGlJ$Sxm1{G%xOHuizaV5Z3T+>sNNO z(7voJ%NpeB3sYK-0Y3O()f#fj;CTvH8Y#yUXFKdA%ok3%-P}ORe=!sqW^9f4M>MQeB-?%ARlxh9Wm(Ol)LT@O``vFcwU=eB6p zu*R&(we!DSs%X(zZsS!;_VjK^3grIY-tAtDstJ=j4@%?eptx=K0|n-`LwQifyXqGct4k3Ta7g`38i*mzO4ILJ% z&i;%^^p4!ORVQMQKYtB>QU0z~^ZL;tA-KUXI>W~SSkC~Y7I;8+|0Q2*6MZt~}?TaY{Qn%3#ix|VIm5xs0`(~Y!|_rYh0{It!hPK=S8w+$r05a7D8hD??gN6e^ zk2K~H_uxt7uyLPx5ERtW_23`5olhvlD%mF(4rC7c42N>#4p@%u(6-_2m*yTgZS{AC z*wuk1#$Xe*^5zbH$psb;7fWoN(wf4=krT_&Fx#7gZl_kdCAjpw3X@`j18}9`@kRL_ zP+@LxNu6qn)ePdx$tQbwURoxvef#+2Wfm=*WdF;Br!R2g2GGK~TxErvGWmCYEmjYp zJ1@Z`s%|D;Ho?*h+FKXRyDqA}xLR5Gv%uOHUyCnEz-itHv*fKFMPs11+FD6$0SWB& z+iJ3S?dR^lbn@X|j>x)2vP?l{jK;^X3_uZ=w#@WcH9gGb(A@H&^6*Zr1>Mg?E^Ft? zqV1_2&GDAkb@C;?@*kZ%Yt`hCy3RswICpM9n#pZCzvp-V9eiG2d=nmhmvly@;RXpa zt26itu9@o`Ksu-FF|YH+r(tAg+KT4pNa|NuBT-!aG1nMhfrWJ?0)j;cI<$f3~V&b++iR^h>Q8 z!lOG}IgiFuL$$mmA~yk{`cQ0PL+4AX+3--XiTOYc(*|I&K5HqM4lCddd6}=Lqg!v@ z3CnxII{40Zc(83I-|%fhJuj`X?M`Xv?|Jq;;wVk|L!R05M{4{duf@BOq+a%|0h(Jj znOh++@UZ3Xdpe;fELc5bZs)Cf&z92cKk|ME=t-#WRoUFjmu6g%oA&mmrYm_Ny&Dp- z{nY`Q-QBLr@qx3&qh(M&StdUW+)ZPz$XkPa=)^0sIcS>L?FvxBuE^v2e5UtAiFR_W zQLSXVzM*;-ta|XO3965fvyMs)4i(Q~^&b!n{!IK8%LlK>SAsvISIgwce#N3EqPkwm z>)bzvh*Poh`4#!@pvLmA148LkC=RPj0n;)h()I(Onr2D23|aD`p>^mdSLE+P9(YUy zETD|{QV)>SB4W(L`8-2gXHFF~V9US>wBWw%F(^okK;2PS8Q)xrzw}^bwfvq zU6B%eSr)?|P)F6<##dywVWXVyp`x~+$Z}ea`W!_toFU_0)+ud=jl5^bAX=*GyL(x- z9X`r_4@$LEdy-3>1w^&PDpleqRifas`~)Ocy(ZzX!Ajx_dDE!Dbgn9}@^aqI5lyJ* z4Gg=xT$XE(`i$DDq^8iCQKOs*>U!O08!LSWMDFv$G9ClX<-8T6mr?N)hO_iaUiYYW zgi2TB55~5#cc^J;LWDdgqK@1@q=S5QY&Q0Ldh}mnLrj{+SLM&f%?4E7<8i$SZFX6H z_xJ z5EmoVJ_9uK>?5!^_T?)VG~>dQVtS)2@27Z^fMe>N1cjzwk?$wWr?<-FIf>2ay)t=S zVq(+SYj6|_%YMPM=D%ujFl-ex1-oSL9_gR?$OO z^16NIqor#hp0ifbf@`ugdrG6tpv!pHcnr>b_M{dNV=87lWPXN=-S%DAmScG zi5s!L=~`aZ-17oG1!0(1AEG2r{$ikG`4CvmO!LsEU(TqMD@X~)UN8J&4TMYnAfo}j zS(Z01<73h!?mD#Q*sYdX*p>fo(B$iRE?=Is!x4I8$v@Cd@*hh#w90@WZin5Q=KeaT zw3QG+Q-Z;B_Y_cN!6vwI%+%|7TUb*8r1Q?LNFoSFtb9mN&7g12A!zxn;#H%~_#5hT z0L3qLAuhpXH)zslr;*orSA!34;?2$R)1kFH>ptez{#aU9PFQ~*bL4{`n!CL2sR!y` z{X=g|qP!a$+_|S@V||2j!=DeKocU)3HRj|da;*F24TwFkc?yDVdA$)NKX4D0WV6|>Bj2zXKw{_CMksM%>&j}uwMtJ^byey3dSf%; zknc^6?Xk^;s?w7X4Em26vGL4DDe!cX@*b`P-dIuN!lRXW=)n<^}AE zAn4!Mzbr)1=GW1$OKyL&r2Nyb3twlw3#TA&GBSR*s~)uHeYXENCXd|j&{JqxUZ2As z|0@IPL!!S)#knIUN|UbVO*}q~()EAl{Zc%QP|y2v$5Y$r{D<=GQ{8CHL%I3sZq)ms z90efsq0COF(isnBkCHJo`=LCuq#N~nDCYr4yq&AZ(^eX_v-UW+z{>${0rRmC}o$qdz+{Iy0`pKLkc zo@!1yT#$NAK%!f$y?<6O&7N zd{24NJs;Qu@4e?uop;K&@73?)0++v;6CR9?8XF16GI%#y<(dI|c~fGkY1YLKFW?Zm z$~6KI#(h<;(FlV|s$3WILUCqL85h_lhum)}I)kb;E<5GK`=kA^3=gt7s2&a=YcAEn zzrd$(-R$ZK4_aJzIHokwGWD_U zQ_i{=IMA+ zm%yI~vY*MRkD{YBi$gSR@gucTbXxE=*i5aob6PMAtmhya9_-RH0Sl*qY9$3Krk)bi zcG@GV$|riDVG^74wAA3tPZe;?GJpA!Uq;7gV{$(4A;TRYj1I_bzp4alp2gJb-T5IYV3hxt` zy2Q%gK6NK9^0ud~$Xfa8(~pRsJos5dD1ZDc1j;*}`9S&BGXs1&KhJ@8IyOJ=MwaE> zeBNG9lb$OLw4{Uxxz7hE_jE*Z6yjeDP@dNzj#}D=Dh}=>S)eIYSClMG zaG=Ym@?&fAk&R1kj{r@g>%>RBoh!v{KAi$II|{lgt-6pTffjUD*837q0tI%sJ2``h zoOcLJ)=>DR2l<9j=e{hmC;60y_EmoCNn9xn&SrnTM;gCLOUGj&znX(uD zWDVKCRtJ!AWF^z~BJV*huotM=z^?WpaU`6D_9oLvxKh}g*bson14&~-H3IuPh%}{I zfz|0lzM{5*@_irDOxI?Y5CX4g7~*#4Lcthk@ZX6UXnY7Oq94RNE~fzTfrj{;LP7aw z02s3I1dO>^TaAXD3?ZKEmw_bPtqgEZfu-sHIHlon;>6T82T2Pq8dlEQda1|~c42>%jSd+n|j?)9sRNez71ehUq0*k%5R^JA}MPJ$3B*5aLA*I>liq38f^0MGYf< zBtrRm7>OYyV(SQEOX{cTLNrwgjk|Zglmey1o90a>NOYG=X*$IaK_2O-y{I&dA`Swz z5fwPN`<&1jw(N)TB#IW;DmL$vPYEp(+1wb?1rgh0h!GHWEN~)OLksL!`9yLa3Hv9J zp42{63ej8&H29Y`50n(g56LH#`b)~3I6?#(D6zCD5T;;>{WJwS-A_`I;>mB2C$=nn zDzqfqjwMYcD`|=yt3Qowv@5U;(X`xi(f$}PoSp^*jmSPpAZ}C;6=MQ26RI1r0wURn5-D`AB%2tGBM6|8_DR6ZtFkiqE zqA!i-c6=@=9;+e3beW`lxQ1MTMNU!%eNPJDu~Jf;|3^;fsJkt@{4@EJy4tcsxuh$t zWy{DW(veEGtji`crgIx~_T-%MF0h8CAG+w^1NDnKU--NbXo$Gz;18wW_sn*N7my-U zOt3B6zljXS;JIxk69|p5WwY`~N1Hel?R;#TE!&nyhSLaJ=A2KO)fofmTOBj=y)dcH z?I~>=VXO4XC)0^r3{WnOF}Tl(Gr$XE{=&I}(&n+Y?9>)A0)yLnD``bzZIuyQ$&c{B zY^!LulUZ6i##TxFg>)nhwt+b0T^x=J(-?!FlM-l%%C|qK8)M6geSdwiNSqA9<#dL=M-__23NAmKYRQwe#WtYv?fkYRLLHtTbSv_m-k45F3u zXGk-_eJ#$4!>++g(w4cNBT2yZ)j8rRvAvgxKTIG`FO$Ax2J3wV=8;l1x8!o7z+%xz(5Q1XLi@fkj@%=7^toZ&^WwkhH1bJ5PSv37sPgi-U-kc zBPBQ^fir1Xy#n{HS)a`oT_f)O|0UV-6-j@PtdUs@>-eFnGJLwoSr6r^vYLmxoVD5P z{xuSt>}TysdVz6YLSIuCbOOB^V$uB@SDE0jW&`esCRC1&imWO_hKb1FVW|4exEEPY zt;v9Q1h+Z=4GYNWZJq#Lk$7nx^;DH*Wo6ZZ|M0J>dBPI4hsxNk>!blBiTEc>wrg3t zKS@xnLLMl49Or1wbuCN#6EbNn`|eMe1hd(dKS?_h&1&5sUagZ=pUr1riA^o^gw54H z^*lk{LYeBALJXbJ_XK-o{0&HW;=?wTlT=94E;mWA3!dqlddEV)fH`~KCkD3YCgf&r zHrsO(Ry2U6H%UBc!}{HVyz^mS-XbjkY`#U($x-Hen;3|X5_y}nCV(~mMW#Y?p8drg zZg>YKK@axe4(Z{Dxs8dv4t4>cv*+KWKI$I%H%$Bn_Wj?);Kb8Es0_Hkk(|!#{NLm& zQ1)>JX$h@o6=Zf@Wa&@<9Od}dChYf&oq2@X+$GV#nt7Kr2iCm1WU3Ww7tVUk!s>UA zq`UC_M^IsEZ;7bpFwAG}LA$e_Gu?f%s3GU*Z4Xq4%$UqjFm}y2)E-{IMAp3fWIPyh zdjQQ{%Zv}mO%PNPAHupsGFZw#8%kH{Qan9YtqA`KD#^@#X+6hbnX+rf*j9SUGq zE%B{0ESC@!;0UUOy+Jhlz7m2O&5l+QPn5e;Nm_Q}a&Xh4Ni8%OD@I4{%du=honbY{ z{Iy>Oxd2cq1ql03>~*aJ8}yj8aNGq(Es2q{E1RW0hP5}E?SD){TKhS`x^izL>J7oY z`F+do+mv94HsQl{4D28zaIc*M^LqlVE@a<6A+13C@DtJoz@sN*KlJ=BPl-D^d-f@5 z)rLE(hbw2;J{n;F!Iqyl5Sm^A&z9Tl!R7LXIM=$yvbN7i8(NUfMn5Bd2$w%2P2IL( znBs8ryYJRf7zWsy{A_me8L5X>Za*U}dvh!I@P@xMwa^7ZQf=dRzyW5P8<+ufb$CHz zA?G$f$Fpo6@rdW7H7ZPhPG&%3UOXr60P4OVmjOI}K~^AfNfl|1a90)S1@nAW70mO7 zCEaKjKyH~#tBC6|HM`NvY$tFCv&78iQkn^BoCWF)D?oRF4ztCyf}Dck$(9MU4~&jK z1d1jr1=<5ZXDz(Dyq1m8(!um#Hv36SBN5u`=n#a_I_isXg^qSocUB4N&MMAw_10nxa1VCby>QG>on)*D-9hJ-pQC%VXpL z1o zmLrqvFs`K5a5|RLr;gzCo)H!$Nh4_)7y%`4#0rhR8Am52kW9l6ZcC=gPMFOwRuj%!22Gz7+7{Nr z$;)VcwjhQ2)J6szU^qn7lxM{$)QcQsk5XtGU^UF4@4Dj}jw@mdm`*2VS*_zU=g?M; zDUQ8xalsuhoQ1H>b7(&t`p@Ukc6Dk7tUJycwFjQRTbD$SJed8EtPh9lfOx+bQDZ$XH%&+wQ*!5jk@x~o$7rFHVxc+ z;lNs_(YEe5HDnHZfR~1u@NQD|9F)Z3)96sx<`$;WrX-2oNCT%HFz<9avNoTQ5)Afu z#A2C^GTtfcK3OZH~@|FAd>*5e?fy0p7?^db!i42?#LT;_Y>Y>K#IwL zc{rBM&!F#;3U(xe`atbj2JKBM6n`Ti&GX9Fj0IlZHa=_e|OudZEq& zh=P`NT|m14GES{6TmXVv_QL`?n#3^OLOPDzW|I~|*lx3(00v9Y$)VNhWa_O>tay>% zlR|b38RC@Q9Wn?X@2iRP!Rey(5;z8mUfN3&7G_PWWRY34l^edLF$5ZF-t__823V99 zvsGCz79e|eXVGQ|uVuly1xrw)MYO8`UJhGKd%<$BY%%QswZn_)Y)8#}o~Rh0D%UtR zdB6^{e@BQb}?K#JdY&0gI1m$;p5@E6?hq; zJ{0W3&Q4INtj;pp#}(D#lL4H-r2-p-1J%NK4n?&E%c#3MS2SfDC_+!m-5}yzJ*!v- zGZt`pFQ=Z)FO4@;sS(Ses|{?yaym?%VPc~B_jMp&E%KGi=^1!9IKBchb(d1Lg1X{P z)O96IhKIx@D`_*RZC?rdkr}M-D%zS}%w`Fz;Dij|>Q%HG!V9Zt6NE2T(K`t5d_$Xc zyNL7IKkzC<>g)SXZ)gCdlf9>-y6=nuXxVq>JF?(!X)p}@Mc-0i@7q8z!+VafDf8iv zDC(2G)iX*UH1l^ySpp<4azZ{s308YrEEz!5E9NG}!&pEJ_ z0sP-N)D@tjUrqaHY4Lhx&^pL4EPVAnO(gD}@rkRdd8p;VYZvqsK8WQjjenr;z-`Qa zW%LGE3dv{e;!m^_31ZG0X@*By2sqxjQpCqT^NlI+iX@(NXJr+Uv=ElRk#H9Io9fH@euw2+# z1+HQ1b7_;V!N78>B+C?N@DPZxZ-ps9YwY{L*p}nr#M0nlw7r$zp}=_fSB_d{EQSKB z%B5blcMVcADgG2p1+ebr*Ja%{!2|-j$84eo3Vd@n(WY2mw}}R}<_b=m8`R@#2riT6 zpFf7CYTls8bu(@2Q??PF#Nl6&PW$r!4c4GDYyK7Kf+4&x+W}nydhlvCbu%n9GrrH; zOv#(P+n-0L)5QZ>&wTnV!r$}hLWEPcz{mo)YKw}0cdLp&v6a?y_Z|abuKG)>$sAxX zf4UT*N0Fc%yHugxuAI2rLhJ@aq_Ca}ZJ?4CT1a9w>0^aP(UO7em;$B%PTmHl09I`S z7XY^1uHuhxSMl71Sajh%I~{l7##a^>0>`qf9pD3}R@ti5?}1t*0O{Bc@PU&~SV*5% zlb(YVEzDC|?4%_E4Lztl{}p$RE`wNP0j#jlfCU9G#X!BNfOfXVx7(xQC+(rlIo}@W zX6;xde-FJuX~i*RRUzzCY4{-4@Bn>}f*Vl>KmzLQ0BEwpI~J+RlsD{B zEii05UKkm#j~G5Q^A~*W=-2$;SlU6F>hu5xt;Q)GUIx}2&^_3}+z!F~na#!?qHaMm z4!pck8eOldia+|pRGXRvr=sw9u1)a6Asbswg0UmPT{#~^xbcHA{=)&b;}C5Q8p}W< zjX1z655ZiU%{m;WZeHiD3>e)l20*2HjioiO;yCv4VcG;l7J>-faDaV(m_E(*snijhZ0oh^fXWnF$KXs$CxLJ2GWahxC3asD&v zdW})p}S6gKFYdYriX08kMfs9OOGhh z71~y7lX$GU{_dafykj$|n$BvO>0YbqMKfJ)Rh?Z=B*UyoMPZxqbv3ffIo0JDnQZ(n=ac4<2HDE9uN8_Lp7>94=p`Fs+H2B3w*l z&eP(7>`EmJP){wB9@9qDN6Wk)!^#d=_#0H%ZEkjaguG!moO*N(y@TAatUPCzNOrtEYAN=Y6wID-!JI5x#uI896QSYR!v zSB_H_))LC$r05`OY9p4isk7f(4mFqcR#s&1W}m^Cr=iR6^F4Bbq9VxNd#H9n2>e57yUbWioW&_MT3 z>;UxDNMDTfMX=Y?8g^hk4eN7w{Q%Yzpk6*1R+SC~6X!h9Xr0pGK?9!;{uqJe;Yh|C zE>y4)F@cDASLHd1h)#%Tt0D>z(G(FLDq=k%Y9Yc-MXWrg9O^Gjr?kx$7BEowmhN(9 zR|X1&0G0KFgu{gPFJcLyLbLk)i$JvOV-c4kUM{IFvrVDGk0=-wCj5ee4TlI#i0#D& ze74tKYruks3LeSZ;Cp>eX&s>t=e)?`IItcBC; zIWJ1NQq_qP)fhLNzlGHg7dp`SgW14v!MlFt1X$t@m8}l9 z3xSS9+|x^RVaLLSo-}3>vmYijrGoI zlud~cJe=cVt+CHS+1H3&`3iPS7%PeZS1T=z5Jw6h(p=ucdTjnkp%#5Ggnc_w=#2B# znUOFylSZ*|qd;Q*5SBSg=;&PXitY8G?8GRrlJ<&~HZXn>oBs-Sei&;pT8N{|4zVSp z1!L`($p?Ph8_d5RVWC3>m*i;P=V}s$^0JzQvAnGIe>^X%NjQU-)g%n$Wi<)?d09=u z2wql`Fou`aBn;|}hU07D|S{G^tvnfEYNy48ZAqk@+*zHK@fAe7G9QAq7{Z=M zy`F^s8w(ukhq66mfukaf{WTVnF#g|3xb)YzB;gm);89ux+Y}8>_=K`E(U64p5xfQM zetE40zJpnlagc=TkzSL8Nug};IOuZCNNcQ182cQtKCfUC!r1rYtdj7?I7q_4a2#g! zSloC>Lhqq0dAyp0TgF2YI)}4>_d%jy2>bYbOu|=e7l*Q+-v=x1uUH8TV;2w`{0eq$ z7!zY42@e)4i7~<+SOGs#cQjd_u!xCZB6})Jn<#9i6;st6jb<8)m?ZS4&ePc1Ny20r zJ&n1<3gc<+G-XDt(4WwXcvkoUAmS65??l*%B%+?yWI9Xu5Y&`SXTFmFI~}zQAfLk7 zIVcJJlxgEYCi_z*HV&1PC9wRD0a5Uox+^OFjQLImZ#18?n8`wwYh^La>}x~RUA~E! z{5^Yye$KZz(Vw$rQ^3FY&)KypxQ2p6yfBqICn=@z0=$z_HiLOh6>@5E75@E14T^jB zOqp%jf6Z1c6(lpmv}#M&`dV9ZPT`h3Q&dYnDQs;5Sc1KSArUMUrzp!3(Ngv-_UCjV zhgKFV#!rO|9bI{r)tM!%vPmxGyW*I$%Jx~pWx?iIO?}NAp)Rrcs=Chh%@ty-sy?a0 zhgQ`!sX|Kg8fJ*ds`p;qCD+hcaGKDAg2D7O;afdTxWK$j!VfkhE^$MmTbv;6tM~G1EH1 zm$s=?_OBCMAqcD)M@>?fZ3&NIpCG17t+OX6EugNH*s@mWD7o zk3IOG@Hcc1yZ)oF$*yc`Z%v|P3Xq%>w&@4KjcjGxHV7fO71sYGttrPNm2Q^Z2u+S(gh z>c3@aU9Fk!I-%UGtA*DN59TR$^|X)eVOyc-y|lrE25w=YEr4bH3FRGc3(M%1$Wl5^ z8QxWU9$qR7Q#y9njwCdA3(I^*dy5`DrOfQ1-JwTyU3+Q&)LR}m;@N_J+G8|i3ybUz zY}-yL{Rdds^h1yh_5tuz60by!)Rw{*BaSoQC~XwNWl`F}xX&(+(ym3gaIDq{&MWn! zwQv)gbzJE2Q0C9CaQ1+QjP2Ea3`D*skrqC7 zVS?5R$AmCZn+^?EzMP2Kla4E^V^KS7#`=F$t$qBEm)eIz`EA<2gs=W{FW7)Mu3ecH zr_Coc|0HWUSvw4%k}_G_0)wagFa;1a`{dTC+FvNf?C$5<8LV5PHW3Hr#zbvQ*QU_H z<_W=ECohk*Di4IRwIA=P*${q`1y6_gg=|rlPuGs3bpA=@;SB8)icfuDLL{jENs`tF zVVhankR~;fU@f@MOKZ3NEoEi-EbRmvXxaA$uabgswdX#qypV_rIdx%HF- zI^AqoK$f#UX~?jG{fRJo1)G*8(8YM*Jacr7ZZ_5Av5>X8 zOzNM-4zkQ*TiMAXog3Vc zm+sf~qdq5Cvje&)8hwJLBFs9$t{%``wR1jI&Ch2&SL%6+nTtTc|0L^l5E$c6G8tj^ zNp}CBZYa(AO$k1vo2bJnC-=DSM~N1mVUcHbAK=V#@T{&oLZMV=K-jWW*9#dxF4fiN zbDZ&_4(7PRGkg}=d4|ROu8XnRsaCg~VJCmroweDbRyUkcHvOT4b6Ak?a9L-IbDPrB ztUJc%H2Yh+K`>FVF}HN@BVo@i-FZHRt@=y1fEU{St*Zxx=SpyeF3OR*pI6qu(3u1q z@jN&F;+*0~^)j__Q0wA(2K5hFFP;99jhl*dP;tsvdc8W0trYcl+`t^0-$>sW;ZKe9 z9ngGPBRw25YOpdqydlpl_$6;b#=>NBTNiT6vDun*uDA=al#<`mY6g?VRE; zP47W%=E8v_%n{4ZDIF8_=U_TLZ9LVq~Q@>BFBcry9r9KC{s-gEVz5IXCqvNctIlh`b&K8sX-NY_IL>5nOe^Yo#_ zMh_4A;6&*W)-XeV3-Pu_{bVBD1p#waCoRhrMK`weOZ^rbL~&Ln+@wE3T@O^(finl* z7zWybqpb4+{X&}>5<9v;KgO!sVWEC2ZE#E}U#Rb{ZFB*R3~QxTPdnj70Gy-|se0tU zSijTeWmUUGKfg}{PqiUMdcZGh^%c`QR(6CXTF!FbnP8%RZhl?j#aH7iA`3AeTSc$*p%Y~fmcgZHd7 zLcH*)9<=tn`+w8ABD%Gc`e!O2=IyR=U41yIp_uV3VV!)aN*z5yRsTej+J!F!=$ z%E2T04|FttBT_5Q6q&=5b8>N%g zM)ho2-6(!Lf>+9%D?kfUA3fBc&{EGM@WQ1Y*2yz$>l1w%uRqmKpt*U&_vfWNRBs4k#8q5zjLgSNO-eDjTRKcA=wv)KS=4JJLXEDO6TIehuuxgB43pCpF zufEV=6I{hfFRRKKSMdgYS!es*UmCDStRmP_M0W zQk+>{L($-$0!PcHh6mwv?|^^pHl{vOk-wC35d8PYmstV0s5SoXPm#ZeTJuzChLnS> zZXbFmNZd*MWL5gzsBd4WBE zby}#9JGHn4I0eYl7Gx)HD`LJkI0ZzzmjB@@m8m4#xb-LG)e@Vh(T+dz^!~ zvmC@<;vnHF2QzMPkaQbCN(yxBU0zCqQY9~CK#4v^>U=2K@)G{qP@QC6Tnt4IUcw6z zPhMIHB?B*IL&=+$)&DEaeJ0h9uv zgfH^2pWBJ`X<@W-q@B2q&}*aEG#_z1n_FyChnaoELu#q8gE$arbvjnlGCEe%VmgVj zNITw19E7k@XE8iE7!CQ`tH5~_ueqqeJ&xBrRNy(8*9-|9c&o@ZGkMJ?gM-dXIq+S_ zf!_`e{Eu=Fc%Fmc+Z=>E;2`uFkE(yT_6d3sVb8%B7Y?F5IEXQD5Zjr9xIP@j58)so zih~&wIY^2}z{Vx8!d`Xfr2;5jLmeW?(70$}e_e7JnR#HBHE#KTO@F{$oA}1-IjR+KPp+sPi*m0~czGs%`4C^qK z%-#OLU&~I!->C{6)K_DkwBfP({ciOYGf%()33Zy|{GZ}A5*PCUub`aO9q^q&FP*tU*8M1ud227GHBey+iJ_tIl5Jycv1i3IcD@6;D8Ha)efM~&^6eSj#RSVxAwz2>m z4^ZOvXjU&ABmi=sZlgri4OOD9wFFYiuLI>3pEUS7+2Dt;ro(pq#vv;UnlUUtTx?Cv z2bIg=BAf=e7h4Mchb)EoVr9`t5x(C5SN~*;_$7R)Iz`Eh6k8I!``;EN@|OXWA<<$p z{?fpw<3uNX(?H1>FSg|v<$bXMVpvIx*qOp*s_g`r0V*djuL)vD3in#PUNM4A$GR2$ zzyz_WHC;au>Ts3G`CTTmJ`;f-Zk2f5K7uX9x)uFTHigox9 zpid|ph!ECG031iW~&@cUHr!#l6*-^`C5;hilL zbv| zntu#_zC}-wfLbhmW^a1w=UY@333z2`;g7H82S3}q-37euWrD%PRy9BPIp*yy;N3s_elqx(@OCDjk?cD9`4&Az0&20? zE&KVUpKnoFB;aMQg+I5NAN-vEb{FtH0rtfd@N@0knSw{M{Zqtd6W*eyNI)$XyP9gd zFpl1$vPi&-VGDopMoYWgO##kD1YYDA7!SJ_JnuvZb%#%2w*vJ@fXwa#(UEQcL>z+m z@eWhrB`_0WKAS4`Ld-8yffwGFaF_c^%59_kGfaOVT~1i-^p_c4S}Z<`2s z@1e@9MDbggX_J*kpNjB47`(al?hH6TfO)#nXJRXSX-nxpQ;dNZ@RM2YY;hNIOimV4 zfP+;ei+hnFKSgwG;4x+>G;xo%ymkfr`fV1>ESdeZ_=!1Nz|8>lLrMSa8WqYtDu`|qSw=SCWCV#1?^AbQbtVo>Sfrv!y0cFck}voV6EVr?^GH5cZuHWo8HN=^5UD`kFpT* zH@#U3P}TRj-?LB^pz>F}f7vBkUiEgekiM{xl)rX~^>o-6X|LFyHzxdusOOCtb5vkZ#8k}8tzkKm8RFln_55K$beWL$AD)A*ks}jpXQ<+*l|AQ z_ufb74Ts3uv4GZegTM4MAOS)TUIyP34c*_WVUk6|AMoWID-GFQVTa4bzq={+^gv_A zfM;fE;ht&5t-QD?ZlrXjE8F;&IGEJHI*vZnfG3@g@(D%WyEc=f5 z`LLC|UuWe0yYH2a)lt*9q38@31T}rX49L|{`--C(1ccJg!-io>#{?kO|kN;u9`5yFraI6w|Pc&=&cq0SicpL+sJ>z{Ji+%s; zakcLo53laIK?6?-^i~aZEgE(YdqqPEXyD>}$pT%Y%V%Y=O*h33 z9%vZzU^D#sA?DpED@mnMrI^!_8Y0=ACQ@JO8_8^&O5-tBlbcGDYz%550Q&c)5>Eu7 znKZ=;{dqH~IW~KBGpRoDHA4-X?!H>(ocdXmPnS^Pl6|vNcLSnDFUEU)eky_db_dr zL!@Bp=f-{tkv_7?;Bkpx8OfRq1U)cq^cg5kYwyj6V7wm(uT0S`gE508J_o-PHV>4( zMB#)%QsRFIKkoA;VfVqR@Y=!uDSRmCO~S#U5}z=WLZxV-3->4>b|tn-ohe_0V#c;H zPk;OZpaG^NK2vr(2H*W05MR_g9=xso;?Z+7MGhGE_J}IL{7Nm zieGiw7B1z(Zx^|-$s-{3V%*s75mH?3Tpr?tLIB1+@Xm0p6!ytwc&ddQ92p@^Z6C^m zoDlQxSc_IIuF=AtL`WGZoHkPW^go2p_I??zm%^<^slxfA{!{pS_%20tFTWHXH5y_K z>AhgI6eV=w_<%TUR}tYe)2|cNSWmoD9cw-_wb+ZX##ITtZZZ~P{cq7Ii>Urp(V{&V zYm}Qk7Ge#%olRpQ)`4S{gJUK5(XSb9EMS~8kj{5wS>vP#uTmasdrcIsAkuB9{rg52 zlsS%Q@!kh{d*Uu4uhMjBlllr>xDNrb-q-+j_%?!H{DJL>dFdrg zDbJ$bT0VS7Y{Ha^E9xBw7Vl1hl=`>mukb_TDBAT^(MNC+t;!9GSBLMMcy;(Li9fd-#$T_;$6X`8Lx$}u2n}f%BqDgrPd@! z3sI_bqV(yTq}qAEjLS=@(}}87%=9-)y?|eCtnRs&Qo^U|0PXgv6eM)v_<*=j9!)+# z+rc-9F(kj8s*WZfpln_BWC(t4nhDYTx9IWys_67rMZ1A0Ookxm__;bj13u>iltp|l z?d;ee-a2~Y0j&o9L{*Ux4X#qt2_UZrRo91&=uluuwju&&#$!_@ zkGk7HWH+WE&ohh@Ts1&feU&PO;lc9tRH?5w|29v6)-1svtu*$QiiEdGg{Q&74pQHx zNxlgGNc#^HwbNA-6Vk0rWWXibf0`&sS4}jZCv`;=k@H|52QbqDf0-xwP&m>4dmflB z!Pa3S2cQ{NwDw@$dbmWlASD=yew(5 zis@&;v|S|Sp|vZEqy(C^j75AUeM$>fv6Ej({ix;}<{?XcXznr=BTEyhW(7McOB0aZ zX)$!Hb}XB)Sb}TFv25*P={9Js#z&O?aeMM38?8*nwj; z9*5|4FXK?W6yxBzp3Pnc!Pk7xPArpJV7+n~#6h#BIu3vtwp^Oqlw-PJYdqHjtR^tjF3dsl;1Y*7PkaN=qvpv zg@Nxe@Tc)k!?0g=6Gp6dppGREv&dRwWt}~_IYNT(p3UR^DxK)S? zc&UN^waV3pOB9c+a<#i;69R}%m$)#*e0jm*xh_tbJyyG3q2a#Ou2%IK?x10_7hEf8 zSn|R-JpS^6^!Ut+=kU1mMb{&lj4d+rJ9%Dcey433pr(2hG{$*B@aZN$3R{$Ln+ERN zlC*eKe0dDkLYAySY+;txnm%o%MYaF32C>2LnYDX2)!f@wWlop10FP+2V>n}-< zx4e7~kB`6XdSn2zjQsqqEbZtyw$f5l{RK2eX$8O4nrbIBhJV2y#fQ!WZ~9L%{GR~}|NK2LG9Ibuf7dLVe`>1J zO@HMvg70JUrvH(K|G$7mekVnKvyA+5ZTV4Coeqsr9>Mo9c{9IhMt*+*Gryz+KARe! zYvec6mLE0M>ChPYCE%g-dOTd2k8LQ|W9$Ko)7pG2(TzO&q&%%%VfO%w?AI{r6CTso zzvjBg5h&HSlTZFcZ(QuUo9hi8E_U6-^#(r_yCyi4O8wf`T`e35mHM>T@lp6KZ|aL) zcU|HLy%}8dy6cx1t^|GZO)iZ{n1K)I|O?gQX46z2$1#W((e@#JvT6 zvB|`aZyAYv5d+_3E%@csbxF@5kgwlzHNY|$pZ@(u1Ohyy)b#-Ir=A}KF}B*1>eEs zjaP$W4l(_+2js|p$ex~>>Ia|^=}(`xn&5@ja{Y?;U7apD0aN=#?XpeOcfIdg#TQFk zZ+3O4&rnR%w`|58FAR@tc6F)GP)z+-Zjm1MZ8?X>)>~bRG8tRs*_&mf?HXgNAZn@~ zfX1jG!Ou1M(+i9jQIBjzY)KR9FYT3Ohz*AO$`D&UhN85s%TZbwmXx2vM<0jrF|cuv@p#3@EjgXKa?JCsW^wnXDU!yW*Pa!DDCJGw$f5ly&+m!!M|Yg zrJ4v)7~x)vod z%gE10Y4u^Y(o$3Xg;~1tm=zQBCZD>xaGM+Nr!H)1=uE|Y`2u#Q;C%U(_ris#7h)6U z0a#NlG|x-T(tD~Fdy@)MlNJw1=#LF>mVJs@7+dFPpJ940a_Un)bB*JcIa@z-O}HdE zjy{v+9K6_@T#%Z~-^@Gr$KE?BpW|GQm#rs!j;j&usB`LbSJRdvtNdHA4_d)5$mvui zW@j_2VDb)^ODwLuYNu-%UuXYdr|S*kdv{@i2Hv;JmFvJ}JEA;_T3>krE^5wH9&E$& zOclz54SX)%jq+5w^gDK=JlMGBi`^)XuR%TK!45zpzLe#e^(D%KeSJiEL{?`kPx!o` zcMr>hH{eBifWQ0-=Gi+XH9TEYr^I!c2m(& zDn#>$dPehLJD_#@Q5@_d)H&>$>QLhK~OEu(+& zYnM*`9|v6Hxvfyq0avq@B8U7hPu6OcWOjfAE%@01S6K|-mVfdPS_QbvHz)=0zHd+p z;A_4`DQX(ZQurFxQ;KlI`byzFUqAURN`YOB=6#1!BsbE({tl(U{zbzgC`IUeSqf}= zv@;@0aV&yTfET5}u12C1B8M}U!h3$O-S;fT38NIicOOP6fV=&OQUEXe(e=H5^(2h0 zhm+-rv_Z0MbWu}17aDP%Fi)J7v>$KS@9J)|r=~i+uDx#}>|eWIo@m$D?Ww8OkN@Oa zE`#uQmq8rwW^*cnm<-M7K@2zS%kB0eh(2}g4>5>m?~_63c6(~7{SQD@D}w}4%GEN# zRC@wys?(vVWiM*+-EOh~SJ>@E0bYQnmOaCaJZ#uExW=A9lwfY%1naVqV1Gacw5zMF zhSp{4TWVZgFO0_)i}tE1|j=3ol0}Ez}z)Hu^Vch*ph_6ha=6b9j z3hA4c8SuTz2O?6HXu2Lt3%cgsPjo#_x`tQb+?i~-NCL$dGZBywid05PJ6Wk{Rqpi4 zRDL!sNWOoFWJ1bhRYtO3hMN^kt8%ADCIi(H6z`0YN(h;XTUar~cVw#4LkJmh(iDA# z<%|Rtn~fQPGRDtj+`Wp)9Lw>D%!)@#K^p0ShzHSKArr(kbNe- zYE=u+k)F#<_rjRoxgS=+s2!0`!ut-yBhwbro1YEsTmq6$i6c!s=qxM1p;SUo2i!!9 z4!*mVb+Mx~8+v$QqQ&Xq)7o?z@!T)B`M5CaU%B^vd5&1Jts2VkliO`36za8WVcJ%7|K!%*^N?`Nm*Az zmM&!h$}Xbpu@h={K6$(}Ms4HRxIrHhqh9I}zwV@mmx>P$M)tIX-5^X_gW^Pm7H-fV zg%xju{~e=Zqx?7Z@5tju5qxv~QiqzrtrxF$sGS6V-Z{S22*v#%) zr#jZ#nd^lX=OrfNZKU3f^6~Q!d*0!<(WBB5TM|cRo;V?Ph;E4yz4-i40zNvpy-|KC zEZ+_#=-)floXhDYGNH8tr_x6GcqdJKS{w$ZugHcYC%Cvs*iCPPw;eE_U8yfQPrb8! zeLKhY@Zc>go|8L2uXk*qb~(e2&B2Kc)VvtC3@LB!zd{MYuU*&*(y^{Q_>HFi7~`*6 zj}i8beD0gPINepA;=-kkQV_Gz0}VfrhtqZ_?#lP){)+bsDBI|Hb*S=o75-s~RBe4c zRprhm_|K!<*}|k!6XJx*WeS|}g2H(h6SO6yQFsliYD)rk2M*#&W9?9V#wBqr{8Ls5 z`K?%sgSAk&km1a?mcu&HgV7!N`oC1TO2hB~nK+HyK2gjJ(%4Weq;ZL1oP$;=cV^?- zMa;$KDZ~dsAs)h%JEwsXCGk6R46@9bORC(NXX>2uENZ?*1q`apnNOc}0VZE=ejG*UW?D;`Ra5BCBr*u6?Y+DMK} zSK0)Dqbgt2lN+hcyZc@os%*o}KWY$^s6l6rL7@Ukl{sfgH2cM&dgX=cWxCc_ZRIa> z7E1AQi5`*YQHfSa^q54COQcJ*iU?f}fynq7(ptQCkIN8H3@K75E<&-whuuen9GB>2 z#g0BMyN}Bw%CSY1qlF)7szfoi(K(KCXN5tPIV(w(IX{)?Goo_m4ntk;tg@)R78SOr zLlzaWsKW+T=By!A=Jfv}@qZ-xRiYyj9hK;qM8_qH#o$2{iB=`BJbOhYbOsfIRb*%r zUWpr(Aj*qx$FdRz9J6}YM$tcU;lqk50fT1eR*&UQGF+$=X&SZOCak6L7HK?B7?a^D zlt|>La9!?Pz1nP^B2avqT<%;8N>=VVgDTxYFU}i^Elr6kav`H%t?~fehEoMIMV9KVdUoA&s{QV>06B zs%bDjk5hZ*^Ln=?YIA?4G#dl6$kozQspnEz%v9I4nLwe4_QMj42nC+VonAnJMv+J!cZnv z?mS|tPFU1Qi&Bifu$u zgiQS(7pYCpFLNeyUYkAM(|D!Kscjm*P^b`PfLYyxa zG7}uQZ8RvH*ho!T^$5_Ef~G4_k|`IfZ7>h5wv5+W)H;hQHmEXZ38^yY28rI1C@9fJ ziAp7UTcUR)`iuy-@K%W#cbX`%cNK0f8Fr*iQ`=cV6f7>0d+bK0{A_iQkl7#6K{m+_ z$L)E`on*KwGIC|qxYA}^A&ut?V=`Rw7m25_pS>v`lZ#P>p!kbmxpSeIenb@-RB426 zoQ0NRg+)DKQ7bK~$f8zT)LM&LXHcmBVoO+JQ5!94lSPFrYKui}v#1J-s$Nu5t7Y1J;hIbyAM5pu8W-D)*Gc1mFea1X zr?nH-xc`-9Em~(G=dJX4^^7JEO?7Xud9|N1iHFu@r zGX3Trznv=Ob!BqQw)pV=^^dkWi7$ax$xp7$wpQ^pAhGUiX& z@npz2LLp-?lpUmu?FAVl!{dp_Cyb)P0(gvDP*w1sANCY%F4$S> zp)ALgl?xfKjwAS4TH3uSWW4^5U~P|-Ju756sJ{q)mXNZ=LdG*dq@^LN&cp4l5c3?> zG=gt-2;1s$raWm?@RC+)vzRpRg|(i9^P4E>$)V2Tk#uhqHBvnVkED}9@ey;6knMRo z9^a3?;oZVx`rOud2(aRqzOuF2UZqEzU6MEG+ghs+cItt+>2 zk#D<-RYVZMxY;&+ZX0#Z8E&Wb-`c3dn|DTvQUz6kZV}-(SJCbpl~;A2M@`k}t|0bm zJQUYo^{6e}89(Bl>ye73(pE~2-R`Y9ZxFxw3$Phc-w3M7ja*6Y|=?&Vc z(G9n<+BLX8=6e0tcIqwMko@}g5{o^VcC=UfQ`k6B3g;MDD32tnqo^F(K|S++TYoF2 zT^$fpRdk>J`?!Dl=8ni0xP2#yMZT*$At(qB8p71hHszMi2nxzeE>%bLX8`r>w{>sb z{kEh)J{tCRzBjtx*0xJk?zi=Lmj;jEJBzEjAUEu79($R@BBcDw5E6u&4PpBvn{ss$ zLW1)5r2kn+Yr7&O{Osr97GT(geL*+m2Yk@LBB<={2nxbg-K8=%Sz;M+GJ;AQ8Qhbs zc8zuPs|sqp)gBJV+A6*OL$7)b@jYI3sd{UbscxL2 z_Jue&EJe+XQAe5b;PV62D`M1+Ca)hzRrlN257N{dZERAyI@ZQ6Pgig4aDkZ?!*%OD z_?^wR$#>MRXP|n6YMJW(fpFB7odUPG+k%G%s*~+eT$iCvwdM1EhI*Tgy?n5mV`E<# ztj@5p?S`n6ZEWEXb-Imp46UWj9jX>YZfFV|NZy zC)wBm*P;kf<2SBV7umu{AFf_+W1kzYX4}|?S?awVthz(J_MU@!<%WgEw?!=-zFMM= ziKYx*I701!745r%SB_NQiB&%{+eZImG{X7OWP`VlQLnJ8U%k1Oy46?}i=)wtKDtGn z!EV!ky!!80N0Yt5KPIY;u)X$Pz2Ri_8Q|dh$!eQeN5vlflWFMVd3%B#r>mY=b>kk< zw*B_#!*kFv2kg~f%|XWm{xL^grVg;SkTGl+C^qeLBik-KkEqv4iKS zk4NLsBlBu?#PN64>ZVn9)#`a^ch~BdZ{MxXwYlp1&szO*?LXBOwtUm)qhCg&dTu`Y zWt44rkLvGWv8dKw1JN&S-@LVS`WyGCqoXN<7v8Imk98#O3C_7sJs7LLY&Nq#{sDxu z)ntR8JfI$T*wmjatfl@(fx6BiI?-bEOLV4jOVmOKc2xR#iQ2OHJlr|G+v(%l>q)Tk zsohd_1dZk{RR?tzpB>?Pl0sbkaJ5W*sSYhwhci{5WtcgEXD&NS7SAt}SsYzv%i_ec zb7YbIu*_n^!|LVC;>U+otQ#4vw8Ll5(mF}RINyG6pswPvRWOEU2#Y1CtpzWxJU%MoHW<9cU%p1{YCt+1kHvQ z)rr(xv_@@De9aon8c2HQ8r8w1!GEr;*T>YCrH=<*mOiRqmOdK3B7EqBfSVVicCW0= zu6%zsmr!86^k=WADUBU9BZE!fRk5*L%}6~bgz&M3BN~2# z_f+f+K2mS*KpE(#NSS(#Q0z(#Nu`!iQcC z+`PsX{{3T&@R3o|GK6ne4uG;8+oA-oD^pV(Jvmy=xWqAx#bns1XjGk*CKydyx2YM9 z&SUgO+tsxC(|hVo|G;*c{*&!$CjGSf0Nnz3n1S#4K<(I*{rrq^`Gnuhx^ZC~eDMMN zrj60te2BQ}O<(kXEZ3RRKlY(azyCwT1wUOY5Et+`123&m`|vwNTPoCcmrO$d(WwUa z8RiSjsGyjS)K_S@{v)+jeTF;Uh2gg!sVixi|M59IzW1^8IOCIZczp2_^^r`*7I~H{ z^{{qf(6zW`W#0J9|Um~`83`J?ze~HqBY3OyrBF zcJSAT4Te8`jo9ij6s7HU0HuZDmILSTs2-Fa*B?BG$DapzC;&Kty)FSxB zFY5UYUJ@SqRUN=f#m-063i8K}sLvAXNBQp3NPXW?wWyz{h7?)lDX4N(R|#>0xPY58dEFCU1URy{a|yDoDXM#gfgd%}Z_e!I{U^ zzAnd##`;UA)M1Xbjr9|!)OVY;Ko2QMe`0BBJUn@2cS#!k*hkuvymp)(qunAlR@v^* zW=~ild&1h&dy9@sC)rz0NSpX3_TDlNYO}X6Lwi=y-hyjN^cJjgAE{TxY6T6sggLSk zA7+I)_R*Lbr_CQaZIy6#mp=mqF|D$|wZV?wP4usuYHz6{MN_3s8?6^L)5Pp?X>;}m4Ag=aTJAL-HgalOZ-Hvf9@X>l zR$O}g((4n&V6+^uv0Vk9VpfS8uiw~JyIjBhB2D8Ey6YnCUO5|h8!+-TWa7M7%fGz- zOm6%qoAk6Cr1P)4Vcz-qV(I+%i?uWk@03flrQ(*ZvZeN!*!1$}Hd=H2oz_}M#&EE; zmd{~5y^X|BiecZ&quty`lpzI`!M1bR$MvBwYt^w>Qe39M)MJx7|NK`(h5iGFLsfG zc)(@aWHE?eO44Sl8M4ukD6y;NY05;xJlZtqyl5IPJMU9nwFl)mZ1(G)3=Q3}dpB+V z<(3zwuGRFNW=31Z<{Y&Hzi1UPzFT$I269YI?yljJ+QZ7?`j@%~tTm4bg{3iOJ{k6x` z)uOh&8%OIauhH;Tw~@hq|Io&Y5%r{3n|Vd9XdG`okv!K%!Xu5Lv|Y2!dSgsvH+>^sfhL_^i@M z{lp+`N*_^_6jTP=4p~IcludSu&_pO0Q5&k*c3xSWM>8;@>Q7qoMXjWxkW{9t$*41; z#@j4|R}R)1x*Sh5(Fc#vG9Bxh==uolakWA=S9r93`E}ac=ybvVT&LmVLl^~PN20l& zkj=Hu)?5t-*J>`yL$tZjh0$D>$B+CFwL1!9H4dFQZIn6CZig5VBa5n0+Jf$9$l~5X z(T216hao5#o18GFNRhQYz(wAZm;*=YUbc&$5eSD)6OIL9aX zr+u74M(bbsH1SaM{0S2GpP+T+W5k>ZumgU20@4BRHTd%>-LPVFaVzX`aLE*{74|sLubQH@Nq9imwcsR;pO6=A)2B~?H*9c#-yECh zuTH_R#)G0?r)bv_r%sjlQ3D?|aIa}nzF?X*g?2wo(*`!@)&?8->Ub%;#*~5qiRA-a z`P=l2=~@!=zhgS`FJ%4$Wc~wMKDkYQVY=4+JnM(uf81Qp@+TgdY=y@D2xWuGoBpt0zVHVu{E4?{ z#~c2372Et#Q=M+6FOLy?ACouzwJ`hv3xDDTto_ACe0G1-RBwgGh)?hvOy2Z|{pUq| zz`~z+ad*7oZ`W(K_^7E)H`ABL2)>WWoBps*yzmE1e@WteJUf7skYn#1Vto$^*>{@S&ikj+l(@U-Ou-y&&HFkTkkh7^} zj}36J_YL;PFPf~!=VH(U_s`YZIZjT}C**2F6N~VY5TDz3UXPh4_9Sv!u%!t;7I91U zKu8M8DAOx*wJwf|$@)op0PZ>q9y(|1BWA%vh2f#^tMt$rOGZr(H$XxUunf(D2kd2b zcosYWx0;Qf4Lo+Xd&#{Fn9<3Xh?POrvbR zkoip6NFghx10Vj2)2o-Vlfo{H|3a1|{0TdcY1aa>=ZaQbm&KO_T?*dGDlK{)o-op| z^ae|QJnZV9Uv+|3_|oy=_|hVJFpO#Ef*p<4+l@T0>-XHHwe@ca!Zmh~Wh*gieqwbN-hIi?<9# zxl=(oc$7QiEXrk30ocj%(xE8tcq2;=zKFw?B?aZq6-L@J=M$vLoc~8u?su*<6zGl? zwc4WAT9gNr%#sd8mOtXVyt8%f${eAG?JpQ zITn>`QF#_M&!8f4&*9wBDgai@mG7`$O(|%V4}r{Oq-|7%QSqEd(LSJLJ`sb$+vA5V zVU0x{v8WRU6?vrS&r=(jPeCh%`S!yISZo&>NQJ$#}gs+TQ- zC8iLQ!Ww&?xMCKMJGp%`R;6zd!;AmLr>I{+sQl%0!RljNvo2>m{ukP%hITTveyHV~ z#Q#D)(@+nRi8y!5;Wk z1OI5?u8XDo_QlffX#;<>7|#UO{>5hkFV%V`upZ9@mcU!BX9CzP;MXO%?*>j?D)FNR zK4{=x%cOk4GTe{D?uTXdJrh`4=b1oBt!D!N#xsG3&-6?H+X3_{L>|Bk4E(u)+b@^$ zIR@Um95KM|vPWWWoA(Yo z41d7FA2$z(>|ZSXjkfy}TXt@R#_%Wj4JL2;J2_Q<`vp9+n5usXlp>-tyzN?Ki%xFP zX{N^4`(Rn!$K*|K*hceKKC=K8cQ#^$&HhD3basDY1J13`7|{uSgUOqBHi_6oA<`Y! z*&JBS?dcPz1@l*EH{tQ`h+z0JZEcKW;|_h1t{npo-v5Mlh#Gy`leoDAe(XtY=6ReR z3U=$Wp3-{gS3jlklO+1gr?gSE6u%pa?klyyNn%3z%CbhoVJhwid@pr-ohT~;Lv{u`4w8!g}P2Q2(?=ZeU~ zuwq0F?Ea{!o@=Hrj}iQ2lQ;dXH2eVzf82W`(#Y`l&^%jw)KnjxXT>M@Z%p3wS7P`B zroSX^q7iu*Rw6#TKWeJyn(519kYe?V_&Fl&`QW!NYC~h2d$9z_wrFQDZX+LZdY=zw zysTXp>%i)rm9J{^ya~sLD!aGuss3vBo!VE<7U1?*-%+;vr`_B4SASJ?N6W9AwD@YA zg7g{X_?o?<{P5D!l8!uo(_SCB9y0*EZCbDWv%kmYZBN(ay526@)0Gx`?y2o9ucJa^ zJ?}N?YVT{>yv}hpSG%1qo2%y}^Ho)&LC(12`ut+8gFo#|g^daW{gYv!gOkl> z?tq0$63QZ9V`E|5Rkkqsn7Oztz*YrULg!35c1on+5-8C#jepObtexLAvUa0V+?uxF zjeB6Y_^9zo-edHSbjG7me;io{K&)uujBWdP9F!| zZ)j?4o8l3v%G`{y^c|ib9$h?aM`Z28C-95Fj>XDiZ;Sqz3wmwP8pd77CnCI4uL%qh z&lIZK>(`fR_g={Pgz~~?q z#2xyIe`zxs=Nj^rZ7?^rOe~MZXN8;oTYF4XZjlMrw$V%e4F`n=U(!a8dsoYA95VQj znNS%UT>P$fgX6*`{0te2kh?~DsA!}A`kr=$ri{!GMe=&|-tWVsf{!?|h!q|^|9x$z zmW!`ElFw+XXK#kSW{c!=+Ug~nwS0R71GZ@0FFeF$vdG6%A?*s=>I)!uC|SXhE!ubo zXXd8m+BIT|9<@!wS8yU_dgBkZFf~U%)CQdgLGYT-v}SP*?*{#bom!H1_!8kX?$9Or zlAT(M1{t_!iY&N8-&3V^R$E%Sz0jS!@_IvA5mm`Ox-5x+8YV`MwR`-P==`dJV$y>iz=5;xrNFFhB7;< z+)L#)DtqO~N{{N2zJ{)Xx`VgLN{{O1Q&&mdqqpfp*{Pzs3hH)HmwKE2RBc_$1JG4b z_v@`P(r`3k4wZYUTxBQ^N0pnPypR_HJl%LdJdS6wEwNf!{}w&dKL4~hs3kQ>qmzTv z^&bvs?X~#m1T>FIIXO+&U-?!`v`tP`)MYYZdy&wt>w5^gEb2B-lTK|j*ArBZq;is> zw9Q;6s2oFO>@?l|J#viB6l1=DZY*`Hrs}uV)@`ItOkAl`^~FEbO4s6B=(3sa;1n5+ zZQ`0orI@%D7)sm3RYj$kxY`>^+r-uPJ1BGMcJpMT=Atvj6IA9=ImuAkCax1y&Z9Ec zP}(N0F%c-|Q@JWzy0uMQ8>ti%S8BE_W;Dwd)zEQk%E-Y<`eoms3ZlAs)QL%L!6bcg zZCw?0+@>(nev;04W(_uYwTEHB5#x!nug2`%tYB%-f5b?S#!xbAPUEm+gc-OY8T z%je`a?wFVXr(bW&->PHra2K}+^45a)Ns$qF1YNG2ewiJd<8k9|9v7>hv~^!}ri<9$ z+PWt@GLPvK+PO;-GPw&yTB7I5$~zjzHqBb4cWCeSHa4XTB0eZu3dOwk?rR;&JNmZv z?jDVEHx1y8OoUI@u9$$^4%cgXe4@K`VwO~dsW^{{I6N8V3F5yM$FRBL+!R_~o9J$L zrVSMCPjpYL7No7*xM_gcM}4V)!(bYE1f&<(8o zk@s&Oh(cdV%V8be8E49NO-FZUNAfZK(~j|Q7?CevnY%=O3*Qk?{=CV^x zP`JpbArdhGfB%RnAOQyopD3^jNq|osLPRCWktU>1l3(w{JS65w5C zfk=RFVe%xvSDE>d0KeAcNr2z@+|V(yhCor^G7U(8KVkADz(-7;1o&+xPXhcCCjZ29 z`bRz8ZT)H7IOoc3$5=XL2!GDWf`nA$sn}>|90r>jskMwfCclBDAa-YMwzkyQXaDLiA2|Mx~5am0aKQ>UFb0$6M zQua8Vzc*0+>+A{o-SY+%xRlim5@AysT-MwDL5w4msNZzC`v9gF{hBK<&jT;J!hId5 zn*&$4?{JW~=_>d4&e$f+Gxgl--7SLSz3v+?p#1F-ZjA;yi1xwi>)oAV9e5se;b`~3 z7>c|3+yja4@VW8gQgi*l7U2Yy8G|_ub5|ZaLrb$$0+bljZ0*LB=^{ zf{gFw2~z*9fz5JGoG9&{pD6YF41BI~w$64BVH~#__!6-{K%bBzR$pheejNX?qdzv;b%PLZYVnZ zy$hx1j}6?qKt}RlfsFX$0;zAkNa7ibM9G71EOMVG9K5~QJ%BYGyl<`BAEOtpb{}`Cx0Dl5vPYhKW0Nj8^fX0C4fJ*>v0PO+P zbpn{j5~N!JSP6I$upaOh;NO5Uz{h}{fPH{(0o45jFb=(7t$S%Oew91T>1a7Dc->l5 z|64D+r^f2zUULt^n{fD^oV!P&k~(3=jG1|!nYoi^c;-x=J$*usCwJ!TJZ12V+_`z4 z$+KtAoUJDmyW8sBi``vd}oIT&SFz((=|2x{EFw-zKMgBz@)Ro3lj%* zuh*!?=Ae(^sPV+$_Z!^b#&w#Mm!>2GewmY|R02w7rzyYQo~DEV_W^u>w45}3Xc^9$ zzAsXhFLtCV$$$jF@`@-_ex9ln0_?J^Iy`mBkkx#as%!?>ZA-w@Z>X}i+-Bofyim6L zBvok)DEt^f089hQP1?k{AEhc@fXUl&LLK>I3=RS0^-NQWd#5Q`fDV8f@QLkE6N%@i zDN16R@f-9`pu4&HOaQ3&^_1X!*)N(PF1i;W25- zr+|}xq*{>gNK@L!)|S0rho?Q3s3=XG$OvFh?>i3xz-JAxU2dcON|u_Yq-v;mcbd{O z9zg(11IkU>#6@VVN?VYooY>c}w!IgHV*q1Ep_NCcDgV6z{sFtdFG){R3I`#xO9!PX zF@OdGgFWBHMbqfjcMMblfDwRXfM@PNC2!V1B@56Npa5!S4pcgH>ykMIv)V(w1}a{_ z+&-`YD7^P_29$O-|I>gYy-r(fT8N}PEx|(q$}3}QUReu>53O%I;PyDO@S*fCo@`k3OW#-OgXB4pi`?n}Ul2 zrFZ;5B?-I}N5RtedHM(~?ZTUQC5etj3zmYe>8{Yt3uK;_LQ1C>cl z2P#JaE1E@(DYqF5dSY|5vn@!wzHN)z_FmXAfIEi|R9XYtj~J-L0gi+2G${C4eJPQ zHh^}N5t~jaH-n`uf%>{&mz(r$seYN50uxMUX6B~cXE^PY?p3@t7y+6xg2w>6{;aeg z3F;cu&7iK{&i6rjf+;&w+GLyFZs&n~qAB>R*eogS>DUfu%G{f-@B0t~@Qa~dB~%B( z;3@yufV%p>!=K5&Ej zWgH;l^D4IkPK@^|cLCx6`LJCAA12%n+6I0*qwJjM6<`_+13wc9^qVo%Zh}L=MPnqs zYcw(exByFT@G8v#&yDgb%K!@Cw@j~c^hN}Sw1<#}FdaPMSJ3-MdX05-Z1d>G(Co`J<)zw+i{v_GH{khSFWKq?Jc00}&umFzqvH&2-`HxCQ!mEzsr zzXYKwc20(;R+hRmLh_IBQ) z{mdAN{t7TrT|3K>O*aym)wLt9?LR#TzuiH7^gKAPPgkG(<9*RIkAc4HE7TT%_6>kP zMnIr3`PiI~H4dp2oiklgV!rh%8@}->&48~uVHk##J@ZQmirP2Z4|N;#GD4&f!pb6E;f>yUD<5 zXHDZf-Qg))0A^;}&LA^&XTz~I!8>-km&N#B`3?_!Fk_h*q&Ozve~a&jDh+M86L=N; zL_iPF_;QnlQ^CiBp99DO?FJqTJP_E_VSp&B47+0B9*T0casb5nP;lC;F_g*=LaFow zrVb-R@fvg%a8K|HehB`%%KdzdKl|`dWh%e{A>mfgw*z7fekN%BP*gwvz))qjp{GqA zXp?99JHg)#;95%R7u4Y&1YZEqpo6_%SqO(KATR^aK|cvF16T?AS%atSInb*Cru`bw zF9TS$)R%w`0$822*#f#8KpkN_=n6ms!TS|u2bf&|)8Wi-hALlzr!i%FLGQQmUxPjb zFzvqs{k=_p81&CJ{eM6owefxw__MG~FTTWi0?OY3W`>Jl@E^l~nfw8r@}ul%>})5Q>w?+Q8@U?%7Z+N?tA`+)BY zAWfUAL0<#FY8EjX(m)R~^t2fQ+Vn^JVc@d>p#8$ZbznvTIFtxCf*uQCV#0XP6K(ut z(9-~BfVYCa-KNh4J;$b>3wj=azUgm1Xg|P#{DqVI!I%l?bT<0H1HwQiScWE92%b7R zSp<5iO1Dl;*w=Ss*pb_W8x z^q5!Nmkb^bk};c@Nk&3OcP6HOB9quKNaZ%jIMWKur}e3A?tzFQo0w(`Amd~Wthdc+ z-gtSk=6?h-x-~Ip7#%Wul|iID3mJ80c=Y`eWEa{nt8zQql%bm#q_W9KYhudEr0iCc zpiHTRkaMPqDcb`X12i$q9)`@0X;*E?OibB-AY;76vfQJEF07uC;Nm2ZO-Az*b%J8Ns%Hx1n zo24kf1FOyd-vEOS0vuMA~xY9<~brOQE`2PX;|BlmK1n@rw|KD<0!{+&)g8%P1 zT#n4y&e;I7y@`DWPx^0x|L-RFAKUx?R zMg@JUz2uJoR|EC|J~w3V1HTTqKN0Oe3&uXcaKM2MDax-MF(U#zfUV#Iz@a{{xjaQF z1dy%)6oIxw0(ixypEx8%$paJt-T-6)JOIka3{6ok2PB`5e+hsQLJ+*=XLmctb)mRS zr2$T$Wx%n(6~G=$@Sg$mBvA$29P)j@yuvsHJR1D>z`RVU0p^M07%;@j$++NWzqp@_ z@h4A1ai*UgCPQBr&Xwjb>iY`Ef6-V88NrU3p2CxTTRrWFyTpIRn<>h|HzarrdV_(p zY`U$WT?YRP?5m740Rx*p{wBsv4jg0|PMR6`+t*W+w*U_UsNe8fG{_|UhK-*EdXA01 z1N2=s{vOcw^nUR6^!J0er+)yvJw3A3m#%g9zlo0Q2OZguf;#+?Iy`N+LiRCWH{ff) zVZe!F`r{|v5Bfd$ggRd)_W}6od=`N3h;uOn-`vgx@J;M_04_Q30&{sm8gMaS41h13 zX9M_p{YU^`Bj@sdfLa@s+ zj0DqcX-zx3jQ)58Y<3~|A{a8>9w>_G(4{|j%H8-!(P>Vv6Wz#nRfP) zn09uVSqm=xzL@yh9nWknd+cUwx%3_|_uF$c+s7_rTkx<~)0wKyjMkpkjMgs8&&1V4 zhfIao(;?HZYyshgKrw^?V9G+kE%6#XX{BS7_JZDlrMr{|Y;?#*E1fcxDlDK9zCj-{ z=m6ztAK@Q#*yA@c=!^^#jRZD2V536@UBiGb1>oTIQX!Tc5${D%j(A)zLGQKcx$3U2 zK49wEFS!z`u0hB&fSxP!>gts)(Ezw|$1$n*%NttgBa&q5*Irm8HkEs%Qe6o~sG# z>H|WL`lo`6t?C+tY!0~Mu&!R|8Vz9E8Pa=gdakCfn?682+nb=wY` z{PUn<#~B=iY!0|0wypyuIU2x`Go<(0^hsw(A4tadHv?#bNuq8BA)ABDIu7zPk+z4N z$-D+0Yv6gn?1V+YrvF1m4XiT)r9R|8he7xpdZlOm8E}^KK+g$C%!Hshmyq^>=1k}( zQv@b#Op9UAoG?V9`+S@x*;YblSq>X7h44TbHxu;L2 z!loeY>x1@ZwTc8#WT0wDhe7k)DiU0ds13OfG|y$i9yCu%!X7kFGQ$1}%=bpdeGQsb zodvpXQ}pHh&o-w)&KV7)o{ksV9Iv)H4xJ(031c+Tucz z%tRxNM9kz&y*cL``ux-Ne#Jfm=Kt&Noar^{IqFXRkzB(Rxj0JJ$uLZCTH*ksBz(f&ahn~o!e{ewRI zUKp6eC;-|VMj_DijGCzeoo~=Jpn1i^#IAp2ii;Q09?-0fe9&Id!~tOHLcqL8AzcNU z*Bhj3{(;ZT6808+{10 z*}Nw$xgSGlKr}&b&}Nlpg63I`8RvlJ35xU*&^+0YUI&`z4bl~$&5RG*==jvAJjq69 zg7*21YMBNm$Ds2;o7G(e+Gof^piP^w&E_QNm8c0ZAEe1XV;`cc5iEJ?`_|Em>p#1J zuZ{r|=AwkAgQ9cj!{^X@(rX1Mum8*pSdBgym?bU(ZIu`_YlWro46Nlu1ZNh4K9Zo% zZ6}+hFX%#p&IDa-&_2+W?a=;AkPD{9Py|4m?O14|i)?h*MtcTD?R_@72sHarKK!o( z&A>MT^RSwS*FSwd(dyk+*TAM{pjFVD!9@(3j+Kl$j*-qh$x!dDM=#o+jsq|-9fxeR zGB`RSJfIJu325&#XqK)BG-V;mE|Ih{Buaa2bikmQE;J;wfvBF!A;BpZ#DCer&u@Xb z8e{MS_<1&dg^izJO9r$A#EnKh!iL|4+60~-#^Q&$`28(@eCrT!C4iswN&@g3MEsNz zKi0%=81aKQ{D{w30KcBYFRJh(G5qulzR2QN_)!jie1so2;TJyUVYlKC=pBFv;3S|3 zvLyiSY0TY>xz{gu`CT^_56qilmI3$xd4Pq0zJNr)4(LOG2w)5Nm4IS^(hQRb;BZs) z#wrLB#vvmZaf?@O?#g{nx#Q_VKxY{C1FQsH49EhV4cG#@3NR1!5i=CU?(vDRVK^FcDyGKZNz#nKyf}+UI3Jx z1C&BQ7C_lGKnVbNbUs7+WXKXq2PidXNbfIV!YU{MJo>@d3u6zUZf3sSknI_uR34DF z8L+K^T_vFK-~h#!nW_{4R}M>60stR?$4Cb7HqsEjk#-5du=Ce4^uaJ0Mjn8#wqY&1 z9NN8yphJMy1}UM}2PuKK1}ViGL9ZXAgf|URJa1qP+P?t*m!TBBGe{{cflcWk5zsuO z4{brMZSfDl$}K2AgW)dV-GEO9DMepl6%%BheMqn>L&@DcNXh*IHeX5y`E>9hN)0G} z0#6&C%uuqnp+tbfa+LC!45bp-^8xh0;q9QID+1X%E0qKFW06a43$3GWN0O5`>=z!saXg!@$l`y~q8IK$ohG3HgP#_P% zP5}f!dpiTeuJT)Hy9BnmcOZEB>;j*c!Y6Dzm%%5%0~wEXuq%R{KN;{KjrIW*u2Ov)X3GCnjNv&C%?f#8Px$L01bKoXUjlgz70H<4JH?m1xSvA5WwRw68Vs*7>SfQNC2qG zh5c+)E9eCBpbKZAwg5chaW2lCk2FYE=z>f|wVwyypeq4IfB?YP05X7h8kB@YAtXuw z)Z781JCP_4jzMRER>*@6%tfF89+^l}c@NS6LT&^ekAO7TfL1_P0v7`cDFg7xK^o7! zs5PYV{S)@{Qx$)B9+Y50fLuTppz<#803J(_DA|uhNLbSlkvBqno)71slR+zhFz66v z03Pd*CV(`RNaG2>AE4+S*r2upppyX!fWmt@|KBSURj@?H8Bch@KR$If59)Y=A+CFZ z;U$pg(!ojsfX89*S=|RK$$+yr9V0T^t|grGLIS{FZ3aG9QLY%QgfAa#Rq45El#gG+ zR}EG|0FNKlaF*(^YA1)mJ&C~nZ?ICh235Wmwf2gvxp~kPKRs9p016?iS%+qNP3rQY z3vGZ7z!O#Si&*}>2K-B~1@F&&6(xQOCm>*+Dm}m<@Say>RTjd5w-PjfCn|3U>&V}O z&1O_D_;5KKtr3j}#*~U><8*;`-0G6OI5y zm}Y%|VgQd4B=miWh3bI%rs5E6Jo}IlpuTCg0ybgjLxfGJol?}^Ms&asa2eWPc?V5k zOrKRSF4~Xk0eF6b{Co7$Y8d|lyA!~N(R+Oe5gFQg>G5=o} z>nB-)?-4z~9JlA{WUf{y$WJH;;A}(Ck1;4Z8LnZ((F6&@*f%Bs@It~L*eLULz)$6X zjo=BCc{<^>T7a3>16gIWAxbX5OiNh+>2hspDf1#-awmM_MV?}C%7n0{%MhgyVE&Lw znGc3p0Mo87WXb;+qEucJwWBNmn_K`h=8*1 z?}xHxHcAPoxA(&)`Hmq<0-)aB51UHpivg$ie$4;&-p?n=S$7Umk^$%H{rr8U5_ZLe zR4ln4ARCB3n`F&{4}dZyO$ld9Ie!kRgsd14o|>iv066>@PDpSU5&$ai#9Dp;5B>np zjhV9mMHT5vypYPDtrK1!sDz8L&KNRwP(I`fC*r&SFn?{OtO%X15P(N-;^6Z--##p` z1~A=;Q-1j)dI(0v06OHs=X1HIu#y{K{zgk#7&esv9#4ShPSS;dN{2CNF@wu+@d2oP zp@B0Xt}jlz&fxVAA9E#l$GIHvmo6HRhL6J%df}AZ^RJ)(`Pi)Has&%7Pv!n|oy&V8 zQDuKz(ExaO!6&4{L7L?GfRFoS`vBf6Wi5=MY!GAsQo`E}DCkB)ejU>32NYBl>JpdUP>YuxFbEobsKmd0)Jk~rN_k9N&z~8-LHD6b#VPHql&j2|H ziX*^Jp@JS=gP~)-$suGNA%om}@!}-x3S)2q0pOblOiY;vHVFXp#S0-r+5~_(?8Kw- zZW&4lAcviNxx?EL^M5i7&0)t!;l68;3BVk7LI#^G01rNO=5FWV>v1uH4rjgwkqNo? z7RbkCDCTPrlm(D37hu-H7|61w<8FIe1`3Sv&r(xZ1fxPgyvPQ>P(xNZ6IVt6bE2Wl zi_#_o%!!7w5YiO`SgkzrA@kgg65o|!z4k&`7&esvGw4D;h55K#0+>-3LZ;xvQv*XD zE5R2Pzy=U1NW+pB>~jNL1SkfC4Vt!VVe4Ir%Qpb_&=j^=u=fDGgeBN11(-((Z2g6W z8Hx{}EX9T)%P=n+_xvF!Ju6U6kK)>HIWl_$nHu-?70_{m`7re6NZ{`;MbDyd0L&*M zft9E|053H8M1nFm9Q%& z`2Rqpzr*l1JUqY}!vyC*#dlH~CettoBY>w1*B|1nNZH2!kFvLctE$-khhd*{6k+cT zUQq!NQPEII!BEjqkBW+l2ug~IiiSo;Mny$tN<~RUhJ`LFu3}MHkz&!!iWG~Ko1|#m zvLeNz;u_abc{_M;|GzV{&kNMO&+p;$+04v(nfF<> z{z{mcY5e{ufzre@-tOyr%po8Ko zMJ-j#!>Sr?JzSUhSU*H!!kR5=&utsFKx!BvzR;(=;v&GB86*C@LF;0{umi1m znxL%#-bPyrm@VQ!(3XNW4`1^PK^qF!PCHY?%lf}d2#D)JSb@(aN++I$DHR{fu@`b{ z%R~fdz3>2RGouH*f|U-gE#lBQj!Z;>)(qM}e93^bzc|2be^|Dj4{1? z1pg;KTilF4uNyyp~>Uf2LiM-|55tC%aQ zJRQ|(tMZ~~NAviDwg_}t_(IV%ta)mHx6$SyY-`G3&~B>%VJW`21%lWM?QJ6tg}KE> z%r@}zT(I`X_kU5<*dD)G!b%t4|4`Mi{{Jt!8rzYq!J42HpH~hhALP7rJ7zn$tWzcf zX6x;2$I@jp78all#B9iDD}cArrUPax2-{*W1#KR_il?{z@9C6ne-=H0)iA#Quj!QS z(Yri~Ma&k^_LxoCfy4BzSQX>zHk-2cXHTz(ZUX{ejThzuA6Tb-F+;(vz?TevDZb_b zFjRX3)*mp?vA;6#mVz%2U)BrYdl|I&DqaE&T$fic@!%^eKzKJMB?1g|?5_g6+d{LD zFuvqcFue!F`>*jM63A{Jn&}$$NtWN zz8SPNj0br3$96N5UqDUZ!{0W3Ou;K3ZTBJwd(7MH*h0}RtdQ|_pSK~jfNL%Q55E64 zZL`x2p@raO-&tf1Uw2bI>Yp8Zr~yGKzW+6Evm+64f5$=~u=j0W=Rj_Q$rjOW`lV7dl?> zu%nQH2Z6`uwGb=g1p>}aI2Hkx#lAbSm`xS%dPZLgdVJH1?g9cI`)gth0A}H<$b=$- zkN=H8i5Lu@ZBH-@n~+7>bJ$gZfDhN+CTpW9>bmSh&AVi`4+9^UUvZT}Z=s#f%KfP3 z3Av9{I+cESLLMo7Ka~vG@>9~~sq}2NJV%nI(bw7X2I-b*bnBDyZBm*yz3`+w(Ui2t zss)hibMh^Qg4I^qmM`DDdk^AyuZ@Ommv5$uCuKL2i-Ty3KunOTR?$yS$y20+RUZay zm)~=h>VK!RIr2oQ`gd}F8m=*kW->P-i8eniPm|8Aq>m9c7*|?p&=c|mDQN|Pb1bDl zExSo2D{0*`po-f|uRa5=s+IITb4ykF+q3ecdLjL#=xKEDS^0r}!Kknjd<|LGv}s1X z5Rf>H9?6vl_X@^gqqc0i{H*NPD;oYr-Jc5o_t|tl7w{bTZ)DSrTqMwtO%tD!10=(f zw3N9)Ptt?Tz4uAl&D;%7(Lb2`=2P?ybI(4-<0h{ivQeshiZsji`l_yDu zpQ24WKp4B7cI-d`3ESy73ny)-UzuC7oq9bFw|F~^WNzJdngiE$8a=l|9!OiBM{OkK z&{KdJQgW`bX6R4l44Rlj#~DX*4*km9{W;Vt4{liwjm(or**bzp>@(N2Ur2z%; zT0M6MjeY^uQaO~?F*hlJUVg!eq3%7awt+E(O{bq<07KzU@_P}4DZ6O#i%x`bJFOZ! zS!RryPOrQO!l3?imJz0nCHH)JiYc$(4b4OsqrLi3QobB$*ngvo_3sH%U=aNyUmiK8 zF{n-JkEGZiPM5nR;`8p+rg<;`{#cpQ@YS2z=-?i-f5bj; zSgGENzJcrK1)hG4VU`-WNHy}jg(K+mFa?l2+7Rj5MxJB5=D7y~$d zK4S!#H(KcrlBY`Nx@c?xMtSp%R_#u@LJ%B}705GLPdSvX^pgv>+|WKZp$^lgFQEFL z(fzI$$df&ik^gGMYs{Ta(_fN982!b0NFP$us=CnHWv^;R$ErFLuwHQ4AA@D#Ymjbqqss@Z0x;0gaFPd8 z{o`ns+Ado6vOG4x8X6s!|JAt77v`ru2&SCB~uUY5t3YD3zzUZSb09NrR#H`(s> z4Kj4^B&>wZ5@2+tM)r#gy#>aDK^P!Rrm%E^@P%aE&}PClR!v{PYGx}MF#=&TzQ6}= zXro!Tt)5QWD{`2JH!AxCBW{>Zw-(ByJnBJloB_PebWfo?!&E#FeUe;b)LTaRRZlMrgos!KYrXb%o?Pj`o!!y{`mp1K@M-M2s zw%Ti*4Fp#194j5z138j8h)(U1=bNgL@G3g92OT+duN-8mAJm3xUtzN_;?nlYkxSFA zb!m_d{ExLJizDKMMKcHxZ(-Iuya7Wm6l$t75a6?kbYQq>kgXr$`l>0fkd2YVwUX=Xb5 zsyx)ArMgQ9w<ELT}AU*pU z$V2_I?AJb;0^6I1}K_AEBkoO*k-=NYOiuum8{DB0duZO2FD82rEG&$ z8xEIM;TlvigD2ywgM8{Ke=-42NY&$kpEYMLzEHsWz-52vCUm_<_Tq(*RB!kEHZ7H9 z&NP$0E{0r5ENRnxSi|_wq=B!?v!%uvwEA^)D4+GT^>ul`kmeMtefYDS8$n!myH&F= zf5c3B|8-0Njd#%b*U_4}caZxVa)6u`Z`B@Sv8K#iKzV;xd?@A(IWW-Y#Wsy~T=o}- zuMQ+B3z1uvqb!hmP4M!i*WZxGnF8aiS`0llUhPLsZ^%9-Gs3ed?2$yz$1B`RU5=g(=dyMyaoA^|4f^P zOLK|JO_I-K+VK{qq5^k1@)jl#R>ZH-9W$2R(AKhw^NylHZ_6{J;7D5iHV6-U(T=y} znWnNVs}@50MxqKE-4Rn@aIl z3v%=l4hfALp;l#ICHs(m?x9A(@9)6bs4nju=Ev2Og<@tt;ccJrsAy{A=IX^Ho=qW_q-?HEJduLJ@26! zBUaL>_vFcp@X$w?Xrs|ae4@>YBF{2;XfHM$cdVt@_tAjCt94|aj`T-so?AtGfRw7% z(~ZE%< zK>y{MM)pf|>SL$23M%Xp8Fra1+Nuy4u6>1KKS6VN7t*FrFdCcp=tN$#>G_Z35r(2Y zT|7><+H(DsE`NljQP!{5MLIRl0Qftt{usdI-*sSC34ot=Pur(Lk2cUL?W&_9ZMO=M zcEe{nQK+7F{%0a>G84LXWO}DoPw{ssel)OLp0Lg5PH0Cc0{esDammIPbXRv+0bqIe zv}x?YC-%qaO7Il|1~I|^7_0){{vNPez_I~zPNNa9ti4t8HfhVi)Vn$ zM`dIGnjZKqz!x(7KuSLfu^f^{n~y?poV%U&9K}i;bMpD4SVkqSZ_`fFzM~l3lPlyQ zrY-k(YH763-D?2dUm^QSRU2qW1rt1X&;jPUZK6{Z@-*MZjh)&pye-AN6a@{hA+=3A zC*qoM3~`00*~5>qa6aPxnC^}A@}W3od30C|y5wyvu34&&gz1uLDk&yn>=@cqd6{OP;TZe7VUWcvrTHi1p>_o$A<(LAV=Ga-CI0LQ=siUvtlCRV0e*Bg9c6%! z2e8<{s4@OHo35RZ2+Ab5Bx z?O^yk;D-u);7T2zk8ssgI>PXA<~D7hj$fkVD-n)}qRR|lG_6frF7Rdv1gulG-~)fa zKYKp~!SJ@MVj-!~Gcz{#-Z5#VmGl-Qw2U zh3SHiD&Fp~`0aXNj4iY2w=dk|4A3ySO*_CSCeEQp7$9Ym4wyfO-T^==+f8jJH1HIrMC`>}zO#UZ*Ysb#4x$_UlyvfAx!uBjC;) zlt1-Joon43ZvT1$G9hq_>NewZmD|2x1a+z0-l>g7%)+!VTlGp(-Dc_dV1|F{zvH8s z^rOC~wnJ%SC62!eqRqMfJYflFA6MkAP#^WVu+fj6QixZLIj6x709q80+dAA(v-LH*te zzj4DHntmEqv6@q8nyegJaT=1NnFRu$5dp8$Ebuf9I1R0};&GjCBj@v#3OQAP6q!q# zK_EpwOD{9G@HzUJxph0}d**K0NuA8KK2Lr%h$v=On>Gvm+_-5DZL3lP2E=%9wUSj! zCdSkVhTAcR9;!hftliY6U4U3LRz}l1HCVVrXVK*v*hJBr`9eFTuv0t9I1bFAG5FaS zJHouTQwwAA=9@Y6{24jkP)pDPbCd}N{{rsmPoZapZodz%M^ZtjR?O;+vys(K)B`RovUDt!Iem1R}7T*)0YI48j+Z(W%|UsEVTLwR3XZ zUsG8h(5c>wrhebat4!f;&{>6fEud5D!}IMLNmtIxV@xg{495&^uK5fyoGLm!`?$JO z?Dz6`rC4j#Mj>Ig6kkTihN?H2T-=#yke9dUKE+LH!TX^gHMtD#)PhBogmZ8F7?|^h z*@1;JWQV|;9o}N@y*JA<*k}j3R@0Rb&oQPf53H>Cs$EGK-6;$?32I<0UED1XS6W6n zgO0Vz!=<3nG`1egGH&pTgb7nOfu*Aqx;3;I#!fFfwgc(8wrPsUPY8fIsf&X&2!?Vm zI+Uk4lUBp@t4EcL1axnUiFvQ&pupV6?UzX))%!>upnV*5rWm_gHMUk{)w)szxJQyg;HLtpxfUf=*+EjslPIwueJ=~*IH>@36`gUzsNCC z#5F-0cU6!!UKLT6Aj&l&pXvU{$Le2^$s#@8sunu+t31aP2cpShA0gy7SWqIbv3!Qp zj^AK^K!9g9ipM3Olu1O`I3^`?L}wq*FjqHUrX$2~)7>Ud?il;}wZ0GBE} zgzKYFKs&-&eS{mW(he3bbr)``2i;)dn%>OiQm2pcibYd}p;5j{FL%geP2~XfrDNA2 z(CXmrLuW=nipE{FXpfSsK^aJ93+91R13hRF=16W>w_dhr6Cfarsq<*f7-g~)-AZbw zyuu)>n2^3x!o)x}w_3FKMgOhrlp{^~*DPAOFyaMXm!k}U3XDTHgPPlQDzA#_Op^8L z%xGcNd8=y+ZL*@fv`o6Lonq}XfKFOryOSqTrxhbD{Tj{bLeC5Bq^G*jHL5IhstYw( ziu#Td^h0jQ6HI3JPHnMRINyV?RMbRo+&~xGVxmhoz*p83HYkH$Q ztyB3H++&w8KR0%1FS3$n&fC>bai|Q3|J|kKG5FK-cHJT1+>qD+`Ue^O<$1e4QKp*Y zUo2XxeF#r-ZJ@s!lu1&IEA25TW4RcR%6=i$sKioDBV)U6~1|W<}56qnP{^LHi^G6kA5>MYo+Qonr}kFwQUwG%(+p1`YBJn&CD(IjY)wh zhP3OYOp&Y*bG?*lrVwMJLb@P?SeDrgnc?Lt+vm4Wq|5)WX)vHKGMln zTJ*gfrZnJprhBL$r6*gRRS?hc@>XpKx`0?8tfW7_mq(c5(kBcP0Die8`p3+C8wbwIedz#WQ9HJd8;fC^sK~6!dAYCxYyGEhnVgrb38Cf7-m;MHfJ zKyc~a1YXNKM?uqZ)OQn7)pe5QM5^rXe2%Th!&`Hukt?MKVD|8ZrPYN&6 z1VdbTD{cGMb1KDsp!AVeTj*dtgg_{At1|_GNq7xaAL{yvKVYZnjLCBl9sZjVA?26T zWgm=^m`{X$lH~)*9#u~F^;6cFnn7GluKl6RwDePAr0`D#v0N^ciH34&8-Ui#ETbFV z%0?--OyKk17x>6Brk6}Hg}&FSB??R9i~*P*&F=}i)I)-<`4ErCl>I>~c4qbsM0#-p zkzPR=?HQ;nHC4Rdsy##(_dzY_?*n0Su8d-R5N`Qp$P~*Hh!|3Q3{En+5Mc z!Q~CFkscd^{qlI)GZ=-irdYJ+XvP<)1j}GlLePA!j~Kks@)w%0ZRxXEC?r|&Tp^L_ zV##j^nl>tl77u}ZDZQI^vv7n?7Z^vq0s&82Nb{K+9VaxA`Z%tMm|7NDVAFf7LH4Fm zLzQt-(;`|i6s=J^-=aOsY6q&>P$fYsx{XE-L%jPp(&}N#G^rqw_6&nUlzp2;i>AlE z@*GIkVM>T8abP zO103CYw}c63hH;I-hv}AJ*UUaLNokA`N=h7h!9vke$cN2n?hOGyn^Vx{QCv>L9#XPF+i86C`_sD!hqmr7Yn z=*VPn?_Wd*CO9c79nlu8hAAr6d2}*D4Wxk+q3kEk=h})PWj>~XOOSl;Oho^$m@Cwj z#5pu}5?V5H4sDzSH6>}bMZ-_}GL`c4NvQ3n+0+TR$X!D!8#=7k@)p`k#&ncN9Xbm4vXe}9<5Ndfmo^A{ zLq@Ope5>D(_D&bAc^k^hmM5Uaye&`W8@ooV1>Nk&UHIv+hBvNjlUS=K&Zq0QD!v}+ z`>$(kU&4r584{`Z4q(b82PDtet*p_^a&qG%d8EPo#&y1lOL>us(WCUu>l%LU%f*;7 zpZ0=vWF53=4oG!kg{6}jXj4F#jjyAH&POU6O!YWK@uukfYo{t>JW`Rdg)FkP`9xEd z5mLwNbY!X$;8BGo*6R$BIiIGR72n;{ATUc?X~#4S{JZ02N~)+Y`q&F%$4bzk1!i&*_73D!vxL-iFKK+Ac|NoIqp@$4U_VDvh14_?eOr zXR;WUw@+6_m_T=KgkX0-!eQ1me-Xxejj}PPqsLQEGUCV#lasjB$4E zG>5n7K^vW^Hj!HwXG6!w){A~X)E{1hL%WpnAhlmm#=BzQaxSv$;*E`HQJ&hq%*%C> zhgqEblwZ@MR;N>b8IL)IT$|`nG~{L3-@2Sg-21w&=|ge7Hk#quYKN=({s3a0ll(SoodQ} znRo!PC7@^33)Ap(&9pUmH?Lv+_*$# z6n=xNmG)+-Hyc9XIh~~jvI23vAkkLR7)OaXqVb4c)WjZ$4j_1$QXFOC967earuRS` z1_v+I7Ds70M>IG%B1bQ7C@(ITAVJ;A+s9QeZlPXWsm6tupPk9(WsSC#HPTkrrY=WW z`Sywtz5jbw>-h_4+;YXS6;+QzmK?Fa2f`m5KQfN;1+-|T6GsO)IHHCl!pNKgdqWz? zAx!kyo~P+{w;pvvkEk0q>WGdWh(K`gsO1=Ynuls-Z+9?oIF92YFM5*cpw>lMahFvr zpMs6tH)B04BPA!==ybL^)gZ&;`6RlOKae^{k&WXfQ-YmEYW$sctb+7U{GCq0HTiG` zTdDYnPHAb=?qPeGSo-ZI}mH1g+%%tyBTa}&3hqTTdmA6=vH6=zNvVqp)&eniC) z%X=VFZ5-^<;)aXPSE9QW;j9x*u}dB_y|?=^t9F)U z;NFGw&NHf`w^iMyBcAMmFed7Vmll%evrZiKHja0JNWqFc0hAuXW;5ZsZOvR5Zud5$ zjQUEt*zT38CeXC?nBGg))5i5o3)bE02oY}5U26($+<=DPf(r2vBB%K@_7?LZ+UV$O z>fQXrrqnTkV()-*;IrJGRtd7DCtL6EW^gatCSnD2j1S(h3BOsjNLEY77SidDV70di zrtDvJ#8*8K88*asJrKpe=p4T+q(2JK=^73`=rQES)~AB->MqzOExe90*>qhtKP^F%<~sitYGON6d?*As;JKrRE=T5E2Wp z=pX6ECM=R&0w6LzRwf&a@OT!Xwh{)n(V`-ipPuKnm4!HXZQbU`C%f?Ck>+mIK4tk_ zj#Sf?B;K41k?y7=(t04mZ5-QTY0alj91%8-7aRz#+<<|n{dz22cvTI99{S^b$}Kpl zeDQu|4Dnsz!%1}hK4rWiC<&U_E1u(B*YdCwnao|+Xa_C!o%=Grybd%+DAu4ym9dgJ zPPn15!mWrGZnF-D?TFKr#^Nj<=$qHmh6hA5a;abPc&qjctA>(Ty61JzK>GRtB}@u@ zhk88-`$FzJwDCcVzml8j?FXR-mCdB955lq}k7?7cN&>SpB*lNl#D zF3`O#o;c#TS-Hd-gNyGI^x&@Bw=aOI&jm$cytjB z-0H-Ts!du6^0d?>ibGye9j`FlHl05o8 z3*sj`A4)6Ey-`YnlN#TV*Qy0E?ua-#`Mnxop69`9wFF8<@$S|?ow=(7ysn@-JOU}z z0baYW+Y*K!u&V^F5jk^VX~e`)@5hx<9+j}(@B?O2?j#`_l=#K%|$7<6Egeu-J!fE32{m*OPW7pesB5-|^MJCwy)BuV?C-fcLKb z?|8YF%P^PP|3MG}#WI27pHv2!Vz~E8HoR%vdkEfbx$qXBvHaIVc_qL{p*C(oscnb$ zY^Ut}0jdT*1vS8Wo(=Eibf~Wh_=f+^AL=6G&Kb)9mld{SeD^wz@ts5CMWM0yF}|V}Io;g1*kO5ixB11&S z)2&Yn1fOVvuUfSKu=tn9(+^KOC7kjf9g*7uQFPs+#i2JFkH*uuX9S1qWUQpIJI&#J z7Te)GiK;q_Fl;YbOs6eM0Ns5~9$=s8@_*E^xBnG3@0>;ZiRJtL#kB2Nkr-Ah1AAX) zz-JcI*UzF(%s*0WF6@R}%gOM^=8wV%L~sy@Iac;#h7%wg;`d@JX& zyl|yp|Hl?>3agBLi`nVBK$^Ql7nPG=*b|HCj~(`fC=3)wVljDcGi&e~YXxDy*z zHK*-F`3`T@t@h<((sa8wy|>*=mtgY-8^_x5Aus{y+p<|$*z0Dx6nJ$rUHbjl#Kp?} z=nJqh6`x>?+@x4#k0R!{-J8xM=BB!o$d%5mpV$O-3Ap(C3dBpBg{Z>+gRR`?gl&gBb_6^2S>qSoui-!N6Ijrqp$}@^H80m z$icy_i2uGWwBX_%42K)9i%jizFz|tr4a4zp)>TTD&`LtTc7x@Fl+}jd&tV)QWtEh3 zf>swO@%F)!4vx`mELJR`(*@uNucQ?(L18V?-IOX3PP!r76y1&dT!f7}KJ5g#zk+QV zjD)_v7|W09rX}kVyLBx-57w_obhulB9nRM>@)q6Xs0Xs(6-<9FSOB{Vnlvw8F(o0s=$>88o8*j6x8Lwe2V#|vUhwDj}f?CLY zL&JMkI=aJiv=NVK3?y!7v+mIiZAtKOLt7G%`W#Wu>9|zRx3fqErNYqWRw@i_iJYOE zp)LHQHqFd#xQEX-rQs7B~?6{Mx}bjp^P->uq$)+c3155B{a0?OolT z)^}+SL)$w#V(?!exY=yf(jJDkw{?5kgdT|fh>CN}=z&PJaV%Ua3~lBn`!EdWUOt*wXIyHnWXm7ZA+e zRt8GFDXT7Z+H72r4zJf+cFR}ge&%H-pIiqCds}t9u&+hxZgqfeZ_{0Wz?r?R@J*Hq zFFU&vE#(E!v{yWriVM;egW9wY+4&bgdjCCThHD<}%T|Z;gI(A^;r{d|)o@djV$Vq& zis2X|TwwlPxBa}e)NT~w0<%zuf8c;W#`ZyM@M8`*-`99Wr~hiHFtvGKfJA_)O|qV+ z6(3*~mvFvSSlY_q>1Ju`0Pip+*}hxKEp4WxAMFRs%f(!cfEms@&H0<5Igd z&0%XR*RBifWd~NbwH3QK+1e;ehI#?x${!yJ?Uc{oAQ3sycuq!9eShqoJV~1lV;?Ia z#d#l#8{x7(&~0soW!;T%aqsI0ZwG>l-n@Lho<;!SY=osJTi{Z$ z)AK2-_kUgN2eNu-L1fn zZd5qg-HZ{f8ncfW^Op&`+g-oa9auY`VW+8aiiQmzi8EhAwp z<40YrW9gaCV1>)@YSShOBU;yIIEm$ghhTma;kBQ`Dwpf~;oF}pFSttQdegKoV10|| zMSGZ=IfZU~p={_?F|JL!)|+BU_N6C|D`!kKxJU_$Q?5LSO4JYujoa?viMSbB4p)+O)4(@uCums+?wnsI9n4$)x_`MEczs5g6I7`7^89 z`b3)kPdkUV`@(ijVenTH=|u;;pGWHWc1>o8Gl_KTmv)AJ9#K&`qWALd2(P6;Fl*b? z<@CJH;kpH-Sktb}WALY!)6ZWjGfeeAwdiNV4B0=m(DQzHMu(qEO=`3wTpD#m9y=Uz zo-Uunm@wDV$ZEJ%7jU1Do$mROUap4KHR&h%60WK6#}@5=aqxT1SIQ`Ua>~?<)EvMt zsq7-X@D&a%6<%!79-yHQs{ZuvuapH+^UpN#6e3UjnKqrmvAuBMa_FH_9Z} zY#Q|~ws;^W_-SurO^dK#)hwq!&f@Tm4H0@uNBrbK#0RVWJhlMw5=*gVIjuaWm>CC0 zlvnGBUMuVfUZ~vDdft6j&>$SHbM>Ny-zm46%1*XmWy#i`t|#e8EpnB6jxN=r0ZYGS zt{<8ICFXD5UA}D*Pj~pQprhX_{i*I>$`GD7+r>ZkjgG|)>OW(R=UTKWEYCs6!8cf_ z96n2{zrjHzGwRzYjw6hN@6rZv30#K=6w2{z|Wi z7)M2LL;?!Tt8TRe!D}c8Y4C+&x~L&(|Cbc|9S-xve95Ya>4j40m!gg`zN3KeQ8(7_ zlt3xx91HO6Aua%lQP7#Jpc%Xx9M==+(c$0;pbbc-=g^qD1P``wC4{LKj%$4 z(tz`fp|8_`U$98tj~o2IC_5w{oXY-1*(9ZYfLmtDW>eE43wsKT%?9niD(j_!_i6QS z%6wDq+ZG5Cl(0X2_8a0U*++hj*q&qKj}3v$gih@=Yx_Mb=%Gd@$y~b#8YwH6$&;w2b@Isn&gL``9=Jl&QY9h*AEUQgu;YX7%WIvE=~HFuWI zw<~DDB`1XW&Q2|tVHnj&*~nkav?II=1CMN}QS(#&s`NX1) zr?tP}ZqM7zP%-LGu)efGY`}+{q|H~b0bh;R-Nxx1>WZ@7l=)AK_D@>-8+4Z>mm} z?FI(D*5#Z2)Yga5r#@p`2`j0+#VMU2^eKg{c;dsxu!>H&Iw2~7;O{03Tt#CfCq(EZ9WiDVJ+CA9X)ham`YO8S z%#b>zQ~Q~vy<`BV~ zA6sSDEqCIfV~<+A0miMBPp+axz0?V=#niW#c>j^(OR;yxw#AK4ucCt{b%H6*waYg6 zgQPCp)Ur(|oVyI#Xyj8lIPu+d74Zd*oubEb-rF72 z?4fhx>#JyppE`k`;7M@pE)Gheh;VUGvZ|Xn@GwFab8&!|e+uCc zF_B;a0UgFi?g8z4$?Q=AKh z?0L+c>-xD}CalHIOrHt1p-Qp6)QPTm!NAAy@T+^(d%DEfNo_`zE7xoox#weRn+t?p zbikxeG=(>_QN&&rpnW<&r;CD;AjYSN9+wxLqW1^|nvd|mui-)fR-*3sTXg(B9Uny( zeMR=TwTAKHrcSGZ70z~Rm0hY}2aAfI?GB3q%%uk`5um1Adf89q59M$XSn!-xiv!$v7?BTB z`+G(skg`JuRtg|_4N{FB6)-Du(i#r+^(cH^2h{1jW#Fx{0ULE7>zKu0<$6_%9$^uS zu=E9;-@z%3uMcP=6L73j7EwOn5R* zQL4Uo_#-oi7{HwDc>jFPcEeM~Crp8W*CMK5)WA44Fc<%s#tSsb5>A#N|F#-ud@^8h zw#?p@Oh^6Iurc{AxQ7fR`(uou_>y}XvwSsGLvaifVy_(maSHP;>Tr)8kmk-Lo8|b5@X7pxMm4I`(rS6P%F;~#4zz}u5sVUXIA5xUgynHV{Bh`5y-5<}mI4U>lYC9dw!*SZHIQ}QjCsbc) zhepr0JNTi^^mR06s5)LMTu+;as#B!6HS`aJP1Zl!Z5Pl(;nlf=9NwzS?Y7elx$ugY zOr*fobbJ^lmzMP`gZv>Kj^w*=X{)Wa`|If(YR^XBmSn5#5MW>;ZgI_~cnere zIvhnWUS-A88Qk7CKS+%=RsW}5+sZCO<3@Q9=B|z=Qb(w5S;nHG%&;_yn^Gg7E(T!8tkwQA{%;9xSfk90a0 z?}p5B#3#u#_a=3!YdU=ztj?v1ajKii3(<}cmg_4wsjGQ%%*0o}LjMVX6UlT>u)0uc zTuw)VQI_c6?bRFN@YY=F-cI3qJ9+8t6r{IP*1zrT)X>Nx;zz!@kJtGYc=bakW_a~x zYFQSok$G(JR~DP^sq2Se1QQp9g` zDg>J-RlkyYGkTVMJI!aV%R1(c=T>MbTyLDj9*t9BYn+p!aZF_^u|>+BVjf5(V^waW zPUXrIl?&0syzf!ag^0o@VX182E69w$%gMJgPnVeom&bWO#cXn z%8_%{j%CT{%wCvL@G_QuA%~x2PU_H}LM0fZ*0Nj0wk0!`#>+dz&jj3tf=<8~j9Eo~ z6NQq)o7W7^ry1w%YiZ3y(Y##kt_SCr43V*x4o*~Om{L}BXeI2uhC$>tNxg+t@tG4? zJ}m3dIvL&LYw7k$B57`~vXu?w*Uk4)t- z#HF=#dMV1r_k(J(JG4Qf^^MiGej-I@)7VI~blypO^A_V2sZLnMp}a%+*Wzk;Bsx?A zhq2Qc(&5J`b}D+WEvuzj9oh>l;pVlpcPa|j@OX#jO;_&6X2lbvPE*H9sZY?fY3f9S z*ApGICIQiP6tK+%ZYpoer0=Ie$ooG=qo+GXo3X7!+sUHsT1$^iM<=S2sq zkmiecT+MvHGX^iW>$Z|86mSz8-$CnW!A!?W!y^kR4`Yb5b#zci#52QI`BscvhA3M{ z{bmWn7T@QnSl6MsGDOQd+BQpdY!St+?a-J?VGO>VF6fA%QEbM+*m;>DQf{Z|QR)Ly zJ$`-&l}rV*Ret-6n{$F!cW9RwRmtr%a5gL$7=jyT>+>X=xDqyXXct-aHr`GrXFDYv zgoJ-$h~N|&Ge<`-qj?z+zcEBo3OzeV)Hi=LG94AjtwCks!Qn*hc*k=(~@Wr6)$Kr zIO17BYuD4kXnR|DyQ5-xQ}}FPuSo{dE%RUsiQB>YolS^wqg%-xR$-S)+CZ<(Q@J&c zH%%puknkEx+dzZns|!tXvDK!>)x2i+=G(l%(rZ>4LO3vNZpDd{E&J(mwYu1ph-mtY z5tzoke8(f}O*(%8Be3xeD-=RLKU=ximN#Cwb8#KQd|$GGJl3i4hRBC8fb=J}1VxNa z(V|mWAM8PqxKO8vyhFs1)|29#jUrp8sC%GC9GP?UII4AulKXp5oQu^dyi-LgAw5$` zT%=PZ=@f-MQ|XwiQxxkI)_Z%T;xk*PXwoSndr}nGD8la)`6x;65l6ucJ&r9pMcq9e z;vp0E<6eg3PjS?Es?(H|h<$^6)+HJqy}D_*3(P#zr>PU9 z!=KXX1hi|#an{kq`6Kp|KgI9Uffdj)8u9F0@ldS8&mL5M{cm7W5z0^t81tE8QI{43>Ox8K3120%4`E+pQPBtB^b*-g$m#Hf$ zcNvVt9q-bCW$N8_f!2Tn(_El++}T~A1tNMrip(3G1)8_}M;0N^ayB~T85_XKf7cnR zHqt%I#Q^4`>D((8&6kZ+<6TUi`O%f-V!C5OO+H5!Z5P8v+=U-^8Vms(w?a*l+=$g0 zH?#8I-cexD-eP2#cTw+^OsW;oij{(Zry{>)(f(i+S$-G2ztTynH6eK}ygKfpen|r1 z+5|X$6)VP`aSWSk^R!usF1WfR?>jG9f}OH(dj zjTQw4F1~_|+{dL?+8!ajYX8oq7yG>-?&~JJ5_0w3qpD4OC`!R)_J?d`|ZS+%ulg`6~pzv7}r49{E{1-tAt!5_%AL+j1DE6BNADJqGVb^%x2SfuZVc z{_xUdQ#A}J`U>7_o86lNXm5UI()cLziDlpxyEpJL2PyZm2RkV2PIZha4YBA9p$>2M zT=qgTe|~O({jKDrx%TC)+3v;V;7%HMw>sL0BT@Plg)KPiq+d};hS&Kek=kDTB@vSu zr;_y(q242zm%lRDa@_{3Znb-BrrLAh-H&szzSq~zUmjw^yVlT*yKtzJzrPg~r5mSs zsCuq*C}_BDTj98-ZlRzN&Xl=VuRFa{l5out>LcCiOqlKEh_a95=?J(Pyhl3|`lG(M zU58IS#SgTQN2=#kL+yjY1EXzxx;ouZYzx=&u&a^c?^UPc$qw$+(oRMcG`(GLd)qul zc%I$p$?t(b)&bFlRo^fs6zcD_pK}zuS9pPz@0v8++x_xI@$dTK#Ks;Rp+InsCI`p8 zyOD%%r%0l?2SYFroT0_Rz|#)8A?}kJJ9==GcIjI=RtLuw_TIV(&)uFArE}>N@F46KKA4~%#8RZodDr$W_!vORJb_jQ3IdgKBtpD(mf^>scor+;8G^qU%zd0>%VJLAOD*~@G4Um3aDIod#mC;){VvDh7j(pm z9*8O+5?J;&+}HiaL*h;yabFKa4mh~=e(QbqYaTptA8>HQGxv#m9_e?r*zS2mr7Hgyr4Gt5b4p}ADrf)m4cw(y%BQe7(T$-V?_eqcGXFQoh;)k#8&IfgXhkvX%1V9*6{6DUbIkWka4`%CmYY3pd(JDGJO>86-+6 zMcpY%8^ud2<=;sGThv%XL#kdzH@%Gbg%MjB`HUAju2U>o&)?^`$?*n;&CNResuP_3 zv|cnAxZc<6e*3Ko9#arFIKq!3^lKFbAa|Tn=Y-*5demd@cO=Q8_Oj(=W)DORIC#`c zd!!j`%gjdSGz&qlOYc(IeqKI>d$06{4PZZ=%ErJ;+)wJ0>NHa@FgksSgFcyi`R$LC z6Ycc;D!fWvd%T@a!($3^uv9^g#EYR7$-Uf6VfO2!KR&{Dge$2#&>7&y>h2Eiy3i@Orc54zO^xKOn1G?VjLEVA8MNSeCsT0B4jnP92O*oT9omT^R9(1kp8D3#=ie#Eh6uyJfE$IdVr*S2U7bnGqU zWai_gjO0M>O$St{KdxmobSE^ch;=R6Y@H5B-5Uq!V*;80=x+NAB)ac&`b3wL!6v$? zQe%I*@dC`n{@&a*CBqb`kEDbq)>eEr;XdAKk+7`2h)R_K(&^&R_WG+bl}6^}2mTzu z5)R~r2nAHK z#+6Dv)&@Mak36%-?zoSqTH^4U9o}Mi9deD=PVP{3_NsW z%JOF0HhhVc;!Ur=kgjhqB8r_k=N7* z4K9Kz%#f>lq{KjQxeU2|V5~Lz0cdE!57zf8q+i z1LKZoB8)B%(#khrItm=;z%#o<5Tpbr$PomF#0Wjglu7U$QN~N-taQ&F&oEQS`gZ($ zDc^6p?M-!=p~{wctu5byx8NoiE*TlDL-2cmN0plmX@R<@&gKch5{jeBhw7dt8>(=y z4HBe#{B52R8_M6t9y3g*(PJJVe)yvaOOM;d<-Kp;RwtW`b#2-Q;sx!nchm(^>RH zt(>hRsve?G4xklt_Rx(3*cE9!MX?8Q@G$)s+IL)bfWK9yPB%sNZr7e<{mYMfe_-DZ@OB^Drn#_tQf`@a z`v-bmvRWy?@AkaSZtUKYNgsXy)2si~Hmw3b!;5PazW+d5$3;=>ho}|&K+{L4EHoW& zoNVtl?PbQ7kVzgNqBh+Gon)R&d;Wny{1xVvb^QS2N&@R53}l+lCH%ePH?)eZ4~m_v-1hs~I;cuhaQYunV8%N)yX`J|7f%~ZeVAVP z6j>>d@S~yXx?b7Fc5SVPcsXm$5%otYr=6x9#Zd^KHt}*+DlQNnRo593eA?;g!+1U9 zu?lsTsm2Sp=5{Gw*j%en@3W7ts!8|}cb0zK!!-RfHH?y%JKaAv;>Y(mcHLiLYi!sI zj*T}34e5Z5lE1q#+rGzH7(kakLnF0B>3f{P#=F@~0j_3**y#*4X?P_3Gwewo=7fCm z#w+ITm16SV`7TTjejUP=p7Ss*sYE|C4`w@@{8y;U28%6DxNM74O5*NV{?fal#jS%5 zeyf|Ine9UA5KoF1JWQVFgf7dsw+f9NS{s|QY96LF=bW~;V5`^qvwCvdO!pkux3}2u zl>>g2F+^>qA>YAXYxbj&C-jq}>DGT@aFrP7nSWw5S|$4apL+CcYoOAA-BcFMYn$nhI(=(^A*?71N4)7k@LH)I*r82g zg)iAm9w$Yua70ySyFfHuTdu>YRtM1D8mJ2O{pfg&I@2{tz)r{D_hfC8mRoO~u|a2SBG+0l9zCOu zpo+7q|L(JD;QyoU-NT})+CJbtdk!KXdk+lf(}1Xmh=>S?fPQJPU%QkmhQw6dZyvogacDl^kTkaN!WTWjwb2I~E;>wB;FpKmS} zd#(Gh*1gW>b>p512ln8MMK=D$f{ZMrd%wn3V~(+nwlpZ(e7H~+_}y0oMP4CE-$1A` z+H=|?kP5$X+IOyYQHiQmA{;*Y2ayF~U14E07t-|82&-7a>fLW>&z4AZ{tj(>w@F@>GPsiqA-D64Bqmk9j=M_J|jXeE2|O*yN> zDqkHK9$|=Y5bTdm8+Iir?aE23?^d#Ut(=+?&131zkEq? zSUYhd@LSq^p3U06RVuic^euV(j1gVALD|YG(mQtI%eWP7eWXUO)NC0LwPr_fYmb^; zccjy1;p6gEw5r}?Mn9dd%dYn?b_q59hEt94dJ-?-q+G4WQJHzt*J`?y7sJl3qSr4d zNzW@(7Ibht&#PP!s|H~d@n4Tvtr>a{m|hKb`cA8Z<3t_OxhT7PSBN$LcGd!CRykW` z#dD~%sX?jj;)?0rtgN6lBV*rW!PXYh=myqG;T7)&rR(5wordQ}8G-xb^dlpvnMN_c zIuYogu!9rKQ3)b@5u8R4JZ6=TQ{Zp#p(=}({pOLZ-IN6lGpCih$iv!~s#01XrzS>O zKZPj;@o}!;Cf7ujC}p)%Le()PFW>hY<*OTuvmq$L>=y(R3saYlo_7~k1hX!BKrd7} z&AN#Bd+aG_6vP2Lyu|a)MUN=G>BANYocX%jrO6gir))f^t&#^oz9Z z50A-W&2BpXhsQE;#U7e=$zz#*$%hW=JXm9twX%xCsb$e;qWgOedU4W<1K4$g=eNiILa5)}?PZsx0q%W>`Bx@>Y&lQg$ z+8j4*IbFq^$1lKsLQk`gmS0u3xx~6xDCUaY%j3)r9d~hx7iizEdJJL5Q@M|qX?UYY ze}3zxB3J=Ma1d3mfIQI7conV5Azynq`fPv4$f{uu&1;0T<=vqC33$ok~2a;ka~vrYc<(a z1RwK487_x+b;EfOb38k3^(^XcYv|>6=OEm%Aj1+ZWDRvXA;{cM()D4N9&~YQXnKd* z0=i2$jo{j8Tg?zt*3b(bxN1}GNxNheMZ=f5Xt%bG6E7s6c zDx6E_0_j#Uh9}q1qgqMn=a^5&g-+Y2EM>~q(3e^%UGKNS`P2k&jG9Z-LbDfg>ZBRk z6}AqN{#M8D%$MARPTRLE^6#yod;eDC;WNqDPUWQA=WFPg3g_~yi0`zGVllk1hJ0^0 zMZGen)AlGsbgZHOuxn41nCdx4y$W8QVKFfkQy-hc$-OL#>a_W@xDP6(+nf zki}cKR>|_>BIk(nEYHO`2i{J2tyN;a@Dy$KktXn#v0)#@=%oO1*Gp#cWEFGp_aiuG z22NLS&hWK#ucz9=h%V337kX)yXd$I#f%0j4%fh*W&~W_1(q;Hsddncq5R0BALm#}_ zW1oc8yrQ-p>1+R`Whs79#ZKo~v@B@RB9x9NYc~bBNYE!)<=luEXr+skptrv84`2*e zC903uhTC^!Y{e4M;J(r@eOGBux9%z29#`=1GJG`XyWJAWu1fpEs{v?Nu@t|3Esb+^ z&OFEz!;0p8Yl)l@#gNOJA=a;@F>X#A*=VphVn;XP$SWw!rcUJm(~E2ADQAY09-X#< zEM;quAGUs>v~*rSZ%49LqFrE5GwV*RrP1zA<*^hk%qE8TbuDdiM|rfGde*}O@VA9Y zh^4C`{hTDUxOCd)umb71j#jA%el{HvZe$FD*3n(wP7F0-r|lb-ItlCOeQzlpDs+Z> zN+I@XjGM~}wM30y$4b-;Tp8^5HwKjUqEVdGsT?HBSx2`?P99gsb=pE%9PV02ud4`t zKpzc4I)gvDju9ztjn|x{H*TOGL`a+u{ux-z_OGKRm5(<)Nzt9Q zDGYIB9ZfVkNe~aw9%FGnvyPs1Lb%or?6e(YasHLQ&`M+V3m^JN6|_94M!Q*wwpcL0 z(fIJTzM;c5hY71)PyM}|V}Uki5<>*8r-!_hwug&Zf1yJ;yD@A%ed){*^kaweqTf__ zWkP1V|LSObIA;;OT*xAL*LwQUq=dx__8G{);E$|#^CYh*s^r zj$jVJ+AElx|1ch|;3?n1eHm6Y7&ENufwTf}!^%!)A#4vtqQd14jfT0^GUfVLLx7Z`FNTQNKV{d!EP;|m!~xvZffAH0&Zoop>a!NK0BN$`4EIh&f9LFh(hR*hw;j_&KIN{=r85H|&XU{dN{BQ~teQ({p%AMa zECUr1JY(@iq!g#CzeQdWio?H3qC`gstJen-h{9vCp zSZ|@0aHM|~mJ`&=KAX6eN3;5NTGt=ZY@SQM4Z+uC9^L4V6l=Sg(jp`*|2|H;BBU7o z#l`bYM)e78_S_QwKEs;)YcTy8^O|@`trFw6ZsG_R!L+iqDm}1##|e6fgvd z903rN^)gNI+{V%vxv{ptG#c+v9$}wK`n$h0MpHnk5z>4y;$bCy8w?$6xsq*{dtpaU z5$TY{e$qfMv@vHFte|nCJ#fZ=OPHTaXFp90_Nx2nT}`V)A?aiT)zx}2Ptin z`DR7+a0Nv4QYhKgRBgeCX8Hx{p!F6l26T$R8QjY6ILZ!S`E@*;ui%+-bk$nPt^Dnp zZeaNprr4BA!{<@?{W@%~vyGWRiind^3>h9BwkQpSjF$XqRUC%EWzcUwPf>q*E>4Qq zpT=D*qjI9d$ZR|r4C1g8li87 z1giTvxU~)78gob*sx5;>ItGi*8<1mCs=f^I&?>L-@I+NhprchS8i701iWm_%6Dcca zHju@t?(TEQV^x2&85yfu%eY_c#W-D@gTHW;gR45;L7D@rT5?Xp1J#-ZS~XY!R-=-< z{9aTBj)wf8Y?;nTLhZt^fv<*EAsfcC*7fvyI+%p0nH{2Oo8y{k_xJ8mItZ?+z@CdV zQ*(`#41LA0X5{jWAKWp>yvi~h)LUBYty7?G4cjoNs}gME84I?)`&x* z^|&>H#~*ghd)9p8boKSrBw}UwX-c znr%jnwxFjq_s90(WhlNxFK6j!hZb$<>+_<*bQ}=Qbb;baWTfRPwWNdhY&*q_m2MT? zuhNFG=mm4pcH}9G70qMOGnf68l@MS+M#Wm`&Y3KFIBLxL>yDO_cdtY z6|Qj$wD2-rdnc_lF9SJq4pF;L@zT1_J&DIxi)>eT${OuFcm+&MxkRsyhZy-d>Czoc zteDh7X%o-|&H0mdO@R2;R`U23RopfK>9FrtN}hBLWBm%?Q`gY3!$`a6(in`zc0gn(x=cTJLJK~rEm zwN3&-HJ-ej3<8|^-gOo!7uiPpC!?8{!yLs_7s{JTwD@9RGtG~e2kW~+nr$bPkxI!F zDM?!p+RU^?Lt}7AGp%YsY2(dU1UPfZ_$~I^Z_7d{I~z*7vZR&TlXmiYJ9*JQ45NUZ zip;I{ZMNORRG9~mcA7L*d%#!mTyu)vm@bWBGh6LK!2a}x;=9_H4goW>j0QA=^)j zH*wgbvidv#cT@VuQY_v6hkJj0L_o7GLs1?s=b#PGh5HeuRa%rIL7Qs;?aG1NwK%b) zwm8MyYG2vsBSP!ePTNbY&1zUr({EO%G>>7Pxvf)q$?V#C8q*++QdD=#c%9`zWq5ew zW@LBWHCi^yK8!_0n}w{e`_w^m7;dr1N-eWcL`p9!-#Sz>=C1#f-kI$*^S`*I)0W31 z5lX1f9AtM;BYkn3lz=AyHS?qq>@`%}OJ!FJ>#oqsTcnxdsY}Xtr|K@_?#aBV66-G0 zJaCH_FVehQ@s;uV_pMSIt7v_3U;_3DV(woG&5A#iZw1;89-R%K`Gbe9FEz5fz#|Pl z6gn4mecx?O_MXS$u&!!e+VqcyK8kw5G7!0xZ<=g4>cM~PV*MPLny;H|Y~7yy7>p%C z&X^_}=9B!#U_~&wyg?(TXMtUYDgLFk$EE^PW|aL)t3&-PSJqNj*JQgF#5%cze!g7_(>I)8O47SEx<&(8 z1x~-aDQzBxS989iW%H!8StTpmdq@}!aTfySEFqI51Mob+4Y0ExgUw;_b%L=l@&Joi zN8)@b#;4(2tK*%52;i!Lvz(&|^QD1e+mEztz7*~j0h%b_bmkIzcD@wmUIRb~14KZ7 zs3lhl3d_NCHw#dIK!q$N(c)pvW7FUtTkWHp;9MzC8*~n5L61pc##2Bxe1O#m#>5nJ zDf82UCz~)E|Dvx*I>k1t@RCLq04iz?2?WyTlJJ$=(6fzwu zE?BEoJwDfMt^M0^K(_1#v-033Il?#>=-{dja9DK-jDQbyM=+am-UN^G-GgR??N^I< zZ`6x}031X`+L$FDx;%wW+^2r+e0h^p zzPXcV!&0Tu;|D2C{nS&OktL2(oE%Ysbvb@vD7wUPCy75@cU`?<6x)m8VzYX~D88G4 z`_$ZDJ*%12i=zk#9z;qnj;_8chou)s2@sqkqnm?|d>6jgs$5FSEOEM&)b(zw)1@Sn z=*aJr8kXQ#@#t!?J)v}+P4`G)+T6NU?<0tP*-?ne;zg zN-EQ-my$|LluJns%cLdxNKAb4%>*RS>pGtw^1VdpT*L9Vvk)!q)3z6-gPUp6}XxvFX=2^Owu zCK5=MWnVW-u7gF?{iLXxDLAL7nu*{Hyzw8zrd7PJapzXPU?4|g-tiueBIK=9c1n1u z%C~hW>Y2ZOqUYtLSo9@RS#qEM7ep3ATzaDC-}cxK&NB|t|l#5D=A7^^lezCS9Jvy{&`)weG+|HwPe{LbM2Ps zOF*&PCtc?pT{c_kS8u|^cl(wZj#980YI>Pvy4|vcTf$IMV9~GOp4cZ5JTpxdt;!vx zr5k$QQHt25A|C98hzEk-QChvB=N+Ytauu<;8^I?k&Cj(ew~)#={L39B0c>nIt2@N8 z>H5mNCM;I+Qps(+RG#a$%CM?;lyYcK2}V|D?`g7MOgi@;ht&$GdPk`l&|Y_x@*z|v z3-%mJ815)(FNU>~ZJWnnTn|z#`dsv~YJJK<->u$K;x=9bvx-~j$ET34?trO;bskW~ zr&Od2ZskMAZeVn`wHj8H>%cYUJzvV@HWp>Ee7d4I2q!7IqHbCJ3NsbAS^ZicQLeCA z8XZzZxH2ht(CGJ7c`kQbi@L21uy(g?yi5oeJCv(0^&1>lUpON6cNKBD7s6~uwDm${ z|E6;2HYzHDT+FIAZfmHjjXM(-u8q427Q2ohK3)QEILjed64HX{FmIV6LR#pB zXOz=e{KimmSDW%GylLaVTvE#DRIvlPv8slk=q`Sn+TWp#TN~Ti=D4NAmF&T5E=R&f z$3TyVx%2xrqEGtq^C6lY2;hSzaANpFrz!Uv9WIptJ zYco6s7lbL z5@e^Vvdo1DxM2kqL`k%4mlUVZS>9qZE4P(C*d@)@)H+FUN|iwLOQDs!r8q42eN`b1 z)8-8BRPH7nhh;a^jni^~vE%Z_ZeULXcrVjIK2V{;n>pzWt>YhUnH`L`^BEW_AQ%_( z3iqAV>q*UM#nvd-lg2!c<&x;XuiI*rRkNp`$Eum7iGF(?3&43eBKZP+l_3XG?SCab zO?^SSORP1pJ4(rXl?N-N*u|zjtseg5Q;7wfq(+)nDe?Eu_~7Z{oF?UQsM06d1*Htf zIe`O*p!-~hM6P*~0$)@&%-MiVo~?2;_uw$OzN0b(ZFVs5KIh_r7Uf#ftj+vdk~ZZ4 z*MK)wf9UFUEKMpGi(Zn3i3be)ev&vBhhK5=NG#LR^DkrZ?Xnfm$MTCsJF2kId|a>G zQ<^I(_mt+~-Y>hSRNHvnwoUOa^%Zz`Qm5QMvf8fqxTjRm#I)P-U%1Mh4H`CSElr-m=5dkf*{0PQZy%6gg)rf73MzfRNH9iSuEY4!?HS3gt*`#?fA+`OuNRkC86eLR+dq8vhyhbfmWM!(OCq+f-6gNiToONrx(hG3V%Y z+oNnz*PC45l%Ou~g?>7!V0W;PWbB1?*FD#5gV-gm&$mFS9)ikN_(y8b_71A-mFu=I zS?cOa>DjkHTJwo2RjEQcirsfI>rJsOwqrEv5ca9LYO(4A5>}(*559LmdP$=%8`NUk zuPn7a@(%W;g@H_k*er5CD7hGf%of`Ns7y?6*ocGDlls$G+o_=$ccH1fa1gsDMFU%G z*A?!x8mC3r`iF33%N?>Mm(rFRCFl7elwuWrQ#YJv{LXDH%6b00Qc8T+sTMYuw%8Kb zTzw^C`7V}oS4^ez?@D**O+#C3x3CSI0CXnOc)j&S$NIGHEw-b@&v6{F56|>-$+5AU zebBMl-24>Z{9?;iJJ@bH8|-K{k>)tY$b1vyXxAa^ z?cnJwzNsthbnLA)yu$+JyJ&o?w(3|D{X9$>-Y*A;Ufa6)$C_+T+qzQ3TTRNUAJ^f1 z8(saueSkjud90Tx;mP_< zTO2#QOrN8^Vqd%MJ>}}%fLdvczUVb5gjSw@Ev}U;`s!DiPNXoadmuH`;w;F;1MLu( z4}!Daa9Hc!bleDwf1O$RYMjdf`hson=0ca~5v9-T; zt;^wynlLhApjsoIWTlwLaDS8Y4z9in`SBmNbBjm5PqL-5m)JHZcTfHVnX_=K(Y*@bA?>=74+(WytZ>x`ef*l;;-EQ-zXz;C@m5tkzWy;3woHAwO zwt5TSxD`wGQp_nVfYxl|`?g}i7FzkavWwy(20h0&ZN-H|V?Rd|G-oqIPSBTPbso2A z8*y~>yD@0m>ye~u^N4_kl3n_9ibh=4t+LSGL@%0V&N!r{}Zb?_j%259vRJUutmMq$gC)(-R zz3%CJ6J1+^Wadm=D!1MYZ}ZuXu!)AA#(4Bcjrw{T`LM--AHrnstJ%S} zZ)b|lYxvHsc<6b0=3C_1fi>;6+t_ZP5B>QqlFzzY*}KhM&G&A_oIUJ2mT%pPC41<` z8Dv-$kZk8Rse)F1hdi-9){e>Ro=MV8;@Mpkau%qz$7vq>x;(4w-R9!8LAH16x5rUF zyLQ>F+KOkI_~xy)c^4MW^inWYe~+!(!re`D)elpF2!Q$4ZIK_gxubW}(jTNd#Iw8U ziyyGJ8dRZ@F>X%AbL-UZCfjrxeqIWvpMS)mkc&H-$Y$zyx3&uw?yU}%Zg2PPppJ9! z7R7YlPtr8)k}{R7^eL6BVj@oClu^uiX{Oe+6Kj3G{chH#kYdp<+|dL*ba+lVh`jy! zC2BVTG2O49BX)fryUQ1F zAWlFEy`_wAAGjb**Js0RQ{2BYckVMySW<3eBdnYLi{0UfXPayvEBGV-1-=+=m4Emz z(sa?3M`=O*hUjqAuy4<^d&hC+zlzOdD@*CmU(}siHXthPqi)r{S<1F*nQpcjzvARn z##UuFlXZuha(e7{DN%oVX}fK;k^p-euyN6_nJ)cm-+4*d$Q%j!;|RP=A^H|fN`Kn$ zq%-9Pdha(03ar%UsCAvTdzfgorKJ5GeZ2*pE!#*fortbuBdz=$zA~i(-M)?yt2fc% zizx1wOO)>l)qQ}w)m_}`4Yc_Znmd>EwCfLitxwRIKTu{Z>&WL4zS$cUeARm8Te?x* z!DZ(v*DE`?^`%W{0{9N@^gq!gl%Kk0-@%P_Sck+9Xz8)d7>oGSmtipkU-n}=v}^}= zUzxhK#NPZEQigG%^X4SydhlPk9(3j^XuI|gE=zFF4ObSHdvL3=sbwKFZ5c^crf$@V zq8Iv?G*X`rH;QWtw#AqKg+qc#qiFwMXolyGqDy}vt%^rc_!YR%j-q*2SRb8Co3G&f zPkb`H$-ddibOvyJQL+_%8P|sxbQLH4=ZvPbt5TF$IGUDT#qqbCR62T98t7A=YPHRP zRP4ugLj5rRy_iZjt|D{gG^_2f(nd|U;+6n=!rcnq*oWziRSGd=KWw#a=|f)(!>G^H zh_lKiMKrBZTCFczW3?TkHy%PH{%Vx^8%*o0Hj|bPAH&FX*fne^HIPrL$&fnHc#6oo~iDj+8I07;f|P9d}=sLiMNMCf1Aj(TmqnGlg%c zH!!FS0wG_6HiXOPcYZ4n0A{2b2dUT=}6=uiJ-g?>uj$L6*os?cNoOe?#X z&|tNtEAX~fDNB@pr3r0PoOZ5fr_;O16@m0p8>+>jaO!B2`1^2dpzWUX!Zn)@8&B7j zP9gc{e*ScGyAjFShkX_T?&rR1jSee$bnDrBo`Vi(%mL9Jr-_$ zfHO@Y%@LipWw0~6nB(fPqtZPhN`MG<#VTyao>hvVUNBa?SNPMe4k=1s2;6vj;~Dp1 zGuyUzI1UEbSt~cU_JA?gY&t(KqmguIfkH6y3f{w$g`PlD|(L zXt2)2f2`#SLS8L-l&*A1A*=k5PN=&4$MTVBfhmIrT)6|EzD#9$AC$8wz%hCkm7d8^ z1Xx2zQxEye0ILSfIZxQZk08jwc-W79@yJVn;O7KP0k95)Cfxg3s+^jt_3tOqiN7U( zmka=z7AD&CG)~oV%`RCo1>BJ0#Eb4U?S^t4X$BsPbSuDq`2djW^0v~mK=^0j8cGBJ ztYor~V_{B8fYI_@?t^>_%dhol+8H{t{2IG78!Vpvh|+90a2Iswnk`E?Yxtr~x>LOT z!FE@9hdzGSHQPjLBzM2_7fnnvYIRU%CbYUR0aJp+`uD3xsZUy)j z;C01YX}(4tEbfb^4H`LWvhepcMK-WIX6r z09F%EH#BmBe`z8fI020PvSE$`cM9~gl@nu2L^)nO8&A7L*+*}NP}A6AfES$- z`dKTFq&lsvbE`w$=1)qW<?`*6pS1FT!8Q0yOQ@l$njqL^)<2X%7P&@uxy6%Z2p zu^gPsEP&ag%wYL2g$%~$ws*^SHTO756$|v`#W=`|FZ(eT7Bd&nIae#zd>rUS$FflX zopUuU0w@|V+yYS*f$%MjC9^wh=|JgRwh`&&0l2`j=OB)@X4kmuqyivZ=BNaI+vs;j zP~${!90YS_btr9Zt4OBdYUeE4Z;%u8xez;^G;9%D z-$xGB=Pzouy{vR&}H<0mVza$tYLEB>5+((`{`S{~a_M83Y z1?oXDmfu~gn|K9d^=ZBe&jP$`?LX-k0)B2CMY+f^Hy?t0tVLve&i=(OY5rIL*vq56 z>6w2fJhsXzI1ir|AsmSLMCJxf1btUUhi$#ObnYRCh}k7z| z7JA4LqHY~M?;)pYO?$4h^J~F7B-sVG@-BGDp_DyRGW(>sV+93~W<+{rP55SQ_J>Mr_eW{t+I04DBtn-bH?de4qD7sWH0$A6z zsTV;kU~_Q6UPk0j4xp7X@>P6o7Z*xMD>)LsNkUaZO! zYlJ*S8+uX%A(68-U_&oh*(~JmF#EJB`7xDTg*WNDalLD5Nn>Mm0t4AtUjCTm*sC|x+Vm}j_)mS}E zFv$bmBmaBNc9@}??dYv0IaJiSGjs^mnPjtA5J=Zd^5B%%5mN*q&|Rl1K^n2KLIg}D zCZZS}n)kr%&!h!c=LtkEm z%`7I6awPL0ayupZAmJm|(>x!vv`e1pP>y0nZ>RM>GJiUpYj<2>Y*m6x*-k@zWq-2z zphq)%w(>EC&a$0sK602_Wr!+S1}6)4%fi!KENyg|oWh^-e39`*cob|LgJx}~Rlahn zm^p}L{6KBpX0_bp0b4VOJpAN=8Z&+1%POR&tdm$__QUI2oO=%E4t8Y$TxJY1Z3cr@ zo~Qbf0_r)d={$g9eK;BXjT+|4q*rwon{3wYbatxlu zPY;&+Q}(NPspKfl3z2<%VvkuJS{zy3%w%lGXaggktB|v3`C33{9~Ro9m2%9g%s<%x zJH!kMKFe1#&&+&+NrG8;jK+o{rUl38zEF9Bco;*PqWaDMtlay?h6U2g( zbe|b?4JYY&vpgZH@Dr;o82s#K548j^`_Re^ILm^vPslS2DOU|#IW13-{b)v*JVm_t z3GE7l|L&jCr@)JTpVE~uIa$p5l%m4np7SY93zq}*<)2z@&(fYF{k*6sT%M!vf;&KY z-=;lWepFxd8JmIQy_-NP>n|6I@u$dRh&-9*M#wIr{5dU-Kp+{P)3yjXCg8wnt8F=i zVn0?L>tW2_T5YZdI{ym>ca0J9O@`VZthN>d?LUU$*Wv+kh@t3$)iy$_Q0y5Xj~16S z(D?z#vg|bF;?J@j(#vuPSn@JjRomuyz%HgNS=~# z`gf}>4ME#0le|KyOe`HYp~^G^@51o-vC3EhnDuwsF-Q(sY`)lyWAvwi3j&Ol5cXrR zi-1J}=FTAstP8M+Uc53&qO*Ujp^gA7=pqF~$^lW9Ui3M@r8vP@{w@J53HLD~*0pA1wdV2g}|RFc|rpd5O{nqde7IqGf~SACUuuqg#*@;ndn7#|{t$apDYop}Q zfZWSg-rTdAI2!@5mg_jolFM{B3T34HGF^&-U?-uWbBH`sU-_5SwnBMNv~Y;*CtCla z9Yf?~edQG^uDPXugwoMCL>{3py~-*-U$RS&#$bJ+)rxz5-2GUzoT#-lqAHHW+mYW! z%YlZnMyqYAfp!f+7cLEzM~RzSp=1)lo^7RN`1&-oTKNPKl5r8)P(f&;mxe+_QyYB^ znt=Q^D?hW%qH-6a!t&mPw8n_SBL=NibsG(gk&}HEws*G-tQ-}BCbyj)jFCh1`M_l; zD^~|%h2NGg4mK?*QN>J{A>%(9!Z#@gxo`jYgVhVtsnFyi80=p^y}mVpA%OO+iV` zOr>Qhz_+E+{uCC|G&;}RHE9%*itn5;G>?5<#?r1-^g0z|>9ipfrs*_!jC`wDeG9!b1`~(6Tj=94a+H7b zEsZuaQiT0j>J&1|t&O%$b~Fq(s4a4mSaloCv&g$d=ux`CzB^aYu5^^Q+=sCjiB!ye zxDng4{OCZ@Io#!~g!>O=3v|_3d4?GA7=1k!G9G%2T*t8*{20ZILmXDDqwfB@$nX9b-vI+rl` zzSZ<<1`B94eUSk{g<={wUS6s%E^fr#O%g!ynJb}ji#Kzi1%rCAdo zYtlN}JOQn-WnCj)oaP6yu1$~w#1-qvW1>9MU-v}gKL%C;V9IgSsD_e%qU!;(Prb~D zQ3lMp68dx^Bz1X$u1u6e{3GFo^Kxl9Xd)PlzZx(UHhXu+nljd!GeLM4i6-t5q!okl z0niilNG6(_6;IIqOeFTnGY8LS%HbL+t#ZrQFm z)7EZS#`CgZDU$^maQiO@u;bh1tzq7)PHk7f_4wX^ao-^eK`>D;X)v>3mcSIjY=$X^ z*#~nN<{XR_#z3+V022$72{Q*~8O&;!9WYfeM`2FGG{D?|@!Tm319!@+galY-!Yqb) z1ZEq|^Ds3qU%=GEbilYjjrhVu!%Tyj3zG-)2+RhUa+v)vCt-erxdtOXgUGV!2&&on1Od3oM4EyEcy9}lfW)sX#m@1eWnBy>K zU@pNl!-(awV1fyOiGfLivA|4*nG3TRCLiXJJp5Y+QwmcKQwg&VrUvFH%%?DCU>abq zz;wXqo`ZleK`>D;@i1vH6JVyn%z?>;Sqf7Cvl3<{p%$ER4Ki?7_#Y+*WbA+Yah;Wj9gGbtBI^(3zFG(d0YO=~uhcQuY-* zXaoCV&Foct4f4cv;Ukgp$7yyflx3G(w{&3x%nqY5g2p5p-40G%D6i@llAk(7aGgIt zBWL=|`B{^0%9%f35MBHJiRqJGTa|jSVYwWjL1^#XFMlPnP``Nq!&P#lt_S2TqTqh; z$p__l4a7Kj>>)-0d3HP^4;N3k(ekhZ4@vHKokW!Cy zzQkr5CI|xx?#UN4^*>`$owOE{6AV8sdu3lX483J9*0bt8sA#Vo#J;;29N&X`Y|fx5xD+c0$q7RQA%V3QmT|D zKxt+QW9|Vs^mY)BU9@7+oevZ&nt$iw1@rUoyZ5g97ThCn(bvI+@6(Jc*E5|@q(z->UA%Kx8?fd$I@gmfypE;w)t=O+8sjW{2Umj| z--*>s22WaEjTs=m8>{6z#dt5WGCaN>Zva2di;~_z47X#6;tjy@-NoQ_UUZVV@%@dt z+q_7A6LfJVn)4>$_&)e1;J2Ho;!T8$?@{JnW1`CpkFV=nkiNo{E{tMvUZiVHg!C`7 zl-h-VUm^WQSD0ufsKj~`6}|;7e4kKtJo9B3Gw>qpPmAn3>Z=v0k7!CY&n{y_6x59%5SFuK-{;@-uqUG%4W-o@~9tv@~Y zF2>K>{psCzG2mSmNI$(R`vxovOc$_%Dx~Z{&DxCGEeO+wBF9Pt$>Tjl5Z~zc<~Kg0Tvjy~S(hv$ejOl%K2rW7+r<#ROrR@_J ziFb{2F4apB!_h)09X$-L>`=OV7{1`^`k_2tyu(a0K4g{gn(8 zUA4&>h>9T-LfC;RQ&kA^C$XwOMIMzyM^@Q6TE*lik;^fR!w%&6&LH@W`3*_MTGcVv z!>RD7Tq4#+kl~p8i1>2^tv&|fg#q-^F*M;L2hi8Yo_lcj+KHcmiSK`_l<|WY|ZD zhtjP)@X-9bm)%`3|IT}t6)aj&Fn_op_A>~PG~%TEmN+_+E}oRl3DYCfg=K1`&}$1G z$>zmTuZ=}(fLT0i3F<)d032etK}n9ek(BlcqVsShJ^G0pIWQ3fzoV9nnWhx@`<0HV zVx=%=$qsrH``Q@HKbDB5}oCoq1AqC=-pO7ugh{uEZ`CJv#_Q`jQRA42J$ z%eROR525nUACHDSGhwiAu(5qr7CDqB9V(m~` zT_@ip)(xfa>QJichf+r!^K>XBekG@*xyC4M3M;z$t%6~A5Nlb)tqaiTo(6tcY8Iy8sa^G4#e)s14aM^xv=KMdFqin)Ee>Rk6dU@M|=VmSJ?_YdKdu zIE)5=gEsK%VKnUM=GTd7ugjnwT9+Yra8(E{LW5AT&K1n=br@ zV7W-F@twSE7@hkD&FGX^YWW61Rm9TZ)AACrE0&%*4bHy9>F{aUKPGs1Z_ZEP*K=8T zW9Js9d>0>Z5wb4FlKxwklEW$HTZsMiaC-P#dGMl_;78>QALZpnZn75PH0uwo15FWF$yBO^3TY%yPoQ6}MGbq^g!)eqR1f3m6#b;0g zZ;zul&dC0z<#D~E;T1>c&&Ym*B7q4)5q|16RXFZDWJEcR1CD#28b`t3q3J1&qbc8^ zE!`VOcQZHM=cn)F`x5Fw_`+PCzN~X&$*g_A-5^YE0fLqI!wiX0qf$9pCS_?y(3rF6 zJ-&`RIQy)8QiH+#!LT3XSQ8u7-*iRJ6SGIqkt^~hKN^7!XlssPiVs%NP`tETvkk(? z-$u})tH>!cZt-4~i^RL)$?#n?%1|m-EF@Ni?TLo;UeFN$Elz7Wy>#VofllzY6JF zmm)d|tAOdm5d9Ru@qD5nB$NZj()2eK_7E^LMKtRPXOnic$^+#F5U^|#rt7=}!D|#H zw4#m4A4Rvc%Im~xyvWuHi9Z-c+BSJW(4V8y1-1{Wc}0v0RRf=w2f#S*WXfnmt_(}2 z2W$%q zBk`$G^j8~NtD-f*dgYyU8-Qi;pJF>cUk(srQCq>rXy9oXNP zHJWC3$mUtMkM1R%1OSt+IILT`K){@(o5G~4M_6oIToa*v3$$Fi87!>C7n14o4mS82 zO~y|73GvuyD({p7qmIEFK3N>2c{f~@ZUf^;{Xz{?n9?6U|23K}fL_G+MyKpIu+5H5 z_(2sU9PF8OnV!8lA@ma_dJW4>6Ivi%R^ z@IG>Cx-jli3WaHm;lthF*vkqWZyZ=+F*GX)vmyoICM&|yYfDj0g(<-i*fUL|0*%p} zvMDWHm;|DUGXXRfAY=Ce@)=6+3t(f71R78w@naQe2f+KE)2L2kGzH%PYD9=VU`N*H z!av;@(ul^<;*2qrCK?~}X&95PczHiUMDdt5038UI%I%LJSAImrXGpbd z9bib-7%-%e>In=h&_coh*jO?C9t29oLt5}yB_yR$lg^0sgEaEd8^guE7E0C|SBo1h zbXaeU5_enZlHM3RD#Bu~3E4_YE1f8$)c|uzt;$zzyOZ|_pO2---Hbj_48wl6JO+P02cJ6} zn)z**BqZ+!$lil|KbHPB7=0tpgXALfdSP;YH~Q8#fF~p}kGMd>I7;bb9OfT2E?o$R zSMeAKX}6-gM43nT6g!TJ`yd&T#!*!t{!jx zj3B@>jOoh3fouJup00a~4&YM1i_j;aQqkcis+2Q{$sd{nTzohC#c+XRH z<3)JiBUPKnDX9w0lY-e55|s8xRWE?mRGkX}%^4K!Y77=9X3!K@BQ6(Z&_-9pczy=G z=V}ZQS7p!-!28Yz8*3<7wbNuG&3AygG=n_cj6)~v1(HYhosu|2*6!>bSvy=~8PAH) zFpN3Jv+^^W4L(22;L#k^qwstPk9jl?z6+1Xv%<5A5r39Jhuw_nV%T`nxEp-}hK^Sv z~ag^+FoWd#yfOY+h0r6MCABN)2f>Pxdre%R3bV9mN!aSCA!*POdJgXyxMQ9v` zOrQ`CqmOuL0*<;GEw?m-5G|3Q3Di9c!erLkXlC)YhN0B9W-CLnwnj5cNVNg3v^29} zV=c|wK=){M6PHe)FFlMS{3}7>J4nGk02)3P7ZUv^91N6t;LpCI@zy61s{y!-h~7t5;Iz_QaUn)2@jEPBQyTMlzF=uodmy<_vDH=H!n8(%)MU!g;DP7;HMd zmQe~qaLGivDa^P~ES*U2h8d>^JP&XkOY3K=P%tC!K?`!vYS6ttk;21`gT(rYG$q^^ zI-nVJYaHHIIlN_YK^&fk1kDp^OSsWzn2?z+yyhTfkr0F-{_xlh2*3r+&d5|ayAV#8 zZzi1%N5eBVlMMZhp{cV#)2=Y<*vL|dP5>mr2Qz%+Ad8gvU>J*$CSC}BW>UIv6Z3Hp zOUMP8bVq;Gz~F7(GRPDmyI2wWiMG?^bPF0^v?SbRlzUt;G2IL%e30+p>7l! z=8bnS{x-Uc1w(0nD|(uuy;Rz0EYxQsY!_L=GF(aDDwaFOb z{|pcjO)i24NeB_}`vH)h*IY=`<`e9Pw=0;#2|XMT)FKO*{R+5U>x6w1kbLfSxGBGf zw*xS@h~RwT-Vqa>dCGvPLV#Z#_VT9OJth~wI2R6a^7k`9@~_dpCPWV3x+dcpZS`tb z+Wn9(l$oFMbn$!8O%MQa;`tenifr5_G=^(WgI061DVWUHjXLr4Y8rUmI6<4y<{`~m`cP^ekd>Te&45AfONL;Q1!ivxPIzhOv z2jqKHh<6;27`Au_x?(@(4~xt+Y557)>lKH~IQ&Gh^IH zWA;%CJ5KoX!Y=G%RV75vI*S@Ib{IqP_V}v5jl=bo2*88FE*pL5v%ih~#cUl}|2BpU zDL|~)fk@WvFe3=h0Wzlt$g_a#=x>jfUB3G8?JGPL@wOlKjBs-Vq8UQQEx!I@ks_JKg@$N6`)dx-bbL&u zJ!D}s$lw1@nSWqk2V~v=XFres1M)o}g4@h5B#4^m-y160&S%OJRHzXqz z1#Vc3GiVct>i1Ee)-%NaZ*CWz816PBXJY!&SA{;o{s$F@6Iwtes6T>-RX#yu`5(pM zg#HSU>SprL!S4Ym=GD#4t#|<-`8V~Y;i+ip(+a&@{8&{0#K{LY$wIAb3Jq&$v6Sltll@!L$^ewQ3Td#^YXSyufHSu|cDVUKgWa{}xI zBo;MH@dS(Cr#!v=n;by9Cke>F(zjh{{^#g(HYyIMX#5CBeFZuy*7IgyI17gpx(X2Y z*;Ma^@?Q(P%OaY#))X++-i|ySr{tIxF;Uv#y*(gj!SlTXVy~vBkvfXlVd%6fX?d5? zTWM2j44x5UsgBMYJj3;sF>Zo}UYq3Ut28gg_TEOV#JO}&AJ0&|0R=LHw!+#c3f4kN zpuG>7g7v%MIL_hvMp(NPYwlnS*(uBg)HSf?$ttxgiY!!Z0j|Fj*2{{u4%P^I15iUc zN^qW$a?zL@3Sh4^l4Xf!NS|8R>x}{}_`@ee7mZ;OrT6vhFMf(=;6nYvsid!`r#E{i z!N4+GuqQ!VoPg^Cz^Atw`&0gG^o&MV&r~lb%Efo*Edq~;7Pxx$*ZvE`b7sFjWOen7 z&_Evr!ZIY5AUW~Y+**?tWxIL07}i0a(vSHNEb0jCMJJp~P+!!*+A3$ra6k$-?HJ@4 zk~{Ao$aR2J^dR34NcP9h9tfzxLXSZ57^DYHH6V2xSUCzYoMhNVO8KgX-Li=CmwEb- zb&JWx&~F%;)!9_)?it=I`sM&nvmqI1M9$m~neYhgh#cNO^!48wtLt+DZbXf~T7dCK zGaL|{wm$9|YzV_RKKo;;W?U=Sm>yhX>O8&ainnK94+h}EvWhvC!VdZPqkdlf)7W2= zO=CQeuN8ijEB(7bal;XgA6bEhHYmmoE zc_9|PMy1(a{WaZQxb&F{d~GmZ&&NJ0jMK_y|O>dAVJQM4S?joZLiY*Uiw&S z_IXkDSu@EuSUTqLnWe+Mq}l7{-RDQeb6R!4JJ`_3{iV%D#I=^k)$KB7LOP_MR)cz! z>*?Lch>BmQ3OghM4z`sdG71>1hXG;@whQ||i)L8P{h^8!bjVL|CYC@UeP6PBNn!E6 zfm9UasY7Oc)oKhS%U?zvbVjFop_jyyO9$fzMsHNI1<8iCs0!jb@xQd2fwzF@TeKp-0~EBOZZDTD)JIibq|fmj@^lx@5y<0#uEdfWdWy#g1qhIuPe?INEL zg{_ve^=Say`l3<|h71`c2)SX-MKB2v!2$W7Yojy~gzyKg4$IYap8e8O4*wVsmq$uH zy$vsNFKI&{%7pMbn=plIyL<)G_?W!u5f4xIe{0p>1yhET_@ae#hV=Oji2QFwmLA?z z8-(61D49Wcf$1|9_EKl8|5^nCIqj`u4ImXgXqps=6V2e!s0Yq8tL7^ZCz?_~^7lEn z4|@S&D=OWM+h>5dNY0QefMoaJ@<~Cl@o=Vz2SnF{YnC1$`RI-i3^Pl(RSB1cgw;tv zHf^R-U=6>+ZczyRQ<>G7Z~`C|D&Y#)^A*B<-0DpDBOnJ?0E#o>gm1H^h<;g0HK;SMMC zC_rilDNnUQ>T-0mC)O*+QmDkY8w2-zy-GH!RKtOTT1 zp-lM^_PP+~x?=_8Vt{i-hKxnl_JB+Qq)PE2>M_`b9zK*Zh}qfC7a3#;Jvtl5pIX{sFCnWt0_n0-KPL7D7*Aw5!Uan zJnrezrwkC3%WjC_2q3kCN$&6Y{}A>za8ix`|Nrc^GqWi*?d?pp+ioREvMCA4Mo3Z< zQIeX{okSBwy4#7Q=w>(R3SlEu?k19uY)ZmnqY_dRAru=SB>(4iU1#cj?C1OY_jr7K zp6}QDecfN@I%m$g_ME15HlMC5rIU{*x$g+Bs(jV28KviRMbB50HMh}RpvpCOgA;5p zYz|L^_gVHnr*&1<5V@N>)!y|vh@+dmvQayg_RAsx71Z#dn!}?0YU;B%tX{~keo6_&hUV_cf}LL};#Zo5GFN3vK`R zHRIWM`E!NhGdS)C!UYcBsX5c?PiqdSDjoANoTzX42pn4IZ+E6rtdN;map2ffJRsz|Xv z|4&WmxVMr;(@CDoujY_{H>v#Z%INjQyHBq#s`oEBnfm9;Yb2{kQEShlz{5oHAmt1flsm(@^4phR4cDfRZ?f{NMW*sy%krNlm2*)%uAIkT>p9sI=dZtyAEe6(YMCmpy?;WPFxK83 zsWX7*X4l%gCN1I8`}MPyhN?}|jQ@4Doa*tbU?)zP7ZJ-W<=dT{Fo$69s)GoQ`X#WP zi2Ar_ruMAO%<-amc-cGmr&RGJ8EL79+Nw%|eQR-)vRvsLx5G>TwK9^E=lcUAa*67A z9zmh&^cbrFn%l#k-&72)9f8fTs{c~?;->~2~v*JKLch2)Yws(*{V&1 z-v$*ZjDRXT!mkA#@BdfF@J@vj&!=NL4$?=Qy>ySkt+Nf+S~`eln2+X!RQTe|bnhlS z#cJBc+}!#REV4nqj0k5%hugrN9PR8--W8TsD3;U4PXjk!&{Pk>>AzV+Zp zC*lj3&mrrG!(cay*@Ma31{Z-to#5_pOI3JhCZ~s98Ff=*EA8FZLbav~y}tl=>y!AE zqPDz~(a2fOQtnnwF389(DR8YjZxXtXn#<1bEwBRf zFK-BwrNlMetBQ?>|0E03E0q10RIVmj!Y7Zdn{`I@WTj_oguTsr;X<<53;tO4j&#E>;LQ9@7aWLillI2+Cepg<>d&T*{*;hfnmBh-7P#vTDhU zcB4c%za7syeJCw+#hi*#;fm>lqF>v0Jk@v<{R+wB%0iU#H1^ybm)=0y>I&M0GTo&d zMOold@`o{%T}o#Zy*m-nLrwYDA7#I*7bl=h(5dKuCuk8;!qu{MI+?4}cA^|{DSx4) zxs>2=iucRnyP&jor!^2xQ~THC{?bVFTs(vi%IB|buLQGi5a0~ zMhL0gbxI#yLz#*acEv12@wmqIC6uCLS3CdrRa4B{ zFWAWUfi7^l8g&VAf5Hh~OAgo1xgps`T9k6SD(u7!+Vc@(htzf*d_7#=Q2nKOA{=h0 z^1E>%s9;+=ov=}g$CG1PFaNWen7z(<;1{?etnMYPui+>vdWDK^%*^+7hbw!l&X=N( zhZDV3tPf|Q=Qm`g`^phU_qKuWz)PLLgK*r@8{NnSox>NxF|S&oGaCaJ@LqY%k7(U; z?e}4GY^bs4WSi^U-%-lbY^tWCJ**OHV0Ti5;R=VRYQ2{E)#6WcoQ@9xZ8U^_Uz-fZz%S@R5kT7PGsl%> zkLn$TJ38FrX1yv{{ZjZyJr(72+T z+50HnFe25es5kePUo@Qj<)x2}+*`S5d`r#ViFbx!>8(a7uBZMAXPccTp$`qq)BYK^bARS+u4}h(cjr-Sc#dC8 zdnb^%b8YoO9=m47T0^*Zpp+M@&R02m1ojQfJtsC3R-pj}fK5Px)_D$tB z2-~Eu%*fB4Xjta`{ZwwWw8<$9UdL&z{9@^e<8FTRW44Wqaa4=@ZbT0^8N+>GiBO#b_3aN8~6|>5H)Q8#cl^97JELd&&R0EyoXO`UDrR& zGVMdGDqN*aYTKs|8H<^RuG~MM<=hF<;eC(jTQ6u9!9`9#_tNYA6#Q%_Zv=$*lh$^L=u<`C;uV zCy&x5Dn5{NAb01(j25;QZ zk^UE8I>b2qpJUJ!s&GU`p1-i%^nx*bBQX+8NS)+?+AG(V|`fhVF?Nl4IuZwtR*yNhpMWRo$o*2FjHMW^%#axwZ!bS_0NT)JJNN5 z?EW90lOBB4Dq_rbqr|qDjDjaTu36r7DnhAna=QkOY>~N5w~EMZ1xnF(Hn(ktWp00? zR6Dsfe}XgNcQUtLRuQ?4M@j6qxs@B1xoy&lliSa5#cq*XNyDW^5xEs>C0B3rFYu(A z-n_I7NB4hroq2xVDTU;^cmLNr3Szl8_xgDk074rZ}xS1^MBb2Bs z>)KDzi7jNz$u*RV^kc{>SJ3qY1zcHAtD!umGioZcegkFyovQWFjQm>PKIKupFVE!f zJPI??eD$AZrL`VkN6mxnPK3d5>$^+}-@S0PqrU{#b@ZL^-ogLZhDX15nHea33oxX5 z{;N0K+e6rY79IvntsKa4b{hs`WsR3H7$((a5IaoGQCxBSDE95Z8)%|RhjSGE4Kp$( z(wDzn4}o#`y1?OPs$c}`Lkx~KG3B z{g)y2WB+THue0-Y?1D4wBlhKRxMG5$A#QpV~hpc@dx|dGOi)DrccoxnizHDY{;!nyr=L zQhBC^@*YaySd3YKeH7^4Po^Kkq)t!QyIu2r-;;uq+|8pHhUU+idL17yujfqt>%Pl$ z9=yjM;{kOyBB-ZbE=ObVn&G25>C>8r(_+Tj|2_t_uxn?9?)YZB27byphx@N>vJujI*Q1X=_&OFN=U$4Ox4u1_F zw(PC@BDtt0QFb?v?5O76$W%HLsrqcc*)v-*7Nek@dq{B6owyXY|(Wn~A<296>HI$r}|C>**mrMRD&8-pi0ZPKvj?~rv zRZgy<^r)dsuAw};n%mv(tiPxcRQHwt7S^eTa!UBF zF;|Rl9r?KGe`*aST!K{U3L1|Rbv59z8p^vUVOPwrD4zCmwA;PO)k&DMBo6&QkEbun zVwW=E&6f1dx%TSN25ln9 z7D{Osna_q2q=4(>@uyDaI?UQ^AXz7w>_(Kht3s<$7P*FEJ4(e_vOh6J)Ye-l0Fvlc}blRJ(@b4V1Vm=VqI!kSm|7QA(LDG(qrT(H z4wNcaTeIG!8(l5yjS_KXJqe}Al}{Wc;99(YL5Y^QM!Lg$9$q3OTQ&xz+*SNil(?&_ zcc7GZl&Lb`Cu>(%pNCTF9z>M#j{Rj@UqUMCB$Wd?sI$!a%u0&CT@J@cl(1{aoi`mx`{*$@ls`;HtU|5s*qt*5Fy z>h!y^3VoG$6Hb+Xg*(~|8*V|i-R!*>ZfUD^3pn~oz4H0yg2fhBfUO@_6;t&tJF~F* z4kN`a7JN+k7Q2BH%);p#5BAX5P{oF3{dWVA-uGGmaYDFo=4jHttr9AQzy9=njabl5 zMPpPU^ohO*HtY|>T>h$FyUpJb`R~W(T2E|7{s4uGt>cQX?p9rZP2UaX(!*@z_72BL zsNPjPgex!0O7~C4=BmOtea~UU_o>opT-$Hgf!{k0&o-*?y>+yLxiqlZU4s!*^QQ4j zdM3!p-|A0c#6>Y1b)sZ32XrE*n4IkdCW|S?D0PY%1xJ&`JctoC#RN8k_VlZ}&YPmb z4KlLopZF<-o3pD{SF3~b_){@7&abv3ne3(QvWHn^&Mdk{y;4-9C9~&VRC{*O>Vs;}G!Dnjh`f>3j8E!U)U=J^`sc#- zq@si0wtvJr36b-Pex;4Af^UTm;|SEl`vY9w(Q>P=sahwS)eW#ciRi3$*m74R#&5Sh z@e>?A)%HZ&y&N^pj<;U$bcb((7liFidIc}GTzegCE_~F=(|7=)|7yYhwM?=3(cd&> zfx7QLj@!M&mHuY$f0tx^!;SMSxizK(O3bBPjnc!VOhW1BQp!9JatwhyR8H4mbT? zcc|U{aS3b&z!q^cW@9I-2jET)zX7*)_#3!~lU4m6^hB`5oeifs9D!q5s;HFHXzV3b z&Z}KgE;3ud{deOkty|09L)wZFu4lWl79GOFqaQgM8c5|96up^GUy0h7^(fV@m|FW; zrCc!=p(Ju-sySL|D3xs`NRezQjXJ;)>dNR}l!9CtqkbYIm(uoUVqAr7LWzWAs%xvs znfEvxZ$@=Bzc~sTNonRmvUVv=e<8+I>sL^!*m{3FqlW&eD}|9H#3Kq`vJpsc@{_^yn4 zpu~sBm>DS3T`_Ogi1`zxYOqYz?g+>5JjVZc@uQL4K~JFsZjj0Lp!9LIzR^Gbjky{n zI$WkIMJaa;(7R4d$?-W{>nJmJm`rvaN)K1E+iJwbQHn;&R6n9LcUAGEfBzd3L8;aa zWBxnS>S3hmu4LPiLC0bO9CG0ivarig4!Np$ca4||lv3CH`0JQbk}SS`N{Xk*HLf?K zl)C2mvKq=)C}G#QHcn0PRJrERRW+2kC;{8k$t|;+b&zY!YViW1YWHxU#9hbBZ8ek^ zwBqWaA5fyMIdl?l<0y58ti&GE5u||YxG%4vBv7KGW#<=o|Eok$id-v7c?~6jQk7gA zy67{Gr@$v9qeM`O3+4LtH%fV)RPOWBLj%>#ig!7!HEg}9CWn0}#glY(ImA=mSA);Z z&JK=9Pm0GLeWAprs?W(J7^$tNPma2Po+SUQh z()$uh_&)1Bzkz1y-GmY!rz&*X(=#+n@BJuMqmlTur8<@|W>#wFRriefj%`%fWP$~u(Z>uo{nx(gK zA)Rr#ob=sLcG^FyDj5w|_M>oJ0dq(^iQ>6YD!X({U#a9YCFTaH^hBw9tyJcq#KuUa z5~Z@gRO*y8BO_N(ca+L&WYBaSbCXooq4aQNbXdpSEMv}SPK>KzH==k($(W_hIkVMu z74{`TF<0wzP9nyYQBRbZtMxNbX1iMdwvLI)!qQq$Ay>?WEjY7zTtRmdRM*wAwJ0%H z>wia??TRTnnHX2=N1@DiRr(1X<7)j*l+*!ZRibll!-ZdFr1kQ&q=v5EI2%QOJN@|V zxCLdlE9M!L*s+-Z`)8JKFM*|XRn^Ox`QDDFu&AhyUgodLW`pqts?%z2sU~2y4jOLX zibILNI!5H{Xm}e^s=_5~R`HxpLSE*jGkFLuXk_`UB2rrRZifrhO2X?$ z+p;d0%YC{lWxl;DlXeD8<~vYpG8>w=2Kg3g;Urb`Dwzh`k&T$$^=|`zYGu0W`~*Krm*WeZs21zo|I~5y zEMIyiIxiyA`txu_z_9;Mn5%uY@J zviilE2dN&f6EhtSkFxr^TEE`Lr}OI2=*?EY94?C3`1@e)icfu#Jl}(>23xLuHfe8I zxRxw01*5|a&IC(`Y4pAW7O8(ysW$HSF{xI+xYY0m{aX3 z@NB2rZ)rVxyxKnhMS8`xiF&|{$?-OoA=I^P+5*NzwY?24CRgk04aQ{6%e2p_NtJdw zHLrh(UOY`<-kvaTyLpyDp99WzZ)z z(`>%?c86D~-f?btegFo0(Qli1{doBD6wl;dc9Z%BcomMp2YI7LPbv;Sa)|x;YcRU0 zJv#9@y;3|&!yZ+*DKpRi9tQ9IFow5(m`bX#E7^_y16Xd*Ke0D`+1nQ8{|=+y6^_y8 z3WmlpydPumhed! z?~JR-Mist9buRCl;@M#_t6vJw=;mnkJ#eu>UV^me{LE&lv1`=a*E5=i)HR%(ewObp zSdQZH`Bm?KxU8+PhKDM6><^QVQ7V2)RVxd5J?uVf2=|{T@n2N&tNa;DMt{vR?-nT0 zpPj_#Swkf5g;Mm3I{Fuvq@xVW#4(h_cPhLN?^46ky8(rFvWH*hns}#S>8(a7{YEQ# zd26h;yw0m}>s^}^lZ`tWrOL}v-k4ViUtkSUzkVo1bd7P}Y7OC@g%Yo0-NB{S5boDd zs()Mf3f1=v(3pH_j9z2Apj24rOoP(-9!mIklXAa7>8yPngJYei8I;Z*C{^^zKMcnR z!_qqiCH|Z5_zUzJJ!lnC>$q0*U2!$GM|LCs4sB-n)gC=N_E|$j|B4bzx@!$IhH%$I zN#I^`7L%vI8p3@VO3?v3c`h(4$M6c2(jT13Gt3$y@vSJ;KdA!#ye>4$uuS|AO5i}M zdHsCwd25KoZ=h8DWJ~_UuuQyHE6I`%TSFxF4`Kvx6MU!@b^ z*2h!m25SiS1eAnxxP|6gL%1J9DgVVu{fae&`#qFW#~u928p8b>O5}j5evK|WA);AU zydg>jiOoWAsx?I7vvdMFMSr>=c&Rmn`)ZV^GnO|RmU&M?sUY#RCH(!~JZpH4FEWp! z6#wfp^Q7=)YY6u{D2X3*e)?#>MXkS*U%0!DiOHk68m06vHEJzKoOiHhIr+0uifsjh ztqjWwo`Vwk(N2h-hNbs9l&bGi?JKk=S%can3toT{|1niP){bfZtTlxDO_bPvyO4cq zSmyl$O7urnp2i<@rVP<6y_qQS{rVkj{Gs$od~u?s5oAb5l!^nYpcVHNA+p}6mG5-|JsAh7B_}Z%e>f&4=R}=hRPcLS zgSLic8CRf$zqd8G-LUj3lmdA0W;QttwiSvdtSNGY1FEA{Ad%OjLA`J2zTZPQXfoJb2>35r&~j~FGh(T zRO{Yi^%-hd7Ci+eM&9cSSY8%dLnK~-5~xSCEc%CL%2UfN#O4NGJma`KFS!veFjSTVHK&9nct|lVcE7D zQR081s689A8Wol%&11)J93@dFd1rBkYWrelcIdrhVsfhQM)Ca03j@0_E&jHKs6@t% z3>{ZdTW+F-Ev+HkXQNd743b;f-{clBXuSl(2weKUQMqT-)W^9v12?*x?C34V3{70m21 zYlyO+M2Y)V!Fwd$Ygi`EAH%Sx`t4f`uCazlJP#%Ohf3U?ogaG1uSzaj58X}h>l!7#VRO+MlQfmnJbvgmRoKDZA564+U zxM!e*e^uQ-pbu9VmgDm-N=2rV_h;4+iT9#J0*?ETHH71uc zO6xi9PSz0a%e6w;W<42Z4dI@EQbgItU1|;CegdU{vd84pX)jwtxZgslIMKR;Tdg77 zd$jV0D*A|{sm?gfvR8^wB8OEhJ2O9Ym0{@}k5bGssRupykTpcsuc4G4Ha{B+KQk;7 z|B6zi&l6^1O)=k@3FeGXipeR_9wl*t>Rd(rx*L|W^IDYH?`m!itJnm?vWQZYz&~n* zPP@#o^uCT#lw;@phlXX&J5kF2NmlPA`=^J$9}|<+t8*KZ>WJ#Gg(8|6mPK?xDYiv~ z1{jt_OhGB&9AFOH1=bMV_Y{gJ#~!w!HP#UBw^1TTeQL}58F{BxTSK^WZm0f7ZDs7^ zv(r(cBpBRXC` z+Pe))?;?~i@8ZzQ>NAF=_f?em?|1J`Ub=DkFOp>;cQT^ z5i|31!_pg=NTq*Ot+tW&4#RTVe2G$>sUq6jWRhlCtpO;d0qcF#u=IX`QuLduByFg0 zvSyj{5R_fQEF0Z^D&xoksV_J}J*^=M zz8)pa;;h}lDb^6~`6z*OmA``yea^5fc>_vSZD;Y_Wet(|kWRq$Mw6rbcxg~#4Bspb-QP(JhTL2HP_+fX^Q|Ege}EG9 ztLW!UvA{IVGI39oDxdL&$_z{IM<}I!r(VtOG=|9f7L=%y^~;83;$KmCL7FM}{JS(u z?+mRpP&;+C9y2VxFQM=eMD5M3G%URdl(1U)X-1RKiPJ&XL31WbHIvT_@(^o?I^T;@ z;7q<1hGougqwr+X9FN}^mR`@@bk^JE#$B+BVfiz03QDQtebcb?9?^<<*H@F=85-px z@i0pKZS$(HPQMtI-mdr1RTs!@#UoHEx=3X{O1H3z9OZeq5Me91GKj}dw} zLbO@tf4`by{;qs;ZME)8KAAT1Z2hi)CM&ZV`M)6auir4~1XYYqCp2KV*lWe!1JK$JR* z=T7~s;cbNxR%K-9zXY6|)NjCu8{In-+-dP?FkKZUD1H;z-eTZh>TK~^aJI#1;2Mj| z!Mz53o54VT`xs>(+(~uWLvBaF(FT2i`*<+YU%w@yi5J}J1fLJ{-6$P=HQ3r>6zpel zCOF;V<6zw4Yv4|c+rV@+_$zYw32blCH(OWUs0H9`i=DtV7W;v`7KvoOv0&gjTlpDq zCpGPBI&Lu-y^hzvXY!5}hxb4)czww=i~Mn0HKlfzdJIQH}bLLwfE&?Gf(J2*hS~%h;E_X}1p6`KYV3CzP1NY` zGU}_ zS?mw8V?+ns3HGq~GC0BF4sfaJ@&olqxu5R7!Kp_RjE%qOZ z*i8I)VsyOKspz8^G1dEL;`uu>TCCB(9pwFxwkM8a@PJx}WGvFr23vq@EEa>+7W;!O z)!1rcZv!J1=YxwZE(5C!`qzQ!w{gs*@ z`k5Gk+wB;7AIBJ=%1Gef04_t<%Y<(?M%n~>{QM3VPp}Se)hdeK^FPe# z5ZyGP8Af%|I18hAvNKl)VX)Mb!h0K7Y0y6h%$j1G>|2fznPNx00_IRSM0m<#JrElG z#b8(7D>?Rgwj00;V6(*T$JjsBOhNA%kFZff9n|p?zyT#T#{U+^Dh#t+e1Vasru|0H zA+S#@c}P8~2UY9d)4_cfdx0HQgWpka0iy=}4}i<2IrC{Z1~XlU{9~du`Wrn)^qq{* zFDy~#VC*#^yycB0?JhfYy%TkiYWoKxw+LKwmmRq;;X}lj1Ey&?Q)#+W`QaGT)p`to$*%ORfECH8Ud;&~Z zdRy%6KNs!#`hphjY0`ioiwpn%g3| zWrpRCl{Zl0546o}5mKFN&w#y(EG%&_#{ff7yFC#}I1*6=WCoh=vJQ7ZP@ zZ4q^z(kv67i^7%Q&Bwk`s}T- zm#iVG^)*T)=?*S4hH!U7377iRKR@T>HJV}#;eHOK_zwC{9sD|@al_?~b*#~&Q9Q=4 zZzebTFlinOICTX*aXjFLq;$UFFpHAG1bpQAQk z+6i>2VL4K_qJ+P29@UpyLnPjelGx3o`d=I5g$`RoxSKuCN#IMnHzK#UHH3R2N`;zs zlwW5nG`c4CHk8t2$+ccEhDh5QrF^eb@^#h_?pY{-UAE-V8fysmS11W8ruRl<2I9sL z?z0~_EwfqZ2J|Xdofe=J@hsSEsn}!>RZX{9lQ`wFe>GMgfT(+ta=eg-AX zfy@`UL)#5Y?-3nOZ`A*jn+7dkG=|8!7fR7CJBU*a%f!o2Vk9q6~~&bSMVakGVK_Yf}OV3j~JHT zO(@l$+N}`5qt+1BYWp%v+fFs07S+1muuNQvQv9V|yEYh>-h(JbJI%A{VAIu_rMD+a z^hzX__q7?7455ylaEVF$N zCBl(ZHk$$d%Niovlh%;kr>d@()($o-6E8xEe`;I1&9L;I_$nQ_-4@)nN_4v|d68k6_eUsIoCVl%5~}^WX6fyWQcl*U z$+uZUWW5|E`ng)`Bk>Q0W#SfVY1C(_>e>@>^FqU|Ardb^iQ?XKfJbWyYY2D4H)!xC&q4uWzFtFDcWHhz230&{)JLN#U86e zy*s>V43YIsD1kk8Uqs>K))4NGQ9NJk{PdHz2h`Xm>^7`jkrb2X^>b0mzh-f)OZ~@L zgEUF^GL%?C)nl7L;TMKw4QsDwChkd=vDxl{>U>O0W^yx1(N}7s-fOVbu*_r|isv?S z1`KAtrCBZuJy5Eh^W(jSrFR2Lc(OP@hK^cAG@<2=+L~$=U#0%mr z3va`XB-RD!oe)=BL%8RlL>+gd_pKq^X>Zeelc}&;-#wcT*44>O4_=+a zJd|RtqReiHo2((+i%_Cdo!t78hGXBrZYW#Z5bP;+2MF;$0}ET*K zpyDk)(JU+82c?3<&vAhqeA5~t@kv`5?U`z}PJFFlnRqrzl+iLoX4%vkF~ zG}vUDF@(D(3OCW)WRiD@VVUY5XqSI7SF4qok8J1=I zf)Y4Z#`|W6M5y_fNikVQZlM5;XY*-T}f)=zRDWHJsG9= zPG=LudTR)G%5M7bPFrca38Fnpm;`zgL~y7zM1pxJ<+JR$;7!A_#Xq3LX8FtqVG2VD zV~E5Tq7;}}q)+shn?1at@yEnuhdizm>L%@Cdt9Y8Jfw8)(;P%8=ZeH^(>QI9F@$?4 zO0nW-{DgybzBPpVb)A4i!nnV;hHz(mg?qYB6F0qDizlT!r zmwpJT8@ODRZOzCo^naZclPx$OCH!|XY$>0nWH0l?V`4Haj#BlP*&z}7(Xf2HS-2N3 zYgWqn?5KLe8lox%-%#p<^pgJI&?IXJ_ZE~G>xy<4w*J-_!hI)7WJ2=rm}M_}6UW44 z4bT3LlaEsC8nb}hU|7zE1t`_`8*gZ%Vd?!D#lzh=y;mYwu+JEx20gU0$YwpwuuQxX zC9=R~{jFi?&H0}8B-?(uHAL1WD2Zg-S6f54_n{QuuJhA_XxpB9@efHc+4jd!;%aaq zHzK!aTqtXB6eV!Ks?4Kfihk5Az1N|X&sH7t@y<6ay>FpJ=c=3Wh7KE+-c$Bd)?5aT z4+Vt=TSHWS0ZN3clJz@S6gOK#xc@*YzE1_3Q1X=rG|RkKphWI7n_7eZpEOJFAe4%G z)nw9!UNbDcfuCv9eVm@_^Hc6-Ylwp1K?ykS;7QfS5bmicJg3!LaYF|T%e?y@WU43g ze%Tr#alK!dgSpJ}F{yT{s zZ_KdteyWuQDyqLz*76U{`dw(rc{>gz>U`sDlVQ24WF98I(tP8r(I~^xyB4KWn8QL1 zKAjifefSrj5d0mjque%8^e6M`|7Y98jymdxW|>V>*PgBFHP6hie;sM;c}O2~OVk#= zw2@M*%>IZ6@a?yc72X4bYJGG5I{RO+tHpMI=|M8;C~&bs|6}0hnLKLH`y+N>9B~X^ z!@oIY&a#hSd&2`%@00lZ=s94imHnIGwX=BmS;<>i;eE60W2cTs^s}R}EvUewAW!-< zrv0N!HFz<&!=P^_n023hj<+5zzR#luug%HV(Y&zoWD=foR43Hv>kC%iXP;2bgws@+ zj(8m`vbZ1QiJw*r{?*Um4PF8AWdyCx023D1fOS=2OVk5kM~iw247GR#SZZ+w$R`kW z>{@W2#b3ZI)#Vh_lTuPSqiXc`0Y}fZo$8&AQEo$C0V@sqz6TG_wNHDSq^5d`<`J&9 zCiKCWptk62W`c3_-aG{L!aL{L(KrCJoud^Yr_@UIv}a?Yd3-krV|J;{b0NGDhtAXg zK1SU#9xmx8$VV}v7-l=dnQ3HOX8ZFdn6Fx$N;f|N4w!ErpnVE2n(xHtdQ&}V_uKe> za3|HEHSr3Ze!q?13Rm23pRxHeeW{+n0vmrN+)XXf@nvA?0vrDUT)DvJ@6GV1G7N1` zqd%_(OAY!S1ou5)!#{_cFSKp(<)x>3W-hcX9t>CDFfD!pBVBn^*-tz_hB*ev)8Du@ zJ%p@3I_B?-u^(f}mpnaRfWZuJL&5KZl?MH3C(y(PosiBL&#FB-BnI+ySL0h?ni_jL zm{NyvwAck4U~w8a)8cw?mBm_hQ<;S(Sr}wzQxW|#2kiK;ZRm&axQFe~`h6!-CvC8` zz*~$_SC#1m1zpAZOCS@u3AF0?+DoS zDSI$qkV6fO?2UrUEItY*ELMR*)wTnrq~@lwWzAqaaHc{3P_W`@`a?fDeiEZPX?%-O zu#9KajdFP#3pIqzbNe9}i&gKl=$nP$KJ=CPy#iY>+ApWAdXGeUhy!rB?SymSO2^^9 z6@%|4ndQW{9Aowh8+8EQjKlO!(}o=SYHUZ^dj;6<853jnNYq;Jj46XH(;YL@{SV`= zMlloPBa9-IayC_~)rg*dmeYZLEdm^e&Hjkd7@p^xwmgKvK0ck`b8rE=8Rxo00<6-W4$78Ua=^Ro#4L*x*-m0(4P!YPm19f`~V?^Z$EhC1$+El zmQQ!Z?d)CwkB&RXK;0(HVhq#S#Tc9;&ZW3<;Lw%!5cMv{SY~wZSKwiTzD5O1^cQXZ zSHm&O{xW#Yi#C7nuNVO}xD#{YltOc0fc`;X>?L|uZz47OGWbx6IYgsieX zoL^)0EPJd6@`)!_vckE@go zC}CGVyHP5-=(gzV!PEF}in^&wW`khuR!K+ldbSNptc!|t$;>ag+OX_`J5Wl`m&#(4 zL}#h2Lx~@h&HlKC@-0f#6?3G9l978V=aI`~f3!sz`LOA~M&TOXF(~cXR8>nY`K1AW z&Ts*j)3eZ)4m6)HsQm<7Fhlzr^hjQAzoye%Z$4w--2!uIcRAl6_!ErUPY%>BY|T;O zPUh{1*2lh1x{DnT=GNrWyb1#rnQEgs=lUziVdGTK&$cqZ%yA zFdw3P3Z2QKdQHpDR^?q;?cUUpJ^VsRpfLF6`&sq>#IWP8$F!|#@LFbe{fyI+Lw{WK zwL>gDUp2glUD?;diO#AsT>nnk4wMeQ+WwOL!H^@@EY^eB;WTB+}wHLcTO8R+TqjTeqlB6V&Z$jLmeIihaH{=Pj)yCM;)$$ zBMw)?eH;#)&NOhi2%g|@7#`qo6dvtxDLl@yc@IxY%>ERLqxVy7yJa>@nXazt#-jZx zO7-h@QS}ya_F8Kf?Y3}5XTD#+Cpb&O7{#tBKL*9~vz+p!T3Jr7=_8K+c|33HEL<_W zYbbxB1Y9u<+WuELr4>@dReTSW#CgeM@c(}CTdd-N+-@_b+FL_e!YcSi6C9B?>vhOURI)Or^iYReYd9 zT1rHnb=k3{)-124Uyl8fUP`*K>u|3?;VM@zuO+){c>hKza>eV_%$=uR!Q4u2J4)#; z7nKe*l&et6FHH8QPCumtslX*IMya|$2EB0y=f z3#+`oaP+-`R^3%ady#M_Oz)~eA7-0{*LRlb+GBQGY&uqzT}p{pU{qbSFigG^HR`TY zTMlz}2@lUoum1>|?M}Ljk9wp$QzzT^jt;C=qrgNz3Jz&Ht^0sU8@TWOYiL{G2SAm zy>Y|RyB8&Dy`j8Lnx(flO5~H;DkY!0vv*lT+?tD{c=*wOC8PcoT=1z4&B{8@7$UUG zc?$>gcD`G2R6k)Gvdpk7ZU+ii_j+hTCwA5>z2~7s-g7E*gEd46rCNDFzl1K|zZR}| z)_e^oFWB&WV~EgOQNl~qzz-;AyJ1;Q`(iR$;v|k(LnOWj#q+RwPbXe&SSC)ORE;>n z_E_64#t@08pd4PLU!#|w`e7Fp7{g|>CKnJjQr@<_5vApWCd$87d-*)89)jGu7aBuk z*cYW-9sG{#@TbAVhqixC{nr{IvgS&CMb}hMF{8VuFVE$tTSFvRiQ-{IwLAE=HH15G z5l6}hmFSz9pF7yFY{GL|QM>zQHVGZo=xSg0iz%3qG&$d94UzLBDDmMY=gF&hH%h@q75kV8wbF3% zo9uew+M$(uoy4`e8$%>M1*LkHN!+fFVVQU$N=1=X>_yU#D5XlzSiPWTs={7b*}>+Q zCB@_-*$<`SaaDCKi^fdDa+1G<5_rOTzcwtr^?H!oaO>@6SbC?RghyEKtA?ew8YMB* zdQZMwv-Dnr5^>7C*Rb@iMyZaNw7CZiOK+2&`at>UTAqwtqj89I&P9n_Z;O4;u=J+% zqPdRuJj2pE4#nd%C~jDKze7nZQo9E5#JzD?v-I{rDSbxIZao@bs%h&Ojd91s#p!X|KPxW;q2;Ln-GzF>AE19~{rKk#`xEk;_p6`6@7we10)3 zy&bNgcN<%8iDBv8fD+ALIE19X8kElbD;e@UAe@Fe6aOyFf6@)pcD^Q zu`ejM&DENvH-Zw0sQC4G7aEq{cXYht{l~EMw&_c`P3;I>V_5c83CdPyELXs>LL0fw zu#Eg0B~fTbE4OPu&C)v)r9#yos2>GuERfFZYp7sTGg=oJl+GwhL7{P$83tG~vxy$c+#QCc*LN*x)tiH;@Oc_ttHKx*&u}|d%M8n; zJ5fr9S#S0L&C+`*O3^Sok}<>5`yxtss2$0DhNU-j9cisMx0hk*jiK--dqb)6%Nn=H zp85u*;v*Fq#**J~pl0dqjuQE}wrU$=lhg`ph$Y`Uh&fW_xQAIoxGPYi&NW-^FV+z5 zCJ}~L4H`zh`e@uHOP-Dr`^47kRm0NzJxalLr{GHm8$;y06eY6Naiy07Y*P=wNJ3rU5@E%6tlX8h&9CBlaYL*}2{061edP5V3 zX_np-hI4p0S8Sncts%008l`lkQ?J9;5bmxcsF&joK41;u-h)!qSN*h`id{TXvn={4 zl*HA>8#?6%&C>g{R><01d>^)k$hzw&dN`ta4vd-K<%9pVG<@^`Z8@XINgc zeUH*_k-0SYoj8X69Bd=o8kUh^l*C{a9YsE~4NLC^6wdI*`>$c??GUAZhgk0b!_qqi zg*DrxeZsKxZbXT5WuX_R-wn%Sx!G9Gs*d+6!_s>vN?@s7VV*ZEz1vV?jyL5N&C=Tv zrP_LPuQDvXQ*^v)GMZ!cS&f_J(YPI@Vv{NuO;>qu)hxZIqeR}d-dTpFcNa?eJH{L8 zI8L+l&OwPfKeTdRwT75@39YC-EwY>B_8kvCEpN-ci^8W_afXU-16|G+QA+tOV~+9E z+l?VIz8od$xPy;aL%8>$R4h|fH?e45I6<@Qs|Qi4cGOZUPhxvn?j6PuiAzypNq4=8 z#t`m%P@?=`G^uM(GKO%^K&eW)Pnc{B;hu$3@R^g^KgAfr9YaYtKjDH^))4MSQ%Ufg z>OO{nTw++Zt7!>mw`WvLdzTuP-oh9y`A`L-cqbc{1Nkw^vIoouZCg!a`a6Ml8D`4AvEE$&-I}HMRFs5jJ6@m3G!Br?2`EM7s$wjYWrtzeZS7`|Svij>PUK{>&>Eu7 zhft~?tEI*+;7Tpxd7IZKmsvx& zt5K@7TfeEZ)huHO_aKzW237ncy*byg9Evq4EgvvHZhd><^0#bc=DnI_wVO)^d3Sf?{BA5?p)1s)XzjIa=iTvOYdzc(f%shIy*o3uwm(a9mQk4p@d=S z^~|Fc4{C-4%zb@&PlWx_H0pA zhxkR6`mko1=q!|Cb#M~(xJBc~(zy&JQe~6=U|4!jUd)=U*8iH>BzK<1t6xB0xzl^R3SKWiDr2a z??;Keqv}n~%x^mNam~_O=LzED$qN3>7t7N#vVx_@)MO0 zs)}pxGQ-k)##2o8<*IQB-c^RBx9!v9yv%q*FBz8JqGgQ~g~l+kL!%bH~_ zf1?Ci*=^AF#_fRBC@CuX7eDA`!9j;t!%>H8zrr{(znJgAE%;wX~IBw?*LVLXI2w0m~iB`;A$t^LvV~Y59#7AdYxAA?jX4SLb&2~ zM$e4kMQZ(Dnc2Q?5fitn{xb;fyq2Ze$z&m%xW(4_EqJk`{{%;`urKOs_6ALMxF6il z;Tdor!wpsRp3ML5W~sO*vw7X}bMz$8Q)!V`MgM3JOx<^)I$B zv%0IQ*Wqb!pp}aK%hS=Br>W=vXwWpZ_+?f7BOADW#>d-nW^y7r{Y|}r%itKW)Z%mC zT8lq``z)SZq4#l(okg+{V6nxg!O<4K0eN+l4rscb4R;m?fz=it0D0xvy#%}ucC(oF z7N;wV=Yi!GZvrbVegq!2*kOY{@fO~vcfx_;jclD`r@Z$;jOj-A{shJ?UbvAhhX#EL zOn=*M@%$BTue!{p8mGLiYj1E6$a~PVx(eKBvGyk2=q*}38|-0m4#;btQ2pP7Yd5j8 zIgM&Gc!x8r8aziwgIx`(0dq3Dd0)W}sDs+|9oWZUN{%`(C$pK^gz4S6nWxw4&6ydE z{1wJoL5w}A^ju$v$Kk74Y`Fgr6p z#OS2f6Xg8|oNcjtrLL4#{R(XTk&X7hk1;uE{EJbEanR59`VScLkL+I|+yOVQG8Mlb@Z zZ~@_ufTIoiJ_k2%vo+5Cn2n;_oErDSXujRqNI46mk6NkIz6Gu^=>HpR{3+eWSIqo_ zKB0RY!?yur@257`KjFX*C+du?9C1nGMvNU8TmEEgKHN!dd4O?hw~a&bGhQXRnZG50 zD?c+C`PRXQEqgP!>j^e^Ar&eGhZ^*s@+k+>=M)uS1%|6M^A{wVkHBRoqVHfXeZd6M zujVVm7>QBXA~!$nGrbA-AX)lv0=H_p9u@ms&%J4ik`y@Epug4^{2%rMVd&dKxqro39twVBAB2kC@mBjl(rNRkP-v|sSDCUT#ABHTreskNRXxrenxmQ62)FY+Ze-MA4Z%yz7TCZ8|Wu= z{stU-#bjFX7mOYl6g(b={}*FKwFd@Gdd{nQWc6HxPv-@$@>7kSAk8(L1&&r4 zeDntPlN&q}IfuiD8pHkx442xiL+=6ojJt$he_*x(({hD+e`2pThJ7Optb+Iujgo#}pI8u{1L90ZtNs7dNAJ|-z+1o&W7gk# zm4H^A#s0yD+&6i*x@)t!f=*R?WlFis;xMv;{A?xvEO_gR%@!%fKe$*q1tq(?iC6(R3*zihzsl;BzS4LCOQZyeWpz0#2%C0Tc&9YrE0cJGZ2O443ueBLAg9bruiLFfgUnV z9i+K84gF6)%BV(NQOC#-nP@%~?<|?-ER?K(Oq2MhO|S42`HVqf!ND@kRw!EvY*=eV zMSD3j@l(u8p*GvwkU|AA+Qo@Pn%|+=ddaNo-nZHM7l_J$QZP;I-x%h7WK=^aBhZSO z|K0jm{*|cXU#L)D8I}#@V1dRz^sh87R5z=ijA{i1OH@S*y=A4z%-{OJKQ^1UKrhaN zGQU9BSN}@09NX$2APc()C8I!88C0=gnjCCupudjFv>N{xNDT^vRY75#$VxLL2CLl* z48|4zQZ7Ns?kOu2Mlq2B`@$dpRWeQA*F#vaK)+5agvIj(`m8JzSAndb|CiD*7K`Q! zjPqCir5w~zrh};eZMG_Ls3SFqwXN%PSb<)=0wt$FQ^!K_6&N1@JNka8-1^YJlmN;K z3^HjlX~zpmiIgb9yajeeuj7A}D5Amz<_|BT3M$*3`cjAfv#yervSa!hr;Epcj8S{m zluCBb%-5_`#c=I6oTc*C;CkI;Vy-YwGw^43#@cd5Dc4-Qesu(~^j?7C8%^HSHu0LJ zcQX|4t5*3_>6JLCj~2E>s{(7G1jbm&X7RU$Y80_VE7^xyc}M-d7WJ%MRI@B=3zWPG z>}`redfo)-Jpv_bmI|%Y*CcUd$eJa+7ohm3k=HX22Y>%G>Ae9ZeWX*BD1!^%FXD&+ z15IjGYbTW8E9_2v2!|LL!aW&Ec$ijnA6!!7b4n$-?Kq!c(aL3vR)(w5IjG<*VwuSR z9F<(7)UglH2}g*fw<^v>a3xQBJ?|1r?@v%%ui;}`xcBCH38y45ME$;n;xq1)jyTbP zA>3a;38IL{D)nRYszLGSM<9 zH3}4V9!j{t)+bj%ngaQ>g%U2X^>0I2U100?Rf);8g@dxNxCc?80*RVH@fS$*29z2F zwro3;aDlDA17&rAG`@$Broh$@gfet>fm$!si3)7Jttu*1VCx@;;?Izkei_Q@0%<;m z63$Qa|6j!Be6l_cIrzyjJ_(<@-1$q%c<1kr;z%JCM=mmp6jPB;u_!a`Vf|L6FF(cA zh2a>d!IG-MCdj{o!zw0(*TC1ShS?@T1+@GcIH-DT!VjH2K>VK2&jXo)N>qnZMktQ1 zP{K(n5221b+RJRuu7N74>&V7YvnDp)%}I`evyzGJeQP09r7p&u2HPWuBy@ZL%qqjF zAM+uyET{e&oTb(yb%|hYRFQrTphaV5s`bB=Omf84!6Ckq8oLG8)gvWTXbWx?WFis& zB+v;ftH!OcA^rg=_87mqj0BFk2+FIXe4l~cbx~MV=EuC4@M_b=`x0xweD<$1!8HM7 z;#gS^$L|N!d>z;)6{WaT80`EVI?nl3y9){B9GBooPf+n&k*G&SB&w`xXtq~^{-8?N zeCRP$`z6(V89qBPPIs*OZY$bs4-k*GYS}RXNpc3Ns7~G-9O$81Zv)4tp^t~K-Ugf% zU_AzDf`eI~3_aRQz5XHcISjTLp7c1{zR#TP$mT!5P+!7loq$ zvaIh%OAJyCG>-&d?Zo;9tq)LRccY1JsMM7Sl^pdOqnM#8=bI#q_LT|o_SYa>RXuj0 z3SppM_#F19_1w&PH3RzxtDV&nlU3F#1il3!g9GZ_ORfW_o^QXKS!uIPEha)Zp432Zm+M zOEyQY>}wAU%bL&7K2wv3cAA=(ct+2iRG7Uj*spG^M&C~bt~T;faG2$yEik;N>nB(7 zUG>kg(6J>1ye%lW7dvSzC43D;XnEplwQ7-tb%JXc%OxkA%&R``cLOv zj)SXaiy~YtG2V=`E!aDYvz-OrVv0KhZXk1Xx5As5q|g~c$mF8HBeGTYK2-E;@Ihu; zs$D3H?hRIqnXmrbhf7lDFk}O&!hT>6TsPQA=)44scf_ckf0Zofd>)rP{Kl{!gfUvJ z)9G8{s={7E$5EgQ-`(Ah61zSWYs0>**?ASb#fdLTUrs7-$90lo@tmgE!zk78tKf}> ze+0)D<}|&l#oD?uJ1>EA3Y+@0s2*#(Yz)U*7~Uev`(t7SM~zrp>mo5~{0`iL0FMU$ z^GO0Oo7RlAB^G7F?yiNb)b)edZ@vR27MpVy_lzGw@?t9Qpsv3!)^^TtLT%J@5Uo&j zwk75z>yEczxH5QQ<8ESkvUU$j`XF9|S*MO>>Foz4GJw4yV(C2v1-lWg-+Z91X6bDV z#T(>u#}P~KMko>XrsNSz??d%aXVv%!o&oBqF({pLpkxo>V!tGo-q=TR63kvt17hh7 zLWzEBR%$L`11Hhe$?TU<`kQ5=G4*lqyMRRl9r2hFvq%|$GM`gAW`d*3c}ouv%OdYW z$z!jl#$%eLw<{E{^^EEyHbgP&piD4JN6%{S1+)6|@ia0-(wR^~OL*z%ZDLu@bB|*z zEiu8FY>43HPy&m1>F8I)GWZ`T>DKf9=}(X$g6BhVnMI-3w0D468t~MUWQe5iLh+lV zXSLTXZ%C=$fDDoJ6(~n}{pfyR=u7T3PkFrU0ES383`!WCO6x9{vLW0NC|T&p8?i~{ zlb<3M-bbMLXgO#~mc|0hL64HNeFV=XmTLs(0Qun804O%I+|&IY8zSTFI)GQ9dW!iq z%ivB>vam^1=XGp|;6jbDkv+^>(FfTO?q*OLn6;tGeIH8pJUt-wxk@Eo8G0gLw02%c(^y;JLv zCEB08bBU$*FqF_>_Qo{REWLH1~4D$T_DIOYcM|KK54o zoLGAGDp3BjTK*56!-KTqFQv+VG|TR51tngUT$_-hBG2JOSD;WnD3_erg&>8Ej^8=-NabgqCB9YCS( zi^S5K)D{grfENh1CYIjUq4@jr0>O>M()$Axukn^?r&)SiLkZwHt!}9DC}P=E3!vbY zj``hr5Vrqe?#`RUGPNfi4f`;6STADfT@EFyDtoUJOK;uw=&@?L$5LJ*l+I~TqH6rt zXt|vlt4in3Py$1^!zwEavvl$x8)D+F)Cn7W#<<^PL%1(M$+J$kT%E}f z?uJmp=eS}o6U(BPK(U=AZ^~(6>2BREs+1PGqFZO!o z5=(E@?ii}(Jj?Sc8zSp{P+T~-qD5-SJ;)I5UQqH(z1D2!&)xyevgo}~ zB7J$m=QBMuOYc4?0qd+TxfdBC>t0ZTLG@x3GvG~P8JzhNe(dntfd;Fgz3? z9iRkF=on(@od+e0Lw9Q|5PAtpXgNzhR zJTXLZO` zNauYhfg`*Uv}1;5>HQdr&-`xkoMuCe$iJZkSKzEeuh|}rxe|tOUxVVZ-2E^O!w~Ls zS~0u0r^Zk+gnJZ}JZm-R0XBp?A&BC>;nkpniDi3z4kg_c$Ll#848YsM9!P_oOOqjA>27oeE5k-i$&{=AVat}KnYoy*B(iRaIbU{X+`hZn^n)dxEFUUU$l1RR--XozT{=0%ZX*L-iLCEmxXqC z729qSt|OKS?PE|?`Lk%y!6O3R^vYDJPsw>{B&*b7aL+TDo;Sh1>Tza%DHME-efl#D>`Dc~G(!@xsuf#ByBRgW_Gp3qvbU(k#8L zpyZf~3Z5Zsh^(hTu}v`xL$|Ua+}}f)VitxLe+MH7t2gx;QcnXmMAAM`!X_urPBw%) z;a!a9$tHRb8^XN{O4PdQaD@%wc1_0EH%mj?5XEpBH)BkATy8on+xD zzyj+epN7)g1oZ`n&C1Ys!7fwOm&CHD5>s)8WLAbg0nRaNNHd9L%3V-ua7z0Xa5k?D zeSR9Sz{=2VP{wja?8T;IM$?Nty>?KTylf6L6+~4MlRC@?Y%%Oz5N$rGrm<qP5}A zEJgD*Rla*D;ySU+WactVVfD!CdE!IO(t93?tz(?(IXfjuEj*PF?|xx9DPkguK#6ux z^O1jQ|Bp1w9R7sjDrGm7EUOxiFO`(~<_b%+D(P5>UaVpzdw`O;r{#-QvXZM%dJ*;1 z@7R|2iFJtOE&DMVvn+d;5linwtI-a%)G8gjj#zr@tckS+(o_`QYFmk=x8YhG=L)PF zT?oZ%)_5KPS2cVOJlb%pb+NWdh8Kc68{P}D#QC>pTm6 z5^K9};_HC}M(+!bH;09};HX*X`7=0V7J5Fh0r`x^n51!O7J9x5(LaJ0dR_vbF_}NH z5s6Ku`+`>(eI|IcSVq+3Rv&v3-Fj6pC~ zSjIdUr!3S zElK6rvCt|PJlAlAFk0F0i{Q@5oPHK~b+Yn1kp4LM7PGzNZhaZKkpp+M+W{vqz6m@^ z=-2{GbaUW6a96`=d$7+M9u2_^CNHr)x(JlzXncWtn@iT9Ng%!yJK%J~^-p3f84iH+n4Rx}{nbpJ!!R<8 zVZQ@ouKKbBM$m(&P`B#bj~&55!xO8FZqsMocJL>BCJGTNe z>c-G=PsdL%@E#C7w>nEi5deoiGB`%T@ZzLUj|gDvdUKLdhs(gDgw8S-p+1TaZuiGg z@l_a;jNv#9WACGsCojT}#}koQ6gn@llq&vl(RhdR5~iH`lwn`s8OD8DeT=v1DtHC6 zv()$K^T*6lq5%vaPLSv@(+5U>7`h6Mg)o+-Q4gI2=B6qC3e-3@7XgoRWlEs?S_v8MrAPgp8xJyVm3MFq*j7jly_;0dv6l?x zPf5V19PVN_hC{z++|!s1@vCDTl+bRD^Xz0pxc`6>gqz+{{^UI}gnJZ}oXx6x`NZ<6 z+ll2TJnuvC;(aRo6R!$?p1RrZmT3L(c?U}LvqJoJ@Dpr^GLrwm25c^*jt|!BRM-&i z_n}0$v)g^14dE{PC+7YwDx*STdG`cjS;L>8(c()$S%+m1qN*BpGp`7RqG z>&O1WmcTu%9iBK|TO}dBOeQNL%^oPxUC30;Xn{Fo=TZC!E&8|7@_+iZgOasNjq#$A zbBSd&&Or(7P&x2=s{Er_dIv!9Zb1*>v+nLs*bo)C10}Lql}$zPQy9LH%`$jAln|O; ze`wcphz${3EGEw8-&F{o3roPG_`2>LSP^Lyl*ksf69u^M5z7KP6pFJ2ce3|WV(Bdz z8)x&aSAmL%Z9^=*6QG1QlGhU^mfpKivNje{i`%1f>c){Fsx=TwUJkq6%h?d_^H3r= zD*7Nw_SiMcywjmfnMxnLa!dgS*Kx{_bSP<%Nm_>kTLhi2)W10}MSy}88FThke5 z%U-Acu7ub(h^6-g6yI9*J`}H6dPhMCaLai%5KHeBDBiW$C-8x9PmRK4h>afr#RhlJ zhG@FwYzX%SC@$l6mn%YsaCd^@+otAMLA4hV%c3tqDK?Fpt`aWqWN)REse_1R%C%7P z@@I#qXm&{bEnl=|huX#BZ0Y}#%snz+w32Ov64|DnLWic_BbH@7_5i$_w4yIIZKf}Q zdtT2MtxUpD!kf@AMe%$=TyZkQmN$VC*vLa6lUSCq3CdA3Xnq6RHgL*XB{a*FeV~Ll z(6C6^KrFrYp#;>7N{JOxTDpLrNarjlURAOxoR>8g$TzJd@>PE!(mhq;-0rh%2zTjZY~pTJwi-rAcVe0M z0w~_?TG1n9n~JHPob1lmtO4?13W~tNh6cz$HbfCCp=9;bD<#T1u7D?CrG|c`Wpy_y zZuAUrw$aysZT(c+>PY`HI0O1?xHRU$v}@#^;L)8_cCmztvG?lWofwtf6;$6`Tu@I*bc)bcN&+jH@v838(#`(s6h<&x{&4XUYJktJIpn z^}tDte*m#A3aaCoGI6$h|4~_`@oNuQPp#K!&jEWAIx3fqv(0YFXQ|oXD6{iExJD~e zVzY8OedAjAbv^?aF}m{tjQG}k67Q^D9-R+EpS0OW!&s({Bf_x{c&au1!gH3afU37K zC(hkqbTtM((TRHCE8ZxgxEJ$I+ZgrTyi(;H!(mKl%jdrvzz3P}T}~uYH;_K2uDbR} zVkPJBROHakAjd*swnbV}e?Y^!7!-FrniY;QeRm+|FLNiteS_b&%pU z;4(tT=fHc<(P^-=_=DJ4I+)x$!k7YseqGFgvDX-muVLKppt62Lm8(94gW2=UW5Bs! zY>NFPxT$Ji7gerN6@_)AwsU5HFL&g#ar-AQDyxe~W4{SZCv?_-ILGmNAtA|qIA64O@|c<^ zV;3#{u9-$GGZ_daXFDr6J;dK3DB*=rRQu{U$MZE#jCb2=87==DuMU*Z$7*1GOoBs* zWv(AW$=jns@K%fxOKgF5`_|2qt?RPzAQeO5LhF<&q47Xvx=yT+08{w zr2l6UfMjaA})ozGlEsh)3@LIb9u0SnhLT7CmQ10{Q|N>4+*CKJn&4@1EV4Wruo zH?j2AL{+@=`K+V|IQj{voJA~C?t$Xks9Hace10dE-s<)AVUoSQh^2Qn6nwk8_0u@l zK1M9Pv5z9QYAhc^pJGD{-4ReC^PH+@V;tN*XG6FjsE=NOyL~L)KHh~5;a&#C_JMlw z2~<0eSQh=*WANewWALVqA(q}PP{O+TX>`@*$A|vO7p-1uoQ7l{s{1;VDa1096Hu~N zTA7qq!=A)PiynB~60J;{Xl1$T|0L?UkXUAN3rfxkwGiIa7EfrFUIis@kyXSOv?|{H zO}=Oqk^CfzP^w4+6w!%TW-<#(2!|_pQ;!hK8^eD?NpG$dy`!b5o=+wvx$8HuM5~Aa zP|9{xk*%0gL*TIsR0J71Pl5x@;?)CwoLCocNQUU7rclx!#t6`-m#?!S+#8_yo2x)W z44+?#Wz{M_h3s@NPTJi8Hbk(366&jtA~^L+Vi{bh5k^lhYrBf@c0G|VTH7@k%679| z%fRsqX}cV!!B}UT^%QEB;MXiOZ=n@yv)*7s)NC`9Krh~`--u;!)yAl|wOPH{5W(}H zq<^P6H$rEgAeNmO_cTiWR!!61CyAwZFckmu+)GQrq4{d;4)oYpn!i!S{MecjO*G4> zrcfe!H$^9T#<3wPv>r;L|_5N>Z%OfF_8FVlq$;hq7-^%;u$?@U+bl%?g* zbP3H+aZ2^y14>6r%TM(ll)SHa9y>%VH{%|ZfSK{CHAgd@`kHbn57P_jN#*-fy`hlyoyu~rxq z`)Q_gcOsVF1yBNq)qTXKo*|ar;;rF5pcOrXJVNte>VSOF+S7JH$v$KyJ48Qz-KE-C zqLr){lyF!rY>Ij=BbH@dgyP%6GhM~Dnx(fpl$_^Pk!FaULoD~ZLr?f+G&>F zdQh60i69HSj3+q91~5Joy%SNMUx{T@<#c$hiJ&_hqS0qTNpH^+!7*YP9M>LQVkQEQ zpA8W_3QAyDylRi{ZL4F?;ZoE(Rz#XhP_RJcXme~+>1Q>|0@^^yHQV$)*k>lUqhNoA zYWWPd$@!dS8PyOE$3@+CJ-DkEb^#wLWa5j|SRcjEGS3Miy zn0X*yv=hMGO%5xW#{-)D!>pVBBUy;A3Mpw-;|L#!o+QzFc zt#R5ghYit8hoGeYpk8c^?YDK)EQ9Mni40WP@TLwVmfODoifz7C^%C?VB+pOzqE*)# z-BG6nn2JZ>tmgwZL=9qlpn^?RUT4(cWnx*zIVj$qtV-kPOXK?z1x=tX!h5KFJO4l}+1r=#t0#YL;~#3njh3 zR`jSp!*AufoG)5k(ykwx;Jy@jZxc&z+5n_) z!QN%W(pz*OVq2;7uE_a0V(Fa&CD59^g$8Ms-T_c-&DG!Oh+RS~ysO#elIJ`R=LSMK z)BOU)l{=?9_RI=HG|GJ2Ldi=k$|v*_*$|c5rj;bh_%5N$xYkgN%{E-8mxyJZW8M+-xaG>hm z0j1s`mZ7OH<7m^Cyr~_DrT1+pL25cZsGn08-%C#NY|R&~LH#onTaszdio?ke?b%T) zRK3)hgtB^vphWVE$mFBNU-_a{M2!(R9^m;WeO!BuSZ1;hN@SPrVqH&jT>C3uv@-FH z#KxXB$F<&Uhz7t z$}MwTn+Fb`rsG=b31XRl+^gu$7p+RpqdPjO4e~`R!=X@uzggAbWbWnpqLu6nlrAvOg&Htg%;hCB*TA7^C$_{g&Yw{WyqUY8@!BtZ_(4~&mEX$Y% zB{GN)bhdGtrFSrt^dGSqe4x8vnfV90man7I?f6jk9OFX`J&Y&6(%5X2p^965z9HV}&UG#?`u z63fo|0*dbj9q3{vYm`nO6qhwI4`4%7YJpagRd_2Fa1qL4T~p9_Be=%Rh-HmOLdoMA ze?lljuRy^Ue)NGZrNUIrGPE5OoBF2%?v+l_m?A^>LP>vt4|Km1%g~3X;T(rc?Mo;_ z7eeuketa4yS^St!!v{W!QYXOaQTGI=io zXR~}l%O;b!*|@>Qnbg-fSxtKhm-z;O)20yH=Y!)^kF!Y?N}K@BpNs~knWL&InVEps zIKGD)gPhj!7`TOr8wlRQahrg9Mcm@d1keB6k@c2N@RqoYbbNnEcVczb?pjGtp=g3C z-6yePp{$nbDf}CQk0s%Dt)ulEG}a6J9P4E8DQ5d&aAkF)4{nzgQTi6AMrTW4T$dP? z8caxyZ2-W-gZRQ<-^6(5TX2nrvN#o=OabSp@qH0&o2&149@5wdxQy|2Al@R<59&_f zY(mH1KrA5B4_P~(dLK>DonM9KcpXM=ca?V;{k0R^SuIAW!~Oy4-h-b6Yy;lXgPw|f z3z!zrXy2h#Rl7eD-vh?=uRTZ4}+z`g93&<5x61l-#&?!81$V%ztDN2nbGP>;$B zA@`1`?kOejh~YZ-E^MouyaB*|J{723*Dmj=-m0 z=3Cb@!By2_q;?($jvdaqI7@tt+%2Omj8n$2PlJI^;0#0lhkzXz<5uh1Xw~^N@csx> zn@kv0)oz`72e1R7^FA)iSUK`16nq+2 zk2QO}wR)br2(NuGuruRw;A%q0cR)PLKm#*n9g1VNw*zB%5638Y7nnC%T^Nqm-w*Ep zDsxN@dY;+d5ZoD8bg(g#fqTbrP3?cdz=vm`+k@-%#t?oF#PHVY^PgbT37yM;>0_}| z|A24z+=Q{r7>>pp(C1_6xnKJfa95Q&60v^*@q~)T<{R|{xnAR^z)6fTpJEClbPNNg zXY!-NJHQ*6?KL;WVQp>WR}lCra4h4`z$l^P(ajiR8k+&LSbYPynsE>C3@7*#=vCuK zqZb-%#o=`VtNekW*GUlVSiO6UqvwkfMW?AOMpk;qB=Rh1t-33 zMsLb?9Gi_{?*t=5Ek>+!I&eF5dM^DEjC*hMxGTRyKh0Bn4D#;?#7G7@rU9=`G?e+h=|i5$Kz{+}N+@U4#g_Oz5!TL6W#m~X zb7^sX%59)`lXRB)LZ8#>Q{9wWK-XsJYy$;*A)M|38h1$N6et-z>1n@|)!Ms7dXGTC zkx1wJ6EIr9={TlOJ+$-Tioj@re49gYZI^lVh2p1^;FLFk!2%nw7)oa@Xge@aAo4tv zqZH}>6X-8cP`NL0%4as90XS5k)n0_sfLrY~pzkwTqq$JRT?rXr{ zP8nGuf|fFc`oQ4=8x5G3*dL|h3vY#1d5qQ;|5mb;3OtS1EuMllR~D29!8S%+Xob3$ zJb`)U4dy!Ft}mrAf!%=&`yp+p z#*;7;{0#JNQfntARxG-uo&HIvf1d1`k(%Tvc2W;@?JDo^fwOlI+dFGkYY=T83ycz$ z2x+9DqcfPMzIz70pAJEEZRae01>Y8QMWMOkliIE-mz3iZ&u5Z$hi-U!9&~SxC$e@N&Sk5m@N7!rTo`Q#ud7! zRQ<_FT=OdwRh?hL>~06cyIuay9t`DNNM+*{bk(Q*%exwiEkFJL{Y8Xer-aId(h~It zj+1B9igzAHj4p6|9rVWy&QcxknOx41__fYW`{G{Q1C|N7xRlDyJ%Vj=unhf#Fe=3x`l`>!(l*Fm%DBaum z4{wPmkfukE9wT1r+r#I7m@g7=n&dOcr?icp*kh#~lt_V`$E83DwvpF)=0Mp#kD4{} zlYe=SKuIrXE7`a z1O}mG6_fAKn5xqZ`|tOz*TX*5g+G`571)ON9Sljp>-?uUK+PDB zC5sQ9*S)VIJ(J5jn}X4^?C1p}bW*LIfq7S6YSpVBW6!oo*)O)7%B@@2j4eg~FzR6Q?TQ%;aP>txs~ieK!Q3N`0eL3a;uV z6f0!gOrOVg#zb*Iz}~8#si#GuF>ZBj7AD2^aFkUgXJd8^0b4AfAEPlf)Wt@nDtQi6 zwH|o2M#FU^3e7R^=PrMd46*mNfZ|)B@&Z`2Hxit+&?H^PhDdr0il37@{?y(%D%uGz z2B~&Qv)q3=KnW})ujfr->0JXQ>~*N|hwuc}1vW%6MZQPh7`OWgHiWwml#o{iisIEN z^N1b7dlX7=hAvI_c5Pn#S3K7etww1DB{I7Rt?qMYvmtVcKnYJ%JLlm3g69X#vi{wm zges`?zwm{qY+_l1oltBz!=|mvV?$(J?njI#%bm`KaK8>Eue?L8Z;!UgVMDmjLy2m) z18=hZiCB1BLkUg8>%8@&ZL`@B?$c0mtdZcjOonj#ptvef!+LrV%gve&C2KmK;jDy5 z+xD;_g7cu{aIm}b&zfcMb5H^^mFs=nl3qkC+w(^#J~YYh9(Yv4bA=3%^)pbir>n6D zPJNYF1}}%=_3FZOhriD2xz6Q_R);_E3wn|2q?2{whwvNci&nBA6yF?G{sVOUB4SzA zAt=H3*n5vydMjQ<*UeU0ixK-WvGneM5}l^PI%oSe&C=TfO3n;*RmZ+XEWJCRxUyA^ zd1!(7Uo}f_TPWf8w4ygHNcRa-=j4mlrhNm&_CLwosn;#hO4b`nPPPipPb}Z=ePUVG zAt<4lR#{ar*ZliQ`$BnE8Y|EGP;4`bs0WTFm2(ebLv-*wC;=|g6CsvG+HPQjE1LbO zHX9e3ne>MMfKdilUP>m8Wa~A<@ioK4jNdT81E_j z2Pql)3sr< zZLU`IWYC76@O>*^v|8Z^lsd%Fy%(Y6%*9Koi(_w2 z{+kT3ZOygvf%-#dok=W%H$cIcLwrk-^<`q|b^n8NI+JyoHf)Hj$3ajkucg?=_C}J8Mg#{()by==}WC$?mG; z^b}7aKcAu5dmtWnv2Y@0p9u^TI`;vuE-<%~?!lusAm~_U<6>$t4NB+*=_S-tbY)70Uxwdje>Ct27R*#>|Jas`6GWU5`gS|6 zE;m|%)6v1eql@W=jbkae-V(Zf=Qs~u0bYr!Cpql4drM4N;LdQDQ7G_@VXs z4D+Up&mi9WkQN|1egk)2&NZuE7`0q(x(9p;Ox**vePneHj2a)A?kR#sgo7?xcY`tC zI97opCc=3U#(m33DQdS>U155pEsPG9F#$%FW$b~m8U}YyF}v+D4C)?m;z|=g3Wnb@ zK8KM3qvv+C26*mDu4JnR&?nGKUdQc@H(UAqnX17jh-?MES6cZhV>SBA;MGZLS`F}0@QNhT z?MJ{Nbz@LU1^bV{xr{MMdU7STEO0yH<3QZM(rG&YCov8I?q!?;#QS1(f{%bx8212A zFln)e@s&Lt)&Mw`u?O%nV-|1%<1*ka#(ltZjJd$0jD=FLH!!9G^BA87 z<}&sI;)a|q?JeLI#wEZNj5~ligt6bG*wytxDXI3~p)F%~q8kSc#@fL7jIDuJ3C*|k z=rEt zN@?^bKaA9YP-Z;^N~ni*6)ly13VL?ui`FU94JbaVi0Wm?5Jd!_CI~4yys~(5B9z*g) zs~)dHaV=6?k%@aUvCL#Hl;C`or@gC)rFS!wz+$R^`w+48ehno$kDAHz3$gV63B_yL z*i)%I8DiU-L&@qMuNrT~rq5O=@~&Rb65t&h4I^N8;bvi4N-jIRLsWRRI#0C`KO3w@DM1GZq^80 zqi$45PR0~qG^^pif#U0;Mk5b*$%>j~9!;Tm18S`-klZz{+Z|j;vV)JHRJ=0&4FI1Lug) z?aP208GisqId#bg?Y3eYaQbuw??VFzHqa@L{T=W|wR;arTmZbhflqVRgVQ$hSlr4Ch10hS})_SKWjku~9s|0PdhJevW!A1g;=-^xoB5IfIgC~mVfbO+ea)9~+vG9O=c)DQWb)%o;hL*z3HijQL5UlPh#M-9Y&p@J@4 zW`2rTR(}{2+fl9PIeMm=aVjCnvoc?__MdZ5vW_{_#b@v;@C(}#;yqVc5w*Ar#rLH{ zrJlnDiQ+ZM5N*=Dk7Z*brG?gOasRZAaD~ zdo9f}*bT*ox-Tw~QZBVB8zQ(alu&*P%%B!R7HA8_|Ap#)2-8r2Se7vuiuZ_C zbTfX-3&%3^MJtmjP(sJ}FtLzWX7VwVDE0&#O;f_e(i?%|Rf7)WiR&vG_e$qKP{Mmu z#$nXX^N42Ytp&w@LMysa0f)b6WA;-`|U5RBT{h?%isfrg}sf zJqaamgH;43q83<-`$N8H74aJsygXzKGI85|nq?-Xpx}LPIoey5SbEc-q_3r3cDE*$ z-Y!t`a#Y!)7z1;NrS~Y5V2(pg#n|*XYLg+xz>`oSyB(_Jm)O73*%0mk6x*kGgC911 zII+xoJe0gowW3@1Cti;`CttKSeYp-i>`>RwqKsW^h%!z>i5^seFR<-D6U#FGfReY3 z8sAgAj%MjC2PL@Kp=O**ESKtILuCCFl;~Egf>_~&w{m!%%@?f-_JoqY#i9N}F7DUa z5V_2OlJgmj4$oF%S%q()1g$;vH#S7Dqb@dnm--e%%hQb5`f-Rxvt>fb{s+I>(EOg= zY>42$q4@3>(f20#MUkE->yaYT42R;i(zK0FEbL}MB)JU5WhK$?oAgw9loXMs8x)&N z&)H^cYn>f^G5E*DR;o0Z_7RMOFJxG14}(A%bm>Vdpe%cRCxwJr9a4Mum~L zJC|7IT{R8UhfTHp4&G73(z_c+n1(dv14s`?1K6nPQAqt)dCFi7rUwJr} z4dGq}CHo^2y`K%?{vL|!go(bzhH%@SK;|n zLGfA9tJx6lEl^xbP4u^H2=`qmp$OMJCH_e=ggX(6OZ7aSSiw_Y<7zqPpMw&%+N?Jl zA~p!cx5kt_lMUfs2PI;nQ^ITr_faVL>dPsV{Hw<0vgD!-5Nm4fDa(e4tqR4r%#_@c z4dLzwCCA$4(QF9!1SsjMFQ9}g z#M2pyr${3*ME*}h$%DK7LF^*a*bwfophPTpX+Igl{UQ{X^`?v2YzX%uC|*2ecUqsL zG}bI@)&NR2wp^d1xPxqn;6+e;<CQTd{k$!aKJJd5@Xy6P8VnMswV zIGw|>@XIiYGCa45Wf}e!s6kA;8dm}P#B?@9@HbF`399v3R50N` znq_cvC^>d(EBVwUbzHt^Rd5}YkfUHS_vL)iN>;Wd`o6UKRhRVwu`Fu_lz_*|q$Zza z9?2K2Ol+-CRx$PBIgE@nVwuSxDCo3ocvF`UOYbQt*+s1)_(aBCthFUtMKpq9E3ED# z6HgYg%w#*1KoK);;@XfQ8uS?`UTZg=z=m*dhZ5bT7M@4me-g_RnMd0qxL8rO>nM79 z6dNLVBb0DqRRrtb-FJxP5xQiGj`xfwmfpiqTo0J@3U@jgBI}+|(v91_o(m9VosB_`Ko_vGi7a7Q@PT`x8s=N+_=TDi7x*DS5>5@xVII;g^S+ z5yg*|ei|#wo={M7?op`c0UGl@5YBPSI7YO&n8dJwd2nl|s(($1e2XOvp=8E5G7zbg{ z+RR^I*tQyvvpa4xT1F!noh>61#snBT#<3a3_N{a&(GI-4l|FY-w+F7SZKI1}&Y|G3 z+i+3uA};EIS8StCMK~9N&p@Z5zk%V}j(gL4aqAx30!(*7-2q&B+|GAF>w))frvh34 z<92WXUBR7qn47LI!^mNWW0Fp^lP|+91dlen8GLmouYCOq98lLUqg`$SPwnC*JMlen zX)&x^S8z=bI6us*rCtEXtIVIF4h8lnbi55bxLbv8;)dKJaQYsu?`Ciad=OV`?||bz zH`~z**Bd|QyRU7)8x8jcC+_7-h~vQh_p14~kmm>By@oe}z56JQ{U~^ZdgK?>{d?fK zeVqJHaN2$@w(Lu&JhQVY*ml6QYfl(84)6-VW#DB8s6Ngs;JAZk3{>xpS-~drgh4u{R%|DydcQygYTZSXD2(Hw^F2s<*svyYgF@h~FB@e#P*QRCPS1Mk7rz2dwC zK4m%X!f<^-eeURwmi@v6)Pa%n1qC=dgA{fhZz@ZPVui{hB!!JmqWJr5ukAK}Ek- zzF#oVhk^sAdB<1<#%p3|r}_!p0UL)^EcRambdVUVQAg6T%D2Nqi1=iS`V&zj?>=(PhoaG{W5y{ zoSEIgWzW-c`TfB8=eah;hNA}OIrLd@-~umuUIt!$!R#P+V4SgxmLsqeerI}8!Ds-3 zo<+I>qrWj6^+sZ}d`B5OGr{-Zpl4;az^E5xN9-%u*`mhL0LCffmaFG#xzpk_k8nW214D8jafp-y2737#+Un2nF6^IU+D_8Aq8{F?MoI zL2Pg3EVaAl-J1+?j}&uE%yjEggXQ!vMXN2l*dWq zVK#*OI+VPS3Ot9IG$j*T@wrLbm<^G%FO3(D zvKO0zy0RhMuR+)RKfiW?X4dGr4B?>o1 z?_)!_bD?Bq#i=8RZdmjUGK9Ox5`6(#|K)?^EIzq7_l5T;rJ;cji&VeISO|F&SCPO6c2j$jBw7|@{Mti52 zq_^1+Nz*3cfc24H-BaHAIymwXSHN?O4UyC{2}5T&yBiK*L%1jWtAjrKR|joGR1U`f z#ZDL@7uXP4#J+xSxe$Tcl_O&pcxJll(iagveXH>bshyckI79F#~CW z8240IHXEX_bx>SGxv)FLGP|_N@CM22$t0HE-BA4KNy_>sHbmC(Q_u=iIqP&{89YlX zQ#k9h#L`=SD!k|;YQZ6Fh^#+@lJ_CIs~4U|hH!VR_P=YbIv`EXP0VNbDwgL>HblT0 zC|*5L!=3mY8^T>|x(dZ5RrL6$+ijuSyr7ax7z!n50zFIF5P>J4MDLhlW3tH*?&?s| z^(3ro)r}3|eiur_a_?kAxUWG8S?<&sWC(XU6yGj8XFi$@;hqO2V7WhML%4s0l5M$5 z%p^m&>q2o&z;jgiik!P08^YZeO68AKa5$!*EO7KqEN3`@onby3BIyPww!tQ+V{8a_ zE|k0vIj6tCkqpks?Vd%3NLmX@);yI{E2+HaSz>u{W*C(8dGS;Y_j_!J;EhnSvpD!P zu?)TqC6Hx;-LuIM!S$g;YO1^uSV_{6SpKjd2IbrbG^07DgL7)C?7mpR85o%y?^#EJ zOnw+j=v6a6US~s;RpLFI0xg{L5LN}&0cIhk-bpe$u_029f|7HKZ+7rn*)SAeV_t2_ z%CAteU$?%xz7iLH^?F(Uv-Y7fbF4JhA*l%z{Zc|C$93Z8@K0e?rCnml1|#wvR?-pa zRyLNh{a;E5QIUxHplDKg_Yq>*_BWvTjkm1QEWJ-di5^!G9XpsgIGi(U=a41n#qBvGpE!0?GX50%U{ibpiN5|YGmh)!0`55H4 z*xQy^ddEQVv)A)6vGksX62)9j>!TbC$Pl&iLGkIS{w1_XcQ%B3A{3Y9{*(>jz5pes zyy@4Ng=7eK1t@;guYPcLIn%E%u_2O~!_Yo*A)S5cBI~$@}lb{6j!BltbCN_loJ1Bn3 z{lHQ(gu6bJydCkXXCFkr#D;KBhT_}KZub^8ggXi)vQzo8FvAyLrddt~k3n(mAg`wn zvGh)Z5;ebuJX_chS)YfJvztp!De@s1!d(XnzAu}Ax7YO0xJza|5enXbn20^_Q;mD1 z^8%Dem}^yRxn}8o6iUea@bdIvLlip!N)!v~N(RwfU$7zEB|pM6X1QNvL%0`0$$Aox z*Iht#i4|lB_iIqRmirnT!u{e(^o99-<5|jvaQ_4)3O7~Fw~7qm9swn6xp%N3+%X@c z5nse(OW&bt-PsWCO;AFXJ9#x3!aWR%&-|Y9Y-K~Z|At~)i)WiJ;2v(JHDm~P6DXlI z>`v{^hHy`U5?QM|Ngq~Q@>{3Zt1W$Yt~x6ebf{%!=Z<8VVy(7wQw48Qh%fUX>5oN!IlJxCA98q@b71U-n zzk$;EPrKA7(^Db^PEl!oM2XEdIZv{*$5vV#RPHpCe9!$=uy#AGVlK~;ywO6z+WiY9 z=52~(T)bL{3Z0LVYx-w$3>8{h_vPNbJ)-F3&fxKp>WCG3oL$G$!*3h3##ErHUtljHTN>1`|@cR7fd&&{jpj9Y5 zA3dx-1s@cwUu;wNT?+QxUV^pz1WNLxiLI!S8CfA%Um5&}607JUS1-0$=WUHrTEQeH z(WC)_wfi_qRzTeBcLZzqSCqI!vuo}c9@gUb(x>4TDEupKF@dAK1#5RCN}jh@7Jc3k)#2}=B-kI5 zgCo37h_bIl$@A>&XB<)Xc9dk){ywx#ze<`Oy6{X$=JBxRp zN$c_~d_~uP4N5onX0345_ZcPj)of)m`a7cHyo!>LI2jc_0G5lBi;^Q|be@If%->N; z{QbO3HwsaKpGHZrGbo+(xg*Msen=R?+vpo`7>4>sZlH7NiG=;bSJTkGzKk>#K-UKO?i}o+Vhj7o)^Ix4&TRK7>-j zTUv=6oh4Yi%TaRJzh66?i+~>;QPrxpjnLTDPowi9UD(qRW#^+5W6Kvq-*80PyHFA{x%m8r ziibWIqU^>fqvp7cwkyHOXI;|ha7R?qDJVH?rP(hyMOQhZ>~B%>C`dl=6#7Dlvd=~- za@%z6t`e+QjG-v0UG?%g=|9S1l;r&;F@l+~O|Xve7fRNB&aJ=0V(ngn!rP1`?-0S- zos1H5k)z86Yj-C~k-sxn;Y%T^Vc95&p>D#q6RfAzH7Hrm&A3yrb{|8Do3;HiGI%P3 zkJ%MkK2)bzj#4_rMNC{U9SY#1UmrMu}l} zybpV+Bg+01CCA^QJ>ZD4D}Bx3^oTi~eb>m@f_0}|iBj~u%&X84aQtCOnNc8Er+fpY z(45wsGs%}0j@ITsC|O=14R%_r-A*XQZud5Fn_%sZL&^EUl$0`G-V&_4?mLvM3{&@9 zI`;B!EY|-Y{t8Md_X4}##ZlAfTOq3L&s)WX&iG8Q4qa&%cfRG#v!P62(T}bUJp}87 zqfruRruaeL**()@$rM~_6Pkh+^vF*Z?$deFOSnny@`PG~n|ZHO=>`rgG~ecM<@l&z z-4{zyIFp`B$QrwWdv(a6D1}}%mV%32-H!nCesXp1{hh@+(-M>!UZx}9`L6Emzqi)~ z)qmslxFaq6UgvoYC0WxXN@~`x4BY0PTKx?e`_w$$lA1T)W3jIJAe2%wpp<}x7JjD# zevY!art84J!OL94+CR|5k0fH`I>9>PQz%9IUAqnn)*-L_k^g7#+BF4SVs;Izkrf1$ z{^Ign^pnLpk3mUFp87%HMsG;Y+DoVHahduH)|s9`+3D5&4R9-Y$8EJFFsrtId3Lva zPA}4GpD+5CXH!seybAp;SjXEU3b{dNRo?)0^=+}s(DQpD#cW)U5@{}%Ve@fvX8bCW#GvA18aE-CFmFi_~+ zjLQXUcLYkz%)NlQI?uu{wD}22@s|=fBXH1S?KVTnHw7=G*UuPl;SO!?LgC3_;$~d* zE3jPLXHbgG+TWRGn=IU>a~?;D?R2fVq10mSE<-8&+PO6jS*+b5C~^M5$@WB{VC^PR z0$$#8ezRD+<51#XxxC*A)^6M1nG~)oB0~gg*Pz6C17M^w0HQQ|jBxU0iQE!N@k zPzrDGkK@(!(SL8TCCk$IEok}=v+IVC>2Q0^daa&zL>2kUf9klOG^H{swr4J>X!4HK ztQF~V%vb%u@1hjHU~=1Ywyt~JVm*>0tTNlY){fraB3Qd;oS<=q{$yF1s^vZI`DApc`3f=*KamTo)@L_QAbpiGYkKH49xqFa!nP6ipw(B-Tf-bjLY6x zruszZH_pwPZ_7kK*>$Ie0;#{5=VSEyXM*hwX5Z~vm6@{1zva9zY?4Lk zwIZ9#R6kvp(?Wq{z?{;No?RhW_g$mYX?2Q;;YOzm)^5dW%!}idO+gX!BF_<3g)go0 zrCDr4U!Q8RuHfe=sa0I)%d1N2tV2J6lI7L< zh+rLhV69M~knLBg^{0-g&=;kJ0!3S0=+%OC=r-w0To*dBK(G#-#-(sPVESE3cRe9k zyN6Lq{O-CrB19GZkyT2}MlwgbvCUM%>yH07o*Pl(uDdcWet-C(L-#^U#i zV4bxtFR9J@$SQVqdBY4}lAacsT_*YyFq*~8XkcC=NaQ)e`eYEvrgqK6Z7@@?b~73< zZ`%8(ieLqk9Kjksu}t;LIEqqok*VF8GVVIVVjX1{3h(#GweC#~E!NH0fs&szk6X8Y zBa5}W+bZkLYTW1zXIiY?BuXBeVf9AWte1V|Swhsnyo-{>Rjccvwx-7{_EOJp?2CTw zUq;FM(cE-72YU2ui**@Kpycvn#|7aAdFuT&Yh|1$Q~fA;O;~-*$;+7{yDbdqAXhbI zid3H7g*L7csLdwL82F$yn>;5_o8fclu%_;TF!wJq7ohMMdfri<#<&5z*WqA3n9p%N zTC;xeBVek)Pow`(Pf57rYnD-nHPC=Tee~M}dnyJQJMo z@Y~>gzQJ=PkNhOTrH{xLBZ7y(%j9DoRchpf0z2eooO8>*JkboTbhKGxvvmgt2Do=` z=79?zH^p!9_{^K&tS1~k3O+XGe{Z4BY!M2K^zvK+UiP5-3Pv0})cb(N7;rC#tGobS z{;xW$Mk^U>lE>-Dz2GEQVD_a%wOVrcKkh!@aW1&{5mUk!HY#1yGGwkETPr(sFJiYx zP2O@UIU797tH=iMP)|Pqp6}^t=Mm&dll3Ky?FWucaQH4w#j><=KuM`R>=T!Q*K&= zQ?t@omt<`kZ#tf=nO5ZwGRyyenQ8+v>Vz+CO)EQAGHbKA_%6v!O9|bFlG@cISEXmx ze9pQu@9paL9&sY3!tv^96%*%}*Z!(*KT&8O2n&8ex)Ek>kF@&1YHgT14qgu2?BK(| zBM!a+Y-n0sL)xE!xenI9FvNTOMC}da%TYGLQ^0Kwz6T7LwO0KL*v!F3Z9_aZB5F_I zSO>=fiyV9txYNOJfc#rrPa?EtX>8@-P+(kOXew~hKKGu~cfo9Q*u+)ag?Lk+z`nqU z8Qu$Z9;S<2I4!#Lo?O??Y zHk%~48raNaUq{;efdd_U4>-%g(_*%#BtdInRkOsVeGJ&i!B2pr96Y0=T@`GC(EY&u z2kav|!G*wPreklil>mo27`cS`=wL2zzk`nfo0+XP?F!&f2MIg-$dI2E_FC~5ZuZfB6Wq+%z-{>XYdq8^}cCm1bcO|<3FY^VMYP@ zFa*$y>YLWm3=Y>y4#5APADzadlqFp1N6(5ExA0$tv`+8c7rOB8$@(%7`PffC;Y z_WIK$3hjX;{&a5`JN0r_7l(r_!8v9v>4WzJ^Br6bOggw1m}PqOBVesA%&#L}ZLWaK z;&I|s4m;pRATR0-z6y?*-6Ri|00%pmb_ENr!0?s8l%p<4@L@d}7 zpSD$92(D|g`;+1u;7|u^bhGo`s^QClRZnDoaBnKA&mkSIZ z2JWfi`X+emb@rsO+os+D9O&Scy+gcYRn*nMJr17R$EF>AD`_7D<~q0mI7(nRwJ*JO zs@LnoAbUL$+ze@KD%?iaCfD1^W?^^&aDG*+*lybrkgbT435KPupnU~fn*v&5#K0*pEMA#kXJM}RXNJo83djHDd^ zEOoE|Sl4vCoqBHpc1iWB`Ws}1=)t--*^D+xursjK!8{=I->R#DT^vm5Z<{sX4%9n= z%bdCbSmI!6+@5U?*#x%%+c@|xaG--316Tna90KIkz&7pMKwj2sVWpdGo5u{H#@7R5 zHNBD92FdqH_gg}NVvhtjLjtDyP%?KLXnRTE`@noN*QzxJ*|V0w+krbAECyCKE$$>i z- zhTnvAf!H-6_$_3-=`oB3RvOGYh+a^c9A`jMBi=OV3uyVMvkFR|EI>`Y{Lx0O^AR^6Vii@O>a}%(hV~4rlRb$P&4iX>kXniy1S5 z)LVd~9Bg^FjcwKN9l$+}Dw^t5NIeTu%T&LY)Sm)7IT*UfP83lu0?u>rIp8)2{{dDu zb8WWPBkY(7d=@y+!GC~L9c*>4T^A(5G~i)@;Xi>58+)~AdY?UYuDy@i-3(leZojY^ z+60N5ZBl0&;WbKET*W7lH1M(rrV94A$ zOqwqtNr+7rY&*)HUMoCcvjgMJU5?PH4->Yz$^U^S4Fm7TkldRgz0UOtY4-@1V~|7j z`5FUw8(6+M`wt{$vL7VukkK6fIbKCJLy93bQMgGyJ<`If$ZQB-ZM8X002llE@G*8Q zME?}ntflL;VEj>gE!OcN((eZDN4K*xeDh*iLQV=J&tEB>oK zh5op79El(@xi>=gN}^!<$L%%ffKjA>9XRTIFKDYL=s$?`>;g#21ujys&Ujh(ZH_|V za&$?Q_9SEHB??c3bZhP9I1b^frw^0k(Fv?D=#t|vNUJtp1#h3oIRs)W7&-{q)5eq( zr`Hcn;+%D%muNd=Bt&LZ&!?y&M22_=Bx2@1!a;D;)AqQuFuVs?+}2I5aKFjS@{7DK z*bW(KT8vJsU#(Aq-;Wnn4Dgv2egPjda~su23xAKeqaDjvkj@)WKu@-JB)AL0wGKIh zeV>tQ9bh;Kj9*;Qy#6uomCedeO9^(JVn?D!KIw{q106hns{P4mRqxsJ&_a~FU(K3) z_N-P4)_ZyzP?FxueLn-2xR?9>B2d4+=mbjaSJQnAVNRcBu?`bONxGN&wh*YZc0!3? zoMPV1=f68gI-+*>UP0miWRvZ9nZlRWbuaf#n{J_w(+wquI9HD$PQD{5&g&?-F7Gb_ zb>0Ss3LfO$wsqNpzupm*_bHT;{bv88Y)@_wtXp>kCGo3%sc*^*QB;JQC^@CxOMRO- zqU?4k@ly9v-+Kh>0$xIidG7mywfh}P>P~a?F}nVkVC`0ama1$wIb+#eZX{T{tx)1S ztYRnMpJw+oHkZ4UiTyLa+`p$)^9p5AvHCv!+&Bw5Uw{WiQSFZHW4qD=JLFb1W_PHnUMo?3P4Oz~;JPf%#HY_|ytme!~fdDEw5 z2{xdVeq|0mP9?t;tgG=GO2Ttbea>R-)<-G&+FbvHZJ=Q7c0tMY-2Q^KI~*m!7KqKe zK(KaqqLh4Q-nZ^S!P@-?CH|#3h8wLh%VO;|M9KewMfFs6=i57?Mx_Tzve@2Cw^MAm zd%EPAGSTn2EhvR+^Q@ zN~pFRdq*8nnS-xTZDO~d#c4Oq5oKqgP7&`!4jEj;Q#bqU2)BTW~WM3Q_hTlpNn)=!mj^Mk#5QV*YuI3E6m&5M>WQ ziJh5ZT8vGrm;J0G%HE8Udba{C$!7g@y~obS2U^?p<)`mH#QQh2f1Ops`+B8zp9 zTTzM|rI>;*_;=hwM^qcPqwv(!u&K1M<`Ro_=58o4=SC+8*6uo#d`9|)Cm87yj;PSB z-e8vb_FaxB`z4forcnX8vww3$*=?7yRLeUoZR5L`Po7|9$}1E7#?M7bZIWV++dAxY zL`A8wjJfK)%eBtcjwt&Hlw5ndHXWa;Stqj5r)2|F`AvGyJGWmZSf4P)pakCY&h6_Q zQPBf$aqjw^Z@k%OTe~}=Y=ct#n|E&i!4YLQf1BXsmQ(*Djwt&>lo+<0+iNTrqU`HX zN(gR0bRT`m5oQ01l0|N7N6ud%MA`SDu+y@|Fr_vL*3FKtq+P_8m#|##h{`-2rIgt6 zvg7TJD7)G!nq4Yq=(~jDtV33@!+wXHkTSNGiT<#kwwel>;j_}}M|)VA@#dm4DpZNkuROUe_CC$wwGDj8&)|vOB6vrfVq;9dr+U<%G zZ*7j)f+q{s?iQ3nui%V|YlWzSTcG5azh=_e_gZ+N&bthy$glKXM^xU7_lTC`y6XnP zI`d4FWXyY4?iNQ>=Hn=(G1G1q7i2BgS*$b1QF6^E&rz*;7Pi#p_b4TP1V5vt}$T5iA6uTYL%^b2B#sFtsTG7lt%>K}`kRuSgw;5gu>DS34 z-$9BYvY-Da|E{^<`d7vLI{@&tLo=5g!PkHz1cpDdNiO%&{|IT;#gSlzO?ErD#fzkG4=fcJ?g{L6h1Z~A zkogdKh2%uYHi+$la1zq+O0RR$KB7(#n=Et#Wc-z~nHqW(yz@$vwK=_hWgypJ^Jq`c z&FuGe^@huSsc5L^!QX*1T$1)5Q)`mQF7Y%-V>A3ED!Lum$HBBM_Ew8k!`A|rck{Lb z4J7p{k9-Lk?2|g5FbEJCo{J$3ySotyT?2`Cmp$#!t>AgxP3-%$`jvqtrozhKn)?h#U%OpV}?j0Sm}*9dHM_O#hc5sn>esS4bC#91ATzvn@MhbKD8si!R5) z0!XLpyv{xdneUNc+imtX;+TcxxEt7|cSX~q9+d*m0!uxPLN-d8;Fa6$ZH?-SNInkO ztB+UjV#s`m90>nFQu}%b!iAr+#F@F|2tEWX78rg9n0mdJ{upGWPcCB1tOO$Uo&;%k z1Ks^M-3Kl-Ef!OBa0jD?EVb(l;TECQCj#^Oc^#94%!k-S;dJ(9wn6MIvEX0`|Kjl~ zRayz`CNO;ZSJdK0??AW#Qsk1n2HfeA908`>~_Qgpip1@}OjnF_Ddgu36*gt*hgy&#JrGOK1mQcVGg zg4=-n2a|vy{y#ng+>?YQtxa+Ouba#R6WA1t;mf~; zm(@%O&QIrR&{XeMqfWJ_$|Bke#Iw!TmKo6se6W0CturdEra@zVtCeOBj^Vq%n@E}e zo{44D$ZUEHob{%DK|=QT%$_pk|E`(+c={>JY}s-(YKHeqO%Hb^WBz*;&8vK*IP@qa z>rL~>vb4<9#bps~&G=1`wKOeKF|fiU4pl$H>|4f!`kEwpv(4#ma^LLCJr-Ayo~|+! zQaHN`nbtO`RnvXF=51dq`!#YLC5tTfn!iDpAB3m@c^W0x5JYNwW<`@|UZYm_kuuf4 zc)syRTJWr&uCp1_nlH5#mx+F|%%2#Nx23Yt+XdS!zWX{#>hdaP$ZGb)k2<34*j`%q zwwd`B7poHm>&#oNvcx2DvoG3bv33hlikJHJyWZ8W($Bu=*IVn|EG$=C<5GtIB~!S9ej6fK_r?Mg&H&bJuwSrtn;hbT zy}4gizwN`zRKKoEQSzki^(zasO>c0;Z>Z(!GQ}#_{X5=QWvU;q?(dAX>&r^F{LbC3 z4Yjfxyn$F$F5EGc1RrX3M}S|wOAq_1A8s5<7jI}bgLB=`)cFHgF5n=P{8HNk_L%mD zW>J~w$J>vRobHCE<(~xchvs2N)X=O$Np(Y0{V!m-;;u(YUS|^Tq-EBcE7-QhFXj8c zO#Ya(29cIW=!|mtMp@+&$(ONCu+A6!+n$x}2t;~WST5`HC^_f4tUn0WSl5Vzk6i~N^`EsixskjZ1?$)0RH=YF-Q4jWb-q@x&N~YwtDuVcxE@=0 zfr>&@o%^H23rzQ7j@V+sI&<}HLh_u z94LOVis}C$`&eTgQTEp;rE{DeX`LcO*-xXCJT3hi*(X>R-Jwc2km|WJ1#7nyB{yLT z8I#DRr&z4r0+b?Na%|l_g05Nh|*StoQ$Rxo!%Eu@rJa~$mUGp@Hwc87&C~A*KTSkfdrtP9K(J$gSO01Tty`Ca^ zoo=x{gkMIf<-WyU?GQK~@dI{}Pl!eaRr5tZ;5L+^8fKvl*d^6s9q?_GSRGS>+u(#? z?Z&Dzjne!gesoWYMkbW0ei@&jqH%5HX54ag6^-?z^HKP{mAlIVA+xtO2_l9Innd(Q`gHp);B2|eruWhl8at})0 zrKUNHU-mnKwOg?cleeW`#!9nx13Ud!mx+E61|@g8H#FZnqI$PUU1~bb4b2F_dT3Ul z8xAD4lJE zxQF9l{<))+;E~S+>););Sa*LiXKun>CRn=-vKit-rXOyD!Gg8B043*VzhbT3^Td(g z%2dB*7c>Y5_z&=nwv5q&b(D1|#fQuZ+-TJ^EY@x=O3tn-X2k~1)UzB>J@-9I?laz~ zG;b(G*&|RmH`&u(^c}%^R4O#0v~R1p17?sTD)V}j#Ji^IW~!ZWrp3BqgHVcAId{2W z?S{^x(-ZD|+fA@8_$ib`k$H{C(Juw-yjhKz4U4?&%5H z`EQ!sj|u&=VC|mUgz@BI+pcMx${%n>B4%^8D$a zQ0Y4b>d@;@Qk|KZW1%)jpu`uNp*HIWg0-90f=h!1&K)dRyKkWsFETr9-jjm0dudC? zzu26f#C=k*b~mA9tu_x@H}yP=wc7(Fw%oZ!uy%K#l$>LV$eVp`D~t7FHU=f$*k8=f zbj$dTGSNRGo17mGwDXqn3E)IC6WdC_6M}WXJ1?LU&h!ILa*NOIGSLs1%eG7Yxo#OZ zf_0EDQ4(kSLH=~hc=j1>eASOK7$xrvKV2VFVPjfaU-Vno3uTfwHp{@VUS_`y*!W_LbwGoX-`x*5 z&W+8f9emLb_#jGFZyB4&TERL2C`b0Zgw(O4HDD#{p? z(vvKHU+{kln;cR0=~po2{`L#$W42OAq<5L<7xElRQCJR{$R5FZ2pV6BdwBW|#%F{; zz2K}u$(`bjPpGR9Re^3O@n_ulOcSif=S!5>VRwqH)4rP!m3bCQ{BF9(RPUEj(`-3f zGbOYOZEQdHw0ncAn7a45hrw?LH@ng4Mc_hD{|ns7(=YChey@8Nd@Q(@)2nQ<`oGFK z?P_|?D<>Bm_u?6F8!z6s;1W-7luOe+eJHrZE9VVxmZu*9=S(zD-@-LmhaRN&@Z;cP z*O>U%X_?iM;F1ZnS*Ar}Q+;%ev{3prbd8tzMsVE2^T0(tUB=2i!-15E|I0XcbdBi0 zz6fe}j7{w&wN5d$2BoKmt|UiE3lqONJ=4T4uTi<;_`A*iooNj!##WfpU#e$@i%GEU zR__K#wO(AN-R6;-Ak83hH{?~wNHgafZYI>ZHq5`;Sr~p4*k`bpek)|GPqMC~))4!s zQRps6>0nd%4LhOVfaA9d4tMI!ndNrxPQgS-${pMT;ZfjEV@-HbcCsRO!oa6rbDxNkHU�!v(KG_Ee4E1hXw7Q-X zB4o@$Mh-mKH$H{TgUBtSMmJEr@8m(M-sw5(AZ;LWzxcF%;lK#b3H5^%-f8mRp~}F` z=(aAQzaf=}nYoRILB>KPR?h)k@AzaP>P%~hkG}(I^7%&EQd%N7eh*iyIWq>ZwUul-Cfa~dpCEZ`$GyL@+{h`kP?X8Ue6v# zvU@x-4Kf}geenxq8ANJx@gO2YBrJ62-Yocq0GrI4{c>3VxOu)`yvb&zHw&CY$y z{EO}&)kxPBkApXk^s;Y*)P2B_P=g^{06k!GN*Pt)dS71)i9Be>E-T1t_n_DF{fE+4 zOY9x~jgTV{>Bckeq)Q(1$Rm(KkA(h&9Dc}EYS=JRjdGP*0Zxqaa)j>+2ln{nT1cCR z>Cq2(q8mI3EQK6~lt5&7I^}UVJmOXC8AzTbwqpN4iXk>n@Y><5%I52RtRJrfhmQ92 zGw&vm=%LxbNWQDpPvCy}E={P_JuEBvCcc3g46HoHtH%~dAD?872nQBJq*8Z6c0gpF zu7tFE)T>m3dua$nX43Lje2|twWM)4G zIqZ|~Anl&;oC_afruifR*$k2Lzky_p_sChJSfqS19J0|Ts~~ls^pd4N%t-oVIApy? zLi-?*2{Ms_10ErjsrD{d8yG{Xz?F_G1`Z}WQXHfFV zExnR-MA=oIq02ox(%BJZKY~&?*$m@8b!3@f-L4-{jy>=0Vn?UY#%Ep1s|D+n`6%t? zxRlGld6VVSe3738>y&k-(izV>w})WuK8jMz#qSY*jus2n?%yc!X;$GfxB@TA*<2$n z+IpHV`oDJaPy&o)K`$ohLPu1aci9Y2@_+ZKJa-kHE=1YgQ34bFLRPsqtWGQw{X*8E zB&M2Kf75dTW3jGj8x(HPNWTsftlc>%xlftG3cNJ)N5R@{JcAK!V&ZSrOqZ9gMhA+Z ze^)(+l4P#iciu<7c0@HH{aHrfakKC!b-Q1%j{g}7UkWP0jh-{pV(mVP66XlFA5e&{ zaYTjw10|J`>z_{NwR}#9vhT3U1RKwe&^YP5=u2gy-+5o76fy+aJ$dZbzCb;iK1&o8 zsvAm@wM5?Q|F|Q{UWF1MguFrhFGrN!d^QzfEm>8}Z~CE*DElRp;z=fPEG@InZo#?_ zBF~fgNfgtgZ+hJ_7VxY81b(hpc4WOHD)=#!oXOLJjBd+07V6lypcFlA&5UOSYI74x z%yf*^s-F=o1UAuwei2HRGw-#qoVgGsSIp=S7M3&X%%yYb$}w}fjd`sjs=gCYik?W3 z&%|VGazxp|7wp+xDiyP^T1^8rUx_$Dur*|Q@<9Z~iI zl+vfC^M<%r6gG9TMpf-e@VGv9@hYTTmomSF83u?pWODqB=qEwF-~Uqet5oGN5d zS>%W+{YRT2;TDz47h0_2zlf4ZxJBi-VC`PBi22G1QWlk`9Z{h-pd_*Fq7tdNSctOQ zq7+RrwJR|i_X^gr7oo(am|WcGkAk&Z_f`6gbFZu-*Eym>PeduiwyQ|w14op70wrl= znTWJ|&0-z8z(^2E%zU7$8+q9ok`x!uBY$K0t)sE0Ezv#^}`AWDflTHmy=ocRk%%wEG(;Iz=_ z4I!$&*Q4YXcuUAkN0hxCC193JORJxjx)fM$-gRCYHXUNMvNQ6rip!PyCQ7NRQmKXI z%rlp$9kxxa?eRay4tXNas3UZlX?LK4`+9XYW#}O6(C`!z; zBkkT2qU;Ayie|_PvQ(fBy%!}%%xHtRE!1XjlzjU&7rTNKIHCf-kCG^m6{O;F3w7QL zQ40MPWTGP~?+%pMXtOz+$0e$+;Ky;?l+*;r!14(k$H4N|oc$19YIrK2A2@pzKb0ID0_4pp zR(%!7T($65;7$i~R`Zk6Y_;l0U@He#0OJC~wcp_f;dHN%5s=j`$r9jR2Y(0FG6Sj- z28HIp5c)~NE{+R+P{OWhR7>O8W!_o z`dM$E;bur5pAfY>5)o?p}_p-y(YX2S?rS%$PSML z>%VWCu$vsg8-aZ1#KKv?ehz*G9PeP}2W%{OX@MmUJ_oF7D%2p`SHLz7MmDkqEHK;` zm?(7P6r2Is=#qR3JnUe@5AAhTfsJu9u%EziA#lcAZ&&79$PS1d(_rQ%TTpgQwxLD< z2fyHUcY#x1@CNE{$X97haU#!z32_pcaUu_x`B#qrtju?J)aNBGaYM@ zVJ&bmx{OrdV|v@^9e{0K^3p#H8ECfJ^zQ%*(PgAgLiR#r^Si?qTKTebf)7Imn*nL$ zSOc7gE{E9d)rQDe?AN=~aP@=sgQB1e>c1SN2fyMGq#{J9WiPezF~_sagt5oKq6flY9ER{l;$ zl>H`3@$gF0rtAtkgebcUO379J-N8J0g-G<7GSUAz^94$*DfbvN`FW82r4SY6R+KF4 zSAVZwFH+=)vj0FyG&d`2bDeX^R~GBrhZ9hWE}#MS1rgskqB1xAn)!+?efy9j%6=au zHp1)rjGaQ1eG5w7BbChXW(0rD5oI4nNhP;jR(APDh_Vez;UgyYd-crh62bavxZ$_B z!>wX}$@2O|`=QCZ%S6BLR#~N^DXh!2X=sqlAdb>Yxf(J#MP2F+PK7G?G8i9 zXXq=u&9wW`5mo!XyP34Uz10zAclwT@_w5;uDElXrBHzB~dm+l6fRe+kv|p}^YA=-UMAiob@!(|NhL+5ZUE?xjC44&AI``}HPyZC7++ndtZH7L>y4I4*8U zPje5Xoc^OIsv1|IlwPCLJn0mbW<5$tFD4k1H=6R35M^JElGDSpCpx0+O(=QPLVi7@ z?iHf!9w^0BKz=b9N0hw-rKIQdEPAQVJ_~g}^hL?ZwPtjdKy7}7lGociB5VIFL$-FfNtqjmNJAJE6d z4Jf4?t#*SpGTRZA_bZf~`%O_cZK`*`;&Pc$0<6EXlodLnGMAvlSY^dN^PmuA--eRf znp&Sh(F+|>_Fk0y2Tc47if;C+#k%MrC|TYL9$Dgu%KRHju2=61N-frz??s8T$k>WS zRy(3HpFk=0O1|`v#X9q2D2WHW)&B!WROZlc^b!@buYihlb41xsp_Dx0I&`~W9Xs+n zrBSi6LnIP+ii+?eN={cZtRZu7pI|)|njEH6&o`U?qSx*htlf7}l6Iod<HcmY_7KM{E~6f5oKR|gbsGI{V@y6jomtw08>tOkV1b8QF%L|#HgaR z>x_3q*&m?9`_i9g?L)QdM8ZcsTDFOJ2}<$RrrB8x%>==^^FKz(Y3GjN^nWbY?)4~z z7gjO5*QeFXnB#~ldlyQHdA)Lt`q3+n0o&-juc4%pcffYeD|LeKATb=DI5~&JmUQ1C*@xW>OPI z;=GC$>&!Dzk~|cT8~t9ecF(Gm5=dO;b=M3>ROrf;Q}_>d3Eg10V4e9(t2DKWJr}O6 zXi_)Vs1<1(^i}_4csELJJ9Drnt$RnXj#4R<5(v;W_6xVsu8ycGJdKjdk!EjqME5wN z?DNAZyk^MdjwBpW_K#M%$RwN6`g2k&)YxfXJ z$t7kXk)wmES*+b{D7lwbF_T~5l{lSKg{T%SMG1HXx2SHh&b$z%sFN$WehrJYI~k?0 zy-eUpYE6r^I|(K0GHGyjjan9KcM3|*l~%DcbcQ_06Wv`V`V+KC8ig_*9merriuXC9 zYX1&OqU@T_xchb~>AvVk>5fv!Vm;t3?{kAu;}jL@Ym`!E^Z(M+&k#kWxd|mnoO5}B zN@Rf}%KjB4-qs{5F+EyGEY>Z45GA#(Dam1atQD-?N>QrV$GMjY*6yPyS$$pP9fGxc zc5V8SLy2;;#|qZ&S1570@UT6dXV&)Q_eORdU-bLv7L=^k=3onsiv@ypke^W!To^97 zg=77kxZ|cbN7)ozE)PoNtE1sO!xC?eh=PB zmV1w`;`1oQ>@V2nXB=`w715y))7cbU!1a8>!g6_cqLh-?{y5KWdZrMS_g<9LyKP~1 zN)EF>)zTwnnm;3JoW&Y?x7P&&9Z^A+pd{I%kS?geTk#;u?uJri%P?hKP-mvEm36`Q zDDnGjs;xKFsFU6HY>$>Dn1m9r38bq1-LJ~;%0$1e=QUvp-&@Jl+r~5;?})0*4wT~i zOkrz&xi)QTv99U^D2Wk%8F#xfwv>r}8JW%KHOi3rIKmNC#s-vJHYIF-L^-8eqU^ya zF>=d`)mA#9>~M3Y>nMV^XUF3jN0dDSCHG-=JWlW{=?6!Yea^YG>0wj*Le{oXf_2gF zqa+_P$s1~BW>?FxSi3z@;-mc5Kj`+7o-Y&q*6%?np@O@w;b_chAw<>Sew4Vku@L>p z5oOorEn2z$zQZs_l>H7$>0xtITk2oqJd5?evEPi6`lnfW8teL-g0)+z6%*}TGxQ>k zqN#%Q!kKkGJ;M)u*=%{n5moR>l+>Qijtsv*h_b&$;VE{Bo!8o89s9UduJx|ZI=2y` zGEYFsXA8n!zBT>K5oQ0}kSQ&Heivt4$Xxg1-QbAIFcT%$ix>IU5oOnF%Zl}fnbeMc z$P=u4X$?viClK2YO{!ibL}h-j!M`hWEopLc?Ejdjo2>TfDUo#|==L{j$CzJhV(l5V zy9H}^DN0cf=l(5NyKUPu552tO1Z(#rl&ou9-t>zt)^0zPqF$z`GM94m1Z(#vlt2%0 zqvv+8Si5(l#5omy!#lU5D;!b%@DEB6r$TE-E{O?I_E?nIb*|)Hf_3ckJF<>k<4R5l z*6xoerT$Dj{}Lf8^k|frHxr{<98q@UQU;$51z7<4JEH8lD8(C0)=s*lRws+~OKBcO z$#-tXpMteJ=&}^G*sMsyT9F1{Xa2uN` z=`}JB$k7`}o^m_wJ4qYrQoy8H|9>yWHh zxr0}ox8_}$66p4-DdZ`G%D|Ck%%xQ372sllp_9OpSKa^acTEXYeT^V|@g(>>gfHH7 zvUfXxLmh0_ErpwjqD};^cQAYvBkSN}z`ACx&Gt30i-YHNPqFWWv+AQj_T(<3(w_p4 zz3$yyJmYFwR^a;oW;$02yj_+w=#3vjm1)Ttj-2$bGH{AXUxq%So~p*v7$AdfI6t zYA!J0paHISumrf*!6v;@xG`Iy3lW9`V-BtW4t227wYD!ML08~<2d4u|9oz-1YYJ?H zv#zs!DR4NDFQ0Wu&#DaK!)N&6D!r-un>3FvzJz;1VsCNt$$mR(9wcFwTtSfiz|{_( z-^bR|s^JHLwchq_Nv(nKKU-Ilx^iDzj)mbXfb+d1;R47uKmAt_KJ{VKXJ5}e6&Su9 z*k`$S3;9*ZGLP^jD|XV7Bp&vhZZcEKBSsj*dh2cqBNipACD+=2!t7 zxYD~BcKVIB%S7)3Jccg!6<>gKGh@0@qhEky1%}VRiKee|V;gz^a%`3S({gYsT-$#2n}yw?I_ zYrJXnIwarer{Byffi6w#3kkgIk@=7=9tj?VB+ObH>7rXw0vplgPW(hj!(wvS?)nmv z2eD4*tbvSuvHOC|J>V?%UZjwpA%lH#^B@*>pL`8D0+Gl)Z>34^d57VLkYx}F(DgPt z$|J$`5WYm2OU14jOdZ#Gi9UnufXKfHG`gK*WxaEP_d@bbg&yQs58Q?>cW|U9kXC3bEA={vnA5 z*hC$MQ-zPb&-YA&?1xAR`yma@A)Bb<-K-^>DWNw1jsl(!mhb)SgVg%i%h2H-IUug3 zHB*37%@|<#2jEVU$On63Bkbx@{W_A&1TGU8`W=|{i5w=OEAQpd`^41l#XIF*1n>F8 zi+&u!dQaBywfB)GNn7mGZHpjrtwaxg2V5*L-1Y&+f+X^w!W2le&rIQuyfhP-Z+i40%IF6f>Ce1w z{sWS-4Prl^^bp4hd4uK9rnt zXk=Oj%SjkmP>R4 ziAsLc*T)l3l2_>dd+|TYYLr;HG^afIZ>0}PR=G4Io=h42FDXHyymE;a|3}$~l5?f5 z&>oc1a=DKGM@gT+H0YvpwLlqNUh0OFS}yc$D1m1FEVOfO8cMvk>r~gV>rjes)yg51 zUggqcPGq3VrRj!zQ~yjkN#kS4yp@{bqW4LGzUG zCbHS%cudQTdf|$bXo5#V7ebQlO;J2Ov&y|-Ie5({n=&#Aaw>Xh;0ZsV#p`Rce zrH;JTFA(5pbfnHxoNPT3JR1@)1)VbL2m1l}k27E>0W9urlJ?D`uYozD?3+jHg*QVu zm`um(xC6RnSdG&vkED0a@T+Uo2~~XB9z^nBceVS$?(m`Ye5qjfm>Ox-mLs~u#fsg{ zl3%K)g^wX}#JH+uO_oE$3}{DLogf?)t{ZNHF#R2wXp{ZMFR9bml3(*n^_0-ND9I~K z{w-Aa8!*$^?iQq(oX2@wJ0~HN*ZwP!OCRom!c6^Nn&90iIcC7)8TG?cfJ{i0dA^nWdyXjk zSCqt2&(4}EMA_X?@_qYZN0hw)rSybX_BW0wyXrK0?WAYN98vaNC?({Us?Bvo*;`PG zk9+n>N0i-kIt}yfevT-6JWB2dDW*auTPJTgqU*ehzjun%BcA!v4y7Wvu>f6wB>U`RMPuU7Q3X;wXglV zoOf`G?(#BMo+U(O?u;_=I--)+n$3dpvbl07N&A9JR(S(4+7Xqs z5M?uOdW_e|46g_0KJ7)V`n(X8^lFq8YM)8cY1VzpOZtr?DrwdnqP}96fXv{n;G|h{ zC$~%9vT(k>RH#sBYwBv(zK0_!PVIUB?xd^#GhnmGmBZ}c-J7HSeMeM?Urm5;f4_aky(Anv) z2vPQhDEW3lx4DNnqU;$c0Zs>EZ+1l4|DYuO+~+dwAj-Z8rN}PHHh97jWxs=x!-6jM zAxD&*wScmHyO$%%ehekgZ`dM7l)VL|(6|3`MA>x~Vvpl{Jk5DrrL`lm#B6!UINDaQ zK92jM#AkDbV>3VOh{`+*C2Oq9{H|b~`5Tnd$Gpse#X?l(Oceg5u5<)9J1!QiFQxmU z?4KzMSm=J6x0OlUS|i=W?@dpM8WD8zH&9{^d&}V$j;ON!LK*w~^s`vvYQIXINolA3 zc^w>4Df^=&?|0vTbJyaN*J4?jV$WzE@}? zCj@KvEtJw9oV#1FcEd%?i=QNNw54F}_OVKXuo-hB^Wq^#R3|=*GGeB?G+7DG%XUel z-#DU@{)3Xlu6`2}z1zti2!4YM@fs$*oN2k}1aKRbKeP1sG zRaVoT>rGBR_sCld)@~dn?)`#^PH;p;ejO#}LsxKQrz6U){0`Orz!cR?tDi1Vhwh7# zYR=84R!>;CNt;C|xf@-rz7?$9@EXnl-jAhd3rAG3*P+DuT~Ixb-kRfxvcE@(`F68+ zg(y1@rKC4s>i(A8yB$&XRmCjHzP-s2WnZ$Eq40i_L?=3;>`zeQ{0@<-Mcxyl?0zUQ z-+svvW$!~t9UL;h?xJd)*9lSf^C-o)d3KfcLX>?MN|E;)sLpanlzj{(mvxPOm%TOW z)XCo9(X!KAN0d_5RF@$8R-cw7cpSy9hVDFjmHUeGqB7AxU4DeZdr!99&XxU7g7r1; z36%U-TQtWLC zM0Y!)s&z(^CbJPBO}@hsWiLj__3hssQTF*;>FziA`IXLQW9pOqtI=eqs5E;}l5d)v zC+*eurxxq#O+iV0%ee;xYxk1RDBk6bJ}+3if1nimn;7l32~h<NbOccx(NZn4UFrep#Q{#~$kYkp3HTROLm zVD0un;nl0d>QnAS!TQ$C3Y09*-7i?XwZEXf&W&CpSi9p;N-Mhm_RV@UiJm4Zf;64_t`)n^t)=E=s^Pc{d#d<|J7bSnWxY26`Yxh2s zQg3rBI?EB&EAODBvY{nMNAPPQ%I<`!3dd&(3(k5oI4jDRG-{9ZP`ob?8Ybsa`)sw>hHnX6&Xele}K+?})NrK*{}? z^OSwN)gO*1`_k_i!1Rz=(ufn$3P+UP|Ai zn1aU4^aU2K(c|_#N|L;C;Zym55S2H}D&FQ;w4Ec$?uk`maCD!xC^o3u?ADor<%mMtx{tYTD_ ziUlGdvQ&tOg0clDdx3xz*`#4dtPm6##EM}N3!(-@M1BZS5vqa&LTzH=FD>E?sxL!N%V3UlN3S+O=I3d42(8hmLm)RgI8?1b}pA? zZ7CSuI92lq_%r(CtgHX z9TY%P{{_Ya^@Ee3PWzJsNu2}6r(I%wOaMte3XFRetJxfRFXpn`V16+BR`LO5ItV%B z5tdiEEL&QypwDLuZF?@u+QDG_Glg~mmu2k+Fivs#)w-X{vi2Mp?=P%8gppF`FOuc9 z>jK7CoBgu_C+_cXSzPlJS10fI8@rB+*xG)@Fn&P*sq&FmQSccN`hG6Up+|u+|0=X4 zT$Z(8f?1l%0#lRgMg0O9&&PJd14%c?@OR;K?=_NTr@>%$2q)8XkaP0I=j|C}+k0$z z3Er{Y&t`qrtSr*;QVORjHf3(;53Dpn%%DO{E__k;1X z#LLO`t>;MmS&o?TA0Bs9BX)v(g(XZu#9{n)KrO84y%1K5pqy%jtyLvy?y{wt|tE< zWCxo$7s=N)#47%}Y@-iH=S5tWhvP{w-g6?6c1DurkgtN-rzY|vY1Kp;Mj#P&NX_T6 z?DZ3v-KtlU$XF#mpP8p%Ou8XE*^+xOXx5VWo9y%rm@TT)ACTjPlPNX|mPc6d3bwV@ zT$a6DU_wG`d5O!ib{7~gTh$5${z2k*vNGKitC)}Tz?SY@mbK4<39==taeD9#iAQB+ zljvC58AEBEN1{&o0~qtSBH`2+l4aK}V7w=Ub{&^x?M*PD?}c_iEXlHVD;U2T`5c#J zZS6QTl>n_m(LAj6=_Hcnu)l%{ zjAS$3LK8ilOtP$94aS8FknKk$*KJ}>;XrDgAHs5)0vr2UR)KKVU$`vyT3#x~!~dAG zEq1}{xh!i9wa_A4*}J*W_T#dw^@9m*V=GH*)yurYLb9wK2FAON7;0jZx|-g>N>*!( z94p4Cn!zhvmZMw%gL7QRdSsuMMzXA32PUZIr=*iCYaa*WD`gwuoAwEpWo@I{$oPLa z4F3=JrsfJDHzXM6hs)Zd=B?|HDEk(JabQ)n4TyY=%d&P*U1)cxk#`6nMNX-QJ{6J2 zaZ&dD42%Gj{-7AWs)op&5K}sAu5u3{1rC1J(k)Y(?BD&4*wa9|7q5DBf8X; zMY5dbQ82y*Y!PX@-bu2o{Q!(>p3r7zlPqgr0^^x4v=I$SmbK%-xVka>I~cAZF3Z}2 zMzEhn3?+X&f;nUGaf}}-SuOjnjWN+LWR3?hFt&49j*{I3li&>I^&|VGT$Z)}feAjz zV%~*zMpKey?LT1rBC=&nGm>TPcVKMn;5*n8J#-gDkF0zbjK2fRdk=x{#s|^-9c1m> zU;@vJl_ydf8Ffr6E4P#l*Un|AxZlSSSl=EPe7kC{l16quJQ0eIHi0v+e3Yp(VAr0^>r{G8?%Gkq>cM*7m@MAlz5kN@z2_<+7~pgD;=>&k;ivf0uutA?;u#snxqPKGfsJ z6{ZV+<0JzgRv`c%P2Cb7-w4Jt$7YnVk<0Q1TMyqNaV8T(Wo%=EuO_EjmsFBkkegs! z=h;RCu}*1EvRuSPFt&Eg`aZO72gz~~7r@|iHe5UYL6T+dc`%+QSr7PTxH^z5YY%{N z^wrX9#h(VT_Ux#UT6$lCF{iTalz^iX$#RfQ#QeoV&^EC@M6#Ux1~4|=bL7XsgcRof z2g}dgfP78JQ4KoB;{CCVS;_UI#zC}l(ex3-qXuF99pq9~wmlrHY*Xb?kYiN&1<2P_ z`CG_mRk?nbSfxyr+d^Kh%1=S|&STBHVNsu_A;%Q4ligG6MJ~#AN2`fK|;7kg135B)3bD;|GgVz2vSK-t*{r^m?YgkX`eI{5oXoELPsmlD@24 zYE%^99M$C)$YoQR^Fz2qbcw(vmlr9Y)x-M zES|;O+YoL)uFZT3Q~41UABt z5OW0NT-Emj;#He}A$vT+rt2fIN|tKFARjH_Efw_<PE#d_tive z4QCpme}!?XvhIgQ2}sX1NS_J z(fXqr>`8!50Q5?9^c;Z6n&u$DT7XUX8gW!_H0F=YUWPZWAXb3BhdvPvxzSH*q>})> zHPGa7j28_|0@$d5F9D7MP*~Fwu}b96;?=O|Jb+vcOa&;^z+Qlj8c6AbcF{mCK%LWg zP3~6=G|0Un)9Y$jhz`xFfeL`#8tBp&`D%0P;2P6ZvQ$y&rru&>0}>tm^YLKt8~d zNc7Un0HqpuAK<(S42Rf(&uTS@z67rDH`O|=KL(Ww3=gsgcGr5Gjf_sI75zRGhksY= z{vAO4IkhL10kKLB0IlzbZyP;;CA^{=gHz6n7ZMYm0_c6-s6_G&ZYf_kBziH(v#{W= zwC@B+xuAjz01g2D?tYztvC4E!(;c8x15*JGYi8>K%omXzz2Y4NaIvC2wHieDRW3Sr z5EA-B7~pkg?1?q-4uDSs#{fbAJgb^64404!Is$Y7pw}d$Cjud}Ffeip_ zHE;yr3IH#(#!$>(S5)8t$OGV27!OdQfz<%#HSirk?q8}|d_J}e03NM9z%~G0g$V#> zHLwQ2`Zs*alIunv2AHmasA1R%YM?bhr>m;jD1cG`9-09h)-+`RIoDLP>i{JhXgVC- zh^GO0IRgOl0eFBH0O&D74vqrs(7>G|kSGA(>Q(?W!o!G5n&Zvak(dl2-?I^O3*@CF zCkr_M`Nwoiy{J)WnSYq~Q%q$Lo8j?F9_J810RS(q{%8yb($qmv$h#rahqXx#LFRMJ z3V=p<;*Iz6c7VwmI1W&zfuu2LNjz2uvw9}TBZXWyx&UAsz$cU;gXyA7M z7Xa_$qyp@2G|&cso)hPqp#V+-=r7YEfGszf8w>ZDAX;&7!`t^4faw}Y9E*Mg;1#|f zAl@K=X%0Y+fdy0X8W+TT@EMJ9eFVcj(7BcUa zYXDa?(DG>v)+kjo5nw3*|5X2L0B1F@8z9#NvmFQqc_d_>^Sy;|(ZD!>fCknAoCml> zE|9I!s*B+n6bW#NIv=uIRhS9@N}`!P4Q&ju3_MSGKY%p`AIZkIKuFOEGA}%161+9g z9iT)544_N{KLcC=psp}=c@_gHmf4%45Qwf=HP$(RVhwbdjA5vO6#%C-a2dcHr}}iB zf>t3w`+dkGHN{DQr5b2C6|DlmN5XpmN(~h>o`#)(2HpbjXrSSA_-J4ifD*5kc>$oA z20A^5gD?%e1~5khe**YbVCp^t2VwEdV?muE#@wMc>@I-58aM?|s)5KNoK$F_F+i7^ zco>F0v(OK~3&1ybFF+Xpui7^NF$oxOf27upz6Ov7!1vBp4}1Xl90Yj>WbVHb;0l1D z79xKEP-s@c7199k{iAIrj#U#?kOxozz#|s|_yKqTADJboU>|8TaGf;CswR6DGyr@E z^#nKpzz5nmfMzKwcoASa0XlYi7hsD94gj17;JGQYvCX9-G<|8}E`X5$`~wz`18e~h zi2_^$*kpm(N`S&zDkuX8Y2Z(Q0*k7tHwRlF00m%2PSmQ&x>#|LG8MGT8o^GzhTYK5 z07n7%hd74K#Uz!6;_1M3B|w1&z6J1U;Es9N4FT}Y{9%Ab>8j5Lfc_e|V?KIK19qxvL1j|~Taf4OD~fM3)60B~9Z4=zMG zbyc4!0C@m>zx+19bPfCnuu%i4FQ7v;&gcr)-AWRFd39;Pmf(VRAB z{t1f3kewMq5q$+$e*>6Z zz?tPsXjjPGY9v5p78G=3cO0NM0Ngc8O_Xs3eAvxja7^Qc7-}p+ zCBB9hYNEEvO8{6xN*oD9m!Pwns$e?6WDQ&bH~~N{X`1vp=8|S2*g420&D2y}E75iU z{QEkG0PJ_E#q@atZ3n5;#zFW0NiIDKp6lxy9SVTk81YZo2WGaH@ghr z2jFJ;>#!x=E802gH-O&ktKZOng>PX4xlb+sGJvy%n2ZwKrEqT%p`H+Jce1cMfh$eEofoe#DSz9 zLCiGP?gE}$*u-V|lYD=J39(f+JO%F94Dm@>ITuXuNp*FU0|H2qQ{G3d2C#BOP8-Z+ z*?Bz}WhlNLPOGC-2p~Ck+k(=DsH>x_5I|D@0!Epows)%!IFQt{z=Rg5tE21}KvE}f zMdCBn)lo(WAgQ;4u`TASqom#Bviy{6#}82&+LNyXyhH%W`8XIChR~&jsMnp_IFQt1 zz<5=)b*li9x&lo3bXM^PzRCOWM%rJC82NCzB7jtZHXozLQ<>uuuA*gcz*Q`6FSYNU1*eFzx)lvp;PBie9-08$wjzyxNiE0^50ivvkL5{%QM zs!Iis)IWn!W}yNfU{h@v;6PFj2jiWgsy7HAsedB|W%FfG?*4=WN$mz>L)m;;l&u0t z>Z@RsnS5E4HlLCxH_l`*-skwTDF5T4th`Rl9CcZg`#n;H#^-W@MyATT%r9HHlWO-AZ2gZe>`N}9?2p~B}m%(8^Um3;Hoy)TG zLNH#IVY1Xu3zDddocIMIt65tg7eI=<6ijdtPs{o}m*vQHzr;2q%1s->Wm&r#OaRTv zC;Kx3NTKii3R}bTLTw!*fTZ3C#)TE8X`z`bT$W?E-iP*GjGd~sbWlc-V5A72g0WB5 zw!weIYgsY-HB#FKyMl2K<_n})mvLDhGAF^EHb|)QC1EHqbyLne4PMN0%yRu zktAPSvf%*^B=t}*{<#0Jv5x$f z14+FfjBA)!L8Q$QlI7T|!T2y4)9NG{zX>2YH~kL7c`!N9l%CBWv`Cv?NovEX3{3e5 zHHDf-Igq0C1QQx77D#!8%W?`wzyvW#@C8z8ALBrB?gz#-N{zir07?B57&jihrv*|n zkCQCN9ss7iKwThZtpJkq8Dd5;^MAOZ+v|IhW#^B;;Jz4NAjNosWLeu8jB8>nyXR3f z`-cKZp&R^wSw{`+<+AL24UG9Ic9sf$_$0})b_p0fmsO7zQ$E3ES(|wZwH&E_c6+n{ zQo-+lv11G4%c4Y-b0DdE6NBcYcLJ>M2_UJXeuR3YSQaIZ%W~0+z_=!<%aa@vKyt4C z6B=obSQce4mu2UbV7z1avM9fDQC2qn8C9MnmPL7%%d&PSn9vxt+?dlGNaa2P#x_Q* zeDVsHW#^-0{|qgfl9u@kiL!D881n>-uFr71a9jW>a+fpMJjTbe7x@}l0!ZqnzoNCq zGshG7?DQL4mSfjE3um{`&gQbL{S%DM&1M+zRrg`Pkt}Nufw7Nf?P$4{$9^YS)*b*8 z7{?=99yv#{tla~~!x9aa`WX+Lhd4o2z6~bC8QP-7avW**T+m2ui{1>z{%kC}*&wBE zhH{Yusp4J1I14B)MOn<3Psw-gLAl8!{iAr%i34L;9F{Zb(C^0%i7G# zNO`W%=5txrt^(tjCn8_vvaId$Cq}^tu1#CRWm$V2j2pX^o<_X==D5OvRHa$O3?&C@ z=VfeWYdq*yR!M3N82cCYs&n}M!fhL=XJSI2#Zd+bAZ6eK z6T+U0tIrA`sheKKtf?J7x&@HbelQ_akM_CND*{OB`>vr~XY%Dy(q?j5KHm8fjALE| zdv721dr8+hkenX}V?)t=J&KhANa~-!DDdX%Q8fOC14%swj1%5BBQOv81(4JsFs=ox zBpS2E{r{3IXZ9QzGY;c;(R&4uoZ~By8ICllXlri)BsBx$c%HS3LF^y6EXS_*ANmrP z3+{-*OIvOMBe&Mnl`yM4u3DT7YT8?J60FrYMjGa!Lsm?Y72amPpBldP5VPI<`-F9JenplhGaQN9+=>Z%mHoMYh0GKzkqS#y49*lIO=R3 z%Yl^NL@=Hg*hUKdF_&fMh&b36^MccQa#_|cBSyVYkoLO(Qt10@#3>F{o$;aolKKP~ z*EQ|Q`cgI%Uk$O|6R(k4-DiUFTo((U9Okn8WPRoxaf*8&3t?H5wD-9zPiyUKqIqYl z3!iKfK+2$A0-SLwPwRnLy#h$;|G<m;J`vzRXd4L6L-vUWWfJef<{ zjLTe>wXKrk6yG3XsN0vaOYY=amP$^md5z>a#io|flgo09MPU4*gtS9kmbHl~7$w)^ z*xR&HO}+q9)i#51;9>$_5k^VnKvH)F6I2@}g9#w1%fTp8`g}F79|P9 zh!*;f%W{V8EXc4(XyEOfTUgnCWsx-yssVb051Ud z`3_)*rfHmw8fcoy0CjRzv%LUa0C=Ib8pbJeH1HBYKm#=!Ap;Ez2gqrw`s@TK1mK0< z(HPYR;J0}P04VJQFue=lYR7M)`~z_tc<#}zNt|+81G50k?N!Z}0J$1SYKl$=;O*HT zz^8$A07n7%9m5L%jT|ay(JW4x48WUxGC-*Yb^sg&;5Wk~?}}5b58~>5IqpS5?gW{q z_6mSo1K$IbXdttBoKmKNF#uNp_|r;|Z5>qq3V=Kfbh;bKXkZb*S`8cl2x=h1j&|0- zXn;l?)o7amdaEF+0>Hy=*0$K9?uk=2b`;NvKs*Wyez*E0Kwc*_7(K^!_q|9SfLH5T zfHDmP0Ip~t>ON%ukZRTyAP;~Kv&8@&4IBp8qM6lcfh}1B!vNwts{u9w1%Sh(p#Z}i7!pnuoCGKU;AXuaj8pb$nqvUgM^&?a9njYrI1J#|z`%|e z-2gm*AE19P)ko=sz6Ril_5`Q^;FT)@Xz`c|P6HGGaI^a!Lh}OfMl1qQdaKdC1jy5X zxijW<0B$xK;HU<^0I)s|AG+_K@-TYtaXvu}gt!en_jnWFng%Wb-3buc7o(8wKEDbu5(}Zy zvl(X~ABKXvwCIk(@uceF0q6}t4P*Kep!7-MV#~v@drEbA79bCRm$DCFDFDAOUH=i( z5`fR5g#capsXku=?it06dS4r`*xUkoo9m0Cns{oif;w$4#kA`V4fN@vaH!mDExe#YF;p^r_ov(wF9Pzf0-;PxjjDtj} zd|3(`07_*C2V-TXHUJ38HWjC27y?zR5g4cA8v1>fdeObf8n3$YgbM&dZaHBO809Vg z1*fJgO#3#NV5NQa2^%Zw&>K*+gobGse7rlD=Uxv#P>+k?GZ5)%o{S3 z0H(-?ce{kqp!`9FQ{2N8N14V@Gu9`!pv>68D9z>CcLU=%B-=az#{7-Uj0WRBA~PPc zDf&*MQ2e;TV}~j3N`{JG0wdoE&4!rQ!32MjnRmcAPs_{!FoE9$BfgSz3XJ)j#%P-s zHiDWtmQ3cjnwTXP`?S?%Q^DW_wsO-pl(0{7EDelaD|00zWkxv9$xDRV(vxha8;A~d z2x`nt7Uv{2=r$L_Tl~{5y)3{u)iWF0-pc&g?p9`1duHp9lv3o@Ew5!qKAkXjr~$LuqPgvb{bhFZ7|m&guoOHQp3^k{EN zzOp1E)$|Wf8qu-K;7*|;#+vmMqES`HI?dJVqUYg`K8 zN|)PgJD6aG%$(pc@0p!a-=vJdao%it)%LanHVbMy-WzRC*+F)xvJ-MJgYzOSEPq&; zmYLmbPj5)TMyXxhFiv=ptF_jAh#kDwl7@|(*_FSt%bm^aA73MJ^};#j zg1r>RYy;!b*_;GZu47_G-OAhxCaAON55`%FQA3-UAqBsY3R_t($!scwCccCpD43Q& z9$Cz`FT#=A4#=g&Y(n$Wo~wy5#`spuJr0^IXwX(- zF{};%XeI%M5kN=q1+da03IM7uG!4e^I&zIzDOvfLh0Y~r z8kVzTSQ;$47Ytl;@y$LQdloGQaK9x_7Uf_X$8iwvl$Y`ECS=x*#yFv z%SE7qI-`uSw=zyJUY*TsFg6{t4U95RPWtCCrsg>8fOIx($Kl|kys0!Fv6O|DvXP0c1yW3zH{bU{Wl z)AN3*%vmETCVDv-G&5T=)>4-_9!`pk7&#Lw(AB^vo1C4KW1XHEbEFX@EeGD86Y?|xt3TDF8*n1 zQs(yHO!864&UwsBhR;LBhha#L{sc1GkKHjJjZh9yzJ(p_iYeZqj`#(vem6^fV`d?9 zx3kn+cE2U&HpdRpjzZM4P7SJOhS4KjBeqPF=E%4~gPt1q>}W*^ReuCB6j7iKc1QUE zHON^CG7@!n4o`{XK?Wm8p!y)=5d`Xec?eQ4lZEK7vXgJVQCZXR*giYBHz}E2oQdw4 z2HT)b?3~gT1GwsFyQ13<9KM#iy%l{+p%x3RPl`!cCqiJNr%uZfi~Q}X3?)d~eHa}g z31j|rW_!(&&RmH}kx}2n(!uVzoLJu!{Y;#4wwTt88JYvpv0k3O^TF73j2BGskZcnI zJ9v_D2Kp=I?6UtQ&CpDJR3DC0_E2k zJp`s)$K;b+Cppj@FdkjfzA$D7n4r$<6d1d%8WGbTK~w1Jao03#t~#SZ#OMOe08?J+ zb^GzkC%V-zq?WF~0>>*Wds|{nAkf-X^OWfv7~ez8_81Nin@-nSm3ne9KN1vk*Bs1U zt6KBbA5HnN3U%ZjrV_~Rc$$O~c0&{`NzM)U<`8`bBpS174l~6)M~%t7qwj`{W)yRv z6F{^V`S%h2lR=`%*xffRX?(LWtpeli%r^GMbQXl{e24`}j-ElS#De$`NOV)kXdkvD z57ln|xFz0L&}vy~62COk8#-H0=6alFnw_kCxupSn>v4?AVNm$is|Rr_097@Jd!+6aaBrU}FMHYWyNTxq})FdHqk zO{d`GThDGhfdi=kI%i2Sc031~#mAV^Jd`>c-3N{G7-UZ=m!n@K*@{P1KgK(jy8)0X zea{x(n5=J&qy<#}28m>=Ix9MRCQr7CiR}kw2PMlkT}`Z=Py|?+y8)m3!3l+W+_Xy^ zH)XNs`=WK%!7wldpTMQ#rtbuh4v}MLVem|$C9Skm!F$1!>zICEd^%=k81p6=WvU$K zP#ANwF(`-5sL^Z`kK@3q;vHa?ze!VaZoe?)(_p+h^B2JQaO_tVU=5hvJV4RTFy#?2 z9-a9`Fb-Wv)0|tGdSJ{to18GF7Z|%P^61qZ6uzmgyTX{?Y8>3`;#e=@?`1 z(c}I&QVBtU=4MNV<4EO>dDPO}D!K_|G^0>F4B!~eR>H%S57|7LKJ{FS*#=l*OtV4Q z#|WhlvNA?e?gCMawQ{p?v~&XU0wIfW>`=$Cm%Tawi z@qn@Gm~~(r)3q`Bf3)=h7@{n+^^e;u78b%$gUPgjie%ddqFr(!qcCwAGYkObu)%FH z=h33T30^Rw9GXz)vy2_J(u^LpIvzH55UR5iHZF$aENqr-&ja}JHN&bwT<3YHUz3?` zU;-r?Q+@KLspQI-&xP)I2eN-Tn@;jiJfz@L7g8|Ji^dM@VlG!w16E@&a_a_daJp#f zwr&8|46V^<_r4rVxkqMpf^qZZ^Jo&OKDX#IYUEWejMBsxcx3h*fp!20%D83}0OE0t zI;jQ3q;^GQxC{otC~*+k^d|uO9(f9AU5x(QuQAog3Y zn5EGn_UOW-T2U~y?_pmKMN_tZk>az9L$ND!h|D4i=Hcmt9Bhe8p!8|?95w;CG3i$I z?0ztP#g+V?7sIr1i!jP`_Ss+*9rKWmslIm6`7oqRs?L3$2ZMCjJH6558vsxi--r{w zstigk(M=qI_=Z}djI*(iTY-ZB?@ddL(WCZ54r@OgBjpc@H$&{Y(_$ARQ|zp(>e>{H z-)5qN9y}#1fTUhX4!E4a)jI@G)z#N3;WrqfOc+w89mLUpj8`k0$cOpGBV#~KHirE$ z!cw1kM_3|piOet(YmN_teSnM6uaWB>aZ{`3djxjLSAzmz92Ih{{sZH#C7-poT!MNg zXiW9Fn@7VCWvRJ;Yh<=+x^IzOfk3FJSdXW4h`^x>`6E#9Y&KK7k!_ecl1%*rGAj zXP@x3h@)oz16}Wod6}ZI^f4&rKFEken{XQIaWgTd2HlPkm#EH>@slvvjqidFt5uJA z##kba0Rc?wpeR%2GRPh$b2_k3_#1M03Tsn<7HGH>gPF_N=0pXt==jV6jKaQ9`F&z8 zO?wBxwfg^_C;2I5vmCxSdbIHs;l1l2I%aj@dV7B`uGP#tmd>DfQ4QjXwU^JQGsD|8 zQlqz$7uKqvHcdMQ5UN}Vqxu$%uC+{fCFbMqWjg?PF#_r={E3)_W5=Ub9;h936#^wR zSt)?JbuLg5n6#MeN9B@6{Z~n#-_8M z117XZ8~2peDvBW1#L4|6OnVYcP-p)y7^R1tL&|d4s5#gn>$P3Ml-P0Fb&LU z5#a$AruBny>+HV(gYN)IZTmBrk?i26)cU!~tG6oC!IXED&0B!+w3aK82gaBh&>Fy=ilA>HC7UxhKhg7NA4IJ)SyTd9U%{JL)J7{&|&10gFt#GU-WdiK*oR-EOK0Lrn_5K50;1Q}ycDBc5bt`~|RWDG5~5Lph3AF{TwD z?5#zB?c_5jMg;f)z_y+>pNzY*3MN_Hi9KD+CQU{`1|JIjNIh)nOWGg8}E(NHM|<8H3m zNF$0}%CcrwjiH3()jYB~&~~s>599owu6D3YV4cCj!(rdv?KX6 zWH%ruOoJ?nCd-}N-}E*}cXMvQcSyLKP3>lw&R(2`w*MJwTRZgQUP~QzV45YW$g8{Y zdlUNUxEVz^YsHnov^5w+?L~D2b3d3I7*yG~z&P8?VZj9tgvyA~6(j_C&`gf+sd3Y!B)amWd+2jh5K8zR(C$H7#j-znE4=}nBxotn}A z(RD*%h-OqfsR53R66jX5XiMsi6h3&UH=~SmYcPWoUkaK7Cr^9!^>gUQ^^l$I_|>=Q zFCe3>DsP-z07fJ5Q&UsoI;uY#h!gwhM1f67voi)SNA@g_|YiGjRI; z9T>;k{G>nOj<>W5Qj)#J?dqW*E7JKXe3TDz4t;pq!pghhIBFm8^c1cW!zmz!Q!)Fz z2*c?d)C#5rI>0G1m2x0;Lk5_jZikc$#-p3@yC?bz&L%p)7{I8mrn-Ui0NNY6YE#@AJD#y7*5Pr%r^$Tr8rm_Naobv6mu zvWoOnQ&2(OW&Vf5n4w@4U7(^c<~1-roy~_}oH`~*On)8q8z`@?_{fd7GWEfDbY5-1 z1ar07y!r_sIv<8K@cFfM-*Y&v&YjD~&BjJLheAMu&jX~g&}`g!Tua4Ze^+@OK6(!r zjPNQO(^)Y7mh1*1n4;gIfh=~14IyK|irry%0FSyq9Rt}c_NOmE#5iL&XJenc5kOJ* zrC*V~x-X5s0D$4ZBSo9vb*@fjj zkkR05@DS|;O8HD&CUUX;^Dx7>V4!>~PVLj&0RB6)L0*0LnAZv~b$-U@@XJT3C+SfO z=F)*n-5t0nNVgJAAMu#%#C*CCB+8C&feU%!!_8K4A|HJjR<2g!D8Op*V@Ablk5&7d z9569!#Iv3K!?e$Vu~pjNK5hQ+QX@Q$7{Ly%NTP?AqF2I=%H$8tmWin1$m}8y$o$1A zIJ*@&8}nWj&&#H4!f1F~92hmV161gC)sKO(VcQV7-#!<9ggZu!laXmn6Hn?C3s>>P z>3SYnT=zW)`C2dfWPL5>cma2e0%{*_WD{P%u}1^;$_wbqUtmTzX72f)CB61wJUl$A zP%)ps^|?IfITm_BdoGVM5&Ip5JvteOf9GFio?=U8!a^ohRt2T@nI&|#dQRA8q z<@*Kg=TDSnKQGD}=x*MsW$XLwb||ZkSxlSJx|O958Z?NaDE>-@BBjA*H|{4zL00cB zK|)-0V3h#Hu?ZE4IBvU|7{|(n)k5OAF*w$Y5dt!{CD|>BGm4zXf4LXN&kCTfnam>8f zl8&dUDovkcJs0EItZXEUfOxVuot`(K;L8{D16$3t3l5@J6(JcvlEDiU{Mp1v=KKJU z6^>xzz38Ks2vUxA8=R1o5kZ3X07WG8#U;fUI*H@g8(vEmYQ}?|2oF}o#w7Fx7n^9h@_3`v>)&?R+dnPrR7 zv4=U{M9^>9E{3L0MakwrMAP?Z2G9bTh+#~P_5c`HWn#oU2F9&p27oERGo|{5McK~f zRmm?~j<$3@z;=K$diLv%HUd$DNQ@?dI>X%)hdn*4 z5crn)h%9bD^2%OCfdNqv9l)-@{PHJjxdNdlAauD}XX`A0P*~jZKbUt#RrW_#AegdO z>~K7+{%e*7*)fl5GmHD_VbA1`ziZ;Kg7HJErk9ry7#~lhzV5aLvMVH#7w1OX!8mkH zy%$U;9di(j?~+z!YW(x>v*2r%6eHrEd95nFW+g~(PA)rXQXdO8I`%TJGr2(|ZX!jp z@lG72H$RWbB8h!mf^p%vq8k^DUWdD9uNW6LHsN)&Q3d691&xb`g$!5N_SY**TegxK zR`ILCT3fIW|4Y0&&>C`IU9CEUaq5`I!I=M+>-jX8-a4E4 zV0=28QZSCInwPfCc>f{>gUPTEQ+T#+dmi})^|6XX+OBCW!skGT z50;KH-Xe)zDm$9G;A33%o)DLmTf)3bfZW383wVotI!$;ktf2_I4C+# zIbYLqrf|v!7#TXo492HpvcWj6%U+$pcy-JGFaaGi0gU}0*=tr~P%a(iBezOMYeb~m zXf--qt=hQN)Z=Qq&0!y|MuSawlzkm(O{bXx2V(z%G8|y_*H{`P|A3J6FCPC#7@oy1 zF8|a_N;SIvWd&<=QEgGbkuh7m5s$!K`+!|rW63tmX7$&ifZ~5ek5uJgGknJ0h6)88 zz@G&2wIMuac@$*j&+{37_<&j8v}7BVFT`+uoubvQ0TU%^D;n)zvCA@g|79C#8q|kR zUdO|?raxxZ4}XlmeZV~HESa&j;Z6U{EU~|(HkDJh4&^w$;KM1Z&_`QZVivYEzMK58 zs@%r#^jF|Lpo1u{f_dHwEB4p7c(FA~d9ion4{w;hykQKr*|T7%#FA2!=ut~FuhN(J z7pt)z!>tA7c|#1hUXblL_@QGsG3|^3OVW*V%jqCUA%B z^(`?eGV^;8D8(vM|A8sgg--eqvq73{b0-+Tj_Cx(l`h*12IHr4gug%^ghyi_=U@W`3(bCWu5aT*wBaLfbSR{_<>WhPdd)SC~uvbd?2yM~8!0uUZ zsaw<(z}Y}#FGlwRU~E}3(;ZAe#|#963+&S9E&x-mvzZOXai<)IwkofVd8LR#XUj&L z$*rNx>;_|RBr~VLxEssNZ(ux4Wad9G{-!dMhHKW2W-`-gJ4UxxSC9K)RIFnXB3!hua0^SRG^a4My|a9+xK48e4FIQo@{vsmgDDRw2z;U z(P{L@%-+BsKJPBq=G|Yx&@heP#E0qKn=nk3FU9eLpH15Yx8CfHO&FMqQM$RcIxyb= zaN=~LYTDfh2D^T#PTRrYv%qmxo%V=*Q%FDNzH zqjOVm`~H2Ly*t#V@Ucs9Gz@2{ThJ6WcVKh6AK$3P$=rQbfG)^~DkQeiOrcii9Ic<= zpw2MAvI8IBY3?ox8`m=_odvd7ni=CR0d4ni0V$M6bz@ok#6mOW!p8Npi-iyG& zHlp07xd1L*xep8VE#;EK%(i&*sH3gcwWy3Tj0|+${~Q>f&Sn7^{HG3)L5Nc@Y@8BoC&%%@0294x zqxC`H0j&@4etX|-7OR$d{8k*=uH1%0TZc&B(2V`C4L!b=89qY2?d=V0RZFaIHd$PJ z2<^bhuZOjN6DA+B4?aTGHlaj&duIQirB0VY!^V#rrtIjbHm`z9D#HqgjeFWw#XMbz z+85-99@etfazs(;IEjvB?#;+?x@cYZC)BzfnQuGBNkF7&biK#YcVH_hV>SMVBtAwG zjxLl$W{R)tt)ZbA4viG>&NwY2!wHtS7$^IPfER7>2>EBXB#3KrAHwn)+;6#>l+NY{pmD&J z<_lLj+A8#j+d1xLHx@3~QDcSReoJF@V%I-I0*#SCxf-Vi1a*TL%l_DkAu10H3|EW+ya{}8 zH~u`y{@RVvnhSU5V|-K$oj9pycZ`bAW1{UMXt*kmz(DCEx8^`F4jnTNOhCs>0aO0) zt)mMCE&sf#eW=9~6wS)e7dw>ZEb+~hR5UnGwSaZsgH&;maSu|RgP8t_%ytmeM7C{D zRUoyY$;asZ0G~XmC1%o@Y|LIz_CnekGmC@x*p?UN;@aQv`VEtDw|Gi>Nsx8k0vG1Q2Qk-E3vG?{vpsOMy6Ef`yo#!!l5 z$4?p`nyF)+DNy{gG)CKMQNiM}TbctKDK*F04_KWqpjyS+e}U2R9?CG!Q;$q`0(g*J z)$X{A)bmAn(fvokxOL10Fs=o%jRE(*mFH!q4j8YF$pPbDDBJWX0_A#9rUrp=ERvaL zz$i;(rWnk0UD9uYvArbQdMRsk&;Hq0 z<-q5)m~L9qBiSeIaYW@o!g$Blc53Oe@Ej`CAOR5*mhC ztk1WYaFv7F8Q~j%DFN<88(;JM!G(iST#3TUFJs#sf7Fu5OyA*#--;uar0mfN7}HQ! z-Ha-`ovZUZ+~hoe6kc=4)ry~NSD0(CTG!FX;AJHLW#rmB%=Kusu4l>BL#`?K$?g{B zT3)T|@Z<2hL9Q>6t0T*GAR4K5-IW7s+)Nxt52y+N*UnMWS&FQ1mkVpM5yYGpAb5!&K<+l=KX8EemsX z+|Jd03WH%JxmJ+Z&M>boxAWrN5+@td9a74I+Zpm!3;Yb5 zLzKyA7-kO)%imkA>yFcK?M?n?$+cUU>+)({+x$YMlIw8%WIMuKebu_QYk*vxRPH|nCrG`UAK^{ld>KN|7>fRYoJ(pX{H)3M#MGwUk^PRN7(k&xe$9wp#1#-(jqhwAo*zH{)(p+fhOe}70RG1XevI}e+!WZjK^j+3>y zTI&+BZb1c#tJZosS=*_A-7w7dhE=&ywXU@;!s}gf z?La?=@RMS%)_N&fH>1)5FwCA2R#49ETtgSpBOA!89e%P4!@L}~^WxLo9NHT-qEdH| z>*z4oF4ekv|A5yza&1FDU*adlS*>-=5Nxu@Wg85$`-TaF zb)9|%t|{bSO0J)Vxh}8P^&fJ5iCnYslfCW#n=6j{8?Y&V;Xuet{%gs<1*8;TwFNmE zqGpT8I+K1jlXdCstZ|6nfL*27@qfY42gB@=u(WRL%D1D!zu~ozTK!H1GcN7 zHIY>i?ZuBVC!Vc4Dn&m-{#$9_)`Vni9?!Cl2{n#fTd*M2xtKI5@ocrK;dMUwFB~WR zgP%D37_Zb|w&POV{uR(%A@u@M|9*=)w-Mq_q!1?j7?0FoD`oHFXypbY#3*D-Ye4&$o$;qz-t?{hzCS7h6*EEb3yXj+EnFb&G@g}aTOhq8aN%i{I zO8|3p*R589aq3Fm3dW^lz6RshF=xPpR7PA8`v;72N~@E0?F9v^w>tJBWAiI(tf^6J z<=pK?C6C$Y(_!@%Nsq<=3v?A|2garr zESjzl7?+M21ExGIIrAxY!(h!cZj>)ubuwDBqH^-u>4@0!t?lG>>wK*a|DcE$6Npt)G={IpCQmsa-ciG*maBpj8n(-Bb%RPugPHCI_3p1 zfz!f943yWw_>pSWHQNoJ6=AUbA_w{eM#@>)?I0MR%80@LD;WFlvR4Hd=Q){4*^Nk5~--q(1E0LA=6yiUBej`$pjLllE2b|=JQOFo4#!At5?bO~U$uJLbzv0oOYhz?5l9G$3RvcZIO zOdBwsKegN_TN<4^bdkHm#;ddGTLj8=MRpqp#_^ZT%p#k=<%C`V6VQd;0A`zx`4r3+ z9rHbykS@-d&oRz?SLM)#Js2_9HjFZN`J~>X`X^ z@F0m|kGAgF31ZRH%~CMp*C? zJ5mF~bc@1fbjOoLeiLpiV0dNKSWYuE8acx74S&qT=uwB-qwM*347Fv5XRc6(+FJli zb<@=rF!l<$CVRp7R7N!9F)$&W%^zUg|H)p)GK>cuV+CWoq1o_?&@B>k1#{kErN>(M zcLq?0IOe;rPS7V8s9s`5VxJxsZ3ye=!x6xo+H$?`* zYZ@3cd<=?>H=3fn1jep1VhURe=CCgE<|I%~o!b}e{hHPWMTemX>J%X`eq9#-g4w8J zV!uF{MmdX2F#B|6-Unuf&Z`}mfR5=}1S%LI2YL#OCsJmn5ECUcJ}~=qf!+tBm}HwW zFpg-!h-Ud7j9158`~sV9xsFo4M9pGkwBX z5}U3$QKpJveSdvdzB~=RTP+?}JzCBALn}>H(R_0b_Q^Ob;+#9g|Ns56U)E$VSI30;6=0 zZG2!n9gIbMLl)z6GZ}T1jXonI9dj5=NXMK7W9}?_RghN~nMv4>gu2O0CYWHJQ7NK% zL=@i!RCy2Cs23Q=qcSrJjPo&>@qqC?E;FxyQJ#>Q4Pab4W+#{cF-4Wd9|C3TBfFgi zKaYX1zV&_LN}5g6xSnOOrSsAIN~ z%@En<0ND(anKNKKqhzK6jBPY$iqytWI)Iu9N@bdW@sE?;I)DjIl$m~D98b$kA$jST z#bC;xk!?1Bu}u~X#y|c06qH+~1allrK*wAHqf8NQVqcUHL_)ebKNF03s%(=3rc^go z_X49#R}(7Y#g7K%drqY|L&tqLE(hL52l#S6+dUv^sy#;;?xf^ja8ZN35%)G^8LC)K^@Zuj8ZHI>I25EV+z4Ib<9g(JUYe?#;0TU7J&-tsFPqqI_5eU zd*Lh$p4chhh- zT<{1xoMy!?@Ed+2Y`BB9PsibR6NC!Af;BJjio7xO3R{qlWA>xsnEmT?_&HSj7R*u` z_AO!WX6hH)I|H1+FsI2-Om@A%lrxc;V1|HkESH(7V7xl!B``r9vl>iD$Gii^{i;@H z6sW8z!t{4k*Lpi(C9Q7#6`2 zIrQBya=k7y-NBew%FHk@J{?m8#`%V9vkXi~$GihZStZ+iaU`y<;#nzKOVp@S+JZRns!)e9R-aIv=^zm{S=%D>}~$uJD!=o1jhtmn$}7F$pcKmDWd z$#KIGOG=D-ea}gu8${gdky{_e8|%S%RDCKr%9@2&ocIO4fmO+{P<>pUv{h!L)%DhB zDF3Ns$xJP~;QuJQZw5-tWzS{sYqqQC&&%xd3~U~`XkIFSJ_t~|VEnidqsO{a*Jzzo zl>)P6Vmnh?0QITMifSfBr_|x5v@vOq<&`VU)*07N+n>e_gCq3x$Z0$jlHEJ(k%O$; zxq6%6D(k&;6aPzkMq&u=(Ph{C|KVz+dt6q!y;n}Ir{iz!%x2Y=dV^e-k?TOZy|?|c zrA9BcX^%an-98vPWyIJ~<3`*ybRyoZ$=5zh&=rkXxJSM4Ok29r7mT&GJkbmTnv-W6cd3+(&8b_M-QDy5ixG)E8o#m)i?*g!dn&ebs*CMFh0Jv z72eVLhF;LF%{zzH#A9$qyTUTFt(nPlsvd_^@0M6uAKV}`?u%mX#@IZxJ8N#bEfzy} z*79*D$~ZM%uXfQbqHA;u>nBnhZ&CNY0nK^3PvpYgAUpy*zA?(cpx`|_=?D~Y_(`tX z@S2NsTH(tdjU-chQ*=UEWBl~T4>lKFpm#~zxe0!bleV2++pHNByGh#@KZZtn?FQ0z zpa4fmTT`!XbQcr>()PxW;RgG$nUvK!(zc@jhe&%~ugz)>#SYRs@q@cwny;rhp1^EF zzF(7KYo&s>itTPFwvjduKZa7hb|qQjXXUe@$Y$UA%Ke$<;Rn&biD%ym6cap+h zso)hg-v>o0X>;*|H)u3Bu3bdhY>K>{v_`!)z6BI(Nt=To!)5kK3#nfgk~Wh9Y$fd( zy*8#L6h6|nzz?qQ>3rvrwjKr8Oxkz#+Q?Q=l#terA6k)6E!WiwRZS<~cS*6ZQbCnj z)*AeBQZ~a68ea3_HJw4)S`>H#X$$n)3eqkmZ6o{``s=k*bD&5flXax+q1Rp`t(UY} z_`w^6x^gGo4@FHfSxs82UVDYK#iX_22lt~iUuPTCG>)_@N%0R`l`A!Us0|bgNLvR# z*hT2H;~s#*L?$ap`?X$sp0smFYsHUYn_fFQ7YZYpEFM8mnybA7YWh0`oK-?Nt02 zX6d#2NSjXqu90?}UfZn`6hD!65`GMQ_1ZGhx+uUE(st2nJ3j=)NzzWl4`vswGCb$q zr0q`uLZnTv)Z%!g1v^fPariNqDiz!<&>4!pR$uQo*b0?*>H|@;yOX+=7%7YTg}+J*0gKKXgY>)^7ZN$~qtT zsH!WEKhTy)q6P(x7;se3pj4xcHdS0l8`~&R5dy^J&rHZ4LpPF`gc1aq2tlGyNd--m z2qT0NTWn#MR#4Pv**30e7cJ|?HPxt8QBxZ&B36|B-g)!hyFYjzN8@+SJ?GqW&i(V= zym@2Z%`*ym%)1xKyL@MP`%P^6rtv=0y4{eQ94?*6Tl>sgY5G=M%Twm9$*3OuO>!HO zT!2n*J#N1eYIy2-|q8yBh%cV)@|NBMc=(@ z4DUW>-o5E&eE4T_Gvh6SrRHXuyUkvwi??H={oSP5kUh+{D>UCdk91G4UWDYg*ko`I zms8f*7(T$xpnp4bvw=t)p@#3nC5wk21Jiw354IRzcF&*)mTUnT?JUbB*zR(wdriRZd^xwzv@H`H{fF8>h^5DrS4l z44F2i)Tw;bCwG?J$=6WJ-22f@D|5Vr>gK7Qj3Gnb9O@K^i|0V1_aQ_4lg)BK71FE} zvPzmQgzS(o-VZTHkm-jZxwCBZuR}T)*<^4p&(`cP1pBVn*Mq`*cQgq8JV;#3FN3JD zHIR^$-m{SAh^NPmVwKb2N71x@6`9g#LdLtO{*7rSJxluwbxtwzPtwJakZd92AcrNd z*FyRlJo7YlRzO0vHhButkSz1$MfK-Eol@1#Tc}Q&b|VymG)X*iAeG#O7R2msNKT1O zRzfn-GbEwQt)aP2hgU-;|BkZ`p(7i-W)Ys>_mesE%cF_=&b_jF4;ga=nf?q?$rINC z^QXT}V5J+ELpmSuWFm`*xG;8JX#Ei@d|Exipv zdfPmiNO?_J8NEsI`{w4o%GvAX-E`I|Fse6utqhrE2uG0Q1(1dHAZ-K&rt z{-84oJ}^XF`~uSGhu_GIc$fOQ+t!>7DV0%pEu_v&6G0{14$2YL6%ca-UN3`m`Mo#q zt$|cXMLh|Lim?|VeP&if-mN0%JyO=>Pt!(G7?iT!7P=EsvC1Y7L7JmBc>!XMz{R&9 zA(0un|5%x^hM0<(LQ~hH+dv^HnJP$pp>6CLNc9|>^g;@yuLJvAmQ2eyFBbVLWh#Ss z8Dxh)85pNGK+IhtL0n#fG)PelK+Fv(#!J`J%=bxniPtJpTUS$3QR8r5r1d%WWif;% zq1R1sgayq!puzo?R4A!vDl*|oo+9JWVn_-V9ys(M#2i69YUx`hVAGN=$Q=3e}VMRuv?WthD%M>LK=J*BXetOtBXs@-0wAc9c%kw z=uJ+yjGO;3swGh`LU?wyH30TQ_C0Kyzw!VhspXEMjB{cI{ArFL5T%fPqOu0k;Rn=Y zrmkv!Wrj@mk0KM6s@k8_?5-rn#v#aliB)>+L%bDZqaeFwwzvh7oml<7Qkf4qAc~qH z1)}E(NT}WJ^&cS3viQIKA^A*^JoFnOzpuvYw2ugu$c%(k3mFF~l0p7MNW&7_d@aNr zL8O~L;wGJ)(vJ-YbynET_Co5VA74PaN^P0kkC~ceuABFyxPr2CQUYVvms9GF1sJgL93Q}Bodil zSyzQ63ECE9(k0WoAO$nMRz~_QqnaZK_2-b`GIG-Y#xNbmoMeVJ`)8`UzP#qnbgAk~ z5sKE>sw*KqD{RsL$ve#+aF0Q%{dgEh-iPGM#_uSEUc@XPhkwHLda2I|kO^yTW5tkq ziCH})bCWIe7-W(^ULwVFs%q*S$NkoomyWH-wBll7Kj}_xpMVOM*@{m6JC!e)9tY_Z z7q5q;OIh6pIp`-SQeIv;zqY~&%jz0MhV6&LO-gP8c&H~REULFa_WO!V7=Ht)kn;Qt zGE>YSg{+cRClAm{f`0+TNu)KIf5({!>U+TM{YoRm5fo7z(jgP+XOK9-Wq>3XpV6OE z4I+~ViTiskqp=!d4m5k`6HTC*GCbBpa#_a%)$c+&CHF%<^A(vAF0YG!33Y~% zNw>R^4e2@EbvSuGaSNzkGF=Jj^aoWWvY=*eU76#4i7u4v>qE%&NvPLD94BnW?3a*S zNzg7x^O|JGO#XSY2`Ebj%*T*?Uv(s6J_MUr)hRu5{y{5W#^^Z{(k+{l36OTFnA;$` z<6c}7_Nzd9AMlV-bT7nNTVVBL1Ee5o%XCA+_t@k;NU0bL9W?Qf;6pkC8Dl>mRPTq{ zh~Ek65V8hR;m_x0dp>1K6~A6#-H@HKEIkO>CiCfQ zkcK8tv+2-jU$Xz%QD~#lUlKIQ>(!8gh$rKgUa6BIF`IRIvlW|`M>68eq z{?go}%#20LTV|7a zkm_L0NAu&5sF|2Y^FOYSZ-ENX9;D;&(V;CTm1mqAyN&0Ab<09m0+}FIAB5D4jprcd z2!>J*$wG$@9U^laE*6iKGWL7MzEEHP=)Blqzep3@VN zIU;&iLpr3E{|uSn_ufRWe{gEdnJM$eNhhQ_VSg1dLKi}E<;3AK$Z$!}G)VPYJ06Q5 zW5n2MNTVcrGbFZOLiF#TNh0)n2tNm61+5QKApE3I0`( z@v%8}vzef%A8OP4DoDQs_5nzz>_mPEnXtju^M;X;ZhQnW1r`)zHb3f~J%TwZK$Ahy zDYl|VAkDI3ZHJ_Y>MlrTiQVe&ki{~Qobl~c=R|2W7P4=)KS!CqhCvMy#wm~;QXh9g z!ezFxR!Co?O`eD3OQ^dcDVuDWk06~-Fh`NvLjDwgXn09V3GE(QWA-!?W zeBx3cSMl;?1T92n+eRak%s(GHfcCa~&5V()5OV~^UWb&HdNPp(CAH=u+3w@_Ldhte zaZ;+2vDA|>?Q9iYmx0U?6k0tb z&(CXOz;L;Gn`Ci?Q7sYrHKbF_zhcNT+x*`kwk^cJ28AE9g)&ZI()H`yh~EyGz<-0K zvj$?0!0DxsOh}OFRghIbwKcy43E7d3Ij@5nDr}(>Po)?ouj3$n%WaukA)$JkJPJ8L zlY9FeJMI>afr9a;)$lJW8; zq+ZN_7z0Jq?W#U?80IBs*^quwbU#F$ejE~)9nr5LMG}v0NXi_~MV=d7Um0mRqdFt~ zqQCLZzSC_lQcq)$O6#$Zywa9Q)fuC&F5~aG__zXcWTmIu__hNwQ|hx9vajXI>Wp*7 zeafGGEI(LCj;7(Kr#f{K^(Z9N@+so6dHflE+!lWf(kQ#`-#`|Nz1JY!al6$3q|fhX zVgt%WE%yea&Y1sw|7mbFyUY{{^8?o2}@i5x6KrHXBmVZp%!ELytK=Rn#dpT&?~KlsM%Vo1Ev*0TvRM$CT#iFNq%wQ2Sx zD8mnRq@2qb)m62*B6G@_I3#_&7?R=7sYcKDA!brD$#E0(L&z#|dNw3G=I>ohvnEiH zta^_@IwbfnLgK!Qrqv%ITSfJkkljMkGw8jHipwF+KAF?=KvBtkHKap!|4%_C6xx9u zauy?~&L+1*`usvOF5U&%D-QhzGHI41mK{GF{&T2@}Op!JOU#lelwWI`xyiOL9;YwGN^te|a2vF$U`1Vk;VyNuHM5Bny%&g)<2Dh17Sp1o2-0D?i`sS=7OqQY}LPjv`MJDA(_)`nXe({2m*W7xs<2G z>`F+;+q);Er$F|c=v-m#yNW@oXnumETdE&~?3>Y&vM^(GZ0m9IyCGe&y6=OG-)Ou0 zIiy39KJ+|Xkr_S&iAxpcLw1YI^cbj6jMYFE%j|7r7E7}SAsMnIc?J@all6ZZ8HxJ! z=X32u2J_A5#~97B+pR&UC~Eh010+;tlRXfP@tcr%ttVqnPR&Qo?qlUc$%%Q;7;G`a zP?||HVhlq!8n@9bgnFc&7DC!39``|VWqdsXiT}jb^S_WWBJ+1h+e%yJ?6K&{puB?$ zF9!9?*r|n>q7PPqR!HUo2|4@j{ef^^8VcEtsDv?Ar)RLG9O@#k3+$s3UA zlTrKtBwwnh9a1MLeklf8E6%+J$reSQK^$2ePPmXV^ouuATU|4EUS0Vlsf>}x?3F-d zL&k`$8!x2E;ghnM znWDB#2ogHe&g8|A+)`WST8QI>ta;$}7^p#Zm-j)s<%-f?NaMq{qC=4OcAI35V=a7pS zeX;3&l6b6vRLG^FEvA)B5W67Zds{k|WSn=Z`%?{`^MhL6 zSi**B*u|_QQ|%C52RXok$UK*v9VS8grE+Q^T@uu#5Ow%*NT-aFXCWPN+t&ZYK$)WG z5Tss0m^z-B*^dq%)+Rz6lA2f?g6ca9vL_~Wd^N}% zfzTAl!Iie67-XxMUkm9I@+(NUERU~3+LP{?6~S>nh78x;P3onbl*qI^7P8gfMw@0= zLd+4kn0Fj0GJ0g5UI;lL^TTf;y_4kx=)XZ>KflJve#r2%-JrT&56-6E*V*yNfK*Cx zUjm8x>$TBS2fu!-@A-r6NHbc5a=0H+) zQnPytj#D9;zeFZvR&aI$Nku1I#@LqAfwLg}GHYA_*(>v08KluKPaf!5&2@7pTa0Z) z#vDP)UW7DEG*QI9+mBa46;k={LE2=H{sYnzwS#}|<)lnxE`{utt@iDZP>tPc38dOh zw0D)h6_h1ed>-Qdh)yW!ViyDtt$yr>9F*mM%y$_J^KE0LkOOi-aWSMm8R_Iz`iDV> zrS}^lc|vwT%n^j~Wyk@Di6A#}abrp$xA&}F>6v%QTxXR}O#2UM)qQVL#^j$VHis}i z;59SkN03R63lwdyu$%#F}y?Ls86+fpiAM*#90VB#P=yvl83bgAj8B!EcA8 z$sE@S$@GiS4Sp$)_p$YKBh#47y-6GP{|d_H&tOb{4(XKM5BeVa8$W2qkr|M+vYBav zI7@6}FGCKO+T=}0U%f?Q&IP%6Elb7CknvJ_^B}E$&y4vckkEaWB4;&3yYU31S5CTj zLE0DCtz!QRYV~t(RQE&jWkx&g`}9oitGf)ce}=6nAJQY`Sq$ltifMv$%TU}D18ob+ z0rM|F;?lEkAUPs4ioN-G3G8K%CNUp_^hh^;2MKSsoqppgHY+=Qp-6FE)m&US{I>n= zg#nsXOFF(Ws-^VKz1qDR9hB$yA=%Pu8bojDth}02#2gH|69|7e%Mm&(H#a>B$&!=3 z?U0b{8(xK^9ZWHoWs`GdWCDF{virIL(%NE^K1i(dCL8sGO0D6+mELQZhNU0FA>$=M zVC8STLoxPCp%WRo{ zK+MNu45DO&23^bcYclq+mqcfQ;wx-&5u{RfM0t=-DZOcsOmqbEM+M}FbYmH$!5;U{ zpCEjOVIKGBnePSd^KZp8x5F$b;rvG?qQWqxCkbkRbjwiO0%;SO=O7cL8=peVk=*~7 zKTp37kEGc+$U*7HjSzDLVVn-xDS2H7$(KcFyU`;HRX3#C)DZDc2LBz<5xH1&$S9Jn z#QE2=C`&)Cf$YE6PT6$GfK0k7D25|7`S;M|MF{FlO_0-;A3#FGTxVRFIgm721?EATrDwl_ z)XALxGNePyzYXb3&IHN*PbiOz9g?A|Az9LFG9*nVkcS}SW!(Q6k|$*N4b+F|xdM{! zRgB3$4+jP5+EorQM=+r-fE@6eCEnW&84xn)hpZ;Dz+^(qk;2Q3;>D2u60c$s_OAss z`gt|tvmgx(o{%A%jiL&hyb9@)YXyfOO@3d^Eh1(BH^=}!^G5`KqOZr;zW~(eH#5d2 zKtgjop-6-eD*nxJ;!~I7aa-nNNLpJ!O#SEM^@;X*{xC>f zJ_fl4GG<-Sj9>SLZ1Y_-<`+VC_=D42CM~I|taN{oGL#H{9GQGO(lO_0P_8T|e}wGw z7iFV**o_43OnWS3Lc%qkL&+~1I6Eam*CA6XTePK+A{jv!tp*jIX7~O{$iNexYGb|| zaxmI5(9HFMos!K1ykm}_OusO)o9x!3ZeseGZj&1!Vd-EMq}z^*vjU=;+abC7X~-T> zij07FAmKY~V`okznX-aTgY?TBF%M!6GeX=^(gcZ0q*@@A)2SCKH7WE*&`iG{5%(ez zUu*K70cTY9Ba`dP7;-`ZgI!dQfV47c0+X7vAm#|-dIjXfZ!uqf+ZVbX)RcVIhwJrh zNL$o)aS>#Hu}#)P>Lq6VkQAA;GHyO@9|AEa{;^J18J98;{!-jB8g_cFfz_jQ0D@>uQ%RGURT=W0Z2mjsMqRINT(Qk7P3{yyO5lv zww|vc1+I*@UJji^Rj;vyE`@}p_jf}a*#kdg2uINSKSTD&-1`Y6^K3goUzt|Pf=#ZM zDYwxN*<_4`G;XvV`VmCyV;ZC*>d8dP-Ah9QGNaTY6P@qL7-u&?_IZoE$-l$0gV&oq zp-4&Mqim;0X1~voNonw8Osip&8LnGwG8STvARbpicqF}5o(-mzzdR)DKVq6m>1~HJ zNEY9K>`1rg)z2Y|MJ9a;gGwf%iy=L}u}JOQJLVNvIz>T*jQw1MqF*I$LP-|m4Uj&6 zH84H;H;6fcp4|g!^^~tpB_8iW7H_a+zJY}8T}RBhXewJQ$Gd{-%&4Bm2uLvV*`68WYXl8%vL_~y41WY)9pk<MLk>%7epkfV z8ju{WD0fMDZ7pSlEmYymL#e2h=SK z>v{jmEE%W^?4_&`(knI81?iH$4nW#u z0H@AkZl$a2PD9Dup8@KSI=>!LDvF{IBOVObTF4l2u>q1LWHn@!49;gE4V0(#z4YIM z(&^cdWbe4w57H&gzBQY?ibEktmN}U@`qEcuhin*E~=MLvUvL3dL z-2my432io{DV~%e{v3-yi~YQsk26Z=S3B-QqrLKMLuNoGtDTUPwYIUpK=z1>p*aL! zYG?)|?2od9{WegY`1lH>Uj|GcB%{$bHn@b1hQurrGT!fo>Dc8Ea|Gk%dPsbbUopo1 zeV{g3Jhnp810iJgL2|{|0Z5%px`RuPH8u>gqu6%(yGDj#<~fA@0?=VG_A|&@3F8(> zj+p;X$W|fyAYs`P9DwviZS!Z89phrmxdhZHbM*|!DhcC!$e6gT=(%GRIX#eGap1;tID~IjyoM z*cn4;K)n9FX|~KZ_CBOS7UdJ}VBaT-PKJbJ)0PA2UTW)^4lzdxFL${wxg&-#nLgJi zg@OrW7o=Y1^FKf)&9PN~2+5I(`E~{Kpj6d`kY;IhO9lI%BT}DL2&Leh@z1~Kl+`L92KbTw?xw$Y; z6zxJLE)IPKX?w&rf8md9J-70Imy}gR%Aek}DdV+~Ev3KB7`Ec6=QDVn#cL$5vw3Cm l8pUfguXA{Xc%A$7Q_r7w@zJM0c<%hx;ZHyG+WGOT{~y-a)t>+W diff --git a/platformio.ini b/platformio.ini index 5bd2b7d36..8ae84bbae 100644 --- a/platformio.ini +++ b/platformio.ini @@ -65,10 +65,14 @@ monitor_flags = monitor_filters=esp32_exception_decoder board_build.f_flash = 80000000L build_flags = ${common.build_flags} +# src_filter is deprecated in platformio version 6 +# It is included here so we can still compile with version 5 +# We should remove it at some point src_filter = +<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> + - -<.git/> - - - -test_build_project_src = true + - - +build_src_filter = + +<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> + lib_extra_dirs = libraries @@ -98,11 +102,19 @@ build_flags = ${common.build_flags} -DENABLE_BLUETOOTH -DENABLE_WIFI [env:native] platform = native +# src_filter and test_build_project_src are deprecated in platformio version 6 +# They are included here so we can still compile with version 5 +# We should remove them at some point test_build_project_src = true src_filter = +<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> + -<.git/> - - - + - - - +test_build_src = true +build_src_filter = + +<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> + + + + - - build_flags = -IX86TestSupport -std=c++17 -limagehlp lib_compat_mode = off lib_deps = From 1c381742039abe798691d11391c9358d2fc62e8b Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 17 May 2022 14:14:25 -1000 Subject: [PATCH 15/22] Platform4.2.0 (#420) * Update to new Arduino framework * Added lib dependency on arduinoWebSockets git repo * Tab in platformio.ini * Working with new ESP32 platform 4.2.0 * Fixed rebase botch * Improved file handling for LittleFS 1. The "filename too long" message has been changed to a log_debug() that shows the filename. That works for all filesystems and can be turned on and off with $Message/Level 2. There was a bug in $localfs/delete that failed to delete LittleFS files because the file was open. Fixed by closing the file first. * Added file LocalFS.h --- FluidNC/esp32/StepTimer.cpp | 117 +++ FluidNC/include/Driver/StepTimer.h | 20 + .../Configuration/ConfigurationHandlers.md | 2 +- FluidNC/src/Configuration/_Overview.md | 4 +- FluidNC/src/FileStream.cpp | 18 +- FluidNC/src/FileStream.h | 6 +- FluidNC/src/I2SOut.cpp | 24 +- FluidNC/src/LocalFS.h | 13 + FluidNC/src/Main.cpp | 8 +- FluidNC/src/NutsBolts.cpp | 4 +- FluidNC/src/Spindles/VFDSpindle.cpp | 6 +- FluidNC/src/StackTrace/AssertionFailed.cpp | 2 +- FluidNC/src/StackTrace/debug_helpers.cpp | 88 -- FluidNC/src/StackTrace/debug_helpers.h | 104 --- FluidNC/src/StackTrace/debug_helpers_asm.S | 61 -- FluidNC/src/Stepper.cpp | 7 +- FluidNC/src/Stepping.cpp | 29 +- FluidNC/src/Stepping.h | 9 +- FluidNC/src/Uart.cpp | 1 - FluidNC/src/WebUI/WebServer.cpp | 115 +-- FluidNC/src/WebUI/WebServer.h | 5 +- FluidNC/src/WebUI/WebSettings.cpp | 33 +- FluidNC/src/WebUI/WifiConfig.cpp | 4 +- FluidNC/src/WebUI/WifiServices.cpp | 7 +- libraries/arduinoWebSockets/.gitignore | 29 - libraries/arduinoWebSockets/.travis.yml | 40 - libraries/arduinoWebSockets/LICENSE | 502 ---------- libraries/arduinoWebSockets/README.md | 98 -- .../Nginx/esp8266.ssl.reverse.proxy.conf | 83 -- .../WebSocketClientAVR/WebSocketClientAVR.ino | 84 -- .../esp32/WebSocketClient/WebSocketClient.ino | 110 --- .../WebSocketClientSSL/WebSocketClientSSL.ino | 106 --- .../esp32/WebSocketServer/WebSocketServer.ino | 104 --- .../WebSocketClient/WebSocketClient.ino | 92 -- .../WebSocketClientSSL/WebSocketClientSSL.ino | 88 -- .../WebSocketClientSocketIO.ino | 113 --- .../WebSocketClientStomp.ino | 149 --- .../WebSocketClientStompOverSockJs.ino | 150 --- .../WebSocketServer/WebSocketServer.ino | 86 -- .../WebSocketServerAllFunctionsDemo.ino | 132 --- .../WebSocketServerFragmentation.ino | 94 -- .../WebSocketServerHttpHeaderValidation.ino | 86 -- .../WebSocketServer_LEDcontrol.ino | 121 --- .../ParticleWebSocketClient/application.cpp | 46 - libraries/arduinoWebSockets/library.json | 25 - .../arduinoWebSockets/library.properties | 9 - .../arduinoWebSockets/src/WebSockets.cpp | 655 ------------- libraries/arduinoWebSockets/src/WebSockets.h | 311 ------- .../src/WebSocketsClient.cpp | 762 --------------- .../arduinoWebSockets/src/WebSocketsClient.h | 136 --- .../src/WebSocketsServer.cpp | 873 ------------------ .../arduinoWebSockets/src/WebSocketsServer.h | 212 ----- .../arduinoWebSockets/src/libb64/AUTHORS | 7 - .../arduinoWebSockets/src/libb64/LICENSE | 29 - .../arduinoWebSockets/src/libb64/cdecode.c | 98 -- .../src/libb64/cdecode_inc.h | 28 - .../arduinoWebSockets/src/libb64/cencode.c | 119 --- .../src/libb64/cencode_inc.h | 31 - .../arduinoWebSockets/src/libsha1/libsha1.c | 202 ---- .../arduinoWebSockets/src/libsha1/libsha1.h | 21 - .../arduinoWebSockets/tests/webSocket.html | 49 - .../tests/webSocketServer/index.js | 57 -- .../tests/webSocketServer/package.json | 27 - libraries/arduinoWebSockets/travis/common.sh | 53 -- platformio.ini | 29 +- 65 files changed, 306 insertions(+), 6427 deletions(-) create mode 100644 FluidNC/esp32/StepTimer.cpp create mode 100644 FluidNC/include/Driver/StepTimer.h create mode 100644 FluidNC/src/LocalFS.h delete mode 100644 FluidNC/src/StackTrace/debug_helpers.cpp delete mode 100644 FluidNC/src/StackTrace/debug_helpers.h delete mode 100644 FluidNC/src/StackTrace/debug_helpers_asm.S delete mode 100644 libraries/arduinoWebSockets/.gitignore delete mode 100644 libraries/arduinoWebSockets/.travis.yml delete mode 100644 libraries/arduinoWebSockets/LICENSE delete mode 100644 libraries/arduinoWebSockets/README.md delete mode 100644 libraries/arduinoWebSockets/examples/Nginx/esp8266.ssl.reverse.proxy.conf delete mode 100644 libraries/arduinoWebSockets/examples/avr/WebSocketClientAVR/WebSocketClientAVR.ino delete mode 100644 libraries/arduinoWebSockets/examples/esp32/WebSocketClient/WebSocketClient.ino delete mode 100644 libraries/arduinoWebSockets/examples/esp32/WebSocketClientSSL/WebSocketClientSSL.ino delete mode 100644 libraries/arduinoWebSockets/examples/esp32/WebSocketServer/WebSocketServer.ino delete mode 100644 libraries/arduinoWebSockets/examples/esp8266/WebSocketClient/WebSocketClient.ino delete mode 100644 libraries/arduinoWebSockets/examples/esp8266/WebSocketClientSSL/WebSocketClientSSL.ino delete mode 100644 libraries/arduinoWebSockets/examples/esp8266/WebSocketClientSocketIO/WebSocketClientSocketIO.ino delete mode 100644 libraries/arduinoWebSockets/examples/esp8266/WebSocketClientStomp/WebSocketClientStomp.ino delete mode 100644 libraries/arduinoWebSockets/examples/esp8266/WebSocketClientStompOverSockJs/WebSocketClientStompOverSockJs.ino delete mode 100644 libraries/arduinoWebSockets/examples/esp8266/WebSocketServer/WebSocketServer.ino delete mode 100644 libraries/arduinoWebSockets/examples/esp8266/WebSocketServerAllFunctionsDemo/WebSocketServerAllFunctionsDemo.ino delete mode 100644 libraries/arduinoWebSockets/examples/esp8266/WebSocketServerFragmentation/WebSocketServerFragmentation.ino delete mode 100644 libraries/arduinoWebSockets/examples/esp8266/WebSocketServerHttpHeaderValidation/WebSocketServerHttpHeaderValidation.ino delete mode 100644 libraries/arduinoWebSockets/examples/esp8266/WebSocketServer_LEDcontrol/WebSocketServer_LEDcontrol.ino delete mode 100644 libraries/arduinoWebSockets/examples/particle/ParticleWebSocketClient/application.cpp delete mode 100644 libraries/arduinoWebSockets/library.json delete mode 100644 libraries/arduinoWebSockets/library.properties delete mode 100644 libraries/arduinoWebSockets/src/WebSockets.cpp delete mode 100644 libraries/arduinoWebSockets/src/WebSockets.h delete mode 100644 libraries/arduinoWebSockets/src/WebSocketsClient.cpp delete mode 100644 libraries/arduinoWebSockets/src/WebSocketsClient.h delete mode 100644 libraries/arduinoWebSockets/src/WebSocketsServer.cpp delete mode 100644 libraries/arduinoWebSockets/src/WebSocketsServer.h delete mode 100644 libraries/arduinoWebSockets/src/libb64/AUTHORS delete mode 100644 libraries/arduinoWebSockets/src/libb64/LICENSE delete mode 100644 libraries/arduinoWebSockets/src/libb64/cdecode.c delete mode 100644 libraries/arduinoWebSockets/src/libb64/cdecode_inc.h delete mode 100644 libraries/arduinoWebSockets/src/libb64/cencode.c delete mode 100644 libraries/arduinoWebSockets/src/libb64/cencode_inc.h delete mode 100644 libraries/arduinoWebSockets/src/libsha1/libsha1.c delete mode 100644 libraries/arduinoWebSockets/src/libsha1/libsha1.h delete mode 100644 libraries/arduinoWebSockets/tests/webSocket.html delete mode 100644 libraries/arduinoWebSockets/tests/webSocketServer/index.js delete mode 100644 libraries/arduinoWebSockets/tests/webSocketServer/package.json delete mode 100644 libraries/arduinoWebSockets/travis/common.sh diff --git a/FluidNC/esp32/StepTimer.cpp b/FluidNC/esp32/StepTimer.cpp new file mode 100644 index 000000000..cf65fdf47 --- /dev/null +++ b/FluidNC/esp32/StepTimer.cpp @@ -0,0 +1,117 @@ +// Copyright 2022 Mitch Bradley +// +// Interface to the ESP32 alarm timer for step timing + +#ifdef __cplusplus +extern "C" { +#endif + +// #include "../src/Driver/StepTimer.h" +#include "driver/timer.h" +#include "hal/timer_hal.h" + +static const uint32_t fTimers = 80000000; // the frequency of ESP32 timers + +#define USE_LEGACY_TIMER + +#ifdef USE_LEGACY_TIMER +# define TIMER_GROUP_NUM TIMER_GROUP_0, TIMER_0 + +void stepTimerStart() { + // timer_set_counter_value(TIMER_GROUP_NUM, 0); + // timer_group_enable_alarm_in_isr(TIMER_GROUP_NUM); + timer_set_alarm(TIMER_GROUP_NUM, TIMER_ALARM_EN); + timer_start(TIMER_GROUP_NUM); +} + +void IRAM_ATTR stepTimerRestart() { + // Resetting the counter value here si unnecessary because it + // happens automatically via the autoreload hardware. + // The timer framework requires autoreload. + // If you set autoreload to false, the ISR wrapper will + // disable the alarm after our ISR function returns, so + // an attempt to enable the alarm here is ineffective. + // timer_set_counter_value(TIMER_GROUP_NUM, 0); +} + +uint32_t stepTimerGetTicks() { + uint64_t val; + timer_get_alarm_value(TIMER_GROUP_NUM, &val); + return val; +} + +void IRAM_ATTR stepTimerSetTicks(uint32_t ticks) { + timer_group_set_alarm_value_in_isr(TIMER_GROUP_NUM, (uint64_t)ticks); +} + +void IRAM_ATTR stepTimerStop() { + timer_pause(TIMER_GROUP_NUM); + // timer_set_auto_reload(TIMER_GROUP_NUM, TIMER_AUTORELOAD_DIS); + timer_set_alarm(TIMER_GROUP_NUM, TIMER_ALARM_DIS); +} + +void stepTimerInit(uint32_t frequency, bool (*fn)(void)) { + timer_config_t config = { + .alarm_en = TIMER_ALARM_DIS, + .counter_en = TIMER_PAUSE, + .counter_dir = TIMER_COUNT_UP, + .auto_reload = TIMER_AUTORELOAD_EN, + // .clk_src = TIMER_SRC_CLK_DEFAULT, + .divider = fTimers / frequency, + }; + timer_init(TIMER_GROUP_NUM, &config); + timer_set_counter_value(TIMER_GROUP_NUM, 0); + timer_isr_callback_add(TIMER_GROUP_NUM, (timer_isr_t)fn, NULL, ESP_INTR_FLAG_IRAM); + //timer_pause(TIMER_GROUP_NUM); + // timer_start(TIMER_GROUP_NUM); +} +#else +# include "driver/gptimer.h" + +static gptimer_handle_t gptimer = NULL; +void stepTimerInit(uint32_t frequency, bool (*fn)(void)) { + gptimer_config_t timer_config = { + .clk_src = GPTIMER_CLK_SRC_DEFAULT, + .direction = GPTIMER_COUNT_UP, + .resolution_hz = frequency, + }; + gptimer_new_timer(&timer_config, &gptimer); + + gptimer_event_callbacks_t cbs = { + .on_alarm = step_timer_cb, + }; + gptimer_register_event_callbacks(gptimer, &cbs, NULL); + + gptimer_alarm_config_t alarm_config = { + .alarm_count = 1000000, // period = 1s + }; + gptimer_set_alarm_action(gptimer, &alarm_config); + gptimer_pause(gptimer); +} + +void IRAM_ATTR stepTimerStart() { + gptimer_alarm_config_t alarm_config = { + .reload_count = 0, + .alarm_count = 1, // Trigger immediately for first pulse + .flags.auto_reload_on_alarm = false, + }; + gptimer_set_alarm_action(gptimer, &alarm_config); +} + +void IRAM_ATTR stepTimerSetTicks(uint32_t ticks) { + gptimer_alarm_config_t alarm_config = { + .reload_count = 0, + .alarm_count = ticks, // Trigger immediately for first pulse + .flags.auto_reload_on_alarm = true, + }; + gptimer_set_alarm_action(gptimer, &alarm_config); +} + +void IRAM_ATTR stepTimerStop() { + gptimer_stop(gptimer); +} +#endif + +#ifdef __cplusplus +} +#endif diff --git a/FluidNC/include/Driver/StepTimer.h b/FluidNC/include/Driver/StepTimer.h new file mode 100644 index 000000000..1ac47c89a --- /dev/null +++ b/FluidNC/include/Driver/StepTimer.h @@ -0,0 +1,20 @@ +#pragma once + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include + +void stepTimerInit(uint32_t frequency, bool (*fn)(void)); +void stepTimerStop(); +void stepTimerSetTicks(uint32_t ticks); +void stepTimerStart(); +void stepTimerRestart(); + +uint32_t stepTimerGetTicks(); + +#ifdef __cplusplus +} +#endif diff --git a/FluidNC/src/Configuration/ConfigurationHandlers.md b/FluidNC/src/Configuration/ConfigurationHandlers.md index 5f1c741cd..3545f859f 100644 --- a/FluidNC/src/Configuration/ConfigurationHandlers.md +++ b/FluidNC/src/Configuration/ConfigurationHandlers.md @@ -123,4 +123,4 @@ At this point, this is simply not implemented. The generator basically traverses the complete tree, and generates a yaml file. The main point of this is to create a `config.yaml` file -in SPIFFS, which holds the main startup configuration. +in LocalFS, which holds the main startup configuration. diff --git a/FluidNC/src/Configuration/_Overview.md b/FluidNC/src/Configuration/_Overview.md index e53c7828b..df2606fad 100644 --- a/FluidNC/src/Configuration/_Overview.md +++ b/FluidNC/src/Configuration/_Overview.md @@ -106,9 +106,9 @@ trigger a link-time name collision. ## Getting started with Yaml settings During startup, `MachineConfig::load` is called, with the -default filename `/spiffs/config.yaml`. +default filename `/localfs/config.yaml`. -You can upload a new config file to spiffs by putting it in the +You can upload a new config file to localfs by putting it in the data folder, and calling `pio run -t uploadfs`. Another option is to upload it using WiFi. diff --git a/FluidNC/src/FileStream.cpp b/FluidNC/src/FileStream.cpp index 41dbef47f..5a58e3493 100644 --- a/FluidNC/src/FileStream.cpp +++ b/FluidNC/src/FileStream.cpp @@ -5,8 +5,15 @@ #include "Machine/MachineConfig.h" // config-> #include "SDCard.h" #include "Logging.h" +#include "LocalFS.h" #include +String FileStream::path() { + String retval = _path; + retval.replace(LOCALFS_PREFIX, "/localfs/"); + return retval; +} + int FileStream::available() { return 1; } @@ -49,7 +56,7 @@ static void replaceInitialSubstring(String& s, const char* replaced, const char* } FileStream::FileStream(const char* filename, const char* mode, const char* defaultFs) : Channel("file") { - const char* actualLocalFs = "/spiffs/"; + const char* actualLocalFs = LOCALFS_PREFIX; const char* sdPrefix = "/sd/"; const char* localFsPrefix = "/localfs/"; @@ -69,6 +76,8 @@ FileStream::FileStream(const char* filename, const char* mode, const char* defau replaceInitialSubstring(_path, "/LOCALFS/", actualLocalFs); } else if (_path.startsWith("/SPIFFS/")) { replaceInitialSubstring(_path, "/SPIFFS/", actualLocalFs); + } else if (_path.startsWith("/LITTLEFS/")) { + replaceInitialSubstring(_path, "/LITTLEFS/", actualLocalFs); } else { if (*filename != '/') { _path = '/' + _path; @@ -92,15 +101,14 @@ FileStream::FileStream(const char* filename, const char* mode, const char* defau } _isSD = true; } - if (_path.startsWith(actualLocalFs) && _path.length() > (30 + strlen(actualLocalFs))) { - log_info("Filename too long: " << _path); - } _fd = fopen(_path.c_str(), mode); if (!_fd) { + bool opening = strcmp(mode, "w"); + log_debug("Cannot " << (opening ? "open" : "create") << " file " << _path); if (_isSD) { config->_sdCard->end(); } - throw strcmp(mode, "w") ? Error::FsFailedOpenFile : Error::FsFailedCreateFile; + throw opening ? Error::FsFailedOpenFile : Error::FsFailedCreateFile; } } diff --git a/FluidNC/src/FileStream.h b/FluidNC/src/FileStream.h index 952d82f96..7c44f2e82 100644 --- a/FluidNC/src/FileStream.h +++ b/FluidNC/src/FileStream.h @@ -25,11 +25,7 @@ class FileStream : public Channel { FileStream(String filename, const char* mode, const char* defaultFs = ""); FileStream(const char* filename, const char* mode, const char* defaultFs = ""); - String path() { - String retval = _path; - retval.replace("/spiffs/", "/localfs/"); - return retval; - } + String path(); int available() override; int read() override; int peek() override; diff --git a/FluidNC/src/I2SOut.cpp b/FluidNC/src/I2SOut.cpp index 704b4729c..475d84c3c 100644 --- a/FluidNC/src/I2SOut.cpp +++ b/FluidNC/src/I2SOut.cpp @@ -19,8 +19,10 @@ #include #include #include +#include +#include -#include +#include // Make Arduino functions available extern "C" void __digitalWrite(pinnum_t pin, uint8_t val); @@ -57,7 +59,7 @@ static i2s_out_dma_t o_dma; static intr_handle_t i2s_out_isr_handle; // output value -static atomic_uint_least32_t i2s_out_port_data = ATOMIC_VAR_INIT(0); +static std::atomic i2s_out_port_data = ATOMIC_VAR_INIT(0); // inner lock static portMUX_TYPE i2s_out_spinlock = portMUX_INITIALIZER_UNLOCKED; @@ -194,13 +196,13 @@ static int i2s_out_gpio_detach(pinnum_t ws, pinnum_t bck, pinnum_t data) { } static int i2s_out_gpio_shiftout(uint32_t port_data) { - __digitalWrite(i2s_out_ws_pin, LOW); + __digitalWrite(i2s_out_ws_pin, 0); for (int i = 0; i < I2S_OUT_NUM_BITS; i++) { __digitalWrite(i2s_out_data_pin, !!(port_data & bitnum_to_mask(I2S_OUT_NUM_BITS - 1 - i))); - __digitalWrite(i2s_out_bck_pin, HIGH); - __digitalWrite(i2s_out_bck_pin, LOW); + __digitalWrite(i2s_out_bck_pin, 1); + __digitalWrite(i2s_out_bck_pin, 0); } - __digitalWrite(i2s_out_ws_pin, HIGH); // Latch + __digitalWrite(i2s_out_ws_pin, 1); // Latch return 0; } @@ -217,7 +219,7 @@ static int i2s_out_stop() { // Force WS to LOW before detach // This operation prevents unintended WS edge trigger when detach - __digitalWrite(i2s_out_ws_pin, LOW); + __digitalWrite(i2s_out_ws_pin, 0); // Now, detach GPIO pin from I2S i2s_out_gpio_detach(i2s_out_ws_pin, i2s_out_bck_pin, i2s_out_data_pin); @@ -225,7 +227,7 @@ static int i2s_out_stop() { // Force BCK to LOW // After the TX module is stopped, BCK always seems to be in LOW. // However, I'm going to do it manually to ensure the BCK's LOW. - __digitalWrite(i2s_out_bck_pin, LOW); + __digitalWrite(i2s_out_bck_pin, 0); // Transmit recovery data to 74HC595 uint32_t port_data = atomic_load(&i2s_out_port_data); // current expanded port value @@ -486,12 +488,12 @@ void i2s_out_delay() { if (i2s_out_pulser_status == PASSTHROUGH) { // Depending on the timing, it may not be reflected immediately, // so wait twice as long just in case. - ets_delay_us(I2S_OUT_USEC_PER_PULSE * 2); + delay_us(I2S_OUT_USEC_PER_PULSE * 2); } else { // Just wait until the data now registered in the DMA descripter // is reflected in the I2S TX module via FIFO. // XXX perhaps just wait until I2SO.conf1.tx_start == 0 - delay(I2S_OUT_DELAY_MS); + delay_ms(I2S_OUT_DELAY_MS); } I2S_OUT_PULSER_EXIT_CRITICAL(); } @@ -561,7 +563,7 @@ int i2s_out_set_stepping() { // Wait for complete DMAs for (;;) { I2S_OUT_PULSER_EXIT_CRITICAL(); - delay(I2S_OUT_DELAY_DMABUF_MS); + delay_ms(I2S_OUT_DELAY_DMABUF_MS); I2S_OUT_PULSER_ENTER_CRITICAL(); if (i2s_out_pulser_status == WAITING) { continue; diff --git a/FluidNC/src/LocalFS.h b/FluidNC/src/LocalFS.h new file mode 100644 index 000000000..811cdbe28 --- /dev/null +++ b/FluidNC/src/LocalFS.h @@ -0,0 +1,13 @@ +#pragma once + +#ifdef USE_LITTLEFS +# include +# define LocalFS LittleFS +# define LOCALFS_NAME "LittleFS" +# define LOCALFS_PREFIX "/littlefs/" +#else +# include +# define LocalFS SPIFFS +# define LOCALFS_NAME "SPIFFS" +# define LOCALFS_PREFIX "/spiffs/" +#endif diff --git a/FluidNC/src/Main.cpp b/FluidNC/src/Main.cpp index 71eccd8fc..6b33b7acd 100644 --- a/FluidNC/src/Main.cpp +++ b/FluidNC/src/Main.cpp @@ -24,7 +24,7 @@ # include "WebUI/InputBuffer.h" # include "WebUI/WifiConfig.h" -# include +# include "LocalFS.h" extern void make_user_commands(); @@ -46,8 +46,10 @@ void setup() { log_info("FluidNC " << git_info); log_info("Compiled with ESP32 SDK:" << ESP.getSdkVersion()); - if (!SPIFFS.begin(true)) { - log_error("Cannot mount the local filesystem"); + if (LocalFS.begin(true)) { + log_info("Local filesystem type is " << LOCALFS_NAME); + } else { + log_error("Cannot mount the local filesystem " << LOCALFS_NAME); } bool configOkay = config->load(); diff --git a/FluidNC/src/NutsBolts.cpp b/FluidNC/src/NutsBolts.cpp index dc3b2d79b..6d529ee26 100644 --- a/FluidNC/src/NutsBolts.cpp +++ b/FluidNC/src/NutsBolts.cpp @@ -99,7 +99,7 @@ void IRAM_ATTR delay_us(int32_t us) { } void delay_ms(uint16_t ms) { - delay(ms); + vTaskDelay(ms / portTICK_PERIOD_MS); } // Non-blocking delay function used for general operation and suspend features. @@ -118,7 +118,7 @@ bool delay_msec(uint32_t milliseconds, DwellMode mode) { if (sys.abort) { return false; } - delay(1); + vTaskDelay(1 / portTICK_PERIOD_MS); } return true; } diff --git a/FluidNC/src/Spindles/VFDSpindle.cpp b/FluidNC/src/Spindles/VFDSpindle.cpp index d28149fad..88214c32d 100644 --- a/FluidNC/src/Spindles/VFDSpindle.cpp +++ b/FluidNC/src/Spindles/VFDSpindle.cpp @@ -75,7 +75,7 @@ namespace Spindles { uint8_t rx_message[VFD_RS485_MAX_MSG_SIZE]; bool safetyPollingEnabled = instance->safety_polling(); - for (; true; vTaskDelay(VFD_RS485_POLL_RATE / portTICK_PERIOD_MS)) { + for (; true; delay_ms(VFD_RS485_POLL_RATE)) { std::atomic_thread_fence(std::memory_order::memory_order_seq_cst); // read fence for settings response_parser parser = nullptr; @@ -228,7 +228,7 @@ namespace Spindles { // Wait a bit before we retry. Set the delay to poll-rate. Not sure // if we should use a different value... - vTaskDelay(VFD_RS485_POLL_RATE / portTICK_PERIOD_MS); + delay_ms(VFD_RS485_POLL_RATE); #ifdef DEBUG_TASK_STACK static UBaseType_t uxHighWaterMark = 0; @@ -353,7 +353,7 @@ namespace Spindles { // last = _sync_dev_speed; // break; // } - delay(500); + delay_ms(500); // unchanged counts the number of consecutive times that we see the same speed unchanged = (_sync_dev_speed == last) ? unchanged + 1 : 0; diff --git a/FluidNC/src/StackTrace/AssertionFailed.cpp b/FluidNC/src/StackTrace/AssertionFailed.cpp index 3947dff5b..5e796322d 100644 --- a/FluidNC/src/StackTrace/AssertionFailed.cpp +++ b/FluidNC/src/StackTrace/AssertionFailed.cpp @@ -8,7 +8,7 @@ #ifdef ESP32 -# include "debug_helpers.h" +# include "esp_debug_helpers.h" # include "WString.h" # include "stdio.h" diff --git a/FluidNC/src/StackTrace/debug_helpers.cpp b/FluidNC/src/StackTrace/debug_helpers.cpp deleted file mode 100644 index 947feab03..000000000 --- a/FluidNC/src/StackTrace/debug_helpers.cpp +++ /dev/null @@ -1,88 +0,0 @@ -#ifdef ESP32 - -// Copyright 2015-2019 Espressif Systems (Shanghai) PTE LTD -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at - -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -# include - -# include "esp_types.h" -# include "esp_attr.h" -# include "esp_err.h" -# include "debug_helpers.h" -# include "soc/soc_memory_layout.h" -# include "soc/cpu.h" - -static inline bool esp_stack_ptr_is_sane(uint32_t sp) { - return !(sp < 0x3ffae010UL || sp > 0x3ffffff0UL || ((sp & 0xf) != 0)); -} - -static inline uint32_t esp_cpu_process_stack_pc(uint32_t pc) { - if (pc & 0x80000000) { - //Top two bits of a0 (return address) specify window increment. Overwrite to map to address space. - pc = (pc & 0x3fffffff) | 0x40000000; - } - //Minus 3 to get PC of previous instruction (i.e. instruction executed before return address) - return pc - 3; -} - -bool IRAM_ATTR esp_backtrace_get_next_frame(esp_backtrace_frame_t* frame) { - //Use frame(i-1)'s BS area located below frame(i)'s sp to get frame(i-1)'s sp and frame(i-2)'s pc - void* base_save = (void*)frame->sp; //Base save area consists of 4 words under SP - frame->pc = frame->next_pc; - frame->next_pc = *((uint32_t*)(((char*)base_save) - 16)); //If next_pc = 0, indicates frame(i-1) is the last frame on the stack - frame->sp = *((uint32_t*)(((char*)base_save) - 12)); - - //Return true if both sp and pc of frame(i-1) are sane, false otherwise - return (esp_stack_ptr_is_sane(frame->sp) && esp_ptr_executable((void*)esp_cpu_process_stack_pc(frame->pc))); -} - -String IRAM_ATTR esp_backtrace_print(int depth) { - char buf[80]; - - //Check arguments - if (depth <= 0) { - return ""; - } - - //Initialize stk_frame with first frame of stack - esp_backtrace_frame_t stk_frame; - esp_backtrace_get_start(&(stk_frame.pc), &(stk_frame.sp), &(stk_frame.next_pc)); - //esp_cpu_get_backtrace_start(&stk_frame); - String s = "backtrace:"; - snprintf(buf, 80, "0x%08X:0x%08X ", esp_cpu_process_stack_pc(stk_frame.pc), stk_frame.sp); - s += buf; - - //Check if first frame is valid - bool corrupted = (esp_stack_ptr_is_sane(stk_frame.sp) && esp_ptr_executable((void*)esp_cpu_process_stack_pc(stk_frame.pc))) ? false : - true; - - uint32_t i = (depth <= 0) ? INT32_MAX : depth; - while (i-- > 0 && stk_frame.next_pc != 0 && !corrupted) { - if (!esp_backtrace_get_next_frame(&stk_frame)) { //Get previous stack frame - corrupted = true; - } - snprintf(buf, 80, "0x%08X:0x%08X ", esp_cpu_process_stack_pc(stk_frame.pc), stk_frame.sp); - s += buf; - } - - //Print backtrace termination marker - if (corrupted) { - s += " |<-CORRUPTED"; - } else if (stk_frame.next_pc != 0) { //Backtrace continues - s += " |<-CONTINUES"; - } - return s; -} - -#endif diff --git a/FluidNC/src/StackTrace/debug_helpers.h b/FluidNC/src/StackTrace/debug_helpers.h deleted file mode 100644 index dc8cfd591..000000000 --- a/FluidNC/src/StackTrace/debug_helpers.h +++ /dev/null @@ -1,104 +0,0 @@ -#ifdef ESP32 -// Copyright 2015-2019 Espressif Systems (Shanghai) PTE LTD -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -# pragma once - -# ifdef __cplusplus -extern "C" { -# endif - -# ifndef __ASSEMBLER__ - -# include -# include "esp_err.h" -# include "soc/soc.h" - -# define ESP_WATCHPOINT_LOAD 0x40000000 -# define ESP_WATCHPOINT_STORE 0x80000000 -# define ESP_WATCHPOINT_ACCESS 0xC0000000 - -/* - * @brief Structure used for backtracing - * - * This structure stores the backtrace information of a particular stack frame - * (i.e. the PC and SP). This structure is used iteratively with the - * esp_cpu_get_next_backtrace_frame() function to traverse each frame within a - * single stack. The next_pc represents the PC of the current frame's caller, thus - * a next_pc of 0 indicates that the current frame is the last frame on the stack. - * - * @note Call esp_backtrace_get_start() to obtain initialization values for - * this structure - */ -typedef struct { - uint32_t pc; /* PC of the current frame */ - uint32_t sp; /* SP of the current frame */ - uint32_t next_pc; /* PC of the current frame's caller */ -} esp_backtrace_frame_t; - -/** - * Get the first frame of the current stack's backtrace - * - * Given the following function call flow (B -> A -> X -> esp_backtrace_get_start), - * this function will do the following. - * - Flush CPU registers and window frames onto the current stack - * - Return PC and SP of function A (i.e. start of the stack's backtrace) - * - Return PC of function B (i.e. next_pc) - * - * @note This function is implemented in assembly - * - * @param[out] pc PC of the first frame in the backtrace - * @param[out] sp SP of the first frame in the backtrace - * @param[out] next_pc PC of the first frame's caller - */ -extern void esp_backtrace_get_start(uint32_t* pc, uint32_t* sp, uint32_t* next_pc); - -/** - * Get the next frame on a stack for backtracing - * - * Given a stack frame(i), this function will obtain the next stack frame(i-1) - * on the same call stack (i.e. the caller of frame(i)). This function is meant to be - * called iteratively when doing a backtrace. - * - * Entry Conditions: Frame structure containing valid SP and next_pc - * Exit Conditions: - * - Frame structure updated with SP and PC of frame(i-1). next_pc now points to frame(i-2). - * - If a next_pc of 0 is returned, it indicates that frame(i-1) is last frame on the stack - * - * @param[inout] frame Pointer to frame structure - * - * @return - * - True if the SP and PC of the next frame(i-1) are sane - * - False otherwise - */ -bool esp_backtrace_get_next_frame(esp_backtrace_frame_t* frame); - -/** - * @brief Print the backtrace of the current stack - * - * @param depth The maximum number of stack frames to print (should be > 0) - * - * @return - * - ESP_OK Backtrace successfully printed to completion or to depth limit - * - ESP_FAIL Backtrace is corrupted - */ - -String esp_backtrace_print(int depth); - -# endif -# ifdef __cplusplus -} -# endif - -#endif diff --git a/FluidNC/src/StackTrace/debug_helpers_asm.S b/FluidNC/src/StackTrace/debug_helpers_asm.S deleted file mode 100644 index 3790d2eb9..000000000 --- a/FluidNC/src/StackTrace/debug_helpers_asm.S +++ /dev/null @@ -1,61 +0,0 @@ -#ifdef ESP32 - -// Copyright 2015-2019 Espressif Systems (Shanghai) PTE LTD -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include -#include -#include -#include - -/* - * esp_backtrace_get_start(uint32_t *pc, uint32_t *sp, uint32_t *next_pc) - * - * High Addr - * .................. - * | i-3 BS | - * | i-1 locals | Function B - * .................. i-1 SP - * | i-2 BS | - * | i locals | Function A (Start of backtrace) - * ------------------ i SP - * | i-1 BS | - * | i+1 locals | Backtracing function (e.g. esp_backtrace_print()) - * ------------------ i+1 SP - * | i BS | - * | i+2 locals | esp_backtrace_get_start() <- This function - * ------------------ i+2 SP - * | i+1 BS | - * | i+3 locals | xthal_window_spill() - * ------------------ i+3 SP - * .................. Low Addr - */ - .section .iram1, "ax" - .align 4 - .global esp_backtrace_get_start - .type esp_backtrace_get_start, @function -esp_backtrace_get_start: - entry a1, 32 - call8 xthal_window_spill //Spill registers onto stack (excluding this function) - //a2, a3, a4 should be out arguments for i SP, i PC, i-1 PC respectively. Use a5 and a6 as scratch - l32e a5, sp, -16 //Get i PC, which is ret addres of i+1 - s32i a5, a2, 0 //Store i PC to arg *pc - l32e a6, sp, -12 //Get i+1 SP. Used to access i BS - l32e a5, a6, -12 //Get i SP - s32i a5, a3, 0 //Store i SP to arg *sp - l32e a5, a6, -16 //Get i-1 PC, which is ret address of i - s32i a5, a4, 0 //Store i-1 PC to arg *next_pc - retw - -#endif diff --git a/FluidNC/src/Stepper.cpp b/FluidNC/src/Stepper.cpp index de147732c..ba1aa0cce 100644 --- a/FluidNC/src/Stepper.cpp +++ b/FluidNC/src/Stepper.cpp @@ -79,9 +79,9 @@ typedef struct { static stepper_t st; // Step segment ring buffer indices -static volatile uint8_t segment_buffer_tail; -static volatile uint8_t segment_buffer_head; -static uint8_t segment_next_head; +static volatile uint32_t segment_buffer_tail; +static volatile uint32_t segment_buffer_head; +static uint32_t segment_next_head; // Pointers for the step segment being prepped from the planner buffer. Accessed only by the // main program. Pointers may be planning segments or planner blocks ahead of what being executed. @@ -269,7 +269,6 @@ void IRAM_ATTR Stepper::pulse_func() { // enabled. Startup init and limits call this function but shouldn't start the cycle. void Stepper::wake_up() { - //log_info("st_wake_up"); // Cancel any pending stepper disable protocol_cancel_disable_steppers(); // Enable stepper drivers. diff --git a/FluidNC/src/Stepping.cpp b/FluidNC/src/Stepping.cpp index 504e36503..d435eba4c 100644 --- a/FluidNC/src/Stepping.cpp +++ b/FluidNC/src/Stepping.cpp @@ -21,12 +21,8 @@ namespace Machine { // Prepare stepping interrupt callbacks. The one that is actually // used is determined by timerStart() and timerStop() - const bool isEdge = false; - const bool countUp = true; - // Setup a timer for direct stepping - stepTimer = timerBegin(stepTimerNumber, fTimers / fStepperTimer, countUp); - timerAttachInterrupt(stepTimer, onStepperDriverTimer, isEdge); + stepTimerInit(fStepperTimer, onStepperDriverTimer); // Register pulse_func with the I2S subsystem // This could be done via the linker. @@ -108,35 +104,32 @@ namespace Machine { // The argument is in units of ticks of the timer that generates ISRs void IRAM_ATTR Stepping::setTimerPeriod(uint16_t timerTicks) { if (_engine == I2S_STREAM) { - // 1 tick = fTimers / fStepperTimer // Pulse ISR is called for each tick of alarm_val. // The argument to i2s_out_set_pulse_period is in units of microseconds i2s_out_set_pulse_period(((uint32_t)timerTicks) / ticksPerMicrosecond); } else { - timerAlarmWrite(stepTimer, (uint64_t)timerTicks, false); // false disables autoreload + auto ticks = stepTimerGetTicks(); + stepTimerSetTicks((uint32_t)timerTicks); } } + // Called only from Stepper::wake_up which is not used in ISR context void Stepping::startTimer() { if (_engine == I2S_STREAM) { i2s_out_set_stepping(); } else { - timerWrite(stepTimer, 0ULL); - timerAlarmEnable(stepTimer); + stepTimerStart(); } } // Called only from Stepper::stop_stepping, used in both ISR and foreground contexts void IRAM_ATTR Stepping::stopTimer() { if (_engine == I2S_STREAM) { i2s_out_set_passthrough(); - } else if (stepTimer) { - timerAlarmDisable(stepTimer); + } else { + stepTimerStop(); } } - // Stepper timer configuration - hw_timer_t* Stepping::stepTimer = nullptr; // Handle - // Counts stepper ISR invocations. This variable can be inspected // from the mainline code to determine if the stepper ISR is running, // since printing from the ISR is not a good idea. @@ -146,22 +139,20 @@ namespace Machine { // TODO: Replace direct updating of the int32 position counters in the ISR somehow. Perhaps use smaller // int8 variables and update position counters only when a segment completes. This can get complicated // with probing and homing cycles that require true real-time positions. - void IRAM_ATTR Stepping::onStepperDriverTimer() { + bool IRAM_ATTR Stepping::onStepperDriverTimer() { // Timer ISR, normally takes a step. // // The intermediate handler clears the timer interrupt so we need not do it here ++isr_count; - timerWrite(stepTimer, 0ULL); - // It is tempting to defer this until after pulse_func(), // but if pulse_func() determines that no more stepping // is required and disables the timer, then that will be undone // if the re-enable happens afterwards. - - timerAlarmEnable(stepTimer); + stepTimerRestart(); Stepper::pulse_func(); + return false; } void Stepping::group(Configuration::HandlerBase& handler) { diff --git a/FluidNC/src/Stepping.h b/FluidNC/src/Stepping.h index 655dd0058..4c742ae61 100644 --- a/FluidNC/src/Stepping.h +++ b/FluidNC/src/Stepping.h @@ -5,7 +5,7 @@ #pragma once #include "Configuration/Configurable.h" -#include // hw_timer_t +#include "Driver/StepTimer.h" namespace Machine { class Stepping : public Configuration::Configurable { @@ -14,12 +14,9 @@ namespace Machine { static const uint32_t fStepperTimer = 20000000; // frequency of step pulse timer private: - static const int stepTimerNumber = 0; - static hw_timer_t* stepTimer; - static void onStepperDriverTimer(); + static bool onStepperDriverTimer(); - static const uint32_t fTimers = 80000000; // the frequency of ESP32 timers - static const int ticksPerMicrosecond = fStepperTimer / 1000000; + static const int ticksPerMicrosecond = fStepperTimer / 1000000; bool _switchedStepper = false; int32_t _stepPulseEndTime; diff --git a/FluidNC/src/Uart.cpp b/FluidNC/src/Uart.cpp index 5b59df724..3348058d2 100644 --- a/FluidNC/src/Uart.cpp +++ b/FluidNC/src/Uart.cpp @@ -62,7 +62,6 @@ void Uart::begin(unsigned long baudrate, UartData dataBits, UartStop stopBits, U conf.stop_bits = uart_stop_bits_t(stopBits); conf.flow_ctrl = UART_HW_FLOWCTRL_DISABLE; conf.rx_flow_ctrl_thresh = 0; - conf.use_ref_tick = false; if (uart_param_config(_uart_num, &conf) != ESP_OK) { return; }; diff --git a/FluidNC/src/WebUI/WebServer.cpp b/FluidNC/src/WebUI/WebServer.cpp index f3ccf2ff7..7d6685030 100644 --- a/FluidNC/src/WebUI/WebServer.cpp +++ b/FluidNC/src/WebUI/WebServer.cpp @@ -18,7 +18,7 @@ # include # include # include -# include +# include "../LocalFS.h" # include # include # include @@ -39,7 +39,7 @@ namespace WebUI { # include -//embedded response file if no files on SPIFFS +//embedded response file if no files on LocalFS # include "NoFile.h" namespace WebUI { @@ -142,8 +142,8 @@ namespace WebUI { _webserver->on("/command", HTTP_ANY, handle_web_command); _webserver->on("/command_silent", HTTP_ANY, handle_web_command_silent); - //SPIFFS - _webserver->on("/files", HTTP_ANY, handleFileList, SPIFFSFileupload); + //LocalFS + _webserver->on("/files", HTTP_ANY, handleFileList, LocalFSFileupload); //web update _webserver->on("/updatefw", HTTP_ANY, handleUpdate, WebUpdateUpload); @@ -234,13 +234,13 @@ namespace WebUI { String contentType = getContentType(path); String pathWithGz = path + ".gz"; //if have a index.html or gzip version this is default root page - if ((SPIFFS.exists(pathWithGz) || SPIFFS.exists(path)) && !_webserver->hasArg("forcefallback") && + if ((LocalFS.exists(pathWithGz) || LocalFS.exists(path)) && !_webserver->hasArg("forcefallback") && _webserver->arg("forcefallback") != "yes") { - if (SPIFFS.exists(pathWithGz)) { + if (LocalFS.exists(pathWithGz)) { path = pathWithGz; } - File file = SPIFFS.open(path, FILE_READ); + File file = LocalFS.open(path, FILE_READ); _webserver->streamFile(file, contentType); file.close(); return; @@ -333,11 +333,11 @@ namespace WebUI { path = "/404.htm"; contentType = getContentType(path); pathWithGz = path + ".gz"; - if (SPIFFS.exists(pathWithGz) || SPIFFS.exists(path)) { - if (SPIFFS.exists(pathWithGz)) { + if (LocalFS.exists(pathWithGz) || LocalFS.exists(path)) { + if (LocalFS.exists(pathWithGz)) { path = pathWithGz; } - File file = SPIFFS.open(path, FILE_READ); + File file = LocalFS.open(path, FILE_READ); _webserver->streamFile(file, contentType); file.close(); return; @@ -652,8 +652,9 @@ namespace WebUI { _webserver->send(200, "application/json", "{\"status\":\"Ok\",\"authentication_lvl\":\"admin\"}"); # endif } - //SPIFFS - //SPIFFS files list and file commands + + //LocalFS + //LocalFS files list and file commands void Web_Server::handleFileList() { AuthenticationLevel auth_level = is_authenticated(); if (auth_level == AuthenticationLevel::LEVEL_GUEST) { @@ -698,10 +699,10 @@ namespace WebUI { shortname.replace("/", ""); filename = path + _webserver->arg("filename"); filename.replace("//", "/"); - if (!SPIFFS.exists(filename)) { + if (!LocalFS.exists(filename)) { status = shortname + " does not exists!"; } else { - if (SPIFFS.remove(filename)) { + if (LocalFS.remove(filename)) { status = shortname + " deleted"; //what happen if no "/." and no other subfiles ? String ptmp = path; @@ -709,11 +710,11 @@ namespace WebUI { ptmp = path.substring(0, path.length() - 1); } - File dir = SPIFFS.open(ptmp); + File dir = LocalFS.open(ptmp); File dircontent = dir.openNextFile(); if (!dircontent) { //keep directory alive even empty - File r = SPIFFS.open(path + "/.", FILE_WRITE); + File r = LocalFS.open(path + "/.", FILE_WRITE); if (r) { r.close(); } @@ -729,31 +730,22 @@ namespace WebUI { String filename; String shortname = _webserver->arg("filename"); shortname.replace("/", ""); - filename = path + _webserver->arg("filename"); - filename += "/"; + filename = path + shortname; filename.replace("//", "/"); if (filename != "/") { - bool delete_error = false; - File dir = SPIFFS.open(path + shortname); - { - File file2deleted = dir.openNextFile(); - while (file2deleted) { - String fullpath = file2deleted.name(); - if (!SPIFFS.remove(fullpath)) { - delete_error = true; - status = "Cannot deleted "; - status += fullpath; - } - file2deleted = dir.openNextFile(); + if (LocalFS.exists(filename)) { + status = shortname + " does not exist"; + } else { + if (!deleteLocalFSRecursive(filename)) { + status = "Error deleting: "; + status += shortname; + } else { + status = shortname; + status += " deleted"; } } - if (!delete_error) { - status = shortname; - status += " deleted"; - } } } - //create a directory if (_webserver->arg("action") == "createdir" && _webserver->hasArg("filename")) { String filename; @@ -761,10 +753,10 @@ namespace WebUI { String shortname = _webserver->arg("filename"); shortname.replace("/", ""); filename.replace("//", "/"); - if (SPIFFS.exists(filename)) { + if (LocalFS.exists(filename)) { status = shortname + " already exists!"; } else { - File r = SPIFFS.open(filename, FILE_WRITE); + File r = LocalFS.open(filename, FILE_WRITE); if (!r) { status = "Cannot create "; status += shortname; @@ -782,7 +774,7 @@ namespace WebUI { ptmp = path.substring(0, path.length() - 1); } - File dir = SPIFFS.open(ptmp); + File dir = LocalFS.open(ptmp); jsonfile += "\"files\":["; bool firstentry = true; String subdirlist = ""; @@ -791,10 +783,15 @@ namespace WebUI { String filename = fileparsed.name(); String size = ""; bool addtolist = true; - //remove path from name - filename = filename.substring(path.length(), filename.length()); + //remove path from name - possibly unnecessary with recent framework versions + if (filename.startsWith(path)) { + filename = filename.substring(path.length(), filename.length()); + } //check if file or subfile if (filename.indexOf("/") > -1) { + // XXX this is probably SPIFFS-specific, and it might not work at all + // with recent versions of the Arduino frameworks + //Do not rely on "/." to define directory as SPIFFS upload won't create it but directly files //and no need to overload SPIFFS if not necessary to create "/." if no need //it will reduce SPIFFS available space so limit it to creation @@ -839,8 +836,8 @@ namespace WebUI { jsonfile += "\"status\":\"" + status + "\","; size_t totalBytes; size_t usedBytes; - totalBytes = SPIFFS.totalBytes(); - usedBytes = SPIFFS.usedBytes(); + totalBytes = LocalFS.totalBytes(); + usedBytes = LocalFS.usedBytes(); jsonfile += "\"total\":\"" + formatBytes(totalBytes) + "\","; jsonfile += "\"used\":\"" + formatBytes(usedBytes) + "\","; jsonfile.concat(F("\"occupation\":\"")); @@ -881,8 +878,8 @@ namespace WebUI { } } - //SPIFFS files uploader handle - void Web_Server::SPIFFSFileupload() { + //LocalFS files uploader handle + void Web_Server::LocalFSFileupload() { HTTPUpload& upload = _webserver->upload(); //this is only for admin and user if (is_authenticated() == AuthenticationLevel::LEVEL_GUEST) { @@ -1033,9 +1030,9 @@ namespace WebUI { } //Function to delete not empty directory on SD card - bool Web_Server::deleteRecursive(String path) { + bool Web_Server::deleteFSRecursive(fs::FS& fs, String path) { bool result = true; - File file = SD.open(path); + File file = fs.open(path); //failed if (!file) { return false; @@ -1043,7 +1040,7 @@ namespace WebUI { if (!file.isDirectory()) { file.close(); //return if success or not - return SD.remove(path); + return fs.remove(path); } file.rewindDirectory(); while (true) { @@ -1052,14 +1049,16 @@ namespace WebUI { break; } String entryPath = entry.name(); + // XXX this might be necessary for LittleFS + // entryPath = path + "/" + entryPath; if (entry.isDirectory()) { entry.close(); - if (!deleteRecursive(entryPath)) { + if (!deleteFSRecursive(fs, entryPath)) { result = false; } } else { entry.close(); - if (!SD.remove(entryPath)) { + if (!fs.remove(entryPath)) { result = false; break; } @@ -1067,7 +1066,17 @@ namespace WebUI { COMMANDS::wait(0); //wdtFeed } file.close(); - return result ? SD.rmdir(path) : false; + return result ? fs.rmdir(path) : false; + } + + bool Web_Server::deleteRecursive(String path) { return deleteFSRecursive(SD, path); } + + bool Web_Server::deleteLocalFSRecursive(String path) { +# ifdef USE_LITTLEFS + return deleteFSRecursive(LittleFS, path); +# else + return false; +# endif } //direct SD files list////////////////////////////////////////////////// @@ -1277,8 +1286,8 @@ namespace WebUI { config->_sdCard->end(); } } else { - if (SPIFFS.exists(filename)) { - SPIFFS.remove(filename); + if (LocalFS.exists(filename)) { + LocalFS.remove(filename); } } } @@ -1291,7 +1300,7 @@ namespace WebUI { config->_sdCard->end(); } } else { - avail = SPIFFS.totalBytes() - SPIFFS.usedBytes(); + avail = LocalFS.totalBytes() - LocalFS.usedBytes(); } return avail; } diff --git a/FluidNC/src/WebUI/WebServer.h b/FluidNC/src/WebUI/WebServer.h index bf3a3356e..2bbf7ce12 100644 --- a/FluidNC/src/WebUI/WebServer.h +++ b/FluidNC/src/WebUI/WebServer.h @@ -11,6 +11,7 @@ # include "../Settings.h" # include "Authentication.h" // AuthenticationLevel # include "Commands.h" +# include class WebSocketsServer; class WebServer; @@ -82,7 +83,7 @@ namespace WebUI { static void handle_web_command() { _handle_web_command(false); } static void handle_web_command_silent() { _handle_web_command(true); } static void handle_Websocket_Event(uint8_t num, uint8_t type, uint8_t* payload, size_t length); - static void SPIFFSFileupload(); + static void LocalFSFileupload(); static void handleFileList(); static void handleUpdate(); static void WebUpdateUpload(); @@ -90,6 +91,8 @@ namespace WebUI { static void cancelUpload(); static void handle_direct_SDFileList(); static void SDFile_direct_upload(); + static bool deleteFSRecursive(fs::FS& fs, String path); + static bool deleteLocalFSRecursive(String path); static bool deleteRecursive(String path); static void uploadStart(String filename, size_t filesize, const char* fs); static void uploadWrite(uint8_t* buffer, size_t length); diff --git a/FluidNC/src/WebUI/WebSettings.cpp b/FluidNC/src/WebUI/WebSettings.cpp index 5d929b159..ac4da948d 100644 --- a/FluidNC/src/WebUI/WebSettings.cpp +++ b/FluidNC/src/WebUI/WebSettings.cpp @@ -23,7 +23,7 @@ #include #include -#include +#include "../LocalFS.h" #include namespace WebUI { @@ -124,19 +124,19 @@ namespace WebUI { return Error::Ok; } - static Error SPIFFSSize(char* parameter, AuthenticationLevel auth_level, Channel& out) { // ESP720 - out << parameter << "SPIFFS Total:" << formatBytes(SPIFFS.totalBytes()); - out << " Used:" << formatBytes(SPIFFS.usedBytes()) << '\n'; + static Error LocalFSSize(char* parameter, AuthenticationLevel auth_level, Channel& out) { // ESP720 + out << parameter << "LocalFS Total:" << formatBytes(LocalFS.totalBytes()); + out << " Used:" << formatBytes(LocalFS.usedBytes()) << '\n'; return Error::Ok; } - static Error formatSpiffs(char* parameter, AuthenticationLevel auth_level, Channel& out) { // ESP710 + static Error formatLocalFS(char* parameter, AuthenticationLevel auth_level, Channel& out) { // ESP710 if (strcmp(parameter, "FORMAT") != 0) { out << "Parameter must be FORMAT" << '\n'; return Error::InvalidValue; } out << "Formatting"; - SPIFFS.format(); + LocalFS.format(); out << "...Done\n"; return Error::Ok; } @@ -334,7 +334,9 @@ namespace WebUI { out << "Cannot find file!" << '\n'; return Error::FsFileNotFound; } - if (file2del.isDirectory()) { + bool isDir = file2del.isDirectory(); + file2del.close(); + if (isDir) { if (!fs.rmdir(path)) { out << "Cannot delete directory! Is directory empty?" << '\n'; return Error::FsFailedDelDir; @@ -347,7 +349,6 @@ namespace WebUI { } out << "File deleted." << '\n'; } - file2del.close(); return Error::Ok; } @@ -363,7 +364,7 @@ namespace WebUI { } static Error deleteLocalFile(char* parameter, AuthenticationLevel auth_level, Channel& out) { - return deleteObject(SPIFFS, parameter, out); + return deleteObject(LocalFS, parameter, out); } static void listDir(fs::FS& fs, const char* dirname, size_t levels, Channel& out) { @@ -417,7 +418,7 @@ namespace WebUI { } static Error listLocalFiles(char* parameter, AuthenticationLevel auth_level, Channel& out) { // No ESP command - listFs(SPIFFS, "LocalFS", 10, SPIFFS.totalBytes(), SPIFFS.usedBytes(), out); + listFs(LocalFS, "LocalFS", 10, LocalFS.totalBytes(), LocalFS.usedBytes(), out); return Error::Ok; } @@ -446,10 +447,10 @@ namespace WebUI { static Error listLocalFilesJSON(char* parameter, AuthenticationLevel auth_level, Channel& out) { // No ESP command JSONencoder j(false, out); j.begin(); - listDirJSON(SPIFFS, "/", 4, &j); - j.member("total", SPIFFS.totalBytes()); - j.member("used", SPIFFS.usedBytes()); - j.member("occupation", String(long(100 * SPIFFS.usedBytes() / SPIFFS.totalBytes()))); + listDirJSON(LocalFS, "/", 4, &j); + j.member("total", LocalFS.totalBytes()); + j.member("used", LocalFS.usedBytes()); + j.member("occupation", String(long(100 * LocalFS.usedBytes() / LocalFS.totalBytes()))); j.end(); return Error::Ok; } @@ -565,8 +566,8 @@ namespace WebUI { new WebCommand("RESTART", WEBCMD, WA, "ESP444", "System/Control", setSystemMode); new WebCommand("RESTART", WEBCMD, WA, NULL, "Bye", restart); - new WebCommand(NULL, WEBCMD, WU, "ESP720", "LocalFS/Size", SPIFFSSize); - new WebCommand("FORMAT", WEBCMD, WA, "ESP710", "LocalFS/Format", formatSpiffs); + new WebCommand(NULL, WEBCMD, WU, "ESP720", "LocalFS/Size", LocalFSSize); + new WebCommand("FORMAT", WEBCMD, WA, "ESP710", "LocalFS/Format", formatLocalFS); new WebCommand("path", WEBCMD, WU, "ESP701", "LocalFS/Show", showLocalFile); new WebCommand("path", WEBCMD, WU, "ESP700", "LocalFS/Run", runLocalFile); new WebCommand("path", WEBCMD, WU, NULL, "LocalFS/List", listLocalFiles); diff --git a/FluidNC/src/WebUI/WifiConfig.cpp b/FluidNC/src/WebUI/WifiConfig.cpp index 8d5e503c4..721c1abca 100644 --- a/FluidNC/src/WebUI/WifiConfig.cpp +++ b/FluidNC/src/WebUI/WifiConfig.cpp @@ -20,7 +20,7 @@ WebUI::WiFiConfig wifi_config; # include # include -# include +# include "../LocalFS.h" # include # include @@ -107,7 +107,7 @@ namespace WebUI { } } out << "Available Size for update: " << formatBytes(flashsize) << '\n'; - out << "Available Size for SPIFFS: " << formatBytes(SPIFFS.totalBytes()) << '\n'; + out << "Available Size for LocalFS: " << formatBytes(LocalFS.totalBytes()) << '\n'; out << "Web port: " << String(web_server.port()) << '\n'; out << "Data port: " << String(telnet_server.port()) << '\n'; diff --git a/FluidNC/src/WebUI/WifiServices.cpp b/FluidNC/src/WebUI/WifiServices.cpp index 26c1636c3..2c470734f 100644 --- a/FluidNC/src/WebUI/WifiServices.cpp +++ b/FluidNC/src/WebUI/WifiServices.cpp @@ -25,7 +25,7 @@ namespace WebUI { # include # include -# include +# include "../LocalFS.h" # include # include # include "WebSettings.h" @@ -50,10 +50,9 @@ namespace WebUI { String type; if (ArduinoOTA.getCommand() == U_FLASH) { type = "sketch"; - } else { // U_SPIFFS - // NOTE: if updating SPIFFS this would be the place to unmount SPIFFS using SPIFFS.end() + } else { type = "filesystem"; - SPIFFS.end(); + LocalFS.end(); } log_info("Start OTA updating " << type); }) diff --git a/libraries/arduinoWebSockets/.gitignore b/libraries/arduinoWebSockets/.gitignore deleted file mode 100644 index 44b2c85f8..000000000 --- a/libraries/arduinoWebSockets/.gitignore +++ /dev/null @@ -1,29 +0,0 @@ -# Compiled Object files -*.slo -*.lo -*.o -*.obj - -# Precompiled Headers -*.gch -*.pch - -# Compiled Dynamic libraries -*.so -*.dylib -*.dll - -# Fortran module files -*.mod - -# Compiled Static libraries -*.lai -*.la -*.a -*.lib - -# Executables -*.exe -*.out -*.app -/tests/webSocketServer/node_modules diff --git a/libraries/arduinoWebSockets/.travis.yml b/libraries/arduinoWebSockets/.travis.yml deleted file mode 100644 index 14693dd82..000000000 --- a/libraries/arduinoWebSockets/.travis.yml +++ /dev/null @@ -1,40 +0,0 @@ -sudo: false -language: bash -os: - - linux -env: - matrix: - - CPU="esp8266" BOARD="esp8266com:esp8266:generic:CpuFrequency=80" IDE_VERSION=1.6.5 - - CPU="esp8266" BOARD="esp8266com:esp8266:generic:CpuFrequency=80,FlashSize=1M0,FlashMode=qio,FlashFreq=80" IDE_VERSION=1.8.5 - - CPU="esp8266" BOARD="esp8266com:esp8266:generic:CpuFrequency=80,Debug=Serial1" IDE_VERSION=1.6.5 - - CPU="esp32" BOARD="espressif:esp32:esp32:FlashFreq=80" IDE_VERSION=1.6.5 - - CPU="esp32" BOARD="espressif:esp32:esp32:FlashFreq=80" IDE_VERSION=1.8.5 - -script: - - /sbin/start-stop-daemon --start --quiet --pidfile /tmp/custom_xvfb_1.pid --make-pidfile --background --exec /usr/bin/Xvfb -- :1 -ac -screen 0 1280x1024x16 - - sleep 3 - - export DISPLAY=:1.0 - - wget http://downloads.arduino.cc/arduino-$IDE_VERSION-linux64.tar.xz - - tar xf arduino-$IDE_VERSION-linux64.tar.xz - - mv arduino-$IDE_VERSION $HOME/arduino_ide - - export PATH="$HOME/arduino_ide:$PATH" - - which arduino - - mkdir -p $HOME/Arduino/libraries - - cp -r $TRAVIS_BUILD_DIR $HOME/Arduino/libraries/arduinoWebSockets - - source $TRAVIS_BUILD_DIR/travis/common.sh - - get_core $CPU - - cd $TRAVIS_BUILD_DIR - - arduino --board $BOARD --save-prefs - - arduino --get-pref sketchbook.path - - build_sketches arduino $HOME/Arduino/libraries/arduinoWebSockets/examples/$CPU $CPU - -notifications: - email: - on_success: change - on_failure: change - webhooks: - urls: - - https://webhooks.gitter.im/e/1aa78fbe15080b0c2e37 - on_success: change # options: [always|never|change] default: always - on_failure: always # options: [always|never|change] default: always - on_start: false # default: false diff --git a/libraries/arduinoWebSockets/LICENSE b/libraries/arduinoWebSockets/LICENSE deleted file mode 100644 index f166cc57b..000000000 --- a/libraries/arduinoWebSockets/LICENSE +++ /dev/null @@ -1,502 +0,0 @@ - GNU LESSER GENERAL PUBLIC LICENSE - Version 2.1, February 1999 - - Copyright (C) 1991, 1999 Free Software Foundation, Inc. - 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - Everyone is permitted to copy and distribute verbatim copies - of this license document, but changing it is not allowed. - -[This is the first released version of the Lesser GPL. It also counts - as the successor of the GNU Library Public License, version 2, hence - the version number 2.1.] - - Preamble - - The licenses for most software are designed to take away your -freedom to share and change it. By contrast, the GNU General Public -Licenses are intended to guarantee your freedom to share and change -free software--to make sure the software is free for all its users. - - This license, the Lesser General Public License, applies to some -specially designated software packages--typically libraries--of the -Free Software Foundation and other authors who decide to use it. You -can use it too, but we suggest you first think carefully about whether -this license or the ordinary General Public License is the better -strategy to use in any particular case, based on the explanations below. - - When we speak of free software, we are referring to freedom of use, -not price. Our General Public Licenses are designed to make sure that -you have the freedom to distribute copies of free software (and charge -for this service if you wish); that you receive source code or can get -it if you want it; that you can change the software and use pieces of -it in new free programs; and that you are informed that you can do -these things. - - To protect your rights, we need to make restrictions that forbid -distributors to deny you these rights or to ask you to surrender these -rights. These restrictions translate to certain responsibilities for -you if you distribute copies of the library or if you modify it. - - For example, if you distribute copies of the library, whether gratis -or for a fee, you must give the recipients all the rights that we gave -you. You must make sure that they, too, receive or can get the source -code. If you link other code with the library, you must provide -complete object files to the recipients, so that they can relink them -with the library after making changes to the library and recompiling -it. And you must show them these terms so they know their rights. - - We protect your rights with a two-step method: (1) we copyright the -library, and (2) we offer you this license, which gives you legal -permission to copy, distribute and/or modify the library. - - To protect each distributor, we want to make it very clear that -there is no warranty for the free library. Also, if the library is -modified by someone else and passed on, the recipients should know -that what they have is not the original version, so that the original -author's reputation will not be affected by problems that might be -introduced by others. - - Finally, software patents pose a constant threat to the existence of -any free program. We wish to make sure that a company cannot -effectively restrict the users of a free program by obtaining a -restrictive license from a patent holder. Therefore, we insist that -any patent license obtained for a version of the library must be -consistent with the full freedom of use specified in this license. - - Most GNU software, including some libraries, is covered by the -ordinary GNU General Public License. This license, the GNU Lesser -General Public License, applies to certain designated libraries, and -is quite different from the ordinary General Public License. We use -this license for certain libraries in order to permit linking those -libraries into non-free programs. - - When a program is linked with a library, whether statically or using -a shared library, the combination of the two is legally speaking a -combined work, a derivative of the original library. The ordinary -General Public License therefore permits such linking only if the -entire combination fits its criteria of freedom. The Lesser General -Public License permits more lax criteria for linking other code with -the library. - - We call this license the "Lesser" General Public License because it -does Less to protect the user's freedom than the ordinary General -Public License. It also provides other free software developers Less -of an advantage over competing non-free programs. These disadvantages -are the reason we use the ordinary General Public License for many -libraries. However, the Lesser license provides advantages in certain -special circumstances. - - For example, on rare occasions, there may be a special need to -encourage the widest possible use of a certain library, so that it becomes -a de-facto standard. To achieve this, non-free programs must be -allowed to use the library. A more frequent case is that a free -library does the same job as widely used non-free libraries. In this -case, there is little to gain by limiting the free library to free -software only, so we use the Lesser General Public License. - - In other cases, permission to use a particular library in non-free -programs enables a greater number of people to use a large body of -free software. For example, permission to use the GNU C Library in -non-free programs enables many more people to use the whole GNU -operating system, as well as its variant, the GNU/Linux operating -system. - - Although the Lesser General Public License is Less protective of the -users' freedom, it does ensure that the user of a program that is -linked with the Library has the freedom and the wherewithal to run -that program using a modified version of the Library. - - The precise terms and conditions for copying, distribution and -modification follow. Pay close attention to the difference between a -"work based on the library" and a "work that uses the library". The -former contains code derived from the library, whereas the latter must -be combined with the library in order to run. - - GNU LESSER GENERAL PUBLIC LICENSE - TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION - - 0. This License Agreement applies to any software library or other -program which contains a notice placed by the copyright holder or -other authorized party saying it may be distributed under the terms of -this Lesser General Public License (also called "this License"). -Each licensee is addressed as "you". - - A "library" means a collection of software functions and/or data -prepared so as to be conveniently linked with application programs -(which use some of those functions and data) to form executables. - - The "Library", below, refers to any such software library or work -which has been distributed under these terms. A "work based on the -Library" means either the Library or any derivative work under -copyright law: that is to say, a work containing the Library or a -portion of it, either verbatim or with modifications and/or translated -straightforwardly into another language. (Hereinafter, translation is -included without limitation in the term "modification".) - - "Source code" for a work means the preferred form of the work for -making modifications to it. For a library, complete source code means -all the source code for all modules it contains, plus any associated -interface definition files, plus the scripts used to control compilation -and installation of the library. - - Activities other than copying, distribution and modification are not -covered by this License; they are outside its scope. The act of -running a program using the Library is not restricted, and output from -such a program is covered only if its contents constitute a work based -on the Library (independent of the use of the Library in a tool for -writing it). Whether that is true depends on what the Library does -and what the program that uses the Library does. - - 1. You may copy and distribute verbatim copies of the Library's -complete source code as you receive it, in any medium, provided that -you conspicuously and appropriately publish on each copy an -appropriate copyright notice and disclaimer of warranty; keep intact -all the notices that refer to this License and to the absence of any -warranty; and distribute a copy of this License along with the -Library. - - You may charge a fee for the physical act of transferring a copy, -and you may at your option offer warranty protection in exchange for a -fee. - - 2. You may modify your copy or copies of the Library or any portion -of it, thus forming a work based on the Library, and copy and -distribute such modifications or work under the terms of Section 1 -above, provided that you also meet all of these conditions: - - a) The modified work must itself be a software library. - - b) You must cause the files modified to carry prominent notices - stating that you changed the files and the date of any change. - - c) You must cause the whole of the work to be licensed at no - charge to all third parties under the terms of this License. - - d) If a facility in the modified Library refers to a function or a - table of data to be supplied by an application program that uses - the facility, other than as an argument passed when the facility - is invoked, then you must make a good faith effort to ensure that, - in the event an application does not supply such function or - table, the facility still operates, and performs whatever part of - its purpose remains meaningful. - - (For example, a function in a library to compute square roots has - a purpose that is entirely well-defined independent of the - application. Therefore, Subsection 2d requires that any - application-supplied function or table used by this function must - be optional: if the application does not supply it, the square - root function must still compute square roots.) - -These requirements apply to the modified work as a whole. If -identifiable sections of that work are not derived from the Library, -and can be reasonably considered independent and separate works in -themselves, then this License, and its terms, do not apply to those -sections when you distribute them as separate works. But when you -distribute the same sections as part of a whole which is a work based -on the Library, the distribution of the whole must be on the terms of -this License, whose permissions for other licensees extend to the -entire whole, and thus to each and every part regardless of who wrote -it. - -Thus, it is not the intent of this section to claim rights or contest -your rights to work written entirely by you; rather, the intent is to -exercise the right to control the distribution of derivative or -collective works based on the Library. - -In addition, mere aggregation of another work not based on the Library -with the Library (or with a work based on the Library) on a volume of -a storage or distribution medium does not bring the other work under -the scope of this License. - - 3. You may opt to apply the terms of the ordinary GNU General Public -License instead of this License to a given copy of the Library. To do -this, you must alter all the notices that refer to this License, so -that they refer to the ordinary GNU General Public License, version 2, -instead of to this License. (If a newer version than version 2 of the -ordinary GNU General Public License has appeared, then you can specify -that version instead if you wish.) Do not make any other change in -these notices. - - Once this change is made in a given copy, it is irreversible for -that copy, so the ordinary GNU General Public License applies to all -subsequent copies and derivative works made from that copy. - - This option is useful when you wish to copy part of the code of -the Library into a program that is not a library. - - 4. You may copy and distribute the Library (or a portion or -derivative of it, under Section 2) in object code or executable form -under the terms of Sections 1 and 2 above provided that you accompany -it with the complete corresponding machine-readable source code, which -must be distributed under the terms of Sections 1 and 2 above on a -medium customarily used for software interchange. - - If distribution of object code is made by offering access to copy -from a designated place, then offering equivalent access to copy the -source code from the same place satisfies the requirement to -distribute the source code, even though third parties are not -compelled to copy the source along with the object code. - - 5. A program that contains no derivative of any portion of the -Library, but is designed to work with the Library by being compiled or -linked with it, is called a "work that uses the Library". Such a -work, in isolation, is not a derivative work of the Library, and -therefore falls outside the scope of this License. - - However, linking a "work that uses the Library" with the Library -creates an executable that is a derivative of the Library (because it -contains portions of the Library), rather than a "work that uses the -library". The executable is therefore covered by this License. -Section 6 states terms for distribution of such executables. - - When a "work that uses the Library" uses material from a header file -that is part of the Library, the object code for the work may be a -derivative work of the Library even though the source code is not. -Whether this is true is especially significant if the work can be -linked without the Library, or if the work is itself a library. The -threshold for this to be true is not precisely defined by law. - - If such an object file uses only numerical parameters, data -structure layouts and accessors, and small macros and small inline -functions (ten lines or less in length), then the use of the object -file is unrestricted, regardless of whether it is legally a derivative -work. (Executables containing this object code plus portions of the -Library will still fall under Section 6.) - - Otherwise, if the work is a derivative of the Library, you may -distribute the object code for the work under the terms of Section 6. -Any executables containing that work also fall under Section 6, -whether or not they are linked directly with the Library itself. - - 6. As an exception to the Sections above, you may also combine or -link a "work that uses the Library" with the Library to produce a -work containing portions of the Library, and distribute that work -under terms of your choice, provided that the terms permit -modification of the work for the customer's own use and reverse -engineering for debugging such modifications. - - You must give prominent notice with each copy of the work that the -Library is used in it and that the Library and its use are covered by -this License. You must supply a copy of this License. If the work -during execution displays copyright notices, you must include the -copyright notice for the Library among them, as well as a reference -directing the user to the copy of this License. Also, you must do one -of these things: - - a) Accompany the work with the complete corresponding - machine-readable source code for the Library including whatever - changes were used in the work (which must be distributed under - Sections 1 and 2 above); and, if the work is an executable linked - with the Library, with the complete machine-readable "work that - uses the Library", as object code and/or source code, so that the - user can modify the Library and then relink to produce a modified - executable containing the modified Library. (It is understood - that the user who changes the contents of definitions files in the - Library will not necessarily be able to recompile the application - to use the modified definitions.) - - b) Use a suitable shared library mechanism for linking with the - Library. A suitable mechanism is one that (1) uses at run time a - copy of the library already present on the user's computer system, - rather than copying library functions into the executable, and (2) - will operate properly with a modified version of the library, if - the user installs one, as long as the modified version is - interface-compatible with the version that the work was made with. - - c) Accompany the work with a written offer, valid for at - least three years, to give the same user the materials - specified in Subsection 6a, above, for a charge no more - than the cost of performing this distribution. - - d) If distribution of the work is made by offering access to copy - from a designated place, offer equivalent access to copy the above - specified materials from the same place. - - e) Verify that the user has already received a copy of these - materials or that you have already sent this user a copy. - - For an executable, the required form of the "work that uses the -Library" must include any data and utility programs needed for -reproducing the executable from it. However, as a special exception, -the materials to be distributed need not include anything that is -normally distributed (in either source or binary form) with the major -components (compiler, kernel, and so on) of the operating system on -which the executable runs, unless that component itself accompanies -the executable. - - It may happen that this requirement contradicts the license -restrictions of other proprietary libraries that do not normally -accompany the operating system. Such a contradiction means you cannot -use both them and the Library together in an executable that you -distribute. - - 7. You may place library facilities that are a work based on the -Library side-by-side in a single library together with other library -facilities not covered by this License, and distribute such a combined -library, provided that the separate distribution of the work based on -the Library and of the other library facilities is otherwise -permitted, and provided that you do these two things: - - a) Accompany the combined library with a copy of the same work - based on the Library, uncombined with any other library - facilities. This must be distributed under the terms of the - Sections above. - - b) Give prominent notice with the combined library of the fact - that part of it is a work based on the Library, and explaining - where to find the accompanying uncombined form of the same work. - - 8. You may not copy, modify, sublicense, link with, or distribute -the Library except as expressly provided under this License. Any -attempt otherwise to copy, modify, sublicense, link with, or -distribute the Library is void, and will automatically terminate your -rights under this License. However, parties who have received copies, -or rights, from you under this License will not have their licenses -terminated so long as such parties remain in full compliance. - - 9. You are not required to accept this License, since you have not -signed it. However, nothing else grants you permission to modify or -distribute the Library or its derivative works. These actions are -prohibited by law if you do not accept this License. Therefore, by -modifying or distributing the Library (or any work based on the -Library), you indicate your acceptance of this License to do so, and -all its terms and conditions for copying, distributing or modifying -the Library or works based on it. - - 10. Each time you redistribute the Library (or any work based on the -Library), the recipient automatically receives a license from the -original licensor to copy, distribute, link with or modify the Library -subject to these terms and conditions. You may not impose any further -restrictions on the recipients' exercise of the rights granted herein. -You are not responsible for enforcing compliance by third parties with -this License. - - 11. If, as a consequence of a court judgment or allegation of patent -infringement or for any other reason (not limited to patent issues), -conditions are imposed on you (whether by court order, agreement or -otherwise) that contradict the conditions of this License, they do not -excuse you from the conditions of this License. If you cannot -distribute so as to satisfy simultaneously your obligations under this -License and any other pertinent obligations, then as a consequence you -may not distribute the Library at all. For example, if a patent -license would not permit royalty-free redistribution of the Library by -all those who receive copies directly or indirectly through you, then -the only way you could satisfy both it and this License would be to -refrain entirely from distribution of the Library. - -If any portion of this section is held invalid or unenforceable under any -particular circumstance, the balance of the section is intended to apply, -and the section as a whole is intended to apply in other circumstances. - -It is not the purpose of this section to induce you to infringe any -patents or other property right claims or to contest validity of any -such claims; this section has the sole purpose of protecting the -integrity of the free software distribution system which is -implemented by public license practices. Many people have made -generous contributions to the wide range of software distributed -through that system in reliance on consistent application of that -system; it is up to the author/donor to decide if he or she is willing -to distribute software through any other system and a licensee cannot -impose that choice. - -This section is intended to make thoroughly clear what is believed to -be a consequence of the rest of this License. - - 12. If the distribution and/or use of the Library is restricted in -certain countries either by patents or by copyrighted interfaces, the -original copyright holder who places the Library under this License may add -an explicit geographical distribution limitation excluding those countries, -so that distribution is permitted only in or among countries not thus -excluded. In such case, this License incorporates the limitation as if -written in the body of this License. - - 13. The Free Software Foundation may publish revised and/or new -versions of the Lesser General Public License from time to time. -Such new versions will be similar in spirit to the present version, -but may differ in detail to address new problems or concerns. - -Each version is given a distinguishing version number. If the Library -specifies a version number of this License which applies to it and -"any later version", you have the option of following the terms and -conditions either of that version or of any later version published by -the Free Software Foundation. If the Library does not specify a -license version number, you may choose any version ever published by -the Free Software Foundation. - - 14. If you wish to incorporate parts of the Library into other free -programs whose distribution conditions are incompatible with these, -write to the author to ask for permission. For software which is -copyrighted by the Free Software Foundation, write to the Free -Software Foundation; we sometimes make exceptions for this. Our -decision will be guided by the two goals of preserving the free status -of all derivatives of our free software and of promoting the sharing -and reuse of software generally. - - NO WARRANTY - - 15. BECAUSE THE LIBRARY IS LICENSED FREE OF CHARGE, THERE IS NO -WARRANTY FOR THE LIBRARY, TO THE EXTENT PERMITTED BY APPLICABLE LAW. -EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR -OTHER PARTIES PROVIDE THE LIBRARY "AS IS" WITHOUT WARRANTY OF ANY -KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE -IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR -PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE -LIBRARY IS WITH YOU. SHOULD THE LIBRARY PROVE DEFECTIVE, YOU ASSUME -THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION. - - 16. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN -WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY -AND/OR REDISTRIBUTE THE LIBRARY AS PERMITTED ABOVE, BE LIABLE TO YOU -FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR -CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE -LIBRARY (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING -RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A -FAILURE OF THE LIBRARY TO OPERATE WITH ANY OTHER SOFTWARE), EVEN IF -SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH -DAMAGES. - - END OF TERMS AND CONDITIONS - - How to Apply These Terms to Your New Libraries - - If you develop a new library, and you want it to be of the greatest -possible use to the public, we recommend making it free software that -everyone can redistribute and change. You can do so by permitting -redistribution under these terms (or, alternatively, under the terms of the -ordinary General Public License). - - To apply these terms, attach the following notices to the library. It is -safest to attach them to the start of each source file to most effectively -convey the exclusion of warranty; and each file should have at least the -"copyright" line and a pointer to where the full notice is found. - - - Copyright (C) - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - -Also add information on how to contact you by electronic and paper mail. - -You should also get your employer (if you work as a programmer) or your -school, if any, to sign a "copyright disclaimer" for the library, if -necessary. Here is a sample; alter the names: - - Yoyodyne, Inc., hereby disclaims all copyright interest in the - library `Frob' (a library for tweaking knobs) written by James Random Hacker. - - , 1 April 1990 - Ty Coon, President of Vice - -That's all there is to it! \ No newline at end of file diff --git a/libraries/arduinoWebSockets/README.md b/libraries/arduinoWebSockets/README.md deleted file mode 100644 index 63eef3e2a..000000000 --- a/libraries/arduinoWebSockets/README.md +++ /dev/null @@ -1,98 +0,0 @@ -WebSocket Server and Client for Arduino [![Build Status](https://travis-ci.org/Links2004/arduinoWebSockets.svg?branch=master)](https://travis-ci.org/Links2004/arduinoWebSockets) -=========================================== - -a WebSocket Server and Client for Arduino based on RFC6455. - - -##### Supported features of RFC6455 ##### - - text frame - - binary frame - - connection close - - ping - - pong - - continuation frame - -##### Limitations ##### - - max input length is limited to the ram size and the ```WEBSOCKETS_MAX_DATA_SIZE``` define - - max output length has no limit (the hardware is the limit) - - Client send big frames with mask 0x00000000 (on AVR all frames) - - continuation frame reassembly need to be handled in the application code - - ##### Limitations for Async ##### - - Functions called from within the context of the websocket event might not honor `yield()` and/or `delay()`. See [this issue](https://github.com/Links2004/arduinoWebSockets/issues/58#issuecomment-192376395) for more info and a potential workaround. - - wss / SSL is not possible. - -##### Supported Hardware ##### - - ESP8266 [Arduino for ESP8266](https://github.com/esp8266/Arduino/) - - ESP32 [Arduino for ESP32](https://github.com/espressif/arduino-esp32) - - ESP31B - - Particle with STM32 ARM Cortex M3 - - ATmega328 with Ethernet Shield (ATmega branch) - - ATmega328 with enc28j60 (ATmega branch) - - ATmega2560 with Ethernet Shield (ATmega branch) - - ATmega2560 with enc28j60 (ATmega branch) - -###### Note: ###### - - version 2.0 and up is not compatible with AVR/ATmega, check ATmega branch. - - Arduino for AVR not supports std namespace of c++. - -### wss / SSL ### - supported for: - - wss client on the ESP8266 - - wss / SSL is not natively supported in WebSocketsServer however it is possible to achieve secure websockets - by running the device behind an SSL proxy. See [Nginx](examples/Nginx/esp8266.ssl.reverse.proxy.conf) for a - sample Nginx server configuration file to enable this. - -### ESP Async TCP ### - -This libary can run in Async TCP mode on the ESP. - -The mode can be activated in the ```WebSockets.h``` (see WEBSOCKETS_NETWORK_TYPE define). - -[ESPAsyncTCP](https://github.com/me-no-dev/ESPAsyncTCP) libary is required. - - -### High Level Client API ### - - - `begin` : Initiate connection sequence to the websocket host. -``` -void begin(const char *host, uint16_t port, const char * url = "/", const char * protocol = "arduino"); -void begin(String host, uint16_t port, String url = "/", String protocol = "arduino"); - ``` - - `onEvent`: Callback to handle for websocket events - - ``` - void onEvent(WebSocketClientEvent cbEvent); - ``` - - - `WebSocketClientEvent`: Handler for websocket events - ``` - void (*WebSocketClientEvent)(WStype_t type, uint8_t * payload, size_t length) - ``` -Where `WStype_t type` is defined as: - ``` - typedef enum { - WStype_ERROR, - WStype_DISCONNECTED, - WStype_CONNECTED, - WStype_TEXT, - WStype_BIN, - WStype_FRAGMENT_TEXT_START, - WStype_FRAGMENT_BIN_START, - WStype_FRAGMENT, - WStype_FRAGMENT_FIN, - } WStype_t; - ``` - -### Issues ### -Submit issues to: https://github.com/Links2004/arduinoWebSockets/issues - -[![Join the chat at https://gitter.im/Links2004/arduinoWebSockets](https://badges.gitter.im/Join%20Chat.svg)](https://gitter.im/Links2004/arduinoWebSockets?utm_source=badge&utm_medium=badge&utm_campaign=pr-badge&utm_content=badge) - -### License and credits ### - -The library is licensed under [LGPLv2.1](https://github.com/Links2004/arduinoWebSockets/blob/master/LICENSE) - -[libb64](http://libb64.sourceforge.net/) written by Chris Venter. It is distributed under Public Domain see [LICENSE](https://github.com/Links2004/arduinoWebSockets/blob/master/src/libb64/LICENSE). diff --git a/libraries/arduinoWebSockets/examples/Nginx/esp8266.ssl.reverse.proxy.conf b/libraries/arduinoWebSockets/examples/Nginx/esp8266.ssl.reverse.proxy.conf deleted file mode 100644 index ec5aa89fa..000000000 --- a/libraries/arduinoWebSockets/examples/Nginx/esp8266.ssl.reverse.proxy.conf +++ /dev/null @@ -1,83 +0,0 @@ -# ESP8266 nginx SSL reverse proxy configuration file (tested and working on nginx v1.10.0) - -# proxy cache location -proxy_cache_path /opt/etc/nginx/cache levels=1:2 keys_zone=ESP8266_cache:10m max_size=10g inactive=5m use_temp_path=off; - -# webserver proxy -server { - - # general server parameters - listen 50080; - server_name myDomain.net; - access_log /opt/var/log/nginx/myDomain.net.access.log; - - # SSL configuration - ssl on; - ssl_certificate /usr/builtin/etc/certificate/lets-encrypt/myDomain.net/fullchain.pem; - ssl_certificate_key /usr/builtin/etc/certificate/lets-encrypt/myDomain.net/privkey.pem; - ssl_session_cache builtin:1000 shared:SSL:10m; - ssl_protocols TLSv1 TLSv1.1 TLSv1.2; - ssl_ciphers HIGH:!aNULL:!eNULL:!EXPORT:!CAMELLIA:!DES:!MD5:!PSK:!RC4; - ssl_prefer_server_ciphers on; - - location / { - - # proxy caching configuration - proxy_cache ESP8266_cache; - proxy_cache_revalidate on; - proxy_cache_min_uses 1; - proxy_cache_use_stale off; - proxy_cache_lock on; - # proxy_cache_bypass $http_cache_control; - # include the sessionId cookie value as part of the cache key - keeps the cache per user - # proxy_cache_key $proxy_host$request_uri$cookie_sessionId; - - # header pass through configuration - proxy_set_header Host $host; - proxy_set_header X-Forwarded-For $proxy_add_x_forwarded_for; - proxy_set_header X-Forwarded-Proto $scheme; - - # ESP8266 custom headers which identify to the device that it's running through an SSL proxy - proxy_set_header X-SSL On; - proxy_set_header X-SSL-WebserverPort 50080; - proxy_set_header X-SSL-WebsocketPort 50081; - - # extra debug headers - add_header X-Proxy-Cache $upstream_cache_status; - add_header X-Forwarded-For $proxy_add_x_forwarded_for; - - # actual proxying configuration - proxy_ssl_session_reuse on; - # target the IP address of the device with proxy_pass - proxy_pass http://192.168.0.20; - proxy_read_timeout 90; - } - } - -# websocket proxy -server { - - # general server parameters - listen 50081; - server_name myDomain.net; - access_log /opt/var/log/nginx/myDomain.net.wss.access.log; - - # SSL configuration - ssl on; - ssl_certificate /usr/builtin/etc/certificate/lets-encrypt/myDomain.net/fullchain.pem; - ssl_certificate_key /usr/builtin/etc/certificate/lets-encrypt/myDomain.net/privkey.pem; - ssl_session_cache builtin:1000 shared:SSL:10m; - ssl_protocols TLSv1 TLSv1.1 TLSv1.2; - ssl_ciphers HIGH:!aNULL:!eNULL:!EXPORT:!CAMELLIA:!DES:!MD5:!PSK:!RC4; - ssl_prefer_server_ciphers on; - - location / { - - # websocket upgrade tunnel configuration - proxy_pass http://192.168.0.20:81; - proxy_http_version 1.1; - proxy_set_header Upgrade $http_upgrade; - proxy_set_header Connection "Upgrade"; - proxy_read_timeout 86400; - } - } diff --git a/libraries/arduinoWebSockets/examples/avr/WebSocketClientAVR/WebSocketClientAVR.ino b/libraries/arduinoWebSockets/examples/avr/WebSocketClientAVR/WebSocketClientAVR.ino deleted file mode 100644 index 9d49d1498..000000000 --- a/libraries/arduinoWebSockets/examples/avr/WebSocketClientAVR/WebSocketClientAVR.ino +++ /dev/null @@ -1,84 +0,0 @@ -/* - * WebSocketClientAVR.ino - * - * Created on: 10.12.2015 - * - */ - -#include - -#include -#include - -#include - - - -// Enter a MAC address for your controller below. -// Newer Ethernet shields have a MAC address printed on a sticker on the shield -byte mac[] = { 0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xED }; - -// Set the static IP address to use if the DHCP fails to assign -IPAddress ip(192, 168, 0, 177); - -WebSocketsClient webSocket; - - - -void webSocketEvent(WStype_t type, uint8_t * payload, size_t length) { - - - switch(type) { - case WStype_DISCONNECTED: - Serial.println("[WSc] Disconnected!\n"); - break; - case WStype_CONNECTED: - { - Serial.print("[WSc] Connected to url: "); - Serial.println((char *)payload); - // send message to server when Connected - webSocket.sendTXT("Connected"); - } - break; - case WStype_TEXT: - Serial.print("[WSc] get text: "); - Serial.println((char *)payload); - // send message to server - // webSocket.sendTXT("message here"); - break; - case WStype_BIN: - Serial.print("[WSc] get binary length: "); - Serial.println(length); - // hexdump(payload, length); - - // send data to server - // webSocket.sendBIN(payload, length); - break; - } - -} - -void setup() -{ - // Open serial communications and wait for port to open: - Serial.begin(115200); - while (!Serial) {} - - // start the Ethernet connection: - if (Ethernet.begin(mac) == 0) { - Serial.println("Failed to configure Ethernet using DHCP"); - // no point in carrying on, so do nothing forevermore: - // try to congifure using IP address instead of DHCP: - Ethernet.begin(mac, ip); - } - - webSocket.begin("192.168.0.123", 8011); - webSocket.onEvent(webSocketEvent); - -} - - -void loop() -{ - webSocket.loop(); -} diff --git a/libraries/arduinoWebSockets/examples/esp32/WebSocketClient/WebSocketClient.ino b/libraries/arduinoWebSockets/examples/esp32/WebSocketClient/WebSocketClient.ino deleted file mode 100644 index 5e5ead461..000000000 --- a/libraries/arduinoWebSockets/examples/esp32/WebSocketClient/WebSocketClient.ino +++ /dev/null @@ -1,110 +0,0 @@ -/* - * WebSocketClient.ino - * - * Created on: 24.05.2015 - * - */ - -#include - -#include -#include -#include - -#include - - -WiFiMulti WiFiMulti; -WebSocketsClient webSocket; - -#define USE_SERIAL Serial1 - -void hexdump(const void *mem, uint32_t len, uint8_t cols = 16) { - const uint8_t* src = (const uint8_t*) mem; - USE_SERIAL.printf("\n[HEXDUMP] Address: 0x%08X len: 0x%X (%d)", (ptrdiff_t)src, len, len); - for(uint32_t i = 0; i < len; i++) { - if(i % cols == 0) { - USE_SERIAL.printf("\n[0x%08X] 0x%08X: ", (ptrdiff_t)src, i); - } - USE_SERIAL.printf("%02X ", *src); - src++; - } - USE_SERIAL.printf("\n"); -} - -void webSocketEvent(WStype_t type, uint8_t * payload, size_t length) { - - switch(type) { - case WStype_DISCONNECTED: - USE_SERIAL.printf("[WSc] Disconnected!\n"); - break; - case WStype_CONNECTED: - USE_SERIAL.printf("[WSc] Connected to url: %s\n", payload); - - // send message to server when Connected - webSocket.sendTXT("Connected"); - break; - case WStype_TEXT: - USE_SERIAL.printf("[WSc] get text: %s\n", payload); - - // send message to server - // webSocket.sendTXT("message here"); - break; - case WStype_BIN: - USE_SERIAL.printf("[WSc] get binary length: %u\n", length); - hexdump(payload, length); - - // send data to server - // webSocket.sendBIN(payload, length); - break; - case WStype_ERROR: - case WStype_FRAGMENT_TEXT_START: - case WStype_FRAGMENT_BIN_START: - case WStype_FRAGMENT: - case WStype_FRAGMENT_FIN: - break; - } - -} - -void setup() { - // USE_SERIAL.begin(921600); - USE_SERIAL.begin(115200); - - //Serial.setDebugOutput(true); - USE_SERIAL.setDebugOutput(true); - - USE_SERIAL.println(); - USE_SERIAL.println(); - USE_SERIAL.println(); - - for(uint8_t t = 4; t > 0; t--) { - USE_SERIAL.printf("[SETUP] BOOT WAIT %d...\n", t); - USE_SERIAL.flush(); - delay(1000); - } - - WiFiMulti.addAP("SSID", "passpasspass"); - - //WiFi.disconnect(); - while(WiFiMulti.run() != WL_CONNECTED) { - delay(100); - } - - // server address, port and URL - webSocket.begin("192.168.0.123", 81, "/"); - - // event handler - webSocket.onEvent(webSocketEvent); - - // use HTTP Basic Authorization this is optional remove if not needed - webSocket.setAuthorization("user", "Password"); - - // try ever 5000 again if connection has failed - webSocket.setReconnectInterval(5000); - -} - -void loop() { - webSocket.loop(); -} diff --git a/libraries/arduinoWebSockets/examples/esp32/WebSocketClientSSL/WebSocketClientSSL.ino b/libraries/arduinoWebSockets/examples/esp32/WebSocketClientSSL/WebSocketClientSSL.ino deleted file mode 100644 index 9d7224278..000000000 --- a/libraries/arduinoWebSockets/examples/esp32/WebSocketClientSSL/WebSocketClientSSL.ino +++ /dev/null @@ -1,106 +0,0 @@ -/* - * WebSocketClientSSL.ino - * - * Created on: 10.12.2015 - * - * note SSL is only possible with the ESP8266 - * - */ - -#include - -#include -#include -#include - -#include - - -WiFiMulti WiFiMulti; -WebSocketsClient webSocket; - -#define USE_SERIAL Serial1 - -void hexdump(const void *mem, uint32_t len, uint8_t cols = 16) { - const uint8_t* src = (const uint8_t*) mem; - USE_SERIAL.printf("\n[HEXDUMP] Address: 0x%08X len: 0x%X (%d)", (ptrdiff_t)src, len, len); - for(uint32_t i = 0; i < len; i++) { - if(i % cols == 0) { - USE_SERIAL.printf("\n[0x%08X] 0x%08X: ", (ptrdiff_t)src, i); - } - USE_SERIAL.printf("%02X ", *src); - src++; - } - USE_SERIAL.printf("\n"); -} - -void webSocketEvent(WStype_t type, uint8_t * payload, size_t length) { - - - switch(type) { - case WStype_DISCONNECTED: - USE_SERIAL.printf("[WSc] Disconnected!\n"); - break; - case WStype_CONNECTED: - { - USE_SERIAL.printf("[WSc] Connected to url: %s\n", payload); - - // send message to server when Connected - webSocket.sendTXT("Connected"); - } - break; - case WStype_TEXT: - USE_SERIAL.printf("[WSc] get text: %s\n", payload); - - // send message to server - // webSocket.sendTXT("message here"); - break; - case WStype_BIN: - USE_SERIAL.printf("[WSc] get binary length: %u\n", length); - hexdump(payload, length); - - // send data to server - // webSocket.sendBIN(payload, length); - break; - case WStype_ERROR: - case WStype_FRAGMENT_TEXT_START: - case WStype_FRAGMENT_BIN_START: - case WStype_FRAGMENT: - case WStype_FRAGMENT_FIN: - break; - } - -} - -void setup() { - // USE_SERIAL.begin(921600); - USE_SERIAL.begin(115200); - - //Serial.setDebugOutput(true); - USE_SERIAL.setDebugOutput(true); - - USE_SERIAL.println(); - USE_SERIAL.println(); - USE_SERIAL.println(); - - for(uint8_t t = 4; t > 0; t--) { - USE_SERIAL.printf("[SETUP] BOOT WAIT %d...\n", t); - USE_SERIAL.flush(); - delay(1000); - } - - WiFiMulti.addAP("SSID", "passpasspass"); - - //WiFi.disconnect(); - while(WiFiMulti.run() != WL_CONNECTED) { - delay(100); - } - - webSocket.beginSSL("192.168.0.123", 81); - webSocket.onEvent(webSocketEvent); - -} - -void loop() { - webSocket.loop(); -} diff --git a/libraries/arduinoWebSockets/examples/esp32/WebSocketServer/WebSocketServer.ino b/libraries/arduinoWebSockets/examples/esp32/WebSocketServer/WebSocketServer.ino deleted file mode 100644 index 3e0d4f5b8..000000000 --- a/libraries/arduinoWebSockets/examples/esp32/WebSocketServer/WebSocketServer.ino +++ /dev/null @@ -1,104 +0,0 @@ -/* - * WebSocketServer.ino - * - * Created on: 22.05.2015 - * - */ - -#include - -#include -#include -#include - -#include - -WiFiMulti WiFiMulti; -WebSocketsServer webSocket = WebSocketsServer(81); - -#define USE_SERIAL Serial1 - -void hexdump(const void *mem, uint32_t len, uint8_t cols = 16) { - const uint8_t* src = (const uint8_t*) mem; - USE_SERIAL.printf("\n[HEXDUMP] Address: 0x%08X len: 0x%X (%d)", (ptrdiff_t)src, len, len); - for(uint32_t i = 0; i < len; i++) { - if(i % cols == 0) { - USE_SERIAL.printf("\n[0x%08X] 0x%08X: ", (ptrdiff_t)src, i); - } - USE_SERIAL.printf("%02X ", *src); - src++; - } - USE_SERIAL.printf("\n"); -} - -void webSocketEvent(uint8_t num, WStype_t type, uint8_t * payload, size_t length) { - - switch(type) { - case WStype_DISCONNECTED: - USE_SERIAL.printf("[%u] Disconnected!\n", num); - break; - case WStype_CONNECTED: - { - IPAddress ip = webSocket.remoteIP(num); - USE_SERIAL.printf("[%u] Connected from %d.%d.%d.%d url: %s\n", num, ip[0], ip[1], ip[2], ip[3], payload); - - // send message to client - webSocket.sendTXT(num, "Connected"); - } - break; - case WStype_TEXT: - USE_SERIAL.printf("[%u] get Text: %s\n", num, payload); - - // send message to client - // webSocket.sendTXT(num, "message here"); - - // send data to all connected clients - // webSocket.broadcastTXT("message here"); - break; - case WStype_BIN: - USE_SERIAL.printf("[%u] get binary length: %u\n", num, length); - hexdump(payload, length); - - // send message to client - // webSocket.sendBIN(num, payload, length); - break; - case WStype_ERROR: - case WStype_FRAGMENT_TEXT_START: - case WStype_FRAGMENT_BIN_START: - case WStype_FRAGMENT: - case WStype_FRAGMENT_FIN: - break; - } - -} - -void setup() { - // USE_SERIAL.begin(921600); - USE_SERIAL.begin(115200); - - //Serial.setDebugOutput(true); - USE_SERIAL.setDebugOutput(true); - - USE_SERIAL.println(); - USE_SERIAL.println(); - USE_SERIAL.println(); - - for(uint8_t t = 4; t > 0; t--) { - USE_SERIAL.printf("[SETUP] BOOT WAIT %d...\n", t); - USE_SERIAL.flush(); - delay(1000); - } - - WiFiMulti.addAP("SSID", "passpasspass"); - - while(WiFiMulti.run() != WL_CONNECTED) { - delay(100); - } - - webSocket.begin(); - webSocket.onEvent(webSocketEvent); -} - -void loop() { - webSocket.loop(); -} diff --git a/libraries/arduinoWebSockets/examples/esp8266/WebSocketClient/WebSocketClient.ino b/libraries/arduinoWebSockets/examples/esp8266/WebSocketClient/WebSocketClient.ino deleted file mode 100644 index b990c13ac..000000000 --- a/libraries/arduinoWebSockets/examples/esp8266/WebSocketClient/WebSocketClient.ino +++ /dev/null @@ -1,92 +0,0 @@ -/* - * WebSocketClient.ino - * - * Created on: 24.05.2015 - * - */ - -#include - -#include -#include - -#include - -#include - -ESP8266WiFiMulti WiFiMulti; -WebSocketsClient webSocket; - -#define USE_SERIAL Serial1 - -void webSocketEvent(WStype_t type, uint8_t * payload, size_t length) { - - switch(type) { - case WStype_DISCONNECTED: - USE_SERIAL.printf("[WSc] Disconnected!\n"); - break; - case WStype_CONNECTED: { - USE_SERIAL.printf("[WSc] Connected to url: %s\n", payload); - - // send message to server when Connected - webSocket.sendTXT("Connected"); - } - break; - case WStype_TEXT: - USE_SERIAL.printf("[WSc] get text: %s\n", payload); - - // send message to server - // webSocket.sendTXT("message here"); - break; - case WStype_BIN: - USE_SERIAL.printf("[WSc] get binary length: %u\n", length); - hexdump(payload, length); - - // send data to server - // webSocket.sendBIN(payload, length); - break; - } - -} - -void setup() { - // USE_SERIAL.begin(921600); - USE_SERIAL.begin(115200); - - //Serial.setDebugOutput(true); - USE_SERIAL.setDebugOutput(true); - - USE_SERIAL.println(); - USE_SERIAL.println(); - USE_SERIAL.println(); - - for(uint8_t t = 4; t > 0; t--) { - USE_SERIAL.printf("[SETUP] BOOT WAIT %d...\n", t); - USE_SERIAL.flush(); - delay(1000); - } - - WiFiMulti.addAP("SSID", "passpasspass"); - - //WiFi.disconnect(); - while(WiFiMulti.run() != WL_CONNECTED) { - delay(100); - } - - // server address, port and URL - webSocket.begin("192.168.0.123", 81, "/"); - - // event handler - webSocket.onEvent(webSocketEvent); - - // use HTTP Basic Authorization this is optional remove if not needed - webSocket.setAuthorization("user", "Password"); - - // try ever 5000 again if connection has failed - webSocket.setReconnectInterval(5000); - -} - -void loop() { - webSocket.loop(); -} diff --git a/libraries/arduinoWebSockets/examples/esp8266/WebSocketClientSSL/WebSocketClientSSL.ino b/libraries/arduinoWebSockets/examples/esp8266/WebSocketClientSSL/WebSocketClientSSL.ino deleted file mode 100644 index d45060e97..000000000 --- a/libraries/arduinoWebSockets/examples/esp8266/WebSocketClientSSL/WebSocketClientSSL.ino +++ /dev/null @@ -1,88 +0,0 @@ -/* - * WebSocketClientSSL.ino - * - * Created on: 10.12.2015 - * - * note SSL is only possible with the ESP8266 - * - */ - -#include - -#include -#include - -#include - -#include - -ESP8266WiFiMulti WiFiMulti; -WebSocketsClient webSocket; - - -#define USE_SERIAL Serial1 - -void webSocketEvent(WStype_t type, uint8_t * payload, size_t length) { - - - switch(type) { - case WStype_DISCONNECTED: - USE_SERIAL.printf("[WSc] Disconnected!\n"); - break; - case WStype_CONNECTED: - { - USE_SERIAL.printf("[WSc] Connected to url: %s\n", payload); - - // send message to server when Connected - webSocket.sendTXT("Connected"); - } - break; - case WStype_TEXT: - USE_SERIAL.printf("[WSc] get text: %s\n", payload); - - // send message to server - // webSocket.sendTXT("message here"); - break; - case WStype_BIN: - USE_SERIAL.printf("[WSc] get binary length: %u\n", length); - hexdump(payload, length); - - // send data to server - // webSocket.sendBIN(payload, length); - break; - } - -} - -void setup() { - // USE_SERIAL.begin(921600); - USE_SERIAL.begin(115200); - - //Serial.setDebugOutput(true); - USE_SERIAL.setDebugOutput(true); - - USE_SERIAL.println(); - USE_SERIAL.println(); - USE_SERIAL.println(); - - for(uint8_t t = 4; t > 0; t--) { - USE_SERIAL.printf("[SETUP] BOOT WAIT %d...\n", t); - USE_SERIAL.flush(); - delay(1000); - } - - WiFiMulti.addAP("SSID", "passpasspass"); - - //WiFi.disconnect(); - while(WiFiMulti.run() != WL_CONNECTED) { - delay(100); - } - - webSocket.beginSSL("192.168.0.123", 81); - webSocket.onEvent(webSocketEvent); - -} - -void loop() { - webSocket.loop(); -} diff --git a/libraries/arduinoWebSockets/examples/esp8266/WebSocketClientSocketIO/WebSocketClientSocketIO.ino b/libraries/arduinoWebSockets/examples/esp8266/WebSocketClientSocketIO/WebSocketClientSocketIO.ino deleted file mode 100644 index 40e343e27..000000000 --- a/libraries/arduinoWebSockets/examples/esp8266/WebSocketClientSocketIO/WebSocketClientSocketIO.ino +++ /dev/null @@ -1,113 +0,0 @@ -/* - * WebSocketClientSocketIO.ino - * - * Created on: 06.06.2016 - * - */ - -#include - -#include -#include - -#include - -#include - -ESP8266WiFiMulti WiFiMulti; -WebSocketsClient webSocket; - - -#define USE_SERIAL Serial1 - -#define MESSAGE_INTERVAL 30000 -#define HEARTBEAT_INTERVAL 25000 - -uint64_t messageTimestamp = 0; -uint64_t heartbeatTimestamp = 0; -bool isConnected = false; - -void webSocketEvent(WStype_t type, uint8_t * payload, size_t length) { - - - switch(type) { - case WStype_DISCONNECTED: - USE_SERIAL.printf("[WSc] Disconnected!\n"); - isConnected = false; - break; - case WStype_CONNECTED: - { - USE_SERIAL.printf("[WSc] Connected to url: %s\n", payload); - isConnected = true; - - // send message to server when Connected - // socket.io upgrade confirmation message (required) - webSocket.sendTXT("5"); - } - break; - case WStype_TEXT: - USE_SERIAL.printf("[WSc] get text: %s\n", payload); - - // send message to server - // webSocket.sendTXT("message here"); - break; - case WStype_BIN: - USE_SERIAL.printf("[WSc] get binary length: %u\n", length); - hexdump(payload, length); - - // send data to server - // webSocket.sendBIN(payload, length); - break; - } - -} - -void setup() { - // USE_SERIAL.begin(921600); - USE_SERIAL.begin(115200); - - //Serial.setDebugOutput(true); - USE_SERIAL.setDebugOutput(true); - - USE_SERIAL.println(); - USE_SERIAL.println(); - USE_SERIAL.println(); - - for(uint8_t t = 4; t > 0; t--) { - USE_SERIAL.printf("[SETUP] BOOT WAIT %d...\n", t); - USE_SERIAL.flush(); - delay(1000); - } - - WiFiMulti.addAP("SSID", "passpasspass"); - - //WiFi.disconnect(); - while(WiFiMulti.run() != WL_CONNECTED) { - delay(100); - } - - webSocket.beginSocketIO("192.168.0.123", 81); - //webSocket.setAuthorization("user", "Password"); // HTTP Basic Authorization - webSocket.onEvent(webSocketEvent); - -} - -void loop() { - webSocket.loop(); - - if(isConnected) { - - uint64_t now = millis(); - - if(now - messageTimestamp > MESSAGE_INTERVAL) { - messageTimestamp = now; - // example socket.io message with type "messageType" and JSON payload - webSocket.sendTXT("42[\"messageType\",{\"greeting\":\"hello\"}]"); - } - if((now - heartbeatTimestamp) > HEARTBEAT_INTERVAL) { - heartbeatTimestamp = now; - // socket.io heartbeat message - webSocket.sendTXT("2"); - } - } -} diff --git a/libraries/arduinoWebSockets/examples/esp8266/WebSocketClientStomp/WebSocketClientStomp.ino b/libraries/arduinoWebSockets/examples/esp8266/WebSocketClientStomp/WebSocketClientStomp.ino deleted file mode 100644 index a0eb011fd..000000000 --- a/libraries/arduinoWebSockets/examples/esp8266/WebSocketClientStomp/WebSocketClientStomp.ino +++ /dev/null @@ -1,149 +0,0 @@ -/* - WebSocketClientStomp.ino - - Example for connecting and maintining a connection with a STOMP websocket connection. - In this example, we connect to a Spring application (see https://docs.spring.io/spring/docs/current/spring-framework-reference/html/websocket.html). - - Created on: 25.09.2017 - Author: Martin Becker , Contact: becker@informatik.uni-wuerzburg.de -*/ - -// PRE - -#define USE_SERIAL Serial - - -// LIBRARIES - -#include -#include - -#include -#include - - -// SETTINGS - -const char* wlan_ssid = "yourssid"; -const char* wlan_password = "somepassword"; - -const char* ws_host = "the.host.net"; -const int ws_port = 80; - -// URL for STOMP endpoint. -// For the default config of Spring's STOMP support, the default URL is "/socketentry/websocket". -const char* stompUrl = "/socketentry/websocket"; // don't forget the leading "/" !!! - - -// VARIABLES - -WebSocketsClient webSocket; - - -// FUNCTIONS - -/** - * STOMP messages need to be NULL-terminated (i.e., \0 or \u0000). - * However, when we send a String or a char[] array without specifying - * a length, the size of the message payload is derived by strlen() internally, - * thus dropping any NULL values appended to the "msg"-String. - * - * To solve this, we first convert the String to a NULL terminated char[] array - * via "c_str" and set the length of the payload to include the NULL value. - */ -void sendMessage(String & msg) { - webSocket.sendTXT(msg.c_str(), msg.length() + 1); -} - -void webSocketEvent(WStype_t type, uint8_t * payload, size_t length) { - - switch (type) { - case WStype_DISCONNECTED: - USE_SERIAL.printf("[WSc] Disconnected!\n"); - break; - case WStype_CONNECTED: - { - USE_SERIAL.printf("[WSc] Connected to url: %s\n", payload); - - String msg = "CONNECT\r\naccept-version:1.1,1.0\r\nheart-beat:10000,10000\r\n\r\n"; - sendMessage(msg); - } - break; - case WStype_TEXT: - { - // ##################### - // handle STOMP protocol - // ##################### - - String text = (char*) payload; - USE_SERIAL.printf("[WSc] get text: %s\n", payload); - - if (text.startsWith("CONNECTED")) { - - // subscribe to some channels - - String msg = "SUBSCRIBE\nid:sub-0\ndestination:/user/queue/messages\n\n"; - sendMessage(msg); - delay(1000); - - // and send a message - - msg = "SEND\ndestination:/app/message\n\n{\"user\":\"esp\",\"message\":\"Hello!\"}"; - sendMessage(msg); - delay(1000); - - } else { - - // do something with messages - - } - - break; - } - case WStype_BIN: - USE_SERIAL.printf("[WSc] get binary length: %u\n", length); - hexdump(payload, length); - - // send data to server - // webSocket.sendBIN(payload, length); - break; - } - -} - -void setup() { - - // setup serial - - // USE_SERIAL.begin(921600); - USE_SERIAL.begin(115200); - - // USE_SERIAL.setDebugOutput(true); - - USE_SERIAL.println(); - - - // connect to WiFi - - USE_SERIAL.print("Logging into WLAN: "); Serial.print(wlan_ssid); Serial.print(" ..."); - WiFi.mode(WIFI_STA); - WiFi.begin(wlan_ssid, wlan_password); - - while (WiFi.status() != WL_CONNECTED) { - delay(500); - USE_SERIAL.print("."); - } - USE_SERIAL.println(" success."); - USE_SERIAL.print("IP: "); USE_SERIAL.println(WiFi.localIP()); - - - // connect to websocket - webSocket.begin(ws_host, ws_port, stompUrl); - webSocket.setExtraHeaders(); // remove "Origin: file://" header because it breaks the connection with Spring's default websocket config - // webSocket.setExtraHeaders("foo: I am so funny\r\nbar: not"); // some headers, in case you feel funny - webSocket.onEvent(webSocketEvent); -} - -void loop() { - webSocket.loop(); -} diff --git a/libraries/arduinoWebSockets/examples/esp8266/WebSocketClientStompOverSockJs/WebSocketClientStompOverSockJs.ino b/libraries/arduinoWebSockets/examples/esp8266/WebSocketClientStompOverSockJs/WebSocketClientStompOverSockJs.ino deleted file mode 100644 index cb0c45be3..000000000 --- a/libraries/arduinoWebSockets/examples/esp8266/WebSocketClientStompOverSockJs/WebSocketClientStompOverSockJs.ino +++ /dev/null @@ -1,150 +0,0 @@ -/* - WebSocketClientStompOverSockJs.ino - - Example for connecting and maintining a connection with a SockJS+STOMP websocket connection. - In this example, we connect to a Spring application (see https://docs.spring.io/spring/docs/current/spring-framework-reference/html/websocket.html). - - Created on: 18.07.2017 - Author: Martin Becker , Contact: becker@informatik.uni-wuerzburg.de -*/ - -// PRE - -#define USE_SERIAL Serial - - -// LIBRARIES - -#include -#include - -#include -#include - - -// SETTINGS - -const char* wlan_ssid = "yourssid"; -const char* wlan_password = "somepassword"; - -const char* ws_host = "the.host.net"; -const int ws_port = 80; - -// base URL for SockJS (websocket) connection -// The complete URL will look something like this(cf. http://sockjs.github.io/sockjs-protocol/sockjs-protocol-0.3.3.html#section-36): -// ws://://<3digits>//websocket -// For the default config of Spring's SockJS/STOMP support, the default base URL is "/socketentry/". -const char* ws_baseurl = "/socketentry/"; // don't forget leading and trailing "/" !!! - - -// VARIABLES - -WebSocketsClient webSocket; - - -// FUNCTIONS - -void webSocketEvent(WStype_t type, uint8_t * payload, size_t length) { - - switch (type) { - case WStype_DISCONNECTED: - USE_SERIAL.printf("[WSc] Disconnected!\n"); - break; - case WStype_CONNECTED: - { - USE_SERIAL.printf("[WSc] Connected to url: %s\n", payload); - } - break; - case WStype_TEXT: - { - // ##################### - // handle SockJs+STOMP protocol - // ##################### - - String text = (char*) payload; - - USE_SERIAL.printf("[WSc] get text: %s\n", payload); - - if (payload[0] == 'h') { - - USE_SERIAL.println("Heartbeat!"); - - } else if (payload[0] == 'o') { - - // on open connection - char *msg = "[\"CONNECT\\naccept-version:1.1,1.0\\nheart-beat:10000,10000\\n\\n\\u0000\"]"; - webSocket.sendTXT(msg); - - } else if (text.startsWith("a[\"CONNECTED")) { - - // subscribe to some channels - - char *msg = "[\"SUBSCRIBE\\nid:sub-0\\ndestination:/user/queue/messages\\n\\n\\u0000\"]"; - webSocket.sendTXT(msg); - delay(1000); - - // and send a message - - msg = "[\"SEND\\ndestination:/app/message\\n\\n{\\\"user\\\":\\\"esp\\\",\\\"message\\\":\\\"Hello!\\\"}\\u0000\"]"; - webSocket.sendTXT(msg); - delay(1000); - } - - break; - } - case WStype_BIN: - USE_SERIAL.printf("[WSc] get binary length: %u\n", length); - hexdump(payload, length); - - // send data to server - // webSocket.sendBIN(payload, length); - break; - } - -} - -void setup() { - - // setup serial - - // USE_SERIAL.begin(921600); - USE_SERIAL.begin(115200); - - // USE_SERIAL.setDebugOutput(true); - - USE_SERIAL.println(); - - - // connect to WiFi - - USE_SERIAL.print("Logging into WLAN: "); Serial.print(wlan_ssid); Serial.print(" ..."); - WiFi.mode(WIFI_STA); - WiFi.begin(wlan_ssid, wlan_password); - - while (WiFi.status() != WL_CONNECTED) { - delay(500); - USE_SERIAL.print("."); - } - USE_SERIAL.println(" success."); - USE_SERIAL.print("IP: "); USE_SERIAL.println(WiFi.localIP()); - - - // ##################### - // create socket url according to SockJS protocol (cf. http://sockjs.github.io/sockjs-protocol/sockjs-protocol-0.3.3.html#section-36) - // ##################### - String socketUrl = ws_baseurl; - socketUrl += random(0, 999); - socketUrl += "/"; - socketUrl += random(0, 999999); // should be a random string, but this works (see ) - socketUrl += "/websocket"; - - // connect to websocket - webSocket.begin(ws_host, ws_port, socketUrl); - webSocket.setExtraHeaders(); // remove "Origin: file://" header because it breaks the connection with Spring's default websocket config - // webSocket.setExtraHeaders("foo: I am so funny\r\nbar: not"); // some headers, in case you feel funny - webSocket.onEvent(webSocketEvent); -} - -void loop() { - webSocket.loop(); -} diff --git a/libraries/arduinoWebSockets/examples/esp8266/WebSocketServer/WebSocketServer.ino b/libraries/arduinoWebSockets/examples/esp8266/WebSocketServer/WebSocketServer.ino deleted file mode 100644 index 1ac3002d2..000000000 --- a/libraries/arduinoWebSockets/examples/esp8266/WebSocketServer/WebSocketServer.ino +++ /dev/null @@ -1,86 +0,0 @@ -/* - * WebSocketServer.ino - * - * Created on: 22.05.2015 - * - */ - -#include - -#include -#include -#include -#include - -ESP8266WiFiMulti WiFiMulti; - -WebSocketsServer webSocket = WebSocketsServer(81); - -#define USE_SERIAL Serial1 - -void webSocketEvent(uint8_t num, WStype_t type, uint8_t * payload, size_t length) { - - switch(type) { - case WStype_DISCONNECTED: - USE_SERIAL.printf("[%u] Disconnected!\n", num); - break; - case WStype_CONNECTED: - { - IPAddress ip = webSocket.remoteIP(num); - USE_SERIAL.printf("[%u] Connected from %d.%d.%d.%d url: %s\n", num, ip[0], ip[1], ip[2], ip[3], payload); - - // send message to client - webSocket.sendTXT(num, "Connected"); - } - break; - case WStype_TEXT: - USE_SERIAL.printf("[%u] get Text: %s\n", num, payload); - - // send message to client - // webSocket.sendTXT(num, "message here"); - - // send data to all connected clients - // webSocket.broadcastTXT("message here"); - break; - case WStype_BIN: - USE_SERIAL.printf("[%u] get binary length: %u\n", num, length); - hexdump(payload, length); - - // send message to client - // webSocket.sendBIN(num, payload, length); - break; - } - -} - -void setup() { - // USE_SERIAL.begin(921600); - USE_SERIAL.begin(115200); - - //Serial.setDebugOutput(true); - USE_SERIAL.setDebugOutput(true); - - USE_SERIAL.println(); - USE_SERIAL.println(); - USE_SERIAL.println(); - - for(uint8_t t = 4; t > 0; t--) { - USE_SERIAL.printf("[SETUP] BOOT WAIT %d...\n", t); - USE_SERIAL.flush(); - delay(1000); - } - - WiFiMulti.addAP("SSID", "passpasspass"); - - while(WiFiMulti.run() != WL_CONNECTED) { - delay(100); - } - - webSocket.begin(); - webSocket.onEvent(webSocketEvent); -} - -void loop() { - webSocket.loop(); -} - diff --git a/libraries/arduinoWebSockets/examples/esp8266/WebSocketServerAllFunctionsDemo/WebSocketServerAllFunctionsDemo.ino b/libraries/arduinoWebSockets/examples/esp8266/WebSocketServerAllFunctionsDemo/WebSocketServerAllFunctionsDemo.ino deleted file mode 100644 index 5fed1a959..000000000 --- a/libraries/arduinoWebSockets/examples/esp8266/WebSocketServerAllFunctionsDemo/WebSocketServerAllFunctionsDemo.ino +++ /dev/null @@ -1,132 +0,0 @@ -/* - * WebSocketServerAllFunctionsDemo.ino - * - * Created on: 10.05.2018 - * - */ - -#include - -#include -#include -#include -#include -#include -#include - -#define LED_RED 15 -#define LED_GREEN 12 -#define LED_BLUE 13 - -#define USE_SERIAL Serial - -ESP8266WiFiMulti WiFiMulti; - -ESP8266WebServer server(80); -WebSocketsServer webSocket = WebSocketsServer(81); - -void webSocketEvent(uint8_t num, WStype_t type, uint8_t * payload, size_t length) { - - switch(type) { - case WStype_DISCONNECTED: - USE_SERIAL.printf("[%u] Disconnected!\n", num); - break; - case WStype_CONNECTED: { - IPAddress ip = webSocket.remoteIP(num); - USE_SERIAL.printf("[%u] Connected from %d.%d.%d.%d url: %s\n", num, ip[0], ip[1], ip[2], ip[3], payload); - - // send message to client - webSocket.sendTXT(num, "Connected"); - } - break; - case WStype_TEXT: - USE_SERIAL.printf("[%u] get Text: %s\n", num, payload); - - if(payload[0] == '#') { - // we get RGB data - - // decode rgb data - uint32_t rgb = (uint32_t) strtol((const char *) &payload[1], NULL, 16); - - analogWrite(LED_RED, ((rgb >> 16) & 0xFF)); - analogWrite(LED_GREEN, ((rgb >> 8) & 0xFF)); - analogWrite(LED_BLUE, ((rgb >> 0) & 0xFF)); - } - - break; - } - -} - -void setup() { - //USE_SERIAL.begin(921600); - USE_SERIAL.begin(115200); - - //USE_SERIAL.setDebugOutput(true); - - USE_SERIAL.println(); - USE_SERIAL.println(); - USE_SERIAL.println(); - - for(uint8_t t = 4; t > 0; t--) { - USE_SERIAL.printf("[SETUP] BOOT WAIT %d...\n", t); - USE_SERIAL.flush(); - delay(1000); - } - - pinMode(LED_RED, OUTPUT); - pinMode(LED_GREEN, OUTPUT); - pinMode(LED_BLUE, OUTPUT); - - digitalWrite(LED_RED, 1); - digitalWrite(LED_GREEN, 1); - digitalWrite(LED_BLUE, 1); - - WiFiMulti.addAP("SSID", "passpasspass"); - - while(WiFiMulti.run() != WL_CONNECTED) { - delay(100); - } - - // start webSocket server - webSocket.begin(); - webSocket.onEvent(webSocketEvent); - - if(MDNS.begin("esp8266")) { - USE_SERIAL.println("MDNS responder started"); - } - - // handle index - server.on("/", []() { - // send index.html - server.send(200, "text/html", "LED Control:

R:
G:
B:
"); - }); - - server.begin(); - - // Add service to MDNS - MDNS.addService("http", "tcp", 80); - MDNS.addService("ws", "tcp", 81); - - digitalWrite(LED_RED, 0); - digitalWrite(LED_GREEN, 0); - digitalWrite(LED_BLUE, 0); - -} - -unsigned long last_10sec = 0; -unsigned int counter = 0; - -void loop() { - unsigned long t = millis(); - webSocket.loop(); - server.handleClient(); - - if((t - last_10sec) > 10 * 1000) { - counter++; - bool ping = (counter % 2); - int i = webSocket.connectedClients(ping); - USE_SERIAL.printf("%d Connected websocket clients ping: %d\n", i, ping); - last_10sec = millis(); - } -} diff --git a/libraries/arduinoWebSockets/examples/esp8266/WebSocketServerFragmentation/WebSocketServerFragmentation.ino b/libraries/arduinoWebSockets/examples/esp8266/WebSocketServerFragmentation/WebSocketServerFragmentation.ino deleted file mode 100644 index 84c9775d9..000000000 --- a/libraries/arduinoWebSockets/examples/esp8266/WebSocketServerFragmentation/WebSocketServerFragmentation.ino +++ /dev/null @@ -1,94 +0,0 @@ -/* - * WebSocketServer.ino - * - * Created on: 22.05.2015 - * - */ - -#include - -#include -#include -#include -#include - -ESP8266WiFiMulti WiFiMulti; - -WebSocketsServer webSocket = WebSocketsServer(81); - -#define USE_SERIAL Serial - -String fragmentBuffer = ""; - -void webSocketEvent(uint8_t num, WStype_t type, uint8_t * payload, size_t length) { - - switch(type) { - case WStype_DISCONNECTED: - USE_SERIAL.printf("[%u] Disconnected!\n", num); - break; - case WStype_CONNECTED: { - IPAddress ip = webSocket.remoteIP(num); - USE_SERIAL.printf("[%u] Connected from %d.%d.%d.%d url: %s\n", num, ip[0], ip[1], ip[2], ip[3], payload); - - // send message to client - webSocket.sendTXT(num, "Connected"); - } - break; - case WStype_TEXT: - USE_SERIAL.printf("[%u] get Text: %s\n", num, payload); - break; - case WStype_BIN: - USE_SERIAL.printf("[%u] get binary length: %u\n", num, length); - hexdump(payload, length); - break; - - // Fragmentation / continuation opcode handling - // case WStype_FRAGMENT_BIN_START: - case WStype_FRAGMENT_TEXT_START: - fragmentBuffer = (char*)payload; - USE_SERIAL.printf("[%u] get start start of Textfragment: %s\n", num, payload); - break; - case WStype_FRAGMENT: - fragmentBuffer += (char*)payload; - USE_SERIAL.printf("[%u] get Textfragment : %s\n", num, payload); - break; - case WStype_FRAGMENT_FIN: - fragmentBuffer += (char*)payload; - USE_SERIAL.printf("[%u] get end of Textfragment: %s\n", num, payload); - USE_SERIAL.printf("[%u] full frame: %s\n", num, fragmentBuffer.c_str()); - break; - } - -} - -void setup() { - // USE_SERIAL.begin(921600); - USE_SERIAL.begin(115200); - - //Serial.setDebugOutput(true); - USE_SERIAL.setDebugOutput(true); - - USE_SERIAL.println(); - USE_SERIAL.println(); - USE_SERIAL.println(); - - for(uint8_t t = 4; t > 0; t--) { - USE_SERIAL.printf("[SETUP] BOOT WAIT %d...\n", t); - USE_SERIAL.flush(); - delay(1000); - } - - WiFiMulti.addAP("SSID", "passpasspass"); - - while(WiFiMulti.run() != WL_CONNECTED) { - delay(100); - } - - webSocket.begin(); - webSocket.onEvent(webSocketEvent); -} - -void loop() { - webSocket.loop(); -} - diff --git a/libraries/arduinoWebSockets/examples/esp8266/WebSocketServerHttpHeaderValidation/WebSocketServerHttpHeaderValidation.ino b/libraries/arduinoWebSockets/examples/esp8266/WebSocketServerHttpHeaderValidation/WebSocketServerHttpHeaderValidation.ino deleted file mode 100644 index 8bc646c4f..000000000 --- a/libraries/arduinoWebSockets/examples/esp8266/WebSocketServerHttpHeaderValidation/WebSocketServerHttpHeaderValidation.ino +++ /dev/null @@ -1,86 +0,0 @@ -/* - * WebSocketServerHttpHeaderValidation.ino - * - * Created on: 08.06.2016 - * - */ - -#include - -#include -#include -#include -#include - -ESP8266WiFiMulti WiFiMulti; - -WebSocketsServer webSocket = WebSocketsServer(81); - -#define USE_SERIAL Serial1 - -const unsigned long int validSessionId = 12345; //some arbitrary value to act as a valid sessionId - -/* - * Returns a bool value as an indicator to describe whether a user is allowed to initiate a websocket upgrade - * based on the value of a cookie. This function expects the rawCookieHeaderValue to look like this "sessionId=|" - */ -bool isCookieValid(String rawCookieHeaderValue) { - - if (rawCookieHeaderValue.indexOf("sessionId") != -1) { - String sessionIdStr = rawCookieHeaderValue.substring(rawCookieHeaderValue.indexOf("sessionId=") + 10, rawCookieHeaderValue.indexOf("|")); - unsigned long int sessionId = strtoul(sessionIdStr.c_str(), NULL, 10); - return sessionId == validSessionId; - } - return false; -} - -/* - * The WebSocketServerHttpHeaderValFunc delegate passed to webSocket.onValidateHttpHeader - */ -bool validateHttpHeader(String headerName, String headerValue) { - - //assume a true response for any headers not handled by this validator - bool valid = true; - - if(headerName.equalsIgnoreCase("Cookie")) { - //if the header passed is the Cookie header, validate it according to the rules in 'isCookieValid' function - valid = isCookieValid(headerValue); - } - - return valid; -} - -void setup() { - // USE_SERIAL.begin(921600); - USE_SERIAL.begin(115200); - - //Serial.setDebugOutput(true); - USE_SERIAL.setDebugOutput(true); - - USE_SERIAL.println(); - USE_SERIAL.println(); - USE_SERIAL.println(); - - for(uint8_t t = 4; t > 0; t--) { - USE_SERIAL.printf("[SETUP] BOOT WAIT %d...\n", t); - USE_SERIAL.flush(); - delay(1000); - } - - WiFiMulti.addAP("SSID", "passpasspass"); - - while(WiFiMulti.run() != WL_CONNECTED) { - delay(100); - } - - //connecting clients must supply a valid session cookie at websocket upgrade handshake negotiation time - const char * headerkeys[] = { "Cookie" }; - size_t headerKeyCount = sizeof(headerkeys) / sizeof(char*); - webSocket.onValidateHttpHeader(validateHttpHeader, headerkeys, headerKeyCount); - webSocket.begin(); -} - -void loop() { - webSocket.loop(); -} - diff --git a/libraries/arduinoWebSockets/examples/esp8266/WebSocketServer_LEDcontrol/WebSocketServer_LEDcontrol.ino b/libraries/arduinoWebSockets/examples/esp8266/WebSocketServer_LEDcontrol/WebSocketServer_LEDcontrol.ino deleted file mode 100644 index 8f32e753a..000000000 --- a/libraries/arduinoWebSockets/examples/esp8266/WebSocketServer_LEDcontrol/WebSocketServer_LEDcontrol.ino +++ /dev/null @@ -1,121 +0,0 @@ -/* - * WebSocketServer_LEDcontrol.ino - * - * Created on: 26.11.2015 - * - */ - -#include - -#include -#include -#include -#include -#include -#include - -#define LED_RED 15 -#define LED_GREEN 12 -#define LED_BLUE 13 - -#define USE_SERIAL Serial - - -ESP8266WiFiMulti WiFiMulti; - -ESP8266WebServer server(80); -WebSocketsServer webSocket = WebSocketsServer(81); - -void webSocketEvent(uint8_t num, WStype_t type, uint8_t * payload, size_t length) { - - switch(type) { - case WStype_DISCONNECTED: - USE_SERIAL.printf("[%u] Disconnected!\n", num); - break; - case WStype_CONNECTED: { - IPAddress ip = webSocket.remoteIP(num); - USE_SERIAL.printf("[%u] Connected from %d.%d.%d.%d url: %s\n", num, ip[0], ip[1], ip[2], ip[3], payload); - - // send message to client - webSocket.sendTXT(num, "Connected"); - } - break; - case WStype_TEXT: - USE_SERIAL.printf("[%u] get Text: %s\n", num, payload); - - if(payload[0] == '#') { - // we get RGB data - - // decode rgb data - uint32_t rgb = (uint32_t) strtol((const char *) &payload[1], NULL, 16); - - analogWrite(LED_RED, ((rgb >> 16) & 0xFF)); - analogWrite(LED_GREEN, ((rgb >> 8) & 0xFF)); - analogWrite(LED_BLUE, ((rgb >> 0) & 0xFF)); - } - - break; - } - -} - -void setup() { - //USE_SERIAL.begin(921600); - USE_SERIAL.begin(115200); - - //USE_SERIAL.setDebugOutput(true); - - USE_SERIAL.println(); - USE_SERIAL.println(); - USE_SERIAL.println(); - - for(uint8_t t = 4; t > 0; t--) { - USE_SERIAL.printf("[SETUP] BOOT WAIT %d...\n", t); - USE_SERIAL.flush(); - delay(1000); - } - - pinMode(LED_RED, OUTPUT); - pinMode(LED_GREEN, OUTPUT); - pinMode(LED_BLUE, OUTPUT); - - digitalWrite(LED_RED, 1); - digitalWrite(LED_GREEN, 1); - digitalWrite(LED_BLUE, 1); - - WiFiMulti.addAP("SSID", "passpasspass"); - - while(WiFiMulti.run() != WL_CONNECTED) { - delay(100); - } - - // start webSocket server - webSocket.begin(); - webSocket.onEvent(webSocketEvent); - - if(MDNS.begin("esp8266")) { - USE_SERIAL.println("MDNS responder started"); - } - - // handle index - server.on("/", []() { - // send index.html - server.send(200, "text/html", "LED Control:

R:
G:
B:
"); - }); - - server.begin(); - - // Add service to MDNS - MDNS.addService("http", "tcp", 80); - MDNS.addService("ws", "tcp", 81); - - digitalWrite(LED_RED, 0); - digitalWrite(LED_GREEN, 0); - digitalWrite(LED_BLUE, 0); - -} - -void loop() { - webSocket.loop(); - server.handleClient(); -} diff --git a/libraries/arduinoWebSockets/examples/particle/ParticleWebSocketClient/application.cpp b/libraries/arduinoWebSockets/examples/particle/ParticleWebSocketClient/application.cpp deleted file mode 100644 index 461228f39..000000000 --- a/libraries/arduinoWebSockets/examples/particle/ParticleWebSocketClient/application.cpp +++ /dev/null @@ -1,46 +0,0 @@ -/* To compile using make CLI, create a folder under \firmware\user\applications and copy application.cpp there. -* Then, copy src files under particleWebSocket folder. -*/ - -#include "application.h" -#include "particleWebSocket/WebSocketsClient.h" - -WebSocketsClient webSocket; - -void webSocketEvent(WStype_t type, uint8_t* payload, size_t length) -{ - switch (type) - { - case WStype_DISCONNECTED: - Serial.printlnf("[WSc] Disconnected!"); - break; - case WStype_CONNECTED: - Serial.printlnf("[WSc] Connected to URL: %s", payload); - webSocket.sendTXT("Connected\r\n"); - break; - case WStype_TEXT: - Serial.printlnf("[WSc] get text: %s", payload); - break; - case WStype_BIN: - Serial.printlnf("[WSc] get binary length: %u", length); - break; - } -} - -void setup() -{ - Serial.begin(9600); - - WiFi.setCredentials("[SSID]", "[PASSWORD]", WPA2, WLAN_CIPHER_AES_TKIP); - WiFi.connect(); - - webSocket.begin("192.168.1.153", 85, "/ClientService/?variable=Test1212"); - webSocket.onEvent(webSocketEvent); -} - -void loop() -{ - webSocket.sendTXT("Hello world!"); - delay(500); - webSocket.loop(); -} diff --git a/libraries/arduinoWebSockets/library.json b/libraries/arduinoWebSockets/library.json deleted file mode 100644 index f1a589238..000000000 --- a/libraries/arduinoWebSockets/library.json +++ /dev/null @@ -1,25 +0,0 @@ -{ - "name": "WebSockets", - "description": "WebSocket Server and Client for Arduino based on RFC6455", - "keywords": "wifi, http, web, server, client, websocket", - "authors": [ - { - "name": "Markus Sattler", - "url": "https://github.com/Links2004", - "maintainer": true - } - ], - "repository": { - "type": "git", - "url": "https://github.com/Links2004/arduinoWebSockets.git" - }, - "version": "2.1.2", - "license": "LGPL-2.1", - "export": { - "exclude": [ - "tests" - ] - }, - "frameworks": "arduino", - "platforms": "atmelavr, espressif8266, espressif32" -} diff --git a/libraries/arduinoWebSockets/library.properties b/libraries/arduinoWebSockets/library.properties deleted file mode 100644 index 00d09455a..000000000 --- a/libraries/arduinoWebSockets/library.properties +++ /dev/null @@ -1,9 +0,0 @@ -name=WebSockets -version=2.1.2 -author=Markus Sattler -maintainer=Markus Sattler -sentence=WebSockets for Arduino (Server + Client) -paragraph=use 2.x.x for ESP and 1.3 for AVR -category=Communication -url=https://github.com/Links2004/arduinoWebSockets -architectures=* diff --git a/libraries/arduinoWebSockets/src/WebSockets.cpp b/libraries/arduinoWebSockets/src/WebSockets.cpp deleted file mode 100644 index 727e4726b..000000000 --- a/libraries/arduinoWebSockets/src/WebSockets.cpp +++ /dev/null @@ -1,655 +0,0 @@ -/** - * @file WebSockets.cpp - * @date 20.05.2015 - * @author Markus Sattler - * - * Copyright (c) 2015 Markus Sattler. All rights reserved. - * This file is part of the WebSockets for Arduino. - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * This library is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - * Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with this library; if not, write to the Free Software - * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - -#include "WebSockets.h" - -#ifdef ESP8266 -#include -#endif - -extern "C" { -#ifdef CORE_HAS_LIBB64 -#include -#else -#include "libb64/cencode_inc.h" -#endif -} - -#ifdef ESP8266 -#include -#elif defined(ESP32) -#include -#else - -extern "C" { -#include "libsha1/libsha1.h" -} - -#endif - - -/** - * - * @param client WSclient_t * ptr to the client struct - * @param code uint16_t see RFC - * @param reason ptr to the disconnect reason message - * @param reasonLen length of the disconnect reason message - */ -void WebSockets::clientDisconnect(WSclient_t * client, uint16_t code, char * reason, size_t reasonLen) { - DEBUG_WEBSOCKETS("[WS][%d][handleWebsocket] clientDisconnect code: %u\n", client->num, code); - if(client->status == WSC_CONNECTED && code) { - if(reason) { - sendFrame(client, WSop_close, (uint8_t *) reason, reasonLen); - } else { - uint8_t buffer[2]; - buffer[0] = ((code >> 8) & 0xFF); - buffer[1] = (code & 0xFF); - sendFrame(client, WSop_close, &buffer[0], 2); - } - } - clientDisconnect(client); -} - -/** - * - * @param client WSclient_t * ptr to the client struct - * @param opcode WSopcode_t - * @param payload uint8_t * ptr to the payload - * @param length size_t length of the payload - * @param mask bool add dummy mask to the frame (needed for web browser) - * @param fin bool can be used to send data in more then one frame (set fin on the last frame) - * @param headerToPayload bool set true if the payload has reserved 14 Byte at the beginning to dynamically add the Header (payload neet to be in RAM!) - * @return true if ok - */ -bool WebSockets::sendFrame(WSclient_t * client, WSopcode_t opcode, uint8_t * payload, size_t length, bool mask, bool fin, bool headerToPayload) { - - if(client->tcp && !client->tcp->connected()) { - DEBUG_WEBSOCKETS("[WS][%d][sendFrame] not Connected!?\n", client->num); - return false; - } - - if(client->status != WSC_CONNECTED) { - DEBUG_WEBSOCKETS("[WS][%d][sendFrame] not in WSC_CONNECTED state!?\n", client->num); - return false; - } - - DEBUG_WEBSOCKETS("[WS][%d][sendFrame] ------- send message frame -------\n", client->num); - DEBUG_WEBSOCKETS("[WS][%d][sendFrame] fin: %u opCode: %u mask: %u length: %u headerToPayload: %u\n", client->num, fin, opcode, mask, length, headerToPayload); - - if(opcode == WSop_text) { - DEBUG_WEBSOCKETS("[WS][%d][sendFrame] text: %s\n", client->num, (payload + (headerToPayload ? 14 : 0))); - } - - uint8_t maskKey[4] = { 0x00, 0x00, 0x00, 0x00 }; - uint8_t buffer[WEBSOCKETS_MAX_HEADER_SIZE] = { 0 }; - - uint8_t headerSize; - uint8_t * headerPtr; - uint8_t * payloadPtr = payload; - bool useInternBuffer = false; - bool ret = true; - - // calculate header Size - if(length < 126) { - headerSize = 2; - } else if(length < 0xFFFF) { - headerSize = 4; - } else { - headerSize = 10; - } - - if(mask) { - headerSize += 4; - } - -#ifdef WEBSOCKETS_USE_BIG_MEM - // only for ESP since AVR has less HEAP - // try to send data in one TCP package (only if some free Heap is there) - if(!headerToPayload && ((length > 0) && (length < 1400)) && (GET_FREE_HEAP > 6000)) { - DEBUG_WEBSOCKETS("[WS][%d][sendFrame] pack to one TCP package...\n", client->num); - uint8_t * dataPtr = (uint8_t *) malloc(length + WEBSOCKETS_MAX_HEADER_SIZE); - if(dataPtr) { - memcpy((dataPtr + WEBSOCKETS_MAX_HEADER_SIZE), payload, length); - headerToPayload = true; - useInternBuffer = true; - payloadPtr = dataPtr; - } - } -#endif - - // set Header Pointer - if(headerToPayload) { - // calculate offset in payload - headerPtr = (payloadPtr + (WEBSOCKETS_MAX_HEADER_SIZE - headerSize)); - } else { - headerPtr = &buffer[0]; - } - - // create header - - // byte 0 - *headerPtr = 0x00; - if(fin) { - *headerPtr |= bit(7); ///< set Fin - } - *headerPtr |= opcode; ///< set opcode - headerPtr++; - - // byte 1 - *headerPtr = 0x00; - if(mask) { - *headerPtr |= bit(7); ///< set mask - } - - if(length < 126) { - *headerPtr |= length; - headerPtr++; - } else if(length < 0xFFFF) { - *headerPtr |= 126; - headerPtr++; - *headerPtr = ((length >> 8) & 0xFF); - headerPtr++; - *headerPtr = (length & 0xFF); - headerPtr++; - } else { - // Normally we never get here (to less memory) - *headerPtr |= 127; - headerPtr++; - *headerPtr = 0x00; - headerPtr++; - *headerPtr = 0x00; - headerPtr++; - *headerPtr = 0x00; - headerPtr++; - *headerPtr = 0x00; - headerPtr++; - *headerPtr = ((length >> 24) & 0xFF); - headerPtr++; - *headerPtr = ((length >> 16) & 0xFF); - headerPtr++; - *headerPtr = ((length >> 8) & 0xFF); - headerPtr++; - *headerPtr = (length & 0xFF); - headerPtr++; - } - - if(mask) { - if(useInternBuffer) { - // if we use a Intern Buffer we can modify the data - // by this fact its possible the do the masking - for(uint8_t x = 0; x < sizeof(maskKey); x++) { - maskKey[x] = random(0xFF); - *headerPtr = maskKey[x]; - headerPtr++; - } - - uint8_t * dataMaskPtr; - - if(headerToPayload) { - dataMaskPtr = (payloadPtr + WEBSOCKETS_MAX_HEADER_SIZE); - } else { - dataMaskPtr = payloadPtr; - } - - for(size_t x = 0; x < length; x++) { - dataMaskPtr[x] = (dataMaskPtr[x] ^ maskKey[x % 4]); - } - - } else { - *headerPtr = maskKey[0]; - headerPtr++; - *headerPtr = maskKey[1]; - headerPtr++; - *headerPtr = maskKey[2]; - headerPtr++; - *headerPtr = maskKey[3]; - headerPtr++; - } - } - -#ifndef NODEBUG_WEBSOCKETS - unsigned long start = micros(); -#endif - - if(headerToPayload) { - // header has be added to payload - // payload is forced to reserved 14 Byte but we may not need all based on the length and mask settings - // offset in payload is calculatetd 14 - headerSize - if(write(client, &payloadPtr[(WEBSOCKETS_MAX_HEADER_SIZE - headerSize)], (length + headerSize)) != (length + headerSize)) { - ret = false; - } - } else { - // send header - if(write(client, &buffer[0], headerSize) != headerSize) { - ret = false; - } - - if(payloadPtr && length > 0) { - // send payload - if(write(client, &payloadPtr[0], length) != length) { - ret = false; - } - } - } - - DEBUG_WEBSOCKETS("[WS][%d][sendFrame] sending Frame Done (%luus).\n", client->num, (micros() - start)); - -#ifdef WEBSOCKETS_USE_BIG_MEM - if(useInternBuffer && payloadPtr) { - free(payloadPtr); - } -#endif - - return ret; -} - -/** - * callen when HTTP header is done - * @param client WSclient_t * ptr to the client struct - */ -void WebSockets::headerDone(WSclient_t * client) { - client->status = WSC_CONNECTED; - client->cWsRXsize = 0; - DEBUG_WEBSOCKETS("[WS][%d][headerDone] Header Handling Done.\n", client->num); -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) - client->cHttpLine = ""; - handleWebsocket(client); -#endif -} - -/** - * handle the WebSocket stream - * @param client WSclient_t * ptr to the client struct - */ -void WebSockets::handleWebsocket(WSclient_t * client) { - if(client->cWsRXsize == 0) { - handleWebsocketCb(client); - } -} - -/** - * wait for - * @param client - * @param size - */ -bool WebSockets::handleWebsocketWaitFor(WSclient_t * client, size_t size) { - if(!client->tcp || !client->tcp->connected()) { - return false; - } - - if(size > WEBSOCKETS_MAX_HEADER_SIZE) { - DEBUG_WEBSOCKETS("[WS][%d][handleWebsocketWaitFor] size: %d too big!\n", client->num, size); - return false; - } - - if(client->cWsRXsize >= size) { - return true; - } - - DEBUG_WEBSOCKETS("[WS][%d][handleWebsocketWaitFor] size: %d cWsRXsize: %d\n", client->num, size, client->cWsRXsize); - readCb(client, &client->cWsHeader[client->cWsRXsize], (size - client->cWsRXsize), std::bind([](WebSockets * server, size_t size, WSclient_t * client, bool ok) { - DEBUG_WEBSOCKETS("[WS][%d][handleWebsocketWaitFor][readCb] size: %d ok: %d\n", client->num, size, ok); - if(ok) { - client->cWsRXsize = size; - server->handleWebsocketCb(client); - } else { - DEBUG_WEBSOCKETS("[WS][%d][readCb] failed.\n", client->num); - client->cWsRXsize = 0; - // timeout or error - server->clientDisconnect(client, 1002); - } - }, this, size, std::placeholders::_1, std::placeholders::_2)); - return false; -} - -void WebSockets::handleWebsocketCb(WSclient_t * client) { - - if(!client->tcp || !client->tcp->connected()) { - return; - } - - uint8_t * buffer = client->cWsHeader; - - WSMessageHeader_t * header = &client->cWsHeaderDecode; - uint8_t * payload = NULL; - - uint8_t headerLen = 2; - - if(!handleWebsocketWaitFor(client, headerLen)) { - return; - } - - // split first 2 bytes in the data - header->fin = ((*buffer >> 7) & 0x01); - header->rsv1 = ((*buffer >> 6) & 0x01); - header->rsv2 = ((*buffer >> 5) & 0x01); - header->rsv3 = ((*buffer >> 4) & 0x01); - header->opCode = (WSopcode_t) (*buffer & 0x0F); - buffer++; - - header->mask = ((*buffer >> 7) & 0x01); - header->payloadLen = (WSopcode_t) (*buffer & 0x7F); - buffer++; - - if(header->payloadLen == 126) { - headerLen += 2; - if(!handleWebsocketWaitFor(client, headerLen)) { - return; - } - header->payloadLen = buffer[0] << 8 | buffer[1]; - buffer += 2; - } else if(header->payloadLen == 127) { - headerLen += 8; - // read 64bit integer as length - if(!handleWebsocketWaitFor(client, headerLen)) { - return; - } - - if(buffer[0] != 0 || buffer[1] != 0 || buffer[2] != 0 || buffer[3] != 0) { - // really too big! - header->payloadLen = 0xFFFFFFFF; - } else { - header->payloadLen = buffer[4] << 24 | buffer[5] << 16 | buffer[6] << 8 | buffer[7]; - } - buffer += 8; - } - - DEBUG_WEBSOCKETS("[WS][%d][handleWebsocket] ------- read massage frame -------\n", client->num); - DEBUG_WEBSOCKETS("[WS][%d][handleWebsocket] fin: %u rsv1: %u rsv2: %u rsv3 %u opCode: %u\n", client->num, header->fin, header->rsv1, header->rsv2, header->rsv3, header->opCode); - DEBUG_WEBSOCKETS("[WS][%d][handleWebsocket] mask: %u payloadLen: %u\n", client->num, header->mask, header->payloadLen); - - if(header->payloadLen > WEBSOCKETS_MAX_DATA_SIZE) { - DEBUG_WEBSOCKETS("[WS][%d][handleWebsocket] payload too big! (%u)\n", client->num, header->payloadLen); - clientDisconnect(client, 1009); - return; - } - - if(header->mask) { - headerLen += 4; - if(!handleWebsocketWaitFor(client, headerLen)) { - return; - } - header->maskKey = buffer; - buffer += 4; - } - - if(header->payloadLen > 0) { - // if text data we need one more - payload = (uint8_t *) malloc(header->payloadLen + 1); - - if(!payload) { - DEBUG_WEBSOCKETS("[WS][%d][handleWebsocket] to less memory to handle payload %d!\n", client->num, header->payloadLen); - clientDisconnect(client, 1011); - return; - } - readCb(client, payload, header->payloadLen, std::bind(&WebSockets::handleWebsocketPayloadCb, this, std::placeholders::_1, std::placeholders::_2, payload)); - } else { - handleWebsocketPayloadCb(client, true, NULL); - } -} - -void WebSockets::handleWebsocketPayloadCb(WSclient_t * client, bool ok, uint8_t * payload) { - - WSMessageHeader_t * header = &client->cWsHeaderDecode; - if(ok) { - if(header->payloadLen > 0) { - payload[header->payloadLen] = 0x00; - - if(header->mask) { - //decode XOR - for(size_t i = 0; i < header->payloadLen; i++) { - payload[i] = (payload[i] ^ header->maskKey[i % 4]); - } - } - } - - switch(header->opCode) { - case WSop_text: - DEBUG_WEBSOCKETS("[WS][%d][handleWebsocket] text: %s\n", client->num, payload); - // no break here! - case WSop_binary: - case WSop_continuation: - messageReceived(client, header->opCode, payload, header->payloadLen, header->fin); - break; - case WSop_ping: - // send pong back - sendFrame(client, WSop_pong, payload, header->payloadLen, true); - break; - case WSop_pong: - DEBUG_WEBSOCKETS("[WS][%d][handleWebsocket] get pong (%s)\n", client->num, payload ? (const char*)payload : ""); - break; - case WSop_close: { - #ifndef NODEBUG_WEBSOCKETS - uint16_t reasonCode = 1000; - if(header->payloadLen >= 2) { - reasonCode = payload[0] << 8 | payload[1]; - } - #endif - DEBUG_WEBSOCKETS("[WS][%d][handleWebsocket] get ask for close. Code: %d", client->num, reasonCode); - if(header->payloadLen > 2) { - DEBUG_WEBSOCKETS(" (%s)\n", (payload + 2)); - } else { - DEBUG_WEBSOCKETS("\n"); - } - clientDisconnect(client, 1000); - } - break; - default: - clientDisconnect(client, 1002); - break; - } - - if(payload) { - free(payload); - } - - // reset input - client->cWsRXsize = 0; -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) - //register callback for next message - handleWebsocketWaitFor(client, 2); -#endif - - } else { - DEBUG_WEBSOCKETS("[WS][%d][handleWebsocket] missing data!\n", client->num); - free(payload); - clientDisconnect(client, 1002); - } -} - -/** - * generate the key for Sec-WebSocket-Accept - * @param clientKey String - * @return String Accept Key - */ -String WebSockets::acceptKey(String & clientKey) { - uint8_t sha1HashBin[20] = { 0 }; -#ifdef ESP8266 - sha1(clientKey + "258EAFA5-E914-47DA-95CA-C5AB0DC85B11", &sha1HashBin[0]); -#elif defined(ESP32) - String data = clientKey + "258EAFA5-E914-47DA-95CA-C5AB0DC85B11"; - esp_sha(SHA1, (unsigned char*)data.c_str(), data.length(), &sha1HashBin[0]); -#else - clientKey += "258EAFA5-E914-47DA-95CA-C5AB0DC85B11"; - SHA1_CTX ctx; - SHA1Init(&ctx); - SHA1Update(&ctx, (const unsigned char*)clientKey.c_str(), clientKey.length()); - SHA1Final(&sha1HashBin[0], &ctx); -#endif - - String key = base64_encode(sha1HashBin, 20); - key.trim(); - - return key; -} - -/** - * base64_encode - * @param data uint8_t * - * @param length size_t - * @return base64 encoded String - */ -String WebSockets::base64_encode(uint8_t * data, size_t length) { - size_t size = ((length * 1.6f) + 1); - char * buffer = (char *) malloc(size); - if(buffer) { - base64_encodestate _state; - base64_init_encodestate(&_state); - int len = base64_encode_block((const char *) &data[0], length, &buffer[0], &_state); - len = base64_encode_blockend((buffer + len), &_state); - - String base64 = String(buffer); - free(buffer); - return base64; - } - return String("-FAIL-"); -} - -/** - * read x byte from tcp or get timeout - * @param client WSclient_t * - * @param out uint8_t * data buffer - * @param n size_t byte count - * @return true if ok - */ -bool WebSockets::readCb(WSclient_t * client, uint8_t * out, size_t n, WSreadWaitCb cb) { -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) - if(!client->tcp || !client->tcp->connected()) { - return false; - } - - client->tcp->readBytes(out, n, std::bind([](WSclient_t * client, bool ok, WSreadWaitCb cb) { - if(cb) { - cb(client, ok); - } - }, client, std::placeholders::_1, cb)); - -#else - unsigned long t = millis(); - size_t len; - DEBUG_WEBSOCKETS("[readCb] n: %zu t: %lu\n", n, t); - while(n > 0) { - if(client->tcp == NULL) { - DEBUG_WEBSOCKETS("[readCb] tcp is null!\n"); - if(cb) { - cb(client, false); - } - return false; - } - - if(!client->tcp->connected()) { - DEBUG_WEBSOCKETS("[readCb] not connected!\n"); - if(cb) { - cb(client, false); - } - return false; - } - - if((millis() - t) > WEBSOCKETS_TCP_TIMEOUT) { - DEBUG_WEBSOCKETS("[readCb] receive TIMEOUT! %lu\n", (millis() - t)); - if(cb) { - cb(client, false); - } - return false; - } - - if(!client->tcp->available()) { -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) - delay(0); -#endif - continue; - } - - len = client->tcp->read((uint8_t*) out, n); - if(len) { - t = millis(); - out += len; - n -= len; - //DEBUG_WEBSOCKETS("Receive %d left %d!\n", len, n); - } else { - //DEBUG_WEBSOCKETS("Receive %d left %d!\n", len, n); - } -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) - delay(0); -#endif - } - if(cb) { - cb(client, true); - } -#endif - return true; -} - -/** - * write x byte to tcp or get timeout - * @param client WSclient_t * - * @param out uint8_t * data buffer - * @param n size_t byte count - * @return bytes send - */ -size_t WebSockets::write(WSclient_t * client, uint8_t *out, size_t n) { - if(out == NULL) return 0; - if(client == NULL) return 0; - unsigned long t = millis(); - size_t len = 0; - size_t total = 0; - DEBUG_WEBSOCKETS("[write] n: %zu t: %lu\n", n, t); - while(n > 0) { - if(client->tcp == NULL) { - DEBUG_WEBSOCKETS("[write] tcp is null!\n"); - break; - } - - if(!client->tcp->connected()) { - DEBUG_WEBSOCKETS("[write] not connected!\n"); - break; - } - - if((millis() - t) > WEBSOCKETS_TCP_TIMEOUT) { - DEBUG_WEBSOCKETS("[write] write TIMEOUT! %lu\n", (millis() - t)); - break; - } - - len = client->tcp->write((const uint8_t*)out, n); - if(len) { - t = millis(); - out += len; - n -= len; - total += len; - //DEBUG_WEBSOCKETS("write %d left %d!\n", len, n); - } else { - //DEBUG_WEBSOCKETS("write %d failed left %d!\n", len, n); - } -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) - delay(0); -#endif - } - return total; -} - -size_t WebSockets::write(WSclient_t * client, const char *out) { - if(client == NULL) return 0; - if(out == NULL) return 0; - return write(client, (uint8_t*)out, strlen(out)); -} diff --git a/libraries/arduinoWebSockets/src/WebSockets.h b/libraries/arduinoWebSockets/src/WebSockets.h deleted file mode 100644 index dee63977b..000000000 --- a/libraries/arduinoWebSockets/src/WebSockets.h +++ /dev/null @@ -1,311 +0,0 @@ -/** - * @file WebSockets.h - * @date 20.05.2015 - * @author Markus Sattler - * - * Copyright (c) 2015 Markus Sattler. All rights reserved. - * This file is part of the WebSockets for Arduino. - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * This library is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - * Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with this library; if not, write to the Free Software - * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - -#ifndef WEBSOCKETS_H_ -#define WEBSOCKETS_H_ - -#ifdef STM32_DEVICE -#include -#define bit(b) (1UL << (b)) // Taken directly from Arduino.h -#else -#include -#include -#endif - -#ifdef ARDUINO_ARCH_AVR -#error Version 2.x.x currently does not support Arduino with AVR since there is no support for std namespace of c++. -#error Use Version 1.x.x. (ATmega branch) -#else -#include -#endif - - -#ifndef NODEBUG_WEBSOCKETS -#ifdef DEBUG_ESP_PORT -#define DEBUG_WEBSOCKETS(...) DEBUG_ESP_PORT.printf( __VA_ARGS__ ) -#else -//#define DEBUG_WEBSOCKETS(...) os_printf( __VA_ARGS__ ) -#endif -#endif - - -#ifndef DEBUG_WEBSOCKETS -#define DEBUG_WEBSOCKETS(...) -#define NODEBUG_WEBSOCKETS -#endif - -#if defined(ESP8266) || defined(ESP32) - -#define WEBSOCKETS_MAX_DATA_SIZE (15*1024) -#define WEBSOCKETS_USE_BIG_MEM -#define GET_FREE_HEAP ESP.getFreeHeap() -// moves all Header strings to Flash (~300 Byte) -//#define WEBSOCKETS_SAVE_RAM - -#elif defined(STM32_DEVICE) - -#define WEBSOCKETS_MAX_DATA_SIZE (15*1024) -#define WEBSOCKETS_USE_BIG_MEM -#define GET_FREE_HEAP System.freeMemory() - -#else - -//atmega328p has only 2KB ram! -#define WEBSOCKETS_MAX_DATA_SIZE (1024) -// moves all Header strings to Flash -#define WEBSOCKETS_SAVE_RAM - -#endif - - -#define WEBSOCKETS_TCP_TIMEOUT (2000) - -#define NETWORK_ESP8266_ASYNC (0) -#define NETWORK_ESP8266 (1) -#define NETWORK_W5100 (2) -#define NETWORK_ENC28J60 (3) -#define NETWORK_ESP32 (4) - -// max size of the WS Message Header -#define WEBSOCKETS_MAX_HEADER_SIZE (14) - -#if !defined(WEBSOCKETS_NETWORK_TYPE) -// select Network type based -#if defined(ESP8266) || defined(ESP31B) -#define WEBSOCKETS_NETWORK_TYPE NETWORK_ESP8266 -//#define WEBSOCKETS_NETWORK_TYPE NETWORK_ESP8266_ASYNC -//#define WEBSOCKETS_NETWORK_TYPE NETWORK_W5100 - -#elif defined(ESP32) -#define WEBSOCKETS_NETWORK_TYPE NETWORK_ESP32 - -#else -#define WEBSOCKETS_NETWORK_TYPE NETWORK_W5100 - -#endif -#endif - -// Includes and defined based on Network Type -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) - -// Note: -// No SSL/WSS support for client in Async mode -// TLS lib need a sync interface! - - -#if defined(ESP8266) -#include -#elif defined(ESP32) -#include -#include -#elif defined(ESP31B) -#include -#else -#error "network type ESP8266 ASYNC only possible on the ESP mcu!" -#endif - -#include -#include -#define WEBSOCKETS_NETWORK_CLASS AsyncTCPbuffer -#define WEBSOCKETS_NETWORK_SERVER_CLASS AsyncServer - -#elif (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) - -#if !defined(ESP8266) && !defined(ESP31B) -#error "network type ESP8266 only possible on the ESP mcu!" -#endif - -#ifdef ESP8266 -#include -#else -#include -#endif -#define WEBSOCKETS_NETWORK_CLASS WiFiClient -#define WEBSOCKETS_NETWORK_SERVER_CLASS WiFiServer - -#elif (WEBSOCKETS_NETWORK_TYPE == NETWORK_W5100) - -#ifdef STM32_DEVICE -#define WEBSOCKETS_NETWORK_CLASS TCPClient -#define WEBSOCKETS_NETWORK_SERVER_CLASS TCPServer -#else -#include -#include -#define WEBSOCKETS_NETWORK_CLASS EthernetClient -#define WEBSOCKETS_NETWORK_SERVER_CLASS EthernetServer -#endif - -#elif (WEBSOCKETS_NETWORK_TYPE == NETWORK_ENC28J60) - -#include -#define WEBSOCKETS_NETWORK_CLASS UIPClient -#define WEBSOCKETS_NETWORK_SERVER_CLASS UIPServer - -#elif (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) - -#include -#include -#define WEBSOCKETS_NETWORK_CLASS WiFiClient -#define WEBSOCKETS_NETWORK_SERVER_CLASS WiFiServer - -#else -#error "no network type selected!" -#endif - -// moves all Header strings to Flash (~300 Byte) -#ifdef WEBSOCKETS_SAVE_RAM -#define WEBSOCKETS_STRING(var) F(var) -#else -#define WEBSOCKETS_STRING(var) var -#endif - -typedef enum { - WSC_NOT_CONNECTED, - WSC_HEADER, - WSC_CONNECTED -} WSclientsStatus_t; - -typedef enum { - WStype_ERROR, - WStype_DISCONNECTED, - WStype_CONNECTED, - WStype_TEXT, - WStype_BIN, - WStype_FRAGMENT_TEXT_START, - WStype_FRAGMENT_BIN_START, - WStype_FRAGMENT, - WStype_FRAGMENT_FIN, -} WStype_t; - -typedef enum { - WSop_continuation = 0x00, ///< %x0 denotes a continuation frame - WSop_text = 0x01, ///< %x1 denotes a text frame - WSop_binary = 0x02, ///< %x2 denotes a binary frame - ///< %x3-7 are reserved for further non-control frames - WSop_close = 0x08, ///< %x8 denotes a connection close - WSop_ping = 0x09, ///< %x9 denotes a ping - WSop_pong = 0x0A ///< %xA denotes a pong - ///< %xB-F are reserved for further control frames -} WSopcode_t; - -typedef struct { - - bool fin; - bool rsv1; - bool rsv2; - bool rsv3; - - WSopcode_t opCode; - bool mask; - - size_t payloadLen; - - uint8_t * maskKey; -} WSMessageHeader_t; - -typedef struct { - uint8_t num; ///< connection number - - WSclientsStatus_t status; - - WEBSOCKETS_NETWORK_CLASS * tcp; - - bool isSocketIO; ///< client for socket.io server - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) - bool isSSL; ///< run in ssl mode - WiFiClientSecure * ssl; -#endif - - String cUrl; ///< http url - uint16_t cCode; ///< http code - - bool cIsUpgrade; ///< Connection == Upgrade - bool cIsWebsocket; ///< Upgrade == websocket - - String cSessionId; ///< client Set-Cookie (session id) - String cKey; ///< client Sec-WebSocket-Key - String cAccept; ///< client Sec-WebSocket-Accept - String cProtocol; ///< client Sec-WebSocket-Protocol - String cExtensions; ///< client Sec-WebSocket-Extensions - uint16_t cVersion; ///< client Sec-WebSocket-Version - - uint8_t cWsRXsize; ///< State of the RX - uint8_t cWsHeader[WEBSOCKETS_MAX_HEADER_SIZE]; ///< RX WS Message buffer - WSMessageHeader_t cWsHeaderDecode; - - String base64Authorization; ///< Base64 encoded Auth request - String plainAuthorization; ///< Base64 encoded Auth request - - String extraHeaders; - - bool cHttpHeadersValid; ///< non-websocket http header validity indicator - size_t cMandatoryHeadersCount; ///< non-websocket mandatory http headers present count - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) - String cHttpLine; ///< HTTP header lines -#endif - -} WSclient_t; - - - -class WebSockets { - protected: -#ifdef __AVR__ - typedef void (*WSreadWaitCb)(WSclient_t * client, bool ok); -#else - typedef std::function WSreadWaitCb; -#endif - - virtual void clientDisconnect(WSclient_t * client) = 0; - virtual bool clientIsConnected(WSclient_t * client) = 0; - - virtual void messageReceived(WSclient_t * client, WSopcode_t opcode, uint8_t * payload, size_t length, bool fin) = 0; - - void clientDisconnect(WSclient_t * client, uint16_t code, char * reason = NULL, size_t reasonLen = 0); - bool sendFrame(WSclient_t * client, WSopcode_t opcode, uint8_t * payload = NULL, size_t length = 0, bool mask = false, bool fin = true, bool headerToPayload = false); - - void headerDone(WSclient_t * client); - - void handleWebsocket(WSclient_t * client); - - bool handleWebsocketWaitFor(WSclient_t * client, size_t size); - void handleWebsocketCb(WSclient_t * client); - void handleWebsocketPayloadCb(WSclient_t * client, bool ok, uint8_t * payload); - - String acceptKey(String & clientKey); - String base64_encode(uint8_t * data, size_t length); - - bool readCb(WSclient_t * client, uint8_t *out, size_t n, WSreadWaitCb cb); - virtual size_t write(WSclient_t * client, uint8_t *out, size_t n); - size_t write(WSclient_t * client, const char *out); - - -}; - -#ifndef UNUSED -#define UNUSED(var) (void)(var) -#endif -#endif /* WEBSOCKETS_H_ */ diff --git a/libraries/arduinoWebSockets/src/WebSocketsClient.cpp b/libraries/arduinoWebSockets/src/WebSocketsClient.cpp deleted file mode 100644 index f98822a89..000000000 --- a/libraries/arduinoWebSockets/src/WebSocketsClient.cpp +++ /dev/null @@ -1,762 +0,0 @@ -/** - * @file WebSocketsClient.cpp - * @date 20.05.2015 - * @author Markus Sattler - * - * Copyright (c) 2015 Markus Sattler. All rights reserved. - * This file is part of the WebSockets for Arduino. - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * This library is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - * Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with this library; if not, write to the Free Software - * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - -#include "WebSockets.h" -#include "WebSocketsClient.h" - -WebSocketsClient::WebSocketsClient() { - _cbEvent = NULL; - _client.num = 0; - _client.extraHeaders = WEBSOCKETS_STRING("Origin: file://"); -} - -WebSocketsClient::~WebSocketsClient() { - disconnect(); -} - -/** - * calles to init the Websockets server - */ -void WebSocketsClient::begin(const char *host, uint16_t port, const char * url, const char * protocol) { - _host = host; - _port = port; -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) - _fingerprint = ""; -#endif - - _client.num = 0; - _client.status = WSC_NOT_CONNECTED; - _client.tcp = NULL; -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) - _client.isSSL = false; - _client.ssl = NULL; -#endif - _client.cUrl = url; - _client.cCode = 0; - _client.cIsUpgrade = false; - _client.cIsWebsocket = true; - _client.cKey = ""; - _client.cAccept = ""; - _client.cProtocol = protocol; - _client.cExtensions = ""; - _client.cVersion = 0; - _client.base64Authorization = ""; - _client.plainAuthorization = ""; - _client.isSocketIO = false; - -#ifdef ESP8266 - randomSeed(RANDOM_REG32); -#else - // todo find better seed - randomSeed(millis()); -#endif -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) - asyncConnect(); -#endif - - _lastConnectionFail = 0; - _reconnectInterval = 500; -} - -void WebSocketsClient::begin(String host, uint16_t port, String url, String protocol) { - begin(host.c_str(), port, url.c_str(), protocol.c_str()); -} - -void WebSocketsClient::begin(IPAddress host, uint16_t port, const char * url, const char * protocol) { - return begin(host.toString().c_str(), port, url, protocol); -} - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) -void WebSocketsClient::beginSSL(const char *host, uint16_t port, const char * url, const char * fingerprint, const char * protocol) { - begin(host, port, url, protocol); - _client.isSSL = true; - _fingerprint = fingerprint; -} - -void WebSocketsClient::beginSSL(String host, uint16_t port, String url, String fingerprint, String protocol) { - beginSSL(host.c_str(), port, url.c_str(), fingerprint.c_str(), protocol.c_str()); -} -#endif - -void WebSocketsClient::beginSocketIO(const char *host, uint16_t port, const char * url, const char * protocol) { - begin(host, port, url, protocol); - _client.isSocketIO = true; -} - -void WebSocketsClient::beginSocketIO(String host, uint16_t port, String url, String protocol) { - beginSocketIO(host.c_str(), port, url.c_str(), protocol.c_str()); -} - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) -void WebSocketsClient::beginSocketIOSSL(const char *host, uint16_t port, const char * url, const char * protocol) { - begin(host, port, url, protocol); - _client.isSocketIO = true; - _client.isSSL = true; - _fingerprint = ""; -} - -void WebSocketsClient::beginSocketIOSSL(String host, uint16_t port, String url, String protocol) { - beginSocketIOSSL(host.c_str(), port, url.c_str(), protocol.c_str()); -} -#endif - -#if (WEBSOCKETS_NETWORK_TYPE != NETWORK_ESP8266_ASYNC) -/** - * called in arduino loop - */ -void WebSocketsClient::loop(void) { - if(!clientIsConnected(&_client)) { - // do not flood the server - if((millis() - _lastConnectionFail) < _reconnectInterval) { - return; - } - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) - if(_client.isSSL) { - DEBUG_WEBSOCKETS("[WS-Client] connect wss...\n"); - if(_client.ssl) { - delete _client.ssl; - _client.ssl = NULL; - _client.tcp = NULL; - } - _client.ssl = new WiFiClientSecure(); - _client.tcp = _client.ssl; - } else { - DEBUG_WEBSOCKETS("[WS-Client] connect ws...\n"); - if(_client.tcp) { - delete _client.tcp; - _client.tcp = NULL; - } - _client.tcp = new WiFiClient(); - } -#else - _client.tcp = new WEBSOCKETS_NETWORK_CLASS(); -#endif - - if(!_client.tcp) { - DEBUG_WEBSOCKETS("[WS-Client] creating Network class failed!"); - return; - } - - if(_client.tcp->connect(_host.c_str(), _port)) { - connectedCb(); - _lastConnectionFail = 0; - } else { - connectFailedCb(); - _lastConnectionFail = millis(); - - } - } else { - handleClientData(); - } -} -#endif - -/** - * set callback function - * @param cbEvent WebSocketServerEvent - */ -void WebSocketsClient::onEvent(WebSocketClientEvent cbEvent) { - _cbEvent = cbEvent; -} - -/** - * send text data to client - * @param num uint8_t client id - * @param payload uint8_t * - * @param length size_t - * @param headerToPayload bool (see sendFrame for more details) - * @return true if ok - */ -bool WebSocketsClient::sendTXT(uint8_t * payload, size_t length, bool headerToPayload) { - if(length == 0) { - length = strlen((const char *) payload); - } - if(clientIsConnected(&_client)) { - return sendFrame(&_client, WSop_text, payload, length, true, true, headerToPayload); - } - return false; -} - -bool WebSocketsClient::sendTXT(const uint8_t * payload, size_t length) { - return sendTXT((uint8_t *) payload, length); -} - -bool WebSocketsClient::sendTXT(char * payload, size_t length, bool headerToPayload) { - return sendTXT((uint8_t *) payload, length, headerToPayload); -} - -bool WebSocketsClient::sendTXT(const char * payload, size_t length) { - return sendTXT((uint8_t *) payload, length); -} - -bool WebSocketsClient::sendTXT(String & payload) { - return sendTXT((uint8_t *) payload.c_str(), payload.length()); -} - -/** - * send binary data to client - * @param num uint8_t client id - * @param payload uint8_t * - * @param length size_t - * @param headerToPayload bool (see sendFrame for more details) - * @return true if ok - */ -bool WebSocketsClient::sendBIN(uint8_t * payload, size_t length, bool headerToPayload) { - if(clientIsConnected(&_client)) { - return sendFrame(&_client, WSop_binary, payload, length, true, true, headerToPayload); - } - return false; -} - -bool WebSocketsClient::sendBIN(const uint8_t * payload, size_t length) { - return sendBIN((uint8_t *) payload, length); -} - -/** - * sends a WS ping to Server - * @param payload uint8_t * - * @param length size_t - * @return true if ping is send out - */ -bool WebSocketsClient::sendPing(uint8_t * payload, size_t length) { - if(clientIsConnected(&_client)) { - return sendFrame(&_client, WSop_ping, payload, length, true); - } - return false; -} - -bool WebSocketsClient::sendPing(String & payload) { - return sendPing((uint8_t *) payload.c_str(), payload.length()); -} - -/** - * disconnect one client - * @param num uint8_t client id - */ -void WebSocketsClient::disconnect(void) { - if(clientIsConnected(&_client)) { - WebSockets::clientDisconnect(&_client, 1000); - } -} - -/** - * set the Authorizatio for the http request - * @param user const char * - * @param password const char * - */ -void WebSocketsClient::setAuthorization(const char * user, const char * password) { - if(user && password) { - String auth = user; - auth += ":"; - auth += password; - _client.base64Authorization = base64_encode((uint8_t *) auth.c_str(), auth.length()); - } -} - -/** - * set the Authorizatio for the http request - * @param auth const char * base64 - */ -void WebSocketsClient::setAuthorization(const char * auth) { - if(auth) { - //_client.base64Authorization = auth; - _client.plainAuthorization = auth; - } -} - -/** - * set extra headers for the http request; - * separate headers by "\r\n" - * @param extraHeaders const char * extraHeaders - */ -void WebSocketsClient::setExtraHeaders(const char * extraHeaders) { - _client.extraHeaders = extraHeaders; -} - -/** - * set the reconnect Interval - * how long to wait after a connection initiate failed - * @param time in ms - */ -void WebSocketsClient::setReconnectInterval(unsigned long time) { - _reconnectInterval = time; -} - -//################################################################################# -//################################################################################# -//################################################################################# - -/** - * - * @param client WSclient_t * ptr to the client struct - * @param opcode WSopcode_t - * @param payload uint8_t * - * @param length size_t - */ -void WebSocketsClient::messageReceived(WSclient_t * client, WSopcode_t opcode, uint8_t * payload, size_t length, bool fin) { - WStype_t type = WStype_ERROR; - - UNUSED(client); - - switch(opcode) { - case WSop_text: - type = fin ? WStype_TEXT : WStype_FRAGMENT_TEXT_START; - break; - case WSop_binary: - type = fin ? WStype_BIN : WStype_FRAGMENT_BIN_START; - break; - case WSop_continuation: - type = fin ? WStype_FRAGMENT_FIN : WStype_FRAGMENT; - break; - case WSop_close: - case WSop_ping: - case WSop_pong: - default: - break; - } - - runCbEvent(type, payload, length); - -} - -/** - * Disconnect an client - * @param client WSclient_t * ptr to the client struct - */ -void WebSocketsClient::clientDisconnect(WSclient_t * client) { - - bool event = false; - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) - if(client->isSSL && client->ssl) { - if(client->ssl->connected()) { - client->ssl->flush(); - client->ssl->stop(); - } - event = true; - delete client->ssl; - client->ssl = NULL; - client->tcp = NULL; - } -#endif - - if(client->tcp) { - if(client->tcp->connected()) { -#if (WEBSOCKETS_NETWORK_TYPE != NETWORK_ESP8266_ASYNC) - client->tcp->flush(); -#endif - client->tcp->stop(); - } - event = true; -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) - client->status = WSC_NOT_CONNECTED; -#else - delete client->tcp; -#endif - client->tcp = NULL; - } - - client->cCode = 0; - client->cKey = ""; - client->cAccept = ""; - client->cVersion = 0; - client->cIsUpgrade = false; - client->cIsWebsocket = false; - client->cSessionId = ""; - - client->status = WSC_NOT_CONNECTED; - - DEBUG_WEBSOCKETS("[WS-Client] client disconnected.\n"); - if(event) { - runCbEvent(WStype_DISCONNECTED, NULL, 0); - } -} - -/** - * get client state - * @param client WSclient_t * ptr to the client struct - * @return true = conneted - */ -bool WebSocketsClient::clientIsConnected(WSclient_t * client) { - - if(!client->tcp) { - return false; - } - - if(client->tcp->connected()) { - if(client->status != WSC_NOT_CONNECTED) { - return true; - } - } else { - // client lost - if(client->status != WSC_NOT_CONNECTED) { - DEBUG_WEBSOCKETS("[WS-Client] connection lost.\n"); - // do cleanup - clientDisconnect(client); - } - } - - if(client->tcp) { - // do cleanup - clientDisconnect(client); - } - - return false; -} -#if (WEBSOCKETS_NETWORK_TYPE != NETWORK_ESP8266_ASYNC) -/** - * Handel incomming data from Client - */ -void WebSocketsClient::handleClientData(void) { - int len = _client.tcp->available(); - if(len > 0) { - switch(_client.status) { - case WSC_HEADER: { - String headerLine = _client.tcp->readStringUntil('\n'); - handleHeader(&_client, &headerLine); - } - break; - case WSC_CONNECTED: - WebSockets::handleWebsocket(&_client); - break; - default: - WebSockets::clientDisconnect(&_client, 1002); - break; - } - } -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) - delay(0); -#endif -} -#endif - -/** - * send the WebSocket header to Server - * @param client WSclient_t * ptr to the client struct - */ -void WebSocketsClient::sendHeader(WSclient_t * client) { - - static const char * NEW_LINE = "\r\n"; - - DEBUG_WEBSOCKETS("[WS-Client][sendHeader] sending header...\n"); - - uint8_t randomKey[16] = { 0 }; - - for(uint8_t i = 0; i < sizeof(randomKey); i++) { - randomKey[i] = random(0xFF); - } - - client->cKey = base64_encode(&randomKey[0], 16); - -#ifndef NODEBUG_WEBSOCKETS - unsigned long start = micros(); -#endif - - String handshake; - bool ws_header = true; - String url = client->cUrl; - - if(client->isSocketIO) { - if(client->cSessionId.length() == 0) { - url += WEBSOCKETS_STRING("&transport=polling"); - ws_header = false; - } else { - url += WEBSOCKETS_STRING("&transport=websocket&sid="); - url += client->cSessionId; - } - } - - handshake = WEBSOCKETS_STRING("GET "); - handshake += url + WEBSOCKETS_STRING(" HTTP/1.1\r\n" - "Host: "); - handshake += _host + ":" + _port + NEW_LINE; - - if(ws_header) { - handshake += WEBSOCKETS_STRING("Connection: Upgrade\r\n" - "Upgrade: websocket\r\n" - "Sec-WebSocket-Version: 13\r\n" - "Sec-WebSocket-Key: "); - handshake += client->cKey + NEW_LINE; - - if(client->cProtocol.length() > 0) { - handshake += WEBSOCKETS_STRING("Sec-WebSocket-Protocol: "); - handshake += client->cProtocol + NEW_LINE; - } - - if(client->cExtensions.length() > 0) { - handshake += WEBSOCKETS_STRING("Sec-WebSocket-Extensions: "); - handshake += client->cExtensions + NEW_LINE; - } - } else { - handshake += WEBSOCKETS_STRING("Connection: keep-alive\r\n"); - } - - // add extra headers; by default this includes "Origin: file://" - if(client->extraHeaders) { - handshake += client->extraHeaders + NEW_LINE; - } - - handshake += WEBSOCKETS_STRING("User-Agent: arduino-WebSocket-Client\r\n"); - - if(client->base64Authorization.length() > 0) { - handshake += WEBSOCKETS_STRING("Authorization: Basic "); - handshake += client->base64Authorization + NEW_LINE; - } - - if(client->plainAuthorization.length() > 0) { - handshake += WEBSOCKETS_STRING("Authorization: "); - handshake += client->plainAuthorization + NEW_LINE; - } - - handshake += NEW_LINE; - - DEBUG_WEBSOCKETS("[WS-Client][sendHeader] handshake %s", (uint8_t* )handshake.c_str()); - write(client, (uint8_t*) handshake.c_str(), handshake.length()); - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) - client->tcp->readStringUntil('\n', &(client->cHttpLine), std::bind(&WebSocketsClient::handleHeader, this, client, &(client->cHttpLine))); -#endif - - DEBUG_WEBSOCKETS("[WS-Client][sendHeader] sending header... Done (%luus).\n", (micros() - start)); - -} - -/** - * handle the WebSocket header reading - * @param client WSclient_t * ptr to the client struct - */ -void WebSocketsClient::handleHeader(WSclient_t * client, String * headerLine) { - - headerLine->trim(); // remove \r - - if(headerLine->length() > 0) { - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] RX: %s\n", headerLine->c_str()); - - if(headerLine->startsWith(WEBSOCKETS_STRING("HTTP/1."))) { - // "HTTP/1.1 101 Switching Protocols" - client->cCode = headerLine->substring(9, headerLine->indexOf(' ', 9)).toInt(); - } else if(headerLine->indexOf(':')) { - String headerName = headerLine->substring(0, headerLine->indexOf(':')); - String headerValue = headerLine->substring(headerLine->indexOf(':') + 1); - - // remove space in the beginning (RFC2616) - if(headerValue[0] == ' ') { - headerValue.remove(0, 1); - } - - if(headerName.equalsIgnoreCase(WEBSOCKETS_STRING("Connection"))) { - if(headerValue.equalsIgnoreCase(WEBSOCKETS_STRING("upgrade"))) { - client->cIsUpgrade = true; - } - } else if(headerName.equalsIgnoreCase(WEBSOCKETS_STRING("Upgrade"))) { - if(headerValue.equalsIgnoreCase(WEBSOCKETS_STRING("websocket"))) { - client->cIsWebsocket = true; - } - } else if(headerName.equalsIgnoreCase(WEBSOCKETS_STRING("Sec-WebSocket-Accept"))) { - client->cAccept = headerValue; - client->cAccept.trim(); // see rfc6455 - } else if(headerName.equalsIgnoreCase(WEBSOCKETS_STRING("Sec-WebSocket-Protocol"))) { - client->cProtocol = headerValue; - } else if(headerName.equalsIgnoreCase(WEBSOCKETS_STRING("Sec-WebSocket-Extensions"))) { - client->cExtensions = headerValue; - } else if(headerName.equalsIgnoreCase(WEBSOCKETS_STRING("Sec-WebSocket-Version"))) { - client->cVersion = headerValue.toInt(); - } else if(headerName.equalsIgnoreCase(WEBSOCKETS_STRING("Set-Cookie"))) { - if(headerValue.indexOf(WEBSOCKETS_STRING("HttpOnly")) > -1) { - client->cSessionId = headerValue.substring(headerValue.indexOf('=') + 1, headerValue.indexOf(";")); - } else { - client->cSessionId = headerValue.substring(headerValue.indexOf('=') + 1); - } - } - } else { - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] Header error (%s)\n", headerLine->c_str()); - } - - (*headerLine) = ""; -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) - client->tcp->readStringUntil('\n', &(client->cHttpLine), std::bind(&WebSocketsClient::handleHeader, this, client, &(client->cHttpLine))); -#endif - - } else { - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] Header read fin.\n"); - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] Client settings:\n"); - - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] - cURL: %s\n", client->cUrl.c_str()); - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] - cKey: %s\n", client->cKey.c_str()); - - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] Server header:\n"); - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] - cCode: %d\n", client->cCode); - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] - cIsUpgrade: %d\n", client->cIsUpgrade); - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] - cIsWebsocket: %d\n", client->cIsWebsocket); - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] - cAccept: %s\n", client->cAccept.c_str()); - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] - cProtocol: %s\n", client->cProtocol.c_str()); - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] - cExtensions: %s\n", client->cExtensions.c_str()); - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] - cVersion: %d\n", client->cVersion); - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] - cSessionId: %s\n", client->cSessionId.c_str()); - - bool ok = (client->cIsUpgrade && client->cIsWebsocket); - - if(ok) { - switch(client->cCode) { - case 101: ///< Switching Protocols - - break; - case 200: - if(client->isSocketIO) { - break; - } - case 403: ///< Forbidden - // todo handle login - default: ///< Server dont unterstand requrst - ok = false; - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] serverCode is not 101 (%d)\n", client->cCode); - clientDisconnect(client); - _lastConnectionFail = millis(); - break; - } - } - - if(ok) { - - if(client->cAccept.length() == 0) { - ok = false; - } else { - // generate Sec-WebSocket-Accept key for check - String sKey = acceptKey(client->cKey); - if(sKey != client->cAccept) { - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] Sec-WebSocket-Accept is wrong\n"); - ok = false; - } - } - } - - if(ok) { - - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] Websocket connection init done.\n"); - headerDone(client); - - runCbEvent(WStype_CONNECTED, (uint8_t *) client->cUrl.c_str(), client->cUrl.length()); - - } else if(clientIsConnected(client) && client->isSocketIO && client->cSessionId.length() > 0) { - sendHeader(client); - } else { - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] no Websocket connection close.\n"); - _lastConnectionFail = millis(); - if(clientIsConnected(client)) { - write(client, "This is a webSocket client!"); - } - clientDisconnect(client); - } - } -} - -void WebSocketsClient::connectedCb() { - - DEBUG_WEBSOCKETS("[WS-Client] connected to %s:%u.\n", _host.c_str(), _port); - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) - _client.tcp->onDisconnect(std::bind([](WebSocketsClient * c, AsyncTCPbuffer * obj, WSclient_t * client) -> bool { - DEBUG_WEBSOCKETS("[WS-Server][%d] Disconnect client\n", client->num); - client->status = WSC_NOT_CONNECTED; - client->tcp = NULL; - - // reconnect - c->asyncConnect(); - - return true; - }, this, std::placeholders::_1, &_client)); -#endif - - _client.status = WSC_HEADER; - -#if (WEBSOCKETS_NETWORK_TYPE != NETWORK_ESP8266_ASYNC) - // set Timeout for readBytesUntil and readStringUntil - _client.tcp->setTimeout(WEBSOCKETS_TCP_TIMEOUT); -#endif - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) - _client.tcp->setNoDelay(true); - - if(_client.isSSL && _fingerprint.length()) { - if(!_client.ssl->verify(_fingerprint.c_str(), _host.c_str())) { - DEBUG_WEBSOCKETS("[WS-Client] certificate mismatch\n"); - WebSockets::clientDisconnect(&_client, 1000); - return; - } - } -#endif - - // send Header to Server - sendHeader(&_client); - -} - -void WebSocketsClient::connectFailedCb() { - DEBUG_WEBSOCKETS("[WS-Client] connection to %s:%u Faild\n", _host.c_str(), _port); -} - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) - -void WebSocketsClient::asyncConnect() { - - DEBUG_WEBSOCKETS("[WS-Client] asyncConnect...\n"); - - AsyncClient * tcpclient = new AsyncClient(); - - if(!tcpclient) { - DEBUG_WEBSOCKETS("[WS-Client] creating AsyncClient class failed!\n"); - return; - } - - tcpclient->onDisconnect([](void *obj, AsyncClient* c) { - c->free(); - delete c; - }); - - tcpclient->onConnect(std::bind([](WebSocketsClient * ws , AsyncClient * tcp) { - ws->_client.tcp = new AsyncTCPbuffer(tcp); - if(!ws->_client.tcp) { - DEBUG_WEBSOCKETS("[WS-Client] creating Network class failed!\n"); - ws->connectFailedCb(); - return; - } - ws->connectedCb(); - }, this, std::placeholders::_2)); - - tcpclient->onError(std::bind([](WebSocketsClient * ws , AsyncClient * tcp) { - ws->connectFailedCb(); - - // reconnect - ws->asyncConnect(); - }, this, std::placeholders::_2)); - - if(!tcpclient->connect(_host.c_str(), _port)) { - connectFailedCb(); - delete tcpclient; - } - -} - -#endif diff --git a/libraries/arduinoWebSockets/src/WebSocketsClient.h b/libraries/arduinoWebSockets/src/WebSocketsClient.h deleted file mode 100644 index 61b8ea2ae..000000000 --- a/libraries/arduinoWebSockets/src/WebSocketsClient.h +++ /dev/null @@ -1,136 +0,0 @@ -/** - * @file WebSocketsClient.h - * @date 20.05.2015 - * @author Markus Sattler - * - * Copyright (c) 2015 Markus Sattler. All rights reserved. - * This file is part of the WebSockets for Arduino. - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * This library is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - * Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with this library; if not, write to the Free Software - * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - -#ifndef WEBSOCKETSCLIENT_H_ -#define WEBSOCKETSCLIENT_H_ - -#include "WebSockets.h" - -class WebSocketsClient: private WebSockets { - public: -#ifdef __AVR__ - typedef void (*WebSocketClientEvent)(WStype_t type, uint8_t * payload, size_t length); -#else - typedef std::function WebSocketClientEvent; -#endif - - - WebSocketsClient(void); - virtual ~WebSocketsClient(void); - - void begin(const char *host, uint16_t port, const char * url = "/", const char * protocol = "arduino"); - void begin(String host, uint16_t port, String url = "/", String protocol = "arduino"); - void begin(IPAddress host, uint16_t port, const char * url = "/", const char * protocol = "arduino"); - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) - void beginSSL(const char *host, uint16_t port, const char * url = "/", const char * = "", const char * protocol = "arduino"); - void beginSSL(String host, uint16_t port, String url = "/", String fingerprint = "", String protocol = "arduino"); -#endif - - void beginSocketIO(const char *host, uint16_t port, const char * url = "/socket.io/?EIO=3", const char * protocol = "arduino"); - void beginSocketIO(String host, uint16_t port, String url = "/socket.io/?EIO=3", String protocol = "arduino"); - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) - void beginSocketIOSSL(const char *host, uint16_t port, const char * url = "/socket.io/?EIO=3", const char * protocol = "arduino"); - void beginSocketIOSSL(String host, uint16_t port, String url = "/socket.io/?EIO=3", String protocol = "arduino"); -#endif - -#if (WEBSOCKETS_NETWORK_TYPE != NETWORK_ESP8266_ASYNC) - void loop(void); -#else - // Async interface not need a loop call - void loop(void) __attribute__ ((deprecated)) {} -#endif - - void onEvent(WebSocketClientEvent cbEvent); - - bool sendTXT(uint8_t * payload, size_t length = 0, bool headerToPayload = false); - bool sendTXT(const uint8_t * payload, size_t length = 0); - bool sendTXT(char * payload, size_t length = 0, bool headerToPayload = false); - bool sendTXT(const char * payload, size_t length = 0); - bool sendTXT(String & payload); - - bool sendBIN(uint8_t * payload, size_t length, bool headerToPayload = false); - bool sendBIN(const uint8_t * payload, size_t length); - - bool sendPing(uint8_t * payload = NULL, size_t length = 0); - bool sendPing(String & payload); - - void disconnect(void); - - void setAuthorization(const char * user, const char * password); - void setAuthorization(const char * auth); - - void setExtraHeaders(const char * extraHeaders = NULL); - - void setReconnectInterval(unsigned long time); - - protected: - String _host; - uint16_t _port; - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) - String _fingerprint; -#endif - WSclient_t _client; - - WebSocketClientEvent _cbEvent; - - unsigned long _lastConnectionFail; - unsigned long _reconnectInterval; - - void messageReceived(WSclient_t * client, WSopcode_t opcode, uint8_t * payload, size_t length, bool fin); - - void clientDisconnect(WSclient_t * client); - bool clientIsConnected(WSclient_t * client); - -#if (WEBSOCKETS_NETWORK_TYPE != NETWORK_ESP8266_ASYNC) - void handleClientData(void); -#endif - - void sendHeader(WSclient_t * client); - void handleHeader(WSclient_t * client, String * headerLine); - - void connectedCb(); - void connectFailedCb(); - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) - void asyncConnect(); -#endif - - /** - * called for sending a Event to the app - * @param type WStype_t - * @param payload uint8_t * - * @param length size_t - */ - virtual void runCbEvent(WStype_t type, uint8_t * payload, size_t length) { - if(_cbEvent) { - _cbEvent(type, payload, length); - } - } - -}; - -#endif /* WEBSOCKETSCLIENT_H_ */ diff --git a/libraries/arduinoWebSockets/src/WebSocketsServer.cpp b/libraries/arduinoWebSockets/src/WebSocketsServer.cpp deleted file mode 100644 index b6f950f44..000000000 --- a/libraries/arduinoWebSockets/src/WebSocketsServer.cpp +++ /dev/null @@ -1,873 +0,0 @@ -/** - * @file WebSocketsServer.cpp - * @date 20.05.2015 - * @author Markus Sattler - * - * Copyright (c) 2015 Markus Sattler. All rights reserved. - * This file is part of the WebSockets for Arduino. - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * This library is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - * Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with this library; if not, write to the Free Software - * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - -#include "WebSockets.h" -#include "WebSocketsServer.h" - -WebSocketsServer::WebSocketsServer(uint16_t port, String origin, String protocol) { - _port = port; - _origin = origin; - _protocol = protocol; - _runnning = false; - - _server = new WEBSOCKETS_NETWORK_SERVER_CLASS(port); - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) - _server->onClient([](void *s, AsyncClient* c){ - ((WebSocketsServer*)s)->newClient(new AsyncTCPbuffer(c)); - }, this); -#endif - - _cbEvent = NULL; - - _httpHeaderValidationFunc = NULL; - _mandatoryHttpHeaders = NULL; - _mandatoryHttpHeaderCount = 0; - - memset(&_clients[0], 0x00, (sizeof(WSclient_t) * WEBSOCKETS_SERVER_CLIENT_MAX)); -} - - -WebSocketsServer::~WebSocketsServer() { - // disconnect all clients - close(); - - if (_mandatoryHttpHeaders) - delete[] _mandatoryHttpHeaders; - - _mandatoryHttpHeaderCount = 0; -} - -/** - * called to initialize the Websocket server - */ -void WebSocketsServer::begin(void) { - WSclient_t * client; - - // init client storage - for(uint8_t i = 0; i < WEBSOCKETS_SERVER_CLIENT_MAX; i++) { - client = &_clients[i]; - - client->num = i; - client->status = WSC_NOT_CONNECTED; - client->tcp = NULL; -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) - client->isSSL = false; - client->ssl = NULL; -#endif - client->cUrl = ""; - client->cCode = 0; - client->cKey = ""; - client->cProtocol = ""; - client->cVersion = 0; - client->cIsUpgrade = false; - client->cIsWebsocket = false; - - client->base64Authorization = ""; - - client->cWsRXsize = 0; - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) - client->cHttpLine = ""; -#endif - } - -#ifdef ESP8266 - randomSeed(RANDOM_REG32); -#elif defined(ESP32) - #define DR_REG_RNG_BASE 0x3ff75144 - randomSeed(READ_PERI_REG(DR_REG_RNG_BASE)); -#else - // TODO find better seed - randomSeed(millis()); -#endif - - _runnning = true; - _server->begin(); - - DEBUG_WEBSOCKETS("[WS-Server] Server Started.\n"); -} - -void WebSocketsServer::close(void) { - _runnning = false; - disconnect(); - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) - _server->close(); -#elif (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) - _server->end(); -#else - // TODO how to close server? -#endif - -} - -#if (WEBSOCKETS_NETWORK_TYPE != NETWORK_ESP8266_ASYNC) -/** - * called in arduino loop - */ -void WebSocketsServer::loop(void) { - if(_runnning) { - handleNewClients(); - handleClientData(); - } -} -#endif - -/** - * set callback function - * @param cbEvent WebSocketServerEvent - */ -void WebSocketsServer::onEvent(WebSocketServerEvent cbEvent) { - _cbEvent = cbEvent; -} - -/* - * Sets the custom http header validator function - * @param httpHeaderValidationFunc WebSocketServerHttpHeaderValFunc ///< pointer to the custom http header validation function - * @param mandatoryHttpHeaders[] const char* ///< the array of named http headers considered to be mandatory / must be present in order for websocket upgrade to succeed - * @param mandatoryHttpHeaderCount size_t ///< the number of items in the mandatoryHttpHeaders array - */ -void WebSocketsServer::onValidateHttpHeader( - WebSocketServerHttpHeaderValFunc validationFunc, - const char* mandatoryHttpHeaders[], - size_t mandatoryHttpHeaderCount) -{ - _httpHeaderValidationFunc = validationFunc; - - if (_mandatoryHttpHeaders) - delete[] _mandatoryHttpHeaders; - - _mandatoryHttpHeaderCount = mandatoryHttpHeaderCount; - _mandatoryHttpHeaders = new String[_mandatoryHttpHeaderCount]; - - for (size_t i = 0; i < _mandatoryHttpHeaderCount; i++) { - _mandatoryHttpHeaders[i] = mandatoryHttpHeaders[i]; - } -} - -/* - * send text data to client - * @param num uint8_t client id - * @param payload uint8_t * - * @param length size_t - * @param headerToPayload bool (see sendFrame for more details) - * @return true if ok - */ -bool WebSocketsServer::sendTXT(uint8_t num, uint8_t * payload, size_t length, bool headerToPayload) { - if(num >= WEBSOCKETS_SERVER_CLIENT_MAX) { - return false; - } - if(length == 0) { - length = strlen((const char *) payload); - } - WSclient_t * client = &_clients[num]; - if(clientIsConnected(client)) { - return sendFrame(client, WSop_text, payload, length, false, true, headerToPayload); - } - return false; -} - -bool WebSocketsServer::sendTXT(uint8_t num, const uint8_t * payload, size_t length) { - return sendTXT(num, (uint8_t *) payload, length); -} - -bool WebSocketsServer::sendTXT(uint8_t num, char * payload, size_t length, bool headerToPayload) { - return sendTXT(num, (uint8_t *) payload, length, headerToPayload); -} - -bool WebSocketsServer::sendTXT(uint8_t num, const char * payload, size_t length) { - return sendTXT(num, (uint8_t *) payload, length); -} - -bool WebSocketsServer::sendTXT(uint8_t num, String & payload) { - return sendTXT(num, (uint8_t *) payload.c_str(), payload.length()); -} - -/** - * send text data to client all - * @param payload uint8_t * - * @param length size_t - * @param headerToPayload bool (see sendFrame for more details) - * @return true if ok - */ -bool WebSocketsServer::broadcastTXT(uint8_t * payload, size_t length, bool headerToPayload) { - WSclient_t * client; - bool ret = true; - if(length == 0) { - length = strlen((const char *) payload); - } - - for(uint8_t i = 0; i < WEBSOCKETS_SERVER_CLIENT_MAX; i++) { - client = &_clients[i]; - if(clientIsConnected(client)) { - if(!sendFrame(client, WSop_text, payload, length, false, true, headerToPayload)) { - ret = false; - } - } -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) - delay(0); -#endif - } - return ret; -} - -bool WebSocketsServer::broadcastTXT(const uint8_t * payload, size_t length) { - return broadcastTXT((uint8_t *) payload, length); -} - -bool WebSocketsServer::broadcastTXT(char * payload, size_t length, bool headerToPayload) { - return broadcastTXT((uint8_t *) payload, length, headerToPayload); -} - -bool WebSocketsServer::broadcastTXT(const char * payload, size_t length) { - return broadcastTXT((uint8_t *) payload, length); -} - -bool WebSocketsServer::broadcastTXT(String & payload) { - return broadcastTXT((uint8_t *) payload.c_str(), payload.length()); -} - -/** - * send binary data to client - * @param num uint8_t client id - * @param payload uint8_t * - * @param length size_t - * @param headerToPayload bool (see sendFrame for more details) - * @return true if ok - */ -bool WebSocketsServer::sendBIN(uint8_t num, uint8_t * payload, size_t length, bool headerToPayload) { - if(num >= WEBSOCKETS_SERVER_CLIENT_MAX) { - return false; - } - WSclient_t * client = &_clients[num]; - if(clientIsConnected(client)) { - return sendFrame(client, WSop_binary, payload, length, false, true, headerToPayload); - } - return false; -} - -bool WebSocketsServer::sendBIN(uint8_t num, const uint8_t * payload, size_t length) { - return sendBIN(num, (uint8_t *) payload, length); -} - -/** - * send binary data to client all - * @param payload uint8_t * - * @param length size_t - * @param headerToPayload bool (see sendFrame for more details) - * @return true if ok - */ -bool WebSocketsServer::broadcastBIN(uint8_t * payload, size_t length, bool headerToPayload) { - WSclient_t * client; - bool ret = true; - for(uint8_t i = 0; i < WEBSOCKETS_SERVER_CLIENT_MAX; i++) { - client = &_clients[i]; - if(clientIsConnected(client)) { - if(!sendFrame(client, WSop_binary, payload, length, false, true, headerToPayload)) { - ret = false; - } - } -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) - delay(0); -#endif - } - return ret; -} - -bool WebSocketsServer::broadcastBIN(const uint8_t * payload, size_t length) { - return broadcastBIN((uint8_t *) payload, length); -} - - -/** - * sends a WS ping to Client - * @param num uint8_t client id - * @param payload uint8_t * - * @param length size_t - * @return true if ping is send out - */ -bool WebSocketsServer::sendPing(uint8_t num, uint8_t * payload, size_t length) { - if(num >= WEBSOCKETS_SERVER_CLIENT_MAX) { - return false; - } - WSclient_t * client = &_clients[num]; - if(clientIsConnected(client)) { - return sendFrame(client, WSop_ping, payload, length); - } - return false; -} - -bool WebSocketsServer::sendPing(uint8_t num, String & payload) { - return sendPing(num, (uint8_t *) payload.c_str(), payload.length()); -} - -/** - * sends a WS ping to all Client - * @param payload uint8_t * - * @param length size_t - * @return true if ping is send out - */ -bool WebSocketsServer::broadcastPing(uint8_t * payload, size_t length) { - WSclient_t * client; - bool ret = true; - for(uint8_t i = 0; i < WEBSOCKETS_SERVER_CLIENT_MAX; i++) { - client = &_clients[i]; - if(clientIsConnected(client)) { - if(!sendFrame(client, WSop_ping, payload, length)) { - ret = false; - } - } -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) - delay(0); -#endif - } - return ret; -} - -bool WebSocketsServer::broadcastPing(String & payload) { - return broadcastPing((uint8_t *) payload.c_str(), payload.length()); -} - - -/** - * disconnect all clients - */ -void WebSocketsServer::disconnect(void) { - WSclient_t * client; - for(uint8_t i = 0; i < WEBSOCKETS_SERVER_CLIENT_MAX; i++) { - client = &_clients[i]; - if(clientIsConnected(client)) { - WebSockets::clientDisconnect(client, 1000); - } - } -} - -/** - * disconnect one client - * @param num uint8_t client id - */ -void WebSocketsServer::disconnect(uint8_t num) { - if(num >= WEBSOCKETS_SERVER_CLIENT_MAX) { - return; - } - WSclient_t * client = &_clients[num]; - if(clientIsConnected(client)) { - WebSockets::clientDisconnect(client, 1000); - } -} - - -/* - * set the Authorization for the http request - * @param user const char * - * @param password const char * - */ -void WebSocketsServer::setAuthorization(const char * user, const char * password) { - if(user && password) { - String auth = user; - auth += ":"; - auth += password; - _base64Authorization = base64_encode((uint8_t *)auth.c_str(), auth.length()); - } -} - -/** - * set the Authorizatio for the http request - * @param auth const char * base64 - */ -void WebSocketsServer::setAuthorization(const char * auth) { - if(auth) { - _base64Authorization = auth; - } -} - -/** - * count the connected clients (optional ping them) - * @param ping bool ping the connected clients - */ -int WebSocketsServer::connectedClients(bool ping) { - WSclient_t * client; - int count = 0; - for(uint8_t i = 0; i < WEBSOCKETS_SERVER_CLIENT_MAX; i++) { - client = &_clients[i]; - if(client->status == WSC_CONNECTED) { - if(ping != true || sendPing(i)) { - count++; - } - } - } - return count; -} - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) -/** - * get an IP for a client - * @param num uint8_t client id - * @return IPAddress - */ -IPAddress WebSocketsServer::remoteIP(uint8_t num) { - if(num < WEBSOCKETS_SERVER_CLIENT_MAX) { - WSclient_t * client = &_clients[num]; - if(clientIsConnected(client)) { - return client->tcp->remoteIP(); - } - } - - return IPAddress(); -} -#endif - -//################################################################################# -//################################################################################# -//################################################################################# - -/** - * handle new client connection - * @param client - */ -bool WebSocketsServer::newClient(WEBSOCKETS_NETWORK_CLASS * TCPclient) { - WSclient_t * client; - // search free list entry for client - for(uint8_t i = 0; i < WEBSOCKETS_SERVER_CLIENT_MAX; i++) { - client = &_clients[i]; - - // state is not connected or tcp connection is lost - if(!clientIsConnected(client)) { - - client->tcp = TCPclient; - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) - client->isSSL = false; - client->tcp->setNoDelay(true); -#endif -#if (WEBSOCKETS_NETWORK_TYPE != NETWORK_ESP8266_ASYNC) - // set Timeout for readBytesUntil and readStringUntil - client->tcp->setTimeout(WEBSOCKETS_TCP_TIMEOUT); -#endif - client->status = WSC_HEADER; -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) - IPAddress ip = client->tcp->remoteIP(); - DEBUG_WEBSOCKETS("[WS-Server][%d] new client from %d.%d.%d.%d\n", client->num, ip[0], ip[1], ip[2], ip[3]); -#else - DEBUG_WEBSOCKETS("[WS-Server][%d] new client\n", client->num); -#endif - - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) - client->tcp->onDisconnect(std::bind([](WebSocketsServer * server, AsyncTCPbuffer * obj, WSclient_t * client) -> bool { - DEBUG_WEBSOCKETS("[WS-Server][%d] Disconnect client\n", client->num); - - AsyncTCPbuffer ** sl = &server->_clients[client->num].tcp; - if(*sl == obj) { - client->status = WSC_NOT_CONNECTED; - *sl = NULL; - } - return true; - }, this, std::placeholders::_1, client)); - - - client->tcp->readStringUntil('\n', &(client->cHttpLine), std::bind(&WebSocketsServer::handleHeader, this, client, &(client->cHttpLine))); -#endif - - return true; - break; - } - } - return false; -} - -/** - * - * @param client WSclient_t * ptr to the client struct - * @param opcode WSopcode_t - * @param payload uint8_t * - * @param length size_t - */ -void WebSocketsServer::messageReceived(WSclient_t * client, WSopcode_t opcode, uint8_t * payload, size_t length, bool fin) { - WStype_t type = WStype_ERROR; - - switch(opcode) { - case WSop_text: - type = fin ? WStype_TEXT : WStype_FRAGMENT_TEXT_START; - break; - case WSop_binary: - type = fin ? WStype_BIN : WStype_FRAGMENT_BIN_START; - break; - case WSop_continuation: - type = fin ? WStype_FRAGMENT_FIN : WStype_FRAGMENT; - break; - case WSop_close: - case WSop_ping: - case WSop_pong: - default: - break; - } - - runCbEvent(client->num, type, payload, length); - -} - -/** - * Disconnect an client - * @param client WSclient_t * ptr to the client struct - */ -void WebSocketsServer::clientDisconnect(WSclient_t * client) { - - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) - if(client->isSSL && client->ssl) { - if(client->ssl->connected()) { - client->ssl->flush(); - client->ssl->stop(); - } - delete client->ssl; - client->ssl = NULL; - client->tcp = NULL; - } -#endif - - if(client->tcp) { - if(client->tcp->connected()) { -#if (WEBSOCKETS_NETWORK_TYPE != NETWORK_ESP8266_ASYNC) - client->tcp->flush(); -#endif - client->tcp->stop(); - } -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) - client->status = WSC_NOT_CONNECTED; -#else - delete client->tcp; -#endif - client->tcp = NULL; - } - - client->cUrl = ""; - client->cKey = ""; - client->cProtocol = ""; - client->cVersion = 0; - client->cIsUpgrade = false; - client->cIsWebsocket = false; - - client->cWsRXsize = 0; - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) - client->cHttpLine = ""; -#endif - - client->status = WSC_NOT_CONNECTED; - - DEBUG_WEBSOCKETS("[WS-Server][%d] client disconnected.\n", client->num); - - runCbEvent(client->num, WStype_DISCONNECTED, NULL, 0); - -} - -/** - * get client state - * @param client WSclient_t * ptr to the client struct - * @return true = connected - */ -bool WebSocketsServer::clientIsConnected(WSclient_t * client) { - - if(!client->tcp) { - return false; - } - - if(client->tcp->connected()) { - if(client->status != WSC_NOT_CONNECTED) { - return true; - } - } else { - // client lost - if(client->status != WSC_NOT_CONNECTED) { - DEBUG_WEBSOCKETS("[WS-Server][%d] client connection lost.\n", client->num); - // do cleanup - clientDisconnect(client); - } - } - - if(client->tcp) { - // do cleanup - DEBUG_WEBSOCKETS("[WS-Server][%d] client list cleanup.\n", client->num); - clientDisconnect(client); - } - - return false; -} -#if (WEBSOCKETS_NETWORK_TYPE != NETWORK_ESP8266_ASYNC) -/** - * Handle incoming Connection Request - */ -void WebSocketsServer::handleNewClients(void) { - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) - while(_server->hasClient()) { -#endif - bool ok = false; - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) - // store new connection - WEBSOCKETS_NETWORK_CLASS * tcpClient = new WEBSOCKETS_NETWORK_CLASS(_server->available()); -#else - WEBSOCKETS_NETWORK_CLASS * tcpClient = new WEBSOCKETS_NETWORK_CLASS(_server->available()); -#endif - - if(!tcpClient) { - DEBUG_WEBSOCKETS("[WS-Client] creating Network class failed!"); - return; - } - - ok = newClient(tcpClient); - - if(!ok) { - // no free space to handle client -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) - IPAddress ip = tcpClient->remoteIP(); - DEBUG_WEBSOCKETS("[WS-Server] no free space new client from %d.%d.%d.%d\n", ip[0], ip[1], ip[2], ip[3]); -#else - DEBUG_WEBSOCKETS("[WS-Server] no free space new client\n"); -#endif - tcpClient->stop(); - } - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) - delay(0); - } -#endif - -} - - -/** - * Handel incomming data from Client - */ -void WebSocketsServer::handleClientData(void) { - - WSclient_t * client; - for(uint8_t i = 0; i < WEBSOCKETS_SERVER_CLIENT_MAX; i++) { - client = &_clients[i]; - if(clientIsConnected(client)) { - int len = client->tcp->available(); - if(len > 0) { - //DEBUG_WEBSOCKETS("[WS-Server][%d][handleClientData] len: %d\n", client->num, len); - switch(client->status) { - case WSC_HEADER: - { - String headerLine = client->tcp->readStringUntil('\n'); - handleHeader(client, &headerLine); - } - break; - case WSC_CONNECTED: - WebSockets::handleWebsocket(client); - break; - default: - WebSockets::clientDisconnect(client, 1002); - break; - } - } - } -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) - delay(0); -#endif - } -} -#endif - -/* - * returns an indicator whether the given named header exists in the configured _mandatoryHttpHeaders collection - * @param headerName String ///< the name of the header being checked - */ -bool WebSocketsServer::hasMandatoryHeader(String headerName) { - for (size_t i = 0; i < _mandatoryHttpHeaderCount; i++) { - if (_mandatoryHttpHeaders[i].equalsIgnoreCase(headerName)) - return true; - } - return false; -} - - -/** - * handles http header reading for WebSocket upgrade - * @param client WSclient_t * ///< pointer to the client struct - * @param headerLine String ///< the header being read / processed - */ -void WebSocketsServer::handleHeader(WSclient_t * client, String * headerLine) { - - static const char * NEW_LINE = "\r\n"; - - headerLine->trim(); // remove \r - - if(headerLine->length() > 0) { - DEBUG_WEBSOCKETS("[WS-Server][%d][handleHeader] RX: %s\n", client->num, headerLine->c_str()); - - // websocket requests always start with GET see rfc6455 - if(headerLine->startsWith("GET ")) { - - // cut URL out - client->cUrl = headerLine->substring(4, headerLine->indexOf(' ', 4)); - - //reset non-websocket http header validation state for this client - client->cHttpHeadersValid = true; - client->cMandatoryHeadersCount = 0; - - } else if(headerLine->indexOf(':')) { - String headerName = headerLine->substring(0, headerLine->indexOf(':')); - String headerValue = headerLine->substring(headerLine->indexOf(':') + 1); - - // remove space in the beginning (RFC2616) - if(headerValue[0] == ' ') { - headerValue.remove(0, 1); - } - - if(headerName.equalsIgnoreCase(WEBSOCKETS_STRING("Connection"))) { - headerValue.toLowerCase(); - if(headerValue.indexOf(WEBSOCKETS_STRING("upgrade")) >= 0) { - client->cIsUpgrade = true; - } - } else if(headerName.equalsIgnoreCase(WEBSOCKETS_STRING("Upgrade"))) { - if(headerValue.equalsIgnoreCase(WEBSOCKETS_STRING("websocket"))) { - client->cIsWebsocket = true; - } - } else if(headerName.equalsIgnoreCase(WEBSOCKETS_STRING("Sec-WebSocket-Version"))) { - client->cVersion = headerValue.toInt(); - } else if(headerName.equalsIgnoreCase(WEBSOCKETS_STRING("Sec-WebSocket-Key"))) { - client->cKey = headerValue; - client->cKey.trim(); // see rfc6455 - } else if(headerName.equalsIgnoreCase(WEBSOCKETS_STRING("Sec-WebSocket-Protocol"))) { - client->cProtocol = headerValue; - } else if(headerName.equalsIgnoreCase(WEBSOCKETS_STRING("Sec-WebSocket-Extensions"))) { - client->cExtensions = headerValue; - } else if(headerName.equalsIgnoreCase(WEBSOCKETS_STRING("Authorization"))) { - client->base64Authorization = headerValue; - } else { - client->cHttpHeadersValid &= execHttpHeaderValidation(headerName, headerValue); - if(_mandatoryHttpHeaderCount > 0 && hasMandatoryHeader(headerName)) { - client->cMandatoryHeadersCount++; - } - } - - } else { - DEBUG_WEBSOCKETS("[WS-Client][handleHeader] Header error (%s)\n", headerLine->c_str()); - } - - (*headerLine) = ""; -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) - client->tcp->readStringUntil('\n', &(client->cHttpLine), std::bind(&WebSocketsServer::handleHeader, this, client, &(client->cHttpLine))); -#endif - } else { - - DEBUG_WEBSOCKETS("[WS-Server][%d][handleHeader] Header read fin.\n", client->num); - DEBUG_WEBSOCKETS("[WS-Server][%d][handleHeader] - cURL: %s\n", client->num, client->cUrl.c_str()); - DEBUG_WEBSOCKETS("[WS-Server][%d][handleHeader] - cIsUpgrade: %d\n", client->num, client->cIsUpgrade); - DEBUG_WEBSOCKETS("[WS-Server][%d][handleHeader] - cIsWebsocket: %d\n", client->num, client->cIsWebsocket); - DEBUG_WEBSOCKETS("[WS-Server][%d][handleHeader] - cKey: %s\n", client->num, client->cKey.c_str()); - DEBUG_WEBSOCKETS("[WS-Server][%d][handleHeader] - cProtocol: %s\n", client->num, client->cProtocol.c_str()); - DEBUG_WEBSOCKETS("[WS-Server][%d][handleHeader] - cExtensions: %s\n", client->num, client->cExtensions.c_str()); - DEBUG_WEBSOCKETS("[WS-Server][%d][handleHeader] - cVersion: %d\n", client->num, client->cVersion); - DEBUG_WEBSOCKETS("[WS-Server][%d][handleHeader] - base64Authorization: %s\n", client->num, client->base64Authorization.c_str()); - DEBUG_WEBSOCKETS("[WS-Server][%d][handleHeader] - cHttpHeadersValid: %d\n", client->num, client->cHttpHeadersValid); - DEBUG_WEBSOCKETS("[WS-Server][%d][handleHeader] - cMandatoryHeadersCount: %d\n", client->num, client->cMandatoryHeadersCount); - - bool ok = (client->cIsUpgrade && client->cIsWebsocket); - - if(ok) { - if(client->cUrl.length() == 0) { - ok = false; - } - if(client->cKey.length() == 0) { - ok = false; - } - if(client->cVersion != 13) { - ok = false; - } - if(!client->cHttpHeadersValid) { - ok = false; - } - if (client->cMandatoryHeadersCount != _mandatoryHttpHeaderCount) { - ok = false; - } - } - - if(_base64Authorization.length() > 0) { - String auth = WEBSOCKETS_STRING("Basic "); - auth += _base64Authorization; - if(auth != client->base64Authorization) { - DEBUG_WEBSOCKETS("[WS-Server][%d][handleHeader] HTTP Authorization failed!\n", client->num); - handleAuthorizationFailed(client); - return; - } - } - - if(ok) { - - DEBUG_WEBSOCKETS("[WS-Server][%d][handleHeader] Websocket connection incoming.\n", client->num); - - // generate Sec-WebSocket-Accept key - String sKey = acceptKey(client->cKey); - - DEBUG_WEBSOCKETS("[WS-Server][%d][handleHeader] - sKey: %s\n", client->num, sKey.c_str()); - - client->status = WSC_CONNECTED; - - String handshake = WEBSOCKETS_STRING("HTTP/1.1 101 Switching Protocols\r\n" - "Server: arduino-WebSocketsServer\r\n" - "Upgrade: websocket\r\n" - "Connection: Upgrade\r\n" - "Sec-WebSocket-Version: 13\r\n" - "Sec-WebSocket-Accept: "); - handshake += sKey + NEW_LINE; - - if(_origin.length() > 0) { - handshake += WEBSOCKETS_STRING("Access-Control-Allow-Origin: "); - handshake +=_origin + NEW_LINE; - } - - if(client->cProtocol.length() > 0) { - handshake += WEBSOCKETS_STRING("Sec-WebSocket-Protocol: "); - handshake +=_protocol + NEW_LINE; - } - - // header end - handshake += NEW_LINE; - - DEBUG_WEBSOCKETS("[WS-Server][%d][handleHeader] handshake %s", client->num, (uint8_t*)handshake.c_str()); - - write(client, (uint8_t*)handshake.c_str(), handshake.length()); - - headerDone(client); - - // send ping - WebSockets::sendFrame(client, WSop_ping); - - runCbEvent(client->num, WStype_CONNECTED, (uint8_t *) client->cUrl.c_str(), client->cUrl.length()); - - } else { - handleNonWebsocketConnection(client); - } - } -} - - - diff --git a/libraries/arduinoWebSockets/src/WebSocketsServer.h b/libraries/arduinoWebSockets/src/WebSocketsServer.h deleted file mode 100644 index db945a6ff..000000000 --- a/libraries/arduinoWebSockets/src/WebSocketsServer.h +++ /dev/null @@ -1,212 +0,0 @@ -/** - * @file WebSocketsServer.h - * @date 20.05.2015 - * @author Markus Sattler - * - * Copyright (c) 2015 Markus Sattler. All rights reserved. - * This file is part of the WebSockets for Arduino. - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * This library is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - * Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with this library; if not, write to the Free Software - * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - -#ifndef WEBSOCKETSSERVER_H_ -#define WEBSOCKETSSERVER_H_ - -#include "WebSockets.h" - -#ifndef WEBSOCKETS_SERVER_CLIENT_MAX -#define WEBSOCKETS_SERVER_CLIENT_MAX (5) -#endif - - - - -class WebSocketsServer: protected WebSockets { -public: - -#ifdef __AVR__ - typedef void (*WebSocketServerEvent)(uint8_t num, WStype_t type, uint8_t * payload, size_t length); - typedef bool (*WebSocketServerHttpHeaderValFunc)(String headerName, String headerValue); -#else - typedef std::function WebSocketServerEvent; - typedef std::function WebSocketServerHttpHeaderValFunc; -#endif - - WebSocketsServer(uint16_t port, String origin = "", String protocol = "arduino"); - virtual ~WebSocketsServer(void); - - void begin(void); - void close(void); - -#if (WEBSOCKETS_NETWORK_TYPE != NETWORK_ESP8266_ASYNC) - void loop(void); -#else - // Async interface not need a loop call - void loop(void) __attribute__ ((deprecated)) {} -#endif - - void onEvent(WebSocketServerEvent cbEvent); - void onValidateHttpHeader( - WebSocketServerHttpHeaderValFunc validationFunc, - const char* mandatoryHttpHeaders[], - size_t mandatoryHttpHeaderCount); - - - bool sendTXT(uint8_t num, uint8_t * payload, size_t length = 0, bool headerToPayload = false); - bool sendTXT(uint8_t num, const uint8_t * payload, size_t length = 0); - bool sendTXT(uint8_t num, char * payload, size_t length = 0, bool headerToPayload = false); - bool sendTXT(uint8_t num, const char * payload, size_t length = 0); - bool sendTXT(uint8_t num, String & payload); - - bool broadcastTXT(uint8_t * payload, size_t length = 0, bool headerToPayload = false); - bool broadcastTXT(const uint8_t * payload, size_t length = 0); - bool broadcastTXT(char * payload, size_t length = 0, bool headerToPayload = false); - bool broadcastTXT(const char * payload, size_t length = 0); - bool broadcastTXT(String & payload); - - bool sendBIN(uint8_t num, uint8_t * payload, size_t length, bool headerToPayload = false); - bool sendBIN(uint8_t num, const uint8_t * payload, size_t length); - - bool broadcastBIN(uint8_t * payload, size_t length, bool headerToPayload = false); - bool broadcastBIN(const uint8_t * payload, size_t length); - - bool sendPing(uint8_t num, uint8_t * payload = NULL, size_t length = 0); - bool sendPing(uint8_t num, String & payload); - - bool broadcastPing(uint8_t * payload = NULL, size_t length = 0); - bool broadcastPing(String & payload); - - void disconnect(void); - void disconnect(uint8_t num); - - void setAuthorization(const char * user, const char * password); - void setAuthorization(const char * auth); - - int connectedClients(bool ping = false); - -#if (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP8266_ASYNC) || (WEBSOCKETS_NETWORK_TYPE == NETWORK_ESP32) - IPAddress remoteIP(uint8_t num); -#endif - -protected: - uint16_t _port; - String _origin; - String _protocol; - String _base64Authorization; ///< Base64 encoded Auth request - String * _mandatoryHttpHeaders; - size_t _mandatoryHttpHeaderCount; - - WEBSOCKETS_NETWORK_SERVER_CLASS * _server; - - WSclient_t _clients[WEBSOCKETS_SERVER_CLIENT_MAX]; - - WebSocketServerEvent _cbEvent; - WebSocketServerHttpHeaderValFunc _httpHeaderValidationFunc; - - bool _runnning; - - bool newClient(WEBSOCKETS_NETWORK_CLASS * TCPclient); - - void messageReceived(WSclient_t * client, WSopcode_t opcode, uint8_t * payload, size_t length, bool fin); - - void clientDisconnect(WSclient_t * client); - bool clientIsConnected(WSclient_t * client); - -#if (WEBSOCKETS_NETWORK_TYPE != NETWORK_ESP8266_ASYNC) - void handleNewClients(void); - void handleClientData(void); -#endif - - void handleHeader(WSclient_t * client, String * headerLine); - - /** - * called if a non Websocket connection is coming in. - * Note: can be override - * @param client WSclient_t * ptr to the client struct - */ - virtual void handleNonWebsocketConnection(WSclient_t * client) { - DEBUG_WEBSOCKETS("[WS-Server][%d][handleHeader] no Websocket connection close.\n", client->num); - client->tcp->write("HTTP/1.1 400 Bad Request\r\n" - "Server: arduino-WebSocket-Server\r\n" - "Content-Type: text/plain\r\n" - "Content-Length: 32\r\n" - "Connection: close\r\n" - "Sec-WebSocket-Version: 13\r\n" - "\r\n" - "This is a Websocket server only!"); - clientDisconnect(client); - } - - /** - * called if a non Authorization connection is coming in. - * Note: can be override - * @param client WSclient_t * ptr to the client struct - */ - virtual void handleAuthorizationFailed(WSclient_t *client) { - client->tcp->write("HTTP/1.1 401 Unauthorized\r\n" - "Server: arduino-WebSocket-Server\r\n" - "Content-Type: text/plain\r\n" - "Content-Length: 45\r\n" - "Connection: close\r\n" - "Sec-WebSocket-Version: 13\r\n" - "WWW-Authenticate: Basic realm=\"WebSocket Server\"" - "\r\n" - "This Websocket server requires Authorization!"); - clientDisconnect(client); - } - - /** - * called for sending a Event to the app - * @param num uint8_t - * @param type WStype_t - * @param payload uint8_t * - * @param length size_t - */ - virtual void runCbEvent(uint8_t num, WStype_t type, uint8_t * payload, size_t length) { - if(_cbEvent) { - _cbEvent(num, type, payload, length); - } - } - - /* - * Called at client socket connect handshake negotiation time for each http header that is not - * a websocket specific http header (not Connection, Upgrade, Sec-WebSocket-*) - * If the custom httpHeaderValidationFunc returns false for any headerName / headerValue passed, the - * socket negotiation is considered invalid and the upgrade to websockets request is denied / rejected - * This mechanism can be used to enable custom authentication schemes e.g. test the value - * of a session cookie to determine if a user is logged on / authenticated - */ - virtual bool execHttpHeaderValidation(String headerName, String headerValue) { - if(_httpHeaderValidationFunc) { - //return the value of the custom http header validation function - return _httpHeaderValidationFunc(headerName, headerValue); - } - //no custom http header validation so just assume all is good - return true; - } - -private: - /* - * returns an indicator whether the given named header exists in the configured _mandatoryHttpHeaders collection - * @param headerName String ///< the name of the header being checked - */ - bool hasMandatoryHeader(String headerName); - -}; - - - -#endif /* WEBSOCKETSSERVER_H_ */ diff --git a/libraries/arduinoWebSockets/src/libb64/AUTHORS b/libraries/arduinoWebSockets/src/libb64/AUTHORS deleted file mode 100644 index af6873756..000000000 --- a/libraries/arduinoWebSockets/src/libb64/AUTHORS +++ /dev/null @@ -1,7 +0,0 @@ -libb64: Base64 Encoding/Decoding Routines -====================================== - -Authors: -------- - -Chris Venter chris.venter@gmail.com http://rocketpod.blogspot.com diff --git a/libraries/arduinoWebSockets/src/libb64/LICENSE b/libraries/arduinoWebSockets/src/libb64/LICENSE deleted file mode 100644 index a6b56069e..000000000 --- a/libraries/arduinoWebSockets/src/libb64/LICENSE +++ /dev/null @@ -1,29 +0,0 @@ -Copyright-Only Dedication (based on United States law) -or Public Domain Certification - -The person or persons who have associated work with this document (the -"Dedicator" or "Certifier") hereby either (a) certifies that, to the best of -his knowledge, the work of authorship identified is in the public domain of the -country from which the work is published, or (b) hereby dedicates whatever -copyright the dedicators holds in the work of authorship identified below (the -"Work") to the public domain. A certifier, moreover, dedicates any copyright -interest he may have in the associated work, and for these purposes, is -described as a "dedicator" below. - -A certifier has taken reasonable steps to verify the copyright status of this -work. Certifier recognizes that his good faith efforts may not shield him from -liability if in fact the work certified is not in the public domain. - -Dedicator makes this dedication for the benefit of the public at large and to -the detriment of the Dedicator's heirs and successors. Dedicator intends this -dedication to be an overt act of relinquishment in perpetuity of all present -and future rights under copyright law, whether vested or contingent, in the -Work. Dedicator understands that such relinquishment of all rights includes -the relinquishment of all rights to enforce (by lawsuit or otherwise) those -copyrights in the Work. - -Dedicator recognizes that, once placed in the public domain, the Work may be -freely reproduced, distributed, transmitted, used, modified, built upon, or -otherwise exploited by anyone for any purpose, commercial or non-commercial, -and in any way, including by methods that have not yet been invented or -conceived. \ No newline at end of file diff --git a/libraries/arduinoWebSockets/src/libb64/cdecode.c b/libraries/arduinoWebSockets/src/libb64/cdecode.c deleted file mode 100644 index e135da249..000000000 --- a/libraries/arduinoWebSockets/src/libb64/cdecode.c +++ /dev/null @@ -1,98 +0,0 @@ -/* -cdecoder.c - c source to a base64 decoding algorithm implementation - -This is part of the libb64 project, and has been placed in the public domain. -For details, see http://sourceforge.net/projects/libb64 -*/ - -#ifdef ESP8266 -#include -#endif - -#if defined(ESP32) -#define CORE_HAS_LIBB64 -#endif - -#ifndef CORE_HAS_LIBB64 -#include "cdecode_inc.h" - -int base64_decode_value(char value_in) -{ - static const char decoding[] = {62,-1,-1,-1,63,52,53,54,55,56,57,58,59,60,61,-1,-1,-1,-2,-1,-1,-1,0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,-1,-1,-1,-1,-1,-1,26,27,28,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51}; - static const char decoding_size = sizeof(decoding); - value_in -= 43; - if (value_in < 0 || value_in > decoding_size) return -1; - return decoding[(int)value_in]; -} - -void base64_init_decodestate(base64_decodestate* state_in) -{ - state_in->step = step_a; - state_in->plainchar = 0; -} - -int base64_decode_block(const char* code_in, const int length_in, char* plaintext_out, base64_decodestate* state_in) -{ - const char* codechar = code_in; - char* plainchar = plaintext_out; - char fragment; - - *plainchar = state_in->plainchar; - - switch (state_in->step) - { - while (1) - { - case step_a: - do { - if (codechar == code_in+length_in) - { - state_in->step = step_a; - state_in->plainchar = *plainchar; - return plainchar - plaintext_out; - } - fragment = (char)base64_decode_value(*codechar++); - } while (fragment < 0); - *plainchar = (fragment & 0x03f) << 2; - case step_b: - do { - if (codechar == code_in+length_in) - { - state_in->step = step_b; - state_in->plainchar = *plainchar; - return plainchar - plaintext_out; - } - fragment = (char)base64_decode_value(*codechar++); - } while (fragment < 0); - *plainchar++ |= (fragment & 0x030) >> 4; - *plainchar = (fragment & 0x00f) << 4; - case step_c: - do { - if (codechar == code_in+length_in) - { - state_in->step = step_c; - state_in->plainchar = *plainchar; - return plainchar - plaintext_out; - } - fragment = (char)base64_decode_value(*codechar++); - } while (fragment < 0); - *plainchar++ |= (fragment & 0x03c) >> 2; - *plainchar = (fragment & 0x003) << 6; - case step_d: - do { - if (codechar == code_in+length_in) - { - state_in->step = step_d; - state_in->plainchar = *plainchar; - return plainchar - plaintext_out; - } - fragment = (char)base64_decode_value(*codechar++); - } while (fragment < 0); - *plainchar++ |= (fragment & 0x03f); - } - } - /* control should not reach here */ - return plainchar - plaintext_out; -} - -#endif diff --git a/libraries/arduinoWebSockets/src/libb64/cdecode_inc.h b/libraries/arduinoWebSockets/src/libb64/cdecode_inc.h deleted file mode 100644 index d0d7f489d..000000000 --- a/libraries/arduinoWebSockets/src/libb64/cdecode_inc.h +++ /dev/null @@ -1,28 +0,0 @@ -/* -cdecode.h - c header for a base64 decoding algorithm - -This is part of the libb64 project, and has been placed in the public domain. -For details, see http://sourceforge.net/projects/libb64 -*/ - -#ifndef BASE64_CDECODE_H -#define BASE64_CDECODE_H - -typedef enum -{ - step_a, step_b, step_c, step_d -} base64_decodestep; - -typedef struct -{ - base64_decodestep step; - char plainchar; -} base64_decodestate; - -void base64_init_decodestate(base64_decodestate* state_in); - -int base64_decode_value(char value_in); - -int base64_decode_block(const char* code_in, const int length_in, char* plaintext_out, base64_decodestate* state_in); - -#endif /* BASE64_CDECODE_H */ diff --git a/libraries/arduinoWebSockets/src/libb64/cencode.c b/libraries/arduinoWebSockets/src/libb64/cencode.c deleted file mode 100644 index afe1463c6..000000000 --- a/libraries/arduinoWebSockets/src/libb64/cencode.c +++ /dev/null @@ -1,119 +0,0 @@ -/* -cencoder.c - c source to a base64 encoding algorithm implementation - -This is part of the libb64 project, and has been placed in the public domain. -For details, see http://sourceforge.net/projects/libb64 -*/ - -#ifdef ESP8266 -#include -#endif - -#if defined(ESP32) -#define CORE_HAS_LIBB64 -#endif - -#ifndef CORE_HAS_LIBB64 -#include "cencode_inc.h" - -const int CHARS_PER_LINE = 72; - -void base64_init_encodestate(base64_encodestate* state_in) -{ - state_in->step = step_A; - state_in->result = 0; - state_in->stepcount = 0; -} - -char base64_encode_value(char value_in) -{ - static const char* encoding = "ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz0123456789+/"; - if (value_in > 63) return '='; - return encoding[(int)value_in]; -} - -int base64_encode_block(const char* plaintext_in, int length_in, char* code_out, base64_encodestate* state_in) -{ - const char* plainchar = plaintext_in; - const char* const plaintextend = plaintext_in + length_in; - char* codechar = code_out; - char result; - char fragment; - - result = state_in->result; - - switch (state_in->step) - { - while (1) - { - case step_A: - if (plainchar == plaintextend) - { - state_in->result = result; - state_in->step = step_A; - return codechar - code_out; - } - fragment = *plainchar++; - result = (fragment & 0x0fc) >> 2; - *codechar++ = base64_encode_value(result); - result = (fragment & 0x003) << 4; - case step_B: - if (plainchar == plaintextend) - { - state_in->result = result; - state_in->step = step_B; - return codechar - code_out; - } - fragment = *plainchar++; - result |= (fragment & 0x0f0) >> 4; - *codechar++ = base64_encode_value(result); - result = (fragment & 0x00f) << 2; - case step_C: - if (plainchar == plaintextend) - { - state_in->result = result; - state_in->step = step_C; - return codechar - code_out; - } - fragment = *plainchar++; - result |= (fragment & 0x0c0) >> 6; - *codechar++ = base64_encode_value(result); - result = (fragment & 0x03f) >> 0; - *codechar++ = base64_encode_value(result); - - ++(state_in->stepcount); - if (state_in->stepcount == CHARS_PER_LINE/4) - { - *codechar++ = '\n'; - state_in->stepcount = 0; - } - } - } - /* control should not reach here */ - return codechar - code_out; -} - -int base64_encode_blockend(char* code_out, base64_encodestate* state_in) -{ - char* codechar = code_out; - - switch (state_in->step) - { - case step_B: - *codechar++ = base64_encode_value(state_in->result); - *codechar++ = '='; - *codechar++ = '='; - break; - case step_C: - *codechar++ = base64_encode_value(state_in->result); - *codechar++ = '='; - break; - case step_A: - break; - } - *codechar++ = 0x00; - - return codechar - code_out; -} - -#endif diff --git a/libraries/arduinoWebSockets/src/libb64/cencode_inc.h b/libraries/arduinoWebSockets/src/libb64/cencode_inc.h deleted file mode 100644 index c1e3464af..000000000 --- a/libraries/arduinoWebSockets/src/libb64/cencode_inc.h +++ /dev/null @@ -1,31 +0,0 @@ -/* -cencode.h - c header for a base64 encoding algorithm - -This is part of the libb64 project, and has been placed in the public domain. -For details, see http://sourceforge.net/projects/libb64 -*/ - -#ifndef BASE64_CENCODE_H -#define BASE64_CENCODE_H - -typedef enum -{ - step_A, step_B, step_C -} base64_encodestep; - -typedef struct -{ - base64_encodestep step; - char result; - int stepcount; -} base64_encodestate; - -void base64_init_encodestate(base64_encodestate* state_in); - -char base64_encode_value(char value_in); - -int base64_encode_block(const char* plaintext_in, int length_in, char* code_out, base64_encodestate* state_in); - -int base64_encode_blockend(char* code_out, base64_encodestate* state_in); - -#endif /* BASE64_CENCODE_H */ diff --git a/libraries/arduinoWebSockets/src/libsha1/libsha1.c b/libraries/arduinoWebSockets/src/libsha1/libsha1.c deleted file mode 100644 index 48f4df5a3..000000000 --- a/libraries/arduinoWebSockets/src/libsha1/libsha1.c +++ /dev/null @@ -1,202 +0,0 @@ -/* from valgrind tests */ - -/* ================ sha1.c ================ */ -/* -SHA-1 in C -By Steve Reid -100% Public Domain - -Test Vectors (from FIPS PUB 180-1) -"abc" - A9993E36 4706816A BA3E2571 7850C26C 9CD0D89D -"abcdbcdecdefdefgefghfghighijhijkijkljklmklmnlmnomnopnopq" - 84983E44 1C3BD26E BAAE4AA1 F95129E5 E54670F1 -A million repetitions of "a" - 34AA973C D4C4DAA4 F61EEB2B DBAD2731 6534016F -*/ - -/* #define LITTLE_ENDIAN * This should be #define'd already, if true. */ -/* #define SHA1HANDSOFF * Copies data before messing with it. */ - -#if !defined(ESP8266) && !defined(ESP32) - -#define SHA1HANDSOFF - -#include -#include -#include - -#include "libsha1.h" - - -#define rol(value, bits) (((value) << (bits)) | ((value) >> (32 - (bits)))) - -/* blk0() and blk() perform the initial expand. */ -/* I got the idea of expanding during the round function from SSLeay */ -#if BYTE_ORDER == LITTLE_ENDIAN -#define blk0(i) (block->l[i] = (rol(block->l[i],24)&0xFF00FF00) \ - |(rol(block->l[i],8)&0x00FF00FF)) -#elif BYTE_ORDER == BIG_ENDIAN -#define blk0(i) block->l[i] -#else -#error "Endianness not defined!" -#endif -#define blk(i) (block->l[i&15] = rol(block->l[(i+13)&15]^block->l[(i+8)&15] \ - ^block->l[(i+2)&15]^block->l[i&15],1)) - -/* (R0+R1), R2, R3, R4 are the different operations used in SHA1 */ -#define R0(v,w,x,y,z,i) z+=((w&(x^y))^y)+blk0(i)+0x5A827999+rol(v,5);w=rol(w,30); -#define R1(v,w,x,y,z,i) z+=((w&(x^y))^y)+blk(i)+0x5A827999+rol(v,5);w=rol(w,30); -#define R2(v,w,x,y,z,i) z+=(w^x^y)+blk(i)+0x6ED9EBA1+rol(v,5);w=rol(w,30); -#define R3(v,w,x,y,z,i) z+=(((w|x)&y)|(w&x))+blk(i)+0x8F1BBCDC+rol(v,5);w=rol(w,30); -#define R4(v,w,x,y,z,i) z+=(w^x^y)+blk(i)+0xCA62C1D6+rol(v,5);w=rol(w,30); - - -/* Hash a single 512-bit block. This is the core of the algorithm. */ - -void SHA1Transform(uint32_t state[5], const unsigned char buffer[64]) -{ - uint32_t a, b, c, d, e; - typedef union { - unsigned char c[64]; - uint32_t l[16]; - } CHAR64LONG16; -#ifdef SHA1HANDSOFF - CHAR64LONG16 block[1]; /* use array to appear as a pointer */ - memcpy(block, buffer, 64); -#else - /* The following had better never be used because it causes the - * pointer-to-const buffer to be cast into a pointer to non-const. - * And the result is written through. I threw a "const" in, hoping - * this will cause a diagnostic. - */ - CHAR64LONG16* block = (const CHAR64LONG16*)buffer; -#endif - /* Copy context->state[] to working vars */ - a = state[0]; - b = state[1]; - c = state[2]; - d = state[3]; - e = state[4]; - /* 4 rounds of 20 operations each. Loop unrolled. */ - R0(a,b,c,d,e, 0); R0(e,a,b,c,d, 1); R0(d,e,a,b,c, 2); R0(c,d,e,a,b, 3); - R0(b,c,d,e,a, 4); R0(a,b,c,d,e, 5); R0(e,a,b,c,d, 6); R0(d,e,a,b,c, 7); - R0(c,d,e,a,b, 8); R0(b,c,d,e,a, 9); R0(a,b,c,d,e,10); R0(e,a,b,c,d,11); - R0(d,e,a,b,c,12); R0(c,d,e,a,b,13); R0(b,c,d,e,a,14); R0(a,b,c,d,e,15); - R1(e,a,b,c,d,16); R1(d,e,a,b,c,17); R1(c,d,e,a,b,18); R1(b,c,d,e,a,19); - R2(a,b,c,d,e,20); R2(e,a,b,c,d,21); R2(d,e,a,b,c,22); R2(c,d,e,a,b,23); - R2(b,c,d,e,a,24); R2(a,b,c,d,e,25); R2(e,a,b,c,d,26); R2(d,e,a,b,c,27); - R2(c,d,e,a,b,28); R2(b,c,d,e,a,29); R2(a,b,c,d,e,30); R2(e,a,b,c,d,31); - R2(d,e,a,b,c,32); R2(c,d,e,a,b,33); R2(b,c,d,e,a,34); R2(a,b,c,d,e,35); - R2(e,a,b,c,d,36); R2(d,e,a,b,c,37); R2(c,d,e,a,b,38); R2(b,c,d,e,a,39); - R3(a,b,c,d,e,40); R3(e,a,b,c,d,41); R3(d,e,a,b,c,42); R3(c,d,e,a,b,43); - R3(b,c,d,e,a,44); R3(a,b,c,d,e,45); R3(e,a,b,c,d,46); R3(d,e,a,b,c,47); - R3(c,d,e,a,b,48); R3(b,c,d,e,a,49); R3(a,b,c,d,e,50); R3(e,a,b,c,d,51); - R3(d,e,a,b,c,52); R3(c,d,e,a,b,53); R3(b,c,d,e,a,54); R3(a,b,c,d,e,55); - R3(e,a,b,c,d,56); R3(d,e,a,b,c,57); R3(c,d,e,a,b,58); R3(b,c,d,e,a,59); - R4(a,b,c,d,e,60); R4(e,a,b,c,d,61); R4(d,e,a,b,c,62); R4(c,d,e,a,b,63); - R4(b,c,d,e,a,64); R4(a,b,c,d,e,65); R4(e,a,b,c,d,66); R4(d,e,a,b,c,67); - R4(c,d,e,a,b,68); R4(b,c,d,e,a,69); R4(a,b,c,d,e,70); R4(e,a,b,c,d,71); - R4(d,e,a,b,c,72); R4(c,d,e,a,b,73); R4(b,c,d,e,a,74); R4(a,b,c,d,e,75); - R4(e,a,b,c,d,76); R4(d,e,a,b,c,77); R4(c,d,e,a,b,78); R4(b,c,d,e,a,79); - /* Add the working vars back into context.state[] */ - state[0] += a; - state[1] += b; - state[2] += c; - state[3] += d; - state[4] += e; - /* Wipe variables */ - a = b = c = d = e = 0; -#ifdef SHA1HANDSOFF - memset(block, '\0', sizeof(block)); -#endif -} - - -/* SHA1Init - Initialize new context */ - -void SHA1Init(SHA1_CTX* context) -{ - /* SHA1 initialization constants */ - context->state[0] = 0x67452301; - context->state[1] = 0xEFCDAB89; - context->state[2] = 0x98BADCFE; - context->state[3] = 0x10325476; - context->state[4] = 0xC3D2E1F0; - context->count[0] = context->count[1] = 0; -} - - -/* Run your data through this. */ - -void SHA1Update(SHA1_CTX* context, const unsigned char* data, uint32_t len) -{ - uint32_t i, j; - - j = context->count[0]; - if ((context->count[0] += len << 3) < j) - context->count[1]++; - context->count[1] += (len>>29); - j = (j >> 3) & 63; - if ((j + len) > 63) { - memcpy(&context->buffer[j], data, (i = 64-j)); - SHA1Transform(context->state, context->buffer); - for ( ; i + 63 < len; i += 64) { - SHA1Transform(context->state, &data[i]); - } - j = 0; - } - else i = 0; - memcpy(&context->buffer[j], &data[i], len - i); -} - - -/* Add padding and return the message digest. */ - -void SHA1Final(unsigned char digest[20], SHA1_CTX* context) -{ - unsigned i; - unsigned char finalcount[8]; - unsigned char c; - -#if 0 /* untested "improvement" by DHR */ - /* Convert context->count to a sequence of bytes - * in finalcount. Second element first, but - * big-endian order within element. - * But we do it all backwards. - */ - unsigned char *fcp = &finalcount[8]; - - for (i = 0; i < 2; i++) - { - uint32_t t = context->count[i]; - int j; - - for (j = 0; j < 4; t >>= 8, j++) - *--fcp = (unsigned char) t; - } -#else - for (i = 0; i < 8; i++) { - finalcount[i] = (unsigned char)((context->count[(i >= 4 ? 0 : 1)] - >> ((3-(i & 3)) * 8) ) & 255); /* Endian independent */ - } -#endif - c = 0200; - SHA1Update(context, &c, 1); - while ((context->count[0] & 504) != 448) { - c = 0000; - SHA1Update(context, &c, 1); - } - SHA1Update(context, finalcount, 8); /* Should cause a SHA1Transform() */ - for (i = 0; i < 20; i++) { - digest[i] = (unsigned char) - ((context->state[i>>2] >> ((3-(i & 3)) * 8) ) & 255); - } - /* Wipe variables */ - memset(context, '\0', sizeof(*context)); - memset(&finalcount, '\0', sizeof(finalcount)); -} -/* ================ end of sha1.c ================ */ - - -#endif diff --git a/libraries/arduinoWebSockets/src/libsha1/libsha1.h b/libraries/arduinoWebSockets/src/libsha1/libsha1.h deleted file mode 100644 index ee3718e1a..000000000 --- a/libraries/arduinoWebSockets/src/libsha1/libsha1.h +++ /dev/null @@ -1,21 +0,0 @@ -/* ================ sha1.h ================ */ -/* -SHA-1 in C -By Steve Reid -100% Public Domain -*/ - -#if !defined(ESP8266) && !defined(ESP32) - -typedef struct { - uint32_t state[5]; - uint32_t count[2]; - unsigned char buffer[64]; -} SHA1_CTX; - -void SHA1Transform(uint32_t state[5], const unsigned char buffer[64]); -void SHA1Init(SHA1_CTX* context); -void SHA1Update(SHA1_CTX* context, const unsigned char* data, uint32_t len); -void SHA1Final(unsigned char digest[20], SHA1_CTX* context); - -#endif diff --git a/libraries/arduinoWebSockets/tests/webSocket.html b/libraries/arduinoWebSockets/tests/webSocket.html deleted file mode 100644 index 66a270890..000000000 --- a/libraries/arduinoWebSockets/tests/webSocket.html +++ /dev/null @@ -1,49 +0,0 @@ - - - - - - - -LED Control:
-
-R:
-G:
-B:
- - \ No newline at end of file diff --git a/libraries/arduinoWebSockets/tests/webSocketServer/index.js b/libraries/arduinoWebSockets/tests/webSocketServer/index.js deleted file mode 100644 index 389e19307..000000000 --- a/libraries/arduinoWebSockets/tests/webSocketServer/index.js +++ /dev/null @@ -1,57 +0,0 @@ -#!/usr/bin/env node -var WebSocketServer = require('websocket').server; -var http = require('http'); - -var server = http.createServer(function(request, response) { - console.log((new Date()) + ' Received request for ' + request.url); - response.writeHead(404); - response.end(); -}); -server.listen(8011, function() { - console.log((new Date()) + ' Server is listening on port 8011'); -}); - -wsServer = new WebSocketServer({ - httpServer: server, - // You should not use autoAcceptConnections for production - // applications, as it defeats all standard cross-origin protection - // facilities built into the protocol and the browser. You should - // *always* verify the connection's origin and decide whether or not - // to accept it. - autoAcceptConnections: false -}); - -function originIsAllowed(origin) { - // put logic here to detect whether the specified origin is allowed. - return true; -} - -wsServer.on('request', function(request) { - - if (!originIsAllowed(request.origin)) { - // Make sure we only accept requests from an allowed origin - request.reject(); - console.log((new Date()) + ' Connection from origin ' + request.origin + ' rejected.'); - return; - } - - var connection = request.accept('arduino', request.origin); - console.log((new Date()) + ' Connection accepted.'); - - connection.on('message', function(message) { - if (message.type === 'utf8') { - console.log('Received Message: ' + message.utf8Data); - // connection.sendUTF(message.utf8Data); - } - else if (message.type === 'binary') { - console.log('Received Binary Message of ' + message.binaryData.length + ' bytes'); - //connection.sendBytes(message.binaryData); - } - }); - - connection.on('close', function(reasonCode, description) { - console.log((new Date()) + ' Peer ' + connection.remoteAddress + ' disconnected.'); - }); - - connection.sendUTF("Hallo Client!"); -}); diff --git a/libraries/arduinoWebSockets/tests/webSocketServer/package.json b/libraries/arduinoWebSockets/tests/webSocketServer/package.json deleted file mode 100644 index 9538323e4..000000000 --- a/libraries/arduinoWebSockets/tests/webSocketServer/package.json +++ /dev/null @@ -1,27 +0,0 @@ -{ - "name": "webSocketServer", - "version": "1.0.0", - "description": "WebSocketServer for testing", - "main": "index.js", - "scripts": { - "test": "echo \"Error: no test specified\" && exit 1" - }, - "repository": { - "type": "git", - "url": "https://github.com/Links2004/arduinoWebSockets" - }, - "keywords": [ - "esp8266", - "websocket", - "arduino" - ], - "author": "Markus Sattler", - "license": "LGPLv2", - "bugs": { - "url": "https://github.com/Links2004/arduinoWebSockets/issues" - }, - "homepage": "https://github.com/Links2004/arduinoWebSockets", - "dependencies": { - "websocket": "^1.0.18" - } -} diff --git a/libraries/arduinoWebSockets/travis/common.sh b/libraries/arduinoWebSockets/travis/common.sh deleted file mode 100644 index be959faf7..000000000 --- a/libraries/arduinoWebSockets/travis/common.sh +++ /dev/null @@ -1,53 +0,0 @@ -#!/bin/bash - -function build_sketches() -{ - local arduino=$1 - local srcpath=$2 - local platform=$3 - local sketches=$(find $srcpath -name *.ino) - for sketch in $sketches; do - local sketchdir=$(dirname $sketch) - if [[ -f "$sketchdir/.$platform.skip" ]]; then - echo -e "\n\n ------------ Skipping $sketch ------------ \n\n"; - continue - fi - echo -e "\n\n ------------ Building $sketch ------------ \n\n"; - $arduino --verify $sketch; - local result=$? - if [ $result -ne 0 ]; then - echo "Build failed ($sketch) build verbose..." - $arduino --verify --verbose --preserve-temp-files $sketch - result=$? - fi - if [ $result -ne 0 ]; then - echo "Build failed ($1) $sketch" - return $result - fi - done -} - - -function get_core() -{ - echo Setup core for $1 - - cd $HOME/arduino_ide/hardware - - if [ "$1" = "esp8266" ] ; then - mkdir esp8266com - cd esp8266com - git clone https://github.com/esp8266/Arduino.git esp8266 - cd esp8266/tools - python get.py - fi - - if [ "$1" = "esp32" ] ; then - mkdir espressif - cd espressif - git clone https://github.com/espressif/arduino-esp32.git esp32 - cd esp32/tools - python get.py - fi - -} diff --git a/platformio.ini b/platformio.ini index 8ae84bbae..174a70324 100644 --- a/platformio.ini +++ b/platformio.ini @@ -10,7 +10,7 @@ [platformio] src_dir = FluidNC -include_dir = FluidNC +include_dir = FluidNC/include ; lib_dir = libraries test_dir = FluidNC/test data_dir = FluidNC/data @@ -24,7 +24,7 @@ lib_deps_builtin = Preferences SD SPI - SPIFFS + SPIFFS [common] build_flags = @@ -45,12 +45,13 @@ wifi_deps = WebServer WiFi WiFiClientSecure + arduinoWebSockets=https://github.com/Links2004/arduinoWebSockets [common_esp32] -platform = espressif32@3.5.0 +platform = espressif32@4.2.0 ; See FluidNC/ld/esp32/README.md -extra_scripts = FluidNC/ld/esp32/vtable_in_dram.py +extra_scripts = FluidNC/ld/esp32/vtable_in_dram.py board = esp32dev framework = arduino @@ -65,12 +66,6 @@ monitor_flags = monitor_filters=esp32_exception_decoder board_build.f_flash = 80000000L build_flags = ${common.build_flags} -# src_filter is deprecated in platformio version 6 -# It is included here so we can still compile with version 5 -# We should remove it at some point -src_filter = - +<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> + - - - build_src_filter = +<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> + lib_extra_dirs = @@ -90,6 +85,12 @@ extends = common_esp32 lib_deps = ${common.lib_deps} ${common.wifi_deps} build_flags = ${common.build_flags} -DENABLE_WIFI +[env:wifi-littlefs] +board_build.filesystem = littlefs +extends = common_esp32 +lib_deps = ${common.lib_deps} ${common.wifi_deps} +build_flags = ${common.build_flags} -DENABLE_WIFI -D USE_LITTLEFS + [env:bt] extends = common_esp32 lib_deps = ${common.lib_deps} ${common.bt_deps} @@ -102,14 +103,6 @@ build_flags = ${common.build_flags} -DENABLE_BLUETOOTH -DENABLE_WIFI [env:native] platform = native -# src_filter and test_build_project_src are deprecated in platformio version 6 -# They are included here so we can still compile with version 5 -# We should remove them at some point -test_build_project_src = true -src_filter = - +<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> + - -<.git/> - - - + - - - - test_build_src = true build_src_filter = +<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> + From 308fee6a6de5a574f3e2c11a75f2cb8b2659a155 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 17 May 2022 14:18:05 -1000 Subject: [PATCH 16/22] Ft (#433) * Make it work with platformio version 6 * fluidterm with Ctrl-Q, macro overrides, error -5 handling * Ctrl-Q for python fluidterm too --- fluidterm/fluidterm.py | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/fluidterm/fluidterm.py b/fluidterm/fluidterm.py index 31ebf3c3d..895a63a5e 100644 --- a/fluidterm/fluidterm.py +++ b/fluidterm/fluidterm.py @@ -538,6 +538,7 @@ def __init__(self, serial_instance, echo=False, eol='lf', filters=()): self.filters = ['fluidNC'] self.update_transformations() self.exit_character = unichr(0x1d) # GS/CTRL+] + self.exit_character2 = unichr(0x11) # GS/CTRL+Q self.menu_character = unichr(0x14) # Menu: CTRL+T self.alive = None self._reader_alive = None @@ -706,7 +707,7 @@ def writer(self): self.upload_xmodem() elif c == '\x12': # CTRL+R -> reset FluidNC self.reset_fluidnc() - elif c == self.exit_character: + elif c == self.exit_character or c == self.exit_character2: self.stop() # exit app break else: @@ -724,7 +725,7 @@ def writer(self): def handle_menu_key(self, c): """Implement a simple menu / settings""" - if c == self.menu_character or c == self.exit_character: + if c == self.menu_character or c == self.exit_character or c == self.exit_character2: # Menu/exit character again -> send itself self.serial.write(self.tx_encoder.encode(c)) if self.echo: @@ -1046,7 +1047,7 @@ def suspend_port(self): sys.stderr.write('--- Quit: {exit} | p: port change | any other key to reconnect ---\n'.format( exit=key_description(self.exit_character))) k = self.console.getkey() - if k == self.exit_character: + if k == self.exit_character or c == self.exit_character2: self.stop() # exit app break elif k in 'pP': @@ -1093,6 +1094,7 @@ def get_help_text(self): --- r R disable/enable hardware flow control """.format(version=getattr(serial, 'VERSION', 'unknown version'), exit=key_description(self.exit_character), + exit2=key_description(self.exit_character2), menu=key_description(self.menu_character), rts=key_description('\x12'), dtr=key_description('\x04'), @@ -1320,8 +1322,9 @@ def main(default_port=None, default_baudrate=115200, default_rts=None, default_d if not args.quiet: sys.stderr.write('--- Fluidterm on {p.name} {p.baudrate},{p.bytesize},{p.parity},{p.stopbits} ---\n'.format( p=miniterm.serial)) - sys.stderr.write('--- Quit: {} | Upload: {} | Reset: {} ---\n'.format( + sys.stderr.write('--- Quit: {} or {} | Upload: {} | Reset: {} ---\n'.format( key_description(miniterm.exit_character), + key_description(miniterm.exit_character2), key_description('\x15'), key_description('\x12'))) From 3cac3226c9963ccbf0248d3e4031a2d9cff08934 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 17 May 2022 14:40:18 -1000 Subject: [PATCH 17/22] Added + to build_src_filter (merge botch) --- platformio.ini | 1 + 1 file changed, 1 insertion(+) diff --git a/platformio.ini b/platformio.ini index 174a70324..e3e6c1c63 100644 --- a/platformio.ini +++ b/platformio.ini @@ -68,6 +68,7 @@ board_build.f_flash = 80000000L build_flags = ${common.build_flags} build_src_filter = +<*.h> +<*.s> +<*.S> +<*.cpp> +<*.c> + + + lib_extra_dirs = libraries From 8b30f330191cc0d428b1540440e9e997b49f1331 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Tue, 17 May 2022 18:57:19 -1000 Subject: [PATCH 18/22] Fix build script with new path to bootloader binaries --- build-release.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/build-release.py b/build-release.py index 86fab3371..eaf45ae62 100644 --- a/build-release.py +++ b/build-release.py @@ -114,7 +114,7 @@ def copyToZip(zipObj, platform, fileName, destPath, mode=0o100755): # Put bootloader binaries in the archive tools = os.path.join(os.path.expanduser('~'),'.platformio','packages','framework-arduinoespressif32','tools') bootloader = 'bootloader_dio_80m.bin' - zipObj.write(os.path.join(tools, 'sdk', 'bin', bootloader), os.path.join(zipDirName, 'common', bootloader)) + zipObj.write(os.path.join(tools, 'sdk', 'esp32', 'bin', bootloader), os.path.join(zipDirName, 'common', bootloader)) bootapp = 'boot_app0.bin'; zipObj.write(os.path.join(tools, "partitions", bootapp), os.path.join(zipDirName, 'common', bootapp)) for secFuses in ['SecurityFusesOK.bin', 'SecurityFusesOK0.bin']: From b9f34ebc51129ea8e26c1823fae4cf821a24fc61 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Wed, 18 May 2022 11:36:39 -1000 Subject: [PATCH 19/22] Removed dead code in CoreXY.cpp --- FluidNC/src/Kinematics/CoreXY.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/FluidNC/src/Kinematics/CoreXY.cpp b/FluidNC/src/Kinematics/CoreXY.cpp index ac614a915..7fee20218 100644 --- a/FluidNC/src/Kinematics/CoreXY.cpp +++ b/FluidNC/src/Kinematics/CoreXY.cpp @@ -291,9 +291,6 @@ namespace Kinematics { } return mc_move_motors(motors, pl_data); - - // TO DO don't need a feedrate for rapids - return true; } /* From 6544d71a36aed9e6bb8920a975705b5ab0c4bf7d Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Wed, 18 May 2022 11:37:01 -1000 Subject: [PATCH 20/22] WebUI - better tablet layout for small screens --- FluidNC/data/index.html.gz | Bin 122432 -> 126645 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/FluidNC/data/index.html.gz b/FluidNC/data/index.html.gz index 38bed0f6f454b8e37a55dac3a8e4a84438e78e34..02d4c2818ac2ee296b8c34a6bb861b24e13eb977 100644 GIT binary patch delta 125513 zcmZ_VV|3+i_%HloYIkbe*3`DmscjpX+P2%NrnYU{oZ7bM^!GgH|LUBR7g_sSS=sr1 zc9NB>ecxA42UO!G6hIgW4f5Xt27caYnYt&QK=j-RK+rUts;Z;PX7MI77Zj9fw=1i4 zrdVkYTip4RVVS`227r(v$=}=SvvzM&g0PUNlxkDwupnO^{2DervU$5_loVKR$~tOOY)Duw&gx>VqLHEkv@)zcf#v7iQO%2I!D!y?IPs8o!X3L zi;-e}%{fQ>F9pq8RpqYg&j-A;x0v}6BResifzOA;pLs6~AupByBejew|*il}7 zQZkJl1P`;=$y=qrbr9;*xlUrRfMni30@|fXcwl<)di=bIY-P z1ZnGszOO`lN|>u|Wen@UQ->EjZEhq@&UD1)`3nUt=;B><_v@|#@bRdidEhL5qa1 zH$j^)*W#4ca&8`fh}JN3SF~>w*$L==`$v~wQg_i;uA`>zTWV=LQsl;$^e^zK2e5DF zv8e;oT+U4;N5#1}zWRqeQNi*oBisoA1JKpowrXF-PAmP$PGJ)MFm2Mpw5Kp_qW@qK zs7O@-R9?{~8}-3Da_K)|HrZhUxA&+KZ}pdw`JVimbUL_tM_RP(DSLh0{w&>*T$vtt z#Xn)>F)oR%2Fim&DD{H$Pwx?5(dTdWu&Ty9pB>ilTzY5PbY9rrUeq>EUV1S_0g~aj zExrEk+7;uz@tx@)1&7@m=EH+t%bDiu?G@)2NbQ*-dMTYee_Sbvme-9sCw-L-U`g>L z!P%kVTUX`Hw9<_k#Mo9Z%M|>CH(giI52h6$A};JQ6*RcqxEd}?7QJdmngyQ9e85-L zs(LofOSCxtL9Ey5KF@%+_kU}119UEhN^Q&EY!ZYbFMn|*E+UR_UBsX#{IbcML=-?7 ze7>`6;sH^3U#$w*VS#z7?u76;jC|8VA~S97%;$TKKxKyycpG$*nGZ8dub{QqefLAJ z6Fsh#O0qAmNPG=6?79i?e!jyD-yW41H)SeP1<*j2P(@4P6r=L$$4QYLfeo3`{`)=Z z9TxLBmu}kS6~{yoM7n@SZmrm~vQ59;r+J^i7KMsgKY_lahr%%{aXbJVBS7 zoH+k+qbDoj_WhhObj$%{?X+)i%TML~;gMH1PdHML2keI8u!(|~?)JK#F($-F-hY&k z6Y$G7KYXB!{*Bv!lB7S40XFp-A?s$%oBnJQcR9})OBLUKUztl7^kB$7eri6ry+t6x zZ)3uT5FiR77oCfGTXyR9j#NTJ-h^U>qp8SkZMKP~1}qCI<&30J2)BLH6&g$vLY4?Y zzEycJ%k9n^6?iHn!*cd4Diox&TUwkBIN8SC$Ii<=`mXKAEkGbm1o(C9fQuki)a4rB z<^QXB)~Zq`%hAji>zarW8-$gkD7;GHsiFJyf_n^CHY$dr&bX`}1Z!t)q0FPyaw%=< zNY!T5Ke*G+8(tJQ&tvjy3QxvrEmoD%dQ^>O(q4RQNk0h9%@?X*nZxPcsBZ3}qeirt zVWhbaZ%hg++pwOI0Pd0-mlXw5&N?(@34QUjsQy@%z-()Pp#&GzR)N7W`EHl|`mAjX z8Tny}2+fcRt6FEivPD!CJ&JL(K1qfzaeg8K0BV9vcu9~<%YJZHTSkzJ0QB^Pv_VkAaig! z@O4U7Tip3R0r;Hi@^vOm*1)ChvseT?{_}Nwm_-M_3NHlAwo{P-z{zyGt&Ngl^a90) zhz+fn$d8R6Rw&D^#}kzL6=I0*RVDGM#_dIFKQ*9#B3^iAqJYHFZ968-M-;%AX1ksuNNX{YDlvd+E89LDm{;^oWX!SNcIGmZT_>lsunax|I21 zZQYgV*#WiFBHcxf_fN$;rc8vAwzB-Ke?cC2eeLFAzd55r?koe{ejg0j5J4CUTkkjy zsYpOJTqD??CJDW^AD~XG3_!6Ky>x?O?`Ql4Izbh%@p|}8Ubb5=-1E>bom}M2^Vg>OMWf za}`1x4IsJaAN9Myu@DQpMI5A5xxWq!z+_K{04Dddzm#ROudRbW9q;Kn5fF1VB17Hd zX2uAY%1#R#Xpol`+s%{5s~Ko>QgYXA{L@;cxuBy#YgI{$?z*IQi-WGuKHJ)_cI&{Y z%I(kECAKo#!<&?!>Lgm{9C*LyEoRfwAh{4Ke@eKNi*$<7^-aX1n(lc(l-!sQ5Oty{ z;vC9}#|TATLnIR7_#{n$^^sI4^X#JJ#ThC6x+VHvJ^Up+Rq{%#X6=BJP9vZ5XE&=zip`vJdHp~hAc7C=wHQS) ziiwCW{PQP)4JQh_Ok>p$4z>SIeANJDnv)}?lw>~~cB+>M0m3uV##_bQbdOAmBqrgo z6iX{3z#(bCGOLH}T>J`s*8&?{@Lo+0t#u|bt-3R7kYfG(nZ`OC1diW+hFjr~e7H70N6AtyQErz>6Pi%&`dw)fhP(zu3+)v9b;~29V>Dh;`iCXfNu$cn^zc`@@S(E zDniR@}4ltoPfJ-7 zkE|H;`4uFa<~Eny0OWME4!%FC>7AEUMKi?We0Q@k)U_kSuzopWA(8>2u}r*_O^B547TYxM3!^$oKd3O7!~?#KbYM^i+a^d;FBB=6 zpN}Exj*r2xEd5ESBu{78Vc7>W61p4x7ZbpA^XZQ4gTV{B2~hNWh{QnAn!ta2)KaC* z7sk{n5_s5n+`X_8hA5X%eW1(AK~0c}SXUzm+qNL|^|F-e$~TQMF(8gJxtR%ATH)y8 z+gPOI3X0FHR8b%or4*}|%IqqHoqLGJoO&M%=FPY_xgL@ zwCc0`X4Fi71GI=ECH+JYdlGlC!~1xO9ll68=eSac7B|BWtF&iB6qm zVb-X<^dGSMqf4MuK^$FF#B8Zx+DU&0>q1!ducx|ylFnF$_k+rp`vN}vn>Wj>e}$AI zy)3J9RVATsf2d7yc}BDbGsUY`=FhRkp-c85jUK!7*2soGo6Z(iXM{7F=uZlQ_?ESwM>8U2L~bEN8$>chbIamVgl97A8T|Ti_ho_ zxyn{#{AbmgKIFT!==$I{>}dL=H-lviKRT@5VNVsP*->*JH0ZieZ;~Ub{hx6ns^g!H z)Vdiw|DXG^^QTMXDXJF@KHJqjoU!NS=q;#FfO4#H6514^96>z~ zzp5V+PQq%XB!{Ds84#(9VTs2q7-4Yb$ElaZ_fwpR zBjTR3IgMbJ#EU$B73pVePAjUZ@qxUl@!z%VNGSz3#A5=#zQepF8ZXoVmkZGliz{b` z!wIj?cAqoIa3AmpSs#JvYKg*wVv5Eat;OMr-(zzE`#Jz;klnsV+x&k__26Q2~TvEL1_QTjZgoGka%W%qTpIo*0(jYeJjP#_;S#-sGkU{UxnoV zrN|oiYeuR8ekxw&NWG^4WccH%e+f1J6OMfe)xU&V{|OJigvnn*^)F$=f5PN1q57Aw z;Xh&WmoWKDNc$yJ{}QTy2`j&ZI$uJ~FJaSv!h@W_xBwa*1+YCU=EX?GxshOW3 z*3U9STrJ7uGO3!MFjUbsL%jWICU4R@nFZpQ$%SZ?_TPDP{!$%&sSdwX6OPc$>3hf_ z>3i6Atd!5YEY5g6Y|doER)?Z7^Aj*%2iQYyOaDT#exc01P-b7KNjxZr3@*gHOsfhjSR>X)bJF`9U4e7)3RR+qwAl7BMq}A#v1qX#rCn51}J0ni-aVf1;*92Rxt}Pfp zFp3J3CHn%oaeySrvV6&F5_D;@#iv+_%RS6BbT)&yJ?VL)+LmV3{LmPpi$!@vado;1 z`y5A`#DmwK*d3`0OUUn8zb;ALt#xME`%AOb?tW6O3u(-Wtx4rU_p#nqXW1X5EW1nc zw5p9VbQ!6VqOJ^)7%xpElh4QTSQl3o5=SmgXw#@LQvd_Wx^KR^_+v}FGFxL4thnZ* z^+~LmW}`Z;MW1vwHptAIsEfR`<^5ia>>hQM>Up%jQC-)gcC{W}bvaIfgfaejO4Z{$ zu>*+(YO0%FagXyIBV)I*jEa2!Y&M7r{rI^Ai?@D3UGJHBPgi@1?X?IsM;;lw)&@=T8xBQoPb6HBV=qZQOeOE31Y#_tcpU zizw*S!W>8!%9e?omTAIqWH-OTUIb`UD>g-9lD;z+25p+xhKG;TjlqmJ!bIc@9`q`w z#+xRiLka8X{-mID#nw{ybR^$QP zwS$C6CP`q}Nt&_P^msEVJv*WhunpWtZH$QODiV5}Z2R)eZ~U4UOii?k`uu0qF;hVS z8C~%dHDNsHqP7jp$8(mvpUcjX5s*tH^fc)h{z@~gro|5ohD}k2<F)5JH&?*LdYK zGqRZz7F<6WCcN(P%6nF7wN7_f43`RyG=m3YzJ4j+n>hyX+fJG0!as`i0l(uc;=g03 z>&UJ#1Wg?}6O%h_U^?P%v-5!H6DnN-P&>mu>D^g`w^<=NABB2BScoAey?=X7e-;px zWEJ5;pJR}O;G>t`8zE5;i-Gt@Qr(yJ(ecRQ9tp4`EZeYHZ*aSUtQ~sG36?_=IYX{| zTL>D>8e|8pJZAqAvDadPv3EDAsQcWf7W0)(x1tg zlhhodnLGt<)d7a2BZ*vn!Kx4wU8Np?8uwPOw{qUk!f>eHQEkXI$Hn5>=Dc#7# z;?dhh+;>7cIDUpjnM{^M{(MXMB3y z<}fR20_|Wuu)A7?Fxhyl=}qTK!plN9A-j!RA7nC1A`eaG-oJX-vH|c|^rw2PT@<{r{-Wp*6m={dQ5}i&cQ>lvOuB97Z_k(A28m0?=&i5G~?Hq0|i z!UNvwpwqEUatwVs6nc1Ql|Q`KO}qWFG5NzOxM6Z~$lkwRy8(5o6U){`uf(@JnEF11 zX8*!u9$ckAt(O?WGtD2)J1a0K`S{xFNt>E23zegWWT2I z_-~sXE*crIZ1O=lI2l}o^XeYdHIavzGA)XjoX$##*{TCd zCiP5eh*Z+QcLHhwcp0rjpNt#BWDkh=zF2ea=3M4t8QF(qJwxE089SPPSEV04L9MGy{=mB|C9sYA$cS+0b9-Bf z!kV9&WJWJ&*#s&*Z-|Edk;cyRvigpVKy+)+j6$r#o|}UJaGuHe@v}js2gl%_0CPhuEa>E!0O@v3i$XY?78YN2cxb-)kuuiWD!ahk#h)!!P zy%JtDErxm(K3b^N9&*vLO*U6{EEo;y%>7#T9iR|*;7S@zgrJ){s=jz{t&XlUi7k;n z?%?LF4uh!x@(quuOUwj4#5@|L;Td~~d6}5lc1lsOdBKr}$2Nv-Q`C(E;a7F6=>Lj^ zfIRbJ&%NZ2A`>g5?zrP~_pA1@}bC47Q^(s|wyYvR~AbtWS zip_<(6E3E6;X_XIV29tfmsP>S*WFwrlzZhzJQ9v9;e)(mBdR6N==cW zdQ!~F`_pJwZd=}LLE}3RWI~h`Bke0u|1j85jccHN>QPd^xKF%6& z!a)@PC*WgNs^h4LUgphep8Sn0OTI*tqw!u$ny*RO=QCnklIjDsQ|w}T`zIufEM)N- z^ER%UVtUi{VZ2bxqI#n>5xkMs^bu~S6&I?cXSjMxD6FXCNcF7j)^*(r%psvQ2j3gLQ{8ti`+vaW=0P7eLZ)~$@e zGBRFo-S`lrota5IyjIwsZptcJY1_+leoj?x#Y=+sNK@E5>|+}Y-D{RY?RJ7^Ofs5!p~{NPs51w5Hnu~6y- z>Hs_5h}or|aJ9N#^(wsQkQ{Mp5Xmm-EI+emmrO4iE1**$H_#EH#0I=?|5*RX%)6RP zi==(r#OLKvyok9=j&-jxNV2WF@B-*Y#?w{YW7^;r9#*39ls9=ry-)Iqp16P<<8TG8 zL^T0v6s|r)Df&rKK7SX;_VlF^^M=Bt@FZnG9{xHU^ponS?cS?M;UJmjr&(jy9~ySC z;yYEs`C50!z*rm+8Rf}oczh(H76WSC2Mp}@MJJzc5>c(QWK+NIp)8LyP+1zCWNg3f zn&>tK!5iGN@L(*KUeN1KdQ$-I(1o|k!?$Dlb$y?4Fr8no;7{hs7i9tf#U#bU#^#%X0cJfwYD7*Pd|O-$vH9KP0wbIZxnM z@)a;)J{!h|!QU3jek{N~|EhDvp3Y=DNZ(XPQihx3cAiUFPv#Nt`u3$7-$-f8DiZ07xZEiEsbX+UE%LkbQ&XjrzmNJyA6FL0?^ z%$ca?O{di~QK!Ai=O|D}xFMN^V3wX2N}@S#hi*jI;3Xix(Ii*Hu=M1;>Z<<}=U8Rzf5)Ms0lxAm{ZF2Vv627c(9--*oQSfoIB4jMhw7@g-X`HML47F!i z?B=^umP-uE!)*St+`l-JrBmZ8t_X*x@AiR23up8792?SRVv$`fl~ra zQxOtp+v+`1<~@kM(pt+5gh=P}kZJ?8HI}4&_H#+*Zkf9D*y)Kw6J`g6ZhCMFg}6!1 z2&DyOGa3n+%+0@zg#0ofOtXf1Ky*H7|_4)-|2TzEL~g6&1FU+#bvvui`re3+WKG$Q3 zv0C+b4@CivN*k5)rC?ij>$x~nmt9DfO(?d02j)ZmI7p+#F*s?*tT zqs|X89o@O+q3Grg&(@r0-Wfb7iX`Ibs1Ou z1M#wgF5~C8GgtQ8<)WZ>SFInv?8@}R*4;pq`S&Oca-_CTVWhZF`_DDi+ApTrE1VoT zLbqJ@lZRK$=*@FnXrM8@P(^@erPL~o0(_`l*&x*1RTROtf7Qz*-En(8zyDy#d=}E{ z<482wjJhopW+Zc;)@cwM@`tbME5nUa`4r#$k!Rx`D;KCNDx^D$XJ;r|vlb2M@y%QXUNrFd`ke;#XYXVKdwS|8T(E+##y|v`8A}wALpiEDUA=rMo}F5jm{@7 zR*Ys-2anFnE4C3&S7br7P)gi>BcG#1(~ePc){P&95<_GMleLH@u_;X^A{QwcCI;me z4COC~_+1o<)kN`lW^<|=AZ)xv>Pk@FRthI4+zpIT=}QS@#);;hyK5D^Vc=Xv(;=|@dICJC&J zzga24i}8vHWB&M#i040C$>dpR11E&DVlN6D(_y-cOjTnp zZ5A2rVZg&gzS<=&+-&ZWXxW`;9hVu0E=)ZvU^}$HaIF(=LmTs*|7~jzdYm<8MSDd_QG!D#3w^gPQM`2gACXN*BzC(7& z46(ZXmx%X`9G&*2_TUuhX$IGm`#cfnR(qp%`(w=~c4PboUD<`^w4`22DEc4OrfVXU z?(mv+`HNwI@$mw3iYtKG#L!NX@__`Ny+`0dnuWTYE6~2SjW}`@mX>fbv4rP-h|w%0 zsizB9!@LoV#SNRdr9YcX};@n(8klpOlr+&r(E84?N&3ejab}t6jPx-h8hXXKuRnn(CKh-Xx8RgPnzJWF7X;? zp4N)LNkt|Y5Pt}3m6m2_Y^<8OQ))m%aFEk3{Yv6L7o!YSJZ#f!7P~ogSk|)cuwR5N zjABquaSwUUbo*udv}t$GN#pnlaa`JbL*Hr@?Id2p3KA`WS=?kWs2DF13t`Ilf)tJ% zzwZN(GAze#&l=Of^StjdF1cI#-1ze#8-=^FP|)taBmDTR$}B?t`p@S$^6cU8P?b>_ zZl?!}_h9rz9@+CYIxwF|D$!L9EjY|c@tDUnP1JS=7f*=^|HD#cRg*r;Mk=+V)G>7qYA-$uld(EKQ<4M|m_bXL%Zy_g@Ht5iC z)>O6wocwwPcAJlFj{7*DES)caDq$G+!?$TN*g}z7-9QtMbbg0i^cc0w-d4ZP7pmok zDTCZj7e9-h{jWZ;LLJ+S@MLF{T81#Nsy#IPgWvxk;d7rJ`AzipZqWVADOyKrZ8cdH zXb&x1;C1qFr$>43W-sx)f%}gxlU(MFJdngS!g|v0Qa@nIr1e>*iu4aFe<1ch%1CvxBo%r#- zjt?Cc=L$04P_&ZCwz`HFhuK7%EQcI=pDG}(m*AH%5@=M-_zA6Jdq2*%G=tt1m2d$uj?~?y73!xZLqS6d{G`WxjvZE1md$(QA0zX&CkNg_LBiCr^yyNCy)@}eGn&Bo`_UPJtp%a z$)o18ZR`j6o$=x;`BkC3bG1Qf@aS#CsbRyzlq-E(PC&Ui*okL1igPbxU zZ}2hS*86X4wM^IxgF*k^*hkS{;dlND-#Ae?1W@wO+V8_bFi}4M*(ls8C!a#xnorSR z<*NPPL8ap(bD$NO!$z*9Z%GAE3@Q`8R_f;-Bt0>Mery8)_W_h(XmsYhC^J^V(X*EN zc#ZyJ>vu!Srj(5aRqV&C*`*u^39jA-3@9$_(`~a3jK3j}G==IFe&d!eP~u%(!9qVx zo&_Sjh8ba6a3}Eq%R$D;v&r3p*%7S`O@~F$Fmyg^&F@1p z62G(!+FXp+{fUL+T*6v5X=_#InMyA>T6h%fr)l3Tta|h$C^u)6@8=%*>M$Ht=j0k2 zFuGdeF=+u}bDaZZc{yQA@i*dW+~XN9RVrF(KCA@RZf{?+kpjfHOJqrUv|KgOE2`PB z2Mm_6jo-n)C1Y=~qOK(vt)74(xOdBt#TJuLO944!6-;i1)qj@6a_;`z0nKbfmk_!e z1nrm$(ElN)m>MMm$KkB}&xDI)K*_OoKS@q%08gP?#b!*4{Ki2ztKq-L5b@9MF}op{ zh2WYUc}zXIhnEW-d5~!gn=88zN-r7GleP~5bc-!EX>I8a+%mK5=Snrs8>vw#Za}5( zcUQO7sV^;edHJ}T->l5~(+Ev<`?#CbP9&~p?T|~8+GDl${+x?oMVrji+D}dVn9OwG zZ>Mz0-qN?#)0S2${_?Ob-KP&xA?AJbl8jYE`#twmIgKhgBr zLH7%}aDKn^mF&rfJ#@*3N(ACHGfb?j!tRWTF?Om+Q&{G=4Qye#mKfG*l?b(=n8gtt zpuo04fYnv{;rfo4{!}o#A)Q2Q!X)AX){@&xaYUNNb*bvG$P81W{OK2kBa8bgJtZqx z3qVVX;&1NXDepCZ`z=aTDRQ7Zy5Od_8M*IgOls8OFw4-zRV}-E)*uh(UnuM9A`Gp~ zEW*kZWE}ivqBTRf+_4*Nj{4zAgtTGolNZAgvd%s+dEOMyZ-I5cTK1pW>#(} z+fB!aCvMsAdpsc^BX-9-Nq3!ecXc<{_d$P==z?Ze>VxX9#|P-=_aj`(AcXnYWDpV&4G@%y zrH+_If@PDGWUlDNDi==y>AOi^@lvy&y8!k)VY^5%FWB^&!03;+(`YyH&;bzB5+V41 zaetc(p>a5jM%OCA?&nYA7=sJ!#+~@rL^%|>xW}#Y)-HGrzt*khSE?%t+Tq4Xw>!FQR9iC*jcqh>kojfk73K{#r+G3n z#J`VKBLxw&U68eK)SkxgA7{cBK_Tf00Z$+; zD$}E-)mIVJ0}ou)i&n>;T7yHYhB?fN2L{q*`XW`M@khA>w4<=d!E1c-)7?52I)8gFi5b0U` z=~xtsA)sB5BbYS8S3MMHX02xv>J)Xxg9Vtsrr`K`ac3SC6ghD3I$%Ymun_PVt`Z?R z7xB}oN#P(2;g$6=0TZbOyi3qJW-m7UM?ukby(Br7f6g1|Lp?cVTovIw1BGywWSw#1 zOdCd`p9tccf(>*ywC731T9WA$a>*N6!>C(kdtBrF5dSr{uK+b*wS#dXGC{>QxecTJ`%NS<= z`IN6^-n^IXr0P;aHyK_S45pN17{)oq=Qh>D?>F zMT4;Z=kU!?y~1bf2zSAxxk86^ zz{ANk$@eE)eOaw+XgnKX0J!<3Lu4b5DW>!38YnwGjKnq*oZGt{+fhdMl9M(e7paxMt1xBXSydZ1Dx$DUR81$`HeK&c zToqS8a@yRc=;?;$82aQU5Wks6IvMAy16)IMQ(YA4(R_61_5q5f%Y!SP3B%(nLWMdG zMH@pYE~r|qWo~hg#kr)VQH*7Ub*xz2c3p*kvcl5Zdm~Kfx(d!Bv7*dr0X4xZK-} zDsxG(x@Py)GNq@uquBRfiaIq(HltZ5TWD{sUeUGJcB7+BGD%N!VMkMDR?NxPwghX9 z+FPnnDyh?+gDnIjn2#_Y#gh!bSEQCtuP^OabTxN%6mHt~wIk_}su!M-CECtb+}xL3 zz$5e3qgk1!fIU3Neh)*DT?P(-f->Gf=W%SxCT4h>{>to>aZ%;XrBrK8PH5XM@o}}U zHWG#Cc(x)^ZScG6KSAOXG?Q#z)kX4)pAAXIgXgM@?(Jn=gJi622k==qrOUTD>5&hQ zI(kt#)|Mdm9;ii0p;awzjN(ujbRn-7zm}++Spt_7qM^c~%MR4ct1YE~HgKtI$Lyq3 zaRN59q}Q`WyJ|!7ub0C%!#RCpFT4}wkmq`5(Y$#KVHF~k%2T*9qhWqi(i>U)Ar1qH zP}O@7zVXKQ1HxOU?)8*?y>C*EF&wmZ_Bj`h7kYzM3hZaQ4wQG~#CNUv-k2;8i|Ps1 z`0nCUC;s3^vcgrgY{6E*Sg+g(SD4Z^H>n?pocW@cQ+>_F)CG@WwFW&w=z8Tt#g6Jd0B>`*V% z^|4F*Yl^;L2^y!Avu9YUSCIK^Uz>zHr%OV=S>bV~tEd+>^X3_Fh7sN0d+*-2G_`at z3vqjW$EXRU#|wp*F)<^gX9xiVv7+*hOgma04xo|}#Q zQ(A~J$6eTf-SVBtt-XQ!p(S|}KaYGX2YeHzd7#lbj|Y2Tyk$X2mXYRfa3X&2{qI}d zmQ5v5xx_*JpH?W`YNO3#e>fa%zeiWCRBo5wiRHI;)uU7ZQ&&;r)HQd4e~TcbkOt=ThYwvvvGjKWn;L{H)(}UTcTk=Lj(uq&XR3s9$m(1_DT-8}&}p zwKao6S%?R@z`V~YYUDBlI_t->cVNr0q9=Kw2GQiJSL#)5@KWQ>Fo-d1XH&^RY@Zr# z@+mHA1U0e%{PY#<+!9FJJ<(PDjT(}=yXUo0V>nBatip%aP_R9N8;EAdb-f;a;GsBH3( z4mWKtq96CN4dyIu=($s-;z@g1O$f6^bm~&yXG!P)lxsFDr~)1NK!xdHAByVsyoF?T z(n&|Z75_8knDTG8f-ot0el%f$f9a2sO3X?56F2dhPB+Ygxa3>clyt{znOChv9H2+R2hpIhe4{` zXhPosUI$cub7BWxv$Gb0oN1ldxeY(s=Y<5M1)2mY>wnZD@`{dd6EMb7I_Q?j)tLqp z&u03Yy*RlWfclhgR;8IjwGt`p8r+dgBaS~YP7>#46wEPAt=o5B(^{nfkYmg;Hys_`lM)U>SICgbwZKba<1KsW zlpxd$MJZrxrtgjkT`>qNUArWA1fj4D=`aN>Z(&-q?aN1#-PzTIb+d?dG8V8<=SYyJ zF3)Gwl%F`;ddD1+`(YL2Af;tVb1CNpqgHC$uI7(3+1Ofe&P6?osd&_R9!#BOTT{V- z3{8EJ?o^Vr6@68xqIBBYj)MuOM(-kJ@}sI|cWWG{^mjeXv(sqBKC%%op&0Wm%HF%4 z@!}y;BQ^~1c6tMVw~u!@7B*gekBnC*0A%qL^K%6A>EHa{q|Z%mAlQJ8Xn>?!XWH3I z{jqC$Z4dJY-%Y31!rz19Pd{C5>+0D=F;0B2YMDe6P6^P3`U*}?P%wp(#6vDGfIF!V z8?nbO><|mvwRr?K^gQ9gUwZ~j3gkG2FN3hlN+#8z$W+_&L7nMW#foN5IMjrA8Qrzi z$5@a@Oz&T_OrN?5j28_ZnakY~vbx+P6>nmmYhS`O;TMu!ETi>g^1MBM0W5=BMDaR^ zH~i-HzPuf`k}ONEIQvmIbjrFB04->R$9b;>YMh|6_4K7 zqUU`!i&RY^xuE5Wmc&G%)?}r)`1dc+z-RY)7I$$r(5{id+@d3e`uq5KM`iP#YCYiRXw2|l8(i@a zPW$^iI{4kI67|UG)#FPOU{)0M>t*=c{ne^)M0QTG)eI5S3ihXiSekG>??Ol(Z@4m< z=ynXO?jNYe^ncgkxsZecY5`t}WnG0sPofPsuk?p7j)3j@bJE|2r5M~0?(9d+?K@K@iSy~~}XH!2- z#>SUhzSSb%aI2>p+Giiq5WLkhvav*QXJcuPBzr3mZd4#hCI@rSOTS9SIK`+dAu2QT z&G;Y?lxs1?Jm@a$!RN^-U8J$6A~8*WBzboOe4sN&euT{4oze551S&3+r<`$F+aBch z)U-c`Zb2@Yiie9Yo=Qb{48rB9tD_vehI~Ljgs>F)AYzSLMM8twhkpiy3SupVIPP~U4qDZx0? z%piXB<&ehcbwOwgNa+P)C8 zM((-HA_+yXv7aP>OY;ZGtKiNPeo)h(L@t;wK?V-@BkO(>=ATV^%qnc_xR+n+;_?T7 z4T6WQbQMHrb4e(o5t=BHLKWsp<49_)=M}rKeLW(CHfRU5abdI~Rn5cYIGC zR=Xh37FjB|zS&yyBhlrT|6{{juxiqFa2o7q^$1#cLmDA$C{xBGUxZ6_e5pK@b2=@B zDh&|1@KfcTdWr_9*3U0EGsy*eXs-aQ`P5?zu#jgkqTPr0h8m!m0x&sS1?ARe1Azwd ze|b9r%DqZNR*5X0BUCbP8L?JwRRb3vC(qGx#C>Tuk;}1^NLklZ^wy=imbPsMTBjF2 z3Nz$`DR_EjhV_{Ic7|G6+{-(kqc(DQ%&l3EVCh^>wP)(geGQm#Nt0=)ITe1SNP0d7~#P=cXXFmtukYM{&Gf;#K|JXsdX z;vGjT?*-V8=ir(&QVlzp!TE{T?t1Og$HkQk0k6Ya+FWLXB-yE%W%aDO{p_W}^ z?b27v+$Foh-2j3j_6{8B1Lf8muRkO_l8tixG0#_WmI~7DzKx;mexAsnvLgf1_P+#F zEDeEUg4fn-k<0N1-&g$Pdu>A10%<*L#{^PtUuW)KedwWU3KJLG{C^Ax7Ym zU-h`Z_FEb`lII2S6M=-)1F`*rW~D&Xes*5&Arb8Xp}xV?^c-JgX#?iip)&gW*^ZH> z!e{1&rO8?T5g>Wg-WIcgh@?aIH4g`KT;kcex;xmwCSd`@ z!=b;HK%!8I-+@_8-b|8rK>=YDN)7DbJ{L*d3(E8hZCoJf<+QyKUt3S4YiH+F$IjzzNS->(szXG zVLQW(NNO7O$EgX|C1=x>($e~9|BZM8w}yUpqw2x_GK{rTIw)7vU&4f*zaDx=GGYoO zV~?9QNb2b$HWDvxt>ru|DbJxL4}k?&{7{t67!CbB*4Y0ALO{L0v9Y5xEdxS5q1Q49 z@U`K_L4aJrKTg)83A|193q<-^g+RWIsPoam5{zUshfb-)1xr#V+vE472Y3inecSYE zYJ23QKJn=-i1Sw0qL9;Cn@T*^L67tCqX%MVM8r43lR3_lDy%lb1h1Vl4d5=(k-Q6k z#b?ycxv1~7r{-bVR1vGu8E%V`!A0m~+BC)Cgn?A%wVTvW4*A9ll*I%I>pyol%!k<> zY6q_6o@}b(FppX@CrdlY%X}rSfKKfAgP-4l{FPMi@S`>TMCZ~^yxh;t1qb(i#y%f- zpfXh8c+nAAq99X_I1&Azbu}J-`v}*6s`0F0Tcm>e3^v~eIgo{GdL{@l<*)ZJDfQVj z(S?pndyS8I{fBztTSwi$neP_4eGfALyZRBy_i-YbmnK;D_ISuG$90$BSTTJf+!p^e z+rpVjn>x&uk+iMshT_QoXp@&E7?RRX0w5NyUvD*n=!e6YnjR2 z_vuuXU62sox!(1-@Q6c@30Xs9RlBA8gqj?Z)8!u_VklN++j)Mf-F6>i)UktE{ljrv zSFRp>u#9lm>_fzzbd@3g9*o6I%v{Opb#~{|)ou&@W(<<-^}6(HHE0(~vlMads3@B! z^3A0LRJ7!*@X3;gVTky6bRP+S#6ByWx8br*2 zi_F!8-!dAF$LeYP1K&A5X)X}IfcEk9kdss@9jN6>ock$Ck)GZl)zamYF6-R#x(yZu zw4DUvi42?Ki> zPMavx)1^bZo@HHw54z(>>^O$;K*iB!EBiyDoF!W#Rie))R8uXj{wEKfcu2J}k|d~& z8%%K~d&05nIdpx~{RC@&r;RL-);dQ)6QsfSRI}g`GlO4)>roefo=4|$+#%`o#<`v2 zEzOs<@Pe~A9tCcW|0;4GNhd}Vy(t?p&=F$W+RFY>SN2Eeu|ILLKmK(DK9LUW zMqSvSoXLJ-UKZ;+M10aGRn}9{4A^6n0K+HXOCQp1i~U^NGQ=PEO*=K8`XjE~1K&B& zvc;mRcD+!{R7PTd9#r3Z>c{0&4FjyU*?GWGJ;SG5!y7bQI8^f*pTBlw>dcX{49?(j zLbW|?hIndv)!n#vC^nyLJy#dgDU-?>lu3Cy`$i4y8!2ZN$q=yz6_AcS(%a{_v0bhA z9RnK(c#nVhX1rCf2O>^^* zTt+vRF{Dd^qP6_uzqQRF5v8)q_qy^R8Qa}UaD>-4WMAcATWJ*KFVH9AeuH!TsIkmV zK~?j0Sygilan*OcTq=eJdr0bCO?Jsqi!=^0yTxSzoO@v;6REw-0z~>H$^d`lyB++L zKHtE`-Y0c`N!K{oJu(x0C{`IF;`m{&042YaV#n;%WmBx-B=h^w_>v~jM9ZnRqc|N5 z#R$W5%34XmfJV(P>!6xg7n8%UuHC>qI-XI>RC<7j@q$ z31|blY0<{B(27Je;ZiSR(JOKEc@K5BJ>S3n6h3(|mdfV)>|_l86J4=N6UztI@f>t_V4kR9yqDMeaPVeNd5BF zU$aeqb^Y(#S-GF8`K(f^`>#CKlRyQ?3~f6e%>MSvW0@~B3`iR78^T+bSa%jf4QBmH zblh=`jxY`)Xd0Dw365rXyY0MK&wqJwg*)tjko*a;J3a3SVt~J&uup=lWYVrA5=2j) z*7dS9WcA&RM+ExCRoIWAV?3%x@lWh04`af9zI*-R3NJW@aRC3ooCZqXcw*@esO60R zBn^59@YE~kS&@Gd_B=m)3gCG1&RedF0z~w9z_SKl;J^hQzqtA)M6}^}u)@<$w@C

iN;QpH}#f=VQX14*<7;=L3jeCs%$Az48eTpCF;>1PKKvNGJ{f5J{DQd;3jD zhzWogAKF1`T;T`&eoF`)J|dmoLkS%qohhd?mFbK>Abv(jX3WWq8JQl)#d8!4_;rIr z=I+KE$zNvWYPJKjB8C(lC;(|6F+$~kxkt_%6u==nf9ycH4{hiSQx7|6HB5us82c!V zq2r<|iabA!@BBeZIylA-CP|e~Ayz&X@ktp>f-(pJWoQw|Ab(aQ5Bf1enF@je`;mOG z-%tniWtXn}g0THD`*F8ju5T{rM_%p&>&gLW!E|^V4iax10dEJMKQ8GS45v0Xr&_W?E1i->i$50slxrLGd z0)NDVKKZKXS2(~UzEDpX5EufMdYD(??;&7;j`z~>_!g@PgV0NH)CVC##P}Vi38(l#+OWU5y<~QU@R;5s29c3XfwV zBncI^gosQ^%tShjZv9b&+61df#}xo$jgaa^fF=SX1llJCqLP?c5F`kH%HB~bfI^@P z3RGBr5Wf9pKrC?rqC5-;-Z&z)hotfVB@C1iu~#GfP9Vbr{RVUDz#$CgC} z3>Kg#iC5_$Ab-F&w9x}F7#|TMj@mgg7?OyfO%hVsnEVX{Fc3;t2ugA|h`<2GD`a00 zjsXDL(M2`>8J+dNe(?x@Vl0+c&lF-&j>|9-@*PRksbXI3v5=f}K39-FiMJ1!iZzGh ztId#@d8Qt_W6(wo)kS&u&embZG=XWXf%**)NTops8sTx zqLAj%4N^d2eknn_82KNzM&k4TAkIVqOm z{ps^H{GTZkKRphoIt8wyjY`V^WYqoRtBEIDJTh4S@zu-!^{4;*_N%}B_3B!g!CpW2 z{`_B-0)PH5qkwHiL8gY?XSm||Fu(mbPyY|bF++c|u2x5w+tOjZs;YfCdH$TH_UF6J z^Wr%7>7UQZ?EK1qtFpsQ4nz9otjJL3nCM9r^31$GMtvn~&-G#RDm&z?WnJ;$(wwVS zT0&@{CqxT9;acbk(Lzsz7J8y+p(hPE30_%8J!#QVZO8~hqQw?3o=}q+4wKtB#z`M| ze`yh;Wly651^zZcUlQEQ1YJT*0&57~8+Zul6eJ@wxE|Vnw!$9~lbaMUT}W>uw66(F zD$xfh0CWI`6DAb#=oWKgw4KBFmbskxM^g9<0zLqqdYV{2L*gUig4J@1b^F9I5d;vz z!UC~@d4}43q=J#|6WV>+xDY4OF{>BJ^-25jkCeaw2$ldB1qgulBNmDzruF!vka)~U z1yX6z#@`a0N`yHBU)NA z_9$nu$;8dUnn-OSl!TlDsf3!KK1w6x7NiA`jBLg>QQv3;486q}K;ThU55T_~#DpQB zqUtZ6iNE0&WYBcK{-RlLpKxW?BEg{Q8paJ#g8$}!%Ii2p`CC^)VOg{f=vb#t0v&m_ zPQqJdxS0BAn&~Ulu*+=zyJ}+I{5ZKKlZ0?UmzW}AuW=4CuELPaCq|eyCdPUUQamER zl1OCX@Wt5)T4?@-gP&yjgAps}3lzSL*ypu@$d3gH?2kx55CBq)mLkZ;9RHYB$q{;l z2>zRYkV>+Ec9;WHysU(eRYAFcwZ8pkG#WwPxSnjon2#z#Akn@s|A@%!XN+1lj8JFc zv?|1f8<^_BU-SciLk@i2VkKS#gFFPbdm&6*NOeH-koZ3lnOgY+Gzz#}5RO0*hcR6c zAnF>YSCETsy2S+~m{j2;au`-va1>Qz+A$%2v<72ih2$7JKoC&Lu0l+A%Bu7wBZD6#0)N#$=XC`V2pb1wtbP3Kz(MN(r@p zKFn>SfXr)wpP)d!e*q2J;tT#8*>b6;aP@2yw@3DnnjiA*JTDi;jrYk@ZA-_lDgR!V zvhK-9YVkeK4skk|1VfyJfsqEQp2oLB986>og)oZgU>X-8E|Wm^Dv3fmDx z=r3Yd1}R_Vi>PUhQer$&Yp;Bym%s!p-y2i&7!e5^;%XkD31RBQs)i+-Q)3uRH~|x|YW!Sh4DSXZdHI*RZYw7>@_#DkQg04cal z0wM&=prhg$C1iO7c#akf6iT{^qmdhsNg9zXI=hQ-?iDBKF_7g{GC88<2pn3@6-Wt4 z%n;=T6j+1~)WE|^aeoQ22cV)7B2GiHh>AW8ib^_Uf&>l+D91rec0a;@@t_zF;MWKz zRX{gxL%`&!!buFkz4d6T!+;Dovhah_m6ER*#C(|IrYPu1GA4sn6eb0b2#8=nAVCRA zAq;R0Sm)Wse zOeD(`i_V#%ItvdosK~+(MwJtYnT#62|`JAenmV_ z+%AbzEFK592uYoIG|vp~4)iK3=~It^PGZRSkgi1HU#*r`qEOL!L(5iw9ou4h`PG-&s-u#N z^6|3B@A5*DzfS9+R(-t6wm116ieP*zs+LK0Jn1D0<&|`DhaGq7;BhhxAE4?U2SnrC zMMNEp*u)C709~sg8(o+}4pr3KZXuo6lKtW&yu$-5OyxAY5rY;tV%+3L4EXVn`bbDs z9~2?=!;FnJC``G3eiPb_=r%lJPz+!R?QX@kV1EfRx;AFxRkgT@;TU_y^B zNi<66j34IpsLSJu9(F+Qljr*kz(=p0towM;;Eo7g)Iv&R)WifRED1a!tw;^;$gO4P zNpE(?iYUdGBEwLQ4gN14!8mMiKnUq05eQ#m^w3Y9e7P?9f!N*FJLI>=ysYxYlczn; z3jcR#LYaFEEuN^Xi}$fqjgSnjr&FUH7b$l@<^h5alMYlGe=k02FLJ+$cYVz^G`{?g z?_REsn>9=~-&|cs!N(Nu12JLhhxlDhdVQv>M~ z%a%q={2GcAOKh1lkjspagGcSX>dih!?=YYLGTXhD>i)-9SF%^i(vY5))oW<}Kem|U zt+kCAXe~w0e_hqO_0OS|^yK+-_53_0@h401Z~08Va_Z(v%_C>P>k~cJ0|9E7X*Exc zWGf+O_c8yDWv>)W9>vEG_N&-E?QIAfC3rZ0y}ePh4!c)s0!I1VEc`IiP)G`QW*qDL zg2k<=j~Q8xBuHAmZZBR6dP!t}zlL;W;UA@voNp3zlO|OcG8&p9)Gy6^ly2kr7lQc& z&J&R=@Jh{_i6Ndy)^jBKIcbsBFzFsj-8M!)1Cej;dasg`Z&f9K?{)SUBvERlNtmB4 z7SKNV5i8kpm-$>Y+Gs4(qK<#HaX{X+)Fgtu!l8vBcL_D3`oDKKpiw0G_Lz(h$wzVH z4^=NB4ujfrJsO>Gt#F`SVw=UiDwa{oUc_IX)!lRC9e?&kE_ zl}GI2DFM4D|4KN)Ya$rWMHuuWjuQHh&j)&rtkCx$6YZYkW z`>Wk17i8hv-z2rH7ILDBJ=C#_GSMZ4*d;pB%H09S)IEkz*J4fnf`a+qmdi4)U>Z<@RRK+~T>kBdjsQsVx4YwEo_|*CSJ{=f z0HiVedV{}LV6^g*h~qEWu`Jiw_VeO+5SV80hd{;ALOZ_9@7849@x@g_5y{07-RDKV zT}TxC<&f=H>p5bIB)ps50+k+#b50SFg7`()0Ydv`GlSudZ21omhp*<7XjeoEZ?D*b z=B&u(ztoeqS66>0PyP~(o`~raqXguD-y4Gt!0808GI@7oHnAfA;=IMnV5*kFYz!wR zzy_EEk>w5Y?~lB}ACU)(gPM4t#G~R0(i(+BF$N+@v17l##*@+$=F18ZL8r0I=^UYM z=l89x^u7-o8;Z>eSVMierA9*o)W$kEXdSQPXQG+9vD5cB_t`uRp{vPZ$ zfauKlp`95&G%zEI1veyS_zrG_Ud;?Ka=xwdya0`n8w?>G{unF?B0Eohu=C`{cAos$ z!V@+W>XG2PhC<*;BSA3b%k1#Ww|Vv#d>+Ngm&*r)!I?NxSwnb%Uq2FG_v-pblT}~r z4lw2U(PV!^^sf0((*Sxb3<9A)<^ld($z8%Be|Sa!S;wLUesQHZZBJgm0SLT;!C{US zf^Z+q1mMyELvfkR*_`Sj$Tf4ruwd+xsc@c9+ zTYAW%uSdWa!X6uIAd}{OO-n!lg*O6^jVnL+ZCoJ`9}ruhAw5-OY!VZo#4v#|-dh3PQiiA~9b9!>VXCeS?w{TTqJC`h$4BxgHSQJW_EV3VZ5&ibdNDq z<4x$%T$=gTrH)#)(T65ClGs>G6G`PlW0jeZ%S@BVv@z!U4~j90(6sBAul**u3E0TA z3y!Lggg&BSo@9O0qK?jFUJLIoXI(Vv2jqWPZ$CudH7T3WQ*ys1MSHC1XGz*i1Ot^U zmr`ocNgoJ@Xd4)x9116}X`HV~$sR4Ju!m+alrF{8rk6e}0aE41VXNd!COwAmgj{%< zWT%BY-+wsVQKiRk6dz6TeC;~~C}hLcAwi0U3SNfhQV`csLBB=H0N^}E1}&Tn9!q~y zDeQ>GlD7F8+@_{!8R1Bi@O(&(R>VhXvn(556U!F3R7qQl0pi2!XNy&#-7I>!X)@K? z$sbmeUELgbiVpbNw|8{ia$JG_7Ek7gQI3R($aP{H33ssRZj&Hpj=RgRUtEPr0v~T) zT#W};9`Iq@Pq8)%&DOc(GFT+0t7m_>pDMx@Lo(y#;k&@qT zlzd$}4C!VF4AtvrVwGOcjZlVtBRitwJB(oD_}?3a$Adci+4pvt0qy%aM%A<`$S4I} z_muA{Qc%zLe)RsiySZ6!Z@d^;cHn!96y39Whiew#j~FJFU2lhQdEcayn_M&p*Xt6` z#XPf<)?6?Vd}gjTHhC03lJ$@uJGv8Zo0At^9Rb^uHC=Ik??EYe2P8^xIUJ5!HG|Tk zv&N$T9tUHXwvR@+C6=X*=C-_N`46M^0U)*KTYLgQG$nyQ?A2%lH_ol@i5nm+bU#e=1?%|JZ)@mG+_w?;qw=_e9G%#`!b8st2C4@%cAp0mdn&sm#ze*PeaPZD zGkt>38^m+=tBL3Q@x^oACZ1pX3gS68`s0g#2JxK#YdQyWQ)zzDAeHk+cMePmrT1%h zyGmS7?{qEOetY?hYsA;z|1c3DKa^X~QtT6(Jeqi=0ycc=E$Wf$7PT@lee?1zFLtu<_+GPVUxLQ_0iZ-`AK;j?z_96h7PROST@9`lZW zdNS?OlW!dz`Qv-;NAWxii7c_Jc88a{<UlRUTF<>~BB9gb~|?GMrz=rkCq~DW^r4n8i!_T8q<#TTNoBS@(+fVhkr0^m&0=jWWR+sM|y=D zycHzd`>et=s9Z@4vqjHUus9YH1&?EnZ!+<<1@US4E>~I7PsTb4ux#NU?Mkd6- zw;>6OOJirz=h5QfEe2@Bc;F;DJchm+lF(Eb?i(NBh@)W zNE-!h!bUzgfo>YPRU07b!HJ&yx2#$;10OorI+Bx-?eUofR6O?arf*%dedVbEQRXK0B6qqk=Qv4n>XjpLqsqXOn-i0d@9=Ck~~R z$V$tphLU#_rFe!%DCxm33=|m9=Z70Z^o`m>^hGVfJV%X>tqtBUCEl5jt?4Tbx|^j6 z4~Cf8JXm`E`@@u;8*=WCicbQHIv6I!2rW#4A=An81N6}n(E0R#cj1eCp8*i%3Q720 zEXHaa-H|t-X{XSXih(>*hvb#LKhV=VSh|C#98&HRM>mj5jpuej)Y=7@t8{{I>xEaV zb;SnpI2l4O;4`Bb={Qbr!9Y?brWG9(7?pkyH3tSq0PGp^RvJFDThTXa$fIHKKL!mS zqva(*`G;sZ!vP6@$4Q4_Iz$J7)|ZkYiI1d`%&PuUAnKCz3qEK*&BoV=s2e~7rIQDG zl9WEElz1pQF?mmjv}Baf=Z4~nmH4PL>k=FbxK$Vi8y`MF zYC1@!V~NXR3N2nZe>_n!x!-=tt*)@J;*mw8Mr}`xM1|yknCkaguddI30~Rr`847y{ zR^XH$f>kTx55cO1rPpAk8PwlkCV7BS`G{|MW3~IkZkAt0F)wPT_wShNIFqDL%+&P? z+sv(DhNtwOCH$w#TzeGIhS{LHyc`B>eOZ@WQ(End{bJGCY3IJJU=n!KUmkWFn0Lcm zaFKr!ydFmnz2J55w1WlI=BiE6mfxL|s$@hs9AYS9=X#1hr+N3%nfx}TGkQ$%yhQXa ze6!{qh!k}g{~Uf;ausxyt6y1=e)l;)T%Ys32x|P>lO|;=247zThQCddS7ls(EBS`< z6y`&j=zRYBMCbR34j1NcKeUO?m%mSR{v{?l-+o|be*F7H=l6-uZ(*YI#qSfHe~pRG zho%8P`+cJG`$Xqm`G#jqbkrl6-A)LKH+$lbAAex{>9;vB$aCM}XmA^n!*@|c-+dSm zV}~{kv>m<*0mgDzVKQ1;;wUJ8e+Up?l=5X<><{{lAOr$SkwOF)MJ0XmYz|-JcuVOH zBI2OX_cifITuSk$G4&{7;&V_s!>AHpUZsH4Me&P#(0rOrieY)b{*v>3UW!sR94EIU z+E+v3$)KwP-_-jdA3TSAq%;RJ*e{xT(QuQtcE8=@^UZm8>!F=SdB5X-=d<89x}cEa zG1760-ikkrJo->{n8f_BYaCSM6l^%E$nz`cC00Y?yAG;kOg+>A$T)S&L5$G)3`60F z;1SpX%?-oKACK`UExzhX(o%95iF&}`#EcRT0SEXFdW>1*faq{UUY#A&Q3ui$4iZw& zV2p>JNUf9>AO$`Lq38#$hjpu^Pe<0Uc2c zppCbYhcg&*`U=@Xh{VIbUP7PAjo7ol>mGew zJ{@>`;KP8#(}@v(judDVK3IX0if6>(-*|XS&YOA(j@#7320~Gop~4@@`0Y0-Sj-fs zPe3l=hM3J)Vv3KEDPaN)xCp%wDyb03z*CPy;)>!JjuP})apd9q(m3ewG(1o;pa47{ zvqv7W*Ab4NKEZtlbr4#;AwN@3NEx;sMNd+C6g`%YqOMXz1 zymqV~v9g_7;$vx(9d6d!30^ufN04-oO1)Kd&J9ofXxBH{Yy9gjFT|DCwmXLP(f0>X zb=IxILDQ{5!q-jqnzll{`lRM{zxt$8*SXOSo?Uv0(Neu}2J(GK$)EFl;b9EB-?WhM zKztS%;aR_bJrPmvx&F#x@^}2#t5)DoZ1b}GfQ7|=PdSi;rP>|mt35VIw8tVh7O4Lp zXc=$2dv(b6c)bgMOW3#}yUP#N8vHVL^J%kQEXbPyn!tRA?DOcE?^;@zUyEHq_{(oc zt>^N+b#*yMzat^@LXE8i-3IQeJq(@Y+%x*X{k{=@fko<@VwWvYgp|uzQNGdcVmX-0 z5Zk?Uaphd1T#F-8WrvEK&xU{IAb#XVhcv&(e2*RAZgW@KFYlfip+a1ZZMwhupLh`k zv_=k|+hOx6JLF;nOE+C^irp+LT5r4je#_<*j z;X8?c*55|328p|_hz%0RZz*g8lC1}AkbR2pr2Jn!P=o8z4%Lo6wnY~P`Um;f2XWi) zw&nT`?S6#<&KS9pNc?NI0c}s-Sdf$dwkP2a%^cnHxc*-l^1}N+-ghu_&MR7gwUbqe zlshf_f8_A*!TT;~GVsO#U}i~(rX-Coq1Fn2Bf&iRjs#nG81&}#u;?AFhs}?NL%yxP z*cH12Uznz7+s_g`!cKbQC2734JRYWZ;b3qZ4nRE*A}<<7xX?xx>2RejjzhZets0WE z?1-U zfoQZ1b62){LQ+g{h#=Z-_C9$XS1u8iatA@nT z|0Vzb*n9WyrjaCI^!Izt_dh6_U1D$S#PTB#Cnh%}FvBhxI3(-DCfXNOq*tgfzq?yjn?uDV7K`r0yb@mlI%-u0`QeB($f>MtTy zJs5fyyN8P;t0gDRTDbF^0JCe}c{qFgy=**fAnNwk*0{6fz&da~pu-gOniAv6-X1$! z$e?X)L3(}5BHu5hdUm$Q^)0+9+uCk_sAEx!v%uS&7lr~YSiUXHCoe46Zj6q9R;W>I z6B~qXps#J#7j9|*!xr|1X?U4zm17QzkBh`b7yA_EHkvR5Q+OnN$EoXuC!Vr%mQ#}S zM<`0MgAWV!-KjtE?1Y};{-q!Jcp@_qwGJF!oMHisDP1wae~*Yxg}bFUw5J%WpUw;p2~SI48A4nW+(MkaG`g zkn@8L`oRYMV1vYl?cAOXa(=KurPv_n2OIR)XM>zlY>@K}4_vwkDtFH6j#U0y><Y^VM+cGd5XOKhD{O=WPBK z^y94ktDLob4vWuQUg&F`xf|ROU>dH4<6JuQvd4=KE;G}n1;w(4tHX9%d=$1AP z5(Zmm<^bx|;YOyad7>j9tO!LgCM}F$$^$}9s z>gfE}?T*P{)xcYD8@oa5UwU#Fs__||as5;_n$14k3kZt|d-1Tbx53iVd5-;gr)2i8J{kHPqgPg?B+Kk+8ioXE#kpBv-<3CI@~u8rTJ9jINnyh} z^b22k;H&F@2EGK@Brijwrqdpy$G;Y8auA?40M|huEbtA5>z&3YbXd7vLgm!Cy~?Sx zv=2YA(lr6#-gG4$p)8@7;bPSZO$k|xOI3-YDUo}yNlk)_`!A#;`Kh(FyFf*v&V^;% zMvxse?;=069rvQ`_zGtfKH{!4JGk5ApHciF^!=TGQP9DUGwR0~^*?+@H9P!_aysIS z@{$|#o19UrxVHbNjwnLdk0a{)Jfc!s2zPoL(e?>^RT{YH<)L+VhmkvdjuGGg5=YUG zo8|wKo8_-_$_PP-qA@3z!+b@iPMeZ~kURaKI%E({KhBtMdd4WXb~o@paz9SgO#004 z&co4vB8LQMOQO0SNYv0{Z+a1r`qKYEvN;r%Viyi$cY=2yELZM3o&OqVNK5Y8%XriJ zfB!OmveHy!AdgFL91Q&UIz=Fv{QoXTYxx)NurkWKiV+qD_i9m)BH=T|0tSIS3FhIz z(_Bd%Sx;~jn!SN`Tb<*WwuBF;WB0vhxz^Bs4}mKQ!fTTUC_-U>5aNp;DA?B>VX@pp zky|m}8PSiANdeygD=(iNAA;1zY~?aCH=*I?FVPShha0TGvbiaSlXYkNi(~alg$!uXy9z$TPBk z_I~O-I&2(0wjZv+yh1ArqSPDxuqm_0pnKtxxs1`|A>D$ug8EbUvTt;_<|Gc+9K{BL zm9>nUXt7NKucBFXC2-7V*fK1{{v^6sXyoxqlrFaNNL#OcjQK@p27#AM)J7$l2VXMTXRQ1B%-oRd*-Wrg$Ulspzuzg7@h?s&{T(i>1}FM%yYyWvi4 zL+~$frX2c8Jn|zlrAc9qm%12VqfMLePZvZ!4!s+CKsx@Vw;KnuZgXM0sIMn~YB)j< zu~Vprh;x+>JH^U}*r;>Zg28kejZ3^?AJ?0tmWIy`eziK3hX9#{3{&L#l+;%^!D+J^ zoW0OHhlMdR9z#5jj>}4B=d0?L3sf{~5piRHc#(cITnt-M7N#8zcqgr;xIH+`%B3to zYH0>iGYe9#bI%MS&?s2+`*7KRwJZ#}B4UNCo|QCc?UtKp7(f<$)!=yXDB|<@?nb~G zD-HeWlT+(%Mlg@g?r;du+EQb9b@C{85DJGW4m+cN(FI$+s9Vui_Y0nyyR676^DGGC zoAgN)^$rg(sjxR9Vt!iRq*G?r$s5o+XIzQ0m8sqyv9?Mbl-Fmei6Vl3&mcK@^v{)E z+`+(`!AWPWU)12gLBReUdhqvW{O|BN`xkgsah495oqu;4ka62$mxltnWz3_2ThbGv z0mzPHgYmS^$>N=fWM$3VsyQqG1J`JYtuq(iGiE2eSchh*AAB?!3DdO6!x9>JxIHl! z&839Uau$cm4x{>uj@@y8H_vo|K_p=5$5>clk2yo9)culr2W0H?RpbrJb~%sGWWv(B zRD0CA%6p^q#VRO#3+z1~%xA<_OK+$X4=3L=l3*YTr{$~;$`OVuh7k}=&)!Kc8#*LF zP#4)pHtGJj6rn%IdHDB~!bSTia$1^4uB@{X^qLDOiCoX$mw|Q^;7b zyQ*8}Ec95-$*`XZmf}zOR@H4GQSK%?F-u_bt9QHmgIx7uZU!zyi(C~4li3)^zh?*M z=ZM8~Pi!I3%eM!^_PA{G_O;!UovuOmtkn!MrHi+H?fJ{X8F3Q5c<4eGS_ zddM%hBGME_d0U~nz!P89h3=>`^v?JZoFI0%3w5?wPadg%5tIT3m(&L`GvkYTsS(Nb zaOs6-LFC=(5P6%hQ4GDDL8?Uz!~8ePwlKS3prs=Y&}iKWJ`Oa;PI|b<-hQ$;6}0%4 zIx3f3;Ow4&Zfgie6}@adnlDoL)jJzX|H?aqc0#@y`1<8}>4lrSHV>)1B^uIk$Cn@j zjD6%k&`6|zEd~Peq30p|u1LMrcVm#*+CkIAopGm$F>sq(9~=sxXt4-nF^@zxuFL#7 zFTiXf>0+A<9XBtVJI;st4o1(#n{cvU!CP+@8V;MnFabL(9w7@D=b%RFLx(I*np>8$ zgAp7zDSFxFR_q`ctxk+KF*{_ALNOQH&C4bQZ$Nv08rF5pVJV}ovP#V*QxvBs@@FqT zVC3=r&17f0g+XPT{8)vB~V1SUA0oEI{+YLRO-V5hi2Y0x;Sw2RjEsX;Eazt+>S^zqZM4 zwZ)8ou8OU$s4Fy@O~L@06q(lXPJ`kPqNyvkdP()lX)eo=!j&6Nkx$G}L*!n1?)OR# zZJ}0fEf_gd~D73X>u`)n_xC;4_ zq&ad%FnyP;qAC2YNJ8*qGDwqp%+Ma*=W38kB<8gq2wOSlyvdn2R3bN6=>%AiXV*K( zvQpD|_1Hs&3?w)lRxx#pkIbomF~v(7<+Y(shfcw&zTWmKlY^DTCg?@$nbU`*gvu2?2XjFYmXR@o(JxWLZ)*K{o^ z7}&J5JU#a>7IM9#CUgAZp7mot1_qtgn}%@}h20)LqO3nx@FxJMedjs9U(Mh(Lkkxlwcs zt7E4DOzI{J^=sY8lL2`g6WQ8iaI?6++XO6&>pQ|M7IavzlQ4N9e@iVOC;w4si0r2; z5_wIoxX-s6(MzMQKUuo^3hzggAc#l4hlUS^14}G)Jp^MaoSnn;U8)My9r{5c{u;Ca zR6>IjwQl@MhM9-(bY`g_bx15#J$P9$&S><5OD_xo{t9WhaLHR4)XT2=Q{oI*a*oD; za|!n{W&v!8af_lQe?}gM^PGWe{qeyI3Q&R{nov;w)L`gMC@wcj*I5t(9eYFm8O5PL zlV2l*H5<-LzYsvB7pY#^=T77AEB<5_gt0q~cdwv%ve4h(* zp5f?a05D#JZopJ!6V6MzklxNO-guT57A&(whi>fJS(jX;f7ZC1*VJM!vuqcgxbAE= zPKe81tXMsu3Mt4imfR1K@4rFhE8Gtk5!2Aa8-{#p%Bl~JSdH(UoKVETwvlgFM2UJL zOK@3)-Yf$v#`q8sK{b|PRWIxKXqjeli=KEj7$bv)s5mk*O?&`H0)!B05{U*sKQVY{ zjvWRRmLH)3e;aUS_^^5h^S1e;aK}>QrC5=pM)13#iC2nrMc@8BRx9|Lk1FFXqPzvdG-^5PiQPgFv3Gx!mj`@>%k ztrOmcCYLQfNtU*Njjqw%qaK0#M*3#f!f^auNqF3gf5F1zrMdXQY;(bb*=FH`*|vaW z>-LarEr!G@KFGGd7nE$>8AhyIK*Epq?*b#Oau~7hfJkoUBBPM^SnkEo)V)9ly0D(j zCijKgkHMDU#nUHGPH+cW-B|sOHlZdvLAlL(8;;OTPHlOd1LI#%>$2rY?u8xwBQk++ z@-rCue+WF*x5x;-LF@tMK>oPJ(nt95b!PO{Y={w>LBIlBgcFoy0sSHHj!`tewkpq0 z52~hjUE;j#g_`4!VFE_uhrYJYbp5Xc*i?Hy8Q5yMYPFY=PmV(K>3S$}AghJ6QM zXn$~+l!Hzbw&|u4`M?Ig*A_oy9?tc4B55dZe<+e=PYkEF8Pt{CKowh>&E^MSN0}-U zJtL5AZWEBRNuCZiL570iG@In(VcWucZ)n(ZP!h9RTf`{?QSVp|fEsfJXpA529oT0< zaO*H#WC7>hMCU@#7Qstbz<804iblLLhgF0c%O*KYLQNrE_T%4}E`K*!0g;c{+g6j* zfBKtr_l|8}Hgmc9ud`BKdcZD)vBkN);*C#RA|b13RK0VL1ghqp6$Xa+yIK=J{FwY# z_%XS|>R8LO0%f;R_ygBx4OQKAjg(DEk}Z|K8P z8Yiv-if?H|Y-U|u5>;{NdCTF7buHg=EkGHzZ^YRle;dKm z*qh{FObxYke_F)M4OQN?l<_7i=blMlI>qWmvtp6T#Adakm1JskHFYoRGxqj`R)PG? zynJyiRO!{#lQs4yUOhMm&hpyMak|&m8)C5!>bNI)YRCzmlKWlyucC*05Qx6zt}EY zJe*H)4s&ZPInrSm%!a|$v>pc+7veQ172p}lkXext@BtW z8~#HJvL9N<-gIt$@`1po9(JCMgTZ^90udZC)VJiX`hVt8?4SD>9hf(8e-0;K+@0GqUxJBuK+j$>5R3wD z*U9^aqU7h~?)oj+t7jeDe^IX|Gar2)V&F+b*R$Zt3+wniOX;6iv7pW!0r6^zv~2=l zPC0dV9IFtp@^{qvOAk&fbKk>2?Uf29owAq4^vk@@yC40iE?k`O142tO>}rr#Co>r; zeubaJ6W9-bdl5uAJDZbjsby-Mdgsl(Hn+8z`=Cue-P8s|5Pq~De>T<|jmCm4zN5o5 z(Oa76Efqa@Ej7S5cR0Z7I~(Bj-3{>V9S-o*oel8Q-3{>I4hQJo*#O0dNkUs$j`UD&-I{`}{fQmvLq_O(U9ZG9lnV_G@z&W5Q6I-(W6I=)<0{nQ> zQnZSgWAp^v%xZ=J-q@WEa#cf1D!~%auIsb$JUM=kgGjGB}HiuyQx}cSVtcj3)O~A^5)uI^6dFs!F3;m{R;Uk7IPcMeob>m`q zT_;|%UP6tYO4?TUAuD1!Gk&qiKI+lTV^QafC&c3Vf6Rk86D#iSu0cgqcGGxm-ZWm* zrt!MO_9h~En>@#0rz{)o00bDy_RZsMlfc&Oq+@flbaS#}Ol=ucjV%}(FxEF!H`O*( z&eqM=%+@p1YGkW5O!3OU#@5~{vl}>kYj1tst-Ty$8Qv^B84N?2%;M{3&we?)bND}*;D2j| z|1H7)w*HmbyiOVNY4W|G^L2qM2OHZ9zAk9xAfvtDYXVjdEZ7S=MX|4zkt`=epWaV! z1+MrqETMFPQoieCEi3_&zvhDO=fhy=3IC8dfAaHSFc%K6th z#v$D=-pPCbaPA#2qhL zekiWL(HN1yps{kc>=`6-;LyeUeX(oY7+7M3c`~{n ze-S__U^J9HQ+=-&Ur}+JQ6@R%ctY-26o3YP&L^o$nu!-h?uFQK$O}6&@JgIeuAr$8 zHsFSyYp$1k0mBnf2qTdG#$)nCiUtQ`w4s9PLo{Q2c;bb=JGPE_Ef$RkTSvp80`TNl zwgrMT4I~Xm8JTer<2+bL+^<>@*l1_Ye}35y|Ihzp(f<_C6>Mb!zgT``O+9?&hHjbN z$a1a3Di@YiQo}uqV3uMJRi9`H>V2HSDz-SWrLco@yHyZwMg&n}&fx~`^b)!zOQ#?h zqqTD4xjFRE@LdVT^r;R~xc9M3p1)bulq>BicLSGw2F8GvTwysbkFSo$Y{38af1|lO z_CIN_VAxGxl7&m<_jiSXC*_=MSi-y#k(i_-!;NO2l#B_7!E}ln-f=Jl3KJOTYF^A4 zjxW|n@g#8pKEaZt?ptoj<*>9-q8u9j&jg zi;-gkSq6ieA*bER<8{@o4R4Kyf1^tK8ykCW(y2BCAFWMNt%bYEifm z7buGygd+e@K(D_fW-!E{F~%PiU%~Zt9n3@P$!~!95cNj;DbM`|LtG6f(u25kL2SIV zmyb^reCd&JLN5-lc}^u2A1KCfc#>Lmh!j#a5s@J~p-@bA$6jcnT1q$5tQE~c*nfUo;pxMyUH$hri9UwnFMs{TH?BN46agBCaJVO2kB7Yq`EKll6AOiIX zP;(RCH_6a`ZTz~22S6d3tKz$#`VPIT9B;Op`2J@Tz2LMQtG#VC@udp-`+q~dwS})_D81FD2bi0i_?)O2=+oLt z9{hFM(%0{neD6nvWkb*oHUp)$DKX|=flbeCEG@8yDZUh^9eQ(--W?Wf3V&)dN;rju zyM&SCpTA$#_5}<~0VQsP{8asU1kAGXVgj32Tvv-LOZYp($ zy*}p~OdAu?mJi94+oi$o1%-|)c%S4{B6j1sr1w9uoB%p)&MY^&vhNs^6`v~qVy6;+JvB(A!P z!%Yi71sG{yIVIPVd<|&%gMngt)inwqmH-{4{yPMF>Rpur*-=A5;0%jgWC(9Q8hTV0 zPONVw#?Wqi;9}w172-l&JXYH;683&pO|+pm1rvf$8+v zX7xfrx9MzTu2%AQxJ5jM@pv}nmlHe&j9M3S8UO84$5)p(ermP0+_No(MR2yZKHvlV zhL!lVP#)bYZ}F8E`Zx2CvB*J2T*{xor{fNs={xA#zPUr<&3_JmvA>BaH?;% z0oRyfk-wD9Eog@M``3B3x@6Y449FZo)VcInPsGQ1R(=%XBh};{BsiO>aEUq2d93eW za=Z4T)G6`Ci@xp=QGAk3gA{zf2KOLajsp4Aww+GuK#HnvicHVT|DIR#FbM(s{P*pH6zl9xEU zjT0BR&~s;D&qcm4TOc29Z*GlScpx>m+bon=n}rf<@lax|ab4!ud4YNp1A}28F$^Q- zBtfQb=6`XK{7*a5U$nylgh3AlLTN&moV=cb_=m6D2Ncl53cU|=FN(e8h1Bd0V-_r4 zfsnX_Adw1I$zb=haVnF6p%mILmRgMhMB)dBi4u#4a))vefv!kKiSUz>UJC|ZLXuUY zKHc^(OZsK;NlW_AVnW62%D4a2}0@RBnCdM_bxF!#eTlg zWkmu1Q+k<7w2p@tMO64TA3BOmA^B7c-+d$fL*C9GfE@%flJMT6b}`%n_PjwbGS zY~h|U!w6*w8V*X1TOfTfa>F=U55fxrAbKG-{s_@KL`b-r+fodwVNFocn&rn>H1hGJ zr)h&C=iVS5Uqd3oCZ?C4^ww-1&H_21%s0wk> zWkY`r)n4k7=o$B5>R!73n0(V6kgsy&PJAJKD(6GGfwrE_R%MN?n%dWK{N`kg6TN8B0t7ww!s_U$;s0rgEPJp z|6=Nzy!5>YVSx=uD9Ysh6K1E-fq$PEeX;AlB@KrZLvPh58TX~j)_u3h0{dw3KW=wv zp&g=_pABZIk%7)E$x(`;CCr|Lb6&Bw`)LCxJ(~p=`r&u?hu__A?{_!HHq>}Znez2h zlEtYooRKnsMLwI(>)!vd$T~XmU68}?idh%2jh+#Yi5Ao>`cV0kP)S#Ontw7_4cU3s z>gQwcBY$P5zUpB9YfTmpNx3qQIX9DXvHd^9j($IH3f z3k|#d&31TIN+}hW>OHDjm>-ECyiPw=Nw0nog)!`qkMBxMJG9ta>aY<4SFieZPxgsc zM>Fy0WK2BT7#a-fAb(I6q;+iT8fV0oEi{z+@H_lS530gz`eWE70NWwGpA$`Dt!rvo zY+fB@=jtreById3SuHFLf6jp`siT?%Qn&f%6>oeS2um2DbRHcxjvm_&*VrSeEO(|k z7UXjvu6;F8H>I(LomV_MOW<-`WW-UjnP#9E@*4U4zIkCFb2SC1f8kAqpaIr}Jg{;_u+ zYYF@)P*TnU=x5SZJyT9$0Q^uQF_z+=Bx$68EJ5o(bhqL(Vt6wiR07RE4yqpq)%UHm z&7K_DT>YS8fn^N`m5ex>e^Bwd_kU2a;JbIBu%!p}SAQZHFO06AdyqX5VSZWfbi%%IHEF0LlRM#asSlRaN^sj)tWp%Hz=N!H3 z33I1&P9AV>rgjCWmQ=Z>#!*V$DuF7;2WY1ZQy&2;1Tu|8Ad$(mN3XQm)Raq%Bs175 zsRTRccz@$Ra~xCTj8;*JArxhlVLT=<9RD?Irn$^m*G$vcBdPh6u^{SUz7+3rHzs*G zyG{Xvl4EaT*eA2ODfz*R=QES|fa%531J(R)gol)_Gm5<#F5jtp>0gkISZHSojD56R zgZcx7)z_y^7E{0qX5JLjnay#{S|yspl+~&fB7ax{R{efntap$<+1VOzwut*_v_Bwk z)7rK$Xfu1^)nK}K^lt$iMZMjor{4`0{Tmo1a*+YmS?#6;3|prS|Hkldy|we{c&pL2 zw()fn`l%33CWNPox^PuN@5dU=56n-6;-*6JQqgJiS7FjcMdG0X>a*(j+KW4=s0$Aj z$5x#NDta527}$CQXtMAL147g&=6{Ujk$C2*Q`|rnD#rihqVokva28Px+QZ>?GAt$` zZ{{TA10O^>vMz0Ttd;M|0fMvD{s8Q{L!(-md z2kg6!FeCsFU=I3gtG9^k@%>_*gI*`t>uhiix>srOei7U{jUPWcR0fJ*4RoKfW8pKG z9UKcLwYX@o4e}7Ie<_3lAwU4Oah}=;Co~9Mw>z{j5%i|DIi`ML{Pj%>{nKm$x?%j# zG5i7)QRWy5;%yc*%WAePhFKgk$U87#42_PxkqEKf7$cO>6ZFSmgxoQW0Fn{SI3{+R zxD5#XP~WEapoD6C@rmz2p>OmSA%BTX{0n~|gQeG#Uo7h$f0knN&X!_RU5d@`ekpat{qRsCcE`<9d%IlK{S;Or zgurQz`PgV3+l}F$Eov0o#0Jq}LF{a^zK|6H7`Cu4Oxwbotp&=$qT6W2qC}I2Y;}$k z@i1lke>(CbixCR^8INIt#xwLXiLXn@x5>pk^yrnynH%{7OGJfVSEWJxPrdY!Vr_ry zPA}Yxf8?@Wzv4Lyv)(tkssl!WAk4yG;CaLK>_ZgEy_*Mmer0U{$n#<9$*JTt%+=8T zHK#_)T;t@(P@XT1a&vG(;yuj6xj*%zkuusdGmZ|<0ecpT?4*6c*`m3NV*K~avzUcP zU@<+Sh0lBfY#kEk@DDi=6%&a*cqgupZoQz@e{&GfEq8j2Qoja93WPV%=fu6XrXG8U z6ncEhkWd1oCP;K=v+*@0O}(q6Lwt(FH!RD&fUeg~YL@#{1;I@C)4A7YG|I?d_#5K8 zrgZC@OcM=|s@&|!X09?RtKZ3F>Z+uPI|u`VDv8o_R7t9?$8*Cz27vEl>}>I#TW$I) zf9RU9AFhbI6ppV3J6`*Wh^e_ndOdRGJ`KIuz2Ie^^7YVGXm&t#??u!i2b z2mIE+bl;d{Mz`CPl!m^-*7PFj?QS+GrNNT>lf{e{BS83gY-gD(1tBF^th6yCZ(Ufk z7_21`S-1jpNBnpjc^05`2t@0=0({;Q{U)-&m2DqvB}P|0~nf4b!D z7aC(4h9d2Y?r}&nYQ!pV*FFiRcoeC2;)UbE#*cnE?c=2O`8%O+GhG0MVQ43#;L3t5 zE11X7z-=e#UIu_~Z~Fr{QbJdtP%di3Yt(0975HstWi?X)@4L)HXQkL6iUu$JSMXMo zHEJ(<1hC9d(Y~6FJ8igG*bkr_f5l|s12BWG-o>ML6@N+!glxt|7|dt7-xl=*Bow*B zA)eH{r?hjT1)+$nE2nK|b~irAEANaqu57Hcksj(qhr%vp(*1P_l#O&53RPdA)i>oQK zRsxaea>Tei>gOP8pSgHk4uZb;Nc%KefUq=@lJipKij)dblYH%+^e|7lX64l^lL^W83 zs0RNFL}ilw&{^QOR5p=dt9mS4LLSam%NL3@r--E`W4(u)h{xE%EyUx~1c2{bLe7q} z)MCw6D_E=sT>h6z$fm`_A2SZ;)1fmse<*r;`NN=cw*mZ&MQqi;E)S+!J0D0WC3Jbqf(Ppk*X?ydPTDaesOyH@;{oa`}}e4}DC_`U~iWJ>)gVeJBGS0LIQgi>4e&=ApB zsQu-*vGOP9#QzA#{o~~1OwN?Exj!Bz=f{{C>ST|PV{9UWt`f{Zc_`1_X^FG_+?_6Y zt{0r))cr+xe>PSR{d+suSx2Q0^`v5J`w)PV4V=G0J|*FGx`(e^D~gZrN3d&ECxX0jmN{0~Ej% zEVU?)-H#Tl_N{KKCEsK+dC&${&fGz(Qe^6&Bkg~Sf6J!93yygyf_Z}PE54<5!$Nuy z!zxcMqQ)X>kqGs-)z**C z<9?*Rf5tTo{PfAGb#i14+;EsPW=RqE0Np$~TMXW-lSlY8_4 z5<0bE1APBx*%oFm)&t%AX`%jT?Cu^IrrKTNnV}h?dwy(adW7~}J~>nXy~&Hiyr+FR zMfBH);?;Tf=^@W47rs$6bL*#t<(>m3o)azZnDoYuNF}jz&yRd0H+KKX>y!V-rCdEO zfA7#SLkXr?Fl6f#@am~>H)0@yB(oeHD2;t3Qb0Ef=#Liq!uxolU3K_sG*R&{I{a|_#!0PI)IJ@WbDSJgKqw7_?>gOq-Z>1M` zu?v}(+)-yb0AKaNgUV5R;Zujj#s0V1zj^M{pGXt?S+za+DjOvU?db=?Qte}=!D z9zW|z%u|$g5MRAX#r`!Q`O6xN;N+Ux)f(sAehsExB^!~9J-VIzc&joCZ`9V{c>oVJCMFO<-W z!)s`u+Eu);dJ3!ztf_l>=7yE(e`h2%m@MTiuxoKIJK5`iDnG6O5msw1(PG#G0t>>5 zw}#b4=-O2t;%QY|va4#Csnv%+2ju1j)^;Y;l)j!_o~geTr~ zc*wZ-$|~NBuGUuFF|hi(f7lNju$^!2bjIas$^X^Z!kz};o90RO!7ROS_GzgPTJ{d=G2SZ6fgqQn`Ibr!1d_?N*j8Ysa&&ysg-mkS6h-MS6=-rw;8+`b z9-q($4-BIlh_ZIgTaSUbf3)??m$HZM#IuN_ZP%-jL#uGIXyk{iSl(cHwl&1gcx-p< zplboqcsdRkKzZX&z_qVo@1kAXFmme1GaV&W^YLOvi;<-69W#=E^3ijYPa(2ENhA?@ z+!#-4gI+DJeuhFDbgt~XRIX>QdAqoVADnYvJeV>afK2@A<@rr* zVG#nSx=udV*Dw9ZKl5Slz6Nn0e*@EqGZY1o$&RWTg8H);{}RVD0F`eYbBf!}zs_9% zahO>myb$8k>;3cO`LF9UH;j-7cgsOE@`pn>)cifmMQjj2sj&5%JUM(EIrOypm<+SrNv9G^-3Z zamWKFtU{qE2)na@+}rFf<~~du98|z~y78J*njb;N4zP9M#iT&)N0&f(WAD-%*XJ{w zS;3#k+kn;ff9gZ))eNP1A;tqWd+S7m>oAD8BFL02KhDeyf(h&$-bswUZh%nNaYL-d z^r!k~l~_$A-LTgHZcVhu5Vi|UQPr+HI2}~K!t;TbTF1DXRWbL(-@2S*70A7W_2>^k z+H}YM#k4ztl|J@%aYTS}9+Y!6g9VD!A~2vd%6ya}e-ZzEwYUqQVAmSK4gs@>)Jq(h z0yz$SZ50Gm^5NF&pN-w=dkdu4DehB}J59^J$ewB;P#&%#bg70JzzLh_N>&qP^w6Cx zg56Fvig@OY@^&~T%HTm`wEvJp8RGRv$fKtHA;O5P@*rbft26sZ|25cO!@A&H5$zs2 zV(rx`e=^(%vOck}HAEx3nnqAU%|wfZbl6*p4vTPOEv7?qSW{=-$FlUe6glQh15(r< zb_TbKbYaHtu0Zet+T$XQol8FVM?Gy$J?#SO$sgcN2`H@@Az@2DVU!{imsiczW%%US zPiZJVFVxOtbRtS8-$;Rz&rucWX-W&QbY;bPe?Y7&R3NpuXTlbh*fopi6Jg*&07yW(z;?byC%TUxfuoTBBE8bdpGl(W>IJ_r zIO6xOC@OHsV5(+w(pBc^L-u#T@S z)(Z`T_~9#`+>QZ`UMdQ*N9gp(sTc6Z}-cQ*5I_0XPUU{MoB%!LEcm0A{%57yXH z3VYt~?z`I5zyhy@eCIr|ldh(=ti5IjZwU zN{Y+X9qaNa(>fcp1F$OyMD2TW(U;hSZ$iZ+&Lee_JkNCwupiV4mZg@bi~cN4C;-fh zT+su3#Tx+)`6VXaa4BFQi4y1HLJ>djMyBQ|yYwm#Mr?OcP6eqe`R0oLA%@9Ye=SgK zXeyVS4Omrm+y&xvlD`?|7Tn0>BX)rXq}Bj&KbrMD%;}@TY`;=U-2yFCpdqd5nq9SP zNzw!e+`aG?=?3z9v6#{_-C#}cwb!V2D>qjW-2gaFY>ZAgkOd^1Vloq=({9M~FB%OO z=_nQ<4}idDub&qVKyjA~LQsr0f3DUfphy$$)M_>W2ii@Z0<%OkERUKi4zM)Hq7;J` z%I&hDg(%MT!gY^D4poAPMvtx!Q5wO!jEZ()Uxn?z7M8DsCW2JQRareaGZm!hgTpaA zK6%kPLL0FWw98otoIJdS@8c~$>3~t5I{M|b`NSQ;;W6_37|UEm{V14+e*>UQ^qVa{ zV9E7^^K&fWM%U8;x>41b9;)k|MaY@N{aFyky@rzD&#+e{cG$*artT&%t>3(}S5NKQ z;}`v3o}ZlldT{(0f1jKl^iNKn9*N&C4o*&fd;U^>KYh_Zetz^=`TY06vsd!_=il`2 z<9{XJzde2OR8~HCA-jQ}e`+uAskZv);MGz8<-zIWp5rtr|JCU){nIxuFkuH1P7hxG z{P?v0C<0-K0&|``ks>{(GW4MnWQ~Ac=qhk!QsDHe@3h3iwA4ycDh%0 zYN(N9AB~#gksA4*%r+$^Pu-~!1A{XUL;K(nL#*MhG#%h(7YFm99~`22#K(BwC8pDm z(@j?c>UrqM!1lf4^Tqd|__GE38MQ0*Uej55iD7*ou z0@FROGvgswf49Q!@?_^v`GYTofV9dzh4M6Jjf)(NPt#_dAHQhQLD70xJ|^M8suwm) zTD7LkE>2mMa{|IXoeb1aTfvV;&A^%%9`Ulhu&5@!;H=SX<)wtzEhi5)(l!3*=y=Cz6Juyntss3MrZ7L zK{c)S>YoEwEM5)kjM;++_6y+ba#~Edxg$X9`ZTzL&A0CKdK%w{o2$kLMz|5N z1eNVzP7SaGvL24tt^zFf!QtuCe?L}7m9Pl_!-EGV9svWA$nxqj4>eGVefjeF%VbPh z&eQw7`7X_SW^qW(pcIV7K_JFrUHrmMf7la;L#8BS0&fM!b9|y;ll7Bn7|P@{3wzd| zsjCH!vCm2JP+$aP)kxuyfm}4v@6^3ug5N**4Wkch(%*B%n)G2!y1)DH)@5|eIOznA zN_yq=f-W7apDQXmpV;y4d)*Z!r@Bx4LyA5qdXgjwEwgGSvKtbVj%JU$*2DKJe^oe( zmW51fjN?eOmPOPv)G*;Ts@gc?NiU)d!8wlr1Dd(YCzG+SmhYd%(|-IhE}?Fj>T!yg z+Djo3Y!!njqGyY0ZKYw#XVEm15|}2QX7t(ZjwBNh%c%+l#p3aVa>|HYP9xeYu7#zQ z7irnDB4A^GPMd!J{3-)NLodkRe`pwrWzq4^-~wl+w&J7|m^=f>=|*$)Y^j-Y7S5DY zEsG4N95PrjK1y!2#*Ks?lVrt0{HT{$>IR%xgL&dCv+ykI^;~(Q8TX8uqJ3w5`yZrw zhJ(`u!58+>>RPMWO{WorDC&*o6Mu+~)Ks)gAq!O*+d zg%WEyu-Z@Hj6Sp_D2nG!od~L3o#p%G)Z(laY&8Cm&H<)jqbth(SrCAL8+)^;*QxP4 z7&TE*k#M?Xxnivn6PT&Crf=B}-+%C-pmGO#j7D8yFrN-9PNVUUY%?2a7**Ljb54^D zr@9?_yF%rcd%=mTap`@UfA%4K6U+RSvCWA^W;zeqg-{d@kY9v;kb3#a!6W@ta207e z%4}vc`ArF?o24c^_*Fec=uLu4k5&&xKJP@fe_jD<%wFP+#G7T=`G>MJb#0E#=+LT$r&6&a5kAIf11B{x0y`J9PtHF#>yaP z&RJ&Be6kYe$>O#1=E_6^cvJxteLA4~461oZEQo$mr9D%Sn^3Jhe=BLrHfJF*Sw_iStZq6YsB0`~9FgTEj@!N1eN0RH_M|2urn{ylmOe@|bZ z!oN5<952ZDfB1NpZl=~$c2TCF+2$TjxeJH&{t{fkmEEnNudLJ|pPKR#LE(T4Ye@*W z?m!(|TEGOB?7*&J1uO;ZFC^%uuEX!%rG&Xgfw!X9NZAf z!!jTZvLJPhJD(8>?YuE;`n+SQ8W8THmSVH7mg2KvPwv_iHw3C#v?(7`DY8Fl{#7`r zuXli|(~0~DHk4N(}KsY@FvQgB=yEB%&4wC8yL+KNaW&W8u>WxGOJ{e|0 z)iU$5uJf}}4QBa@dt@7GOL69@CB1Ojq{>~FEN56axIkV_-%o?9X|eQJHCS9O7FHF@ z)}H+fw|=!%BiEjN61yAt%TC+7vaAoM{tTmiwz0Pu%Fetr^Vr?BDz+{)X(08_$Al^CE#>F{7mn4R*z-mNF5#jA3iD z=9J?&HOvCjDZkR#<-bhW#joFv42VrWOqiuF6K3hlgjD*<;8Xle-cdCXNhjT#oHTG7CT zeafj>b*Bo&@u{1IFQ3M})t|QLf2-E8w|d;fCSfv0TaCsCr`d*XnoiTIZ*Rxj+g2TZ zU)DR2)qsW|x6TveIxjVvN(N`1m5iTCXiY6ssPgZ}FHfF6|5Ywk zHA$H)9o$qiAUda;QInKr&aaXt6pIaZpo>S)wbUuT(#v9WL5VM4Gyt(Qe`h&lZx0^i z;pb1`LTH21R?TS6~jC+-V*N`=gZSi>ztXRYNso4A88AVn13a?9AE zWc$oVro_dn7+O%hWLIl|TqQwR3o!8729VneK_(Csa{(PTJrHL_j)RQE^+Y9%04-R1 ze}CV^pJ*d|<^sSY+;vD>f>wD9?p7k$E*QdIieM2s3Gi2L?Y8P$<`8hWfFN>$JGYggldDQrYFw~UQLGq z7qBpE?rUxvQr>|Q$3f&cAP$}dS6+DN(hHNl3NsZ_)As95H{SF1f1Pe4)9O=tfui^# z^7dk5c|^)%^23H_g)pm*rQvVQ?fw34H?G%rlc(_UyY&ILoj!>1-O%1<=gSwTxwRL5 z`Lfg43m-fP_jb1SE1R88tJR}7g<;Rx+N{=GsNAz3{A90%Yxb^P?NS0Z$scc6?)rZM ze_F9sRHdvwq^Y<(f4$fQ6Ve;CfAs7ySW|m%kQ^1(33>en zQ8xv+G_+3vZc4;71nDAlXQMvlc)(FGBSx0U9syJm<9{VqJ=(>g)3CHb|APmj@C#uL z=B3M#k$+MU16sUv$uVZlfIfO|geGjB^7v{TT-fir$U7Y!0m9Hr3%3!;;(#SLuxtCr-ujZkr*iH1*!fW#~J%t4*LJAPjGu1#IS8#>?Rh>Cap%sMAo3# zf2crf*c5k>P@9r7r{3ZxL!9iG$4vC#twYUry{H%R(+?lB+5kW=qM2Rs*#x6^Gnigr z;iC*kl}`Kpr+3-JkKJtAd1y!^o-mtCzQ`}K8LLJi!lGvERdeY?may!9K%puwe1AIk zXz=D6+%I1iT{01(qU>AQ6mt0ZWS{h?f7PO@6QWO7$(yeA!d^xHf0#w~ewaM`#e^D& zqusEYBtC$o2kvABBCL|ShpFROPke}p7c5cj=-}DG%VWa74!|$LcxXsI3Id$neS7a5 z2E#n4_Ev)s9fG32(1$2eo8ChRLL@(`XAk!_u>M0>emEeFQ1B^gwu{gkiuPdvf4`c| z1dqFHZ-4$78%_o(obOf&GJDf1tl?y<&z=~n3Vb@$PDPy)p&WXw!))Q`nB9e=Ut`!c z))m-h<1xEFn@70+nGa#Hf3+Lc!c*E@nX6y&LC$}DE<|_L2fn?*m-0UUdkRz5v)5qI zIBw~Q-&0BVCm`LwH(PW^oJQ)2fAFZ6&UnJy>M0YV4{#yxYnZ=UYkNg4(rzf9u$Q;C zwH6wCML5mPXY;XNkXNsF+YPO&g2IJB)Sbe*YiqT}Uaz3Q&3hKENX$fKtoeIEU+?G* zXu;|`NgOGf$rXteAFO*4HShMlE+=B?n={6vRuk>3c`CQK2%IO1??5v=e>lPWi@dUV z!pR>CSd+7(&bRSA{xWDxqSDCaq~ECHafsFB?UMvtQ@r?U1Ij^jcB;RQWcLd{04`m zBZ=g`%iK?19+!3lsJWZvfBt2yv+E?F8zZ0^b1`dS^>E$Bm(@jM5|<33gsHUl=oF|q zTO{YDjtJLbeA$N*WO6#1AOCUG7&AGxx%CuooF*Eo<`U6@w@Re-OUMJz4m4cJP{K+U z8T%@AbkjAe{3`QiH<%hsfBPFcndAn&rsg!8(fk7CdpzzmTH@l5f6N6rts5vpyBso; z8op>YJOGfhrRI2L=!Gt(k|N3?lhARqMBzJPrNLbf82ZJg^Safc&F`0TvVA7F$)Hl+ z2PJslHLYMC{jUeB^2?VMid-NjD3|1+=UpfyxhEKjKUHHFp~r6+^_1l7MIsFdJ&P^C zRJJXycC}BFW?W0le?&Dpn9au5{nYS)BQ`UK1;ax`HEf}qXJ@4bhx!zsf(+bMug#LZ z=9Xc+rh3w71f^ULD;sSRNf7-sWHw6a!zM#$L{=tx65i`m{>Ed)(Kx9g3~la%oN8*4 zxh1z{B8sV5Sh18RV|0LAISQ^2_kiI2B-o*dcGFrF(Emv#q7@slP_x&vRJ3MSS1s0`9^L~LW-ji-o*LhS118MX>4U{e=Ro4C zLtwQqY!#);8WVn7dT0U)DI!e@6x4l{LUd|m!7X_tEs*tN*RJKh z^^rSw-gA;NTl<$UhLw#YXm-4b-Nj$z+J;88Y9(R9f5LS>xs-wf3#K4~&S!GObW#pR zs0~^~02>;z5o<&UDbyLTC6|x|75d3~O3lX2<}gDuS`^Sy#8ZkkmspB~8+6S!iw-hbbR@oBMG(5|s@0I2_d5sa<#%nw z-;K4sfBSS=jJ)v-*MV{;$r7v83^WKU$j^VOaZxJ^-6@zj&1}$yvUjGZ#sj0wzWsKat^9sAwhx%pP^j$5KW|fV- za6eCQ>Qc}J<)Yuz9t%{9H=GuI?-G#l(FmUG*8$ zf1;&v-@2nTxXdC_hm~DrLi_`^z}>3ba}|Ha7)j3J3iecS#7(L= zB;^+W>8DKbpMGM1;016pzg&d$hIl9YnYXmkQ<~btmY8Vln(kFi*Qz|m!Drrj*R3h? zZ5MrTV(ZnPZ_Ihe@e2J z)T;vs=mXkQQ`s@%;)2W@g_9b^lnp{@1i!HjZBQPKNh!ruE?7_*q(MJ@H&|fHcx_GD z3)0J7YVXAMEO(d{8FvsFyL*+)_E%OaUY>n~XSS!%lW~b<4WLVS_<}Wm^YgZ$nR)(A zSpF($J=i4lQjcGtIdN52oaqFbf0+}-l`4kVmdda5%EHmz@5IT20uJ@tS(}K55~&gQ zC{z(P-P&`L^E5=Y;FQkK7M`E5yZ?^+IUJH$oQ}~o`osu~f}}&fAn0w45&xW{EWm#W zq(69IxML9mboP=}1zYqAh3tg?@5jG8@45sTb@A0TA&OW3UWy;vrSnfmf5k4HetKGk zob#iPUX@_^TsbgLvC8K(WOM*z(9k~<7G|@S%$Ovq8{9q#oVSv2s`2klfn~2}AhumO zO-gu0F)>Dxp^cweOXbcw3#za{BoSrrcc(Q>t%J{-4D(w}kcJqryT*c*R6&tmrIm}- zZoa=Vw_*&%hF!8MAmUyAf1U%%I|0hBSk|i0!>1gWsu-x8Sq;T&PE8O%6`2y#%!|X^ z<3^)5-xS;)7kldwKCv8HEF^boxU`jho4rB8Sp?Q?_x_yLd&#uv+ii706~yAkFxu7&dktx%X1B=v#d)_+$*=7${XMa3t~f4se=Xa@KqdS%dAc?* zP>N>EqxZ zy`l@tBy>lIVs=0Ue@pC@XWjgG9y~(QbNjTTBQ}zg7%{2d*@Qhvg_-e}%-ZEp0pC(sS~RxkQvT zm*D#AQs^Dx9b0%i?2-oXcDQAp_3r?`JU~}*eBS4CvcDv2^St2h|3)%JbH}ur6VB%q zUEnlaTHg5%zRQ#^IXkyJD)pt-o9|(cDr!(xJ9dnH&T!Mi>Yl~{_fJt-@W7I@7{R%yGt*B)s=(i9GMUnzNa-=$!>~Hnh})Zpku06ythue$I#Af)O6OAFT+GjRX{c77Gi+klcWl-smY%{jHt?s5#J603DC?6hOnF zmf}!fID`;RJq0h0Lwy=^sBdEq!C=fGSd2LYf0HSvNw6KjN=2Fz#JB0D$E!fx-y|6;myMB6LH6 z5!JY>v!vYmD4vW#)T-{{gZmY7jOF&ie|3*JuF`|29twKH2kFpIom>x+BDofpujJw5 zKCI(vwpgKx8@g&{(59p`;lWYve=7|RyJ3{PFdHR#Z%Uf2$-R+B0F0pkJ-gx+D=F%E z@*7gMdK1Rgs@$qTD5v&XLXqU`GVw8`gT=zl6&d|8DGlj~AH^PqYE0Sja3v5_f39Gw zj@oL~)LcrLS)$EmahnBAh+{}Px9r*Mrxl^%)vGmotc#YZ3kIs1F1RAv z&xNOJN5c(U_S(+rm2r!A+AmPJ(s3uJW0R9oGPhQ~0dI77$Xb5zz`ph(N^?Y7ZF5hx zNk|7?v^fx)8W38O2N+5fCMei@G(ZoPj>M0&yQ#(>X_5mt2gQ zR^EQ4j5AOfEDITNIMKZ6Jk<^qg04|+yr?jjsWgJFZdq-vDBK!XQ;WePHW~p^xG$a4 z${I7%vrOMeofOE#qY zr!5*$21*WndZawrJk-K5m2^gJvWYDj^CG=n6k{Yc`JYV$l%izH8k}FO|0jYS%w9VJ zabkTMTqO=akFf+)5LZp9yyL*m)I9* z1E|<9paiPnxJ#cJdcV`&oPX{pZ%%ufp`~Qf@zv-$9?R*pi}Cd=QxLC`O@-NHrc+6l zPA4+&E1$8IuI#)*k0Yoe#F)^Ck<)KxmIQ7_%3Lt#QIJNvWCdb4fb4g8SJWNh z_}2=Wlr;9x4ac6-XzW+?*zUZC{P^y?0No_ZY=Mgku|tXD-s+z<$7}t=6BkN_2tbqW zq7n4cap=p#T1Pjym492*R%iP~0^lLLsujjgC1+ySI1^vKltNKu0gkFGNN#s^c@3oy zpgMJ8P3BRI4{px9_{#I9RwJ^2k+F7mB5Q>%v}@+Ikg}{!$m8?P4H5Aqdchvg39nf8 zz6~5a^W8}QI8GZQh66$B7D#y&=m5sRIfurBtWVxG8abma?H$c;Sv=jOKE^?LT-ezAAY zLeG7_E0V3(4W9Elll4Yqy~$*~rK}`8@;)}brlOifI;N<{VteXBp|_$bu1Vog{b|6U z2iU8rJ4W?S9hYx0l5m1c(XL`0lt$#h>?qzfGHJ*8Llts*K$zQ+0 zdk?&f#Oa{Q6<0qKMc+7q)ZX6dY#I)$$Q1yUl z@%E-&Q-9zMZ->iIrBL}v!Q_p%g8fPg4GR`&4GpK|v%Iav$Bw|(_kixsTCR)E%IRc`i($T5wlgauy#Eps2%v< zo+k*)(>S`f%XIOnpa*jYs^ozl;*ifPv|cC7(Rk_n)SI1Zg~e;8cB(47WTZxvS&WJzxzYz%y-wJLwu zKq6d5U0bzl_9}b|u@gwgu0kR<@Q^tx;a!Mxx*K}1JpD^=*NTH#w>A4n&Wkbt?#F2_ zKYys{wSi+wrSobGXz4ekvFDNit`C>H7@@K(pVtyDgNo-7XIgmGQoXsvK`@Se^yIRe zani!`=q7XZ;jue)FFYQXOLuZ&cA&(sxfJIts0*X|xFx2EwQ6)lbmk5(yd>wQ;SzcM z<$@;iN^0mt9=GZc9W=A}iS5RgwcTipoqv{NwK}a2Tb8q9Ia});_#4yTy0bHOnmbk< zvPbQv^8xm?hDEUy*E@0DfgjDrdS_g3wVUv>4W(NRtKM!n&=_P{^#-=m>|p6;8-8!H z(k*CYQ&!vhPhjsW*b8yw%S{e;!tTU4E=kRF@au@nkp+$AM0q#s`>$hSh38-PYLY;9r;lYfkdM2I>M zy$`*1yHOj?Lkw=aD`RAdABtmp9_I=DNYrGu_S8L?AsA<#H>*H{HEcbnD3!s&9%_{& zPznZ6?bIKJ!K{zhapEjzeh@HZ9pL@!x=$N!#S5_vAGdSPt`Yj z>;90Goxs_eKxa(_vI90wN{;{;@K z*3CmrvL!F$a`x;~5EFRjlb7Uyn}0mRuU##$Z>lohTIDv&loP3RDf6geOimlAV5FH) zqMx%{k`kEivnEwx06W}f=oAn#9$j9gf*E^Is@IeF5OJ@e#tBWBHzY-EB18(21uyL- z77fyf7VwUMOVozhIDdI-9S$mdmIL*fgcYikhxM5bEO6u!&1^^N7s+UFPPs^-ysRpq ztv4DAq`;&nc}-f>SElqby**}?G1`E7sFxZHY|&)_38my43Mj%vr4sJn;WdGP!V*wq zZVQA$gx?ted&j>~L(+9soVg|i&|N|+aBDH#W^XnS7=TZOm4Cr$Qd2VZ22*-G23htW zG1Gg5QtzQ@fpJBUl~WQpEPs&z&r)N#yu99yOg1iuyjGD!JB=@2fcaPHbHB0}mb;pS zG{!rPzZ0?nq`$M*k>-1wCWvV#Op~jk0ye}nN^|!}LMi2DQK}{zQJU8(qO^%oe>*0W z7Q%90C~bBaN`IZsB9t~vD0QdL&(Bqax>NHQ0GpVVMW&K!#AQx{$kQH!T(%wta{#c} z>HNdn07M~*foL6_XypdMeVG=3d0&X;r0XmoU8k{$c#d^E%k6ta!B}}LAcccXMFWB} z*<<3}zDBKGI;&Z_x-meyOYSQkJWwZu;%AbCL~U=5NC{***7Em$n7CF8HKJoZeQRU=>XDl8FvGUM)(qpnRK^XRN+ zzk(0$OO@vy9=ya7GNd`PNyV|@8y4kzH|6)9VB#YeHb^YT9Spn~u`6@(sn0{ir>*4- znJ6#=Cx4wnmGqS&L^B{#pmB4lT~CN&ak?E;)B4fS4{NR|3nlkmV->;}T9NT;$e&Xh zS5vqo^H3JUfQY|=X?)n}umKWD$pbMMd?M;pKkE}}@^h392%uFE_)rYC^a5n@#NGsG z9<3UxsXA(DYZli`uftglBO$kNigB6!kDB$5^?!e)Nw8=0*EKAaoMwvv9c=WySQ9AX zwCKQfDS5%O+_Y4mnr0f@q2Pxarx?85j?C4UazibxBbt^2k{37}rux_P7zRI%m zs()1NYLHcpEfsZ@!A3z@!#H!U4q+7(_sRF$lBm!NFxBFGhK8r5(TySNi(JkkqRX4o z?rT`@D&1G}rkih+&xm*DyB0N$Hd?C05Y`)U%&;xk*s3r34UZ3yUJ4K_wI2n zO$CDPvFzM8pWeQWFxK61YaCIy9ZPSZLT zXHCtm$+)%I^R5>0M0EUwH(z8v?Fp+ZBfJkD`06qF<%=19yjI8ifUz$w$Ox}2kOFd! zmhwHqH^mfoWSWZMz@w_9lLx`LJ{i_K7?GwPP2k5gpohuG=iyy!#QWzLqd+=Q5Px=O z0WHs6<))957Je{aS9C>R#S7Xg-LLAgT-cSLxNoKKr`;pZo1MJBeuObX5m<~%&6tn< zY5IQkJQxFGTgNK_yV}iW(~-%BOSdc-0z*beQPxea4>m==?5{^dWONV;@w-dE=~8xT zjOZZZJz#J)hUAt&atm+NLz&(b>3>ZiE;imTUoecZzmCja>`y#$)h^1nMfo2=PBLBs{d&DxsV*8-w1i$+#C;FygxdgZG{wtf*fMD`LnX zHyR;cXJW3lHpLn=-+F(H^vEP>kf|97t*|g~heLFVgJuO*o7)xK+zuzR0DtHShPK~k z7YPBT7vjV$t|HmDh;@=M@+>Na+^WmrhddQzCX_WL(Nlz>6pF(rGv#VxUZ4dX2LFL(`FrjlytY_~7PDgJS9+l$-yQW+U7GGc zQb553tATS=?ypbz;!SLNTxuCkB)coQFS!k8ScXQ`i)58quNtl17k`oBe?BZXp+qn^FNWQ6@0DW}Yl zCfDo-E=@{LGVBk;+BMhlGOtewvZ;HSIM`61yLlWPY-Uf6n6gVe%QWSkX99m~yQ$o= z49YN%JJ`*Ox{N5bsDB;0yE;!+Nta?$q{>6ZeA?jfP{*d{k+!Y;k$-G57mkZJrmwg&#mnwY zb}esRqG_tlXiVR@x=DtTidZ!CWoVtrK}+s*@ty5-h8f~-UUC5PFIb3k#vh`szHU|Z znHj?Xusq>U*q-oRur%w^9t783P3oG5&u_gPX3q%@5$&S2^zHV$8_VuPp5@4jk`}t zIfF>pqd2vxhY3njb$(B@P;k-k`6jlw)8M@ zg#TyO5r2NJdgHUKq*>Tb@n}x6Wi%s_D`3B^@V_1g{DEH}6M3m4W`knwFkYb2s3rSz zwdZ_mbS4Y=o;{AN zdW3JWB=KfXz?w9~h`i8u$Nh0+;?Yu>oJs3eSPT}sMkW-!6b0=I+e43e?b2i7o<2FX zPL6CI#>K)0)`-h6FBf+ItF0L1n}KS&XtA+;->*&{$w=wH0dR%@&6 zY(qU>%vAOm%BtC>GCx1Evp1|cGbtYH*?+svUUn~#Jg)cuv-c+6Z5&DZ;J;GB%*wJ~jEevP6e&x#_HW<#zR0WtC;${GU$gzXEf%Ws z&dA8PV=p)94~H$EA^L9O7VR~p+P+Lj^KJE}mbEd0PLF17v;-Tu9oWDB1Ia({@qf|m z>^*t@C$o+fxy{x!YlWRe9E&;hPnJIUSn~nT&Sss1JAdTU?Re)z)!=EquRu+Fj%HmX zK{x0J$U*GM{k75atU(z=XC|`Npq_ZM;63+3|9;Rv z-DNMhNmKSgzKNlwB-{)Ji8K*h;6MshBD*?oF}y3o?%Jf*-s5>IrS-*3=kBQg-Nxtn zWcy=V60!Kv*{Z`VsOs50mxtHmS*4Fh99X+LZmM}_T~6l1jhjr)!~;(zIDePhQYIw; zBlJq2zR`Y+CgYpg{CxIaSx28Nm|Rj0!~7V8Vy?eJ!++dX3NPf-9U| zTu@S(Nty9?zQe|FJ(>;sZAcZW_57{%{4LBGn>A+))*hWhRD=FbB;F%I*w*tgJ@|8j z%0M}M{NLaG_xIm_eDeLje1HFB@c5JOfBE6jKYx5&6|@k2`0&BU|NZ@O_xI8Ky8Pv8 zHUCA(!e7d(>O0TPe~=%Sd>9^mfBefo4?mvSI<>F<8GYB=so2LGK(_Jj_*lT@fqzo% zIMo~UVK)zYHwF3~58wR3?MPR-SCBrez7FQQV7_}9v{3R%FQkq(;eT{-_8yR0-!prF zvkfHc+Hz|H1-~b-uHL;jp6(^cu%Wk=sGb^ADcL_pRNRQ6_&#z>X~Tm^VQhT`!53PA z=x!SER?+(zwzhUQzFJ&eqcB5WRv^69#$N_j4R>>s8@A_7ctwVnSPz@z#c+BxZ+l!{ zX;Eh2{S@xDbrbMX#eZf$0o)3n+jz~zUhDuaX?G`5ZnraCtSSxg*u11rYX&e^keiQ; zBy6(`A#uG8iLG+I#K_{^X)lB?)P1w0*D<6h_%l`?taGG zSsy#!7U$>JS0>0bf>*a*47az{96Nn;(wl0|BY$*zQj9pXlXBGbaWZ~) z&>Zm)?X)}i@g7A7BAc$Sj9eUi*ps9E{wk_F00RTVoKDq8gQ4tA{pwOs#P|Y=fljG2 zZ+LR6E_Rq)ENrl6MpHYmY7hM3fy=4AY6sVKKU%zFQ}d#Ln(9Sa+|Z%d7=|7Q#sAAM zTi0CMsJ(|C?tj{-L(~ot{FL_Y?uNHVj~%y48k(5c^@X8=PB3CUwR%N)?E+m%UY)qOr=&p| z>&aFEmrkiGVI4Y!I!4vSUpHfQ$ko89^t9EKKiz;V<9~nhUiQMhwwGI$dTki_2nk+83b+ zl&nS=0*#ntEbun{es(xQfhMhWjEx@6$^>+A`z^)CM)Gp7{kt~ahwd9VI0Q`9sGe8* zj;nJz)PGo_tv$5}X6LQAT}7|LZLvIWMc(LoG4io>H{$m@D1dj3@yQX2JlLKCb55Ym zM#kGZi!b=8M`zI2!l)5P)HOw^b&wV^fTFe#1}7+h5wUrbl}U^?wXxxWmKqJ%`s1LcCTENbUD@F>2jF z-M!elH~Kf@mc=&rtjA>LVg;727B$;9gVVm)180X41r44B>ELABzIpr-Si0_oKZUv3 z-x}PH_jq6FrypmRFIVF}LJ7lt=6l)q^Ul9<5WxsJ9Z)TMI3V-hHck-RIT-XBj}<*M zD1YN$Ds^(ycA@IHb@GngX2#V_d-kfSudDgM6T)jpQ+!3^fZbj#jY_g1^mYnnn#2U7 z`Pr%^6cV~4gRmV!(1+!-6kGLlO18p@u05%PE7@Bs*8ls zJva(uMv62`*>UJtaf{G6<(p$=u||m3;Yp1)Rt@;| z#tlG}wg6Gu_BXg~L%UT5Wcu&4givKXZp9T^T$dAPzNj2Hhc(vAkO1xnpucmenw+1z zSkvd9JLkv~JSi&1f;h~e_8O)&Eun$?-8&r$?0v4AUQpRs&t{naSi#$^;MP^p`F{$j z|aJTMe%rIV3hHTKUG&en!rfqC}{Y7-NJ< ztB!3*X{VF9q%%^}f|2(&UKDUg+&b2$ZD-4SA%#ZnF}#ye^{-}`$vev~f)NJ|?rIml z3kmLn2&5h56^q4m>A?KF#m`Rg!_*GYrX2vM>`JicNJyO3@kQBD<%QqP0cXFA{ zMz)q!fpqbPK~n=$Xxq$83v6KzQ@oE6-;_c1%agW6v%jV{7i4Y5zi2h0;D1f$^^KwW zKi4ttc6r!uC3N!seZ05H&#qV~%0~~>yuFL6=2*h{g;OmYgO*z8c=rftKxDuWHoMo> z^A~1d6a!8^E>ueJFNmzw4D4!kQIDt%ONL{AVMo!9XINVadBcrFdj>{b(qk`+nrX8i zyb)8K8|nM{0!;3IJpI}v{C^#N{qNtN{fyvEC+5X!d^M|otgn#1u`oa1jh=n;_4Bju zypjCxhtYquf7H1 z+C}zku<0$^3g;x}@>Bb@mgeK_Q%&M=RM+jMp>HY`9MM+sQJdN}QID{g%1mlzqgp-> z5&UEQVuii!wC-}XOMkN;IkO2OENmrZpn#WAD4Wmv8()uxj3Y5V3xzd2v*1A9Fhs<} z0vmf0na58DC$V|_Y;cmuqh5+nO%$ZZi!07ZPsvC0_Wo!v3bi0gIBOGG%?3_VL9mT^ zuk}Cqem*!gq4QZBFGigl6tbu|Vn>7SvfSQ}ukhSv%~jJ>F6Kv(4I3U+tGWYCqkq9rx8fZ`FQh z7IzCj70qI-_kYcOw7FE9i?QA}_tEB3Z7#-o-`q!=OSQQe>wR+{Z7x+?&CH--yi#ne zVg5ka9ld}oj|MgCEfPiVh%(TMs*UC~Lb(l1u(!(^wzZHE>dR3bY~O_arD>|SF@T=V z6eDZxYH@u&wVgq&H5hG%H(LDYp3hb?kpWET&KJUjj(-MBi_rX)Vsd#G^8sQt6mL4& zj2CnEe>wh1Fp%t3UqIl$2<1>6HGti%A2N@f4yQLN?^cxC(F1>b5iD%(3W~h30(CO1)&l6nH^UV|9?0alJC|K(Nni~X@0|%;gB4T$*Bjm9o_Uc5VDO=5KrUmtd~B1a@3A|zd>=0 zHmU3`8P~~p+AOh_-AsykyQHU9jk+TdsMTHVNqA~;WGmfiXI2J9?i=gK8;1?9Wi@u zh<}Z7$(DP<35}Sc*+qWU@BAMu#XdGPH=`YU*Cn|Sr zH*`8XuEiOx%5$U}fuykosLj&N1pqp2e|#!u zoJKvO&nYuw0FY<#VD#x~HGXsaYK2rq{Q$j@y7l>vw!*;%f6-ei>XiBmO7VoAJ%8{z zKt+gRgih~WcQ>AY-m_xs$u}xF>)nb8p&P5!Zs;2VIMBe^O8OYh+OFCrfWu#8U7p+X z(N2wl2p`vi+Moj+U$6N9wPqy`?@l+CjE8l6%z|{}IA+m}IqT`?H)(lyIdh=l@!Tpr zd}ozF-4r~APpfk)V+zdgv%S?u;(w*wjO7Ujk7_~OchwJ%22H}^Q6rHIg-MZH3o#b% z*zD!*cKhaIiMmlW8go8JNF%jl)5g14yrM@?v!1-rHKm97$gXgIN$#jE$R9gfL`d4Y z!J-njnEOqV(|gcQm_B@{uT`-9V!o(muZ%to5%c$OxxJR>!=Ayli7OqTfq$>Fv#xc@ zd|b}na)d9T4N^&Drz!J^jXXHoA&KrAgQ=(^H?--#rQTJfy>ENU*q!LG3=L>K|9k^v z&D#cQo)nKhGB&Apevp@%_yiE`Tbbpf>d{Bwd(Q?!J`RxI&y@cJp9cSzPzQtFLFno= ztjlisLpNjex5c=G@5Ix~U4I#zr&pkDK4gE(ke3Ky;v7EJXHj)WBnl&0$Irm<(un>~#^YJVCV^&n|9OFc{b zs{w|pq1P}cr42`wx#Zdv1d#1(em6H{r^hy!RlEx|qMbfB_8i|Zt^mEA?BW+kRY&pA z-pZfvgwaNuaHDqFBu<_hC_M_I;YO!l7S%Us^jm?!vTD1EQMZRkeT|n{n=U^MY9%r? z>tmst8gkzxUi8lz>VK`WF*l#=o*y(AU&f*HrRV$?j2p&6b+l*|I5dvNZ7QV#wbqGg zHF$f%48#lL?m6r?9(*L+fe;DJS&l8^zk&H{-$#QV-i=I?ug}-*_Moeje`Efe@ZXgG zX8bpA)uht1UDszxpC$cvNvcHKB^h=F8q%hWRgkueY;*s(T^!6z zrx=$YZ!Z8((tr4}Rq7eKeTL?qVdb8MUaPp_E!xG=<}<9D@HI_Aa1rfNX?s{;J=!0$ z_JGE#9|gYJpJgY0c=yBUCi>AFu!499D#uhuwRo0qy!3}3cQZVNd)c$N>KSUuA6%3qC5Z8BBk;eW~C-v-EH$LpV0{}cU=bl&p1 z6AD21wBE8c|GQcKd4GAcXPd>F1GYUKxil-alUVmMr(^ZlViVt~wkn@cw7fVbGjc0F~cWE8vwR#We4FdULG~QJlSaK+4C1jt%bVWP9ZQ?42Rz!NyA;Z=Y;8yMI|5qlD){cQL;C_A~5vFFDhtxC_t|Po@9l3#=|8fVXyHuvoI``@k>koUhYasI;-BR7Exi@d2 zmVexgYue92`#WRu_cMEKvJ49|@^^FKyE*4Bi|)OrhFuZyPV;48A^mtcse>aJuK`#` z!iY?Y{B&8Ol$yqkWQqA9@J=^!nA=taA~qX2+U%yCLK~k}Jan(-8h*c1x`zK+S=jju zV^&)m$=yafzYejv-KN*m*((`u&!lVTiGOY`OIGI^znZtilBe%KX442IXuCd+BG1=* zRzMS1_{ByP-odBW)l_&(YwSH+udfT|s$4tr6`(!lAn!fx&g-2U^q|`woW#ET0_4ut z{Hixs#gn7W?!A%0DK;?ORy}zhb>L;x-Vi~017Y6ZtH-T^u;OAcJTsQsXmiTLQ7ee1uZ`j=|iTh>oJnPx1YT8KmXa8m=B2=cmSP z^#K~q-t!2p?sJ4-l)ua~g+v3)6 z{^U+KpG>BoIJ37reY+1~=}qADEO0i2jDTkisjC`N37X!XJM<|8m*vy8>y~VMhs8KH zAql#au2yvZzU3ygNq?tpt#uzv&+h`$dl)GpnL2a08}N6Rp>q)SGI2a5-O8IMrVHSk z9c`bUzSeGalIFG}JRJ2kGuqQTPFVNz_G#Bki zy)iy}iW%Atu5Bs#})t8 zH&Zu8F^|P^DHi4Yl(3v1di>?d%Vp-Hy3>AFwMw(Isq`nEc}~+q)pV>y+)PHM1Cyfs z%2BZj#}wP|G9dP#!_l5~Fs_UyL=Vk7r*fOZH!>y6ZRv72Zryn0);*$=sSM`rvj_|3 zdCf{BGJ~L*W+;~8ISr-bAd{DY6GhTyTKS3N#%R<0)z?dTmPME6rlKr*)1WRyRIiij z?jlsW2GYyh!RWkPTu%fx1gFTyEMNM*C+i|WfH7WyW|(CcDTH^uU&IhNn&`o}T@v@S4{U+*V>Qg9nQ3#1uL*T;f# zYCe}+Mx>A!meRHCNSw&_$R1)F@u$L{Oh1}$@|w^RR%|1F`wT_0pbXG}{Ig_zwoqw9 zrCWcqjfZSSy5~r4Vs5mIOn+DA``c%^G@eKcXh7SR9S# zJ)4f%wG0aXynU8`Nz0K8JH*gJJ8ZKYm1`Dg>T=CoE}FiSo;iQk4DFcYpNdOX`e@L% z4eBy-74gB}Dla=F81j5p5;ysB<^x|g34jrX+!}1L0A9GnstDZSPZ)BJ^0##JT#!>B zQUzx{Fo}jS&4h2}Ew`e$Y_R;>)xWDODGjAF{-MQYiFOsaQ&z=*JIAoPsa} zEL~o&XXnT=naI#RKP{68s3cs5xj>+kgpOC?L`V6Jn}t5M1BX2Fv52{1OP@ayo?C%? zHy{d3r4$c!;-mtJOS|$&Y#8TG6^B5Jku1f!7_ZK!L>2R=}3Q%h+|Gj*eZY z;ON+0Y_t@r^l#Pv)~=)tz179>fePoNUchwx*JuNuu1zqkI_&?#RsbC&QE71_*{3#_4Bf#blI(%cx302Y5uI z7)cO+5{y$EGH#+z6rSUB2f9FkZgs#9f+w)kihd$M9#&t*mJ!eibZMmJY%w-q>gOS! z*)n@%hqwvkoZ_Afs}#82Q@E1X6}DEkUna(jN@r$3&Lgl^p#`+4aHIY@zU8U?=6DZHe0K3FS%KwgN$7DQ4y1l)Q4GF1@d2m&57%)v>t zbSRA^bv3y`xXb*(Wk-2bMNPID0ZWB)XoJ{iX%q&k;>HLTlgl#-a(J|3c5ZQbRlOPf zFP-GGNDgiaLM4b~W;vRT1l6Y)svLfKB_I*XKyw0_$4^0k7r^|e7z(Zz{1W)Stl9N{ zx&S~Vh6WbuCBhP*`%G>|pdmlFkty;@1r*C_y1Crs2~duFN@H``0`(AwqGws&GK^6@ z^p+^;@HJ*`%H0Tn+iO}kLr;y;fXACREh#n>;0DS+H>}QnZMSHiy=tck`edtGVWQu5B>P|` z`@<}X3?%(v<8bb|JLw-`MY7uu#QD|tCj6ru95WE-_ure}ZAqLCZsUCjJJ3IWB#KM# zKa%u*DDIDPoGo7YFe~ExFFMZY2S9M?eMT}EEq(-dlEjV>^JOetru^3u0;LohfkBsl zAT&xTJWFfgS(=5A5C}7ws_={?b7p8~DG+9naJ8ER-Kw_8+gXw!&D23U7W8RYLQI=w8em6)cS%8F2A6hf81v3;h4P}jdabp%z z*O5l_0qt(jH`9`6%CuzW3%M&ve+~n~am@n?u^A3W%a*nQ-2^mh7{tseZSSRyCzDl5 zm5szIky!y^e7jg&y0f_=MhYU*We#4$SE;u0;<4eyLo((nM!>r&WJ@f6yCnn)A>Rt} zz9rX{gosNvXXpB$0o30T{Vd&Fr7^L8JgtF!kxp+qR0Ra|d9TcE~!KJXyPm)UiQhQ;(R!t2l;NTBs8~6mNyJ}we zlvHm0jZ}%gupz~a{9;`wgd~HqN&G^QVL6!;p&qyqQ45G2#i)z21g*IZbNpOT8Ii` zl@4^bpnL>4>k`JgKryurx^i)9p5#Hl>u0IO_Y_Qdx&V;pqZ=s!S?=s&K2|MJ5SxA5 z4?zb(Xg_-L_khrUv(y0bAuQ|N4?&VR>mLE|e0*>O(fvjc?O6g}1`r+`Kya@CI96EM ze~!-=7gm}JZ9^DJE07JxWtdSJQKH9XlvBD4)kT=&RZ#k2B>T4n+Kr$i0iyE+cW2Z` zMoz!-%Yy34V~6B1 zRtlg-<3r?Vuou^b*fOlK8{V&>IMosLnoY>85wg3bgsSNa3k7Zi2D*J5RC3r_D?31h z`2HR$WGcA+t(u2r)VLk6kCN{=Ie$zCY*BE!1aaay4e8M$NLqACi+Z^mA#;e1sp^O3 zV^hPnq8LT!38*ZEbny)3LNdkekS}gS*3?hVohTeOWuDsKU0X{InqlGgU#tRU{$3Px z=;l3e9QIwj1B8Tz&7nIkmB+HQ^dZTYK-m;lBWgCLWqjMQ8&Iec!T^B^GJl%0pr8~ahTo&yZ7H2jEsf* zKeqqFZhs>CllxIwZ=l&fvwyRdYd2etzwD74+)ok~q}q_ZaLxW#3J#@(5(N^1j#DWl z2@aUeUoL)vm8)fo(;8-#novts7ZUMIhMfpeozen1Rf|R8B-L0~eqw%=3w{YZLJD8V zA^D@!EZ<>(f`2hThnxTwCjsH_JKC0vL<;26U+kbe*lnrJE$rJ!b$`BnmO%>b(GojO z>cxRT490CL`_Cxq03m|qb|PBU6651!IvdmU%`^@3w+y%=_H|{-O@q$*n0i`GYuQTm zU|VQF_?${OB^{d?8b|9x?||`BK91ZUP0aRxoX!u6oFk!81FsBd8Jx@3sJ$8fgdX8i z{t9-r--&u@kd_&9G?SS6B7c)BbV3pwkXK3pKnYoYW5JC^$OFrNOUjK?n2W&(H@VZ2 z-)Y6CR#4UvEIPjfz%606C!}Mfrm)-urgFdiF8DeVy9+8r&sw|S@7jfk@(G|hhi1s3 z>_+?^yD&8}Yb@iPW(&z?DjcwI#YkpIRD5cCOdQuf6Ewv3)kZ(0$A~My8$|rO)K%LHc0iNN4{ulqzZUCy_m%5< zcNgsXUK*QgDcfkpt(!3;$?AbL<7kGFb!K5F!J1hu*sVuZxy=~D+wgyf7Gb}LV)p`A z$~U@K@6mzocgwXg`G55HoP7E_Pd@%VCm;XLlMjE-$%nt+mz9bc~T7wCgcS$(GdDZHax2AUioAddxe5@J0^K+KClj zHg0d1ed8LNX3NAco2d&B0&Kz2zMTJEL`P;zAw3~xhllt%(ySQ>cSES#`S?-O7x^r zhY9n^r`uA77*tCrwOSn-|Vb7*`o0A5i;)fl`{S6|LY#n?lf}1GJ zmO(Rq*Pr)=?OyiDKsy9AN!966PiZ^KB-MVs`R(8 zG+s!viqOf7tySjGnc!woUSAgO;?*l$@1bmc29`R8@ljwM76NsVz;bl-rRE)|Er+Cr zt>;pnN9PPby1NjQTws7TWkaf`ND|>;14=TD-4k^X(0@RHj1nq}He;#Ur}0l&8%~t= zp;gGKOPTsEzmY>p$*7nHWMgbge%@P38qoS`ww6{YZQS7G1AjO3uvI{-H70PW`dr%0 zVQRlW!S19Lm7AO zz#fK+Mt?ku6B?P}z$p^Y4I796E|ETjE^sDN4QNK^P4NA>N)XT*ge!FaiCfEjeT7BN z6Ru!tcv6$_%e7r>vZt3Wt9OdlBsVkOGvRp=$nQz zmfVn>O3HHA65aZQ_`dbrE~L+VWDzalwx63K+Fjy>F!Vvc6yd_}I1MY;{xz@h7k@$& ztn^>LVuJ5-b}@JV=XzbuUcG61?D&W5JN;YOcOEkE^bfg(WWRsmNN(Z6`o~z5-~*1t zx%*HAdR~ps3mCJwH?v8x0QgurAdq5+hM`Ref=VthHx6qA3&Jv!^CVK^SlU!o1%owM`mdIdWh7*;Dt3oq)!Rvg_U7!3}HkG1ku z4`HIrgg(8#-{cx;L`XHZjh78H6NaA~J z)8+Wey&V5otf*C^kUPn(R*kH?SBD@;z^W?GnyECMco%;bl_1|~q|d7tT3wB5;4>OW znls2q1T$n1ftdz9aFnwr->cX#_ti8%Cq)=!6@$G9Ol7pIBozo2KLSk%Lwwl9V}3cW zp(v1jL(mx_O$<6r;M)z{m?L@yi+Lu13N*J4L<0DoR!JRL#eR+IXFeu%@De_yHoQp! zcpp!IDF1)#n#nZ0$>QjPDko{vMoKjn01%EL25xfY231%R2*JHezQ(IEh6>86%*aZF z=~gp%8~iLtjMtPOnwVH5n2o{;d!t`{Ij0C@lrgdk-^E;5U1YdyM2-SABk|zqk_w=L zD+lk7QF4iT9?rx``X((`G|)%)7de){;&O4Rd|dK^-kX&QIxCfa(3Nt8Glm6z8kQmMMewKFuB2)n2_0+b zC1j2htI`#ez_aV$1Ttot5CMna0uj17t69iAs2hY-n@k8r$_PJ~!<1h@w}OGZllgyo zjQ|%^L{vO!@GK=RO;n04!--(T1W6Vn)Ew7g>^LxW)j-;b&fW?wl&EGII616cWN{kg z!u&N)Ly|X#A@K9xYKIe{E|M@WLy|Lb$F5(KZopd0ne(Hokf4-Viz_f+O4Fq9|h9?KXcfSXafB z`*M8#4v62k~l6mhMq<+YFSZwm1@Dt@qRmU&ybrkn~KBVa@* zmG0>bX}a3SjIFEAOh4pAf33y%@N4G0&!XAoqKcFhjS1fSAtsVTfaKAe4KjPGa4Y^> z+HZGXZg9Be_zeIW!417MDl>m-2J&o4KGr8f3KAYv`CGd6ch?kfHSlm`Fiw!Q*Gu12 zrU<%Y>TPp?yjyrJWcQEPksXe4_S=ob*#}8Tv zqef$9?6h$6D6sH?lA@IzMi2B^^$sn0Ny#mgRJ&IlE}K!9Vk%(U$SLdTHIW&8bsg zu(ht)ZLf#J%X$k>{`YM7o-ca3E5Zi%Ig?>2FMZCW}*1L~ncrg00cw^Bs$fD!}1ZV&v zi#=L}$0iaF)Q-9F$sq+7U$BY1}w@e#%vD~_1ujOT|?Xxa7^l`aJ_aB zTj5XbrV!H=di(IYt(|LIl+nQYP{A6gS}@fDDMD0}Lt#gu4&*j~Tc;TC<9!7zoHejl zH4v#lUE9_5mZ8jiHveCLu*WuJqiTuYf9ss~w#43@R~;*=al-!eOPbP}H1~0h1*&OK zV~V_G)#h4*I6;-UDUdr=tEAco(p<*;p9*O6x9qm$nx=Y7+LrjubfESfxwXq{tn7LV z!IF{<;D2n~6sqS@8~F8>G47F?mjJ&~lW2d9cNMNys zjtP9CR<2oy{5*lp0+Un4#bt}=RVmA;Tym-&`-iQg{CitR^_eOOq|WBA7Jq(vsrGTY z%R)LIU?n+(w2pr>vTp=?cQTEQufs+l!S`z=+&zn}NjS|c7zDBQ&+iAA_4%qO=IiN# zD&<>7F3TfY)x*u&SJjPbSdBp%-%YjDo#W@By30%-=&9Xu<+eN3;oK*VS{^wXIF7xs zX{#{y)F(Wv2XvQMkf?~2V)m-K!K&5MjZR@lC^wkG<}CE2~^2^B7*r_v}OXC$tQ zvAN{e6rb<2T~ZwlO9!UK%JgxgtB2|8w(~+6e(RBG+zNyrOr%aDZ_Zl(BFH zk<7zq)R@3*sB$cckaD>{jpKWlG714jf4hd%#{%8xQ{a z_F?2_oiPyb2oYysbDTOkeMP95ih`SfQEd9bYE`UfZwvR;by?O*x4^_o-M2MiuLVM6 zObc?v<%QW&&XjY#_k+Cy)Gi1@B~S)giAqRQr;Sj#N&Tj0m5bDmsRgEI9On1HZMdbc zGfL7jXYgFxpJO7FG9!W-Z8eu4f3GmeEK-yD)lAH^vGk4Ys%IU=10%O-E%EwttZVFh zC`zH_hv?$NEy2bLyrn)X`7prX{JPK}%Ut|)UXCxv|0@KJsTZm0D?q{l$^sR&MF#&t zkXBOY=po7him1?>+Cde~8Kp>MWQnPT3{4nn8qoTn<1!R#b)uQXrhLloQ6@i!f zAyS{3NRToO)Ajh_cf?$-Orx74#U(_*bV`l_M`P)GsSWk-hgpT_)qb4NIMPRG51*ku znBLqsG5DFDfmt0Y3Ldi5e_Hy|0mN0G#VEFpNlQ0Xi*=Vax3Gv0eaBo&`BE-pMm)gH z9BYd6z=zR(6sgTV7D!^Tb&F-s31bws4^HN0BO0WR+J$K})(qakFGJYDgN>5?PyeL*{J;iIZyhtr+=kv87lc z9dW??Jh8PI=3EnB{V#&pprkj2ySOSEROAT?V{jKgQ9Q}vM${=(zEK#kIfZ1vEdNA7 z{R!w#ZJC=VI5=hMe~+1&if-M6+iuvky#fB}A($UQU4jKzO>42S+_s-^a=LOx;#{rVCw#fIbCTmdUqVtq}=aup;IF8L}TNNvwf1$O9qJy=Ha==c=h* zUCnt~xtaoXN!xb{!eH6#Q{SLoCyJ+Vb~KTyhG6lLZ_1LAf4()`$TdMV9YX{%K$fLG zU4pWpQseT>C;7#wJ_50!b%k-v4`_ZS{Trn;U|*_9q>R$8D|AUq1T)Yy z(ui@NA%AWpS7rb&XaKcIN5KE`ItdOppY<8&6A}CA!ej|nlM2VL!om&n zLk$Izm`A29e*kXEKmwCzRRd00YOm7UDX>6)UM|*}ZWe*-aWpi?a$s%`IVeldBw;u45{zyO$Okx&Y33Pce=)Zi)72Xh6D|?Y0;)7bQiUTI zvwcI>A=lfE{f}j2#Jea3_e&pvGNbo`U7w@^lU@i8g*ZW7DotWwONK6@ z;9lJZtkhj&dJ}g8;q5wLPIJP3C1{1N(J!HlMBs2Ix;1pZ9WMw|>f_Coz!op2Z*&;# z$#Zo$#aD=67f~dogHV>2tPcS=e~WuQUTOUJM43sjFR68F_Q_oYCZKN;OtV}T6_L7V zrJ(8F6>N<;EaIIoNs3S9nXBg`HV%7JHwnWM8-=doFy6zeRJ(;sp4BGq7LrsuBqN^5 zFcBZhy11_azjopd)R5lQG+VhE*_u+dz3QBI0gJ%f>r8-X=s zbeXKe2FTbMh+=>06j)xpeP*H|1SWflX*yGjL^BLa4FwvhqGYN{Sb8E3#w~^b+Nlms z0|b|#5CKF1H<#rQ0U>|e#k|s~=5qaHiL(DLLL8al;g3Bn2K~8pnHqgJ2H`F1apCA> zmI&Q`sI&8vHmUXcclpHinWUgSqts7 zp%0BO_hkgY@P%ng;c*u`j0PVX{#}q#K;OWG(X8~CWh$IQ!N`Btx^iviQ=#cHld~tZ z(09ni(Ldng$ToI+{O%3Ts5$3s+!wz&|nP zY!jwSI>{pgRb)5|de27;o&%Ti0Pcq*9m1(x$UZEm=olUu9)=8eXy_CTxRH{Vi&WX3 zTb9x{4ho^lmHdCu#P1@;#l+%bxGp0GJ<)H* z7#axq0Dj-Iun3QKHT=~{$(%6B5b|HygcJe3W$G0cBclhn1JFu95m7i0sDruB`-$+KVx%BwIuMxThw`oXo|Y+2VBy00%^uC3O?%BB&O$>Ra3P3x^;y&%Yv@!(-gkC=En3z}od zW2ZUZ5Y`?|h@wbk_81&qD0oK3BF*}__xR~3>yMjLN*j&5UxnnlJGSDy;_@G$>bJ9`& zD0^((1b^=h5#lG|NMPJ+0E%8HfV0v`1n zY4on4umu?+A|Ntu$S_REFd8xwqlR-c3eC__gH~$R49`MSXBU5bJ4DwR_y(U4A%})0 zRGzX148B6c=Mc6}9+273iqsG$vMnDT6lYZXgInB*{ocF_~|6)K^D{%p7C0 z8wwMlfsi^JGq2t-x3q#lQp^xt6(B9l0C^>)LxJX<@C|>R31(ll0RbTyfQ(QwhzsT< zZ=Z!JZswR9<07^)bDZEam|Vs{3^-}V*TBxgmOEm!oQfPU|5Y(Ph46%r#Qcp?o5WJa z#R(HddR0JzQvlK<{0nqO)IDbTP0T1RxXKWv3hw2<5sWwo?*_t%Uj1q@AT()8;W=Ex zV+In#UfqB2bcgzj#sbJ=YK}MOj%~jo9C*|`W95At$z@>#%xk$)u9&oB$v6mL7>pPe^@c$nTqjRJrzS zA+Kx(JvEMp!cb{o%D@<~9~7tpcZ$<3OjZO@1Fr;L1IY^5gmOZAO4#Qb^I}8nLp>dp zIW3MkKtBCzRBEe`S{eXWXjaI^t}^b5nh%#Y7XdAQYJwES!`cMS7~{E(HJ%>|Re@sn z(dh@gYQoe4zcs}(mUwm)ItVqxb89=i&eB^V;Lp19apF4}S!m{$GE3hwNUMxZSpD66 zHbz)ZWevixG2Qgjx3-nwhTiCY)TWWOWu#hqbynSQ)PK@7m-S}It*uO(YIkU?0Q)j^ z8q-04r>YGkH!?lGrvb}mu25^B7#PR0&Z2j@+&|y4!yqWXl|fKX>Pv;m%Gz#j=HN7j zn`*b&O^s=cHm${}Cg(ihpmk9$Uba$L*Qv__y>bx0lUyXP#6ay-vZ!J_LbZZuJ+=zC zt$J?Lnt6;8EnvQDJyw&}w6Xf3`PkI3t;kY;!@kpJG<$pdCw0_vON|7^@IzznCQK+p z?Se@!=hXm1=>)UO7(~rhBC7>lGBW~W)Ek44%;wqSCnl^=qZ+@KX6JPH4jI5S4=Y+K zEluEkh*U^yIMj_VnO`(uY&Wx(u}R$NM@v1I8Z@*rp+{p4a{&_#;IrJ(%sYZj6Hj@6 zeT6pPf$gN3G~Ho!OFT8zl9B{4X@hZ2sZ^ma5%6$Sa== zT}ZYHR%Alg=rAL=sypNkLduX+C$n}$#(s!dSxx?**f%jxRpAG6%ClBH#2?T#Cq^4V zmUk(2RBM!I&P(WEeH}4%9aiaK6Sr!Ah!{OKk)|kGDxXR=Rn-P6=*~=XZ6kyCH6$#t zNC3sUpHp6zIWclH_<&zzxWG8nCYupom69`i3ey0SyfdStu_~MiywnH9Ccr=SK-eZk zXH}g#$7XF2IauUpLPMNv?m!NpC&)%`#;_t){DiFQn{R=#W3>Fh!XP!RP{vDtV%X{Awf1CpN(J)?CgeXFXHHPYfnJfl&&9o1Wq zouFw0b5#ZojJvVcxxpobPne*_ByUN1!-U3HEeWg)1XW0TxpC&C@hk#RGqnaoFoY&R zE@c{Vlc~xxfrT+B1k=UF=6Ys-gT~a)p@AYa8{i_snuoH{Kn2ylUKR86DMPCRK_lj9 z5;=JQwuhl40_HD6B4Je~2q_f97AOG>Ww~K&G^n*2I$`M;Yg<1-tZIxgaR($cMaYR; ztT{d8Y1ZAau5;18$pyP9pVNm8yG8pb6JhoKdv>X zFbtEDO(orSW(fZSWQOqfXv2-x(f4F9CU~Wd!bt@VzH`ME)Q>Ju3lK%Okl4W`6@KIA9Bs7 zcU_k1oo)hbcAPo-tP_lX4}gzAITFGB67&}+GmIOTb68!|=?Q4@`>37!`2RX%)3 z-xEj2#R6U%AwiElH$A@lbf;1xEY-fN`oVmxn)0>{^8XmO$4kc7=zJc> zqmG+?%-Hm>5mic@{s66K`0$z{?TY#wt4$XOH(x7heYgE=zq?HxNM>mb>%nT7F`$eE zWunpuwYp7c67Sl7PfBpwENEoPayn0DmQ3*zxTC*M%a(lgBQ8zO6H4`*&;qLcpnHO= z#zIUs!o^8c$>Cc|AM>n_EP~%lnmdwWBmJOi+MLuBD9WUiwOLYx&$v>V38lxW)l&+| zC8b_|Xi8bVL`r95#*)M?($->ST&$j!o%=S8aJN^*>b#tPA*ySvX2oR$^QP2W=0bML z|8X3Viw?M>a_@BV|g= z-(@KC3x#V96JP#Imm#h0=#ClFy5An9C4rxYR7+Y*IcbApHSGrdSbW`!z<4m>nHC9Z z66CAdG5)J)6-2KCb$p`b6R?;S10B}_BGuUBCKQ!_dXh)rCllQu23~{VRcgYM=akjv z!p9<7zl=3gJJXa(0Y3@LScW41E#+cChD0A`sem|`?FgjB@iNnlZGmoF#&hil#z;P_ z43NdN3N{w=)Q764iD3px>76>O#A)qKV$MfOC7pV1MV4ry9;g_vDz~`2s@`ZeA!HlM zmok%o1ni$?Muh(z&6+iRu2KHmNIXfz1c>yytpbz&gy|G8A(IoP9;@Evz6sSD7@SNl z*Vyr6%t-traGfdYBXb^UIa^FwcCDYQi;V`%teHY_s%-4PS#vPYe)A7rq z8rb|nmj)mK5PvP#D)W33jW{sIyg{AmkwXvTno*2RMH{aenk3DX5}W0-%r2G?-0s$j z*!Ty(^)!vi@}1|R4cvAUv8Yk+nzq+uv6^V2y5D6nYLJZDuo={Ipctb);lPw_rkU@Y z=H@Jaw{7>g4qyK?_8x(~3)Kels#?unURTBX_n2#L+<$R&iZ+)HezbQyG~dGJ8`g+( zi_EvE`DT24RODtXbo5*AynnZS4(iEo4YUOWJrnfoYghC|9R2_%iqd|}1 zPGJmYzkj=?0NDo`G0}J-woyOt8UQJ1hdpPbq`eV!>Qy;jQ^Sx$RgncHqC_L56q8Mn zeKAY~X(tsDs4D{u@j}hZK^McIiNhFMYOD^PYgCieHG|gol`^+%c~J9Wu~BJ5o(l`X zj4}ovTA46d2K3=II^7gLOrSwDbkLL$J6zhfGk;%eu4*P&*dYdUESn*8JiYNlwN!wm zahz6~juaHB@W|BC$iGttClh9(&dO>!EVq;;$r%?C>B z8d@8qRb&h;GNIADvPhths{ zV-%*i0TQ)K(+KK3={#mWkw6$9$f6$JCTkDb9#X-$eWk{}#E*W{g&Djm7gtwr+{tYHQm9Pm6M45tKxA`E zd3LB~pn7Y7)FpXr=C4}eCR32*f`2TTZ$=N;pLB*_GU6a&ss%Y+=s?0CbV?^dMkf~t zqf{Ya(kaM-ofJ!_E!$LIL2bt5P}8=pCr4aQ%r@68S7#xLHxAwgBrr%o z7~d|NRs4J44H{u2w{QRpVsBs23&+X|La#9h(WHnfD=;oq_WQ1=7r}w(tY)okSdrFR zYm|osM=M@7DI*;ttZ*ru4FM5FchJ!VdvbAMZC)l7ZEeCMqV zgkyZo?4qMXw^Kx;mUXtZvYz{K?$eA2_`f~&tX*#AQuvuc7WkduQ1WSvSzVbzg z7MGEDS7WBitsm-dIQv5g4L`3tB?IblYih;7U&8(|@ZfJC8;rr^3;?9w9+eS2L(+FX(J>NZ29O7y89bu|yEL>1@M)m+D&-=@OUSCjl#evI4Yc zq{@OJiXFzu;CiLC*^5aK3IS8RRQnwg5VS#8f<0PdKV-`x3Pju-ZUuLO8=?CUsn3&f zmQjzU2&R2bZXBg#Wi7?w$5#Eq=oo?KOM^Q}PIJ{n1FO;kEa6)nduW{<)f_OizH+Vc zhuhH`mWY%0H)*^x;Aotx62UA`-qM{a`$9@03Dg!zBT%VTQh?VRWL+F+T82E{ zgGlA8=`9FA-sFeSa?XnnY+nD=8ux^X64qZj@jclligjN9llB7* zNeIq5h{!BxxX&pfgi94kC9Zg7QFn1#qEGZo(ki>El#0asoXj$v{PkY827sCShzHj|P(< z_q{~Go8hFq=IGxbVy_#txs@cKHTt@$bu9loHZHs6zJaYXJY86S2eGB4a%$uA*9XgO zoi>-}&+O?QzqM?S-`ZXF)DLdEspGPsC1?^OW@Vn1NvQ6b5wli?6r?BWo#83T4TdjG z7>?T`BN1rIzl1@wLwdDGAc~MWEP@+G%!oLe^CY`-&XW(5@+8*Vu4c}iniq$+l5ku$ z#%A8Rd=7CH2*wzH=e~v`MwM(=;?il@+)BaLtpxE-a_e4`y}V4mJKtwBhO{lQ2-FaA zeLh>S7ppam>wSj*iOA71$ZH167y4bNhPJAxvFW2al27@F^ z+L5d7B&|S=rGCknsUSYGAUuF#8vLO#0m4v~xGCW{R6`tphRc$LCAWx3U^0V*DRkv! zYLE;MlB*{Pj@Ud)#?(X4o;`Yz(B^&`3OAAAmZJl`p_3u}CbcMIV@#tMp5^#6g+|Ea zRTecPFTj~p%Xy&##HQrZDkwDRXIP1#afKyiec8Asz*80-7UhI!J*R*5*WUh@1N zM|CZItiQ{Dj1W^Q%bgN#9X{lvjQ0SrrL9VDA#I^c`(YxdA zvk*CGQu=^W%(pbLhrz}r0sNH!!bn$8i(ZW8F&DJy93Q>0s93_ z85C<^z`z7a*5J_@Q%4I{g>;gkyYg(B3XEjfc_w^I{3;>9BJh=OfrQ+ZZ-Nle@GP~V zn8B}rk;zhP@ZuZm5H&1`NjJps{KyoB5sfRSi;o{M;xbt{fuhi0!q5bHV`8Ek9fgcA z!9AImfGhzhe?S<+?}pPj@%TfYvBEI}CI>bGU9OA46nAV^^D@!$f&(x`bX*{SQ#q)q z7lO1-OCLFj5^_|t^TI6`W%;HKMj6&pKn7+;kb*3soJ^kER&NZ|k%f#BD$gC8xlB_= zNr^19@?vQ(Lm-O0LZewyGgvn;TeRqko^!_EE=W6C1sf!$NQsv$Edd#51HmydxJEix z3Nx&|GELw@T!&dp!xcOFqA~@R3|FFc%ev8CJxOOob+S;n$AvMgqNc{~We7oD(JF$t zaZUd^O5aK^OgWuS)b`De)S<=M==SBJsuq{VmxC8+6J7rgToifLxx;cc`y(+KQZOZ#L)=lC4)3JtBcium-Xc+e> z#ox!K(!p%@+fxnRoxZxBpCdP*b5T?;X6K9fi}lULQ8B7UFgsl zr1R7O?xRm0UpT7$T&yn7KH_63lcbyyjcC~zdifwSuvWoepRE{#0;{WT)faK$2a5hx;RsCcp%{L zM7B<@`|0Af&T2Sp7J}JWzCr`~tVtoq6!ybxv7p1n<*74xwEP45T{i4CTTOr8N+gHG^=fW)KtE^Qzc4jt9Nt zK(A_uecb6<&AYaGe}C8XNCy)G;ku_|9DW7gO)$5G4VV{00dH(H-@h>6+lD)PObG!m zW*EodtBF9eCV#*HR>ktVSXVN&;b<~jUzOuGe_PB8+bC3q#j5%CnauA;`%%zPC5_2f zIb}5Vm|q@sQ$I8u8syDv%+9>J}u6F z7I<(ZShQ!6`&t}68Vqan&t9+B#cHFUuRiazuVsd#))60^kLTwYMrY+V0P4kT^5X0H z|6RQK`xVyB4}a0!kHwp(i%IeDVFNN(g3MkoRuhXMUMTLHJ-6&{K>yy7f|Ki&-0mu2doX5X^`_ANCxCCx4%R_5A7AfBV}PPxa7``k-Rev!KIw zKxCKW^VLF#(HDFGpL+J)4-MB0;=~rgQ2HraTcS!-IFbKcVLZpzWz~WS zg*F911v-U^k@Nk)l>UC;j0l7^oNUgrzq2c$D#oifx9rT6zH4W4kuPr96N=uo8-J6) z`IbGI(s%7_GM--)0_3;cEtWpq*T({r-RDi*R*hE>p!|Bs&2(@Z?AC$Wt&G}NAde<#WSbu0PKIoo4 zY8|9r2&#rH?B1RE(B5F<*1;R^K6o$zo{uk!ofl;9$?IH`7)R?k)h$xV!gKXP50+gZ zz@K}uT3lZ_gOLYWrmb@UWbi8({xO4FIswgHe$LBu^FH=!HW)KRyaiDt; zm=-SeqrS1UM`3nYcQ?n8YJZOl;2`tFcKukqxxU(J%1U~x>1=JO6H+x(&@5*k$sToU zbW5sk3rfX$))zleYpvhT^1MfxfN8h>1tvpeS=)yg3{b^IlGvjT+Swwve+cgHcsWL5Jvokemkmn zcjILLv_=%e0U(!Oo}j@FaaUtw!_`!as}m<|u{k>#pP=>1Y>MN78FIE3muN_q)~S#G z;RuM}M)*_vEM^pCQ6;H@aYZbm8qsC-=*Gsyp8vomu^ZyR`RQ??2Pg zo-@65N_U^o(ZF2H4`iQFOaWh?4Zwf=ev=wJ+C}bQneNcgw&doH4fU`|cWkNmMzL)T z&GBcu5FqL%*sbiy9vh^v0|U3TWKC0>D8CvC`PlQhb30Y_wSNhG*VZE#ocH9&P=0?E zRC5e?8qenIqe1s#dibziN^#$2nbGcsc-QS~#T4j@`*!00YB)SO>Z%j=ls!DIUw&y9 z5hTzZ)NK}MM-xqf;izr-uzi)bw!G&GsD6;WE;{>n+FW1u3rLPteV5TNAClN!S@+k1 zf)=lw6_5siw|}q9U!;8p9XRLX`FtS+U*Rxl`UA{o=Y`f5P5R9>s%b+<=gOAx*r}(46@dXO$ew7?61yQNk$gFVNp z*jkXTgntp{a=IwJQibskr<=TdjoLVV5`eO&yGJnIH3BO!x!VxTI^3mW!(-m9U)`8n zcB>`;`2P89487d&XNx$Bvj_gD4b#2&t=asuv%T2h;luv=`|9qir_+3XtdT}XyLqBTsyDF zb0Mx54qTw0NZG5^0!mFC!Bgy_Zs72w&%&zN@Llz&W1TN(aoN|x$#d!WZ^diE3aEj$ zDb)5i*cwi&>Pk-W<>mFfwha)frkD)(-{GHKuiqRWAMaX_r|lNk!iUQ}u41n8jiVim zoPVpb7_SRiwOQqi=MzV$#nl^WQnsaB7cCg~P749=Lcm)_EQChCh<=Ns9te}MNAqdS zIUO2N{K^!|sTI5;hOW?!FOR;XCC6Imjrqmw)tjU3fsUZV9u1tq@Q2aQVA)Ov<12OX zlSTdbf7Xln;N9@_vmf-#X(obZU9BsgVA_o7w7L(zJIe?T*!sI{#?m${i>g=;ZEz7HQ(7lBRwEM(%M8khg#dtSqDVehV17qz8z(fwrX29OhrHc1_` z%WCnL*-ypf$lEkk>NPvqypcLnH}?8n%y)p+^!m<;rGb?Y-F+_@N_5W!(2%10ZzoHO z?!)Vb7~OMe7;3b?gp#8tI;X+FjDLMFXod)qNQWU$+L=6Po7KD1t);be?7Lf-i?ng} z;>SV%KDMn@_hY3m43pUV5$Il@Yd22V_8VG&bzn2!A3&S=v|g zu35Msn>jy>nyQxVsNa0I*{tjT(D4&!PuKbsINsyUYESmIc!KG^>zFIq7B{=7JweD3 z9h=<}IvFTout^qn{4?Z&*=)_&_R}k9SId+(3mI82V|%?8SFnYmr-C!?>0ktt&o(IA zMW^cl9cZpEuf~(JpQo=^<9{nI#Aqrn%u_A$=C7BnGRkhPPkw$U=WkY>*e;G>-i0QQ z+2Yw`aemEdov#Wx1;%?un8Df20C3h61r!bB#ec~2p#Flv-L4J%W19G8JQ;M`)+_Gm zR4DqRR)ubDxlM>m&IVp*0LMmS_Qhnz3kP(4`}24*`2y-JP;P}>9DhfHAB#6s&)Q=0 z`)bv6W;b`-s8Y?ZguGq>Sj>pNw~0~!Z!eUrZ!`$S0Vt#5iMZqB-I%}kAEXfNMm zmtVHG`LnHk?(L9uh7F1&^%Jpp3 z95hhyg1`}S>1upltbYbXsd5s{ML#}EPsfkX^3$>0^uke&uq5?rOlB9eN+|84!NY$- z2CLvy8j@q)6yTA^@g9z()R&8DAtf&O#}vVjr;EjEGMj@|B#ALTi_mLwsMn_q6u7Ft zP{N|U$$zFPA5DdantJ38x}U1W#YI^>pIyv3^yfu|MJgJIm4D~fxTTCY8oVu5i;c!n z`54QxXsXJyt_K^vXf?Vj&d0L;`1n*AGMV8|uZ8<>Ku~@NGPMBpaxr<+3y}oKccb~@ z^}i`CLWC$kpN)Sy@kTuA4LTG&yM8^Rv)A#}idyf_RUU+`17Z-8P&lo@7whx!RWUf> zkLBQ`HL4>p5`V?`$5VduOc~$&4b0!r{Ef`t*!)e*-_-og%-_83gA00dq@!tfb=(wL zRNYa0Ha`E6plw?FT$c2t1D)OSKbdm>S(hSEbqk%FLQnSht z*&S%?8gwS*n}gJM`F1;YdtXbRi%yTOf7U-=rOm&7g(Ek#v+OPTWY^u&z|!XA(dIit z#k5DG@`e8K=<1*LcjiL|(ifR>(Ac&JANK*wE*8$DRVrQLj4#2aMZyy??&CLv{PG1XD9kG|R?Y?`%_bqoeM;;NpYnHE#{A|9>}CU>WYY+D(jDv?ZL0ECBv&AC$ph z$8o?XoCw?;#i)a@&WKf7b3+)4>jEgO{lQG@NtYnnR@u%MpBLwY;mNLY)PI^nqfJm? zmtCrTqb4Ku%lrWdyBLn1QJHG3Fb--HVZCd>!|!rRX_ZmG6kxx8ADtaOhuT-;y0^m% zbbqrLeP$`8+OFC4H|mtx^bovdN&ogmgUzCQoVIPnBlWr3Im(Xyy77$MJ=Pu%$=##v zw0@fvy~V~959E?R*jBIb=NnUF?MxO9WYL$11yHOX$icA}+hhNiU;N~;{rSr;uK&1o z2|I(~Jv(wo``y?^Iq8+_vL-EU0*=H1vsA!*Wy7^Wo@+jB)lxaDN|Z zvurx;Z+vZhSihWHN(;V89`h_aIG52o*r&kaOGr(PoKH1sU8g>nhmY`qT{}8p{LntR zkMPcJ)RIx+24dj74s!xYv3hX@7kR$N(5}fIyg!PXVayoP7<0Ht=G$_DLA{wuP*| zuYsYJ?_gEorI&)28#C31rPk8zJJ_%G5HtBLH*?~_$cpKfJStg)>D-ECb%n0B;P=8h$^0n%%uT^hfSbd4I5(s?_ zR*&{VfGp)c1K~?Mnm}-^Vf$f#BA5GMw4Y4MmE1Y?`kz0fL^xw3`47MR4}ZV>55N2mzx+4x z%bx)A54-#iyZnEFU7p11eqp19c-^n;`u{&*b|tB#w2e|pX}fwvr4#&AtC!4n>9ATd zyZC3j?FozPY8dtFwQY>wlQ*n9Q}L?gq||D2&-41(e~q?I&d8y-HLr)3mcG z@bmG(?LVCLKb-YHoPYH{ob^AP^*@~TKb-YHO631_zWN`|`5(?XCg+TA?ChRlPEaau z2n@1h5|tXyYcqCvEVIq>$8p<~7Y{SrJpT-5m3Wf5bMM_dM+n#w$Qn8=49VgQ2LsD? zom0*Poe4B5nc5K1Dhf!X(4iTt!Vi4s&Klq$E5bd-S&0vmE`P-d@T!!~}=dBb_@VIQGjy9(TJQnYk4V zd_cWbc!vc+(tE^E;BG~Ug_nRbXX4D3z^gM;FJddnC)!ZcJQuX^)H@{7*_s&4 zhNQ3;M>IxPzJFw{m)(+?PN#@xMmjmZXF!wqi@`tZS(^8g#+`_Ps&5{ssbo4Erkk`= zKV1@1EzfLdV|H15!i9BU6OmUI9sd3t?HSp79{)8fwO!P`At~c4B=)Qatz+eLS1vng zQL}13?uz`x1wo6vb9~4iX&DcgNq{qh=Jh56mt}_;pnvm<6Tt^rrugvvniCs{V)5cP zBG;ZWP%=|8!$|czv6c=Y#je)+#PT8hgxJJK$W2NlMMJuTPmKhN=5^e`Kb6#mP~nb} zG)BpaV{)bv?+N6S?&oQC!=G(p{Jbwx^wdh8`=^$+rxJvYX$mk)gxe8ULB~ufT2rBR<;}I^M zWWB~lU-cH(;IRXaqeGlo*ywu?jw*Zul_J|8xPM{8^l;}P+XCj)LhqpRpFd)Y1SZsU z>~{Dig;3;<4ASOBP zq<;beHg^?SpN!Y8aOza?qQrBn2wyC@3DZNH#cX3K6F|Pd_2@AlQt2H zq_nH#mIpSuZ1(#WV9dp`q(E>v#RC`BGzF)Qp<6*83137z@NyfgbB~B)0Z@Nn9m9Y2 zP>n;*L}goG=y@hzq%q+6*MO09Nw_7PK$ZMbV`x$|n0%@jAh|O7L@RDN4Q{PKDtc;g zPmvxaGKQ=zC^UL@d<7tT$xq|#vZLi~1Vk6eBN26D027QSWI*q;!FdS zA$0SC&K%*--Hit!ZbK<`F$AR&4~l;#LRkty*^CFJB|=#aL8-=r(vI#?D#b2N#93kf z+A*I`3%fYEQHoQhFEGlYe!CK{awW3zX1vOqk(I0QD*HqELGP!en{{b{ZULc-9A~)_ zzvvP#*yAj8sfGX~>W+N|ydtVo;K-qTg-D1j5QPW?Uqf$7cT`m#3!HD~Lt%e-EYM6u zLKldH9}9>nqN$QPqLydDl9GMS3PmTnB$A5xUWvx|knp1zh?k&LA0IqeMZoccX-C86 zUa8iJ%haFiu8ncJekvtBU6$i!-S@OEhRxyuZ)rp?8b5^HoA9m?(4MKVeEGz~jdXsJ zm?Q9uG^~U!fU!CUCj0u1e>;Cb-0y_%N&N#j_T@ow8l)+g7Qq_;f*B?XX)|FL1Xzp% za0-&LIq^p5N`BmRMY*G+Sr@Q6F0dMUaw=%bA;p8OC~@W+wfBM{1X_2`G|Nz-IJSPg z3n{MU6u@v(_nA;(m5LML#6yWFJOwz!YJMhUutsq_geho*?kzTA8LNMkXSxe1#)Ao{ zMj78szUB+-^9$=qJx)oW^>cA8bM%=FVDyL`G^sqA^~YE*zS3GiJ#1Pw+Y<8X7vlnr zxwwe}T3nlwz1ocH9P1Y20E>ql>YoK@@b#03LCxZHKrye(nSxq?7qrNm@oc2Ei}3)) zLlX710zA~uehxXPS)6|kC>~OR^44Pn1e>mz@bc>wC&QWrHQ_!z0MxS_`UH|b)Z%og zG1s7^jP|)I$<%DNMJQG+PK6i`%?K^92RXv5Y$k-m^^5Uf$3s1!C-y)G%b+Hwr zi>=Rfar||}L|xPLF1BauVmn3`+n?*Acvmu+TFKh}`FSWdwG=lV4;?9g!*xS(cAyi+ zA$XTDbtL$(O&kbbXyQ10;kKkWBfx0`;8XXh{g1d`nK*wG5#=Y2%75Ydr}&kIrVU-> zeN!wxM-+@gWAV4%Ruw-3Jr1`c--%7+y2leo{nK|}#aTd2=#O}vHn|i0@-EbgFWvzJr>}dUun-e|-sd#{<3%L&SX$pznImeXUGUS~v>)Bnymq zqvJt{9`7**6fs90Ye&M3wt$ES73xO99B+TL5OY`4`jN1s?GEC>g}O4#NjKXuQ57pk z0H1UL9j}EjgotLM3?AZv_iK&?8#Ydu1+>qTL^Lq&!aH6Aa_tE4k+;<`*NR_N1{`(! zJO!lBM?`~?u8?EG0$w9>Ek|GW#$C)}?eUa){N?Q2tQWsy+n9JQIycjm>(mn`;%a|# zF7}0|2YuGN$@mw9b8#;nJzQqIAdG)YHy8Kj&qHM?Mmwz;+i69#vmB$H_KfYc!|jAu z(Rh9K+$YrKV;8GFBkp>{7{yfd&c)Rnj|Cj1XpKjM{F>vTN9#r7!58aJ92i$-KPTuV z$J5Ek%fY$Xt{f*r4_>>?&2W)78S;OGE2_EAUWWObDCs}eAy0SayssM|9O|hJ*s@5h z@J&!;Oy`>BYKgveZ`>Qi;Y4&HD>1T$iC18%6RwrOhBk9?Kz-c{8bE6Y`G50ANB`n&4g+ksB%-#h zyY>h`rb_4<2(go{2(aJu4nmQAXU>U=1lp~+WEJ-{S#ZvD{$qZAZ1FLy#Dp4=jKPHR zdc0y$C&h%~9ub;cMyB8s$_9VQ(X^sIZJAawl2)Wruo{N8N!=RF#v9E|of?r#5*nKN zY8jW7$ofogNsDf2X(k}8Xdufo0cnSUd_;Ivq|U*<{rWA27x|XvUrKJe{7q3qfj7RT zr>NvqRxu*l2CX|q^Tz9k!fbp?<4eRk34xxBt!7K9az|(g5{gNb3N3$7+>e_gRSBue z0@YZg6seA^3*!}{LU~Bl#%rWFh=_n96hd6RSpa!49EgO0*B(yELvd6RXOR7=*f!dKz9?3co-rMd@II#c8kwxxA!k;T1v- z{=-`=nvs_P2>$)Y)DN=iQuS!({$n6bV9h<^6BQjM0^C?lP6&_}*(D5RqOOJmk^{Vq zCu0%HnAy#~S)1?inha}PW;e0sXJfn;wTKp%BEYrcfony8TaJGK*Nz7+tR_jNLhB(A zF(?deyk5j33zN|aYdrjlLcp4E#W89PURw;N5?R?De}YOuPQsO=^d12Sf%qn27}45| z(8&~t+aeuJ(MsU-Hzg31I_UV?O?@EqsHtw*)L#>uJ*$=cMe-eDre)lZg7UtK{yJ18 zp`>or-|lFj7ZrbWgU#f|EQxOYfo|BXR|n1(16bQeT}l1nOyj@b# zSWn8NR_}iW_xh7nFT~&eIK@koD@hpe1cf^%by<`Zy?`fkIaMp?O3dRF_bD~~q%MZa zMbPeWp$O&y_MoSKq=6OKX*6dzhuUEh%_;KhWo>?5TQ9>>`tv7AT=L)bVY)yzEk};X z1;R*J_X#Ag3#6q)f9SZ0mJa{Buexp~at={It*w7KiMcr(TJ#1d`ly=5Ys5u89?DnO zi7j@vQ7_vb!kU{vrJ0+^C;I(t-!Nli`~KfT_U7-$RbX(6V+*z76l(vsdR+n5=3Ih5x;+pwB+MWb>}U&x|N@0W-l{3}Mbko8iB<#=lSPMnDGpFZYDBmf+3( z-Q9l>WYPa}KcFR}KkT#q&_*MBBlaX_FCrz{SUcjY^Fmrqkfsw}+u>a@bGL$GMV#Jb za=EWe5N|R;n+$gX;eVzhRQ$nsM8I>4$otWWGN|{*5}Kd(9Xay zuiHjD(SCrjN;ouO;s3EvGu<7LSz3e;D&5zC}*m%%Ik~`V};Qg@7TAQ+$ zK#DDLrxW?fqoIqd1+q|%QlSMRE^Ycx9nZRxqpBD zxFr&e31q*1GQ|W0)F#Z&b9cSg&;@bf?tIVzl#eUfXX005? zfrZEts@S}W4OQ%jDl8PB6jD&hGSPQ~{XK&rDl2J_V^EYK_Y3Ez4Or|cSO-8L+JN%E zK<4{TVG+G0^HE4ej#m>JG~LjsrG9@$j*%EBkM;z{GwGJc0Sphp)KQx_1a}UB{>hQx zeTy*?LU^-D%SA(ZRu&BRFD|YwZ$>&>&u>6xO=3)i3@}+B>cWWz!^wXogd}ee<^eTYD;IC-#fxU z91z!ZenCs6BdaH9)FM2ewV$LgEPyt^vAuq|DHZxo1_1~QYDLg@uA0{u#|*NlGzsWx zzOa<2LWXHhr0wOZ(;^>=8lNh+{=unm9HT?v-#Kl~d^PTk@qS*qdW|(jcdIunCI{^$Z@RWY!bGJ|# z&Kv}H3E+4*Vj<~17=(YA8-(!!cYyw@ZU^*oibBF&Vv1ds0$ZXXh{tu=85o)UM)NF% zEHE{rqVa^ioRXPwEZg;I2w7B&SN0?lJ=1J#A6E8L>t2$}lQtIe#c;u&5e4(b+=n03 z*eILcxmyB3%_tcQ3pBd1YyVVK`l*v}+)+<2e|rI*6)0kFLF<1RU9;FXI-Q>Wjg~Wi z8Mm2cvr(g!vc&gwpgvANtD8Wrv2K?lL6#(#1akuFKha>vptVk$fbvRSDN|sL=H2n> z(OJEERrxQ@{Q7m+}o+1vnqrXvmnN?wX-V@!{AB zD5D2)K(X10eyrW6Cd&_YQwy>O`aKjw3=F$!Jm?Aml+h zFHv&2sz=D>s?nr4RSeP2wqSwL)f3(2`&coI$wB^^Zhz^FqEbVVF&oHh z#2KKEC`N&v_e7{7tVg?7{&lPJWyu75r;F~~z3{-mM^cVNNO;7A=$OG}#e8u{_2J;o zaPB%VPUwGIq+{Kgmdk=SvnmdrML}kv$?_1(u{`hw3k-5^bYqXBWO~eOjZt5u0bUOv z^{}a*?yBHI{Zm{zWo3EjcC=)X;@_`G)x#b&yiEi`9N*r1Sbr0FmxC2!s8XM zss6SJ2jM$cve((n9+6IQhi)Z1ola>{v5n>8zwFzL(Mcm46_xR&kq-l8bbw5SXz+5N zwU3%t3U7l3fr;~52~R0oMTzk?vWd4n&tq`$;;m}(uTn$NEe^UEw7*fl$rKv`Ih?6o($Db;VCSGj+q zAb@`}Ov4qeQj>w(lpo7ErPwiS+$v6|oEMhOm*D0X0WO@YklTf7hTGExls|%-mEVzL z=kCZQjYNuB6e0x$OmQqzzhNy6TV-Vn-jNf-#p^cE@<3l!_Y3 z1PPXn1WP1$u%#8_}pEj;t60AC4ivwct7m9h=`0{^{jmMvu!UeKZ_QJ}qr}TCQgadVFz{i9sZ( zN+1H$2$Z~qoq$?*-YWNJ?{j~19=*oo_+@bxTdcJlV}CFO4H+ItpSbh6`iAk9lKO`7 z+d5@7rTHic@q%1N!_o>ZlH!N@w}eO660neAr9N}*Y9vmrqg7Jedn0~!UbuO);pdnO=a?%p7cLxTct}!Gx0!z}e)H{G`_`*&SAmTIMn^Gq7YOE)GFK+W=jX{Eq83xM9$x?I zcpvVmj@_85V|V=Nuc4#Kmfj-=zU%8YX8;{Kg41KCQ6n2JOt^v#V=i9cin>XrP6%m9 z-49VoDvT*o4zCv3VkPfh@ffwq3Ch>4hUvhe1x`nQ7npyj?J;16jZmSI0rTu7 zq7oWKBjmnJe7|2xYGo5Gfg%)AaEzgX<^{-cCqcD{Y|AQ}9*%$hC=Kt+Mv|LPsCcXH z+fZm|1f+Vm5_Sg8MjQ#@rh_c$a*LX{xD_(*bS7IW=9mwtCCJCh_H~;v+&v%^MPz6 zzVY_Hp^8?iczr;#f2fUeR`!3Ah2>wlh2`5n1^Bac3%}NG|NP43Z#T$C@@pgYSLT1G z+`qFaVj44-kJ5}LG~}Y-&}|%}of&i~k$ii5%LxBcxWv;k z_4@JY(E+)`lP{bPtpv?esE>pM*`&NeXpe%#rJArs&0vv|i957RBffjI9B92gO7fz= z%v)e|OF#oQl9HNtetz895`AEZLaisNr;6nEhjfB``sBTla4{6w8$$H(z%!g+PRc){ z>ANL3+A@DTFkpJ-0w^2Pl;&@bQIncEhRtwBKApj*i!yLY_*~wbIMfhl4mLFWT_nT` zO2XHLd|{RDa{4_-w+sCOISu-S?B<;K9w^h?xWnHbFd%yz%w4&#yzB$IE9aL*NRXXh zT3!0FxU#e=fjmm_rC}kZ#RRe(dukhVe_6NW@J4@WBGIN{hFzBEP+z$Lb{wVnhXo|pHN=>JQ6%jG#oWT+X1x8Hxb|HN`mcH%CS~0G1 zWiWr?6rB@=(LaA81E#75ha@QRdQ zBcO#u*eJkA0OJ4`F0#WMnyn*CdFNVpY)gL#e41*Pe1lpvoka=}(s=;k5LY9RF)`Ev zS6Jfhg_bHuvYa+WX$OUl5IYW1VMCKIeu`S)%0*=+b?n2ObPW*2iqprzc)NeD zaSVV0rfIT#1M3oLT)w6a+)S0ddeX=<3q*fFX%-GP%aRl`5d$AK0twBcICTjD^k=N7 zGy*;1O45nEk}M{D6A8*J=rfwSPk27T-%2Q{bcj2I^B><+rpAa{Ors`l<8pY*uvJ)! zvkL9$E6~Q(=T*ZhvhytZ+LJiq0@;7cBr>crWw-ikCVEp&S_>!_M6G-qSAE#Dg>*{B zm}VtfT8FkI&$Q|W#y?mYNrP)y7uR^A8WoCdbAsgPE$W%oz_~UBDf9KrPU1oy|eTuNqnPR}h22p>aoHA_< z3~s~`E>)(cTOxoMe8ZSY`cz|6-}(3xIFXwWBD$0Z;rr8#iR>Y|V z>3ED$O|&uA*Nkq0KqRZ1aRc;Ov$EJ-kqpa1sb94$o7P#u;-0?znCM&cm_7}t(qiLI zS@xJ9vDF(Iox`f&S5s&$!c2c!#06gijdVvLx<&DIie#*0m^yhY0Naw7#4$5~L*gAx z;DV_&K%!YcJ8K+nH}AG8`}>=f>fYVKQLSDKjo5I2_aaeK204{uMZB5!fmV(saNaWb z95lR`iHDuokN}Py_fydcR{t0~!oqb%>UVJTCtY4J=P~3>!`-X#uGxPbV#iRkqaFgJx18k?WhHt5Yn;Tn=GNh@J4i2ODkXaf=l<@*3(eO(eX|w}o zf<8_E^Czl~Y00HzPH_O(+eu+5+OnZm$9NG}DmO?WEBu?dBtd^Jt3g@6D7`C{I5yzu z$UDD~fv@C-*z>zA6N)~Fcy~i1cwR+cTfx*t?s{RJDAcZkEhYw*m8Mt2F`fXCI)cJi#DapelETwzMNMOJRnE61$9;=EU7_Hh%+Yy@6V%1wzm0!~XP zo5^PV5%p+BpxS@fel8K`VjX{q*z-e5(|}6L94ngTpv?g{OH4xvO8C6xMJ^N+f3*=~ z90O-M<=uwD%ESV^xa=2d%rjKJw)rbL@)i0@R5ikbH>Q0QmL1*yGF zAiC2ho>xA^C0IQo_De-6Ps~~_1|5h6_%=z{pvWW;y@Vwxx;{kOFU%K<&Z#IR|Lpra zXl<1(D5!t!9qW^*EF6BE)l!&1kl^n_l#n;gPfaOaOpmd6Coa=Q))1eDkXPZ~(3c3U zmT18|6e)^hIJ5fk-C5;yyMA`JbxF!aHgfi0I0^V4b)cGS*&_@o00<^Pj7*@d3#ycW z9Uka*4}IVxAb#SjvtZt`a1k&n0_YDr33Qn&1O+O#R6 zDILOUb%2ZU8^r$kPkMB*Z@?(G&}v8MB59Ppiy%S+X#kCWii!%@?Ho1F4l4(BPM2Zr z1gO22PS+GC)KM$HFm~npOEPlZ22Xu)-Ci171{Hd{LtCRKRb;175~7{DY-}}%{H7`a zNlAYhKM9p%CUSwSM0EHA3uYyeO@P3b(0V=V)xn{EwD5lS4Tvx^i@VFFlUx@zzPB`hj}#B(E|y=X=c zr%P(u$&Bp)TcFI))*Aq^wvXI#rP;hZI;DRIa%MO%3@GIWMgev&_FWnb>?Z{blD*gI z37DbJqA*ra*+=T{BX?mu*gAA{AP|N-Vy&N_?cAMRAJPtSM?eQXC9>SWUo%xMY97 zp@?*;W)#_3oIrL8lgLg`h!Dw6vzDkL6&_1@8g$i)+cW`{+E9tkexrF;Yn;}r=p)@D zL~KsN=a5J#YGOOYrzm@r0~;Hu4&}Bv4M-3%TdPKv!^)cii!e4sRFN;S$jP=Eg5d+)LVA5{zfY+z5K8twPj0QS7D$Rd90E67qZRc0- z7K-FlDJ7LO;E0c?MoQ!FOv^wQaaa%}H(%G?;7f|f6JzmmWH z=daZ5_rFrvZc5dH*`>^POt%B+X-pLR#x}99NhU@R-ZxG9W)s~q8bD@~|H*t${YfS_ zihuq4uYbcQ{P0U#c&{wnpL-5P6O&jpBp^N zqyswa(kZ?NYVPW0d2Y_-pH(+wTF2g)VUF;f8ori)BXKY4A85@g<@>JzG)jNa zrsh>ZH`xcHOmy1R{`)S)s8FuttQ-DHV6RM&EICM)EYuRY*7;!Iz5i&JEpOA8l>gv< z>}@FjW`7UKUmkz*4c$F%DBpu==0?&gvpc?aN~NDN)c)Q=U7uBMqpN;4OdG6!lxFwR zKu@HUUp>{j1^Q$9FpIYESws6Rr<|mJvEy(OS|&)oNkvKb(vypDV<7LK5ItE!g&v$t zf*r3(65CGMgw+gx=jX*`np-c^O^?eFZ~PmA|5fIe-x+_l9M>kKDOe)qJ8XhY9Cc*6 z|3i+;3_cC00_CZ=$sG4a07o3)K(;mF1!(HFP4u1G#|PR2Q)*X^Ab`zLzhwbURUGmm zn2`bg#751@M#P@vH1wkwwP69~_~vw+1Q?8A8(_nc;-$~=&pz?n;J6jN2Gu*_ffgqA zsPzc^WCni(J)>*>`4deQ^FS3rBpISxUPpXC=2?n)xybflMGcLy?Gyv=6XFNWIeImZ ziCV=SW!fP71J%*U6vOlYFQfUK2O>)Cv(05{{%>@$7pUbJ#0!_ib0ETwv736yMzyIGf( zESv$*I(?8()l7T>gX5jh=p)F42LF4wiK=zOEcE-rS}ZJQmcHwRIX<(j9!3p`oQpPp zHPU}6<6&45Cy4|5{Z`a7Z|P2^yH>F7??GhBys0Bd8%b#+^&QgQrL=cJBg{^bPUhZ3 zN5kaA?EquZ(RwN|skCJ`pm%)id5wzQt`6;&h+6OqZ>@s^PL6k^zQ}oaNR^>KIlw;$ z_~sZ}!sAax<&n0^zbOY)B;3zy8)VGwWe|T;;1GrrP1(+`D(cWQTud+I6_rQ+fv;;& zL9^TVDW8EX?vNc5074rCCf$ZFOUPFBEc~>lpp{D3*80G(Lb5Y3kXM2)%TNL4Q$vN$ z0TgrLi-)Ptk8S590)!q!A`kKky>8bHKbjqNL4TG2GVX)AF7V^HPVhoz-s`tWD=7EmEd~JT7wF2 zaHNdj-#b*?&Ifv%kKNn+{}1-I5a?|oc5e&+YrVAt^&61h2-M$&wB11cJxJSw`ex*4 z0Ws|WuXS~OjN1_Sn%~s_<1eI8NRfYl0^OG23zbkIh03Uq3?B-&B`AtO5u}DiHC|NX zMKz(Q4MlAzYGYBG7qxj&n-%@wFXj-pn=1)72XT8>8GaNuhvVjO+#GC>6$b=Vh9kw# z;rKZmKe0FP)mPpnB?gq zP&>BxNH$$z7Iu_O0Ctvk)Z!hrctPVvUQEG(*1Zj=XkAUptHU;!Wbwt%zJgHNLcM7>=;fKxN$Jlk&4`fjCr z-+OSxmluGs^)r^fJKvoJ$X}(+ga!4;*NL$(VcPQwr=Qb8V;=y;dZ)Jd=PFmT* zLJx9D+6dA{AgQQ#Ng`GTcRub++>R#Q`HO*_zZiSxFZw&*-`M}`>VJ0iKf9Xj>hU}J zzq+B9qz#RnOfHnN8f0!(#a&M(N8a=TPx?W)qaQ&CKjK38!62*!A*_GJg|J2;6oL$C zLE=aW>nua?xak~&5M=TS`M41B1OgDjADMy@B%zoVn~Gv#57uG?ti@SiE&8yQB491e z0&B^KwHyI!c@|j94A#;j$SVO@Bu#(?5{nFoi7;4<%-fQ%b_jsAIMvy*SzeMWFH2+c z+78UPCzsL6%Yn+vaVmc=v&t)h$}4dyudvFify%3KDzojn{3B5LN1V!Rr!EIZdwDHR zWj5MBa&qM#@ukKeY?rPDK&(k1xKu0yk!58HCLaKkpA8IKduy_&MED>7r8Dq4{M9}A zb}fCo*+_~4Qo1bbKcsKvoGMCBa@mnob|ja5m&?9OW#7xWR55=^%}WWgNw*y2)>QP& zA|aD5i+C@%Vsmh0@vteRzcN6=>V*J~B!D9s;79~`L$tmD3~xdJ-z9+W3%WEQWqhIm z#AmG#BtHKKrUTd1Vqj@XBp;PK$VkaclcyF*ak?}Elx=NkHZY9Ftp#Y@+VX5*D78C~ zckO|+X_+P}aK3*F>L~(2-mnMx86eQjdQgxd6lQ=x59Nc!KsOd=>Bl1LNI=FqkfxU@ z;$#@Uc8<>N!BPOk(hMNzydKEYdayhL1U98B5)!)PU*s%s=Asf2Qb|4O=%QvsykVw! z1O$49n^aTsskD1w%WNLMC89jcKf)guToZYrok z$8$tZ7zKY5fLJmS@b^cFUAsK#BPS^$V5Be@gi?gHxxKkY%BjY6&xcqc*Oi4BYN`5r}g^1#7aC7$_8|GzwR8 zH{3v_QJ~U$xRSP^1uDIRu%HvOJiyr`+BJXpQ@H)Vj7#Keql$ChE){D0ash=vf?&Nu2=9i7Fyxm5<%^;G3>|@FAVUpQOnKavSWq-p zbv+YR8f(PyVI#l6A9OHJgdW#H;(>pPcJB5>I5vkFbCFv?lg5``%S^qXK}>E z*C`1dlb17q&oNArUCz-Qw2wQ5=5+ha=<5eYuV*;r+()nnWmuo+aR{G%Iy|6haZz7X zh4kVanuG}aGwH6#H%D{R|nn(6HD9+IaF-Jdb~|a#LPD z&VK$j&|V-nunB^&$tGY9aQ&J(spVB3`=`{-tUxs3nTJVFQx2-g%UcDDBBx;HI$LtdNQZx)L#Jo79&sufrg+F zSy9_aO3C@#bQzD$Kw_#GNGN~1MSDGrcNix-o%gZwbE)MkNe!$;c0P+~DPTLuZ5<@Y zIcSV0Pl8yTrTNtjQ_jJoPMWF?5Xqxnr-r*^+#`xyDb#Q6C;HIzhe%83afH`lzO;0@ z#Db-MqnruT}49DC6y)J0!?-;8ILkIWtCVfc< zUC87M%Locb9H{9&eXLV}Vz$-mZEEeOSItK1mRGyB(JB7Ehhb^rTlk{#uSymF1DLLD zJ?T7kmHa3w8lGPo9gKeyq&hIP1M;i@A$dbf6a#r6q}=s>lRAQM0E3og17QZLZNQ)t z>Pq|zJ2DFQ?}N-ZI^$@eYu4*Lj5fp-!XqjOlEZ#@}s2u&)}x85fgu%^^^#^gt^V5|z9E_ftbLstw)t|ybIvcYKNDO9Ln5gNsN zCH0Y_Dk2Jia*zK4pwleqKeB{l0%hariU6ue$(5|O~N7^<53B7ix9lMEiFxH z@v`-VV1xst)4_i>DZl_-lDQE|SAV-+>7uSO=B60Q+>AvM$1kPooHY_p{Q3FZdSnLY zO~^AWAsvyo8=Y}+=B2Vpw3D0!Je86Mhk7WC93Rm-J}^#9i@*%gi3K`mUc5s15Wycw zJT61S%?P=s@@Q!vQ5~P3mt)aKl?n8Ut!~;hUpN2Fo{4`_lvIvQg^XUy2I75YZP`G! z{<{M%a7fX^9<>4RttFoj8FAQcy4F9lqIMB%{};_E>y)GD=sj(Oybytpj!TlEmFEDJ z555&6++9f&D>A`@dw!l0jQROIa0ZO{bo3YK6FKZpaU&A#{g^yp(EO0-KI*t?Dz0lA zt)WXCECGLoA%P^~l%|pK6t4J(GpTEsT91&a`FX-W-S;e*-f;GJ^a_j*#U$`f1Tv}! z=R4sjnyyWwHmFi%;_il2!hlqRH$@Ggj*ei^Tai-epnDu-E0XBDKrT(0tkh zjrTy##2DdY`^AP$?3gyaV-F1QY&}Z_*D@^1(DHwyOYfeZT}eG80g{|@G=CAzEF^;< zY$CJbOLf>1^hqhEr{pim5W3bN8XNLxCla5i6FKQuM7PvE-DMIQO_Cd>P6Gs?e4LKC zEbds<7NtB>{6dw@k;IKCpqX)KfUp@NVJlG?MUZb`qHHF)*r^Ra!32a;`cup|Q%pfh-ntYEQp+i|CmWr2^F68L&La>8i4rwLFm? zN+6Dw-35lm_aFkQ{B&MlD34inT-Tc8S9PH^ykW7^s>nYq2;-nGM8I+aF4h@y(WVjTKM`S`tOX+`9qJ}Ey(vQ^j^!qR~IFzadC-4AsS~?u%$AB>@ zhhAfdo{Wv0>fs5QFuns)$^+|(`hXYeAN&MT9GLpkNdU3*!~*D9+Ol=IQBOMLjd}@K z$`==TwveRe)>)#Y<4FCM#=%poc3=s)|B0$m>aCYMrOrY*8XQ)>E1Stqs>FYh@H8wK zBx<3YS;npq(acKTsX5*;^37iyyhBMk{+6Rt6hAnM!*aefw!CIoCvxgQ=meilk~XFfu-aKOk}?UM`UaYy08S?_P7koWa-2*+fiyoK zO5)0RKB|4-V*2ajik13&Snq$!p)$Yvx9Wp9+U?{$J)u&mh0JnEUZVGzw$-!jKYx5x znYh63{m*~?L{Wd zBj}|UQHPxDQMOIeZpvGHGUZDfuGAcwF&>w{`CO*da&N|)ct=bTk>zE13sg# zuxnet4p2RvQlH9g`Xzr$XfvJy2PtpdpUbc66N?7OBiv^sy)FxLk6qAgrRaT8ir#b) z5JDt*rU))_Kcm<&Od)nzP+mNTo9S2b!0t^IQfZ?4qy{0Qrzol6H(}La;g2SC=&k(p zkr#$3Ir51**_rY(OACJ!l+H^aqf78TD<=!po+FFMr_D$@Xz(-cdTB+>&nqT6+l5&U zq>tMb64^lFH0K?vTzx%1KPOzE_y%_}fOCH%WBGyTrqfFjQU6=c z{4rE>ECS+L91F_;;gvcNxzfaiMkwn+IVs&FEePL^Q>k&sw0c&ac9NIKAv za*T@UgQ%+BL0SQ#TN%rqR8Y%F)(9EiIL%eQM>ePyykTFcd_QBn1s+b0tMvySOw`Rs zvTPjTMma3{M6ZANBA0QZvtf;ViG6%mt14q5kq`xNnxDU0Z~XZak=|IpLj#s-nai{Q zL47Yr4Mwt>QmbVd{db1G8Z{7i>1w)Ayj!R)6x1o(J!%xaiGEjo9(SRTD#}?4RWTEJ zV4o_3M34ROx*#jpB?}mKccriAa~n!dDJmF*$8!gmB(i_!jy1F$p!{hCLj=(@AhJVO z52nJJwaE1gxqlI^Q(XAUR1!M5p)T7WNd*pK;!vj}SQNeuEZcR62|$s3p}U_36JoI! z=oc0{3Eh?Y-tI{bjSVrz!9FiRJ?sbl>a!R_v{cfI4NL-t(zKlDZN@~`l)NxIzPfUY zsf^y!(FT7Bhp0|JI-8>^kF1eYh-vEr3iwJ2Jv{1y7ffKM{H||E9WMp~x+kcr`6Kx2FQf=%`HN?z}?-z40lxI{k*8TAeU zz#oCd?fBu&WJkl&(k1N$`~Xu-crY*am?XGb@i3%2$Mx)@W?jMPHkCiR`3vwUg*U7p z0$hJ|7ix16gSrdlFp3I6tFT@+J(DmAWV)=-H9aQ!5wXe!QkCEfoUQ9=E4V~;aA+0H zaY-ZCxnV76~ypDq2gj-JLxR?Eul9aeHlY(yN3^_5_^S9 z>@8;8=5myzsKKMdGjpU}8r!~*yCr2%<1JD?Rh(HCn5~PR9`~`Uo$_4X=LcFk4cUK% z#*)bFRfZkIN-C&=DQfsR`>MT^Fp9>?lA6s9PfjcFb9vC*e?4zpS1Qi+(^c0xd9Bp7 z>;237r^{}ok$b&#vJDr?ZP&WjZlzlp9i~q%wMxZ!cs;o6FKz!gIXSHv2kq)+duOrQ zPFHI$+10no(%H+y+Ua|C^y8#b+k}6j-IL1AcDAv9SgD+zEN$VH+xN~*rS0rJ?Y_Kq-|CO=Tj$;T9jke=cJjQscli3e^E%wjFCKqXmbCnH zw$|UYce=;z{-d#NJ!G@>*XpvleO&K1mjKe!#op1w?tS|5sB69LwtHLei%(rMo9%2? z(jzUu{V=o-%^&ZrY*4Em4W6yuCcWT#-;c?-hdvv+gtS>ITUK^*&#`DSXV{W&hTNj<) z_R>Xd>8i4_+OM<^wfz0VdnNz)x-&dGeXE_HWV6QgX8Zkd$2i+<1EkSjZ|CIcCA+_K za(?|ZY#Pg}qmwh3?{4@0=1_Y)S-j}Kr*8nwbicoN*z zUk97p2ff{=#`}-Qy@&0W$EBy0$M;k7S#u8epo0&~-Nx$Xu2#)g@)hfF^KrM^8dU}t z&80@Ichjw%FJGQl-s*pQwZneDvcL0wGstZ{z2~$&q-`}saD|79~P0ljb8vEzV{msX% z%3=TXwRf?*m|cH)yslOHZ< zVc!O1P1JK2Hz#|qYmFwZ6}nO`P8y?bqu#r)x1Khe>D>n-U9Sv>>E2%D>H56haQgL1 z-8#@~{c8Q};N`x#bGH4owS0QHv-)FK3WC=pUU|ZqCfz%k<&Z+jGCOlk?&;dzaQNe1KYke+!w1XmUOo<15AL(ar;l&#t?F^@>2fje*oIZD zzZowtYrXdCUR~R9?z5}bYXMg1S$6FdMz{WOUGINYtm^)jdr-08UX7R9?ryqun%_Cw z+wJt~)>(bO+Ia5PUoW-IBWobK!3k&FO3R&x!i93 zvUQ`q>|Q-xYtPnN^>nAXyu8)EIeXlL4SBd{Rj<#@=1I=Je6w#_TYIg&#>3Ix@r|Bu z@9w?dG_@0dyD>W7->Kd7FP8U~-bPKQcDi?YWDhlS+kM>Mz1phxU$sW7wttm-XdG{z zpB!IoT|AvU)vWWw`=(Xvo^0rd93zWrWVs-3@>=2GkJy?tZ5yCY+;cYl01T7FHh z^~|f+?z3Zzb`JIC#X#@BF10ROYXj$6ei&EFDqp*H-j0r%mxKG`=fkVQ z<@1xfm#ZDT47Xo`)$=UyUT-R!{{F$-Z=Ls``4QVr?%gCdOzK} zIojE-Xy>C^d$6_H+}~b1sGd~z;ppw2IECwfp?T!I?>8%>lk4M)YT>%Gy{+%m3Z1jg z?o)nHfvT6aNAsz@zqd8&Hy2M&Zq6F!`>1Kbk-MEc8S2%=?txRSU%#C{_w4rD-pW&c z|Kz0Y^hekF$#Dlj-Ve8rE6wWWQ~ToJ()x6))8&8Ms+O_#)XwAHTWxS8t z&%5^9(%#X@qxNv~cG+s*bl=^_LVIb=-0MFzI!jB<)%;_w{X@T48`bt!hR3JxZ_8Kt zAA0TO@#SP?v}di|G@C2EZ1x9ms>gfTePAyd4bwi_%5J^XtV->=vb}k*-CEsp>vn(n z;Od~)Kd!)xbuV3Q_2#Y6wbDO--ga~6Mz!^0e`lw2?_Q4fck6K2RT@qsecrknuB>)$ z4j%j6+IDrjm)}Xh47QdIo3-{+v+?w_deKQcZ}o@GlY`UqACK95;ktSVZdD(wi9KQ5V^;$1?ZoatM;6iJ>TlvSE)_rz=P+O_@_Me+q zY5Tl?baFV@-O{pl+R>Ku>|nD8vu%;tTdbaUn-BY)?Z%sPy^80^@u}UdRyI4e;mPuL zb+z_$G|Pm_BUOjc)Gxesp>MVC641H#aH2vbj{*ym?!Gzdz8PbOhbU zrBc~i-da4)y{>H|Pg}izCyl=DKODeby}mr?Ueveq=ee!Mc6GCRwRu%>?+izms?zDGsvz$JvHJ&P?y~_6a>&;^SVz1xU`t4ow;IgoCaC+Q5 ze_eS@?>{|^cD65nwyz(X=jVHegW>M^iFMSdjA}3S(e{t#^5}kVrSovp&YivG_Zr#m zi?O%A^8E6$<>b>XSc31%KZfUrragLId2*Le-;b(K$Ctf}=ZmX?mIYdJ-Z{_j*;o7b zOSx^!Ft)DtfcJbJSVry2KI%T#P8WadZsuCAt4(V^eY3fLX5~+-PbZHjh3e+@&0Z&) zzSw=cIX%7UJvX2Bj8`Xjx%GBFs=hjV#=&Uy;rwFjp`lgn!xNAQ&Kl0X@$$O2XLOy% zA6M7CS2ugPXA};XIz$et0z>k6etOv0864bfZeJVP$#L^~ghXhc@w1icCHXTr-^w0z z(>cw0Xf|Mfel{!4LGLJ=-FsScEXx_?cbi+M*O%IUb?NzL^ZIh@bo-|B`V1I89d2Iq zE#UEYp8(aXrL8R>q^Ie9r@3^QwYPw2`{(EX_RmFqYo`+P=e)3%Z}m@&*5cFfX8XMI z)t`gM%Io3wL$0$^S=k@0Ep`^$!}ho~s^?`Th5jRdMxrj6D4g9Y4GQ&}nacZW>ldSi zKG&0l9EQY2UBaTel*_64TnI)JFA;Rd(YiW&4}c*q%4mVe%&eVD!+l69>*#VwPQuWs z!8FvHhSF?>n59aI#3O5w#m@Lfm2y=1uMoSLqOEsI%Fk~!l04C@VJJEm*z>f%}?_Ppw{E2=YVQ0AYh@t`VW@$anmraRfUY+rl3b8YQK@7?wLWkic9hIAXv z-mlI`o^+MV;(ef{dtp)K!8}qJ?k}p1(X=+Mzuv}M_QC2y;cS0kInf>2vHJShCYIuK zV_Fl}Uv0wc1@+DFqTkV&cjyf$+@YFbOD!yaE({O{rQM%|vr6Y?7%d&|(2Nf?~j(x96)X+hyDL_o3cb>#{4)wF>@vGKo z_vL0J0-}mlSp}&y1&}mI93pD)_Mz&C8^p4bu(-3p;y)Y@d z*+bLliAD1t>bq`Rl{dqgxIA4fu{k1tR@1N_aw*<#;)+C?q_GQ|xzQ5*UTqMESkz~7 zpzOc56=O($ zvO9(ed<-7>F6(m%L-KKec>>TcSPBv{{C)s^7(ciH-zxOxnBDX~=_7P6!(;uq=`y6G z^!a_6zULXkIH%UszIE#hh0xPb=c*Jl2Owc>n^xbLwL5R#kv(7DT(YLCtliq#e$0!5D)@bMxjMt#HL``mVV*R$mJB3{LQn!1@?E5{>`)eJj>6s z{5;Dqu>1ncFR=W=qH-I5;h&R)F(ZtRe{HP&a&K9L5wjfLuqAH&0Fz_-CqWtStT8xZ zgbz>_tc0J>)Da~+n?cYT&oyl^LWEIftwfI7{_%*;Y;Fai{uV^oXyLl;Avy zx(k4H#g81?Ift*Za7R?0$6O6iu)2`WnC!s6tnx>!f*U20H^HX z78nXbWrrr(_m%0RvrQ7cd58KsRf%Pv4Xi%`S*pSB?1uJYoRho2!VS#L8=~OXLFi+a@%HdWf zjH%c)uh20a9a4z(qSZUq(JmAONXoMkb5Pr5%aJ*>uK8krs22yXInc4slC`KcsF(ZC^- zFR_O(0td|=!4NjuMx)PixThQWEXHRn=EVmq$Z}7pQN$V_l)fr3lM3-rpzJ_T@MB5t z(Hx20O80$#jcvxHg0V7Pkd$Dpb`nT*`wJ`uW`>inamCRxDY6tkaq3vF<^q*Jq6=xj z+b(d&k_penWURu|5e-xri|QmS%s+of8(JHm#16Hd@s2Agr3TjuGbM}?p89=|of>BQ zLE$R{Us#j(zNCbbnkyS*Vx&~nAR9;EZ=@BKLYpUlvPPOc9bYw(&y}8LLvsws;jLJfx!|b>l@O&S10$DqkYWeux7TO#b;AqZC8nnEAw$XZ zo_CZy$oMc~!Mb1QXd{>o;dujj$H3gJnDP^c3=lFhfysiZ|+5grz^JeFd&d32Z|cTh?6`Qs_v0|6nAp#;#*1iOty zC&%O?YO#fz9m4C0jM8tSr|WkN#2xQ-9*j;$H#fpe6}|@piN;SziQ-li6ZSh2ba{@x z`(dh6DP6XpN7PAz(&0<-$rVSl;53>Er_m&wO5O{aE$;vk4hz$LKn9_IZn9@o=zwV*_*d@s zspR{$=GXZ^U>5QvcVS_E-cG02fhU3;urs+6nqRuClD-vH#U-TJ#P>Vyc_o70_-u#w zi5)LF6%H8SDPd#7x9qR~$=-hdcNXX`bc@u2Gp#rAcM1qx<_{y@Ta3)#Ow3ci4`h zJ!<##NIL_1?-FtGgHiURjg(I68~Gya0TPOEeqLX9eLq6-#eJY=88717m?s8v)5RMU ze+dE8!ewp50wsz8uKYUMRuEr~^pipW;xls^OWn19do@^4$P9x#N!umYZBT{C8Ud}h z^I+V&=Yu49UP%g|C)Usf8PD{9reuI3bJF{J;SmgLboVh=ttDO-o%NQJdc?#rR>dEL z06p}Z3tZ6UbKl*R+@1gL8h5jK$vp*trHhI9ohK^?%{hoFI%q)@yvb-d6|#K%aBSRH zluyHd;5W(*YXY?*_fLEJi1c5lj6(o4@dqU$;;S~F^byl$RzQ$^B`Q;;==F#U z+1tXPH+0AXAK1ifs7AGsvg(-tK)r0ZJ}^ab0h|wl)kiZlkAo1dAFugit*eJye~;HX zR*q`?J!a!|r>zaR5}hi+i+n8!SC~?rChj?Zr6_DYNmtG;Wr{wv$w}kYgSy_n5p&86 zjWqlfX>oEcH?12Bp(^f_7yJ#=4@=d*`q|$z>bX6$jcq$(uO}HslWYYmz+v6P_ z;WY;5huFIX3Bi_TE2)J*S5)HjMHZHS0u(*Pg9A|6%EcRy4vE$qO@siimO1|@wH`7XL zykrGSO1lzQOXT>~jt&SpAopouQcbj~Mv&M9B?a6TiZ_gw$>Nd(DA8vy3WDJ1xJ;WD z388Pn`GNBmO&zHE!eFs*?pz(?X#%~m_3{F_(jPqBk*iU{*s2b5JqJsFaER{hQTmbG z(Ivx?(sIGzWSLNSGDr!BQws$xV}5NTLXUB0#!~bqyW7%|`N9vC|I1~TQ%X3v*m58O zSuPlCEFT?gEJuFC=wbN}SZaKTS}F|>FH`gQ_3%No7M}!o@&j&UJCAKlAAtmnLX=oLuqa}iq z-A3B(9X%DTp$lw(GUy9Wz};bGl&Bp4LGV5NMrz9sL-gJFoOe|hK43p?qvRC(!#NMD1riAxI z`N)s(gy-7FxF6O%goK^`?HV&_?}agb5RxeWj8IvtQpll~Lf*fxIt{y<=3$TGI)c=d zEifXoH_GRK*ULpPI}I`%0W5iM84};H6n1K#8VM%Ld=Z=^@ZaJsXd6Kz4?x8V`u#k( zaRblt>ZR+`z+;g_1rBRZ!$!M?Cw{OKBxt~ua+k1C|-G98Z=l^u)EUjn$^kW>m6!X4e zV%lVgR=-2(khefjlJuzd8Hc>E>{j1LKbVf9MyAEvwg2-!F&(r>glAQ1|FE}rx7IiS z1!3TR@IyOHIj$}CzzCZA`FrbK?RHMh%IF+__1X)V(dqm5wHN45Ilb$O$inw;H>5Z^b3dlRRJ- z)|%WrhVZgYp)eqcZA~*Scn^xnF8 z(D5{s;F`sM`}-f{ zhxJO8seG-~8Kv{nMuic?buQ!mBu!iRvsj?mn`07aeh)plFBtU4=nH@PDV>~T@nt$o zp(vol5g%OEInDEteZE*<%#Zj(F_rRSj?N{Ai@A|K?;xy;-}mGBQ7z+(9`MS{p;tQr zlH~j_L+ycpX*8e47aV`^C`_V%`pW)!fu5|#GmKiW(vS4^L7E+f{FWaVa}IDocNpQ< z7bmj|PTu|3i$Qn?AmG0rD3Le3+2>dI=fj8k2^4;eiAB*;l%ZQMRX2m?5I{^AcW`lp zb&VG*>qUG4CH9>+EAx$P=|lbE;^?5;=+-Y*;_o{gDpWs++EKf{g4g_i@D9^2%oTG_3WZK06twKQEI)RaIeas~GWY?$%vV-4F{vHK-220JWf2{3vcS zn+~^vyP;ulmQEK(e}z7Y=L2-syts97aXUF!-MU!8pLe$|-s$fv`o7}tEB?OH-#^q( zDR0}86quK%QE|so&<1FKn9i-&Xz%t;ZD)`e_K4f)y@8{ijlUD2bKvo%etZt(see6- zN9i&@>hKR3{kMNQYTnXcFlnE-4{G&qK0ngv!pltD;Khp>9UAY>=LZ*i`x?%EQ}knH zlvsI6Q1@W@!Qy>9L1#wHic7#5fYDLo5!ber)Y4tR2x_{BX=UqwG=0|VI2%&8>)0~` zId^hA%g*YJdh-@t*gk$-M-M~+$!rXb?uf3hvlO~wBWz|O3|25M-$wl%2K(C7`79af z9?r0bGw5Mr_b8-#B0O4n(7v^g;<03I;+=e@@+5OXvlzciJfnIV56__tx$9Zc1KEoE zl<#%z%llmmeiMp+Hz6hpYaC+AR=i##S>IjB8TU2w9LRTv9ODgbokvHKZ{C$`bzgJe zfqb`jTfeMNkFd4d8gM;zCLsnStp-?Xe<9`~_7>6Kr_T4x`M&UeH=8)Lm@!QtJnour z>nSWBn@9V~VMhDap3SzO7G9c*M|s^~ep~HZ3m`sfuITtd|JIblc!(E*B=!^q##V2CZ;9&-1rna0$ zT@;b6Nw{j=2r;%Tw<*2<>>e~)x9}R#+YGIQqX(=oIk$lYCIsTJWVw zI2)QTvLX^iI7J-G{(OiG6rWf4ys87VM82Qlvv{BI7|&Pp*8a7*JrTV)zc^18@zHQUm-}jblJDv-d!LKO?lv2P5XfqAq(9!77N^lWO_*{S)$s*2 zmILc+9HyU557XPX_vqd2qtSv&0r3E8Z;yG{!&$yd-x&nZ6JT3@%yEGkAK$@$q`h;< z2tW9#ma zt_l4}oE+2S|13jUFbu+fqii-owv<0#O^0Nju!Z(rgVCYW;Ce1+cG~?U`)zf| zDOA!YX;?w7K$cAh(Y~ylZG#y7$V%^B{x|Qcb+%?VfQwJzD~C9@S9Km%k_^($V+d z)63dJD4yo$@RaZqt?AkiKNtz1m+5%)+Ny53siA)uoo~rR=4RN~oghd@M>~}CVJDbP zhvevav|}Gq!QPPO;#h2d=W~n!gI2BhGpkW~yD!F#2%W+>&Pu>X;n0Lt`uq5Y?;Afr zqt3|r{n3$pDZTh)bbuON!K{7m0T=#&(HOZ^?4*hT&K_z60N)$u-1aCDB5yO|{vds) z%~lp1y%x77F@BJmKzvX!g7C*{+?Dykk0kyEn6gK~uQdjcBF(OUBHHR6cRXs;Wv+Sg7i0;jEW3$4{44zaKKr{BvYa4xsh~_AK!oZx@#Xl$G}O>JHqqwe|LVQ|mjS zmGJ9scaMqy_Uh|@QHIxRZr=2kq3f;ZvoR&KzaGTe2(TLX`=ff4AZvULk05I#yX!Dt z(miuPo)-2je=84o{D*$lL8?4o#FaS!m46KtP$X5?F$55pI`vt?EpP}A(ASH}-1GW6 zc!}VqTk#XgL5mY-g85$I@P|4h0zD)Ob&!=80jaus3ZdSAf`}QJ{Ldk+quS1G1?Kin zP51Zno!do7I!WN##c#FjBVIb2=MDb#YMgu^TlLLynsTPy(NIJDel*vj|-VzB_fn#Fg%~-bo<$gz&X#(PT#sOIdtRc z+x-)Y-7W5a#B*;Z`I*&bjeQ59FmJBP?+rfGFjoH>uL(UKfhQR1YhVK73d4H%{5X0L zd_(nWI?@`yho&Emm+9!M`xxb6v-`%!?8sC03&E(3m^+hZ*1Tjh9K*bD^#`DeQ3RI1 z+7xwny>HPM%Y1cka8Tw}#IS=j4+OY+FdrwV*uIT_(*=1I!4l6_0AO!Gz2Q!pm+Ru(eISa7 zk{ob<{Lwq;2(gIAw=fYBJBrh?R)I*%*KY~QAY2S|T-&={!pkUjcw&Sqzg_zWdn^d! z8$XX1)0CFEl!OHphCJwFm_H@J&2LGh-a+oI7K?{^W=sJ4RX2Yqu7p3fJHIk5K0 zWI0WTbm#vy5@a&kyV4T8Z$iui?6tt^colGe18WxLVKUAWLznX|Inc&XKYj#y9U3|? z)7N39mds&>LcF{&l+lf$JGI+W4ia2@UOSAXLw$;|xYKtD2K5xLYLgYV@%<0A`n0a= z?R~J8x$4quR4zB~DekV>aN<&%Y{UK{H?6W=*5nVG1&E#MnwJ6HD#PHJD(o?l*IQ73 zkL%v$EXFP49gFfYKp2@~s#QuRhTWp?&l0-*>azO-rqZ=ctHut03sUe+ZZe54jzW-F z%dX*(v4F4IYzRF<0I-aJN}FIE%~&XgiK;+C#;52J$}oMyAhuHOoObYDiq zvZKhs+Ln29RVqV~j={RoY!nhL8fA@Uu>~VUv(@cFtwQl5 zy8?w!_GWA>0xp!J%zTSNw~cW+g)NXuw$o7UfNDl@bEQ*aM5DHdyH+U7+^A6c1YdiK zKN=?&#nPwn)>D{rFceFZSh}Bo*|D5OmB-U@>g#<<@4Xf1V9Hm6K6t8pGab$RIC7#6 zis(pkQ+1uSt^5)?W9siHB}!RRw%?{%OX=lqpm!vZlAzVD59w26HSjjDx*@OjJP!q$vG? zZyQWsW6aWQ@%nB0F3#-Gy%@(WUnFxQa6mn)PY*$Yzp=X?epVX%PY1DQsINz~eD>bI zFEq%fCz+0Ahz)8xCLexe=7C4{ee4g5=tf0ENHQ!U!Z4ix-317r@3Bc!>qN zgDIK@m?#||K%1L@?6yb_f@euQS_O+)z}fE(WYJI-O{e>FAuMBQpsC<(Ivxj$bKokV z69qA*^}~7(X0wc%zy~&=jJyp{L2N)AFjJhKITogx`2yj`KgQXAL2y5w?kq&r05hJA zC144sDH}xkLm1TSU3dXo+E1t_pw0%^-P?93kv$Zl|3OaxDAk9hjqq_hr^f0*dK!Rw z28$J!^oBO>J-PSnDdQO^I~e1wi{L!YgA=@Aw#d@6vn0a-Ni3-}kZBI3e@aMA%@@IF znIL}iCGs+WFkWDP%ln*l0}G$0XXj8jOHhdhF^93o?IZf0&rTPjeePZG_w&VXF0mAA9(r+JzT;VE65i>8T&W9aorOhEu`2468a{Ii|{aCr27d{WM?AiZngp>W3DpF@->Ib`&bz|N+`w!N^ybSrq~JH zZr^S9{%kpB9G}9LV>Ki3n?w8XOUA>`3(bSpD!N?{MoF<(Dm|aCU!0)~m%LbDFu$;% zP+5U$6y_+v0H;Yt6B+Xn{Xy`A-yy=O_vnzL;o%a0ewyag4~sO7Mi>(IX$qV)ONZhG z-}sWW4ewF|Fs?sLDje+maVN-EutQF8=fEI6sxP>J&Zg-*XbxF7U))R#Ah?*mO3q@U zH*OT_B=BoQbQ@1~hh>H!F>VE;t!I)+73XuACCKdMg2v8pR3;c~8cXuXHIxqFX_`)! zlK^*rdz`c!*hD(f7ktksC0+)2gnmWKJQ?cxxEStDgNF}~pMCul2BDNs;By$ADpNZ` ze0s_Q5@mt1g<~3z%;;3l#IZ!~kh1q;e=vAEa!lOWsThp(@q;H14}yo&9Ph&hd`%S> zVivRH&1*3Zew>}?cKVv=L@R9aWL}K-2~|aZ;@L1WKhDmWs~M!*u(pfb=&8g#E+m8| zctJeQXY!i?hj;%ASRpa)%}JIAFn|CR53$d%>>vn5B8I+8(!;PzON-XRrbV%WK`_w` zF;xJq51M;SiHY;VjnR8p+DscoA`WpWn7nTU!V}G~=7HG15z8-hv_t!X4F%W27w8p# z1Yb{Q0hi4d%eg&pNjCJ7Wl+X9Z~}aVgGW-cVB;G3GtAhA%^HhHY${FsaQ32qGze+&V<7&sVG+661zGSg6LMsf^mjo3HCCF zf5eJ~Rs{_hMSC8^0+oyHFP2Tn4G+6*)Fv+2?jKx`WCal5b2`Ni^7h6&k=9p{2}BL5 z9l>;fch2ai+ytw$h~|E`1+MtIt}j)CF5cL25ji%oiF^7ssM33`WDWrPV&vPshT1A-pjt z>o2V`WUTB75S!(lQ?$A@vMEh#W40L9Pq*)oF<+h<pEOB$@ zG`2Tq!!#QnLf1z#ko0dR^mCD+u!8>r1fT-}z-UxvF9=}A1Q4))=eupgI-lGD`9?f5G>6RVL=wxOhB|t(WUV%trXb=aC^f>KdNVmgndA`n z0|fyj1G5ir(oy1nZ7jKRV@X+KkBE{7NRmi+_=eo9i8lmy#KXbjVxd8Z23m^LqbJYZ&QfIfzWi}E;PZpIu&5$*oqytqeR2`Qbsq~j+M zDlA7P)>Pkld854Pf1pOg20T=1?jNuPQM?Rjvn`;uD?-J83JA8n7HnH|Hmcg$Huo0G z1JLhY2B#oVl0f;!+dy^3GTw=Y!<$KrD$wCrJ_sEU8Y*Ej7LPGF%&TpCcDatd+O}Wn z-o`*aCa`ndJAwTbwkNV1$J!sUD4-UAk(bO1#IOBmP{lnt@0rYc~8K%GAy zX0!2lPTAl2D!UR~We}T;A7%v#0F$P|Uz~j&j5u?8T z#SAuK_>IW`q3`l;*`W4#if*2>DLNzLn>vR!!J-q5d3+7revIae>2gd6yU#oaWjvv6 z3Qty?&&LxOGI=<|4lz5Cyi^of@+@;TfQ>dgV3wzUr|}R$-$!dXs!lK%{5c!Xa4fSW z5(xfg>%*WXo^U?x`*6}IaRO2{bn+aypGdn^=R0r#VksT@l{#qo}!Uz|j0bhOm%z#3c3pza_j0gPl{ z4W`)6B%~>Z5tGMYOw;uC0s-HQdG`q9&1qQyeb8x_zJXHw3S`FM(YJud42O5uAz;w$ zh;p%JlHCaYq83Janqo(R*QL0QXJ_d!O~y!nq7(%u7mQ$rw}I>TK`TfX_)eh(f7j{{ z;{5!C7bx9>h-rOb+GRXQiWe~m`KQ>_h|ZIyQ#F%0YIpEOzo4Th91xHS;0vW`Kmd;D zFSvf*?Z2796erUxIm4(z*yUPW1f$h%+ooKIHB~bt$=G zZ8>VpIwOBA>8JTIv_FOlT9z9hauNck!ER$8rHnnqK87MerUTW~>pGie6dS0V zkoNUEE=2q4fTp5!YlJQ3k+?#t&@9A%M0|JWn`e(T{^=J;DM@w$+?LD@q{E|duK+J# zjf~YV1kV?w5xo|{*B*^$Z-d=-V?PoDRvX$0a4h|yUi%a4x`b!gpO&z=&l1M7{1n=s z0Ly<$#&Z}uiK~x?m^K~%#UFUn64?W8W#X|`|MM)J4&-7-Bs{^4 zlQ%F_S_bARI8h@#z&1ugiIhh5u9;In2Eaz}5SBA*qVOPOnF)TW)hCky<`SsaSTLy# zM zApGEoq4x^?XPP*lC8tpOoY?OYP?*zlE;@&(X`IAahAT$0M6Z`fS!rF^SIUA`ygKcx z0;Md>KSPnlAXQ8D$nZOCF(~+H856@Q@)8O#h>+Z~rDm=6u}nw@NzSE#3b86uj4Y7R zD;nKHs}{UR^;wJ?z-I7&KejFQEpy94yAZ9M=YTNS{RXw1^n1L08whEX(eZHlW|qoV zELmeA{;=Y~C2~L|a;g_+K;7d%TiorhyWT>Qv`is>Zn}UDgYcXJd25brU{v24_LU31? ztPm>3yJsh8PzEko50F*Fiv@aGyhAN7(?SmkuYh50%Lj)#;#|0f!4!5+7f{C^*Ch__{xI+i*i^ARX9i%(3KbpZW%5k~Ehe2FhyjK47|G(GT

Ucv;g>}D18_`+`m9F7TXVKNGm%km}1C%~b6C8^JZ^t+6U==+(`er6&6bRRwCt|(TEDBjrd{RrS~;BYVD>r*3HxQ)XbK}B zk@kBYa-JleW+xqWs4mjHWzcFm(AcO6{bsO7%mJ<{~X6g|zSm-!^ZXVnb zSExBa-slgIH*|o!DRY2m284X#vuAh3Cu&CVRzHfjG>W(NZ_g-p%FtAk?-ZSH4qrL& z*iP}yp(_U*?G)b_wsMfcPSIH`v&v%T(7jc2q>f&3*f2}Ff8+|;p^GINrs~D<*F%5k z2p6k}kC8u^3!jru@V7H$QP|FZCi8%&KboL<@Q|*|Z_8u|;H#fYS`KnnYh=I^enXF* zR#wH3a94nY62x;ooLT>UII|YxEKQhb2S_&ZECyC+glL6w;RKP3kLbu3yJ4T<{>>g? zO&mk;&13?YH|p&|{yTA?O=e4yvwk!mrm+%EIT!g15;+DiD8mxm<+8|s=N9}i_F4D= z<9FwhdR`d00OJ)5Z{PHe!XOElUOEI*3LXV<&*Yd1C9ZssdTgKokwsAu*d+0vKsb=T ztz9$-iE+d|0s_rAlL@*06-J|gReOkb!}vmi{W3FV0Rn{LThM{+UDzR$P^b1}Qb!AB zw0BQ@e+Ldeoj@}O*(YIt^1On1DBNHz6>KX_4PK^B7~1C!zg0@U7<H*!oYGIRq^Z`HJChGsELv9`S}9p*{7id)*0`m~rL|$IhTqto z>zx~qPhPZ+*4Nj?$gzR!0Z+}48~MbYg6wFCx5fjcr9I$H96NN3OWTd8BW6<`2Sy`% zRt%0(6bx-q02~{Z8M&-SNc3QcL1WZOD!yXC-hSoJ1LMgbfcXHGIs2(t5*nWq3Ql65 z_OVlJtt~BlD5g-6*t6-PJG0?)BaFzZQ;8uN^iC4N$}<-K5*~g zv*~fG-6?R!Q~aiQtAo`i^>!OdH(Q^M+dG@w3&u9{DMfFH@l_du-o}Sr9ei=zX&N8u zZRU2mX%WEm^sKd&e>_3$v}5nnTk#82DjYWi?O-!dYMT-x?x$M!0L)NA&FCVYaoV9* zK@Svi}6 zv>z;Z4ksE)2Nu}*H%%^md7k87LWi8hQ)wnQU~FZ)T0mT;@_0ZTGZ$LLOhm%FI%w0O;W zyjAd+_w1#tg_}yPB*bnYLyki?W^9}#^wNc*jgeS z%#QHifJ27?f5Uhq9RK#Ves@SS5ky$V3r<+6g}3-bVa~&ms!u^=WUQ&d1oV;XOoj%s z=rCEKL7{1E7k|=|!^3fa;wP;YgScp9-|#gH7w~ywT8UB?{?)iQAi4*M;c&cQl4Nac zx7;04MinEw7+2lJ0ni1Y0*o}UoRaHFz5;aogMp%Ze`h!j9+m(dMcP{g+jA~Ufo#da zNpOZmE;5AI9}PY845r3+8dY=IQE?CZVsMhAq1n&x^gz}`cF-IIN(iMxN|YiMy-pvjQ@72l&h#COw$R)m@n(nn zkk~{wM&#)e*_0N!>1dOPv56g0AcJl64Mr|-PzJ(3W2fCf8Ic_6e4Lyh)^utPJ^KZnIPdwgmBqm z0v!2fYNL-Dbg#i&V<4YJK%t}Ev9;Cuz~;=@j#>mMiAwEl9^nCTXmDSuTNL1Dy9L}) zyUBcKkiRS@IMp}XfNM-K$b--37Bs^mP^i3GJ!aOp49HxQ)VcInPsGQ1R(=%XBh}C~=87?xKwQFS%VgVd|84%2g{iJ|H+v>gVvvy!l9*Yg2N9?`AXgSo{*)UBh%H2Ag-b3L#1FQc&1!o!6eU?x&nd;&= z44k1Gg*uU% z&ak~9_a`@Wj59lQ)?*JZLWTP3sR1XRVH+%txckW&q8(C*)%}qQJi_ioe`nBr2xyw& z2(nYdWQ%JS92SZDKo4I zDq1t#2#ba;p7bd3vOA4|(FAd$!JRGEYD$SnbF)he9De@K(Ja}r}7n5a^*JvJb+N<#E_jXxu_2N7#W^VQQqKiyHvnS;;{m3 zQy(~RRFW-#P8pO8V{YJ9A>9|AP|Sbt#d!fX*)s<9%;H%LDM-(E6!+uWHeP?j3tWO5 zPNOA`zbO7?e_SgX2Q|fi$@z6r3!rK>jUB5!Vc~EvmL-dZ!{g-eyIqTp;?@?0)mdQe zR%qI*(X{Z#l)kNG4W_)usW!NKpBwMF^wynk@zJKI(Lop+aw27j74Eh+D%=zx7FL>`I# z%N1>fEGxQZqHfn>;@jdd+^2B-EQ-SYJ1kSJ%=<|foBLs*NGqSk!b|$1Xxw~(F#%R# zIO5PKW#49fCs{a$x&2-uF#|^{4zsKuvhWXCfB2ru!WzLeo14-W({`cL6^r1;`EoF? z`!~C-io;Fw_|MBKfEUG?qGr>|+>MO-n3rR(Bn5Y~$Z(FGa`Lm`I5f7BD0ai*ZSZ5L zdPh-X+SMa})@{x{#ykJS8AVD0KMJIjGaveyc4Z%t9t?mVN+iZoT&g6E6p$ro{fF*W zf1E}PZ`y-Op!vr^_2Zzr-%8u;$&t-f4=NVwSaVRtF_7~QDqi>Q4=NT8`Zg4{^q~Gy zgolRF^>YuhCnE4P>%IJmmf8)MP{NKb^A)i6VBpMPpIJY1y_$jluAhI(=wR8vMzOjs z(ZR-T-%S4s$XizT8uy%|cRgY5Vn*cQf8}~=SAc3sm1}AorPQr4Q04dl<&Z?;17n8v9XO4&I%;vaetP;&(%4#(hB3J@e zy+1G3JIJ5xY)v*>#QikdACR|cZ5tRyoW1aBFkL+Qw*Zc!-fq*=?*@xU4~!DI$bjms zcGCcct<#2oBlx%8+WB<6)o2^rfB3oy{Zt4i6T(wPUAU^C_hXIb2j-_ja#JCBspz!% ztFYKbMdG0X>a*(j+KW4=s0$Aj$DIZ$dK(uQYJCi7GVlolLewbcf3)P0c;=~7#7GwM z#QkKW^94w-7Eun`!{K%^EG8jmW+mhUA4EEFUE1Q{L!xP@i2kg6!FeCsFVAcd%YZ2Mw`^7p3y-u*#+2Aa6uhQcE zBDi%LKYnzm3>3i{=ssn~z-KNyI2KH5anWEKzfApr`ZH_!}y_N_ys7U%n204+bn37)od9Ivp8gscVNKK6ZJ+S#CBtX zP(n}8AA=EcCo}>`Ml|D?*lprAAoN3ho8E&Gs`14qz6XWA(OX3POJw3-_yZX%y`KDH zS$D7$f19_q6r1u=Y~K5&2tsU!+FjsO$Vy(6Uh7KLiXWC{+!?{n4=`*m1YzrD5Nt6i zT@OJUAm}WFpnWq4+65@E0D#s)0Gc-fz!1JybP(MBnrhwJnrg{ws&((zRI|Zfcy8tU z`04PMou~@piD>XZrN(uvSZ6is%soz2XWnx7f0N9t`B1P~z7nmd1pijp;tU6VgV3JXfOLkb*PX@4WNvW~L8=(enpS0Sy zLRyYDlv!{7dGE=qy$Of>*4Cu6Wf}0_hiwDSUHB(L_2c%$+9Ia{TaaGgLJJvmWPpEw zf5X|@Mt2C?iF%QCj%~h$Y$Fo_r#a?hqjhXIf`7KCQEU?%M27{DwaxlMRtR9&!oDzV z3v;#>C<}{jqa}+HMIJKcIZnjGlHGnmp-vr+n?CpxqY5of7Yv4JZC}H`zBX)z$g%eS>O*GXSkkyh!S(} z`hkuvjST>KK1@A1jX4c{HMD=tsnOEcI62ak=S!p99GsAN5A!f`JvSUnqdn8(=wJlc zGf-qF?F-Hp&0QGbzh~&>87(|~gXs|seCFe0>yS8yf5?fbm`Dr{Hnm-J>jkZjf5=I+ zcZE{F0!9jiH_+$QzA`+AJwyr|K4nNKK2j4T+Oyf@ijq9%GU*VXBJmB&u+O3Eb)A~! zE>%G=6RtOR`iw>y`3rwTeAg5@J!zU~fK=srPd0OvNm>0)CR0@;o})^V zbv=$9^oM~z>tl3v@t#|5`Wxt)f3P2}h`Zr6H8o{C9=eeqT+24Q)MKEuLDWNyO;e7k z(^J5hCYg>XP5LQ40n}um$u8=9H(tGbT4*MPmmoBe#YR$P?u%ub#%pa;AvA7gtoLAi zVqYY-lHBi2qRmcOZ^kVyVZWJ%V&((`BFqNw^dFiBVmI(UqmblH8mjop~ z=}S2|fZWAu?dtH=U$A834Y$?GNBc32cGFcu^x>!#)cM&Tlg- ztCTbI><{Q+zONwTvMmf>y!rGD-vLZr4>(NDY3}Tp zB?c*5<{VGc}}Q4x^o%$-uu zb{++l7*Z+9(bOv-9UbESUbHivZcNdG#chz!r|VJA+iyiYo68cK8u-bW??L= z=*_m7uc9BLzmUKAT@j+aF;&|uLc&T&e8CCgSoFG4CbmvTJP^Au;RGoqoCXKSc8!vb> z1)6g`f5qA3?=CqM(2KL2@ZgjY8k`?m)=A$xi#NV-DRTLpCJ%i~$MqM`4SUF|kNZ#t zJOGTHe+ErClFUPEZ-b@bj8OZ_abx9A&Z+wmj{C>S$(fufXLENlOwNx9Gt|i*AII24 z23;kXf$~s}Y_G)GKC-coVq^`&L;Aqe}88OJL{`Emm>k~!_U-x8#Dl%+OpZOwxHTaVBG^2^pG79t5z%xV3dF2=Z@@(WT_$zPOA zv|DynVzbvXf556h(*Ol91xqc;WBa4Qs(r89>X>iRnLH>1D`)PYR4FobP?7e(#bwjr ze+9?96u~^f_Z8pMx?v%`h+&l{7g1vowZsVf-{ZJx{E(orSkba02R8CnvHi;M#mQA z3cw&LO|W-#Iel#`!D{PAqo^OsuW>a4e?NV4YMdMy13MVzj5(%=JAiH;o-GFN)yX4# z8vMQ-e0hf;%nXXcj)$StLZgDw<#zFfVd%_kJR+)hyse=}@N~FI4Na6)O=8(%l_XKv zZEQy+?u5UOCG>P^d&6)kQ)szLku5YUccaZ#Qo7f*V$=K3r%e_z*w z4PH3GnIAg+sXt`$ODM$V8$u^Htby;}EZe~B#d@IYKP^-rjosb@!&JLVJTufobjObk zb&t^Q<R(CfT7%zN6GQ$&4zC|;dspC0m@a^V|AGdF%(SnfGs;yKaaj!CcWh%_d4 z?)j0AXTJYFG$!tQa{NHu#eEs0z@Hkn=SO3_q{hcoH6!#< zT*UM9+(EY#9vrGFfZr%6?4|1s{mXTX@rwgn4;R<*iPo1; z32uW-NJyr}Bsj6%S@iJ24tT7)KKDO^&RlxthFMdSQOE#hxu!(v>igcg538%UV(pIR z9(zR^N7t)3)z2QFZ>1MHkqwy_+)-yb0AKaNgUW^P4vof2ujjyr1|p|gbBC2wXt?S+ zza%rIOv(Fhb=?Kr2EUyie?RNRn5QV~Aig@&iut=w@|Q6f!^!2DavxG4vg$gylwId+ z9fnNx9HmP4Hjh{b%Z@jvY`Nq+C2*qP3L2<(C9kcH1S%eo%4Nu(}9!yUIgCttv}=RSrwF`tVnu+`_BT4d5?RL&2*XtGj%JCyqBfWZZsb6>m~kYpeDIM1$SG%!eDQD`j)n+l$tj zjYr+ut@0t|0fSDhe^wU&Vy;!}wO;h6_ihbwwq}+C%v@ttvaX&t7^F3CZEY7Oc^-HM zfhnJ>W_p@AiDN*ogd!z4*Lu!cvJc6SndC8`W&&hphI-^UVV_BW$fan$1(U;pWU>vm zb?B)a9i?<3liWLnVY*8Rnw%0i*2bR0C-lJs&FBWAtXXr`eu4k?}ySRoQjJWR} zOz{RFL%(|Yf3y-+Ym~{D1t}xDjFmH$hs+TN+JzgsXD;mBaHi33U@~!rLLV~OQB^}w ze|4hYqG$%7@~vY|ao+jY$OaIHnI*ytAwHenKTn?jzCN>q5Q%WN97JPxI0UAE;Lk)5 z%bdw)=n-UzGn|*_tPrHy(O^tvS%jDDxyZ)J=If3}e^9z`G0X5c2z-F7#(o$;C~Kwx z%VQ1bN1kR)etPg)3=xMA;h7JR=sCPoKe8uXJmj$X^$0(AZKPdEvG7IyfZnzIP3R1h zcINO^OPVq1_ukaOlLT*$RvW7%%C3SayK0OhUaisE1b+tSak|M-G(vVw<54PTCa>YX$viIWAy2 zqNm=_`S^TP$qEas2xD2ARfd}=;DH%dp-|`t-I-7Bb9NVVD>{x3Dqy_cXw53kzaS$B z*gAJ2Qc(B93!uD-bKy+t^BK;p;Ai67hSm1!e?#Nd47CM9O#syFtP>Hg!yuxHAXBz1 zIrB5{r?A&JClUJ60YY8J4YU@~pX%2tv8G76UatY%ooJ6CY!{fQs#&*iI;ehy=L7Gx zj&VJ!V(y6_wmF9@kb42^(H(#^Yfs#BuRDbuVB+lJhydk0=;vw%3ls}RU_fe=`9MV? zfBwg6aTh?rwlRi%17;DampC{Havb{FDhR;jBd*s!o7moa1EgdR_pg|nP0QBE&MF~R z9S=T8X%|pW{s6B_ zKxxej31{jFBWp@9?ysDy%KXW(pVDZ2Ua0-aDp`_FzMq0gg~_WpD_8Xs=sw^tk`oGdKFm1CrX+~fh1;KQk*!bZFXHkEFJua(Y zWc2PVB=-UZ9bVqR&YG1HV+Q#Ne;V*t8dc;vv)UEb$`c9$_Sqd(#vqr`4fou0nYNpJ zCxSe7BW>cL++xUd{|wg2mBBhF&@b*flhEPn!(1wd6@cEIpZLM_$d2sYXx*O899&7X zM`>8vgmJUsz_ep64#*R0Y*~3d=TG}x&DF5XYaZWePt2q%x8||4w3hVFf8y-@`Od6) zwcKW^Uo+!kvGf*iFAKM=92I|~oGLpj2Wyq%iukK&D_|E9h~0PMO`^mme;ukP^#W2e z=@+;T1on?w!7^6zR8<5^6AB6arXcAhzU_@hF`bm0x8=#HEP?4IZlg+1$^vapt+CQ`!dc(J zoIWZG_ba7TN6G`-s4mhzx7YwyugGVOgKGw`Rn7;{*ym??M(|4o}ToNp1yp1c-lWX>TP!#nD*l3 z)8m7eZ&(VII(dBf{P&|cjoOZ@^$&l0eE2U&Zq-g6pPoMb{nrx&459B?NfHea)0#=z zlY?i^9vvM1e~V?bYOZ+Phc3E%b*qNjRrb-SN#47W2g__zV)EpjDlx`5b1)1N9#6!! z?#5;o+(hMIK6L#giFFMpCde4- zF_~`bz40<*8v$lR#NjW&cAv|=vSE38MU8oi`$!y;a z0{iN0J{mcJnQ$;b)EJ~MA!?~XnO_;4HyT&W zJ+u1di<;!WH%`0RaG~wS5o{ry-KvkkH@Mo z4un>Bn|r;)@(PIT)ytQUe?RR%e?3BD8{p+3F+Q;WwBD6HuB$SW_TYi}0=T@K78B0y z2++Fj`IoTy)~#Mo;Q?`TRd~V>HzJlGvmneF1eQQH#B$nIfW-Eb^dI=OY@;w98xnV5o2)>j zDd(8*Tfy-hpGeqb{bU-3GC9q{p7k|#9l|m8IY}N0jDXx4O8hdAiy{V|+UHCN{Dt3~ zvNdVTYtn`#w;o3ojgn5_sHE3nFX%G0`ne*r_KE%TzSCWia;p2pOQh(7qE5vmp=4I| zM0QPrQqk;imxTE4rwV7$f3lD%jd2`_*0P9t20IOHqq1!{V}4k4COGF2U_dih|70@u zTRqY|nYPmS*cTck=N*eV8}M2{fV+Db#0&!UhfB`{4qY3Va%T1+M&qEi(L zCdT71<&+V*oJN$_ZwpIHFZr@%MWD<6oHqUb=rRLBLoLYPwrGlFf6?(z{~Twgwqh|< z@Ndq%a%-T+BzABX76|NGv-fPNxw96|9S67sdaQEju@)l$CrZA4legr=?#&UWn}MfW zuV=@1u~AQ}N7}d6w|^m}HXNlkh{dq0R@Yk1ZaR%1L_u&opSnYINhhOSDGi%!d~Mjo zpWI%AZV-XBi1KnDe+-@TT_~}Z1FQK2PVGZ821W9LsuDr9t1^MVof@3kg006L(#gQ| zZ*;lZKl6PMev0Slwi7m`jTT?f2t0v?$<@WX%&DR2d?hPwe zqw!0&nT<4zvSgk)xyia!-XNV_p%Bcyn#J|G^v+E?6TU8Hf1cmicEw^`jRJNx6$S(3 zAfX?mUVfJFm`N2}MM{n|o7qf$2ZQN)ISN?;S&I=kQ~$!D)q^o49iWYhDYPeMEu}}H zHNCh#3V&EzQtFhfiQH5z(W79ksw6IOol7ki`$z}9)-x+03OdNX^ie+?xsLv(;V9PS zROvP(t>RB8e}?Z>uzjMz`lTJ9ODZ(M6NVt-!G;TCoXJmOYm$85{}@kXpPo*u_e!r# zrSMf@;WujGPlbiw#)V-!?uS!Y6k`|fLNAJ5MIC%3F_2vUA#V#Zj{~?2fQ@8>kCCxo z0U7nB$gU|{KgEYHx@$vnnasR+wKx=dvcEpSRpt~P*cU`&@dm>U;4$Ym&MV6$sQakSt+WbMAI@(06)}84Y zuqD8&f9Q#mdy+7j)`GdX^h05*vVc$%*vimdQo5Lmq*n6@C@EBeh?BxFls++geKxdt zK)pJb#g#v^fiiVPCdYr5)x-jNZ)l*^7{MdoXZjQO`8i&uj4Cz-Rvs z9rz2fIQ;7k2Jr8%_}}4k_V3YS_L6#o7Ff3VEbk@kToDG|RhXD!rPF*ICy8*;G+xz ze;+l>Tuhyn#8kD`NytipesHVMALfHPC<|(LS@4ows^B{Z{J^br4+aI3EDnyApiJ8PD_KJcd- zY+9f2ndYBm$@AXxPmHt+Df$O3{~c)ge_qqqdv|&k*v0$izgU?c#P);OZXyik5ZSMo zwIpr*j|x)D$+=63rnf2-e+PkY(K3>XmEv#jh-IxUC51CZ$?^F4DReZ*4 zzVhCC{-sx5cT?3^$}d(MNiPz5=5PGff+;^v=$R*xy@9{X^g9KX^}-IrOFtNzf2n5+ zEcfY)V>G8ozhMxWX8JJ$%lH*GgG&&s(oY*$?(a@CwZr$O^3b7Y{^34xH{#y-qX&@x zUnI~=&mSm5fn9nGL750$=0QTUW|fna6wHFK6n~|$%YW&xi(h{nX%L%y=rBuPI?U3S z4yp8&!Ke6{#%DhdpE0y4RQB^xf2rWfYBe%gXtmSB-`UBG8Q*xPM`bnI85CHJZFP_h zd1y^*J3Xi-d%q%&r)6zs$0ARuRclsju^|DSVwbVKnY&2FM z?wzwU7@t}8R^#Ki(rMJNK-CBb_Qa`JHKT4-p*TLDHt==qq__Ih7X5G481`0=o7f~w z#(1mI_+T~L&`r~78ujh%XnWhJ!|#iF2eKN_5aiZ*VpQj)#&xV%XEiAiYGNs@$tq$V zONdzhr(@{Q*l9E_u<{sxf8gIb{P=VXbqxAyVm?AfKU$as|6GU^OO(N!7BBnhc!yP| z3KL8+>T$^qtNO_}-jYg82S_-YHWeQdP{rKg{)91g(OI1#iCQAi3)y$JWGR??IQZu8=qzTEEj-T?}u|_R* zim&vt7+p}}%NGSee=N-zleo7B5At$iI2ir(oAQg;B<*uCWhgZFs}mVQsbnTDcX>*M zOgve`Elp>wECun~Z$H%63Dtu&8?8l0x1vwH#wFbzQ5`-NW1Fx+CxxEl% z0zoq5QejhrO;_S^(1RW|Q3{nq3)bA<-`DXc$_Ss?0Pq-he;w3FJE>Vd$1pSdpleEmCa74)#}lsaIa@=ZB}bGRPLD% zelpj*HFFna7fQe;`RhBwUjL8pdKFVP!A%+F#qWFKe`AcjL*=gp(7ye`tP1nGNO>jh zAR1wL95N^FHRX#Ps@QhwsSRd`r&^&zl9KcFyhl3dRCd93yT4dI01U2V0r>L8$v)QM zlAs7`LvMOC#T@U$+?hM{0^rM+N(yXp0Zk8-G~FUYp)_b1zc#IGKbYLe={~1QoCo#r zFw`Nve^E=%4udtd3H!;JVVqEii)yu&0z7^ll>%Ish-nDYd0@}ReadlwwP1GUERnt3 zsw6MAPLmB9O_$MwW%?D?g9oDU3t_P9q|4FEtfU}DZ+dBySLd1ree^~Yt&AP%_3XsI zRNH`roJRfxw6=!t;d(l!%uP8jKSa+Y<396`n5zS?Xs0;Ol)iY*%L6Ol z!k2cDu18CXS4CG~ zyf!b>lh}qrWPu2k3it$UTLvbE75LDte>!PmcE1}1)r3ocnd4QmTSp&Q{)1%W5W>?! zJnk1SzZBoIusLpclG~nX5_7|LbMC&fKZd6K;0oBhnl__Py9hc*Q6DHHU#Q3}Y578W z<(YcgoV*eMBMyjf87wm>6=>eLz*gjSCAdf#NBKskyi#1-->@MmgCrSI`*BLWP>` zhGEa+Cnh}Pw%pcAG_JKQJ_gA{xX|PK{?K| z8LL`>#Gq!(RekA1E-}nspimVTzU$2$8od50`^%R_H&=wHFzYNKg&aP+ zDbc4b<+*D;uUAq3?`4s_??0b-`pF)V3=$0-l`vbkagzXP&x5b?t^mZ z-6b;;r6Y6~j&+5xS6EzNueC?$`fMKJ-ljib#op9zR0~gFePynu$p<;#wTKY$7DN6%b?LF2gNa5IifmOlYm{-fDK0Xu`#6XB*co$-YEe`=K`L>=HlepfSp zwbu5ET%_HQK4G73Z7VG__KI+to6qKBzaXz(@3tFCR|SO&fv8)Bb=THvjlEt$f$R4y zY{d0MrLFmAL0|9aIe)?GJ4w9r>d6&}6}^!-F>2oJJ6%r1v4iLck5NShP|Z`#MMdB| zksQqG;lT;sU*vw%e-YkPaobwx2^GDTX5S%m4kzUlXF4<#Z>O4ijMd=}$=Dx!D2r6YRAYY54Xhrllaq|1 zF^O9VQ9@T*@gD%xoGnt79|NW$P8B>GL;+EjnF@>v6-+HE$S0!62n{z{9nDp9iEhDD zO424K1F6uJn3WqzX(w|BT*;xz)I?ImO^Nzd-pOk2{T) zxLG8-Nxn8Te-tFED{@E^omuQl{#TMViU}!8cy#|&p77#+xV5HmE40$!K4_MMC)0j0 zI62^FVM#EUL3n%{mCVkrZeQSmc6+eazkFGtAU#c+rthW;>1Do@EG)$Vx{~A}~uTltv`Q z&>+Qyrp2+A_CY@kd0U)LP()bgROW88Bn30tf$m$TyG9D zG@}I2E=4@0Xmg3BNVvf_$~hZMYK>;rCLDA$UyCLrmWT{EAK>U23wEiudg36aa>BAg zCJPkE*QJ>7fK5%HQkY{V~)|LRkahxsybG?QdL@Dp{=EZd^yHFI|SABO%5-gQ#Fy< z>M=mIWq{?+@YP;PaL^zq!_WhFR*j$V7t|~znP>2}tUPr)l6ltnFxj{JY@1Nxf4!_U zxcQt)(Hf!DhQ(E<_{dBZPR@c!qoEkRqzoDp)0Cgc{LGW|CW)R&yYCEa&+{W-sxBO3 zwZ2+2R)2y$aSUMlfpG@A*mQaq z3g(LojqC}=gsqYl=M6^X=%>m1f10tOosZ`Z_pr#kX5K? z4c1$5RY4!oH7_;}ZR~mbc>-9MV*f}c2D+PU{Blv$8RBj5XWr6EPikrpTVf)% zt-I0HUFh;qJD+*$UArd9$z62+jIDR08i}+Rm65m=_$xE#_&t~o;m_AyjVf?oC&hO& z5_^?hSbEj3aX3$xWVTrAe-9vF_yI>wWygq(3o>sMR%#S38-&ydeq$TTpd1>LREn!^ zu%I+ZjrRO@u)vn_+M2W%q?dcF1r*zJyu+--p?Q%(yi*Bpe`TfOHr?8@lk?Og(@8o%TX=rL?*1q4=Ws|;aXd!X=o5n! z3zGKuf}p2DTKsd4vH<@jkpAF-=0-;h(ArB@6>QNf6xAC3zaRZ+z3UQW)WtW~s7L{2 zdMSQvm(D*G6}xo$f2nB|iVK6z;AMj4b7jFiMKYh$hy&9ggNE+burQmoWX58my2f3X zz;IVk}4?DtF&^l+V%HW<~@+1ShGu31w_2dKXX8NeSLapx3CTThqHO0?nFG)`G$AF;S?+-zQ$Ye*wCvqi=^*1LU5er!e{SJr0_?u*Xyp* zoOin{VyATJR?E4ZbKa>YLyEo%mBNlN=28{>R7_DkQ&B0fUrP1Nz5b=H!_t*LQWq#fK`DOE`%&QmAD_=;g&`Qr$W|=+FODh2x0U)INKxFPZI&fua z8N)EA*aj@Bsr~hGXv@o?E&e=QM;@MzvNE?sNMyVb<;Ezt#f0G0>q#`D*HXAwj>2U~ z%-Yg6e+V|cj?b7~gjur-uJ0~|-XY%A1vkSkX#j7ATNc9Q7VyhsLl%dLe?BMcP_lDJ z9$Q!D-$yJd51&VsKlPLv*Fc!uf9=B6V;8L+-bg)k&plJS{OzTezkSQg z-@f+px0hc2vS$v>3vysD$sn3Mx1cc8`}}jGYo0{T%$Ut5p;I%aE;@ce`>i4D)jwN2 z*BwqAW9UrmD=adZxJi+wXuuEfRUNW)P=?&i{oLxBN92TvE;lp<+PpH4?kIB4eBjw^ ze-8?Dy5=)?>P8r_bk6)a8(L~Yx8gED6qC9?8u8(` zV1&o^Mi6Y~W6Xpx9>XN)Ghvj^?9d5}DLEdMX9ya7ZLs)r49N{>>5ZBK z)!(WqfSLm}1<>(GO#w6D{FzIrde+1hB ztW=~qL5v$PFaKYY@(IF%e1fwepP((sCzuQJ3G)2>R*YLZ&qlVzid7zT^?Ppn;p7n7Zb#b%2(Ev+z7k z8#iZ;)4U7&FJCHIv+zp0v8m^|{|J2Ck;%g5?`Kt0)uTyX4#fn0tr6#qpkS;EUO}-J zZ(aTl4FJ2Dbx|;-h?uffQHY*4FdQiN2A7muA4k&(h;Jauz?r*3F2n4ef4A;1mtJZt z@Iyhv_`Dt(s*`s{Qcl;r@|7HX&WLqv#U9L)@kH0x4BC|BC!Acyd+JJq!>$=6FU&?s zeyx&bYw>=|!`DVofF7Fhij~wQ=aWBhrO3ByTvf|06@U363dh-&d{Zql1Uj~I(V_b6m2i@A@T$2Z+m`#ph*_e)?fm{ka4i;M{HezRjEhe5 zqd{}eNEC+ogn}$Xe`89B=$_|X8d846++e|(kqqtO@H(-dv(=UeIi0PnjT%kb{}Y;W z@}*VP906g%49Qz_%3tb}O9R+ZSWP32wk|ne)2+PyN*RBttIHrxW{)_Ze}T!1;zzJ*eO?;%vWr+C z!k>4pFUrPMJXh=uzhKyqF_K239@Gm*lCW`Q2BI*1h2!8uUjBjOpFo4#jmA4OoWnf^0!d_g?y8b|2cVD@hLmzRCAWCK7FO8@DfKe7wC;@|wK z^R}qKp&!6Xe}7vlRNkkhLiQ~ekB0?INg@drcc8i&)?g-gSV?Dj$dd-1gS~5_hF2@; zhg@qveBD?mrLoKR#RR`8lKiYA>(u(9tikAf{XZe>+veI42vqByf0;OdJ;oAHL0sCU zlAolXOH&4Sd`)n~Og=hc4z50{#t;$n0AE0$zrIEXHrnwdPJh(Ijz(Ko#e4xJP@&1) zGS$$7q4ElNM|uU^Q%qK4(FEV|t|K#&PCK7m%`ye?QeIb>O?5hzv=Zq==4IzIw$hC| zuTgK^q~n_CsjKu`V;yy+PHWUlH|bCqBgdV6?XuoXlXn9@;^y%oHfs}Ytf?uy*PW;G;8e0lH)qO;s`l=uSS)7Js;?5EGacp7N!w8=)ojK8^<9J3RG=RM_c6LHzg-io#`n8a53jh9+fU(>WXc3(@x4W-AHcS_SaL0*EYQAHxcX#m-1sAgf}DP+9Zp1M%zt!Rqtk2q9c zHGdd%0DCog$Ebc)arqWQtS7kCO~S8M!+6$g7%v)lre_;e+5<@;ZZ3Y;sGl5Z5p%2j z*KhC!39of=I;e8RR?mcZMO?)kdVDHW_bfD-#)H8|ho!Ky^m;uzHfp}{j{f?M@q`1& zTwBEZxg8mB2EuQP-$&zSPBEGmL9O%f4S&T1BC4_f*gQ;pDvt>M49|Qk?rs;W0Tc2> z4yFJVx)RLgh-}XQEJ8*CLt9H> z=Aid+G;%*WL!NA|=^9{?V%nLHS!=+OWCExpjzcHhLkZV2bWsblimM2+V*e~`41A|G zDu0A4n?xZpR z?ni0AOQ_#Afn!Rg^J)y}*po|R&n5v}9WHnJLStco?M%{Io$Y_+!_#iG(!82ZQVqh`whcmTki zPv}euM;&|MIZu3qU7X+J$*>xh1)W%p4=@Q0qt$}Ct%=pazc4pei-wDTS}njl{hicz zU~YDrlX??TVYMea9b;z`3&VG-3IAdsQ~1Pbu5Vh1S|}A4hYw>D3xBl$qdPbu)UVZ? zSQf(2DTz(YPOEy>Nj42-t5n5D zVmcq6yufp$YWFIOy}JDT%!kQ)ah4+DSJ$Gb>zsx#jb7|al6;OweTTYqoG5z1T>D*(nl#=_B) zX|ryb+z6*9Yo48TcS!1T{2@EQq&A(fLXBbP_1K0C-OB8GiAxzz=*L|xT=t*dyDUrs z7*~$bOu*p3E4}E!1FXoH40@}E{oAe=vbev9wp0OT@h7sss;Z?7wxkG zRNZ&FdZe=yZhuWxi&8gs>g1J~I2G5siW}@gY&iL-P_D|Z2Uce8n77^-JPQ4gXI7RS z7sxOvkR$*6e3F1n?%8=XQnvWx(5*f56a)sI`Q#<}T<0Ip@M~9z{hX?d_gA^iGBrgi zJ(hlCfhMPoRJ__uwAs(u%}EMb_*s#!Ftj0VHFO>bX@8Hdu~PA_9Vpf7#rP1R(V@l( zO_(zzm2DzU3gHEf6JjiCa}3gu;GQEk1^SRfB3J;nE^MSW#TFVov&RvF_<$j5uB!N3+>77#C%fjt3* zmnc`f{eN4$Fc44}0*cJNfl!U`+XG6n!wR2(t1@!ocM(65v~EESHy8+liC4%OS5-B+*Xe z%NGy>Wcu8%EQaN_CLxXSPU9bhYyjyW?8T}627jjs0^14G>B^{p4Ka<<+&z*|O1W8- z%E?-k=Cz6_ZDKs=jt-@Tu-p|&n;nKytFs8D4IN5t@A+sXBh>cvV*qSoRu-93suq_y z4I)o_3=-OU;LicTW~cLuvjK=g6a&#(D$&Lp1otyr0OnmGnv<@zfOM_KCgM3#@f>g8 zV}AIEMQ7loQ>cpl&j`^Bh!kjCUuxG8qF9t}2Nkw%ICO)Wt;<3g zepg$CFotGiyc+W7l*SbnHpx7c#V{Zus9+i&b~>a(jHKkz9SlAZb*i7$3DxgVGY?-AN930gX^f*;jD&{kgGk(%*_0yX8f}LOPU0GCbzg_ zspQaH1W#e3??sA05v4^3u4N&)0j~uX`OnU-(d4m)1c`X9lw|UUO9_*nWJ&yfqb4Pb zC}UMk!}4Q|Ow)3v(zue5G|y}`SAS%Xl=mD$ekdNA-oPuY>8I7B?}8<`Q@>lH?qZ8WHoc{F7sxd@9wvSWoCFrs?PZg z4PnbQTxPZxI2*>fEpHgSU%GETliejrlW+deCENG=w%F?`IzFIUi{EL%On)hl_<*wk zHbch$6a2_-U^1JS-@C&(PZycY6AbP$I3dU%*aU48+qh4;aOKtB4ve9^;? zix6)+Ca$>tBfPS}9mowE(tr0D-=0&L8#fg*gh%m7ClCBdeLAdnFalCNoWc*!rw8oF zyW&lA$ouElzCb#mA9QCvZ34T}JtikD{9r!O$N-^=*Uv899;>l~*oCIJO{M_7-6O}D zoxHz#gpqC$SgY3y7(=!1rf-i&{sfryI$n6dHl58THh>M6?vOC#N`D-UM_MWxvfX5&}#u#EDs4w6bpzTPG1tSPYbSt1gEh@@SEnP}Wq8o+A9L zso+O}9gbD-*D|mxWRUxN;!^qaVZdfCK8jM;v6;hkEl239YJb~J8j@u+_-BC>LQ{+8 zUEPIu&g5>FN${1Fc{oo6Mxkc@d~(DtrPrKl*F0{vD8Q*AumdwRVjHF|9YlX%I@Fvs zhXMy5H({5mT*IJT*4>;SrXrqERpdB^&_lsqp@@%iV6JxQ1=6-b#rb+3=T>JyEcJ*}}S$`_^?2AQ_ljVnf4o3}}<&z_( z%oERIb$O#qD0^jRjkhn2vd`g8ne*a^BYF*LhwkP^$%^Sx9FrXV7qBZ!w2AexIUb>z zd2T6Myu1-o8s%)csm01-vgWSTqZm`%vxLJ!K;+>~tScT0jJT1!vehD0tA5H@gYkmb zsbd+$@qhBlj{mN9i3*v!F4`EN5KOXe@#nzXrD(*hhLP43#|Mo56>n1CaF>df-KET0-nv91T$9n5x`}m@3@H_{sOd}7I+KZRu4&9inD<8E_O&OQ=WYF~pG2P5@l)06uI?RHAa!rg0W z%zsiUAAVi9vXXx|u2k-5ch2&UiL~tGUs~-(e0wM}{B+Sb-Y1&rMu30g`oltF&G=0KtId zYIauB*Ms7!mIW6}TJe+>`^h#s*tM!`5aeLEQ>unvXksMG8V}m zu-{hrUk8In!7q@ToYWDsL2;WHk5FmUlKr{bb<%(-OIL~bAa0)J%S$K2Ye`q~=zjyO zr#DKFFYeQfSE;+4lrcce$?4Kjx4`ew#F?Cs5HVCM${nc$ta3Y%W!7?SD01!!Rw_D6 zimKc>aV87co~3xCyJF)P?Si@o1U+*S8ubvLs>PI@JsxYZbxP<2u082bLLD=g%H-T! zx59$`m^HF1>7^)TKjz_>D>pT8^MC1+Q{&{w>Qg&t*<9ga@jB}G% zAd5vIPce3GSF0%pM>#?d?9jI+EZ{pU8>+gWxcRkY3oRaRqJNNPdmmrZK7TU1_|@L- zY;EpW&={`S1}@cqf)6<>O$?&-FJ5M=wbiz^p&l=$D|-xOL zU28A97sL#(Qz(L3)vENQik`OO5v#Q>%bv6~H+w(I$_f`syOluRme6o8XWQ3j5O3Jn zs|39z6$Sf&Vp=c4!Ud8qQh#*w;o=3BU|u#@;OU?jC=1tJv*=ZJ?m(Fpm|IjJ=1gmW zx=GM0@sla)0lfX~3w}2nc+# zvolrDVMr(Qk=2mxE^bSV+T`=>y^Lk>Z-d9H$MWy!Xs&6y8$xd-3;Ae1tQoAvZjOE4rBD}Q(T#Z2e!sC(kZ=lNv&V_QtI_`%t#!*sjq_&$?|H{)5Qk4GF> zyE<;FSqCmBv*E@~CVS$MClj2>Z7Guygb^yHPhn|4Mw9W)Y<@nwQ+nH{C9{~yW|$p= z>ioLJk;oXz^zT1^ z|M*`&Ij#zt&3^RJqfh?(@5kNWNAv6Q=d0EHXCVuJF0ZQZJU9Pdeq8clc=Y$&(061=08obILQ%2_y*HF&EWni{E_P>;KqxEe+nFyGjHQH z^?>CLM3Z)R9?YJ0^yf+phM>w8j-uN>@wnkHn2Y>eT zXuorhDjdMrz~ZM<_3>aR>r}tGl%r#O0c}F3)PI>bJh@dDJ8U@?HUc<<&>eu_BY$|{ z(rQESAdL4Pm-lRHUKG%Cy)26xdOsVB(*t=Me*Ssu`fGat^w7y&6Mo3&A-CKrwmHX( zg^uj{>Zt8s(?f>qJ^zV@QuqXW)tAe@mXQRfL#QL=mZ$1L?*2Y?&4yFg-qqc3jcGQ3 z3V$9BL~XAx5|xyKS-YhiaMO@|pBPZfKB}{8H?_>!vYy-`n~t^dXCQiO z4QHdpvqA?2Zoe)2*obxxwtwHoZ-WzCQt)0Zt48%4+m~paRir+8+In1jYVEvsx2xz~ zyR94GwM&vgZ(csOE?@k94^{N8F+M#)kw@EeVAd0~`Lwl#>P`8QpL!G*eJzao8h^mZ z57$Sj-s;U9Ylq$52AXoc&0H0$b4`YJU?BbN96G65G51gIe83?*#x^FXaAe1V85@EP zzcp`vY0D!Y?J3kVkl_yh+dB@gAHDQK+pj*@)5WNJ%^kjjb}ZEG?ykG9ZI3a~#R@!V zEgQFQ2B&=yB+d?{yBa(X(!t5LMSu7B6;A!S7yc9uY=3KTBH!bkrk{S8UA|h4d(%`% zN6&pP`}@4}ZyZE0yG{pGG9M1Gy|;}M#Oe+Py(V%+4{^+Rrb<5@wRwt;b1v`fZRvp; zrq5nC^%a_rJfR48G{sjmb=d94)96qe3UsF=sYx_3nw`yCQY@ikGH3@N^?#l{weHL( zv!RlI{%{o4PR{PEe%Wo}ku=$n4jm8b`tQ~7p(gc6U_OA=F~+h;7M2}{j+GAy%~ZZU zMoy&Pk!~5{xx;GZI^U;yFid277i)y<9iG(Z%Bn%X-slgAx)&ho-u?!+ErqwrfPeUn zKnUH-lU8)7#dSGx=8MXKJAYhbqYaVeegyg}LDgi#-NiG%_`*3y2JJ~vF`~y|&bimj zu4!q|F`Ky0{nVl29&#=9qRs|SGqW6R7)>YB@3eoAbs;*vkvirRRt58gC7li%u z>-F1X=o&^l91mIzuN~P$HuPQj*3o`O&XpdS(2X&Y4AZL}+YsVTCx25-XQZYD#1d2j zz!)#UL33-{pSImkA9QFm0-NEzOv`^UJ5=6j76?X;HMp;J{H{ZC-)wtgT?|j|2%e$I zTYHf77(m}eUa93Y%!H-n>tS-M8SL4(9@%T#4Y8cDGP;FE--2Y5SlUWn_ zb7o1Cl{7hnr+M{wWq(X?UksXt)+6=A1<7ICzI=;8ekYgRYGi9!olf^0F~`>6vGr-* zw5QVoTc^oZ@dL86J{!1$!e%1``vv{pAUrhQSMw1ii8|kJ4Y%-x4rRAP$bNIEle_nE zXWOP-k#LlUAE=Rk_XwKivi9rvoJnLYc#8^Qe9suR{1V50x_ z>>HErdi2eI{Q2xBgzh>qFIMBLS^Z;ug@mPr`T2hI{M&C{oPFnw`)=@~9GP(9 zekcEp<-b?*-}&JC5i^LN{UmEKFHQzu`RQOJH&L~g=fEF~-kjqpju7WSKp~{6{LH<< z`zFHHx~QJ1&%&&nRc}>FDKG049#v0USNe(J#|i)1hky8Nu<1_Ris2>O@iY6i)=J>* zGtJ?0RM%~X&TUsJIHIlMqc(AFLR|rd%6n>Jt6I+hRl*bfVr9+Hxw|GfxZL#8?8nY* zf)Es2IXNg_X6Vu8v;M}{qag!rjL$;hB+o1skd+J(CbPhLoVL`NiZjy9@iE=uKOT%iEr=4%+Jw`y(XvzyZBrg-{ZIcsADo)Z2`r8mqfQDE z0V;OZ(Vz=9+(D!6w{rZdkZZe_p3-D4k74mK+Qg=?eQ`p>#CUKK2AYa-Y{9W*U&luZD zN!pp3KHIDv_SGKmsQvk7?WnKzs~xqUZPt$aYM-}izc;|$I+ltC80&p=A8mqa6Bz4# zb02MjY7-dieRCgef@%{O>wR+{ZGx(;I%lLf-Xu1_G=Cs2k={F&g@d~I7TM8vgkflf zQh!JD8kXM1ZrIypjoVtt=n-VA4z@4A{?ar>+!#PlXL=%Q?P_s-KDC`et2P*I#(!G; z;GWM`GLZpH1kV@3qmBm5iqZU)Vsd8}^8tcc6mL7Jx)*cye>wh9P9RyUz9`Ut5Q3pP zY7o0yLz**oYmbg>5a{B`nb#M!R348$V1Hy|8N=-I`qJTm934(?DCVuu#-m66HV`as z?uvxH0f9OfS_=R=@y%G+zZd{?;&vc+i$dKC0%F`1`V*@4{D-+vdbh@ip1QrD`4u6< zAvqkAQx9r8r0s1mWcxfpz>%}FUb6V^Pr6g_I_ut@ z%i*J8$2#rIh`ZVMZNTXLelpQeUaJ&tcnA1^}pE$vV}^R*h(e76!$iOr~yQ zyN1U%=L^eHUS2KM_W4cg*`ARnn}1xV{rTdm#icH8R`wBg7k|1IQlozJx?C*kl9$5$ z*=K3U_V?ZfCG2?TKOqg!{QlIqCm6G=pCRyCtiBuzf!Nr#Y`I^Y&`28!W2D#p&i~$0 z>|;Yiez91r1}A*{_eD7woX{CaA$K+&t&R=o&Wbku_UG%lsq}vq7v|~f34aI+)6%7V z{Hz?WF3mGpNAvumEQ+g*-r7CX8bS}qN9mp7t zw{<7c#;4WR-%ML?K15s3zF|}6i-)%KhZlnr6+^ZgI$a&tQjAvR8FI`(@Yq7sR&aSi zfKJ=r+zd{(+7*O0a+p>{Hh)WbOt-aqhqPV`qw#)&)2K)E1x00yit;=jj6Pef#&3^b zuNIfGuDuAok-7K9j<&+V27l38D(aN_14?m+o;~t9NJWfd2vhHUcQsyo(F3vd1&l| zznm|s*=wU-Lz;v=TyC#5{jg_nZQ@D?Xz=UotZU3NAD6Rt9N{Y{hg1^TY07+JBae=D z2%!7MU@Gd!4Q;v))Vqqb*KJQ3yAmCip+T(|Uu>YPdD~#k(|_Xe$HpYq&JXfZ6XXFB zeJitkTs{66eDB#n$j1TFJDT#J;?v;&66#>kI|zkd!@BI2KXem@|G5~K@CSKzxhnyA z(Iw}KTh(-hVsf=4pjHUQPfgGWaYf5w1{q1%(Em@d^aW(<5pv^aoTQsMoyNAP!oF z%7rV1<)nHKN6Cr=N>lYs)7bOo&7Q^{H;s*Y4rw$?^-BAzL58ZK*Dxog4M&x^Fpb0c(U*I>X?)5D)rNLtD}e5 z|EU0uJ*n7;xljd?kv9qwU$uGEB|aBiTc3TW9(sezg;FLw*4HQB4Zg|{kmW1>mYEsGBuIsa;&ys$- zBvqj8k_;mQjc8NGDn#4Gau&{T^wyb2i$~@X$pdCXqQUc!vd?({+P7~G+zB6DAxWgEAjpN?@u?6 z8-GptyO}xjyRV*|Y={i>Sg|Jp;=>ZTj!joq?`~cyKp2y4n~WARcknzPKw)~M<&|$5 zo7!ZS#>11rUj|4?$ZMTf`cwUmEba2T6T(3FuimmXU%OfUMSpp-Hk-wpjkG--xeO~c zdsz1}on!SPV-w%0KhXCwz4!V*rfFT2)PJT57=@xSzlsTLiI|&JU;H~$m#r+M>tZj8 z3RQ*mlOwFVz*^}G9@5)KGmV0`=M&#~UUWJ(|4dfG5f`&%RX?2n)Q`FYQKu$4WpA!fu-ytA{e3bY}L zHdLd1S7;rUeRK4n3LRMPcW9eGgMS=s8}tr`r+vhIi-|#-gp(=Lc#!Z$b>yaT{>vSl z?ox$9o7}4(tUv70nt`Hwd`mT|CQ`kHx^XjDYd>e~?@UI}&&0JUFaT!c@8+y`bHrWN z+q7K3E*M)Oct{wRb z)E;w?51w}C_09!))NK#GVt-$K336v^e%0Hn;_1<5_uj~yDK?UJyC- z2EvrzsmHB?u+Cx-KQorv26p#g+Ak4cW&5o?OzeRBhks(a{C2Uf?$zZ^s62cA#V(-8 zDs4lhZyU+;@aUeH)Mh6?n@pbB+~s|E^r<;vp4x4e=XpQ7_@Y?d6n`sv5ovsI7;z)h zb{BBQp;~?-Dv3;4;W3)YZ_-gm2+@H6DNn1D;{9-A=v@I`lk>vlS8F+f^v^>DHs;50 zeD~>Sq#jk;B9@ci$%;B>q@C5-yb1IIS3ZO}8(p1wr&qn3_4MlTHI<7P7Ch?!o|A?{txmXIvRGrR`7juEl z;#ud zZY7IIlYhyVH!@tr>M7>M>ZpmOF&dNM-WZ?V#SAS7Pc;~apZzplT(2(Ri-Xt_p65Bf zK>Wt_V{hp>Zs0qvA05Yz8^*_R#een9)QwThW3gO{ML9nuEa!(Fe|hq9nfa*hwBJ>& z((G(1{Yht@)AUd^9cvLclacAbq$s~~RII`=#a{Ni42V7GaI|L~j4PuF(L?jjsobXU zjZ6u1Te=*MTQ^?0b&u#|Dua3VJOaQxuYp7&GYFb#W+|T2P&y7Wc^NoSByFaZpEz!e zHqBpsy_9DGx;!@(1?WwK3W%tNlS%I)Qwjs=<=tR(UM{XDf*W$C$j2;S`o1S{5hTH& z;+){+Liuqb{YvA03JP)K9OxFiMIW?c)mJul?hNW~ZD-tKNJhFyZM*OMpC)1DSo4h8r zgcaL}-#tf>EGPpsApa~`pDk3{Q0dm+Y~vwYk?uK?o0tnNBh%lN`Tp*CE{!MB0vgb^ zWyM1Wbun(#b+xkKj?~e2*qbQhXwRl&b}fU#KkuGrf6{U!!wxaD&<@*xqjC*^rY>RT z5@`BTdglCDGqhupe=35k^wFSi8&oh7iumAfm6w&06Y_jk@@(>D&j-FN5)dN{xinZ} zLA-DYs0iNSPZ)BJ^0##JTn?u|rYhg$zcP=VJV9ak9SX8U@6d4Q$Yw6x#FuF$QmQU4 zKLo^5e<<`*saQ&z=*JIA?1C@^E?r))XXi+-naI#RKP{68M@hI0bHP9-2_3J(j*jvh zHw%3%2R3=+1BkhvmOg(Z+_!@FZonfjl~UZ)iIWQc60|5;5$~NWSf&BCupbJm5#Z)tg%dm>#M8?!~linm@F73)APs2EOsyM{4 z7zrrW#dvi-*u~~DDEiS4`E*Mga9`3boZK5qY_xTQmS;Npa54!MYN6NDa|lg z*+VJLiZogVAxF>Q$=rB$=(GGQ`%#*Tvn3}O00QhYkoku=%h*AJH3HHK zlHnh@4MM)I?BDu}EsMYSBk%EA%AuHR|JwJimXoEK%Fd6X|BIXg0Q{mJlT zwSj_RhH?6tftZYvco|hG=m3w$C`J;5e?;RHn~aO-^9awey8{JKpi3R_gPapsX+3@- zU>=|^W6Ox>M7lK6a<&*7F!l40&up1JvP0YivQKf(g;k2P-c!7i*A!hT-*K@L(NoJN7KbP6wNoey9If6NQ9 z*@8$)hrm0}U#5zJ96`X1hB-KimJX$nq^>462v?au2zHc5Rn%mg5l*R4Hf<35ERDiA zs<<$6ipk{}1vwnlF*~=oysF*~{+CYjc_bS*1)&l|GP4}bMsn1r7^-Z3c_k zna58-fEPIVQ8ARWUe1@m_XTFxf9nDWkr*0SsFw&JK=+y4j5vn;;6|p%D-~EQ&~$UT z$rBto@+pnYWs9SSXDE6W@RnhW>Y=wpNr$g7b5rg{5ZqqVx){1^lm)gm`CRM`_~P6i(bLITTV^6W-uhpA_POHg6{e;ID#K{a(t zc+U=az$?`xi?x?*kGz9y1d8mVwY7Fk1Wo z?j(sFA?C|ixJ>!4B?L+-Gy;Pz|3GMzQh1iu!m~6BAt4ZEGF9OjN#@MZ&Qc)EBH?N` zWn3v6MVn|)x~T<;7#e zi-%;)Rg8dlRmhfDe|Ad<6hgig({`GSfxNy|KVJ;{~&f=z~SVA(gLETkBcM;oFIh& zjVeDMYO^r(e+@3;%A`Ei4FWD4B*>X|m?=UBAq3`;meWVpuq9Xk6-_;Ulu`g$hO1A; zi2f>!A~0G>861(2x(!)rY9T6&RXWhsg7OjQtRRdPKryur3b{BnPx7GO^|RFCdkUsJ z1pwsv=tfFFmOHzck5x+)#Ae<0W6(hq+J8Lxdr;_ke`=8U&?)OZ?0_V3);|KA^YOtE zL=PK5vfZ#y`aICPhe;=POF03>c+J-QcRv;UW%P^xdqC}6&D5rE8s*5nk ztDyA5NY-zOV>g111P7fbXLm+@bW{S%mqDz$bto7^XsnV_+Qi+l#Fx;a`X18@BPw6h zsB}#Uf2z5#VNen>cWuN)!=>qEiN4*0dKWtY4$Oy=%9V2(2QWrqhVF9gu1?MuJ_X7n z_KV@VoIifVEF(owBUoYpknZQ03tolVkDK{RSTkT0J}F)f4fB_ALe(xrJMT&dLl2y! zWWO?hSI%;oXCmNUQd28WP}SmNDFvZ_jd1gzS!U=cWHIF^b!5UgV9=WnU2Eo*7-a+n zfum!DijFgo*8nr-^o|Ri2|#gwIjU`fMpcd=YKU=OHBa^<{>q;OwF5)N3{&vql8& zmJ+I_FDw?g4I1e3aZt%&Ypv`65#sxMsF10g_3zX?EThKlfPIvF$IgFY8e@9|r%Mng zp3{&XErO&)r?jY-`w=pS=$NX0Xg)SIY%6-A2t5InrI0S3pOV@+DX{h1H0f zjcFO*cI*Zes)R5=pn`vlCO^=^LO-0qOimaJEnvUnGwRZcz}U9P?4%Dvz3d{oeGo9w zAuxygq3GZ!yC)p?cPwj*6Zyv9$LHE*_~#bf7st}yfwsP%a%l4Nwa)XCS z!h%#AvKOvd|4PxJv{<4@Lez08#UwccX7g8zA7SNc+2XXuS*0e_Qq_e-Jdd!itc>7jj7cC^gG>7@(ZLn4d#V0KiE=`1_8wB_ojnx%3x1 z=ni&UYI6(wHd23`@1AFnLVL8tj*}WV5QxFJO=bTXMI9hS0B$FuRV`0^>`Z54n!cH) zVg8l@SH!-qOu1>$fsd)D)wGtaR1daw3<#f738$oEGehHOedrx9e#*y@)1!&S{?Fa{ zVGrj>Xw<+f16l^>vNURMhCiW4yp+Fky4vqNdTEfB8FQ2N`XhgxD|A8<9FSK^0bmJP ze`CRoM#uxpe@n`ZQ<#gv2sgPG$nOR5sTGuU1dGmZfN)Eg?Fs1^sVOWMfvM(izY4z2 z#IAx0(X-Yn_`6miqI?3!oI^9@P*x+p!zxUT%of(qqIGODHp{cgE7CZB))mXl9^cevc=F+I zIr;FnoBUt|cUW4UsJK*(YGC>jQ^y;r#F{QectcU;(#?3!_B}m1D%yQ zK85Cm?_>SZU_$eVz$dloN0t5-mc|QdRuMXxv9-z^IuqP1%InL*UA%sc>phgE&%jd0 zFg^;b!$P1g5&%a>Uuxcg+Hy#0*m^GId34V3qx%an$pr?0DH~EfMUn^)8&HyI?4GED zfChg8WRy@*v>8j)K8=6M+Hj(@53NE@UCPvV`HdV(N=C&rAPZw#^7GzO(ty@iv$eEJ zY2yYbANaeOhphrytucX1)#uVK4pa911FTM(BubTF&$~YNr|&Iu@^!g`zd^3Ui|Gmp zUJu$$M}-+EP35b+Q{7=AGn8@X4(wqFG@gI6*rAab4xA!^-LQcO;1cOW=mKXV)qrMn z-UQ#Ds{{e9LAXNqpST6)>ni{`Pr$->(G>JDXTfnTeI9&i?(iYZ69sdudS!Z3SFj8c znx8a&+M3i9YT|lEC7eM+nnH5seggg`lkRZB0L|o(2r_ujd*;;k)1-2hH^I4*IO>1C zlvj{~BqiDlnwnj}n3|>UCE~ zMfnfnxZT?4D5cM{I)~!US}HymI>0wN;?&r1Dt)ZlV-{_Zpk~d6VAhXMY zK)F0OilUko&kb{xTf17=+J&A^TsMD`%DCjk<7G=lZN2Rw<={=*P;PvY=uG{%Ot3bx z1>o)tu_SB}LWhm}WWjRFfaQiL@KZJJX-jRPcTLQRC;!)Wy?aa31jlQ z0b9SWZfa}gx^B`ZFy3N5lfBHRznl5oYgKtWle}B?=rmm>w##027u;~55jh^3IUAX- zTMKnvE7f&XtQ%UXZmd#W5Tn{ZX{IXFBa^QGECK72+y5DVa!7y#rGqGhOj#AlPVi;$ zc-HCQW6LT7RwPs3T9%MvhtM|-Wh}WNIhB;IC&#$WsiQLxf~`HK0v%h|=;{h#Y~HGBQG?Xlw@vhVb7Vc&Vk zz|%kE7LxsciX*v&3+wL#D8UCDiF5y<2==@lpBFG@ac^dmVgdBAazGr4AsU7@AqXnD zz}z^j4`4Wm>nq{gSi%IiVI91ZIw&D^w2FM-&x+q*Na@j8M-9XAVE*#hz}-1JudY|H zvw>l?qO|a$K5WI&J%Z6-gZO}zuX+d*WhV6L^)1hT01_Bj*1|hqW2i_iQ^{v+8L7dK zv;{JOkJ3ytjnr<@@}aw?Me9?Nt&zH%?eKNKr!)hOgna;sG%>+aPdND{EB%ClxF zP3O6P3yVsS?=;fq)eEhzMm6vmjU&w&WF&$aGKj!TgC01_*^}?p(=hkdG(RUr7-SWL zy$DWaw5uc)2o^sAO$bAL*u`UhIj^B8kaa`Q86KJ#beO=m8)svV=ou{LnE)!#+&T~m z;CEUjbzl|yHL9QanAE{b_>|i4CJFF;Ji$SK`H!xdOv9Tjjy|Yzk~VFmRAWH^;TU3^ zO|IOaic5kaxOd6dcvZ$wL0OdcZ+fenxG_F$1{9)1cUu%IJ8y^ zD~4$+$?-xS1B+E@OyJiJUlEf+^-Rz)ANCFM5A>4RAyI97KvWy=6V>wM_ITmm$RY-+ zUc?!at5`2qvlcx{@}Le;fij-??&MtNoGTKiwfY=onwM2mmUoDppB@a~;U^-0|CGRC z(9UHHN?b0x822$sbay7(MTg!lA5#y+k*v9Q5+wvC#7eVFYl9%JXfmG0eRQf?7 zP$(zj(`1!B3!ii89Ntl-*$(gw0T5Am5 zXJ} z5$(}oUVD(PHljR6Hp*i?%097KH&&vW>pLdQBTTJtc=V_{MjCcvE^5R@+eEzOb*--1 z_~xm5L+F?Yj%%L z*FM6(DaPNZ_`$MS=56Jgaw>3)a3Vsf^gw4w)73s^Y+ZF``XML!O9A7ihhv=mdLwc6VGNRwSa?B6(aH{^2l}jfhd^FZatkHZ zZm7d$GYV5o1#BBRW!=3dGNZ4K`E_i@raWL2$D32no8laTO2|3@IBq~7C88vu0k@+~ zbIm-bZlS81wI%&l!JXFwFTxgFv)f(|hrxOaPyUDFMro^m-yE1}@jt~mg)~B{3svry zu}7lbAb0GTBQ$|Sg31vvfe7jjwbNIYK#y8EI8onJ$LS5#Z3VF%_*CeJBL(8a<+0vF zB*TNz55-%1JcBGsK0ts59AvRatMJ%F;(^*RH$FL};DQ_?TBCfscQl8{D3W@-c4bL_ zq|l+B8l}sB&@)pqLwSn1s37!0)KDQ?0BAs$zf(_*fp6qEF4b>Toq83et)Y|pUWBRv zi}H#w+k-?scVk1>@azdVCUsP}Ub~2`@DJ^#5YrWUd-J-jm1|p+(ZKpp!5XPrIMqTa zVpNkuVMn13<~E31rx@_#eFZF@HMmzb7^z5I+tu}!q0D?XfB#>w#x`W5YKiZ@bWVF& zV(;Ei2Shba*grf-Q(BYeKCZDqH4SP^k+-bcTx$>~M`dmbuq+|p59~(D?>Uq=#e!XQ({q|h3;ENyr;TJoO z5+{L}EsLBiV_r7WB`2*tWZ=*NjaZmlcM-~`EB@=0fd=^Ym$htz$sII+U6{&NNmZz2 z#7?fpanM#xqwP-9I-DFc49ynve|#usnUe#70@{u-QGp3MqIM)Mw2d0uD>4}&Dh3L7 zG$zWEKk9rCaxw;0K@hl8%7GYZ17HNB5}}f z&NJr2Q^>}2&72HI-r&5k(otq4uz;as0-varYZf9uPhhja5EQHUbIWt(9>1 zEVd@$G_zn3#M(czPZ25EdZ)l&D4pNHx$ zGku_^cFUF9?o@~KkT`02rhLw2h9^ITt-i&Q9#Z}Toq$;$*(CsKV-S2IvSP^OpBH2<3`8b51RdWCKVCo zHKgue&ShBi$WZy=eoK+S-dP$19JIB{)y7+N^FRIKe;Jp#2?0JqpD6bWpYE99wwreF)E@)eSKY)wbCsxu~PRfP1tLJ5E;{g9C3MJwv;pFT<`s0?*O$6f=~&RK~|y?($r}q zRBlqg=~?9>^FbP=w9FYi*Y@X_2&K%3phjEG<;Q<33^I$VzK5a|T7HNwJ{$-(An=a*tmMNWgY(N`gMhjC@w^;g zj{jE(98)h+)mMOo1C#~o(H5EW4}!FkLPrl#4p2me=F|?VXwE1_A|p#oEoNxKP}6|c z2OXCg=^V4`{yyY#uV;U>98Qo9Itb;sgd7`@^i75b_`xW``8qScrsqYZN1SH@8mMa< zZ&66Qa?oMQxnOdOv7~De)t_Rmn+lg=16e~5ip&SqrlNv z`d(^7{rh27A$qkRCp3=q5!%CNXb+}0_e~6bre|PQhl+xSEVX}@zH|U_)n_q^tz**C zP1R!ErOhoY;zQpt*HXTe%a{=la5Kl6;ymzSv>!!kvkw3%PGlNM8|o3|6PS0q(kS9S zV_SJ9s<{F^%junf9G%7^#mz(bo$C#jn-sJ308(e<%yVd&5UQI(gh_DaL03R#;c5DJ zI$_7Pxp8dnti*q-pzw&S&jVJJ$4RUq(~Uq)O?0MS57}6_21LU7@&GG8#1` zjcJLjO}ioUHiN`THT+hLe79IqKuAX%Fh5UhZH775#8>}|AT~$R+rnL370prP$q~lj zE`FltB!?SOr%?GuVZi1TlYz7R69x4r9Di!d+&sa-DN}!c%*<4D>n7ZG!>;WO_*W0X z{0Qn2EWm17i;d;B{am}W4bq9GvVS9+eHvrW;pS!Pw%RjYC=>$v6l7T@-*UA^Byz!u zm;+?Uey}952GSr8gh2P2*%h3trh0WX=V|3?3e+WS-zf-#WwTFxgL<9lIfcEWiBvTN zi;sL$mXv?=t>H$l399KBBA5ZPEcNLUlm(Rbkq|2yl#AKEpFgS-LD*9Lt<#g9?BRKHFWZ*x=IsEr}yI7tmOT@E)Dh-iT;mE~o-;j04^|oXEV;LFGU6g|RrH??F(VcMDC#k@s z7jlL|oS?215k0XHE+g^vnnIr?Ll;qSuWkcY>aH=pd3NK#+qJ=*W{3Sk*a}^vUqTs) zz~N4GYwUb8Ud?Coi<&~@?m}1&+}K`{fLK2gOohJ%2bLN0O?-!pC81lJw3jyS^RZ`1 z;VD*K1{0>#6MO2_$D1pGEnZCD=rG!o=jw2ZuMoj5qDV>yp@5eO5CJ%Uz&#(YG=6-d z%p};C)VekMi&q0!`{?Q!mz|b zp{qEI_pmC}ZsC$=wTZihB-IYdh-WfP#D}sj?rXrWowx%vq<1yVR;~uQkf-`ip7@i;XC3G*@1flVa69oXEzFz#1~TOjcn7Wb6z?u|IVREU(@@H_;FRlfA?=ovB5l z8HS~X0*zErGF2rkJrM`v7DE8-R0pTQ0hj#{0YrZn&=j!Wd$?N~C8C$M39I>5nX;vA zLvL_4TxmD0iB1=**}KKO(y8Wh{bY%<|1Lrtnc?A&-7V($bL%qo@!c4Nx2(s7qmyAK z#I9H+wO%b0Fu*(3k!zdUq#E?gAH`z*TiWkR5!MxJ7Zb9cQ4T}m8=v0zJ1o|blx9L7 z8ef0z%Ls_!3)7Us<1Tg>4L&sdyBtaZeFGClv(jyrsc;SjBVX&vwV6+arprvup3q|7 zAs0vgfQuvB*zNJVH#no_oU?IX{AQ2K+jrI_y5}Ptjf%3QXf~{mY)$5on>7x#%aUT7 zFkR9~9vP@2!&%UKK4S13xReKQKP2f8PUU|>_F*|i$MDGTFl4wxL#JrKjg-7xq{{Z( zvXs7YPzY77I7@H`CKg0&_|*Vhz_AU$l!mo@LDMKE_AG|$GGfs4_{|tY z10f&4?|T*(;nA*!zd9+I6DAo#{ws@+BEYvyy#g>YdVo7XtppSig#&>)nESl1=`DW( zpK%oM5KLkjhZ>m3Ni;sc<`yG*C>S{9&@)D7`hZZ@xw_%v{CX`XSOswj^A1Ky32{=I zX+$e|mJ@>VDh!X&C*rbxaP2o+*0q%*1}b0%G(&sVbtMx&!vS~zR^0+~2(|T)IF9&4Fc<`{LM@+n(10JxZG8Tx2=-$x_=&qTo!KD)n$WmF_)2d1%2MJxOS~`$1Hwjuwg3rL9+(tq@(^( z*4VlU{?-d3#81MJz_`~S6unS@XQjou(jwwCW+J1~Rs2G%KHwajafpCZ=&Z5I)A4-L z=v_l$3o=ARKxEvIVVIC%G-M`54d-SQnxUfxt<e0-z|= z0_70ZF(}Ogtd0RqmQMqumXz)g^#S(1zNRISuGmumS~oOnZIm+j6ML0CNTN8Iy6F@- zTGZCqQA1N> zDGxA$0h&GLc!3BzG_-<}eVI85bX2k%6Dz=!L7Q|p5QHLyRCvuBJq^e&z;)il!hZ<#Ut|4m@P@nNSTnvVS(!Q{$3V>{ z445jLMMJy+Er1Id@1&c6S#9ayp%xzrSr#S5antG1XM+935BDvN9~$b9*ir|+w!Xs; za0$D&Pg=_*O&2-z65{BRB!*@U_Csn|6p>v;338u;AvZi<4Eh*`JJ7JvY5-$Ut#l0r zI)C&G4w%?W@Y3R{TqI;a66KhQoxTcCu`T#JV93rXc7P9hOSeR&JEYz-b0v z5tdU~gD@;iH~sXjZ6&y%H@Y6RX=H5~sg_~5 z-DWp6rZL*I7N?q=^MHfaMY(v@N?~26E(`R^LHtf~k-QQEwNuHWitz~53ZnJcD&V&2 zxlL>4F-o+6`L6X?OWAiIQ^U3*poV{ar_X5i_V!QesO6R#35?-~#@tPqP=?wC zlU~lN5r)zUW|uJsHCu_S7I4YT2#is03_>!SXOEwlutJS${92lw)8RX00Mk6IXsNU` zf%hR&A+h05H@;+k(SWht3@l@lxYLi8x-T_oXk|i=#v0}VCK@=;az``o$Z48*%IkkC zw)qZhC(Wek4y#Mzsi~HfB!WpBjB`q*N}ZEhwaKo=5l#)`#q&c)##nBt+RcN!^2yMJ zWUF9BCUlJsGlHwSL+&7?3^{c&Ye!`4hnSVs&jK71JzVoY1G_+<3W#GWL8?esJSwj4T32IF8mXtS4XnfU@z{)_53TZDl&YU!!MF481)?f&R&;-b( zOe1bGRe2_`Fb0KSx>(p;_iTUAnEE+1P=sa!Ttry&P&OK<9JOy&#r%BA(CRp#5py(& zoIC*A!%z|d^Oqr!uqqRT6pCRBlmLga+%Ps8)LIRl06NCn)=ve{0SQeJa-J>L zoFuUaq;J87`=1GNe6O)7gT0?olhXwa5p;6dhzQ}0AWD=DaRHSLjFo@6tj6mf)*4h8 zhDph$l5RUQg#Q6DL->2N;YRD|domakywXPDqyn5W$qzS9=b-~lFwWSHGj5MF{2jqF zz%av&AWz81{(4qc#R@23l~DO!na6HJlYGBetm>7^!<(7V3u~JRtTiKFg(mkyuKDz? z%Tm45O@PggGe@6wg7JR=@DZq7{^|2YsQnarE%ygRRqR}A)8ZE??^CA!HrD+t zQ@NcVwuq*FGWFcLHTxJbSrBh}eD~>2r9@b&eOL8^`B*jOZ5!nOF>a5SjIYu8JdQ^l zH~pBg>0u+PlsNqXTF>y|HAUJL^*L6XE)Z_MR?_-z``LbXn>vup(i+x-)iPs184Jop zr4ed%o6scQwV!{K;IvuL$du)Dp3E$n;wNxNze~%OeDx!OCg%>NdQNBo)qc=D!Bt}+ zCL1Ae5>;~e*3!p3>m!Tc_mbw0q}WJ5sG2q>H3fcKp zA{QN!yTp*h8k~&i;6b5rM6EzX63DX&P^m*zW-zpvD?FDABTG$L8)bHP!q^oPNa&-MFy#$_3gHp-Gi3e>q<*x9ZRXI6YaZDo#f+3GF@Kk# z%r6wKHB5Z@FI|STx}!U0OzVETm6k+)8d5E3E#;)m5vyr8=*QygS_H;}3D2}hP?I2E z&5rS3MXMls9jN0IEuV0TSuxOYEg({jO>RO_sV9GV1b#Bn1!CYe7+$3&Jb6x8Z7zH) zqV>yIGqp2KsTA;&u#9CW^50S}7Gy~DVU`MvgV~N?S{yGk&Da*`!e!joeqfB`!^$98 zOsimHF;9J{dYTw!pp@RJvr3%S+9YOwq*T(W=T>BiChCET@v3r*%d6_GW)niTp?oPb zNx*;pX=X(D-_fjD)8`uHzm3F`L`;B4uiGjx=}(wW0TVJgVd}B!UGAGut${g{$>kb5 zevBE3e*~{HJ^IL;M_SGnQ0!I zBbQ1a0UCb=2qm$R=_Dad2~)@j>HT9&L$P(Ds8VBlQ%Qbv`$DY5ZLQ)ZKTz+GFhMC) zVid9fY5t;cDgQv);4?d2-&E~r$qm_uJ#q>>Xcvdh) z@1Ey(w!F@5>V`%teIMg!%-4PO)*Y8u)A6gK8rb|nX%mIl8bZ}iv0)J1*ycn3HDQ%` zzKKR07-QZ;pw9Hjp@(tJD8{CujaLj!l4eSY4frgx3lM_a-GYdXfADKh)0iyZdoJ3* zZ5I(hje23)hRI?z(L{B>2{3AujM})D!5{$>f3s!xw>Dq@H1=+Ry?|;Xc~z}uudb_N z{aeg6H|{t(MVm_pKiVrEnr~tA4KU)|BJ(Y3z8N1M6}cG;9sSlj@84{lgL?8?18pHe z&jdX?`E9`DcJ5p79E{4v1+VJ3oxM#HK(!J>RjrIsbr|~Fq>{R)`4W>{?{xWy_qu%0 zf57`8nPY|Zak3;WLnuUoOx1B%JsR{F?i9vg_Pc8ekbR&L6O9*Q8};+P0g!@r*mE{Y z+8a@)UYFxFH4Hga6cLkCS6vBRZp zJM*>Xs%ChZFnBhr>?<|)C4Tg)0%q{KTwGnfbtkj+ z4+EPzO+Dwc_*SWjNTD*Je^2DyA_0-jE#=vvnt|%A0aBObv6;VWg_}%4mJ70Ez8O7m zf6^I#$%uo9sTSmPp#uqn&?%h+8J%1pj8cUZu1Ib9YtKbSE|`>rhvU&kbadH>N9%l; zfV4rL%EhxQAguwmhQi)JmLLHPH6A;hgJEnEM)eh|INq|z^8?L{e+mhG0(*oY|1E$H zaK&j*ro6a2vP`2!vatbtwQBO6(mw4gZQ9#Qg)l&u-?Y59bPBRyC&kif%Qn?lP@6G1 z)U<8u$r0BRv(0tO)mez*jg7Z~2@Dbt#<$C675^6J28}S1TR4CPv9~Yig=1v}q1PCM zXi`L#6&RN)`+Zl`e~aKibXEgv8&;$RYmM@dU~9$8CS{~!gcUBO6-?lgkRbdm4mL=< z<0Li$?^XZ~&nmq)1m5j?*DQupUpsw1cg@iC^4%dLkFAV6*d-%BUlo&Cg~&eL)V&9j zGsbm{nY{#$Zz96nDps-Y-y&GCZzV-e9UjIClCaV+>syWIf9uyY>r&kVmV$wV1S_rX z!A7cxG|_1NeUF(F=iC-rHB;X(-+5;P;TT`@d&-Yui%^kmt>-+?gs#H;VAdk+)-FpR z48E2Qa~7?1czq0}X|XSjunObC9Ru=oX{NEwnHt?mL=d%{2mKo>+nl&Jvq`bAF@}hw zDTI6!|JXo*e1xf5(1J!Phj03#((j6JIVPE^P2LSfm=t%$R-oB2 z*fh67OF&&qFT+}wVFjCMZ3L)^Vr|J-s|r1vwn`D&VN1GyUM{ZHOR`*y%|?bEIg@Qq ze~v&SO~1MnrT$u(W9DD_?|YaT$qsHD;>ZfBK>RhP|IPr}z#>%kZ$HrLqp- zQ!_PG2onth2ulVZR=v=U3)hACHJVi?qcH}&s$s+|EJ#X^5s#7gGR9^kC05}_l)qyl zpZH)NpG}va&7kD!*%C!NgOby`#eDAxO5X8q+0JZJuj2JpvxY%;4gGoroAo0j3LnVW zTG)Y@f7bN_rRgaM-JBr;K|A}_j)B@|;R?gVYdo!d8%0NRl#w%rDjv5fOaOCTrI_I_ zYWcw}S1N0-R8+^*)WuSd3o>tsfHX={<4qJ~d*a}4_<7wc8BmW~Q!57k684XQ2Y&-u zU<@W_03h}DsEp_tlD_kah5`4~a*%Gov{jEyf97A@%e0qcoYv;$Qhl}=dP(7~t~`O7 zutZ_=L!Y%6OD&B#Jgp5ibFg-UURrMu*$J|Mre@V@vE5U94089RWT6l!)L}Sjq_L(G zGu?+gHUFVSNM$WU_?BS_VdY>9&V1t>QNq|KUt+T4^)w(1BEAI33T{$md0Y4I!MvSMaOLNR@Ng9 z`bM16*@piv)wd{85c~GIGS6;gTvqDOmqsW7Ab$b@+A~sR!4Sm`<75zCX>Imm5`;p) z6ff0&hXe#|(3N11mRJv2a)<&EH-}5XmEc0?Iz;O8WSnKxqbY)EpOYI$DS@n|IQ-bE zUl<)D(0pldC&_89nrL8ET7V^dt78wXv!j{=hSpcEHU4mW{0=7|-SgCiGm@I186QB7 znSYyrCP_Mnusw$aa|khqROSE@NBBzj^-NRWq=w)ll@MmQ=`%y)hLI)WaCS0LojsQ)ORBNhE>VB54FFwMq)`dV{Qs15L}2$9oP^`D%I#0+2WPp<_Ac#RoR8 zf9i2yJRxZJ0`)G_#rR%+ziDU4ctgTTCVyCmmb|gAN;7{s^)j7qyl=X3JjEKwfnqw# z$mbloisBntP!kEQEN+U@xNQrg5*RYyj?Sh4ZwzC?t)W_0gVJx<=OGe!P+7aoW9yq4 zdR3~swkAFq($U!9gb-}1uvEjDrFy}$veXT7>-;9|2O5$PoOKY9S#EkV{O?$}?3U{Ww$AW$VSgROmX^w?jn7|iEVs4WT<$-!rhEL>vORul_gPav zxb32j%Yv4mNsO44d0Hl+x@ShrS{YK1o~U<*rzAHRzBFMtZjX#apeg?n2GI`b)gFN; zLh7&xZWu8m;%Ls3?A|#~K1|A!SZ}+UId^Ja9NtR8aoHG~dFS#u#8n^|V}G3c8jcuM zvR#Qwr(ts|1zWcg#5>8YdrkK8GWqU&pUoK3w!|V(L&){{Y`tEr)- zTQ3sY+)qQ{CNkV|bf7nMGKAlx7G-RVX%xe=9DkXxs{8eIMB{Px{y@5l7Zbp5NoBuBDIlcYm1?VoGJXQ^Kvo zhkTUr{z1@2Rj8o|tXMOxgD;zyn-Fu?X8X$BF@SE&uLn zI?2#oc{WW2M>4ED6TT&Wl@MVO_{z6PLhi~pK?rDgmfBFv;8(!NWT`cH@r`we8kWSQ z8)A5VWQxOx#+B2>$B!6snJk=OQD{!W&;)s7Vxk)zg^V!4J(t`p0V#iA7{l*|(>U?? zL!JTQm;sXm8-XrYU@*lUo7KEbw7lQ|Oc5Oy2;fvUYU+g`t<%y+PNIYy)$F`*%SBnf zt%Fg9wG@znnGvKQODHFk=eE@wLv>^!qlC(H$7U|mlu=S53$46Z+RG4#BCpVBmedT^ z4a^qpaYfHL<8K$F9j$*25>uo+3Zm==L08odX;7_Zy~w+y?T<)i0WjaaE}XPRz*#X-OCVyyrNYE zapRi)b(Fr9UYK$^ov7`b9jQZ$v(fFVMO7^>jV}i;(k9A)ia&pX8vQ^FHDKDIudF*Z zL5Bkqv6YPley8(lab=SU$T~F8vN4NIuU04%_}%ygrpd~5QG-mU%<-sh4&imL%IkHT z^1h9AQ~2<7tRdB%4^J!_#yv{$yVz7Zn9Y8Bs=@oy*VprN(`xnhr`cIKTWjy%72m%XTJn5)R1ANT-|IzL92cwA zVs$k5cD!28<`)iso(x9Ca3oE5?`N-%R>M_MU9aXcQ0af`iA=$HGn-V?vyTUltH*V*Jb(WY(~(}j*GIm6c``NQhuqA>(Adl zE63~gpT?KP(cluzxYevGi^1?a@B7j0_LYhsE3Gp=p3UdQ>fitJ{EuhFXx92wjb;-w z$Z~S=QmY)_jLYldOwr+ypu^Mo$w03A>EeyfYB+yv0Ksf5U!wv2RwyJYARxc#Yx%wS zVQ_XZR z13`aTGYF?@1~HK}uZn%+c+@)%^s0u~$DOX#ylboX_f3y09D{}YKCQbfj>p&46!X>D zzASIbk3Je)V8*hPeV?Bm9jHx+n?w603cRGKwFCIUk({nQ!0&5u_;@g^uLbscy)J)N z8~uF!MW=l&GaR+H{@{E(KgTdSklR4Cm$S*sZ|47Z@%FD*fSVtpyB~_T&lZ#7qmP

`Sp6cwYu1C+FW11x|~%nUsZEy@VuOz|FG5I>+!5CChe`zTGy(z zu46&Bado|ZdROeX6^ADe-8Zwj9H)P?$s<`hdmBr0M}seM2Rnnu#p8iq3_D0Wx# zFc@3q55UosZ14ML3z@UI#}%TluLTqhuwQWF{Sgy8(tTB&HB-ew(nlbSsx(b{d?u(rKbO7#*FS&#Y;k!d5Sv%BrjG|7ef!yq7k~Ta&tLQxsZiv_Uq65T z^+>3=ThsYP`~TgXjGfv4p>-erZ=U|48?+BR zdY%bh3~*Qo)_(L+&xU&X#n&&MeevQ>dwIFO*ad&Mej-_0KZiu& ztq~TgJQ+p8Sa{t8kpMaAzM+R*NeX&}Ke%oSCrk9H42x z6t;+K_3@{J5o^D?t}3#uY(VHeS;K8Weph^d%pwpCEaoH#&pyU{rh-y0(JxWvNYHg& z4L|<$qxq}#)v4*DCC7j8jk|O89{&zWN8B&z zFqPW!j`Ew@@#^g@J2R#4+nEpti(B@DqWA5_B&@z=Pp0&JJDZH>7lk1C zEmw=B5BK$n;AHoC^K7feD+r8!xx>wLaGTSugSA^bBQ7paZ+E~wSznC>1Ut@39nfQJ zWfuGAIrw`$2MvELK7KNGrmN!h*}v4Q|M%|h&?U9oWANpRZ)InEY<7nHdh*Hmo=v^@ zqSexiFYe!vaA>WTlT`*d9I({XE`j=TGGd}yEc zZPZ!sMh!iIx-?nq*M6!X`pOxMJjiHm zon!fPQB8lL9+j4-HEn6SZKtNsWBM$$e^HZenGZ-Nk%v zg_Uf&n%GI-Aa}VOY3{h3UCd7|XOl@;Y?5aiyK+?sQ~pxF9o4J5v9o_%BWmLSn9DCu z(O`dvxT{ZN!_`!as}m<|u{k>#pP=>1EQ;fS8FIFO%VS7D>(tx-$tTt1Q$Rr08<0Kw zIF|XI9M$79MELDS7i^C%y#46pepyd-<=dk(&_B3Jd-wJJJss`Y(_6cA_YNHm%*Fgj z))~bV@%7mt{3myt)Zp3^n|psY)Was-v!&h}#kMsx+n?>$60CYDJF?2= zP}p$-x3qsvQ=3PAH5Br(=X2+Fs_JVK=UrQ8Va~j#M~3qIqZ~EIz^CzSzCIdsFQ$(^ zYM0WpZ?nv3cSF4E_O)UPsEx?3W54Pb01i)%?pV#}F%FLR=bzg}CUf*$aP=K_yS7!c=98HVY&I*SKkh-tT zAEbQ;9XRLX`FtUSVBs)${3Fa~=S9~RVs}p|PO|Es;Hmed=tbP>xIM=c^V1$}`!8O| znT;B7FgV>I;ueleFJ|wwdXmc>{Mdi4#82qz#2mhz(Q*(Yo`U_~`DtWVsK1Q;I?}VN zzmR?#5xM$H@Y85EpAdLpib48jhr zyLgE{y2?!DZ(ESQ6&CeSHZ?WXPe_5bsSIs%WKrh%;PH|FxKels&g&wb4dj0uS;-~Q z?5DveY^+oK@!*g6D8d+-E;_Um4l3K@py{OBLA#|^GlM$ zv|;@H=_Zd~A8i~z2}4=a-6I(98iAFh+;0d54)^KU@SgYUR~P1%-KrS^zJDtFd#rcs+YPqw!vUp@s8yaqYYr&xPn-IB*4jDrK)$ z3n)Hy1kbRFx`4xzK8vzu!FSc89(KN<c2v>I6py)l2kn7w{`v^~%f^xUI?GZ=n9`U$Mu$zXh?u8soKPyT1Um=E3$ zPhYJTZ(v+B6T%ir6Yb8p7QfvmbP2 zYzt6yJs6Eg7C3*UrvBU2;zBOu^%qKP>sS3`jf7gStf|n(F}|xcn)DbHg4NV@HGWls zdj%OttEI^&LMAS%artk)=XEU!u2vVd#d*S{Uww% zJ<&N024?JoK{G^>qbz;p&99=2J%KivYYrD@;a(Y&O6mM?a#Y1?Xd|7rE5VIF%w z;u_Fq9SqsgX316EZPc{fK@)V)=o;*FO>?ZDL+z3y9Tk5=d;D%2C7n3)1q_phJONJ? zFLB6x^Xh+u@~VaO)^$YNgJa0#tR9d-+0odra3hEt1LtqR@Ra^vufIU9JL0UR4`+n19W zFD20a?a$-MN){dGLIN5ECyED4hN8JcQ-JZ>xjRq>eI2s^4)z$dCSPgij%1$%{!1ydZ z9X~nCPsc(52-i6RNNQ+IW*4(csPUu0NB@FsU%{y~B-^|xz%7sMJse4?uNKupN?h=d zDS{u*7K_znHU~XP(qnuUq1WV4ug@4%aaDhRp%g}YlmARpKAH*-HTBpXbU#&#i;J>& zF}s*^=r4*2Kq?xHmFL#DrHnTkyen3VjmA;=7+_g6RpnXX!A37yjjoFGvA`c6pDEKO zGyL(*Y*I8RC_m&dwFvcUF?rjIkwnP%qxs^^UzA4Sfha$pkAFPzM%?PnaVY2P`ptig zj&a9VD{9QYP?-^y4hMsfio%TzzFeP=uZqD5e=G+ltx+9;*(k<8obsDz%J}AQVE%^Y zZ)E<)=5J#Drsi*E{^oTb1nA9?j;7t!aZ_Ybbw}~}`1}W=wrTAP0qIExJG3#qBtQeXR^xUInb)fBQjx#CWY^1)+x7)GX`&#;3bb56C zv;O%i&Hl}6Y`LMGWpBx+yY7|-mo_JlHs2d6rac;!LG+JDp?})nnGZRQ*WZ8L@%s9e zGXHX}6s|8l6UPq2Q09!XK()h#8??|v;ux3mGbJP5k2>hr(^zk{en_CL&wiY(KY#ll z_<6L|0{ncX%<)(X^^J8JKnOS zfBT}rX3;&)?zZBQ`he{mWk(O*czNy~Ymc|*?$LHyzb!=Xut>!tAqoz*+bcNw*3?)# zlZ6BM_9fyh6zfN_(d>Uk_{9JDXFqvjfByWl>py8-+RkA3z|Nh^>oq0opZZi8Jn<7p z$lB@Rx^hScVl=mg$)>dA87tYo?(8PNxg~EqyV_g+c0TUE+?L-3iFMaK^p*p-hxc^1 z+m0J`zf!iZhLZ$N4;x4>e~~; z_x~SzZ=>BdjwFn}ip-g@NsE#t|8ysm86C$?(w^ybd}8#@;hw;CmdR&#wc+DvyAw z@IubO%a)bu1F2p5@d(y&Jcp%%5c(^E2$In)Ud3fVzHWb1V}CLaCtjF-C3(crrT=vx zE-BjJ*AU2!hok#-K(4&-E3x2rZZj`LP0v@XnCtj52lE_^=&2BF79;T>0O@V#xj;Y= zm;v#p^Vt6?I82my288>?2u(%-1*9~5lC&a#heG{TdC1pQzx=xDU_SftCCKWdTO^#X=c%|^eHCXV2)7C6afAbI5s zWce0OLk5m-$A@irGGWdd*~1ewV7&8U|M8JZlrx6rU-I%_^73Eu@?Y}uH4p z`7d$#KS5ls6Lr60p_OFauUYl~KM;16Q_0{Ro=OJq4nMHd34R^D8HD4(Plto>8vnc- zq~3pQaCUGqNbl3Z*{^4R3D%FUy}G=lK5Ye_+OIvUy}G=lK5Xr=l=jX{4YuSFG;(hq;1@K@iYi)bkM`b!no6< zq-5N(RBo5bE)(3PqDv)r?xQVWesxCaRXTr4Cgo!EB&!ogcZO1Qo?OX@@)E$-!jwI7R{Q=HW-h&o0GfOt@HBj3a8f|=Sk4DI*HPDzl$(CBa@GEhWmxF&i z;bmW&`L-A@gE=0__DVuBduy^SJjb#*%uyCHY0sT$1oG&N&rnq`LnD1(J?a<^|K*y@v#_xeT4?f zs@S0vrB%SQa~x~wzd>oDeC5#+Vj-V0%1C5fvk4B%3+qwfr|L>1M1DgwniQ`{3HLp}PYpR5*nYP># z(LM;fe$7%MX>+v&wX_Oz)KGFPq}@1>{o}(s$zFdS8RaX(8cG#LZ0Fz`hEtKVbdRjr zr5M{>W(oh?hAX@BrM&G@n9E{v4+9!Nn;?;j^Uzo7+6MV0B z!yP16HE-DsCa-w*&R8Tn$=1&$8zL;tH(32hEeFTPs{y`nfMt}1C)u0%Z7>PaMeTtT z3rbsC%~jEIu=zwRh1#G?r7HyX-Y4;4G^NAB&&PF$Tm^BGHZ3e+JYvnf5w{l=waPWJ zw#+rQLX<9O5#S?irmjBP_Z;l++IN^UaW1-(quIg}J1wG)}KyXLgFoG?}Cps(s2)|f=)s*FcR$!`lNjntqPtfTAwCJb_aQ1&)qKiU@3(MQe)K0_F zpyzjrO$j5L_pB-#t7T zy4GOqG%DXfuh(o~xe~8DwBl;F>EQD6<>AdTnm4iH5I;UP@96q^?VvRRMTC(9s#59# zX7V}vI`(Ea!MK0+^x3ou-+Pv$dgX;ov*m>~n~hUfgtcWp+d|%Ibh5~GVwqTaqQ5k_ zn)>$!a9FzAqSHRV;N}!oQ*{NtuIQy?MO1UFgbe`4tG@mUsL7XcY~9{QVUR{3ZD?-m za%JdR&wkGfG6dyvro~?OHw4vhf@oQRRnl0U)LkN}!vJVNm%k~0RV(w7FWx7=E>#i z2vt^EWq|5;2N`p-jKwS_gPi)|w9EBsBvj`a&B({erOgmduzK{Iohw}a#P%isHwad^ z&TRyk`HP$caoq@iHronhWj9xT@wB?N*#vfOpP}XClKDmrAJ0owaB)4DKKJKR-xX;J zqU2bZlo62ZvM#&s(`i0RCUHzt#P;m30mxmu*z&E<{Q|Zu*gTj@XE`v*!c7JAuo|2P z3CuD{2_^IGeJq4N!_YG@{2Be8L1@~LW$%=r95jRC$xwEGOHf`ngK{ZD*(*UgYzAel z?~!Hk>s@(Pcz_Vh7t_M8cYjxJ|1{HA7-ji7>7ZHV18wEk%__gvRz7T2IUmZW%=jZW ze^LnaEpSNfIIES!b-Zi^)r8QM8WIqlA=C|65|i*HCXolFsTI!LGB4 z797o7@asLp)wLts9qyB=;njW`WAMmV#=vj8YB0yEsdtUB97Pm%7G{zKui{sbqMHOd zd)uL2?uuAflUEe*3jU#njgrXhS6lc@d8US-NNTM zE6p-ga4PFJyW17Ya|w)io3s)typmH3rx{A5F_+-bGpCi1!5U6Age7Q{uHuG`%rR6%84G%a0!39r1KQx9tu)C#61I-|X3AelpTmP2hw zgC%9Z#x`{|B9yB-OCdHxvqGO`+zzk$xzc_!#4ofT^3 zx}HjE<6)J|`!%X)=UG5&dZ*~Qi+A~J<-7b`KaIMgx}kVjJ`&H@r9007Su+fZ_I#P1 z9y+cl*lSfO%SXXmZ4|r)qu@Pn6som<|8-rwT;9dY)w+1upo^E!>tglQM6IrAc^Aj4 zb#dIFi{s~YQNA~+=T@rbe|;T_EiEP9VU)I%Z*cYCtPZqh9E$fEOGiQsTkSxILbc=Y z6*ni&iU5}lK+fHl_Fr??Qacoy^0lM#CtL+NU(?XCq0`mGd0v zO{5+5eympNu4az@v+u#2RY2ABN4{FC?}WI>D|O;4?**Ne;nj90zi(`C5|XS)idbk( zKUOkKaTpC=*_mV#+K6{Yf63$=BTJkJM%y`|U zu2Y8331fv8PFcLe8j8vrWbYq;ix28`_lPwGW!+#MJXPOSQ?jVEsVS;cN7dq>9^Gq- zDteivz0cK+g{a`tL)fFh!)X;)+H3tmPfKnhs#g}uu;ztmeJSOJxV~udy0*TwdRy8E ziK8FR>dO@`sOn3XZrK_k!S5*>mBpLHMg_C0qGn)`R2r3}*9=Xjm)&T8G%9=Lh4tkm zDmNcY(Mcs`r*ZD)vY73w> z*KBM}#9apTn6$CPYG(<5;Ns4r!fs?^v$nbckJ5hlEF(eaJ-rpq-wd+ z3?A008P6Jvi?!ObjK)}`jBvHd$P(ns58!p+>nt#ujZOwZKi(Av6b(lnYir@^Eg+gf zg}Pdp)kX^qS2e4zg{`+cXa*PRsxa$rwi}`;yGhVTsak-r`6;gL2)dSrqfc0X38b@C0wQi%U;3_~bBeuR! z)LKOI)*T4dtu$(3Lqk%JlAl3Y*?frFPp0y;963n+7ztg8N?%_a{rDMS1Vrc$i@x)e z9$U7q8Ou3^yc0RXW8QKx3z`b9%$qcw(bhc=gRzGN>EH&kxi|IWv~mPr&yz*B+pQYA zLm6Vyf=#1;#ohQ#7cJI+-I`5(FY#f3gR}*bLo4>vc+o{CTIjtBu~V)Hu;1(s!ce{a zuE~l7)~z-35Z5&kT(VsLSYNL!ULi`<)X)kBHRb(g#dJGGP4SEg)t6B@cum3Q4ABE3awB)4|JteDXGc|)p%$trH-l#6BTr^my~MN8Yuxn69I}r zXsS1VD!iLEF1|;osOvhsuTxD0#l`n(RQh-GqqLK&^c0F zt)50yR^sKbN;(}(u{ev4qn1|`EuumxB1?IHiRlG-1%MQgrJ{aOR9C9&qp?&#su9gI z=A#Ser2$u|$teNKLUEO$)aq&kAT=UaH5=0?V^%l&=50PSYqG3yS>421?2XM@^fWE* zYQSAK19zzbx2FL&ZU(NbCb6s%JrqK`m7!JZMKZQfk4{_FtGZg}DDO;0X3EbW=FkDlO5Bb!3LgCS~Q#bVQ zTCbMEJz}<7av4@2$>RDHGOl<`A2kNe68NZpND$`Y zaO|JW$%zOlYw+Oi0R!CfyJ?hq)6IUbr*ozVdh6@n zz6&Jw_-Inpi_tAi9h_NR?TGvr!e~WTEo8eLYN>TQPtw+<5C5Ou`F_~yC8U^o`7&v( zt>Mt3_c+;))iN2RDeBEo{`I%kTfXNp2k{xgUfM!sTH5NjZg014gRn7wwhw<6vcG?O zTqVKBsVsEaq|o@!>h%GLOy92Kx)sv^-QGT}h5x;!;IBTsw0K{_|5ij<96Vd1#S-RX zv^oASUy9#LyHPls{mDI{)>@*uZ`}>)jQS_{16m4h=eN8+tWj-m6C|2!u_nu%K={w;2s;*G$S;t^W#sb!U|qZq zz!F}bwuusblOB8sr;C<1o!xlh{ML_yacg`7W7SH07&3Hv+qzt|2Cb_oMz-LG30*$r z&q)aXC#L&uv1k&0+ZbKP(R@Y$eY_<35hS#3?B7P8eNz2&a6w*wdMGE_jmrC64C95- zX`dpn8r*-e9+EeiG;cO5ysS;tdmzIWir34NALc1i3uIkWq$hcP@JKIREyC&Kg!w-{ zWXDI8SK-hT+JPNgUs5-_o=YDe(*XrMgEQf+Y4L*tY8lqog?ry2D4E9j z-!3Rn+ow>z_yh8PXPzH%XZGAO4m=8-R3#KuLZ}jIs_>wuN^n$Tiyw)H{O=hIk!!T! ze1k_Ex_9{b<1rAs1#|!mVhkw%4bFo9*xo@G>|zuw?RcF+gJD`4HS3FZjO37?tS2y@ zX6jY}EDyobQL7z-Q9{t4ITE684MswWAXrCcQZeSMd#$X0XY-mjHs5P&iJ85NS?dz;+O{^$hhMmEs z2w1vt`N+zD2H~}0e9&cv43fiETf@T+aE*$x>{5GK&{0_vbSSKaa9WZim=OF?GWNo| z;3{xCeVbB~`DHO#7Jda1sj`4Xcmt7bs%xN_ zNi%bQa6&0$9iR)3B(3_aD04_$IgO$mzkg~1GAp`d)=!~uNO$*~VAMX<1#8fY7f>Py zVLQz>Qq-nGc{m6#-qY`0Kx43XVH>|d8zMlvlyp@L%PtJgM1c`><<5@_`aQ#-$h4Re zx=IXMG&ISix3CMN^yBgAnT4V>Gt*)b*0Y>{LC{U2IL-MF5h0hkvy+YAJw1N+)4`9{ zewLJqq+zG;lncJn6zn^_r##Gi>;~EXJ%9sWJcv6T7VkZcUl}(0nzU$2+>Os5`vNze zcD!kD9XhwcWHR+PSh?UlzUZEw9v`tvTjX22P#;Nw*KMIz+K&fXkOKuKVNRg_p$A)k zf!0220?HeG!)3sZPe&&oKb*ZeJbQD5!3T<7!g)wa-iKFed*X`)SZ&dv!rcI(ZNYyX z5Cv|%c(KunLJD*0Zio;Buxr8cH$NFhI~%23+QUnxPoFl7TmalKHtda0pNtI@Ibd($ zqoHDoI&h9A!$)8zp^P5Nji*)O9V3l@iqoFF!a>yXl=bb&hnYf0vvtB^N3syaM!U=y z;oQZOi>#5Kf(Ks>fnSb17sgdIo?|HDbPaEt015{LhiEwBO*G72&+64(>w|KCQRYr8 z5Ox(4V&PwwasDzx*E9Y)c3!j9H{skOgl>t~n!CO4^mi`5#1RlAqc;5zT{Q}SPfmiu z^M>h9*!S2e#^FK^$~dbI;*(BTVKN6D_(=R2Pu=qiTaY?eJ|x%Zfqns*gkHy%^P zT$yl&t`#@CO{Or%?XSUv8d9!Zb7Y8-9z;eU;AGwzXOR3!3$g5i*}VTI9s z3Ej9>6cQb*$X0?}*?dl)DgE?>^aDRc1CjtFrIrs}6aNa&4t^$x04nGHMVC8{A?8|) z(ZTlt47D)=5krkhPb-$J9Z+C4cL8f0~K7`CnlYLwhh`|iTUQ) zbo;^*O)6?rQEQ|1iZ`T2i0*F~117d<`ZO@ZN8D=PLMI4k%XPD{U?PLTH#{IXz6Y}n zSN|j;NbqtWj=nvyU-OvMpF+M(tJw7byD)EZz=q!p*WLf?8>00lT!z&agN6xJ^Q@g> zAzOO26Wj{I**xvwWy~FaUZH)n3AaPHHwgFn%zmIw2`6-eu-&#iUC3~?_<4BI4JK_A z&2$-GHS%SEoDa}c$VNKvz43?BUk%X)3tZFWU!y#woQhi2GmEtK3miw|6s>Ho;^>x1 za=c<6)oie3&HOa*q2cUEzy1h+ZZFYxeV5Xb+X(n{ z;G;UxaK587Qb#(*a5$9knvIK(*xCsSVL1SQgiR0rUjfpE%>O1~>pjxr6Z` zF@$zjpb+V*T#FbhwYyQD-2oXRE3yS;#5a`@6>frw52J@OMCrN;c{Hsi*d##KI&{1V zh?gzVUJDw;l9~w~dLm}m5{Vi0ZaDq8Ne?+fd$Gk&a5+=0+>uy)w+$cKL_Dn9u5W%aHAs z`&)#bAa0r%M3Si)G?;2o$_Tp!wMH40=d<^`IoH#e8gs1)u{EOQ2J3?>eQ0{gb zl@OOJ6_pT^w|ypTD)TXrVjQKMhqVn>#1fnOMl0igYb_vTpwt_2;&3-$Q$P_&e^CIL zcmpP>i}Eefb>EzfPR|ZTsG1VoTCe639w+fT`Ft(+O;V$yuFG$uYHI`g_6ev>r^HHp zFCO2N6j_#L_M3cXJIIqF?r?HZWF58>vQ5$VXZQ!k0RBx6M> zlP!dQWds+nI{n)1mzt22yOle19fnZ9*a#kz3*3vn>D3-~g?bK-VIb|86(@h>CWSO5 zvhW}m^m_wO9w-k6>WYlYaiF}5?ptvypGH4McYb^bVhjj6M(C%&F#j;tTq?f4PJc+% zW_VM)n)dOoK2t}h4b{8u42QOiv349BHH zgBa#HOGL#s9*ro}H~JhHpg|K_DQOf^u#KUD<}p(#v% zJ8Zo1&+R)rG*Gg$n~tyxdn1m7bo;@MX;jXXOvUIHn2PR8MTcvB$E!kHn0o=k7VWeR zviYJE4$fv~XL+-hW1LDo$?Co;^&kl z?*C4?zi(M&wzJmPX+~QfN>Q-s9-p8M9CWE=-rwJMrT;9t57OKYie*~99n3BUy_$0VI1^!_Pou{?wMb!gEd6%|Tr6i!@r082C|78wM%LR}W#KI7$o!0Y3M zDTttwLZQKfr+b-Twm4#xOdxWM>9qYJ@i`N`Oc zc*4^l>CWcKjXAcSp4iq9h_WN7jT@em+HW1d`_`sC)(LG{v+4x)_;%ud#5UhCoW$m= z$?qPnWgQ^u1 z8dnYzcF{HYF#7nYJz(y;sd6h{P(7r$TUw=tMiW07$HA;<2C!PA<+k`_mLvy78dWb! zxdzr!>by=vW^u{PPjm-=p_H53{)7S`mVm9sQ-GY3?nH)Dp-oXiN&1u`#N%W`~2^*cZ)ukwcVp9>6$cY6LbWhldaf zOT4}CELWE|l;=DTtn28KdxoV;&lQ*wEf~_V(4ZV?f{h9-7%QlM46k8WrE$v+%K2yw z7%CEWlBx8t=Llp4Z_;T8rH+to2vrz*>cx-a6|P)tZsNy3)|6`iohZ&8G~ zt%iztv9f$AbK`gg+4AZ{p-Lm*SJi6%2K&@cxg9X{Nn^#c#K?yaqQW^<-dY%3%@(dy zX69frfCh3y#Uwqev88X2@(Hc&_40|nu9|2(NmZY7#eqs^LekK*i=9^FsfE*Vg;7nx z=B8wm^Bkjpn<5a!>ZWRdRxmw#URN?K6*b`Vt;|;Itn>nay-KO|2YSMuDjc$6Rl6*I z+|YVEod=Vj4kcfpQfnI1YZ(`OskHDDgLI4X%NfO3DF}Ufy8z3QOyam1z)$4SO_G9{ zH9+h1&Dq)UPw!4gZx4R_@%6#szeevr9KCT$BQ~FZ;k}4%${^?9#E@_1bD#$&3b>36 zo(BytW}0CqHza}M+x=2>iq)SgM_9Vfu)Y*WzwYvaJG`NH6{EZ0!HXwk$KdwtTknCH zG_YiMFE=JkB~uh;iH$VQH0U{wq+M4EW_o&2UQ)v6^=^D`LQ-2^^Jcf=8qFt-K4kCT z#4-$jmdOr@Lf@pX&akYw9K!k%U9*um!f9ddRD5|aD*Vn(%6UCf;~DC?YQoIXPE&uD zz3=gb(JAf}cvK4~uJJd&hyO=g7znex9zCC8Dbk*p05r7lNd)+bVN0mXI)rHEhYcFv z+4=t9_4lR54Wra};kPshIW9&i?ixeE`hw4Ys*A&zJ+fAYk-xE%OQPYIGSX-h%n$l3 z{qa#(Cydlms-!pr>|;|R#aK1engpL^N)-kvMBy7UNy5482+HO~*ynv#a3-PmE~0q3$rgmQlNZ zfCRApKF|cV)8`FUmD}d!wwILK;pKL+a@^{x$y-`(A6HXmXcjoX(v+Md;k1iqGgIa4 z<$5fmP_43`yW|jUl1~wT4#{{LaA{RyMY9~VIS^)vZ79JQUq)VZpNr|8+NAhanb4Tek$(Q8GDmg`Ao{L*~!aH57W$Tz-k!DtUTK|$?oPp@OK zu=5Ey%iyPhmUtXul-z$lYfAA}y29L@e7P;6Ilc>_C+ZvM0lbE>ffXQ3RbBr~$P2aSR)<`{Bds*-r=W-w37*v{PVz^;tTjDZ!<6 zl)qg``8i2y>9)A#%XIro@HSv4-s^env29A*DLe+TPW^KH_LvTDwoy1H8P$_;aKg`9 za8M!z{w#u7X>GOOwAS*b)95b2q5pS;m%I1Cgpsg>F_muU@f+nv<zP*sx8sP z`2GZ2x%6@K2-)+7G-BO<61IZXefTY!w?H0dRD&OkvDgR__l=hK*$bvPT}snQx3UAA zK)ID|HUM(%9J!N&)6-u*d}Ig;Nw_c!c*HG?0<2!_yD}KqPX-u{^;xHDFhgfbWvrlb zj?}kfcV#>{9VR|7h#+0?)_*?xVRZJ}$s0=@5wWDU3rnr?yf4##v{b!nMRGXFBvZ`5 zi7UG?prwRpiO6|FnslY6j_vH! zu$}EXwo^Po$ZY5IsC9^3xRUc6Gpd!BX$vZip%R<@IT4O-;0kk`WW{1Q}IM3Jx_D*R?PG$w49WEorf37cW$X>6P>{^DRotk z9=XA^wohh%+Qsc7vG@~4FYiMr2Fin`?AXPDdVIvk-fj$^_7wi~FYE}lEHMr*^v?x8 zJ2WFVX-^?7n?=>(&A#^V3nun9!k)kZ z#&;v<1%YJtp?SJN_M`8c-~{E)sNCZt-I?b3-J;SC%(HcxP#&+``AHO_Vd1{UhW)!OA znNL!Gdl*G7jSy3ELH-uT;YZ*H$>|~-S1dPtAR(=^%>-IpEOW7lL(Qnr3H*r(vZVys(iF8sY4r1KmOcKMxYKOW4~&1{dW?p~-}&F4=&y)ThkhuB z#%3`s7@AX8T<}>o`|2{|dy3;Ybtf2GfDhA<_mA=Hs15u?NjZ<~=>_ngAcyIM(zl1k zTZwD3zu0lu38N5BzNTTcqjr4}VF{FfZ4|PLO{g#h+LVlV141If%hr-9zZQ2ycctf%}M;Dm>haw|r~19p$$ zV>p{i3v4j8hQ8ws{dVerV0sosQ;fQzC5_B)*Vx6qc_7n_Xzt6s<9F}dp#?da+X zPH^3OdjV++C2e6pK-z%0c^0wyZ-lvJr9Ev)3^JEEg~nu&zDfai^urY??RSvT#pHV0AUR0H$R3SyC~&N zBm8=4pvBB}?A?O=49UqXK+z3;>_G*XPY?A=@1a-<&Wi-jl_HTf$(Bv!S6mmww`OOFti;U`L?}85REu3-?!xYGrA^LE3K?Rn5|V zhqT{;{C%wNQ9B-gf%gFFARzMyn{XBD0xI0Y4!3~+9-!j8exbMh#=Y(TAK2UNLT|Sl z_jdb#t+!#J{xPH<7wZ2L(*9Yf|1U`U7t{~*qjd$mAV_}w?F5%0h*@8lf6H^^P{@&h z16>T@2RkrB3Oh1GGJI@b44^0iMUWmA^+Zum6!oN{I8Hc!I3X4dMbS_c4SCTg@p=z& z`~6o1w*+x}usMDVw?yEU2;35EkQWC8Y>p$tFA?}90zbJpAYpSn8IFm-F%dW>0!P{# z5y{_v7f8xtYT>co*^S>KcGtp~X{a<0LV89CEQu2zWitw!Vn=BLu(PbAQ_<0>=;%~n z9$`mm60oy>tfP_WXe2rsiQ*INC`|-*mUVO@Iyw;@olr-+AMy6zm5A!2Fc5@1ILqKI zHHfwM9h{X2z7`!sed4}{U9+3~Pn??5&1pN@j6mXWJ0NH08M~XwX3~M|4rXs{TW~Cj zwzk{Tt;r@7O!j-j4jjPnjqkk+@Z08eYr7LcE~PDhAZ-B$CwpYlDYv-t1HdQ%TmrW8 zcM2wetU3`Cqm2t5^M>y6AV6MUT=>uaxqAQ2_d0<_t7BDr1o3)+dsn zUKAm`XbRy4hw!op;bl_@FBydGqR_gnNUbDZs}M4YyT>6E1;OopQwV*60F3fQciSkk zSxjqx%xST325UzHYiAW$J2|Xf4XoW&VD09x_B62eR)Mw0VeRg~nWg}X(j-`Ls!;*) zV-6OhdE1p}hXA~6Qk|2{-mY4CPZ^WDabd=@vm2|tSE#(#r1BoG{9U2)cTFmP$18td zsQi7C%6z%*y(mZG7krhzEP!~afDk8V6^MGC zW?=dSF#XlQaN2vR9;Zk~%3o%KtRvJn^y@d}*Y8797Ny#*sv}W;xjkE!v(&N+rR+j2 z`=FM6P|7~IJS-rfyMMv(b}`f($~;@$RH@bFgKJ5H!?Z6(EUvC4dVB;6ep| zxR3$EO1zbs%0W0l_s*bs%2Wf{>_J10?ef&!T6# z#Yfx}?K$ zJ;5I(Y1#-$N_L4Iy1a~8>~nY_J1hY4I^!JF2QZt{U6p{}mrjEmPOE=7EQ&{DdlH;d!q+iPp7 z2It@YV{u+o;{5x6EY1&=I3F+Db>!10KK(3%_-A7fzg2PAAZ67 z!?(~O+OnB=db+Ue3EI!B74;vU`-L$%nZe4|DvBKoS||?k;2iydUp9oo5FMGV6q-Hd z06-j*e-y+xGeyaNO|ay(j73N_&Qn04kRVz65Z701Z6Mz*ly^$`T{Z${A;T_Iv@%go zE+`xKrkP1E3(S(_uu<3%4`8_4#!Td)V6O7JfUp)$DBv94cyS3>0yN+!r#{)rGw|#g zA^Ai5NO5-hY6b{dK}gwdkL92};YVoBkI#Zz|9vo>28r8$dn)$81^PtyO!!PT5z%O! z9e>A`(w#N5S&@Wy>aHxbQj_RUAVc}qyJz@tVh2*^83NHfLj^81EH{BRv7(jCy{_6+ zmXEXFzbLd<$So{_B5Ya&+*@#7)2Ev0E2UlJj4B>5k^4&HS&xVZOX} zo7wJ5`T2Z#Rt2MRzuXc#IPv3?;NG7)+dcj+{%97Q!bv;`uVKmC3*ael$>BDdyj4fO zeLIcNcp5_oyajmZ?Bxk6d-u<-ET#aF@twXc##H=fPZXl5$L=aF{Ra$eg|VKe{waHT z2wmuZ_P6&C6plD>(;wO6rfnz|N7LzRZ~Vud7bAD;+t+b0alTx^u$-dr0LS>-!6E)1 zz)a)l4_~ByPyaJ)G}Qkkm|##PJAt8{(K8H$lnpIuCHlZfMVx|D<~1V$3@)P>7&CC~ z00y17D>-9MR1~i0e}?e%F+uQGQJ9_v4*nROD+!FkS_A7u*t~c`8Sf_e~S^MHounLTwIz z7GWXSzq6h!rk`Q}Y__z=6xO_Qu!=*aE3RTmo2tOfFExttX11J9NkllotrF%IA!KV? zAx(vNIXxj5X#<%|uuTTAz?W2Mgz?ocX;#|tZ7$q6TH&S=NgO}R_JwF9@A&KMy?t$l zkWJ{>nv{;n$HxqIwM-*sgQz2el(nih2PXZB1!MJeU@RH*1(#=yMK zqPH=ytv`3bB?(DC?79VjZ&SsDsEEUA^S#@%NVke$`G58j*Jl#N#K*Y7DHr#D(b0=p zqPzsSeDQ4^Np}PJSkWzR-0SO%VXUwBK{DXXXX1Z`KGA0X5f>tz{wwl8K+9v&=cpsq z9HeO+T+UPSMg<&(qHZ)P&B6#8;?@E7r0XE`ro^V!*GYc5nnp0aY z%V$0CL=V(V4ANfNFFtH?$GqhoyWxOW>zP%gWgyBD`7zSFVtbeAmrj6`w zLBw=s#h3lCB-j&NOt;h@W(nPBrpJaJIcf3H?Z{?c5q)@1{gj{3Sd!X*D08wP9m=Z| z+^)Q0?NC1D1@aH3>DDqg(tdNx)B`d`BYGUq${Dg)E6<~I21Yoo)nz$$+8eWOj3$CiqQyR5X1-&<%gZ1 zqgTzKroL05oUyr{j}u*ZO1w7ldm!k z#q9`JWnp7uM^>HKj0WFp+P;cSHzOT5A#Hu9&Y*faC175sQmM6nA9DHPiSrNKI8CcY z3+CDME?44=Ha*?;I%d8*leux)anpa);5Lw-%jHqnyM+_xka|n5=u9*1_|{gbla5qm z%J!yCMbRf_JMWj+xt*wtX6k+cw&?WisehF^=*AOI1*p9XfIMh-wRwPFk;pcsCp&V} z4o73Nh=4s&q%yyM<5p0e(6#o&Jz^{<2$2L8QAQo4|t*eAy1&KI5U{fDl`Ali4wgK@{zgTu-rH!#Q6Kp>H6STLei$L;Q6 zSLkRKnIpR=I!3>8;t(A&+4x6^&rp04D9+vfU@kgURMQORV#l4i5>d`G>f5TQs7HGy z&{k=NccN#1&!kR>*`&0JJ^;1zW)x)-v{Y<@0r*%?oEc!1a*}RAfwaC}N)pO=F{-y9 z#oX>!6&u`&VZCxoWzKIe>>GKsC*~E~p)9M@-5aPRdet3A(gvUCUyBn|T@wl381tpmtvYsV^bctePxU`yXu)b+=h48x4Nrs#hpteccGrIWf#~A-!rn{M*u1NUNVpUGnBwU{Jmpi-Mr3;s54Nd0U?c4$^-hQ+q()=|0a8W1=p-ZK;DZR zVOe0jN(Z!*CKDQQ);rf!Zjw6EuM^9v+NSL@ciB!ppiOoO&FLv;&23PzeW$CMZKP;_ zaQjdxo;(28Wn@Fc+oZXNO>Kkrb~fyths`rCTj1uDq~7f;gNeF%t;i-2K6cATA3eo8 z;*6uu1{(P)@$t|;vbhL}jHrOq`ub@9`0-Jbe!M?I1C}FKoM{1qedy{2!#uL=BUeTL zkfU$w24d7cYHvHE&QWLEUb5VEqnJ&9^r4;0xSegwQL{Qnawf{aIah`gJ@zB(f~s6s zEMWNEmA~Kb4UL}R7#OiAbDwC^+4F~J9w)&0+Xlu{Vrjr+=c!*z1)7cM`i1Uar0bLv zesYzBPdC(V_+%Qe5t9R=iDb@rKa1itArk9`|D)!9!cEvD+;@aAc>(IO?WyCL{V$D0P% zp#uln!N#k7BE>u^&a2mPbO)k;sI$LCIj<<34+i&P;UdIO(L%r1`v*V)oI>W2$=yKg zJ3)9AVS0-3#ahv&lw0N`yY@qjd=E{%CP6Wy@6t|`$- zZUH&;ojlzd%7yymPgR;i7KW=b>RTEIz+E_T>Tj0_%4R)q~Dj=Y1HYOj8%m<f_ET{c$pHlalw~9ryiKkv;Z;X3Y*F~a5*R6tQ>nNdK~UL$#~Svrgn3mL8S(@D zhBx5Piphp!MHZoksaiIM4BwT*9vkOxPEU5Xdlys&HR>{FwPgwc{_D*rBq$!tCqcwD z@znEcbjSH4j?lzi>*qqqrO$$@p@rsW7piyJW2_I!7(_VS4?(c_+`Xck(r~=s5xrAL zLpjJb5>$WKbE)coJHQjAk?u8o@bcaMrVmxPXLWOKWuI7Y;$tidreT3n%=&-;GCezr zXDlO{71P_@Ua!CDS%r9h=^=AA{)L+q#vxME>v3GktyWcCpI7ML# zM%fbqo72Zfeh;1e62QsN*vAK5DQc8<4%`{Vgj3j5=vSt$4MA?u5Gl5!d zXqHRfXVJ_R-#>75vIgIeegc$}h{%5uU_KT8Qvx)2$S6;dx7E0+M5;Wl3olKN3@Bjm zN&e7~9lsSoQUfMFSZlrO;mXHHut&$^TeVeXx@@^Bub`A>0C;#jriOj8)94xmlDDvu zVR(E$EEx%Z6oz;(iN<7V-@VG}@C83KvpoMkNOPEY{oh5=)7{4452BFx;MIjifv(;z ze&uuND|3nN-)HmmEr3h>iDG1)9LqUqnMp-oPjL~{7VSUT4}KgS+y_bRkf&JU^@8rF zV2*p)kkX?M#fYJDviNIB>3QRj-aRtcIEAu*e`i2{8^G32{Zu^IsceRGZvQimFN@m2 zI4>SBDcIY;qw9`%wkXj#_N)xO)c-mNkX}#QeNNkLSgrUp6S{RBNyAw*yi!``nk&DJ z#+&Li)YemR==WMbZueRz3=auZEsSv##S>(@A{Hj~d4SI11;9Q5%nJ^RixYpphdxvf zZs8Sw3zNmU?EHtnz=u4-3q6QWkka*mQ^!DH%_;1hNBM{qreh0q&&aTZX_OfDqRuRAZSRX3&0SNqm z+p~Az0BQi+bf`&esgDv$kF~Rd1$xwqz1M^Pr^mSGjo@Mh1cU(gQ0(z{uqhzh!8xvs zUJp+5__xphZu7r8>~Ejv_j!Jw=l6O3HqYPY`P)2yd&juYxM9e{`R2m3cb;BwXOn?j zUa$jkoe2_k}LCdK5tV%Wx|U1!)=PA&TTKGw*p#afNejJ`j}%%{&m`GK9)Qr(z^Sw7!%}udkQWco?Q@5|@p?z4-3xyBFUXHVTx+ z->$yfh5s|`>lhEN@Du;fQ0D7@<2)oQZ)i|DS`O9m#=`q9!`r9P?*VDsn?xG8~uBpGuv0uqly zRGYiy9t`_i7!JVc%UAv=O4rnIum+1T;2JPP2HAKUKSWc!x9|pR?H=(3Wg1=N6FlN) z(&{4Rv3?nLAh?iJnwJFXoV1Y5-io^V;sN8D*{kMnvaLwvkOYrS(LNM@u?TgZ_yw}qE|#_oC$O17s_KLaUOh_AB}~@ z8p(4c&R7ZX!CBA_y>Z6Z*!L8dv_DR%>X3G|M|x}oQkYLk=!EGDasCP)VHB`KiVbzV zi$MslQ6+3Qs&m^XyJh|%9{6dOAj-yXuY2wptTE}^IttJ9i=KQU?yBrFh4x^x zPG7q<2S*e?xfBcTg11E}dH7n8!eUcgnG2YW=1hAxIngXBGH=zf84No)R@ycR=5$Jl z&~>;Fnj+t{x1j0$rrZWw&T~1FZLR!3k0Qob)DvF29me)2X%-iv|AGH^kVlQho)YL7(WhIMlM&wUnQ`2 zD2iG@WJ*i-J)omX#kinDvfFryz0tK4$P!y@uJUDmm$0h=yu)AQFZ5ReW2Up9Y;SML`!?{I~F*R>jK= zJ3PeE^!;-zRMmHj5z*3V#Vz}?k4eeYhv2)K+ufn_PuT?3n&m-CU|0!uI_JmRKFAGuJ}#1h5bjNG28M{wpoYouXkBzn(5N9ayk{ot*~h z^$9OPg?yrYqGFZmxL1qWv+((_0ylSsWwDY>zO3x`>3240$-gYkXe9@5aj9urEp@C( zNXg5ZqFmJnhjH`G4(^d)lIAW8szmmo>?$bL`W4g>U z@-K!S(84hDAv>x$MqR+~=Ct=V{*vxzhjNk+NO|J9@PVfrigKEjNX;|`0fm&V@4`Cb zR6tf_?Nyrjdg8Srr$0rTpo^oWF?GM-#bJ5m1K$PDydgv{;=0c~s!X=1`ibL}dBaRn zJ@_e>S8ihet!R7R@rb(PDu%OPK(cpbynIU@bzG&2ELadZDe>7AH!S>*0~RN-cV~lN zPSq)ma)-;ns+h8>8)s>eD>yD>;Crd8CcvTzoV|u=@zqEx+bKFQgSPa79TYm% zSb%%)w6eVORqnOLp%eS3&!sKlg57_Mm8T7wTI{w9L{9{HZg=OM-B%VY^m8~VP6Fy> zXZydghL|*rX~#Xsfvg}yI&>9YV-ZSX=@Qi%I7Ljtw+^xfVlzBQY{YM5tHnmp{VY zE>m>?%Vl15V434V#9ktg}Rk zONYxTW@65Az#ttf6T7&z8!uZW*;fJMRz;CR%5xr>>!zZX*w!O2?wkRqq}wj7E+=U1 zlH5J;NyQHj(kzdNJl&|HSE21Sf$2gs?b1K{vpZ`VFi|}wZS$YMU3x!d&BIG&`0#`v zA&ChXQwKps3Dd&`cf}5E07)2tYU2xvpTL0KPeL~QVmwY@K>^E*AMrqSQDWW;|SO#1WRi2o1{A+p>}L_&}!f;*7c_)LdsGA5$* zckQJI^d5$*ea(N3mXHPpOHSdBtL{00T;r@dBAF8&%@fv{u3}jNQd+%8B0+41S0`)( zDP>~ii}t$Vcx?Z{71IB=3VTpn>o;3m9E9R(XR%#$-nYyuS^FP5BH}{C79Qu{YWxF@ zgYxb}(WDPstubijyJs^B0p&XoIa)7bl^E9#AV#p0%2il<{*F~t0G5qq*KS<0JhmoA zVAalt8~5OM|Ao2uo6&mVWl#@n08VD%2@3jQQmUx=TDV#5DOZEe9XHUv}1L7LpoBzf6r|{D$&|ot1g*F+5T_6Vl z^A7H`?XR24?=ysid0E&p7K?cQk_lmVr4}BpJ%W5sRQC@1!R0Nh^f8P+wuqAvoIc(M z`Ka2dR33>ifol4sh3QytE(wz-x{sTd5lbv~H3rm5 z%_DEQy^EK6sX4DHJ&-vIJ``{1KbwCXFIp|!DxXDXRF&WY9-sx|jNvJPWVux)ohrj?p!=KK?zshy zo3sekm!}Rk>7`#cB&pLkHNUwFp8+T9t$;~U%0?sVm}YcYwD@0b!{B))Gq{==X>ww_QXJILOIZ5lA1 zU|d!|)%h!84n0RzN{yOLxn)J%9m+{2@~zUhmW!S5lS6}Q2>r9}@3>}*`d7JwUgS@q z>7uh?tW6&Px)AkzbifHWdJz}!+SJ~1#!6n?>5R?pt|lQDfBWtjHeKgSd_w|5YlAtM z(a2C46_z78rLSLOPn$UID=2j$_8+1V)Ljv5|6u;9Gxv*bm=Ie98M6&O+({EQ{;v{Q z^@c}63!~4=_X8rtqdJpS-&xV)o!Pv$&cOMP4ksVk15HY0!I0s1U;7!LR}O9!!<#=T z(8cv=Al&|f%6%_@=`Bq@-5&e=e9T+&=etk@ImQd}4x2AKK47@%$x=5NgEZ;PYLo+Z z3eVOKyT8H5-HZ6hRPn~Cdbcm+N2+iB3nPdC+@2>HaU6pJlc%Rs!av$5@1|i>rG96F zAWvL$`0~cN^#nWX9WM%)Ga}_B2$^GBCvSCh#fJ# zph)_it?Es`k<($;?aS}Y@A2{CZtk05({KElWRr1n8M)_Cdw*wqubS%9RBbfz(PVbk z*ir+|x9AmaIwLYCK=p?7JmOx;j$DFCBY6|17pRZW!@53yWbO%cJCoo|N+UXM41eDP zg)6>SwQA)}Zbn*Sg)6}W0jiU;Vt9iW=`6;?T}Hl-WkoobK^aHkA+}k4QBbk5!#LXG z5Ca8&CaZZTXBk~1Y)!Z<=}~hZV^%|AoQpcIqc67wTg_yu@^u5tRqOgk;pP_QMxkpBf7C}tj5?P-q-WSKEFCTBaXTh4)jz-^nug_n{)jfBe zkGTT&pBP@Q{k$o10~2rJ6q#;e5w+Wy$4hrLo#uKd&^u-X{!UXJ{!}B$d~;1I+reTN zV0BKf=yg>@oi_K~H?Wn@7ReC>KYzXrV5rb-E4{acGxY%2AeiMh`KrF(BYc$N^Ct}z z|GBD$bfTulF;V;JQCmBC5WUUV!Ulti*l_P=g>VX zC0yzOp$0GbDryg;bJ=e+?XxLJP3@%VW@7evg)?*y_<31ye@8K<{tyxwbbGhu!q)DU zKfZ*`BYFa&Er*6tJF@LeWB1kJu|JW6G{0Hjqvw6X-RbyNzlC}NZN`$kH0uMtX8!7S zYflhVX?1?TW_wo%sf~r!uCo=^ooRX+LO5n8&zZw4VSdqLQJXl6f=vNnl%ZK7-#CBj zs)PbICRV)=8y-sFWp6auIb##Vwtein&YBXPto4ARs&pNcVTguVw!g&LGBt`FKAGQw z59T!}Z2xL@2?RN~slsWS^=naGW<{w4N>`6&E;FR0-feDgIs#t)-zt{8@@IAAANLQY z2BLc=5vy&>C;n{p?H__UAO%>{S6z|6i-Up_cDKaB6-mrUO2bleF5bOb-+ivV-hKPN z1$%*-PQSlf*`e#qbUUoo<1J_t(=%E%>GsZ=`NZgczRzV~0k3poh1Bo8j2~of=zx0>C;&&bn|t@IANPyz z7biV}o{5Gze|GALX5S5b9a_2Wvz}@M_Ux_DKg`*$hksqo zJ;as_GZH6h!iaiPi}hkXb9?6GqmF{5>|YR9Ip)v7NQ$gy@0qRi;{F8D={-vEsdx1M zO>VB&YNMI2&@)BCzZUs-KD+8cGzlm{z|j~ZIjH_mTu(LM5-t@M72-dvGqF0|G4j(4 z=u|jS_J+X4*vW?6)I+1@GS26a31@d*+8l~a{sZd1J`qDJV{r{^(T^2cRiy1FaU?)O9Pqjc+(19vf)QYOND+ zLrTtPh0VTHm|17_@wSY?TyQUsPe#u1E|-pwP@xXk{=WOcOVT~f$+N$enhEOFIEKb8 zqlp9Q3EPtC?HG|$aY<{2m5IMh?7)+4#BLzs1pd2$v6OII#F#WhpXIHi@qJkYe>YQ6 zdT{F!~U>FA`)B``m8ma^k~I7q$(5Pw{b8l`flAh-^79j`O96;v+o!jj6$IK&w_a;jp3?n> zvaQIku`Oz${GoG)^|1R_*1fpkfY$XNqFNFV37v5kEppueFz_{)=hB+KhXPG zaBn0+oz#aYBkBTww`Rm$@|0wGU^VpE{(OG!&gfqYx&27D`p8g;vOptSshef$oXUJm zawwBE5mhLSY6eUd#IjtmoO1$ANPpanwFCV4ycrDJWZ;y}f`*NFP@o-S?g{Fv#sy$!OY=A9lS#I1%i2&TzR?YZ7y#slU7{Qdl5z zZOQ)UrBNDjOD~!+|8M`N>h;C&PXV|2KEF&Y_96Ze&mjO0&+eHy?T!5R{bY3=fAqSQ z=+7(nJcaUlh{1+!;#DMQkq%pB?TzdrHP|rdkQRb^yV%0PB5x?LQy57dQ_4TRMU&8J zO`%{oMj`(w$E?ZxYx`aI@$QfexgfjbiaM`(YO*oav|Smlk&*O2=5CQD5ePF^q@4$R zz77TZFX({Stl~%LNj`G??b$DrM2Z0x#M-x^TIiQ%248`_MALHW3l$Y*;)Tvrzefmv z@RPp~Ae`c7cpxELp)t=%=VtP9@l>o_Qg+-oaK5Kw!Wx~}sdQR;-ufS$F?KW#YyZj= z3pDxyw&|!`Vsb5>>XanLbO>1EznT~x;OnGxGCTl{0uRFE->B}T{hu%QY$VxW9gQ9$ z@qSt@MasRlu##QT&g6~l)!Z*YBgdQ)e*Efu38;l_}j`O_37Wq)&Y|EZtJA%V4cZ1}E@ zR;L5f{@@*kxE5l7KC0dPJ;?hO)4V}-l=8ZHS~@8WLTypP4}QMHD`hVSty=hYfk+Uua|xM z%%AiVUl~0ss)!kJ4PsyFm>Lv_iu>Jw^hpfV^JCLAW6|>vfp#jSD&NkzDjAr)_m3BD z5y+RexnT`aeWtrj@z2}u-;=dkM7o20Ffn_V(a(y*_w-)h?-qC+P^hq9+lW)Q$O}@p zw6IfcD?j1G2O%hjYK$^|LQ?X(1c8)6p)rA>C(}I(ffd&aKH&C{_UeK~URS zBJ(*hmI%J@N7_J>h}%E%&;@?8Z;7YmReDIV*n)lOz2V&g2`{v^uf~T3>0OSVXkltE zKXs-lq%bI{)*~5m{TaqPR`PtvV+efh$ymY0rTQ8(^J+D*m7{~JHRog3p#7GIh%6<1 z-NS(dmY6RJC%nw-FQm13wj!Wr^}y+hc7Q=q&|?c1{Y*km&Hdl+`g$D?18;Q1U8s21 zXG;7-SkPw)U^!0-T)8F z-U#CS&-^AdJ=m9hgE z>N*r!>?V%NH4_DgikfIjc>9UXaBnP!*{9RJt0P7&-7Oi(AUkS#-$n;x0=jVB-VM3K zWyOnU6jkDZ9d#Cb_oI9!SJR-`4#_M`2Cn|NkXNrs6P$xCeP2}$TI`ZHxR8KQi=~E= zFu@kHka20SOm0TZa{;I`YXU#MpW)_!%3*$uoY~+1fmj z8yo82HagLGWAJn6Ph#**B;D@UT6fXjX78@-^)cHgze$5 zxEEhLjG%2SF zn0`(FB9|p^{oP+6RcPkf#hp`@KrduaOlZ!}d^KCl=2~X(UJXWWPNh&1=L} z(8$|mOccv3UJh26DC!?^XF>5^fXi~h9*%6IhyO!-AHG~}EEt0*Z;_Gzb~?M1b|&7h zmN81vWCviZGFYiL$Af4cS;|~mPQNU!M&S06U_ZUyJdtL);kC8?34lqgb3c=^<6u&^ zVAqr@=F`QV5_GR3-F0gc9M$VU5>hF%Cs*O5PKg;6rQG@gu_}F0=iIas-q_A~8VS}x zLp1f-_&z^n?e*K}455Crlials63HPnoToCosR1Df#}P`dUZ~?-lzVNZ&mQV79wBi- zGi*>)aeELyq@HY#t$Z?@$xqA;t~a72^}6$%dS3Dq4fL~f2)LmdYX{NLBLy5C_OYSK z%~}*^Ki29Da(RZW4cllk*1-S6M(yq6j(Y(uZPSSxQt8=vJM~JGpo`X~N0iY(zlbt_xa)PB$Tse=u-WwqoL3> zIQJU_4Mg_QD4ooE)3cnV14FlY*BuHDD;0Q7;6(K0e|gD?W>fO8j^OmD#$)O;>@A~2 ztf~FP<|CJ+f$KpdS9(LrjVYH|&zSVV-!YBxMj)0~wP|xkBPq~)q5RYB-(MdaYKbhf zdRqVF_@Y=?nbbN{_b-T$cd=w_j>k|kW&QeWvXe_*trLS3_16NZ=tF|qgtKI%egP2G zG6!qG72n^h}3Nu?3U5_dr310(*o(hllmfoNS42X!#9`>Tv85-Mssw) z+F6FNhPZLijf|m^`808mi%EtdWpm`Nz{E-IpUvvG1}p{5OuQjCV&|iP=kIH zN0t8w74z|JJ2-A9G{ZAm5ScIuz*G4R44HfC@@@=4mqtISQLszuHHMUiL`JL zxs77gpLqCn`>z9oZj_`|{|gck%@W-$a%4V+nIzPl2| zhD?er{_KLaBL+fSB5HAYX#>Y{!VWB-hX!8a_EpMd2LrV*|I{QRFhOhoVIDbQd%eoD zstmnmjR>-O)#st$9CJbO;<*R#C*Y5}u`3!m@b%d4O~)ptfMou#yQd0UL64ybafIk} zJq{O|K0h$#{-I;Po#p*;L&zIXfbKt&|DDCXfznw?w@jjsNuAlTUz#(9#&)?@3& z`PcFJA$d+o#Dw$lVFdmI$9=w(Y%Uv^H0$F%mV ziLD^C&s)h%+uT+z(2~)U{VRMr~(Yw6#!tXI+iIE}7*1*6Pad(K08ZzY{jIG{2 zSm^zXFgY;)i6bc{f2}Twih)@$P}GYtrfZ$a`;@`{xEf!?#`qD*fVfo@=qw}ANhCKT z)Cvk@ag{%>^Xrg~J!)u2O@jkVF<1@^@Or$JA)!qVm{x((Mih;M z)V`m}91iiV~vb<>83N**4K0}_{_nz2e0||5u31%7qk`r@=5=^ zc6Dq2Tn0>0JX?t`^8_jki#rh**?Lj%SBbEMZWHc32^VTR!4T6S2xO3}l^~mGS;5Cc zdGP4y&#x`t`4b?vbxuX!zFVFt_?&dtjC)WgpG;(gE6`08m#(0OM2rKAU<)Xh`-Roi z(bH8F$MeNuuY!w{_mVAE={9brZ=kVnrgQt3-T}DWy=h02ae5U`5G+$Oc{lFoO|~89 zhx@SHpUNbQOeBFu(4cnQ=>HO;k5Z10Qo7mJ|2)4tiZ7S%FD;%`L$aU7|8+`dV?{nH zaF^ct%?~(PPRYjQ#{*7$Sg}a?{*Vt0I?yXtX zu?KFVyIpu8@yS`0S6Kfmw*OPSnR=7rdF@#v&-8W-jW+pzEus;KKr;+e^sz^%Fq)4} zzHCg5##b%Dg%tEOboQa1mC8>jLYGS*$g;k*g@T+tpO$@gQL7Gs_4|WblxZS8T!6#XZoB;Iji_va zI*6#c{T=#3q*H&%GAmrYF{OGRdeugK!-f(nvx&fFxNzt>f9~1E zF}eX@;CH+OH=etvz+LlPKqSFs(pHJ6@r;*J|3X&6EWWlbO#LUA`#?BqMOsMy7Ipdj zM*GedvAu6m`}0ZA2<+lfNX*zdCKPlQ8=Oo0KU3_G(SogS8%TNVntENFD7_qp%m+dy zmPzO4!CuqOg&w2_)5L>HI0TPQghk(&ch?DYguw z7F?b=IK8A7EO1bSk7ju%*Pk#yH zx%i}OC*-@@`bxSxDu&emC|b+5`p|p=b$@b`2xItR$u59^WX-ky0eoK%%^~FgU3#t| zIeMqgS2{Dyetk&C#fHjJxS*haETl?;D760Kx}M%HnUe@g_s%fJu5MNRo@(vHgpmjQ z!|Gtu4?c9#EREuW2a*qmobbda(;3Exw{Jf>`fcygf#8|q!w7>3EfYO>kLFUjdm~e! zC^hTM>RUrO(OuRT>JNzGs8|%>Eo}uN9MQYP?s<*>K{?AOz!sJD)_}B|H@~>d zG`d%XFq|wOc2ZP+&@0#Xe#ry@Xa}PyUeyI_rf>#7yP@8!3~{TII{pirc>+HFLmzI> zEB3fDH!!y0CQ)2olcnjOvinV>=Na<69l~Pwr`PHx6I@86H~LyE$hZN3e$O$PJ-9TY zN`DvieE^x0C4T2uCI4~p_}!AhK;_g(hMZ&QW9DhrvVn*8S0LUl5igC_7JLCtaaCH# zFFIa{v{-qHqcv#=G!KP8=yEcHI>ppN%iRB`=jV`dK=|RC0H(Yr+G}B~c_PL|$kHPR zjs&Ml1I#Yy!91JxtVJ5Y`e&r)3^wH*CrrI^DwY_JS`={++&~9XB|kO9d|guqA593< zyItixs;!;^!QWhC6%_Gm;>@K7)2x|l_*d;W#lzcC?2X&huNtp?XkXKmY2my?W#}VB zM_hwhcXlLiFGA{wT7$gBo)SmUnS5hva3%19)}nRymqza8v|0Vb^Gl!bG zOrC?EsL%cIH?vL^7aKC8wC>wS90_&EBPkxbHJaKZEUwlS7#HutfLTZcIG+93F+rV~g+FbIOwTD|OQ~n)^h+hX!>6 zcG-Vpgm~VF^iYt15QB-atl+jNs5yB8zs`Tl5wW&GE=o49w!NYs=q!@mb@@8%9iht_ z4n#{9EcTYJ;NNxjeXa5-!LB6hJTst%y`Pj_3}?^oDxApk)PVrkkD{FsojByO6FAbr?Rxcb>$^yOy) zp=0~=9%Vg1sUbAv>Cyf4&}d-8kGI!)vdv~q@DX8@ys_GwSy??2z+v95JB9Xy*nGW9 zaBBK@;2)+T49rNbI}qq?LGorM?#k;<$z;2PP2Zh_!0n=7*7L1q9k7H+eb>=uwDy;G zem)E1DZ^{ku{YF#EpsbHYc>qTD_2fEYxHT*f5`wmvhE&9u0ij1`snAoulZJYd^M@2Y~%mAhBE>>{G1W$Pw4R;wksz4?Q=FQ@6S>e@WkoSQJF z56phob^)y_`EQ;fRlQ@K)ec@nBu}Q*otSMY_+YrvtmK(l?m~!eI$OC^ z#?IekMJ^IkSXC$m{WIDaQT`X5*e#%WnzhfCSj};G(PPvZPMg>0Q=_7)Bz*fo#_!%l zTjF~u6{$l+wS57a`oC@1a5_T_Q;B}Tdo;vUCq=LWAY+GLA6cYI;$h4ek*|1Avo4r^ z1yD|K8PpLJ#ea7}XXeWOz}IMGeHqgvQyTGAr$K5_{$d}a7}vy0Xvls&Tvxpu)g?Em zo(-xw;bdWVTm*Fx+(c`OW}c4$z^c`ND1wHi{*0#OmOxSJ;ZutCKF~;e=8o`TWb6yk zRV~c%0pD@gjWyI@o!3anR;k8a-|9Ce@iu7mVTr^(0--al7=k_U_@ba;9wW}7TY~^4 zxZwvYkN_qr7+c3Dp{m)gN8H`$$Zk`df|JycIhLt?ME+GK8d|(Cb{_=5p}+YH@t~&) z(Q$Pmz=WBxc?hrelkJv8X%|u`zrVNA5PRCOgvmkkH6axXaB!*%&4B{>owv92|hxNeN9~hJj zD6U&h772x-mx^Lx4p;`vC0*^k!Zin&xZGLUAl4%4&yJVWXuRM4SlPi5BQ$Q|eY3lX zHt99iM;48B!@^eVs6Hnb7eA+o7#SBe*(<6YBB=oJ?gCZPbto-LzzUOepVc?!E=OJF@2AC%|Ni+ z;O{+QtQiyMHLx8s7W*PUT=H&!4FkVaCLdFy04ua~O@l-}2zr+56C*z;G2wcRGWj(o zibVd6AUVYr%Mrlu$81ozk!s3s8p?CAv{tj5Mm7m_GQCYc#21tNgG)SF?#0*C6(sEa zdn2+#=YR^@a%lmkUyEQ8DEZCFVRj|cv}6!Th9S6aEtm1ygTs}VKB)I|QYl6a`sKrE zreMgD@oq~6(DoBPlS{{3B@7L`B4(gixpL|DtzKEDcx+fOMHvW4=^6PNy?CWUysuS5 zby@R*TCqe+)S^(D|B2-873&VjO~))H|vv^(O)Z+DD=46gq8N z3P{zyQ0Gv;cyP-Gpf@=DGzOI!=p(|AXYAD*5vtKWN6SDpc|HigY*6N4=RnrhIoFpZ zg;}iXT)&H#X<+0I)x+ zVWyfgWxVNQ*&(m%n^d<(#z>bXHxXXt!2I?gt`-SZ{b;3uwO z#O(~RZ`?tReEbGU#V6Q_E0sIfI#0vv7(VfRE_YvK%a0@9_u&YKHZp}|o$8bVQ-p_K z+c)Bk!i7K8nUdiiIq2*h;9~XCynQQ(tfSojGa>CDjo-0GD(YKLhb|;8(0x|-4pt|b z?NI`ZEDb}!WRnXQ$m2ZXX(qqaYy}n%VBy#FZKmp^Emg9N2JE$dD^-umKL7W~_II{Sx7N9(f2(6ye@hrv!mF^ z$BgO3_S&*IM_t@T5v6)D%5lk$4_BTJI`fKMXAYQss_UvqC3$@ttCjW|C`WYC0nDf87XyfMMU$WZ{Nt$+V%9Srl) zf`zgCQDbGGf^7;`zjshQGF!Z^Y$VWZdunO-Nfz7e%{*$NRa~wjHQ-*K#?@@7VWq_9_4z@Ors3|Y8&YCi~hzP zMqVkNE$WbY(G8YqytNkW!S%VQgHLny+TegrnmZW=)PQQbAvNoWM8-^Vfu2T4pv zRrR|yD}Lp@+MOIfHZvtgY5|ske<;WPC`**XXK_2 zj80F-ikA6gl5-p9Qlv9)6m>v17fuqFH|O4ik(}aVBFS%ctZ-*mkT41{vLK)PqT&Y` zZL~DR1#vOci8t)V`!TEuW>S&nk1+V<}WGI?eBw}A20w!v!VV=jLT(t zW$a@S@my|q-)@JDm%h~|Wco=CyF{|cu4^`z-Y?fE>g?tl$j!;0hLK{LPmiFcs1FB8} zIk#IZU2)gA@!9prizQ;jH7%{nhUY1)oQNgzh5iTX!3kHM#RAGrv_zs=xQt=4qI7WC zR9%L-4RRxRlqZZu{;&G&1XXXFpXl_g;9a^VAN-pyyFqmgH8$YVOo4Fn>KQ`ebjA>) z$Og8C)f>ZY3o)09z=9!|rSStgYksdAK;gg3omVckI%3H#oPo1_whl}pzSp3v8s+7B zu#&eDN2n4=}5&ygIHl4i()^#ucl}){^oN>%?PmP@mR!ZH$S*L{Of-zy5k(;Xqdf1_dS(<+E~2!j|xW; z|KeNM703qIY+@W=4+WPR^NF>QNk73;#V7~9uiMPaIdQLU`ByRW_&FkbA`Lx6$tIIE z27k!scd`+aJ5@2)& zyHukfpLi*(K)N`zY<8Y0w^)66b8g_AI^>W4eZ>XzYgEPSlqf80pq_QJ8oKa8u)&+P}s2bRrcI~2ae>KjFIY5Ymq z%-cXTe5WFAexUP@9SpT+Lm>sHzx^fO>CwGGiEqP%e#$Cw4Dpn8P!%lT>dIVT>=1ul zoxTN@p~5)tl0>Yg`UZ)>v1vDZg;M*A*^;^`fGvyblYo6?hbZ3n0HS^d(7ePkA2A%Y zmOSe^>GHb+C2bz#6t8je=0fn5iz0MCgRAB-9EAl4hFf!vKjMtwfevSCE<3njITmW% ze89>$w5dg&R|4GxiP_nlT5f}PpB}4*Iuei~@g(qjs{WT9S2;)lej4x8fY!N_eIaWy z4Ex9TS7x1?sw@I{J8OP+_IM475mCYTzp_bWmiU8@z7yXH0V6ps&nPpGj$sR5Uyjvx z3s$Xw$IT>7p4KnkkD+o0#n_AqV(8if!N$wXFB5N9^I)zLnvlfCsp{5ljD(6zb8RxJipzBY#xsn?v)?w{LCIGLf=cqW=GyyB-1eQFN?Z()_~gelqi6sxGQu3Uzk2SqmJuy4n%v4f$Xj~JHdJH6m<58 z^)T>ybA=%VC+@~BA$`}&#$X}9PmPYAJqO{>U4)Y7vS!AvoJOOf6FkF!-c;a2(y{uZuI(BSM33heGfz$U5;%^!>nNJO~`PnZ;U1&xo2SwJ1<+{_B{*5%#Z z3{rnU_)p3!!JccD+?>`$1s#^x@61~~fk_NoHEPH_HbGxCg_X)+kLT?o-9)o0!LzS< z&Zs7-TB(Gw>Z*6j@MRG8;t}Zm1=iFn9MRvXuFmg@fEKN1&fsSj6GIkf2%S#)qrH~B z-Z6oASyZ}-(vnG{R{q3u_i)j+88bbs)?;jnmYPFa@YfWAOO<#lOV{8}OJpBI^0Hpk zU(V`83`E>!^0=pYwTWuC=_JP0mWim@H}u=1J?`6=j%2ZjxLO!S8lQmDMfy!OXUj+g zqN5EpH}~#EWX3n|#%Q8#{La+B&wjtBg)i}NM6;@GV@XN1zob;q2deNa3+MIKtLO@4 zCX6wl>_zt}tai0nlSQ4zKOm`c$r{kclgm`8+6|OLNGu5x>(q?|QTsi*UGDg|Q;&t5 zcYUed4{sNbNAjAF?1O-@6NnI95nO7dA|AT=R%?sA-ZhUZHsQxj`-!l;)r78eR=w2jsllbG zqy&Do)`YYXlBILWEB=9#16yK_`I~(3x;q6~{c@MI2L2W#m&>T0XJC}2$xJ6qH$~_$ zaeGT>D9|A(dvAw5V$VLIxUesstDNFXkiPV2OGv^oBYOJAJ|*OViy(S%C+yoi{g2|y zwcj_Ti8m8sqa{FGGh(r~C4|smnwAqi!n{w7ix8!esLUTT*!+@NylKimSTawKJ1>8r z#7|T-?X{_o8~!fl4a5yGFY3tGjWrT#HY$XMLuS(};+F+4H>cehvX@B6ACRjlMX)EC zGPXa1CI>ou&3B51BgCimyx_rblgC36H6NntgoF>HUI3#ZeSBHKhJ3+Yy8p&nS_nE- z_~57Xq+MEgKKxP@@}7sZOd5H(qY$Fhm=gSNQ+b4qcs$aUQc4k)(X8_5SKhH{-b04u znJ*Xx1q+#A#eJ0Duz`wb<6?81CKcZd0{Fre((qFI)tlE8Me_q}ah05770vc4w?3G7 z4`eaeZNPbNRx^~2)dC)mj-G7v%3RtTVXOpRhIue1yq&WNVG_wQfj5XZB`)GLJT9qy zrwQwNl5R@^$v)n-k4rIq^VQA1d^FQL!LWv`+j$I=>W$ns!$-_y*83-%_4lZNtj`yU zsb68kwLU&utD7JPn}2N*&o3~8!O}SLB=p-ue8-?`L#^WB$rs3q+||W&u*XEmVvk3BgW>sbv-i`AjQaV;cvNWJIU_|RmfK+DiAHdm

z%!Je^putYYKAuy67*}Br|rktY|5L8 z|NfY?Yc4gwk6hUm&bK<0wm=V&w`+^JdKdz2=#Ojm8$mJ1_>#=*+D&c(@jb)dNrt9Lnmum(ItKVtMdy|qPFT&<9R9Vzv(oJb$CTirQGfFh z9iky5MTQODjz6V1a^ReSPbqjZmDy(;QxY6$BEnmk> zYN$Yt#D8RpVSMpu?>c-xdx3=_WA$kO?o@WiQ5bFgzkksz*YRR7Y%5Yq4;)ltWtLtQ z4pF)I{}>6BD2t@iR3iz_1`>K@77C(rJ(~HxsWA=D9YLwWZ%! z8?^OC_DagVq?DQFRqs>(FBlf*>73E9WmyCFky+z_aV#lG5j-b{BoAnb{ACb-ooX{10#s=!UwH44#GZ?V|8E3+N6Ov?8 zsycct$1rm z;LY;8s+vUG?#x;fNYTcGqVR}+aK|Y)!Mi~hnUF#;1tugUgSn+9lq#fFi-;P)mrPD< zD)iT#X!WVortD%A&2Kl9rf6!wrxht({4m_n_4udL;vO-yl=jN^cyGwPEgNDIQdqGJPK#sTt*?8Y3I$8ImyVB~b zic;5#Yc}BBVv~?y5_rmgrF3uAhK4Sp(zPYGu*w1RqxCKqT{)noBu&^d5RvmqS7M>R zp86}&VXp7V`YZB@TY<%J9S+9QbS>QrqY7*oBAlo~%L_~pBr3GfA6c8_85LaflxBhd zxGu}R^Ire6uZ^PKPEi)03D4)_bBnZCdQluZ+FeqkJe%cQ;HRm7SUDY<#a-}s^{cwX z3%@h;FkNLdFpIw6@0y`HbzrPZZ><-3ixne#7$t?s?!&1-Vz<;@#cDAdog~V*Q~jN& zB=ZGk36e!*5TS=8NhD#yCM91n89fR6bxKTCQCX(d#G|m}SFbBKW3@RL_)OJN#yy2=?CWyj8vD9jxW>M=3)kr1-kLRkrCXIXYP`3dGBh@ej-0uN zip6lOzf+f{-f`o8TvM*b70X@S8~;W_9a3LYuBIGt)Yz22a7|l}NsA8b!ZvW#B2LIE zZ*$S+3#-V@!!}=(O5Ici)>t02%oa+uLz8q_u8LEoEH#>~*F#N!c( z97h${u>-q*T{3E411IC$hjJp zbiW&&S16vM^Hz0!+Su!KpwKajwQXXV98xg|?i=lia08fr9GXTVWiU%3+Z?XU-?5`% zsId3U3`v*4paAZ$QiJYZiKrRk23o2SjlAJJdS#k_HI=%RxV7>|?a(Pc6D#QplCW$U z9MKn!$75rKJmF5mVT+YTO=n<*>~)1(LS!X|;l!SP4-Frdn50WOxx2lpvJ>6(SnfT= zodm=MCZ%aAJc!}IoS`6ez@I@#zJ-EM_s;cl-i9O5XL^zw-WSk0Jfo2syLu2(_@ilB z9-SS3qD)Ghiln_$4%UCrq;m}`?j!Lt_=5rHiwkRK!aTMp7Wqlp_9pgE9IXatnsTe$3{_%EJ37+j2+(vzdAyRS106Z!yqYa`G}Q;YMX!D<{l22sm`#%`Z+aa~ zYAiW+ThrtA8j6tpj<7TfnpxcroLEF<${*N&(s2cVtBRggMbD4~XG0Iw5w`TT*k^BY!LQPPgy8=+X(k-qh{*;)fogo$_n*gojHxvE?H zK!f)=W?xCU?h0(l7xEs9&QaLiK=*DQk&x%4mK|KYt&*pV!7;p zj@Pmgk2lFUVkpkW!?^bSM*b-E1KF>ltC0aGpS(~So8DLdZD!ChJTun7a)a)=#-Hd!js6P8o1nAjf5rDGz#a*B1fqqZ`q zTT8K;rnPUgs!rpvZC9S1YAEwa51Mem$k?HS7X0EzLup8S)_s4s?X_G}QuXJ5J#chf z9+EZ%DY^f$m{7^`+NEb{tYazqEwiwJIL{V^j>h1HYh}&LvOoCPh{dKtnO4}fI=gS5 zk5X1Q&zWt6GS3nohr{{+vG;NwSI%5i^R%M>2Wd%)wTgWDUk+`j1hHpLWIBW5 zjXgo?x}GWjsHkRI=RH+eV8nlzzCL#UBvF{8XZ~uZwXJh2i8%70#O;dkzxGv7o6a$P z9m>V=Hc@?o(oii75x=3DYE$wGZy161;ATbf)vB}?-A|4-b?hnI+BTto#_bQrsRvti zAo2D)wra^<++O>#=xo)_t13c!&A2JZTRBk&)(7hL{ zv@RbUI;^2m+1=)25#2kotMnqP35UWwHSh;Olwc&~*pUe2NC#)-vc7MB`;Tvb{qJvo z{hx1t`(JN={daGF{U2|CfBWt2Z~yu2Z~y!4Z~yo0Z~yx3zxpq4fBiS5(!NKGz%KsV zd?ck@6xeOlYl~IlO8p?UwXThjBnuC_)&RHYus#5(kK`$P=*YI#YkrB=Tv?yEnrNwV z#YhOo^6;(oimYGUB$->~jIGpKhOieqKKWBy-MBh3PdnCIJBwR)uL>mdk6Y}_EUVo4=)mIGqXViY zbNldSvurc|Y&e&&R_79erh^Gt5OYTU)GvYII?Rv*9KFoy3XC>nYjRT z_lWA6Qqffeqn3Vu`q!aUX4)Hp5GGz%FUsKlrIRWHp@pha?b1TGP_@K_j%T=>YSz}J zQOVkcnzw|td&gVD+PPCIVQpQyHLU5%OY5K9ah0a`ma1%2mGK)mZ$6!r$G@lPqSJ7iDm(E;+7a zT0#7Y$1M!Q%K!N;N|2KP6q{}n%+SGZUm4zLTYo!5 zkcx`z^_styeqG7_k!*hf7rR0rQo&WU#e7b zn6V9=(oVb4Ol@h85j!GIuC$IvRfXl7$JQ;6!D(QBNBR0=y2_C=uJ9H4eH;TBw!jXv z@hGW`mbU8N+u0E#c&G#>AkHhcV|V8H~cv$_QLqf>!8IH^;;Y$4cxu zM`?}6(Vtnl{9PBActeQ@HgV&6B^7OYVbXx!xLrprN}OoxrFJVsjNO~cpRSnQ8t&mX30T&%*B`Hj7op7xpNh8ox{+diA0%>qR2n!)}8whJc$z4%SU4? zjku4F+iAn?*iR2J8cTj@mn2X@8cE`uvoWnEuEh@bOV;@eRypobXU))y=--G!=SfQ& zn$vPY2hLfNHjAyO({O03C01^_>cwutMC|N;bIY0HjiU0Lsg&eL8N_U;i0CV~GJ}%= zP&+JQDXz<4la}PEX@csA1KW4QQEFnRt*>=ptGqgi(4B1Hm~>^-ijH8T!H2!|p7&PT zDr~_8Qrk!_vA2@ZX)IX-UL+>i++8dqt(3v3N_QQ^cDDVYJ_dlDq-KxVt@LPV^U6AZ z5GgvMg3lXZId1n}$;~qG`fy7}=$)W+b(BoFc|hS2hNoMjfJCGxUs#h_?e2lQm~vx!^X`Kn0}H z`vy{zG&r=6hq=Y9R0d2p1!NYsJRa>6`i`5|dOx3kvbw%TAu$mNIR>$nv>+a+#2%sN z__{i7Hsl(UNgPMjakEEMpW#Ix{~>oqi55G+l-09L+I$=`H6JF(Y=?jW%(gXu-r67m zE`AFn8bvY-Pn?y$x7J}~Mll_ZRB3b&l5tIMGy*i}ZRV-Ka)sSQSXFg_OL{&GSpdqS zFg@6P;_dIK61R<GVvTY;;^h6zX z!%?qL&d^A!GVTqlD$F0aR6_8`vd~Kw)OV7sj>Fn<=pu)SlM<BUNbPnx=f+EI60mwGsNKNRX4g*Qs`*t-(j(pzS!82ndhVp zZ~>7Rdla^^vNH%qf;h_g1C4A&0u8pSJ_lrc{NTw$@3Kh`nPA7I#6aCVT0Hi#bBxSy z8!a0({9LLW3YLoEl4YZRNEv|@FzVQCTd3Y<^-3*Dg-6=h%Ly1-3FK8tG-^&`Wp%hy zL+lQ~p$H|+$WC>c`g3zILvrMGR|3?BD5@;}4G!>12B*f;3W*ThnUh7cxmZ$b2{eig zp~|G4_F~(Gzk;@9?eS2wL6w=glgUiXGIfe*YevTE%8+p+&W26&IPu0T*5@!X zFdk;*R?n7CWA1NBA)v>%$TL zOYeBw>RM9cv8Dj$3Kw7*RPAuh>#vBzR5in zHWVQrM;&cMb+({L>9lpdx^_=bj^NVzI){u0sW&`V7@|}b|3j?w@uUv9a|^b z2QlvR#Pqz3hK!U+=5@8gM8}S4-iZ#6Mka65H5sBI$D$79x%YvU$?)JMuSck)vLd=4 z?VHKX$Zwq(3~tePnX1!x?qV>_O=4LLIX$Pi`|u}U}77Q)VwHwRPj^NN1uhBr!$$YL!V zvXiD##gxXRI6K~ymWtK<;o-OtZncQ=e-xPCo8ve4_{ah4FIt)*l;eo4<@%Np!CmFmx z;=1zzqmq|2TF4CX*!yDf4$smns0e5f*w;2)uOD4!x9+b?*$84$JC1( znBu?$0bO^)k#_kNB76GpIJLq#&z#bKeYc#BOZJ?$HpO;7-vwLPWml&M(TD_Hn6#%D zeSCh^R^rKLo7K-|@dG7}M|Pq#w+I5vW43&GdV1LKS&G50kz5w*V7;Gji+-?}O*bo% z6pB)1{##0t`G5ZLKmGfE{ICDPc`iPkUCoQ&s+i|*@cDc`)8G5`T8BMmPQc}V$o0-w zuyc6d=}^vP1>}FWyeT$2cp=~Z7+2IRZW$REaU3(qUBl5Cx2P&hV-A;6f3kvtsPV{a zS_c zDyZb`r-2f+?MD=+-W0e12IO0R7pE4H9-X+$roigv#U@{3-YC(9YuLcxoYejFt3u!)R;{VR zAFWqKC8@~*>*{(J%n@12O&t)TXEyx><^rr}`hau_R@18m7TcJd`@YDQtu;pB0oKmqL ze0BcR4sjQ9d%HYil;t6R87Y*K-f?ah(>DJ_g~(eJ%5pS&=iT$oQT%qQOmxE3g68wme>;L)F|Q2T|ig%@2~xbU@b(WQm& zgL~6yf!suLtWN=@|3xh4BI+i4zUS9)7L_f$XxG9;bqg2mTHv*PV0Bn*Jnu@>?W`B& zHePgX3q~qXN9}JcH zh?6glth1G-Kew^~^2Z;GM7Pf=sjbLxD=z+i_UBKx)6HzX`^%p{yt<8 From fa6bc4d9246e5c2977baeaba8b39f42d06cc1bc1 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Wed, 18 May 2022 12:59:00 -1000 Subject: [PATCH 21/22] Fixed bugs in CoreXY feedrate adjustment calculations --- FluidNC/src/Kinematics/CoreXY.cpp | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/FluidNC/src/Kinematics/CoreXY.cpp b/FluidNC/src/Kinematics/CoreXY.cpp index 7fee20218..8f2af0104 100644 --- a/FluidNC/src/Kinematics/CoreXY.cpp +++ b/FluidNC/src/Kinematics/CoreXY.cpp @@ -278,16 +278,20 @@ namespace Kinematics { auto n_axis = config->_axes->_numberAxis; - // calculate cartesian move distance for each axis - float dist = vector_distance(target, position, Z_AXIS); - float motors[n_axis]; transform_cartesian_to_motors(motors, target); if (!pl_data->motion.rapidMotion) { + // Calculate vector distance of the motion in cartesian coordinates + float cartesian_distance = vector_distance(target, position, n_axis); + + // Calculate vector distance of the motion in motor coordinates float last_motors[n_axis]; transform_cartesian_to_motors(last_motors, position); - pl_data->feed_rate *= vector_distance(motors, last_motors, Z_AXIS) / dist; + float motor_distance = vector_distance(motors, last_motors, n_axis); + + // Scale the feed rate by the motor/cartesian ratio + pl_data->feed_rate *= motor_distance / cartesian_distance; } return mc_move_motors(motors, pl_data); @@ -316,7 +320,7 @@ namespace Kinematics { motors[Y_AXIS] = (_x_scaler * cartesian[X_AXIS]) - cartesian[Y_AXIS]; auto n_axis = config->_axes->_numberAxis; - for (uint8_t axis = Z_AXIS; axis <= n_axis; axis++) { + for (size_t axis = Z_AXIS; axis < n_axis; axis++) { motors[axis] = cartesian[axis]; } } From 8639708b01bb7061ae7242d25b9ec1f381dd2d36 Mon Sep 17 00:00:00 2001 From: Mitch Bradley Date: Wed, 18 May 2022 13:20:26 -1000 Subject: [PATCH 22/22] WebUI - vibrate only if the browser supports it --- FluidNC/data/index.html.gz | Bin 126645 -> 126651 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/FluidNC/data/index.html.gz b/FluidNC/data/index.html.gz index 02d4c2818ac2ee296b8c34a6bb861b24e13eb977..fc9969569b85df8ab6ee09148a1edd0e77232d15 100644 GIT binary patch delta 24708 zcmZshQ+J>Ztc7dawr$&Xr?ze5t!+;yVG`R+vc3_+?|V)l{_o?0lC=8Zry_Z zy#*cA0_qjWfcgI3wSB+*MWc7`RHh|V0^MMz*Jr3In5R}S>F`bo$Xm1LgVobIZ5B*H zXO;wl(n4z+@#ArgK89l`?&$nG>-q&bvWTFM_(7=5}x# zq>{KlG1C+qogAByrA-Of(T5ZW&3FppgmyGDKcZl3(qy{Zv2=3doiu`_nc*-@&D2|- zlw{xD;-&Jab$Jl)6xq2#d-{4hpV&z1J67UOT@`fc1{ir3x@B!m2G$G zkBlojC$C?1J*Pdt1N-8vSt(N-OQJtla3@lK1?bqLw8StoR14fn!-<1SwX$aa8GTya z@SYOV4xq`sLS~@uBIo~MM7%Mqmg}fsxBp(F=-pEoNMQKLk4KCw2p!I^!ERp_K4MW6 zP8$#fEcHJPLy>VWS6w48ERhD|9UaNtj7_~qmgMBoX$s3_7FQOUFPQ0YxqKDwQ_eKr z1V`gZ%5XwP$vz&YuFV!PVfTct;9d1@#!1*~G}6_Oq?d!FKt=0F#2*N05V~yQJ^MEF zxEtJ`9sVuZA*@l{Bs718E+0KgWc$n(f!Lq`kWz%o${)MfyM&sjzIVy<2R4T9Q_cfk z&csNfH%Kp>BJfMJTpJq=3Talyuo6bwS-^XLtz11nTE`u=YRUOpZ~2X^uQ`r?(LzyW zb_cRf56o|Yp(Jc4>$>2XBK0y-NpkyHO9?hwe~SmKI@H`-@}Or{#8Pre4-eu!i!+S? zABvk9GN~M%ChVDdA&Iq!`vS4=T1aVMFKu8BE&9z>zc&|F)-2ZoBECb!N0+U_7SeXpS4dKlnqnjpyN3PummR#kndOoFqymxA+acfyhF;1ibd=o7a|`( zbMHomZ?iS)?NJAW{j&Df7vVODNNf3q58TNZ?=QIkK@Q@=2jOaC>fyW>D~->wcZW$N z)oO!J$(-ni`&X1i1K)Wki8X=NF==q(SgNLb|DwrSVK~&6V|pE$276-m?!oc}WS2+o zvhqx>40`CIKIn(F8jG88F(xI@ksLDXGsl58?22kfMfAfGvQI zfhWr&n|0M7>kKJWjb#Fp*t~yd$*{(ge=Hvnd@2iceZ@dx)02=uG{lL;_C_fVG%QWbM6Kyq+>TEbw$!4cg{FJ zYO2eg=2w0iI7RKFq8(Vk@L&YFh#}@}aYHh)*h{DsNbIC6H1;6P<5u1$%YY08ty@ag z&0bTYwS4L1+CW<7eS8w+GGEEM%32G$hWqyy%fIU4$F)9{laDXlt@Wq8t1nhr4Q99;HWp+85WuG@s*-nNY;2&mmt!@B&AtVmY1|mWstiC8a#}s zFk2eB6`BDBlv8SUDy;k!zWC3j@zeqoC@s+|G^mLz^NmBJ^XDGcG*W{PC~O*VGIbk4 zBDM248*#Fb2ev>L3GIOH6-CnNGqyI|Gy=8BK}-pz zx;d>s(n_P@3?v;OfxQ^iZm_FFgPzYnsU2QHj#tTowIZvX1$-xQwQva)5ZVeJ5NfH( zA^yU&^u(bQc={mW=bU~H9n^yA9i?&#m4&6`)Z!W+mZ_>1$Z4D!9rzFz_43V9X0lqt?x5FvpVP)whDl;V00(%Sy?^M3JhnOl=V7 zQB*g()zn!iYJXRXni0D^0Wmm@KXlq*2g+Zg6;oJB3h-BDdj?+!e5quX)$D&t9M0nk zYeQ&=r8W3gMbQv5NMgZd=qAv4xC3+YcL1~>YTC?I?VlXaHl2f(FqDJiMcsgDx~H_ z5j6oaL9Q!IGJ)42$UcWB`A?3?@*7Q)0sa!T3toRE?a|dA76bfo$&lXyWpcFiyg&># zhBDqi+99pyN^%DbM9chHC7~ilk*2KFJAcURR*_48%$3-G;`hmj%5+4~RcxzAO__Iy zZ+5CWH#p3noFQHlw^tP@8Swkz;Ax-HfA$G5ZL7LOkR+^U@#|p*PiGhtQ!o7RrpscA z^j-PhCE=;ZSAAq8zf88IyF zPx8RnZWrn~C(TArxg$PRv>=_ydxS&}3?19H=a|Nlv$tZ~)6p40PTMk&2uMtZ!%a{?GO5v&J!p(&K#!o*db0=G!*LD0xZxxpnIS%?gkHZd zcPU-sx(pt8eJ2eR(>u+R*;EKn1tfaW$?daxDM|;hm8rxV)6VHth0uzArV00Oi|9*n zD^2S3_+;?b(w)=Ojo&?$0mHAJj9&1QeEKs&4N&6#^v+V=+SB*iFIi2@O5BK+u=Txf)3sfm>%SdN}B_0()~ebM>9c34rox>tQz_z1T)Vc0caJrOAI zgh?r5^i&nrZe-?s+7vy*Z&e(*o}(tNkn*YGx9WjJdTRk1ATWzvv}we7TZc_230-=IfDxPp3Z~=z)~eMO^5xq#qtHTm;6^^^GSQwWZq+qhTzS+ zx0(Fl8Cr`9t+NUr;ZRBS8Ru2&qhdINt_z2VK+{qtXz1dEq@c|lEC^7{Qj&jJJs}L> zm&;tJwi|QVMVy8H`zHsc~`4Ywp?zq2eW31;9B*Fs4G=z84(p3ao#+lsE zUMf>nv=c+TGB@0*o=sZb3`+lLoAUI(;Nycg(SB8+RU(lUt`piedqy^Uj2X$Okn+r{ zfLAg^*O5+E+v31p)`|@KgIycseFf5=zfRjh0Qc?Z{GYU&K#Z~zQLPpoo_KocE0=h1 ziB!d})-;MZWCM`Hcsc5_c|B~`{|5QC!fO=cYa zNUGa^Q-y@cu7k#K=o+vY&ETiBo>=80nMbI#2xdZ-tf_LPQl061>K)p;!6kSY6kb4a z!@4H&^^2Oz0gqjy&e+P78}J;X6YyZ2@yyNe@HZd+JVWSwbEcmyBd2;mFa(JGs4tV| z{c>_Km-4=XIp63Xv=-7VDU?XvFVKcd!h00{D%1i?fiBRVTMC8wkedZGgO!CT7R3%? zC@K(F_tSkSl+N62WfK)t3R3*eVip`K0@pJERR#DwU=Up2%*rz*(4AH?B2cyB$1mHM zJ*cemxQo?Sg6X*_>?$Q{c*$T>nX(|$h*=_HE=MsWf%9@sXNLaSLnOPvvnILs9~zjM zNv7z+cO56`Fun)Pgxl1f-G>@H#z7Tf@rXN3ec#l6A7480+@Sra-7{!+4S3(Z^ zAk8!Il#9ILeYKHdSx?vol=LCg;+XOdSk-% zP3RL+#+XK`^1_Y@f5da;))M&@!fB8E@CdThVJepzUzO8gYy-5++Tfc{z}8a$(ggNP zaJEHvl#^LL&Z{D}lgcM0gaUkKD=K^%4OGYdg|(jOr_iD@9B7pCqRpnq>h+4TC@DJv za8KcosoyS&NoEJpvOOE>a+8moa!5->8)T>_j%_Zm1fHD&8Z#|>a}zGjQoFDb>Fr*w{rKBkQcpnyHjJ25$nX3hn8sk?f8_t|aE98+pxfn+dI?U&@&5^$W5RG$_? zs@_tS>}ibO--)-o^r;CUhVIaCC*|+~qqVThF`L3yXXJ}O9vc$q{IFMAR8;+6|3ztq z934>6`}9hM^x{==HghNV(Cv9rcz z9f94)iLJkg9KQq&FSL29?_RRvSM%DqcIDiwA(-!5DfCU`JhD4Z(uy0NC=7Uk-)Xe( z%T(0yTFB?VA5zn_>>P`?TBRcsotrI=3}MxW)Eawo4h!%>Oul5dSlsi~%nS}Lg-Pd% zxaI!KEGB}W&4FW;B`_cz$yq~(@Oyt63<}GqVKh&$JeTR@o_gDT#k&XYN#CUs;y=J^ zERufjG6cSZD}*@U=GB4{pf;ESsIw-<1cL}sED0J#q!4=IZFylLATDKc0vl*MHnhih zwA!r;sC4YshddZ~HadBztGN&{zP>yR=*!ePJ*T>e?hqwC{gd2J`6+TARg0QMX$MvQ zVH|tq8p(>#<_?Ko?qRDqxx}V7SQHR?*>$B@UfV`zu5acY3GQZJ&#Y4MMLH+EF&=D$^G;uj=bnAQYY0b+EZ3_Rba_J8 zaNH(EAFqkwKTXYUbXMi)qR( z+H`fy{nR>U@7n5lKdp^e`Gnb|r-@i}c7@Fm7yTr9;AvB&v zhvf~G>ECAMw-xBC?ou!rXs_h-8IupR`1wcZz%_&ImpB7?8(wnd*4_@d=_m4T5jGwBSe@kh z@aNp0yqV(BlsQKXrbkO8CQ$!hc4>rta6f~nzaqHsq5)GIPwwb&CS+7oMyoP*K%^jL_3e8c#{ zWc&{aL>2`kvRiN}_su-LEk5Fn#JkjTV}6Z_`6Qsq6iXLvk5XQwiEANOjxltB#B7dd zVp@oSyyGPe=TjfI%u7U`J1i+7=_Hi7A;WZdGO3y?&w{i2Z)3ZiW6Xsj{ww|XG7v%p zssHTEM;s+|UwjHtO)P0yu2ksfLY55(ecPc9*hy;Uh0>+ z`#sR-EOfrL!Y&9>xq>|a6McI2YqEOsznGq!d`w@j@w3QJ`Hc2ndJ1Q4^nPMdDAt=W z+>%D~3zf@4+eSYk7al~$-pRcOSFJ#fh}4md+J9QIhq_z$VARR!2mWHCHQI;ZplvF(Kp z5b**anDnPF54)p?0#h}azm&lfCDAZ>Y6TJTuki9;2b7WupWrB(mLQh@n4}!oP)1an z^Qt+aaXTGP@s4B$QW>rH- z^o_ELBx(XTZo?j?q>7yX2}*qejZwr;_S^A(e@5g9*wmmi)CMxF2lN3n2b7=8M78!F5{wp8Gevyg+7? zuUYjqw7tEhdjNtF7W^@Qe8qBv)3F9l-hX{^Q|HyX!OKZs;@Z*+5~oi^kkx}{2VGl#5HyojF*8#C+mTCE-6BCWmU%P+QS=Gg5K z9f?j=T-|O!)5NzoNbT9O^$Y#WZe`q7s^t(g*G9P0JcV?#o>Ah5$~Oex{`<`#m+w!F@}xu`HfQAsXNHC4NM zs)u!BX0j;X2N`JFxjx_wPH}|~22r$e&e+SwSi-A~v&b4N%4d?K0LT}IWm3^{j)ZG? z*TW_hN>U4c7sra3r}@W<6*DyJaGy0 z=UIijYsyIG8AEt+5Sp~Vv(8D{y!7*%X#lJ6KJrM*R4gxFCIQp2RC!Nm15@Bm;)!%? z9J6mfJ^PN~6@*NR+XO-@G+6njKc12E=RgTd^f~><38ZfmKs3i?*LLkRcT*YiQ*3NWsAGv0ZvmhytU4BxVcl$OVUG}0c53+ z4+MNUME9DI~DH)#Y8$SAY5u z(^vocAqV_Z5iTQeQdToI%$FJ=lo!P>G~sJEEa}+*_*?TtP1ndBOJ1N7e7U}r!e)cV zGT-lblPbQS7>LTIJ}ZZWjURWu&nkW7fdL3$U#N1W@9k5j1fH4QB@~<4(%rh7zkpc( z^2(0qLvbN7UDfo6R&*=$2s-xV4k8biHIxa|3PegeURrS$TS$`nyj3 zfxQf{^~-Dy;c#=}j)A|1`+P>v-Q?rdg-{R$lA@WFql>(&cUJ8*CcfckG>i5?hd=(4 z7tW=f`bo2SsUOb}(QIL4^j1mIdGxLIp6JIPp_s9h&SdmlE~)t*Xq5it;{!GjIW9`+hJK6wJuS>nZccJym^2ZrPb!@v>V9|p=%s>iw6;* zY_E@2(@MZh0QCLVw!>GGkl^4SN4x%~<)2|VNiBHBRbSy*v1@t~Kmp$l`^m@P$Cmy6 zyy+-M@NI`(Z(T)$zdg|veS3&&jbM(4Tj#6ks=r=A_H9(r$7EgM=A?82UCw2=z3K^& zz}OwLr)l4pt%hBz)h}=n>#F?+tgwNUGlz`1S4c2C9!aOqcRw92*WjL%nEXVnJ!J!I zF!H^+`>~gDa!5EbxFZ@s~u}-@U!i2JC=z5@+dfXGyKPl-raWI7Q_L?-ct?) z_SLTydR6maNi3EBunaeKzSJ{huy7apT}K;vhr$dYdr1oySGT>5wh>NHwFUgr^z@ML z=W{<%aNv#aq9M~ubzbR0HMQ4sRQLV2E@<82xW`%Cj;jkRjjV0r>WCiRGg^0;uqJhQ zq|jaG&W$UPH+mH|B9CgsApCA8fR~(^?qh^sf-DQmh3dk3+&KYTH1sg+kE-`s7l%CS z_DNkej#%^vC$Du7O|)jmQv!f)ptOtHL-=n_MWl6Z55W2o{MH6dMnb*~Dlz3PtiD?S zgAsrdBf9Z%=Hf6im!ybsj^WApdPBjb5vsrS(S){+_7@(qx)a)C&96Uh9=XO4mycI< zGkya77k&2(iZXENc+gDnEiAWJaJF@3CC%&gMiW{FuQm_zPwZ$Eqz_mMeP^U2&49|! z);A%oVdzL%$Y$U}0d5Vx*B6$9(fR8v^d&uHyJ`Oj5D>@TkU2V1gL9rxse;&vxbqfJ zVwy|iu54!(1mng3olsS1&6_Ls#Ka}3k$8}$)Fsv`z6%%Mz)9gVD80ie0X>o0jG5Ui ze6|=WeE2<^;26>)e-B)V*x!d5)L$D&8(hFp#O83T)`V1GzAI_>z`s1xvF4%eMVv6T zOQPkX!VX)R9-JR zp;Y-K>#tj-6}JlUDR*RnF8K`mC3}HPFDtJUJ1a)dLfG+J4qQ;ANh|v@KsP(1Qi)eK ziy(XT0lX~(^q*B81>qc`@^+`2h2I;}C6MW0`=HC)L=O#-&HkCa>@bDY{cWFF2Vm?% zy`i#xCrPM*w}ARYkt`+gIa|yKxKI2@8kR5tmJqQBc`WX+T6>5wL1#_uQ!zeWN2y8r zeri-9D+>bkAI)Zx7GcscZl^=Ync#+>Yb#`5e{0E@=X6+vX~>ta^C^WYy<-{xL3cKELKvzTkLk3T0w9f`xeSLd7DZ_*=AL}7?av%M!a1P{D@+aUG@s*CcO z0acmOlAFGY%+^R1ftk5I+C6IBrB>oVmJ~_mrMuHs%`I1T@qa9QJ1MerGYyUWqDct} zo-}7eN-Q}@6AKU4V?w1NJ)|=ujcc)kCJ;&qd0t2zHpb^^q|DSBG{V8 zmpkMg?!X|ayySD^)Uy zZOh>=(RZbsItCtJMn^@{PZG}H*FsZ>y~NcH`iD?r*-u0ki^LEkI|LHRYy;W(nN_2* zH(+Qx|9q(DPCN3V`M$U>YL18gow57cd%1F|`*ELn98E>X6W#As>-8((eQ3ZZcPG@b zlzIwMLkp*H zF=Br06F}H4;k;D$8huze63sr~U+?@Xo`)Jtgci;>J{cRNu_YL;;v_m8r|^A}1pHBT zIB5fO^Q$QT_;{PWBBRKoaK74a*L_B1&YO9F`sd3fm{X=s5#H55ZFhIHjP0DzS2Pxt zrWaiKX8Eq3R_A3`Jv{Jc%0^`R_0P(9~M2Y?A2v3|W!7kw@ zg8qR7f-t>BzMO)Nd%Tm*Mvg~$-O}Ggrh8^$V zDkC&tQ$`LkUB9>6Ph%~5`FMC}+~`f$M6;p6^aZmL(KYOMM$baJV~nG%0D6!H?!s+n z>X|7I_nvTmkL>dfOb;X|OC_O^X94$dSyZI}>^VY+r7pWPye#ggXMc({71ZJD2&lLx zc(9wf-Hidq{em80C2-W=ZM|42sGj?Y-Xs-hd`Q1~$vCrpsuP;mbutb+=dDj$#9GGg z6mEr3MkHjBc)m{w-NUqpfdjoPm}tTg8=V@F(xZ#^Fmn_pD864;TTFWv82kdPV(B}- zzCs1D!tUZ_+56dDM$*ylSyRhs+Jf_mqg(MeN3sgNm*yN6PUBvFM_Fs=4LpYSc0$jc z#EuYXf0#GrmWy{i{KJD~!@V-Ff!*dNJqCT&HTLL+>j>tIy=TEa0iuhhd@>2F%_@n7 z!FrGo3A4^FSk&c@S;R>Vw{a#7`a0k`q` z9jP0jyZZDjq&=nYamGoPne&3-wQA4fQl;2t0wm}BSZA`khn@i&R`Qsc3UW+0xmCb? z&Kkd9tQ_;Wam6~w0PYeb-*8Cc6j)d2DA9);7hbGjw*o!Zzd+T`bjvl(BKsg|U#Yl% z4r5D`%G6qDxg2ar7ooapYVa#S;Ky97@+B6?esOmK>q+ohCauu? zYc}LDdauoerT@z1d;$emmlb9D%`~S(G3P=nxODRZ>);bD2hgGchoqc1si(F7veW3k zzW#OMfZRwynYacS;iTDPuu-$}M4!y>dE~dEI=~ z39^fs+;m;_5HNO_>h7dVFOnHE-m>O`i^hs?8kH$;Dy6IFzTr$0{Ag?WIbOULf?B+O z?pgGs=r!3OSd7MxoeK*Tds5Z1SF&hhlqYWxONMg8rqWY{v!tVQk(RYsRd3jU9>da6 zgC-!PUT}msJ~h_#Ox^o}R)H5Mrc9P$Ywl8ews`X34B&Zs5-NMyhI3~*su3j?(Cq!0 zU>Qijs|qdYPSIHxoPx?a)+1`Zb5rOa$ARf21|62plAayQ3$JA;FBb0TfFV_N zA-G!FH_+dXSYFR+Y18KY#T9^U<#}otcaXuH(uvAbn7>jHNiwjrwuLNAkN8~?y2ie| zO0Fy9ce8_yces?QFvd0v)k>I(EX?-MPyQkF94YBuLPkb`ihW)>kF*RzKV zPX4`jG)RnAKEqyC(nqxvEac?-y}w;Jn*THHClHO6y~R(oe4VU;M^Hi!)P0Y{ieAAR zAHa7HgKZ69D1s}bB_J2hD2jOMQ9utgQxMgKj4;+L|XyA==L@o+b zmX;sK8n-B*^u3|^;ELcdHyj1bb_Ive0ZYwpG`W?5LYO3 z$+l>!HAaDMS1VGTIUYCn3z#uWJ1m4yB~Une1nM(++GWsw?Upq(0#|BejXL#E4DP-p z$1-3;B8WYHhlVwL`KaMhAnBb2FfV>V&^EE7x^wG+rm$+^TD)b89|hDR5K>|sfR%NK zIH_NTIkw-l`2lSN>hgpi4^E=+pD(R+(p2BIFGj zSh9??RVr&mIN{tdjDwaaN}}W5qP|JI2X9dJmi^qv7jB(lg%#b-BPFu|DRKnZ4-QDB z>@xAY5GQ}xzY$(lpg60Ee zMwC{p3;5h{9%!$eWL@zUT|;c*NjU8x3xC)rN@E^6r_s!xT}92Tc<9g(xZ){&4)Nq7 zZ#fjHr(}bE3o7X%*^}h~r|`X2X=u#g0%Co|7WoJs0s06pJV{^TMaG@%b)VI8G zO6gUEq(Xv6pwUet>w~QE(w6SkR{PpyUNY-`jlwwHguGPOml_CC@2>-?kq_s6X`(89Ay?)(9Y?!}l~K5WdRA7RyGclKF7iLI=F=@o=U2ki|>$48BQ zB5X7<^llQO6ZW^6prPOYAZwFwUXCfIz;Q%^Vj|b9v^`P6$WX<1D9=pR%E~0|OqPnZ z2S~C`BeLj%{y@(NmJbj6?2VoZGB}jSlc7d-U?^;JgY89IYCniv?nE77^ZhLf7>Ee5 z+k=0E3#qSY4w|wAVvjb7IwB`Z|5V&d4F7Miv!4vGP z8dyqeoXX)I)@1l7Jt;tH@=+d!46>Fj!6A|{9D7?lMTePzWeHx!M3>eB9lY8nT;pC0 zqQyn>Qbe+JH&OQ*^8p_5MhL&3L-%1LiuVb>2rx5pY{ksTsN@yEO!KF1v+EQ?gJ0mm z7a<=*xlM+G4rf#OxzqoQobTO}={Y}8g9%7Rl@eg{!X_(+>ktI`~`c5j?6ok zf%~L$ zg6IOP>Dfo=JWKlwdS{EMnZ1c+D^`p@&O;bWNI3Hqj^Pn2W6e~tph`^sF4_{GSD2af zqHN=&J!SsDW&80A0h@13r}?06kQT@^%w1CJTQ=!jj9dcIS2-nK9rPs#b>8kSQiVUJ z?MUihHkp@@ekR%XX&&M=yN=+Bc;K4(R%VLYF`&Ie|RJ!P`Rk3GnuEmXt_1$CN! z!Ijrs@<0Z9p7kK{h1x#P;v?`$ls1sbI#Ccr6VDFpn*9sdmD zhw$(38M`#j*Fdp;!gzLYOvu3%OIo%0lYfvF71y-WN*st-cR6Ec@9O8lHMrW3AZ@4? zUv+vOx2XJ$ro9SFn>ARxONGJAAV;^WzUl5(-F_5SDKP;jqT_r)UJIcyglbvGQrW;P zGKGZLFobVo1o-eZuk3UDVvj&iy_iGQlW1fM{SO=p`OI){hKKfMD5Nk?of(M3kYEtg zS#V>=a0rf9+5~^=j~O~_Fnj#xQ6xrRn>@dKhu%r3%}!$`57BpXUmvrk_1IfJOKzkZTf|l_z6J7sKF_(TUeDl|#rfwY20N zRd`d<3J_>g;~;$J##`}ZtfRp~0L@P(D(K2Q19EjHTSh*DpB8X|&r9;{Ld$Hc05SMSe$w zHV~4{?DkZz-z;M2_XP^esi#DzHv5Dl1fU8}E~wa8(tn|*Ki1sro<(Iwp&ApC3NOV1 z3~ls3eH3Dr!uwauhxFM!LAwM74#KBhiw?I4v0SkcQH;dmgng>p+e)0sE>&eu5VZ2Y z78}hkpd-P^K;DKga*%*XKVs_(-#qV38^@&DWaOG?6kRewf)D)<;3wFpwru%LXiPCI7={5mdmHuXig|0Ch}36DXRTYSI!NGiayGhF7= zWJT@!4GiOAQ4+g)6?LWQH?|RQTIMD9Wjro@;`}8Rhh&_JN9KhMUNUZPOjH{sG9?yI zCRqx$J@?3)5&u2&EEI#Np(OM1PKaF`;31-}+Qm7TaWA7!s%ed7O4j@PVWxQu!29#CLU?mIU0G+#6=R#GSq!hf@LahZN&N+Ev_UR?K;G5u+15L_I$mic0s`zw!(`R ziSA5Ofe4pM96<*(Rt}_EQD%gtt~T#;bRURd{IYPjE*6c_>)|+ueCMOMk?F09cF&vC7&<`3Py8e-P4&qLaTeWQ%$)1>ZYmPM z677sLUV1L7o|^hgQNMr=kfH?M4$u3Af3qv*&ZVf+1Snm4!O~3I@M7nQFLNmEGYnyp z>lClbm)5p0UD8{K(i`SIYX+-f9Tyahn*4W&3)6baYHq?N)NKgEo{F4BbGE_r7dMKorACEmdL$mp~HiVUKD%({u-Tn2{f zD!mJC_acUIOrCo41hC5=(Pz{)q5#@=yJ)Wdh!zpy}l&SNq|*;!JA{Jou8lf9*+QXAPN24~Y)6#p8rO;8-@ zyKTi`0dEWQ1CVL~2hxrj`5!Qt2V2eP95mqAwb0{q`y*h2jN3&SnKng{VOsqx?MI>F zgf2|_L&k9YwAo>^Vc+2z)|VJRz8LA5b&4EraPSG?-_?^And-sCZ)=owN}8AEvd)e9Mym*bTyqf@H4aU;UC z($VTfWrTZO_|y{u-nMW8vbR)wlo}sgyum%fdh@ddjHmvLIaKhpF*!R8)tve$8kTRS zbT4)p$<5pVm|_DJBk#q=qiW2T32`@wmeY)GZ}zB*Ud26(D~(E#?O<>IK`<2YpmF=L zH)Bh8ND@8;nzO1IGMc-~xL%d-u2qPravPpfkqNwisWOxR z>6Sq{B7atV*TrxU1<~Bah%V~JDwjbvWYr63DW#gV(wSa70u)t=pN# z;BX7*fISiLieSx85U_{t)?km_ZhUXM_j2dmBtHla-uREcpX#Bh4I2tzJp2n9wn}?8 zQ?p^1f|>dgG)HOsB(A2VQpsu?zzSYn9{a@UFouGO8qlR1)U1Mmlc)*-b@ufJ-lSf& zIGAR-d&Y~4=5OKl-rvDJoFOtk>WY@oDk}xBxI0wH(A?BA?it^dDtgkZET+)E&amy2 zcapD&{r zliIkl>$Bdb0cuy{`V>Yp^I^ZnxL7z`mO-5bHqi+2iz*0tb*rAU_$Zc#@ml`0g-Xzj zddr11E?E%9Sr^kn@bRO1W<>Lu2pj));FH|@A=J40OoMn`ulX;W<|Sye!et zW+EBp4YzHE2G<&=MVa#h9CyL6!O}pN6MQe)K2jfi539+8iYjbN` zc_k$=GLD)Jm6;qcj5G0R`-ID98_R9?ZbxXC4vJy_7mBWw z7AxC&LrQm$cVf=Rs2SBE2l{n;g!ZS*SaU7|mwSGgALmXj*s+Kmh7KF0rwDU4q!hY@ z@ZOQeC8_H{xgEF5WN$TKUId-dCsyyXZH7pVY&>1zeJRgI`>U-f|f7gC05cDyAWTaY7itU)%Jq&8qOout^}5 zHiF^wkZIt#>fTxsWZQhX=DAEkrBsS_xm1J4+Ti5V7F(T|JbHt0wteyrJ8Q9fgr)@H zTd!UTZnO&hn=&o8zk)l6x4cMe-yAW11A^sQj6XtE26+}S&|%DFb;!>djosh-fWJ@T z&!%^n?W2e;v@ilVfSBytp~u{-ya|-jellEEPC>sB%+r5XQejC;#Em&w+DNg7Q=3D8 zSR!2v6%fEOqJoV7$*|GGCmlH)V44bdn#-h4#mG~)l-GuZ*ByQF$;0J>4kVZ4sY%r~ z9JjNWf%yk=IiV#oY1vqx^cqy7cxhN==GWfsO$^^|@f!_*t|x#BhHCthu^R3K%kXCUz!iL0 z-3_uxgC46B>eiG?yePn;c6amg9UjFf+;tp}cb%T$xBOm9=nA->$0i9@!QPkX?j7}% zzlBf7W>PsYsb5n@qXQ14GYf1pfILoIDi9VKHta*y-~J8noI`%HQbbjDkUK1q*}Qpz zEp2RlAc_l#;_GVvq;G)>K7prscP~s%+UEQ|Ej4`JF!-E@zINZLoj z|6`#U973{>Y5?{d_1xRtyP_0-MfhE#Mp$mVlBE(5M61TsIh(a|0-ybW=rE?=>`}L0 z@hC<4+*xd!;2}y1FECkV@Z)9nlcs+XLH$K|az9P@LhMOKUJ@k$L1yqvR~9mrx%|Dz zySK`h+8uxDKsSXx?GTLGZKy)=2XT{p4s7vdY_%JnGCfBp!nQRvqQRSH>-P09Htb)+ z1eakC_>R(%FWYcDl3H#z+mroXkc1Xw&Re%{fhPP8a8Ij^3Y=!d!fOtXSDr zDeB`3x;vjviTDnsj;i#cy_>NGS;=z9{|A)F^!$~3re5safV~a^~ z-J4Rz6&?tFX^nZvs=RSfOkNRnWKnObpK5LawD(_w)UmCBVJ09(GRcJw9So}?&w>{4 z%7~;$$1T)R3-ooq*`0&_?ji_Z)zk7vgHF^L36*|;P|4?ual>;_2<89#HpxdgN$`(I zpe(nZ_rDS@!|x+JK*78v-8dO(T(txbPko0~5sr-RmL4TfA_G1j4z$XZt;(f&p zg}B#O2^x`rcP%7YNt1h@*8^1=EfE;eHuhYDHk+05H-sP`$V9vXyDKpOwebxd!;>DP z&HjpHcV8Wqm$63z8=osYtpRUMlZvQK9aF-;zm?Q>36N%4oWIMxaU-SQqgDso7bh|h zE4VB4(#G)|vCta9QMHkvGUlfZ5Iojf+fHGB)KN(>)v4-?R3xEta~CsA`vLgng(YnKn$cNA@*(17n=2uKF3Q?m6gerMsSy82ge-kn!?-#lDW9S)k3t%jAca8{jbcv>1wY&I-dJ)hnSM)baK z>RKhG;-~7Lkt?m{Y4jh?2w#dL%)g87D z+eB^1jsko?=35_aRj6lb)_QA`f~;MgyM+Ymgc@$`P#<;kx-x-Z_@zQiAO>nEbJh-xaf()VEp6!7VagTQJD#VuAY z$thaNSb8LGYR6VXfwLKMCFaf(C8Th!dGAQ<$+Vk9`&YUb#Vt~4=RZNX9+fL<#cRVe zcS36^T&{MRXUWr~Y|OvkfI4i%_E+Q8)sPHnHx21!Yic+7Uq(WgB7Oat{#&m~Z!Uf< z1UFzY2v_GPPFx{f4=`nQnj$3z)x8-os|!^!|vwb)pBS)o-Sd^(<)9yf~GN)XD(CXn2AJ=Jo=Hc2?C7*2JBOgQYb~1{k zX+fE9yqudN)ES6t9AUwv0Vn?5a4A_^*E2;Y_IBsQOi)hNlr8-scJ;c1a z_yd9{gqA3^*5aAD3SW*x33##6zJsPI^VffVvpVwlh?(BR_7D`x#&^81 z<^0P-+IcZJ3A7kqP+=0!t>Is50tF^R?X6jH6PS(Zz_?;;HpCB-gJ@0{!hP{DPoJ)0 zsjCfnxvRz|cX>z(JGZhXI8W!6R! z(K!`29D4pILm<506N+)U1kQX!PGVMu=^5okL<+8E#a7$g0xN_576da^qxHkE;;>a2 z(jtq0Ocs_)BL#m@CPZ5>Y7)<&xkfGcS{9{R6K11PK;)^<;eon|A1^cL@ zFZeNB5dk`w+&2_KB?n!DMM@PPhr-IyX1SzDQVY6p&4+)K0`b$OHaVkdny@8GmZM9= zGB6mI4n_ADL%{R&3PkcOp zjT~f{OecRB?M`gZw0^6L*Pb|d<`B@VDi8d{t#A&H8cP?2SRZ|e?L}QBhX#f;7{(Y4 z%5VXU%_w0#hZ#Jx8n`qhq)}2%uudPThp?%!3g}Y@)GT>rBMdm`>s*KFvAi2f{75($;gUE>DxwRB zV00XoP{MFy67qHFfMXL{-Z!WnElIx303?4#Ds(~=3O<10d_<5hLl{#Vi@iNceoaxz zoOp%DcxKN#hP72vD>ygW&6T1R%Fu=74Y&~upIDB)9=u9~Cg@0!c;?FT$6m9EHr>ry zAj|9>dmzCIGDQ$PzS7Lb34*v5Ljs!Mz2vCzQXbb(T%Jkb`pY|ICx3TZztca-Q*r0N_aGNMu! zIx!fZqKlcHkGy12Y$6?Vatx#)pSORMaeKaCB*hs+EI9ETaXX<{i8^$mTZf%iSu}0n*Yp>`?27W$6NM(3|d>f5+7K+6cjhX;VAB`J8N(qW47*fP+$ zGd|RRjM23vPed%sALBvo<{y8Wokp*Hh<{sQ6aGf+R|A2sEYTDp;@ z5^TuE!ABf_)kvc9n?c*{K6R-XMUwVIF}iMBbfv3Cg#^!CiW*TA8Sk5oUepy`?HNNu zIC4QW?V(9jblT3)`uu-8Y9DS9w^V-nCp0u2B^4TJ_NY>!u~@x0?q4XogJO>(Jb;jJCp}H)6KBoEm?JeQLYk7cex> zYFIe9&V_lY2(fPG1K4N6Zs*Y8A@apXW}};e%a(44SmHPDT_Jx;t=qk3TlKH~cj#Xs z+^yTcw!&ZZaq)M>$hqIWwAPPYqtxc_K?b-|^xaoi8QVu6ni;@X%A6{IFVa(kB$Q^i z1zfEplJDikU@6l^JrK_iHwOO2{zNp+sM%>Y53jLdGhFamuw7e>Z#UakIoy~iW}(bO z#og|}R3Fk-OdEe!6gGMKLRhf)yBjr$xvPvORBb)IP#m%4@SJaQpx55;rzuC7;GXvF zfeVDR8?xsu&j_1gtI<><=Y|l;HaG_n07gVl=AX_q^!kTJEM=>MVcV98`yB;Y1zTpA z?i?XZBmOei7HH@;RbeX@GtYM47RQ^oIAmC6p6`;*33-1{%=_B7&HTnx{(2n}B_c(v zQH$rG)1+x`b;C=DFCyeK{ZRp*iRMK!k=W~7M06qqw1o$$o)F4)OlZbLS74&ys4j&4 z%Z7^9l2fxGr9I|lz}b3DL&7T3oScMK*OvNPg2bbqloA_uJy$1}i@Vvg%13P<4}~?% z{cW{64M%_al|<2WwBFE?VwJKW+mT8`uVrg}qWvcG;IdfQnyutGF- zYd?RG+nKRNU7vMwyBRdL_YM!P8HVC-vx~eyhj*WqM0e*`o0p}YTRpOlqF-NBcnLXb zGoJ#Hq}@351cg^UC_uJIfxj06#~bzAHZ{sUy+B$-$||fpF5)JMFU>|@+Q++O^RlDN zUv-{+!RfCI(+z5WRe;4%_+I7(#}ln2P)q?6cT@~c|#igEO-*7OJ3r;Ud= zeFU6FpfPNDxSNi-e_5{Y3(xPou*34RQquD-8cld+wEoRCR1kk2Maw3f2ChU7>~F0+ zflrf*Suy`Dq$_>LK~2L}vvvQlQBD=WL=!U0Ya;^^83Qa;qhTphn^OlA87VU6mbHH! z>osL72rM3WMrR$rg#A8g?Gf~;e^|^!U}{0GJwUB$M{+aqS3Prqmw*jOSW09v&{lC2 z&Zyfmt%3W=%yGap78Rrj9+Sh8J2XZ9GziZhSUaz=+6*bb({J<~7H&)P{$mYJovf{exr|IZT?TxV3=Zdg3{B`W7Agy?FN#M(3S(QzqYIA0;3FK&fB2oB6 zwBsb4;MJg$Oh}=a91|jv!Q506N)=MGMNAFwOC~2a75ei|RH`bqDLWa(=F)!~Qd4XK z;M0nfE`B-M(djNWDdtAr3-Pcv@5MTXu9|VgGik~zC^Re;6*SMHq9exKiwpw`C)jY| z>MR?@7Ugv5d>gj8+GoC0Q*5N;VE(;M_S%q~W0Q?gi;!&mG17OqpWHki#t+WkVeRdf z?kjV7XcJR2Z1vlRGOGvo(jI?Yt4k=RD4-O=UM2Vt2^*Z;9ssk)$1a9Je%r(zSFtwm za^Fsu+CtghCcDU`y1|F`f|Eu-9L)-BU=HVX*`fhS$c z_E2qX=p-uJLUI$UTw;7Q-^HXWmw*(tBDM^Kboit*vCv;n{uOy(uHS#j{44T{n}NkR zI_&hN=~^By^h&6qi+G|8EiW-ZkjT(Ne`Ic!uPEV~Cp8QF!+BZm9oOn#yfBh_J4so5 zCOqF6pPQt`(ug(7kD%kE2lv-xeGp*7u6|VxJ=ix=_;dvne+vp*L2m% z17rR4=6aE@STVA@QBZ$~>^7VXBsQe#DprNj=pa$XoAP=hlgytmN{~z`>{+cw|UrBFzl^TTC*e)l$%dcoB6PEf#-WB6b#IkyO_Af{%t3&(a+wTHHBBDIcmJGoisG|79BccZ>TMXef^!hH0uv;+{$ax z)wp80t9#?$u&aMv>er;JDLNc&1m#a$Q}x88LIZYU8~9bhPsmDd^QuY>E6L5nDm4nJ zZps{MtP`}hEtKj5P10pKD^8h~S0*7A66b6SK&bAT5bBatz5=9gmSgsKVogV9v2ygy-9zZ$hjJpJbpJCFHt;2}I*0zadaG8uj@ZNwY+znv(&4y_tQUPKb#I>b2szy%DLot&+Cke}z!5)2$e!p+bkjLGr z+pRFOsOf)nESJ4)@fHzVX+n3Jo^~(mJ}fCor*v{xds${Ddg-y;dy+c|j0;L?wOZl? zvC%O{C>R~=&mbgUL&B$f$9g)i;~>#zdXfv?=g`?bq@Eh9y3-){N7J<2JG_iCDQPN{ z_D=DwOOc5KQIc8#a{mGt|PTw^v*vQE?2@uZC@$F6I5 z3~xgcvcDrP&4gxFvmM75QJL~Pwsc&A;IgD=<=zOsO=xo_G`XbKdpSt4xQuCS@>NDA zwncvmHBFM-@A}+ql@Tc1L_7$r?)1Gmt6OzPgWs~x zzLav?E3k#Lkl!%r9J$?fbnE6733*St*|QA;1wON--A(VL(O)-+gw|IpS*wJ)#$E0!Jalixz6#WCI+edl*ONijT90$bf1R_MF*n;K0OU_H1t7VgvHL>5OG_zgcF8uz z$pCo?xvrt6gRsaDXqw7R+42&}0ypIftSS~5DDU_AghM)9;>PYFcXj<}t0aS4^{0O{ zj)1#^hx(pw*jXR4Mm6;DWQGlBcaSNeMrb_g<yMTnusr*;yT+=RhiSx zrC83>s>3YH(|A?brFW+`qjl(beLR zR7pt5?H9#_(k-uAc$STMEJeG;Ev$bd?z4prM`Q5fwKV5t@jUpd9*dh2Wm<06>h8XM zKT28MJa@Jc%REZ>+~}@%5c^H;o&|N& zJ*F28IXPYs`B{NHK4}zcgD#F zTXrGw`Wv=#$-cTi_%i8i*~)(_OG1088^YVI?D8bGMe4mA@Iq$W>$pFCnU2`0a;t3w z+qYt+*5!*smjhHtySw>X#P$u@S$c7+X>^5os^fQnDBwuSu|46)(drx))B67U%fI{e zZ~x`jzx}sgfBEmf{_S7?`nUi3>o33j`pbX#^_Tzg>o5QN*I)j{um6AiKmPi+e_2TF zdxaj@$$vLrNhu};c7b|ru}WN7-$`w)t0E-H#KW#Nz)d==FF@)mdCDHzv#s@dzeH=U z%uig-v{brcWCVSA`PM2T^A~TD%&m0BR%k6l*bB&=*3D^*zp=p%U-#_xx-CVX-lWE& zf_tsT&Sk6(G+NP8LQH?C&r#jf#{8rF=Fi&f#^s)Q`e42CVR7Z=Rf1%GxW>lJw8~pw z9hhA8>VV40T;09dOxui)8}22{)xCsZ)5V0jzL>zzZVG4fS0RV9FKSJ%(X(?nuXUzY zd7ZcSXXXUZ+j~^6NflkjFxK)<|2!1ZOnW^L8j<&?7iDn&)JcDpfyhE-sdjmxo2Xh+ z!j^ZqoNU(CPa~7Hi#2ZwYxj*ehqd#jkiy#f>E^JeU+%tA$X`vrJf++W)|++)9}Hhg zYvY}#hLzPCe|XARDXrm$SB;U@BKuN*G3~W_<7vpqfvq0P5@0h3+lUeD$|#y88Ltbk z$`V~)U!Wqj-xhzfWb>P=hoR9)wXY$hO<6APtHvW)7fx<{Xr^M8?~m0Nf1>b@H}a_6 zG?w_|xoHFbu2n&ySIUoCKhzd2E6aI{4UEx;NU^-z~gxnq513WZ!nX zlvd}ax=0&3uFZbFB-}ZjV=W(Aw~uUCniSnQ7vGG4wc&q1IFmXv*wAy1Eb^+Gq*z?% zC>E%E>$bm{UnQ0bNJ&Qa;;^CyAHM@(vkI_fR`v=PYE0i;5!bf?V)vm0^RZ5Sw@>K) z>UTR9GZnl(_?IeGv(aW7I)$Bfy_u@=9>aG;++3;bkE#;OZ|>W6aSRRu+soJQ(^d4G zafPqYf5v~&k!}loVAk(NrQXt3-g`SbqIF`dq6W*##c91()Ki}r_04XR zA1j28wZFCg6xNDjh3)pY@|tb-8;8G_#pTXfbg6$e=F-dNh)Tb+v2zx19mCKciA0%> z!qDI8%8mO7JPIS$%X@t*jJS`F+hN0P-%k%S>dXDoPD!AgG@{74XJcATT#Fs9m-g0o zu!??Clb1o zjU1D&^eXWY1R8u=TfgzzYE^PuaFJBilS{0vsCUqmTLb=xOtiVHSbAD1gHxIA+G*O+ z_PhET05;MxTWnuTi(Sm>1 zAhG)!Bk_8WVs6cCuUv2)YM??=@3%(MCTXy1Uk`JWS*Zw^ZV1SBqvG{wpU`);am|wIS4M#sJIIvT zvrOK6HDcO)nV@YS2pGt$n&Yhs5#WF1S0JKZD5LN++lBhpJoHR2rppsmE4&nuaZYbE z0&LLR%v*uQ47-uAs_F!n^u60)0jM1|T9-aP@wRuR6t^39cE(CmdKQTQJ}R`WyTbwL zRMC1hb}mcHYiUP17Mio*I2yLywcS`_({VjbO7FKaworThGCLUuJAd2>Hl=^Lsp4=c zu_Uj;bh;(dp~RAu_MC{XHrqA=0(!iTwxdz6P|nzBl||g^mSvc~>Qv7M{DYAy9`7T0Llev8d5M%Gp7H3LJeYb#P0 zH^*Db4AHsrtQ*ZKDYV!1udt>SzSvliZO=^`*abvj>|Udim7P)06UKSw~ZE!8vb3X=nB>n$t8b_Mv)=`D`c$O zZmVMTIHYZIr@m`xqN7EZzjf+*v*E_aza)!aKQBHbLhFj+n_Od!4N1uR;g&X{b+({T>9p%w zb?u&>7{P`4buNDycUoTeToqH)vJn+8l_H0^2J~)|1#%tQnicZWS^|gKr2JCt6{)e) z3LAwOmF`;6y^pq@^xk!-CNhGZ&!Tso-oEZ+wJt^D4jXs{bqL4^IIo6 zoohV1Y^mFL?qo2}jhZqUa`OtUw159(VWwjb*ZO~Xl|_}j9x{@rVM1Q_oMiO8yUlN^ z6h^p3f7yx-!oV=*h^$XIr(MP{n}}7onW`9erhKzA1%EGTS1x!X)rd^i!Y(_lmQ*pN zF{#nG|hlv6sv^eSK6`fHrz(oGLnBBB?~ylW;QgSPJ+DmU5e=vXUpL^rW0H& zHzB4MF2OzAQ_MTUo6y^qf~s@`Pqo)NFR zAJ8kDl7kI8fD129PMgR)}&#HjK<#!7c!5jmo|Se z#DR$d`n?^EREw_=+Qa|Ip%spKg|lOSW?; z?=&dKG6VLXPTwTi0t&?WPtB5?#T7jRL-u0^xvSedWQZ!WG{$f#v?ntth#ZeRmnC4R z#|g)Xk}ytYvvCqnolr@IP~ehOtY9;4GZI$4_9UI8i(sBk^OA-(Ia*b1h}VDEoDwQ| z+u6X0s2h5NN7Qw20Gr}!G&Cs8hQ=aEh@+PI!1Mq25II(x4 zJ*r?~J}VCFtZnu=K`##iSFhd6hOpI*lPsQM+$hn6YuG^NoR(YlSt4if_ut2(G=(}#M;YsYr|F6=3yqw)@uvG}WWFEH*tdF5@fgrCM2LC$}%#5km4J$QEf z)OK+fa(lHnV-)2f>M4?vr{fG4!zWHRHdyefze3`OgV-bIOlRfph7>=S8!pmw9UX??5RSg2q1*^ki;dy6b-O74dgz<7) z7_W*jUTq8G5e9TmE*8lYBfsXsE+&RK#8ifPGLLbt_bNr1$Hf`p$+()r@^&+eSeMk^5bbH132KmY&O`eHI* GGzkElsKy@v delta 24702 zcmZU4Lv$rv*K};#c5ZCjcGBtCcE`D~ZQHhO+qOHl`hVWZKl#?$rv`g=Cg)VuuHCf* z-LeDi-wf*R2LSo-s^5KB{-)7=a3}#6EUK%w(d|Q07RXV}o3#6&1j<>m<$^)eI&9}n z)uk2rfzm=N>+^?YU1+5(`GL-oiSW?wP%yyk#i~^}jWv5|=Ke`c8z<#6n~|u??r@Hd zya;L=0)mz!13#^=u!}+j*OEdALWd>v1`9irrz+lm!$_htp}LMObn<#5`;#(GS_X_y zSLetL`AXAWojXe_4$fB$urFtYF4~5qm&is8liMVW%)UvcIIF+cp>$;w*0{?~&N;9r z@-I{y(ePp)h0*&)HWU>@lwe#Q{-Sv4zHFqgWV2B|1?E-U=hK0+*?R@KS!k5F32>JV*oJ1Gss_vWkc0c zbE0$<02SRV3^R~mduf=oyw3Dig$Q=8)hlFGI?u&R$fIDU8YB3iF`4vZed}bG=S3=M zh2;y~bBF&RJvW`-SFKvUo|sdB6-H|4Kvu9r#_0Cs|z^CtMtm6qTG1VQNJU*<3BUU+#JQ%lSZxzS>R zY3oeKXk!@2pv&Soc2kXfp|Cy(MDL7OKo?lC2Pc0|uz4nJI5gHTKM-FWp?1(cx~J3h zohQKya#yAylkbiT*5cx4gS*dGaVVl4P!Evi4UqZ=)Z@)1oAIgrY{hcz!7; z%{Sx_amDc%rbg-1evKPmck-0Q#J;*no@czD9Sj%ZVtH=jrMjStHFg1rxB-<~AXe>C zWcnFdH6%V>lU0DLIw&ddz{?219};;`lpR8!1P!DLUnS`{*vRW{5XQySK{UnQqa@3f z8{S3G@1l*;*NzkDP9=H}N<>F$!uS984*<&#NJ-!-eGyIJh_Qw+tisdGnn<^a$W zQ|K7$0Q*Z<{a(x-*KeTD%q_zoNCUWnztb_$R@E8F)&eNeAD;2AhRJ$@fc3dt8sBJY z_}gO1B(19wokS7XS)jrnOVeLEBmGe8Z~Bb{Mq#3$fN4t>NEi&48g8We9n6lOV5EG_ zH1$EgxF`I~G=1?;&HWFU>c7DL2ZM#q_y>7O!7Sv_aX`E3Z)XRfPB3Z{!EQaJ{WnOG z$p^Iv?rk*-w{bACGFEkP-rO=OC0~}vJl;HvB_+2$h;j;UF$zyuH7d845dZL@P)GtX*Mk&R0 zF0h+lszlD`WP5Q_Nzb_1K*9)%_!$;{;0J~D*1P;|{u>I@P!ua1p{RVBj3l}Xrrreh zPPI?W?CeZTrqCP|Pw*Mq7$6Fch{KIsa5q1J6M+(NhL{4(%|kA0FkI6cT%!B;(cs+o zU?QQCP@w+f*4GH}kJfr^Rq~krr%d|Mjh8**7SvL?zHvQ%3?Gu-R#+p`HP|S?*5pE+ zMVVP?^I`HplPbDmouh7^g^*A+{JC(2Z)JfI144ST3C%@$%WNuvr@8jsxEve0j%U7M zF0rMYqdXm$qt=7yy*P?aga)%YjFucOh10!mWMcWu%ic|P;0c3E2U)yoCydg0dU?2| zL&n#|i?`5En#9x)#ta5MLo|TGxhYvR=iFX~{|*?n0Gy6M(~mnVm8%Tn5hwT3F(<*@ zE9YMeE8UsM+$<18?8v_Q#@LM(2R5+k#U~rq{6PasyMDq0Ak9OQ>YYXwSZNzE1f4Fm z>rTN^gbLxU`nMPz#}Z-ZMog;*mrxPaaiT6M0MkN1Y5ZUKdBaF8x%aX3v?Wk$aBP&( zXt^K0@i}n0G5N-V>+ji-@EVvSQ3pxF)ZrVNp)7yX*y~r& z;-IbSE$27HwSNdnL~B=7Zv`8weGOB|oX^k2Tovmd;3Ep4Q&`is%9A;tM-v0U=tyO? zd(_2~kyFXwA>|mPQg}Q2&Pv|MyJ03j4{CtgsU79VxW-} zd4i>5`J6$V@VXM@@ywQ9lk4|$R4Sec1W^G;@Rg1G_aozAz+Bam}N4r5Jpd@sbjs*JU4w^RkBZ?8@-^z!ZJ8i?+``NH=w{^ObRLw`sVTyS!d|)0re27b&Ke&{0~$O6bTKu z5tWD0z9_1CS9t8_lMX?Uq6({DsVu%*bi>dNy?b{kesO!QHA^SiG^hGE30sgs5aHyF^nOIU4Gu~g zR{$|T3(*xLPCa%^Zru=)ML2jB5xwY8Sa#)(Fid#sMii|m#lt|$(*Pg@rkdN|#*m`_JQ>@Jjc(QA1n z4RI@!qL6KdrUZqTFBF(NI2~_+q|L53%2-8)#}1BKkcYB@%xy-gj?B@yPbf+*n>TfIi?;X4{2*&bH*k<+4f$h${7P2}F68ka;o!p^W zcw;4=Bp4q(3QL~9x0XfUUL>#J4&FfCSIq|!5U%aeB@_B8B@#HQOiA0@ro3OiP|*dT zggp|&2Jv)Xl%aiE4Iyy+af_l`4x=4t0^OnlK3+Q{uAm)iBx4jg{ z#f9_jvxLH3r%bL7K4|z(FCNI_e*(hJ zc2IG~vQsr28VH$j$yyqOP}s2Fyh<2LqGfj=YwH;~#Xw>`*@OavWtEhwOk)_(Qre>r z4ngS0#|MeZr3q1$d>mEU{PcpRv9Oq|c<{JRD?|eLdbSSqOoPtq#9mB|5z6BA;a9#J zPs+gEH`}n+2tp3O(apm$(m_Tx?+%IsEah#Y zq{XvKPJz(bg_HDKVc}1j)Z6mI@Xh87_ykt_2*j@3N|QovtT-~H62-BJwD3kA*79p3 z>tLH9kV@cCKKm$^8G8s*Y-jq{u_&EC3-cujQ-IYgICoOJvNdi#|UMdxB0_ zR*u!4+}C3Z1gu}5r1`+TZqc0XgH&FMW0Dmw@!!d=LD3=|{qzmoeT76HMtt+lahVRc z(y5_bmPYU~fUuxTgJyQaV3d)dwO_oOnkWXbPf4O6hioo*ayu>F9NNm`2toWZTa;^d z%D|9uJkXl9N5k!|vmgpjeHplX>eYEj+_@+JQd562m&H%-15^YX*H;#;8cKbvoafXe zui;@9%@N{Y5P_#G_}}vMD%~dvDC?5t`t#s8KsvDjX8e0JwtyxC1NWqo~8Q{@M zQ0Hzhs>>uo4EqGSZEc3f)JBKZHIW3#$N=FD`OQdSgZOtx)^c5k(TIz?75?HBV7y=_f;L015Blz)15x`Yu>5?K= znoeZ~J;q}QckJDR{_K@2_+?b!c-9=J^FDUy4_p-#;ep3&vgl+`VjTv_X9rw$N6mt) z2`0Fo3kg!@yp)0WREQQrj{G|H{H zj;@1qLMV}v9yNi9(kWaUphoawv}4Y$eQg)*DmGdmT}QZ!f%)pF0_;!~q)H>WPh4A) z?R`w-T9UQyHieXv?LyO%JAPY`~cRmNX);TP^B`sUWw!)04?Vj ze)Cu5BVl`iawuWZ891#6B6smZPf+$YAoGhqa(b!Cy<#ZZ%MX$u)oUsv+v9k`fngjd@xaRaj!_<;zV zJ-IWK+0Er8om`J2_$ezNJeQE4HI_xy#NP4`SOp8JQbe%B+Oah9^t3MGw?#Mla<41?3Gbv_j2Djr0F=K6AGn2MPxI}9sm$9B69jxMqxPS`lHVoJL5V;Gr9&3P zig0yvTMTOJ0~cAarsdP8=Et7=ukmp&?h;?P)+h+zJ48XGf-wf?pgEx^TUp9TDR1_y zEHO)qC5wll3h)G-9mo^ooayY%F4v18v<4M-{rS#u|xiSX|o&KPHC2zS^TRL}ofUm0ec2xLrvB|Kfkpz+|2 zUS7K>!})LX&Oym26fI~KO6Kh5c*1gzs;>wU2Z_*iib#21NS~&BJ}%sYT2gPO|1fgC zn6l%%fbP%o$RO6w63n7xUY%8qm5q&!tWAxqSNa)c6x3w9uD(X{0DS?3q;t(it=EL% z-F&pt;8*eY@wmI-v(2$~;#Gm*;GCbocx+a;AuN6Edxs2`_#))U z!Xt1W-~8=P;Bya`C09%RCJEw@NH$7Cl3k(He)Z@SmOWq**X*DzZt2G!zakE(bz+yZ zhG(+gofTP%@+P!6@49eIA9d{F30A3`plqFmKtp-(oM5a~hxPMHH;x%Bciq3S$A@_H zfT8#{F?}u%9y9ez6yPMAbxt;-PEPkF$ z2)ZyHdyR}YO~W<h67gq0GX%3pB9y6dks_oRfb~=Pu zY~iXFUxCtHGj(X&+|7TP#!Y9q(7@ksvKxE7ZXEJ%JvrA8p1m8iJ7w7R+8vae(``Q) zkM%VC1-8phMW^E{tnTx<~;R(sfE zM^b71&=wE*JJzHi!BdLt7Xnv-smF8oQN=BRPHovw#vu6gn;bDKZ(u2G?YnIytaflW8Da3c_dRUS=yX^}Ggc!<}tLZvVfs0-a1%IAa= zk)-mp+v&MP*?BerhO8hTvZ^KC0m6ag`{dc#)m8r-=yn`wpK!bP`uRPF#Y*_s`1ad7 z`496*scSa{N6eycfQKA3&d(At2~)-)jGX4YP|d)_$}fWb z%#qJe;^VMq*^~;Onibp<;Ny~H2(RRk!%-B` z-Q;wE79VKh@fWk$-vECr_PkMS0^l8ueBsCBk7qz`^%z_9ulmI};M0ppCSk}|DlxVT zlB2LY&cPZsbrZbe?)O@hhzB&uejhPS0$2COnbzCcP}m17hF^4q#DZ#afi9B^{-+SeV@ z64MDA{|bk9$>c2<5CYUTu9B3!`nf=m54TK+DM?gA!^o}*=ic^aRZnFH1zwn=9H}3q zC13N4#-1$;sV%Upz{oLG5nBovA{cQ7?z-CD?&jpg$D_T|sXdVA-p06laZCTvdw5I# z)4RAQw5&wyu$6?7o>r#fG^RQaWtl!(vu1hwqG)FkkMj}^+&b?GD9VlLLoaaIzc2Cg zK{~Dg3Ped=unJw?A>(|v0eP)=7Y&%L^4gKDpB)5+7S9K# zX8qKjOw5wCJ!O?&4c`Y2efdQ!B&Q?g`f>diRE|*BT2q!6_4;9~JHxHauGoE7uekA5 z+pgBxz9FGL!?qLK+h;}(rQi%?` zDYk9~E_(q!ZSJ~#)k<;oEn9ew0&Y~KP!u&#+SWkQQ?eJVg}t)b*Xj4(J3p>0?&fqB z1rq+7OouC40CASo=cJM3=SuEOXUA`!2Akd*B?XV+dEXOFW&0CysT9%|(bn?E0WAHI zJGxe&fkFlRD!pOuvjh*o22^=HK2sq9+aND@P%^CAK;T{$a+dKuJ}$wfKzG6p^gzs4 zL*L6FMSo(EqM2;3ckUq!w;X-MI%({N^idKk1k1xKelX(TR_hRq{uqB&kgh*mz4$Qd zt_dU0G*)jIjb^Pet;>k834W>18|l;AJGT(Hmg-T#ikgMEWfx#yZHh?yLM^4~$st-> za0amwr1u|wGVVky!%iHjQX>7 znL^XpPX_-#unsYMzSupeJ%1DVx0*cU5sn>5@qz(4s_Ebm@mDl<*?x_#tCP}@5ZLKb z+L|q?hmlYt({8;3!_vyoM%(l6nuz^Z+a2D*7D7#M5p*>(Pg}&G{*k7$lr8y#Gu5tU zXBI-C;?bYM!;)~ORN`+AqL}fi$?m$Cg|K3XtnhZ6$L-_b`2$bm-f)H=%~9wxo}VQ3 z<4|R;-?j@GTNfFreU#nb@S{?LLG+tX{RhbQrWpze)pv^2(bfC_mw*YZSg0qt(RGFT4#F*dfT|FfMvTFZjEV+mD#rD}Oc` z&A;neNO2A9QojEo;d~#c)dIfO7S*~zB#z8vm1_(v!TC~G?}m7Lr=%-JI1ag_ZIQvw zmK@TAJ~j9)Oc_Nf^US|~N2iiJ5$0;vZ%0F>uUXV@9PO8@M+X(D@}z+wT5fLVthfNo zx+AW{DA=-!=2wF7&ym69tUNxYtzf{rO@1~|=HgzSb-Uvo#hDz4BY;|Mf0DXBXGGAI z;%&d|7u7sUB_}*k`?!^`?iU<|(mt(y5^pb=yz`<)Z#eOTP{ysDiiLJFu*w$r6w;k> zSMDJ>Qo*lm2ukx5ke9aFUe9;_7A*wIg5HBzJH&ae59##E?cqYqqZ{h_O*;kP67LNZ z_qdG12)$Jt&le{my8&@W4gVk>K-?^Ako89*cBEm}9qBM!XgfF@G=C%iha~ z&*R{PqF+_&pls&FA7ybp1fB}7%U@e3_}OVDq@4lMiIY*S-RIDV)%hjX@2g*3)1X@i zuTN(JYhk~ovk8`t{{h5;)BRtNm=OkxY&k_*lZ6Zv!c24PLx3-OK??;-`(BI|e>T4< zKJDDbY1J30t+YjIkBMJ$!vYb|78*LUi^QT77_PP% zQ`xQ3#gbw`^u0i;TS0|obgo}YQd&f>LME#&Q&_xZ8;pEt1=im-|DEc$`)iu{FH5wO zCoN*Ew;*yKO9WI$tM;9!Y|cRTa9A|K>XJ3+RG55v?fCrS;KJ zEH1q6Elq8T(d3?<-6h|l*IaBO3*o@#r(JkFZC2WMR1^SlavUbaPtDiYb4aA6r1+Ab zjHuHU!j8{9n@xyS2X^C654CO2T%tjPG;7}2s#H9?n1G`(Fgb(Vv$FkC2lK%iAD?ew zxA;QBMYH4Y-wO#ov^{U8uKsv>1J%Aapx8hD3pgDb*Ts>bvqaVqAba>{+b=YzWDabH zKP0|oGn!ZgJy>m2EPnBs!am9@fp=pz+bQn@aTGsL>5WnYbsSLfWHYrC=ciY7i(f_# zO3w$o9>D6MXPu5&gJFy8i!UsFcYf<-vs%x4Y*W~BKv#so7yZ|d;P=5k|Lm;@*J9EM zSS5Y5@-N1i~ogCDL|N%kztm z+7(|x%H5T{dt4;Q%jK0y=$eiF?o(>PRn1uw3y`w8k7#%krXKI@v&bu%#Ks3Pj>Lwd z>x$W6QNTqw7wZK8q(}Dn3iDePspK~pPT>Jb0U}~5Q)sNQK%k`aKI;rJIKm*$uSHF4 zKYs9fMC_O9-lI>5M4?**zUv>{h4GSu2~fbf#iw9{R&;v973>Cv<7Rx#k=7J#&e}nq z0$&srUSA(`wj`u^W%f5m99pi)^?9?-5PzO+y*TB{q~Y8GGS&{KDwy^OfMRi|v~6H2 zk26nYG`hE|>JdSYBc}4*{-PN@l>T+JH*2|Z@EQ7)WXUGX{COv?pBs_=Jae;(d!0-? zu16PJ-{_G$3^&6r4pi?ME9No2&;`s6z}m@MM8Rcd&3|}xumVH@)Hs(mhG0ikG)jcMuVAuCO6? z^9I_2c7}z#f!R=Gf9!l2D9EpeiSLCKDP0ME`$|}|KdKX2G&KPxTnZNEtwJp0jxzRr zNg^W>2^_x`_|9P(!pGW}QPKD!flG~=0n$@z4zLp>zY$!2Z*}PnPSO1FFb<~c)BA+> z2EZKQCz<KUWXItjD&{u{aF zqq+9#uWx;7$K|4pIwRLD?M>~5M?RAWO&YHW*X=Y-Ozpp-8DVZWV2bf`8sUb@hx>I;Nht~Oh+4u=wy4WILHHrj;SG`lPXN_Qr z6^+-Psy!V2?};Kmt}OqP4#SDDR_B87A3Hnn>vrGLW!t}l7+*b_L%-&}lZ#6?*UN#t zKp(O@GW6d%T23NmZ8j!Je;nbI%HmwB1C!}kV;Fs>hwz^LbY$g319u0l0uZH)Gpa`^V`oZh533p z{KXsI50i?^KewitaJ?;j5om&=o|<{E%P*PDq=|ttn@q-Ym|E+GTogo@ZQe9dy9eiL zAUWJvG(NDI>gl3E2NX+)9q3%J#Xw`gGmA-(Hu^r-Y^Y#0BTPQlKlS!Oi)qib@2(!1+fF^Tr<5BP5SVLe{mQeu&HaNH3w~}K& z&rMP2PT>5(apt`*3zL?g$GSo(aOv>rEMWBmm zz5^Wa|ji2bVI~ZDE9^+z5>FQ z8$)Rbge{}R7yl5$S-#Tq0M*@8DyPn$g<9X)`a_c-fKl*ILM2$zNr=cp#?zaJ_Hz1ygDe6gvCVhB_QP{AH=g;WBRl~$O+ z9NcJ5as^{4<4hPfh_R}hNJK1Pa7*+KRZ#UTO0oGCK19I7L?1r zL$D|`{8B7@Igv!ZrrFK;dYuqbgC`>WbIMk{x`x#CV-q9Uu>#-?uaL5uqmM&(iWDAa+m&l089G z3p9c)t~P|fCfM!mZy@^(?a^U;l>Z6GOo2ZnFSvEt@0>A*MPW+!&6A~`NkE^MrWgh; z341ZdA5j9rH!dnJ1*7hm4T?WuRZT5`Wasv+U=${`tdkEMVUwTQxV*A7qmZ&r0lTH^ zusim9cCSCSJmv&>gQ+GQ!A|^^hfH8noyH^6Ct-3lP$}wGEm3 z>hqO#0<1AkY5GCRWF*mXA5p(W?t=G72PAkYE z#)Vw=7?%`xHsY@MN^W6hp(HH!kVQ2Xi87dHE*X^L*C&CavySRiIJS6l591ukNC#G# zim6E;?%vtW1nc6w3)nt$G?e;4D34%2i79^E%a3-P8-<`S3*5R{Js zCbltF)A5WA3zA=U&iS8@%yV&i+Xqwq=vP<`iNg(MHlf+s^eWuqt@>7A)b@GBumB@P zFqMZ0|E$GB7HF9JKX`3YmYW%wRA^>@5KQETx%z7o7zwh_Ub)4gdO5kM)xlDUhCmVK z1wwGM;T7wQ=*yjD3>FcPe_oIYLnp+-aFg$dgu&Zl(a3K5xGDX?>sM9 zrj9Ew{GZrA;dKXCDT*%Jk+UKhqT<=8PPinF9sCh4=^FCXvbgrD6zfM0c~AsvvxY{} zT6^-Crws|Nve(iengXP!VO`7>Gf*&OwA(&be*?n}$|IbA5gl0r$C}u+uh{y1X!(mv zq@?l1>COVrH75d{LXBZxSi??Wqq2?(^?2w2Tr0t&;_|8K5X1aw2OPRtP~f-NP{r`) z&<<23M^;Jf98y1}@v^#NR)`dVb>=7i5kS80Oj=~b05g3=lKz3#$`AM{J7ae7V$o!U z1>kUGh$bW=j)XUmXc#Od>Mv8O!Z;#wm)$ZIeSN~(2xUr_Tz&%I{r?Qw-*8!xYRW$3NUaN6>QY8Bxm9$ zzjQea2w@V-JOh;X{2R8|1Cg0hPzo|@^a*MRUl#oP8IfS%uqPA#;9x)ggpE19wZm2y zt{%0^=Njpauy;Z3sIdAowTxAvKY6E(6;~ z2|dXq!nt(dxf5N*N+PbZ;Ii$s&MM)iATbWuEktPj{GQm4pm>Nf_8?*?GM?i=!9Hkn zEj`B+y;CW0M5lGJgq+crSgvaBSM@TauB3=Hf5tR6o-+1WApk*gsJUcCa9L?=(1)~} zh31N>hSjwC8WxRzK)v#`tdr*ZcesP3&VP31fjF@wte;9+m^$dEH^Q>Rg}*9SY{Rzb zn`{anA^lR6-}?l_g#r$t9tnKJXtHL_RoZzooi46O7>) z1WNr`m)(E9|2F8mq~!kJDd1j6Y_WenY)>v`S3D5RaO*eV2R@6P3_%PzxUon0Gy3WFP3@#WXxwk0fj@65n$9 zJ8f0ajIOo`OPkYGd_;{(2auv#Rp0aUEb6`h=1UGi@vB?k5Z6PhbR$?cG32+>i;lp- zwDw@x>bi1PZf-wi;aSjtUD>)w^u-1$<++Qa9osg&JL>pEq_4o_O!=f@9^of=GbN z;jCjOBQ{i*(isK_=Liv-H{E+Edy|Ak;8WgP1RGRUtzXi30i(u#K>RsJKocbz%#ZoiP(D?zqu}39$3+?^FjY?12ZHuI=`M{kK1WbvdcJbR zY%db%pYG%%#d#{^NnAyVRB0GF|A1F1&515UL8uGNVoWp+UxD_9f)ITB9tMX8(!9B# z0z}e0(su;xDN}&uggu5MN#2QpJO4IQCmXB_hvK>f@I!sdJIKF+Ku&n%KDN*xTin{U zdHHWYp6+!14G9fsw5b7N>G~{1F>NSn(wL$A($fnV=w7tvE6nkXl@6%yyj5Cnfa({V z>FEAKoBtR>nEM*3;r!ol=LYk{9hjd&EJ?3SW2u0(lJ-~&iwkCjQRzYqNNVh8!_c;X zt5*?vpfvWIVgV#@?GpL$>nj+WW+y1z%GYqyj9)qun+4{*Y<)R=HmOvNBZFZxO8$ed@_(s%?w!_$t$9kHV9LR7{_Ri8Q6bkn%6`$A{4XkXy-h{X$T3}c(luV=) zd}aBHH!JK<)?Z%?{POJhmuEgk@y|>D(n438V1|=~cG1dtz_7TF`&pJn9LLWEwlu8_ z@DJE_>NH~UP?2LD2$Nw<^a>Ni9Ck5k57xjMQH+H{(9RzdAvADJ{7qO#z;}WEC;C-q zu*G^_YJK}0+Gx`k#%3PK6i{~51&1%9DlROYlkndNvBwhH2DrW1VT0zsM?enJv9S~d z|3LJKI)xq}26QEN+$4#MS^XE(DJ{1OkX)djQ&Kb{S@O9yLroZ}U-AwmmCdH`j>I$r z)~{lPItla?t$ag8Ndl&EXss9(_HU-jSd9$!mIEcE#FKG16jxA^w0V9;{H7=QTP!6ys!Gt zdieGILH)*e)_u=$@1HU~%pUH_dYQjXYJUVz6n7fXM*tmpbOi>hSYq|N|Fimh5@g%| zjiG`w_gf+erOnG~8UD#ldN;vG4gG>Qr6P2UoRjFCPn!A>0C^BNT*8#+dv7Y{2?%t? z9Vq=PrjeG`BBNhKElTpWA5riMg!{J04AkuA{aXcA@?ZQ_EMbI1L+)k#j?b2b=FJKheTeP>4URcHe!Ho}yym4r zUK(0vwj=2#snnX8+?5;id2BEvp>DR zKaL^$zeu*PWtSGy-sv%buolqkBdktKL$n;EH6-oJ$rncs2tk>a7l(aBtq^1d0uO9h z454gcUw;U+w?rMa(yCE_bfaAs)RxLnjM~WY8pBbLUcb7<7?_qskzwonjqInO!*~yW zw}%d3{843x&4K-fub5w_t^Ux}Jng)?DyO319)^1B6ms2i6tf~BT(_BSIJV9EfHF;F zPa}q!w7wTK>@-?HeuD9Me1?^{7N}XNm^gDDNaO#Hau<@_;aoKk7vc8yg8KRWWHr`?yg+)mXGL zep$XjH!j6Q&%0#|kHme2LAml5J7+L&U~7Jkkna5ZFHQw4RSd2^BMqB&lJealXZ=t{7!z!*59VDNzb%>6G* zPe@WOX^Q>A(O-XDLVm@?F;ovI=^PK_-3&GJ=NF-6Dpax(IBIwmg~{aQbH+a7EO$f| zuP4(yvCjevU494*;`=PJ^eordC(M1hM+`f4X&yQm2x@2HX$A3L$G2)d;UFFf z1d~$NSx+rAn}Hye{j_Leo(%E{MBT=%AC@u-*>jEQB~#GKDJS6|Qw6%H)%MNKv^tyn zO%Rtn&i(*keiDy4)PNRK>_OXi&xMZz?;iP?ckteO^z%X+MR9nK2hHg}(1urwfV{>%OA#2>I&FbHk+}ebYvf{Eg%*JG|WUrFbIpEkI<%NswE+` zBmGM*tQ2pPr%wS+4&e*|@i8Y91U5<0hUc4#3Cg=b9o@l!U74(F&HQ3Yt-CCkr|K5wgywKZ(N5U8j~GvY)-Y{Xs>empaIiq~^cO1&vCgvN8{n{t6@$aPqk zukl|(Occdn>^LK_yAVwtu{Yot$N_{|b0TfjQ7N8&ia+YqPDnOdp9dmWuz77q7v!CT zkfyW1NHz9ZngEAlyNd@H2YqJR7#N>HJW{%^Y7G(M@!2SQeE-OIpNKyyQSA%q(S@|1 z-$)D50Cvnq@>w0|?Fn#PxJ10dBVo$jB($pDsNQ;w?L~fAo%38UXJ`3JX4iQ6o4L3N zaEW%9p-!AS9FZY*5DCO%EOr$NHMqF}LZTv|iW6S;Ecfwn+YA#y_p5DdU1A!mWSow`yTC-yquy+e9q0Pe_7n5%Of}}YwVySl%wyH zVNA-VcySiQ)nHuzkX-}N-3I;o|7^KN4%YY>5BycZ+cv2BfmgW!?QmK!bR0ppULA-9 za)T#S2Y>MF+eLo&K@?%(FXezh7`&iOIz0)^-g#Vs-Nhscn&B3nriI=cW{wcP)n_Ma zaWY#~B6jed13#q>w}g$D-f%IYav_HtW66CZb|TC8d*1pR zMlRRMXx}ywEMB5he+(Q;zzO?6jlGkAr-LMeRo+PvNGszwYtHhq$ii0nUL=~qol3uj z!(HH3%#opLhc@%&Kt6|G?!DSemrSCl7w zKdgtQ(G3wVj8BM9MZ;TNIR7ND>u4#8T&*qpnpsr{n5(B_(EiN=KY0)OtrX4yMAv^$ zO;5;AE;PfshKA)L`y!gBV5~|YXGdft{|skId|$a_b6v)ASbbXK?WO~#S#L&EmsSI? zFSN!q2fHNZJ@%TDZ*n5v^+c($Cd69s=-8g~!@gSg>Of8htkN`^%3k~Hv%^PIh5HRo zRji90k1DL$A13>1Oo$=_fFb(8$L=vaMWX(6rTg_XQ~qrv6YZ)CGNU|l1ha1W%kGP# z)KL66<5qF_IDR-eS*|aS%p*}1U*T=UCC_Otg?Nqw4)O^QHY0ONo?uQYj|iXcHiAs~u9|M3(#ugS|41Slrr@QyT5#S53^*oc8)9y;@YTD z1#U72)k2w(GF-(L%u!yVwr-A?um=jb7UzmokcD4F400Nwb{c{6Pt z=XlJd@+pkk0vQ}$qrw256g+rJtG(&0tE3@6@Z@W~sVD$q!*SyFrWd2l;grT-V0*cPyL}p(&vF8QX2Vh*~|Z}e1hEg&3GTO zP6l*<$xNVW^LJc!)u5J*aD|{bTFOZZl~KmAbx^)x0fs{ShORp1EJOEh#@Go|c-bkO zXoV)g8F7EaHdOR;QhT6d;~ATz7w#mU!?{sQ`%l`S6?7H!%VoO=Kyc_YsQ*YQ^?mZe zv4d10r9)Frr4b7FLucU8tpjqNw2{Fp+G99^sDID`?~+G+IhRS6yO}&LmC(L-g)VJk zb0&ZTiR$L+@UCTv2{wl%2JYzr<=@29W*cn?1?kyAiq;my|^Hgc0xj-I54LWg!17cJHJ1 zta#3uI@Us=MKb}Zcp9pdRV`?m#)&Szfvs`Io~vo;jN84Sh}Zd0W!Q;2&hao5SL18slLrI!98P4>tyZA4E<$qrsP~$v*$?qYi!0g7VHondw z4B;{&huM@j;X1$>e_1GD3FMnBBA3>Ve|RjFwWQy)1lm(A5+|TlX-pwJY;zc zT>d*iS=zUBH$U{pgW88o(U7vz>~gqYw2^l=pvpCjidxGoay7Bk+z%ko(oa=qB!WKA z*+_WY&h?PwIhFRqE|+An6hu)C{nz!#qrmK#w{958KqmZ6$U~_vu*D~+IF8s@HTF+r zi}Tu;wD@%bi1<8_1ubZ6+86{K>bM-v$mcqqw`TjquA70aK^*xjp=S}$(BaNyq$XUYjr{}@lG&L`rJO^mp>A=si zk`u+TsVES*eXpNX{f3P*rb8K9Xyl)#K}b*l`Yzc*KbNz}LRsktIN#AN9PnRHrXwsw zi(&R#tt&%Cg`Ov^VH`CeuL#mG`EUnEU7cveR(pVJybS?4e^bi`IM;rk(&Vr!Q(7x2 z6Eq<|B4X>JN$}qP>ZiSpXqWGpSR~_#NUjObVRcns(Aw5OP=_QV_XhP))nsr`u%$-x4 z_LDDJ=bLdf&FlX&Y(yU3XWCqGchW6R&`(Qv)0H+r{*QssElX2>spG-7z=wxR8`l13 zG8psMYp9@NoW5SG7~TBJBao6XKSFNiv4NGE3dc$6{eq4p)-DbiN&^4@&vdosgXztP z9GA#UAN9DvOpzp$MJP$oZfI~MmLHd`gst^*hf8QO{_A8rSR|Qj#@85#YZ7Hdrwk?d$7mx;Th}{HO7U0<=^YNMrnWP~Vgf9rADD0{7GI``QhWJ5 zkJ^!I*o^2brH8}LC8-COgOd;>x};?6%OO9y5grss4STV)j%{p7Vrb$>$1z8c7MvDz zAecMivOZ9b=r$XY*3kGAEgF)~$6y>~=!`)>UvsSng1H|x=txN*2GK_H=Z=7yUk*K6 zJ&+uXei%=~5=!-`A9xT4X`ap#p|Vw8FX)LH2pVT-!A0{jfut1FeN+kfN3#CYEss6Q zgMw>`T4F7c)l_B@8neKZ7pwGaIUa!(EDanpOPjd+_nO_5%8AE#FSrgPo!futf+p`? z9@fB%$wHt;bAtdAacu+t+2AQS6zX8Zf}2EdOrMa2#Q|F_3>-zbIpiGl}C?#9UGq*)!I8>+B0h4voG!A)(Q z*}COLjdA1*oBbZ1JzR~j#5Nffj`4dYvZl2IQWNU?{{<)@*WWD&W~@f*hhfEGt1_fT z7XO$mESE+KpvW7uoPd#kU$Y`Q0tHX*@nYT%f``IPJ=%$vXA{06GS=e2lEXBnsHX&P zidXc8H)C35Cnz7=G2W^m(I%cEDy=b?^kX1Hxf}S$lDK?^!ned1bw2%^kUt9cQAc0! zW4Iy$bTGMZD1u53x(17sDn1T{m7~paNs*)$bm5v0DFx!EOKoz0M$=`;wYw-zvA6mO!HH zn7YlwQR`waP#MYu0RP|rEbQGBQp3Qm3}|PEvfD_o4^idST;3&4V*0*Qay!-?P9z#R z$S|2sFxs8io@xDmRu`{5aq!F`pjlNO_={WN93C~6E()xhs7P;~*ceOeZbTwQTa54rl{9YAwFtLLGs<1xxR^}_Ye~Dbg(+3qIE57a zLW`3~YemU}_I(x-?2vj-49Ut6&&0sU6V4bL9{#>DS|^Er2*>89r-0TzI~#!DlBZ4_ zK8`hlHV+J5#FwPvp%pS^PEk3}O2j!K5+9gzW37+!wV5cx3H)Q+VKf8!*-E2t{!ek= z5C}MRt=xj%bCmZNcy5aaz8TU(;sp3(^}~OylKn*kLo+gB`aPk8Xg-IeGi5d(&+#-$ zaCBTJguqdM5)^$%OmUl|`(WIfIdJ@imZ?S*D0%pk^g2;%?TLg<4qX}Jnu>Z@GzAL8 znPN3?X-G(;q?}-#K2i^1Q)3m-rw*uD^2$aSaM0Je4%1_KH(T+oCbYb7P&-#MJtq{3(FgDBN#rh9D6-@l?YAHks|TTmF17UW)p3?o3%ie z**o??f)!+nAb5PGnT-@fG{Jkxdu2G*9j8OxN^{W`{xxR|R$*y_(d#3R-sPRVIx5WmbjWT`)K*VA!E=$hkTu&ieDKb){GV@@d?l5_573PT^?`b)j=bw zBCM((lO;30S!SPD(It+IoPz_7zNq(KXBl~-EppkI4@wo%eqQb<(V`MHm9`7=*Qq z@{tjaK0DCm64pR*Ak9&czP)w?YP|7S?03#s zI!e{Ry%)tj^q{cxlDuSnMqOu@k&Vb3kSIGL#DIfH8j?5#i&VV?xgX;TT_oz}i)~zg zz)gQP6%sf>biznF>r=GqisC}Q5J)#7OnP=u3NdNhc_%ZeY#V1^M!-os+SBq)M$VDS z+W}}+O8EJ*1WdCWOd-faIh4q}4ylS8vGa^GA1{EG5rz*B082|!@Jgk_6y>pHpmS$@ zsQ(zFYfGMpSe8G=gWAnMG&_x6`w;(sw!$X-joPhV=g=F}5}z*@)AHsY!e*=8JH)^3 zR)hYwdOh(s2xEhigLNR{vHxzh?LJL1?$|bdQBTXgP zkd1?nIR2`UMCCVww%dK`QZtGq?T2D?-L~jTSB(k@p1Tw^q9`)nHygdEE4tbS4gS##nYh=Xxm_7;g+*_~Y;`#`{to-pcE2xRXr9%u zaB!Uq^HLFF-OdNF&xGC1p}|Asi;v7kHwBk1-4L@)U;FRSze2cM zw|{Mgzv$!Q?~0Lgzk6w|AGt=U&EJCzaHZ(GudXt-k3KXrfUlG}RRCY4rv^zV&29_0 zT1h0|%ZtHMrj2?ao*!-u{EPjGXq-{A(`+7IW5Z^+;I&}8wiw@TwykowF;UDynTLwI z-GQk-q^+1Xt|)Bs^o6j0VDWc1Y7%o-8BM6#dU~NaV$0z<-{e5Az2Q$&jxxbL?b`zv z2x&KD&s&}mHp5n$Y=Va0zMPXi)JFR*SCo1LC2>X`} z6|E(wW1e%wp(VvCWkI$hm4;r+*7`*IP3FO6v9QZgcwIwQ+s4(xYOk5=ey2}= zn^D;O2y>-z-fA?gxnkVIT(%>xM)T3;a#I{|ZnW!|4_dZ)MRkh!M%d_dcynu5=9EUi z(P3K{@SV-k!mB7?+qC3~CQgrf$u`^V1}So&+40gx@qvD zpPM!|Rj4bsG|>)dmd?w*E$k;Pds#Zm)<$53XzJE} zAh$DPi@H94>*RJbXl(Bt9$YgF#ouNZd4Ue^J}Zgt&aXBvOFg%GWF1AnzNqjLa@1x% z1tLkiap(yOuX<2`Y>@(gF9wb`>bGrblzV!Cw1|{dSb1E;O%h+4jlQ&xcgf~uN14Cs zJo|#vUm2zw)c&dfi=ptn%nQhKZCrd;(Du9V5WR}-P1|%{DSgJ9T61i+_% z6)9c(aC*W&Y;(2Ge5t0`NXNnad!6jHAvwn;8=)2<+4y6m?{Gi4c|43CoV~-^+b!K! z=JL=cre@gcw-04j5ALNsxK@`?Oi@68DTKXB@F5a5IJrFlW{;0u41@f(i9N1jZQ$j; zoi4S7vb{}qkxO-h5A6jfjet0s71+jaZK9KTPqtTDeOXb~L2=CnyjpA)5)1-Qx|Hpq z+St%ZRJMiWCRVw`_-MY1NmnibDQZP*83^g{NoQiAzn=Un^1xibllfQV7dHcci*a<= z=}XhKJYMLPP(v5-L>XFMVt^o#p@sg)+$>*F!ZlB77WjwrvfMka)xUUQB=vTZviMAR zzB4{INsFZyHJgrh7p+mA&2%pCXew4tgJyCUd@e7lQ@n7Qu4mI#MgueH3qG&us*?xC z`svN}B44p$WOt*W5ZP@w8Axn@NYz!W3Zv0MqKr4?^+YC_KVg(0nM4K&x=WHo)QH%m zrkQ)k+e~*c*NpLI z-Q?LBW~`r1Vj0NHv`x)OH%;GV=a z_U~fi8vA!KagF`kPF$m(y*X&cwakdXzVRIbjIFLTMYa9J9%l=AKbW=*QBd) z#d25o#=l`#yVS2qS5tI% zuhWh~S5d5O6U*Q-8H3=x0Z+Ia!0?+5(@3NYW>ILH!1Y_r?Y(Wfq)TT|KzE~5 zgWf(9(PoSrWT|@8^Sblsnc1wVtec5zOK((-oSKJXCVfs4mMw!l`WpRy-#j7)5c z6l$mj@H}yUlg}SmD}TdGD^9xQ>5WhW&7#WuJX1 z<+fK~3uhs}VbVEryX)xI%_|b}o^-Qk8wLt|W=p>_eTM5^{B5jJi*1kP;&Hr|jkv#2 zn>~h_?S8kpw*1EZQR)Y>UBy>J15ZAA!>iF9UgK4iy7xwtDcA8w)mHyz>@LYqvL=yA&_W=yP(<-#=)UpmEgwxg;tr<+T$ zoTpWXS(c~qs<2D%PHjl@NFO%QfDy4nJ1zLdj}56I@!R(6yK1Y&oRX?N?}ekQ#UZJZ zkdoUkiV3A#UbXNn8}nF-c8gnBN8D!%8;-_*;Kgfc&dcI?@Krq)Hzmrn+^*H#efxft zvbuThY$KL=l<>LHUGE_Fo7~5hBNy2`E${zMt02W%Nk09B8}^|DZO@v?Y~h+|_dk@u_zi3@;Q8%fwUj9bNf;?*1ktwg3sradCtX0y|O z?t7fnbv{#mD9L8J?(|eqf#LsQp7rtZPZTzy)}cS!>00OvB@$O2l(=2u{#QK<>ZW^4 zFB)=kydcVNP#UU*A>wbyrn)J3h1ZS1dvUWQ`D$6%i|ucYZfe+*wzXlMlA+ zLgMu|Y~_-Db$#$<(%G_=SC)kKQa6Nuw_DleNo3iDLQ?*LK2k(6V5!jYrZIV`62{q>iB_v_#O z%dda?Z@>QX-+%qvzy9@a|Mk~je);v6|M2TC|KrzR{`arH{EJ`z`G5TNZ~wA?klObO zJ+PDiZoZOIObYA*_1a>UxU#;J+FDmdNRo+%U2A}wbXZ@2)K~J9J+x-Bz#)?AsN zxSVOJbj8RB`ttIvRYc}5-Xxh@>5Q$=T86L}kUOoL(-?nagB`x^+3j^(iafnZjYS3b zT8*8{SQ}`xqNRkGP@ki^sg3!6NBPa4wb_l!J@fRzdga67%FU|;$^3AQjhShcx4t?s zx$4ycm6N%;d$XCg86P*?OPH&B3Bjg|33GihfuG$J&gQQ|4rgD~nqH%4=Wt%@Os(=d zZ|~2{381(4s9uvQx{P70<)8j}D5RP8dLT3+?@=$x;QpzTDg%*)%2Mrr@eWj4Untpjoxf!fC?F>E`zLeI+ zJ5LQOt2O@cl(AA;!w;_-BdtaDrT${tYxTy{kdXshJ(eZFW)QX!BiNNuG)ppG7haVm zy1u?ZMQXn-X36F^R}Vvfqmyc1Lr9ylT-;ZUN3t%Q-1^W=#Vp?+t1tdU;U910QM<`U zUKGKtJmt9dX$A48*{@(2R_C7|BLz7LKuz=51S53tv9EM*w5`8ec;hs?cJ#=;?RF`x z&P{cZHgsH@{d`Hdb2`UbKD2Hh*|0Pzx^XVP83Aj1;IEESNFjO@i>MGZcF2f}6*V9TuR6)x16zPTcC6?dZx9#E>90azPuivMu=sDvG zU!nhuqa)oG_`s}x--}AUrLDa8c63DR#8^cQmX(XsdabCZJ~8T>-6qE=>GT>6D!m(c z2pwyGYyBy#6~zkM?Qi8Z+w3S3@Y3V#}fhuR&t> zH%8)r^&rLEn%iEv;5yVmg{0nZjigP|VAsAL<|eaJ5is2lknKjr>(M@;?`q?kFURBk z+36_?iIE7%(P>&i3z{7j*rVaOzOJsDbvegm)NF?3ezRA|KEspV|6Q((0xx!uDYIvp zy!mRxwD~eY+ddF5kXbdyTNNU}$*({}y--Gf;c2!D^{sj6nO;nnC#qI>DI(*X-e?5a zptqT~0*e`TBVkq52`=e-x4{BXJ8ZNreSG3=?@B3dH}33=m8SG85&?WvXj^xO1JbFY z^=j-~mX_Djj&v+EXTfnaY`bf_vBsw3dYY8pZ)I$u_WEUZG7fhBxD#wjb5q6PQesJe zUWMs&OQb`IB`NJW5npY#Z3G1LcpYs=qh6t$vC%4vxYsSqFn`IZ5`ss&-SDynRZp_j zeq(Jvbdtl!35irmP~pM1x7@Qfik?^6(~5VZ)t*#!Pwi~D*wFWf0=?(Xjm%n_G;mtI}%*hFI5Dq%Llb zx0D&8bLCk#np09}uj^l7O)Gq{u_D`^n>Mfuh``vrMkOmdqo604qZ~i*$Vx2G*mhNQ zAjZcJo;>tUn>-;C+i@W<&~_(U-1ok7jm&QwEgCiayHwE?tR<357L6iB0#?X>Shw9) z#p-otuhgPc zR$?v7olQsFSaV+EGS^B=P#mOxIMx`L%1&6xvA~T7BbO2<#)=x9zRmg-wk>Oqhog1M z%*uxAH&F?co>zNJzIX2cWj!V0CFx`mFV(*$M*Pka>=`~32VOueA-(KZf5BN^O70xjo>%$e!FTMS(s%uG&kKOZsE>D@Awb-k| zTib`h&JnATI#{8zPubSEFyyH)ypA@rruAAo<0Ndix{mwDWyAty;dVK$6AHw4TSLrhQ(1UsKa?>fDG-N|ZQipI-Vm~DvzX{gcgrM~nqu40V3E7NqS zd+4!$Y=x(`h@%)u9Yhj!v-~Drg{|iL5WgL3>xeb_cblH|cI{1nJadgZMW^X7hsKs@ zZhPtWw>f=ai9t!yjfOBpsVM%JvC=ntn~r*_2xoq(Xn77fw)SZe-9)3)m+k(+h3)v} z^Y6e-gio7Tzl&g5w|yBHgpnL?>ozJnFR$rh)Sxa#vVkuf%I_t#I$cN&T}*GhUhp&H zA>oeLHJs?KXswEW!b`7xzx8Ni6pd!%cf6#HW7Ml~)QHSBP20Clzy~qz%g8)=>2;YX zqqg^`6$aXOO!JO+c-S-dHl33p?6NOvSKfQ?Sdk1bJ>}~ODk{y0?kD@r?55|pPINlg zcy`%RxAEM`V4fQ_WisUE6j2j#~!Zr^D2ufc|Bx*Bu~SHyzV*4=y`XW-&84# zaEt!36&-|uVayR(pKwmQjA1qrt8g<_G3-qFW@ifiUec~y@J6Z;nXH9fc3Lf|VoGCD zvwd|_TGUgwYg(SDT4iF*@4)n2W&i9nR18PG-`kNQOOmEs>R3~^8&-@R=^nEJo9K6} z_=@iB0>2l3UgcO(hHK+xlaFi`mNg!loADs|nsmsLezMJ$=VqJXrC2te{^jRU_dEJ% z{k~$Y&eOVd>)fQAv}nQ(yOtH}>0~*P!9BD1O)^%u;ZKsq+a#INWq67V54(CFpKnyX$>2RBUUxsB zS2!gNCo)1jwmzAB#JltgD*_vY_PI@%1>`i!kaIcO)uOCP!x9;dzZWiK9#b!EV2A?~ z1@wD=I~u7LUm>)I|B*v09P`L2+;_#{xNOgXl_mLdya;kwWut>j@rVeIFlkLO`S{LN zD~TsxWV5$s@&hG~hjySeHwglaBb}Zd99*vZEX81LWS7Z2m@mh9QV%BSFq?^>P!uZj zUr~_E|Mma={lEEt|LNa4-$m7QG){t1GLBb&_uis0$KkT)p3awS=TP2h zP>y8=>_45pNwNhLi1VMCB{_>LdIpB<#|&~;w|B@8Rc2|7;ZkT%W>6409(gWHz)+79 zju9ncoXlq9B%V5o zffH42M??ii4 z!NPo29N1ag>~n%%9t5slyO#}Ns~aa-JjJ+Cq6ycqfzCNCx9YP*&>&{5DWe~)SA_+s z$wKSwbPtGiWu+8U)H zIWbptP|cNSRi;uY;zXP2tndf(C zVvHa4+Dr4xOY_Ss^UEvq%Xb0J1q#^)!G9Nc^rte?e(8hoavKP*d=Or31L3>i-f)=U zZX$QAJ3!L^tSQGL@+N!gb1@u$MJa@r)gZhohw!Qz1fC04hsDD4&cwQv^|A=#<+d3Gk|{=h&4XP`40DL74D)0j<6Q4miZYLjFB0K6*w+VLrFJ>^V$Zr; zX`bhnCP3cX6M=4@Q&3wG;a2?kaQNAse3+&4#pj>hIhl=C@aKFn8Grr?{{gb8@%c0~ F2>=<_+}Z#D

)D(D< z;7!6ysP=7g0(*b9pq)Qk(D_<6O%_rVH@{(3Yq%h&%<{#5RPNU-BWG^}nqW;@a@M!$ zqZIqYK6nAH-kP<1HI3u8PUR8gP@qE9gnd270}Vce!EVj*T4;F%AvZ`Q;G)J_c5{VV zkB=>^!B1J_!JqEKv^=1r5}Hk_G8}MKdZUL)pP)95^%&H-i=^0;DD*VWf1-2#9AJ~x?chzyp7SQE1q=8d&kw0J@?ZZfY^lf@|u;=)%Qzn#QwJ6$x0II+# z5<__{OpzYEVz&BdNll#3vY4gI2T+yehycr>TM?{(ZnSbKS=!*U1nN0*fGnVsIc5gI zS1*p?xBb28d~Z76Bj)Df|5n(TprK6|y7FSqI$7 z0~rdE8lvMsCEk+~tGOO@stQ-r^`AR(L_@Sbao=_ zEE9FYe!zCybc({Qd}6`vQ5xJ|tNsgrQSJe`anWFK#Sd!M!Hzfsk*tLJIpA%I{l5gG z78}!@00dw563TJ(KhE%Y>jLnNlRjk`qUM)|@nD+89r&=El2Z*di(T+6-rZ_KcSP zUvQ-Z9lrr$dz0qEAi}GAlZg)1$QajhOpXsgX`p%_R)o4wTtJ9(3e{#02Ck4-B0dak zBA5zmT@iI?z;eVGgCb~dQnGv7Q^Xp65#Ua02(l%8)8N%m$$k22!^{(44e4U#ALc@c zwsSUiku+IXPC@I})O}@XsXbFz7VHNJHzNEV z&?GLaks~w>E+hMhF_QV!>N9lI7H`({*E+l^11Q+E4OB=|EHu%!jkJVwlArUwW+U1* z5AeNEo7$8_#04L<^5R3QI~i z{CJwln0K&xA zCKTnN@_9&8_*vLdmk;tepjY@&O)QRx7?0n~(u`&bPsj)W%pBH-KRFUwA^?!BEz`C( zLW;?QU6u>qo-a=(DLSXjmaq~Qw2bfbIx}nz{6>m!RwuE%kk`tZ5&i+#ldpi3&0=36 z@c~zx*u7H6_HKE9@je!A%XTFWUO5OJPsQPSfcU7%BVzbs;03Qq0l_b2J+sbOBHKEwNiz~fJrfBDMtaJeB(mAO_+ zQL+a9DqncKSpevh*_k>*yxCC9cC%Nes2_VHCHmu940tG?DBf123 zBh>Ne@J>lLs(X_KsHSfg)Tx&gGdq?mz5AMn(~N2t>MEwUP=ZUrhBw@qAPDPUtq4$F(F^ zD9Hs*=7vw3tUhFyHWNhI7ggspo>pjb8NAU>8oKhUYQ5cwe=icWy&U6IBe|gEHC|pQ zO5oC7QkZjD)4rrA$VB3X%DKnTrQj&Hp0zNvH@B=uK{+=zEEbb$jZVzhRpRqVrj!fTl1YP+cf|-NLR@O zub0386+1&u4nut>_o6sI5Ad|RCXc&=iCz8_iy-4veUDlY z-oc*_{B=1BueYxFBn}?4iU*J837|Z66z4SJmS}BU~?g3D(E>2g}F-xtECphu|2T1g*=O8|O^_&hGIC8KB zBb};lf5da@B90^;i?P7$un)$ZjrhC>MuIOJ+6CfAy8_bm29Gt4j#D)I4`=AEjhB$v z90ZV`LD5$SYAKBjStpO3Hss-pu;TiTV5FhrIp60(R>DuF1jL6tx`aOCLGQ3I?25~- ziZPXXvw_B*n5)a}S$9e@y1+guE!N_BJ`;5;&Oq$ED>?$IFWV z3gCMFmR_;h=P%+(YzGhi^uh%JEEC=$(ZDxyLD8qC`U5-T?+Snay_#?d1hrtC_^xy< zsi|FgDPWH$ET5wVV3gwB7*tdq#cWu?H^{dP51`ste1Ffl@s+c0-btpeMoEXzr`Sxh$51uGFXRyPiC{9IQ9zJnP~ke9z<8Jl@C92vX%ZJ3) zWL8NqxCPsV=x`8ynAEG}-9GGGz#&t#k9;BK4xPRqjc2nFIfKq}(r}*7Q_Ox$rPw>o zaAcprcEn*Lh`(gCsqp2zL>#~=9qzlA!6W}I9d(;lUemeqeW83gH&_X7{>p?Ee_Hp3 zK2DEbUA99i(AD!L9iWLz&GWG`CngwiNBQY0AdYR14+d2%ECZT!YC8zNnTp6onwZ9T z=@pemB1#OUkyx>@a34&_N~#I2dUpzuvtsRWY{H{PlxcNFjv?^gz7|nvA)sT~pO-tb zf*E6rVJc7tK6YW*i&$HGmq$+Ie@71a3Kp%dx|wIm0)@bl>O+vHRuHc0{m>D)o?x^M zaz|YlG&e?F3Y{2{gF@3!VtqAC#@UF2f+q>-)7TecXdqx?a4I#=9G8TbgW*1&#dFxf zs10?_g_p6i^o&A)ESE+KpvW7u zoPd#Evm!bI1yAnrV%`pdhr&!f+KHEE6TTuc*5bgD!!)L-rvz_`SM-KAV_Ib=C?DG~ z-l`zcCY~ZHtudJNV<1Dh8~DePxO|4fx5O89KK-1KKMM9yM_=$`xFP~{Fu89if=Uj$ z28)y`J`RPIqs?+jf03jXbm5v0DFx!EOKoyS(==gAlq^S=h-F|fE**;QFNT2U=@pL7 z-?TadvLnzviIwG$qV#C4Pf@<$EtxCJJIf;blA31UDz}-IK%(rJy3NB;>tZiZ8Oj6z z|KI;C?A;Vn!@#Z#XlIAA+eokvQRUTK-X%_A`o2?gJJuaeeDS|^DJ$L6P}fYv@c8-U=Fr%oI`jx~Zd4-8(!m!#sM z6*6T`Q8~{_#5o}nADDAvt&j4xnJB{v{A1i+-|e47DCj8y1^C=`4E!}*9HUxqNIHWqt(l>C~alsWMVkMYc&cMNN*q*icl zw3{nME0m!N%NuYb7(THadp&rS2u;wDBJs?X<&V8)6K%SiwLq5HJN7_=6=aGaczmUq zjS~cMErtX%!F$PjWjNLyr$gOJbI}(5HD?S~e_?5Z(d!lp-$9cBS8h0 zxSBKjX!*b)W6(f{e4U_*Ul}6Sj20>J3D4y9{FCQh9&hB;K_jXntg0WAB{RNRW}jHm zC60`og9DDfsP|uI8F`{Da@m*F=^X*Co`#R8)siez)3sW)ACJ5&XLO70cciA`1!H~OtTzJ zA;?2Hl*qgesfru1^NceeFMyU2h7S(_OG{GlN~OaT<*{X;b7y?0{}`idOP+{Wf0jSS zgWAnMG&_x6`w;)O!Y2HU+O1ya&>PeepD!2F^5!4HW~<#h#J}xUgZ{R9J@Gf>zwNg8 z9r51||Bd=suGwgZ9r3$=*tq$JPCM$h4*PxRaTxYGM$xF(?1$pF_}gwV$YvKowc25q zM%rwM@12%Yj^VXJ@xF`YJMAWPfAtyzZ1Si()@WPZ$ihy$897*MSii-PJH0+lVyhW7 z6qZ7bB^itEx4_D!V|&uL8j>19F@Etk6nKb23qNYgCAD-TO(ocnjf0Ok{;H8g@a`|r@dLbzMEe{F@o=;Pw=iji}_ zdugp7xkjnY--8TrrRck_t}?cdJ~T6cuar4e0AHl121zK*ZVR|tNhIIPi@{Q+jd~!S zA8ri%i~WgcoKdsWY#v@?!)CbPwP3rp7~gKTt#Y_AQOrV_hl;!1e}Sn!q^+1Xt|)Bs z^o6is@pm_B5_4A>O{m&>dZ9RC%i%fSa%!&alI zM9vK%l5KDfA^?ntp3Fa;Y3TJ2jabT72g9~46Zbm`vI@4$Fx@#qm`40%t}W2eZK}dn zEM}hVzAcV7adF77f6P4JC7l!Uo|yNwahv&#sr>aiBuYezSfdutL8nR6-0Fsx5MM;d zXZoW8J`>H0W+JiIw}|LO2xtorQavG*>zL4tiLSsz!%sLrQzh%Yd`> znudf`q&YbWt*$NgwFHSrJt-wN?0T+FE*E#RXO)lIJ{}5df0+B*YIPcp^ec&?>1e&7 zCB-UbLAE26hF;6o`b7Ip=D}sLu**?+T|-ve#?``VubJz9r%!*IQP}(lbER?KYBa35 zV%)=Awj-}b^U>yVQyg$^wCk7;TDEybb&B{#*ywb4b8A@Ult#bNVOtpRoz2n0t0-XG zwB(5U6g1}So&+40gx@qxe$CbVZy%#J&3wX20v>S)>0 zMY~}$YC&~OJs{47#F$m&a*L5VwjaMpp#q%S(nrhM-1P3+JG4Tdn>IF8s4KTL(GUN2 z>c&Vn=}{G>eF$WlKB2jTXe?bXISvt$se@0-1XzJE}Ah$DPi@HARfB1yY(=m`q1dQgCD zkph1&297uCw{2>adwPMih?G@Wd0fOz5?`8)zO;{b$>wE8nZN2h`-0P78KxW5{;B|r zq42%Te+$TSZCrd;(j)R(p zt!C@~VWXTXfQcq#me)oGBr*nAsz$?7q&BAxe<(6iWXvsVJJxH;RuEV`@QltnehK@1 z(%K{FQ~$7-iNMr?Tzi08)sEz5;;(w<0xtm@kg$}X8%DmgE1RK*cTt*F$lAVw{#99T61i+^iDP8<>w4>8qY*NgP zycgnOZQhG@3|%$jh-cE2S5RnJDk^B6MMX!9xfdA*7EZ9?!qr(eiY?0N()l)QbG6TW zsixRS$HDx2o$R$CImad&p%x+8_+zB+a6h?uJd7Wly~EnuE!|h<^3W!xX4vYte-C9= z5ALNsxK@`?Oi@57guP1eArdw?xjg`8kB?mpgZ#FMJ+5MH;N`xZF13ZSy-jwJOLc<} z?FA=|fH;~J*v4;dqLX<~wpUtxSy9$Oam@z2T5J{)3<6KOl&i7_)K`dGd?#-i=`Jen~ruD ztx=xMbT05{DppQ|W^xyNE-$K6yl|PWXVXCN>be_yd;WOt*W z5ZP@w8AxnM)m5wtqtQX4j5p==L?)R(VU!@5LnS00EOm{KYjPYjONHv`x@7NU#@!d1=-k+_;t3q^ohoe{xs%#=l`#yVS2q zS5tI2+6c;@xTflfNreXN#5VA&f}fC;-sV-68dj2tQKZCfbS2b!eI za#ox&Ew4;MEF{j^7J$~R&}W8brP=S1$Z@3vJGNuD%crEtso@vb+2LH;_T;q|Vzt`z zZCkmFaR}vVy??~oe{?-AG7Ni@IFWNTEP4EHG+v^3ipDGD`Ke;B(~d${QLJqf%iuB@ zgW$aZPq-Vv@S6?ONTdvAQD~dPmHE5rXc)@vy=}UrOJ`6(ccWB;-aZr2W{ewTse07& zy7TCn*{rFon~7^nZ&Zz(nulU0eNGaVErUJ!8vTCXm?4k5e^a+xVP;X&=~ym%+u|)E zw$g;|G(GKJ)_qt~l1}O5uJ*FbPV~}ax%VV@5*Qbh)M~ZF31XvTj!-Z<*q=d2zJ`QP z_m1^+UdKVA&-5f0yw9Ptdq_PsR&}RA?vJKvxp#OOWm3{qDD9oHv;K=FTj#LiHX{E9 ze`y5z{KBf4e=x6_6pPMD+4d&ZPcvlOP82niAagw@&eD`ycFa&Frc~o2n+^grUr{Gs zQMd&kxy*evTkP1BAM6@W^(*Q3CAr3Io@AY-uj5G@Q;uEN@EG2PBxHX_T$%~ZtY$lo zFQPK#cWmjn1i@uV&&s_Ke4EhbOlWdRt@m<}VsRPMf7;}$j7)5c6l$mj@H}yo&mUMT zf5S{GPP*mkjZiFXPv7;q*(xJYxQTcWSl#J+b5^(Njt0MFpM5FiwpU;aXCc2~(m8Uw z>*&_aD-!aabhBq01`2#;OTROHhU;GZZLCp?ZI9*RalDp|xW7@GJ%*a?ez&={{KoxJ z>Ibr2f5lfr15ZAA!>iFmLiqpC8en@h2rr&WhpmZ$NmuuJbw zZAkM-A2!i|5wSx%E%?Qc4XGjV+xF|bYOBSZlBzxLg`=y*A*qs(lG`te38h;hJEj1+AjCtlM@h%JpOvy)Nak zLaxzDSKs=P_pAqr3xHZ1N!T`wTg7|gf7KiWtwg3sradCtX0y}odz{pDK2v@u$!5Cl z^i)xS;s0Tt_3`mf6gHyPp+DQ{TIdWV5?3CSxLxA@S3L{rrh7~;8gg>HAj)r08mfgM z;%~^Nx+!>t*Nwn?akC`(YFXHe?Qf25YS@#uwQ4|(>+g({54P+=;`KLd<&u4Me|_*} z(%G_=SC)kKQa6ORTiNAFY>U);IpBrNw%2ig`Z67{Q{`6M2)1v)-y%uYdb*zy9*yfBoCP z{`GJF_19m1`Sq9o@ar%CeT_2lexNkvzfLT zA2-}fn5%mU!KRA|bA2&^pWPJB=C48yXJ6EsUZZE{a9-<7t@1i=@6XH$pttv^UXv=i zjA5+hpZ<9$q?z`5AT%QHe^D>W;QpzTDg%*)%2Ms}LN`&hq=YT+a5>qmt)E6FYZq(Y z6xQw=Zw_ncO(BJ~_0!E^O~2fIrI5dxetAl{8LT($3_cjXl-9;OPYo-pHU99Fu~J&Y z53d>{twr{w{$ko|^~TeXkpo*jmL-ff4;szMQXn-X36F^ zR}Vv@lWJc>NSm@;+*gf9vM!w5`p`_pEZ-liFaAW~A8+JQyU9mh6v3@L<+%1~1@WiZ zuV5Hf=bs-V1vv>oP4n0UBXsbwuXJy;t-o7%<21W=^vJ&Lb}6mSO?8nrbX=SLd`Y-- zI>%Z*v~C~Surw*Ue{n9p83Aj99iU5H%YO$&QUB-`POZJGrvkK6_ApQ z?8RY44L*Jc!e$j<%dG4bF4UO5xgxG_1H|q_3Fc#+`fi`l{nhVwEM_Wreef?;s%E3j zHgpO*?Rqm+0kSe>vj{U!nhuqa)oG_`s~+ zi%Pwvt-SYkbVTdKSVaw%m5bAQt*ECyG3uM$CdVo1^coE-B5+{}Dv`swF-DF%R%DMk zY^^zQ^hZ`M*4qXrURNT*O>^UXMI|u3IN3nnxLkV`Qk-b(r9M^&9czDU{VA*!#R}W) zZ{;=H>^Ba7e=m#6owMjtYs{sW%@LJ;XJh9q;5vq(KN5*D9fhI4)0G?d5qK0vte5xt zRv2*~AGgDX+rFP3X4IGarJa&MIcY?ZbI-=Knz$A_Trcgd?_d@E9(B|VJ&FE>D0H4y zVL@|PE@;5HOHyUB6?f`(ZMDRTO;ALtCKnqS2q1$KD2ntTI#Futp+Re?ushV#}fhuR&t>H%8+1AjRC8+g`cg zI@Cagq~33hq)pOb*S;R+CbLozFx?Q4?MB7x(LSN?YU7$O$K(Ck=_v|{kqF4qX<9)G znjIC`qv5%}uCAMPImcwwY=-52vscJI!;{|sU9OA*FLsbAvuByS`D(!2(b_Y_u+YeBy2IN-1tP?(B?}rt~Zl0en$t_ig%*bo>X;D?QFQ%(D$b@+=^m4b}~|=ckl8kxJF6KelxNne-)aM z2_=(=mU%L?(_=eVdDU9#+bpipu>BUBTa2u$(rX5WSl3phE^dyulo_IPtA6_D}1rBBHNyuHn0nbz}US;B`Z6lpeLB496#{LN-WUWc2#vC#>WqyJoHYRJRuX? zaUn3!b|+fg_r7zD%x@bl8a4d8e^k*GtR<357L6iB0#?Xax7}97>UCzX)S^`5iZ=FQ z0ES8ed07yRHMgu6^Uv%3Thg(zW$cBspiKQ;$%NRGVjN`U$jMVZBa!vT2d2B-Q{ ziHH#0Z6}K6=445gCD5>G2vsKUv?tq6EN{s=8#a%!2!)ZeGhbR(VlB&^e@#c+SaV+E zGS^B=P#mN<))<(|PFTsYz>NnZml7w&iW;51&H5F#Eo+a5qjk#6%v+hv#3)-%5^cSa zvAWV_8fmt>oA`0$^;ujW!^og`7?qnnTYi;yY?`0|axPkx==4(S)@YU2pC?!8HAwGa zTQPCpUgcU3_)ftU&M_V9f5R2dFTMS(s%uG&kKOYwPnn&y*sH=@+lRr<5v!3pSfR5| z+19u)4w@-c7(nLp#E`RIP z^=8A3kAF!PzkXhPMugTC#W%Ue8XJ<3_roo1MC)upq0(vBwd&eEe?2jR3-jw-GVZjz z?zt+asAVH6UMfWna}DU-CJW>`v^6W_rL_bOwMqG<+AC6Hrxi8|F)H1)qI(~0J?Xvc zP)%e6JD)}GI=y|}$!cAS#>-cjZHWVEsL}AHzVtAzVvM>g({!kN=&^rng{QWNqZmmY zL=ttg{3c$7t>*d=f4?1T>xeb_cblH|cI{0(bB#Mir|B?<#+GPqd+GMKIelP>K}ph$ zhA>2_DE^nR(l>jXj(VyHXMU<^c@8pksNR9HYz$Vujyjcpe{zTfiD}%?oeLHJs?KXswFE zORs&u^=M-hjb`I_yrhj|)T?mRh|D%k+qX`@2Qlu;$UJ%Jb(tumw)dzN2HJN_^Nx3T z*faMwos%K#vM*{^-h1y@kqj?A`eJ)XA1sa(ym)Kj->TArv{ zWn#_m!1P>Y|LinW3`f1++mRwmlBQhhSW~wfR*W6#e;%^}o9K6}_=@iB0>2kt&i<>yiNJNjt-zGBo}(ZANl{%s7) zB~0b&pwDMv>EilPNt3NpU-yjUa_BxDQ;M^K>&KNbTX)o7Xl!zfk> z$FHn8X+9 zWI2(+J+t^tGFG?YPm;ykB$?7>c!~@UyLum=Z&ba>;5{Q=cR!$4I3*1yGD1AIKAC*P zyYvbx0vm+(xlNb_uVv$tmQ10{}! zcAzvj2?C5Got_;WT(0{p#b9k@m&rVsFUNUO4<_j_n~9)M6e{yyQIO34_5c3;zxjXv zf9c;k-$m7QG){t1GLBdHeLPNeeZOAoY>#cn;j-tR&X;WGP~K@!j%5byKb^iwvIP`~ z^Pid}Ig2ZL28Qg%402bucgPS`W@(J!QfN&Oi5hY=q%x2>xo;snD z3ZcLysaU~g+-4-KdhJO%Nf*I9o#rJCe{FKKs@f2*u{kAF^0u>q6IE?TB&W_2oB#v! zm6KBoPY;+O5iEjL`(}h&gqop0FQ+`uqvTCWsR!WGq;O*IM0-@h!hBX7*jd}`bAnzT z1g>7YmknX78z)&j#kf(T3D>ZJ&N(f&>a#@9AZD#8qaUqTg$1d}LhI~w5sZ;oe~O?k z;i6}P{u9OmECGFqa0(Xa*#whq3|GT(QY5&myH$JI8l_or*;j3?B6|=`;kI8FJNj15 zMD2)U4fUGh>aB2dUc1k$rc?*=B>Cxb9oPVPl$^|#Oz@t)qw2&tF;{g^&883aj@ORu z`d!#lL`UTvCS&ne>0V&mee%lNe_{zgjW2?nV~KG{#d`4U_^IvUF68!VamFahL)23w zB~Qm0E{0E>ZfvmNQ-75PpTr>NP_W(N#4Wfc8wjs_5MFHq;k)48aG2n3B6qAie?ZdztSQGL z@+N!gb1@u6DTJ5RAiOGv@TwXFo(ooo#lrK>#JZLBvIyhlwlH25VZ7QF#v=^qo?I-F zDMo(HgI!DvbBL)7^JE_5T<=wiGLMTd65%-5*9Tptb~*TB&$?S_p68Y(K;GLEfo`8u sP+JkXq;k^0p_3g9$)lomIs#f1u zS0DVU>+Ysa=-y6f06zi-&+viO~4^O9^ut*!h#nr0QRi+Yuh z_$4~IVjY^KkBHWe60B0k&C=&BVg#WLjG&@@@h;)46fOzte>RjhQJ>cu-S@|P+n#^x z_+83Pl-2x$Ko`;aR%ho}i|UPQHf=Tk=7I9jr0Ob=H&KzII&5(oQ>}JZUjF3c|O~Bn9wFqqlL;G0U*NOHp+_e}D9GEhTAPJ{N8B zXdAg+y5ArN9+uXfo2I_?WSWY8GW}LCdh?EZ%hIskk=|7Ap>4Yu&SO9j=R9omoE~ zAOm6v^V(I1A1gZE<*QvaAtGOQt$uL!Vx9~0)#xO_`D&SnrmgoS*BD14YQ6P)B;al- z8mZFXu`j|w8>NAxVW3*I$qQDr^!j4<{96WqTc7I>{g#Tcv)Ie7j#m8VkS(RekkJUt z-Z-r3^J&)%Q<#qzn}1KW-RjCZ-vjfI{=s+I>ef_H@jrCZx7_oAc|&UV(B22RZqVHY zJU^yvD;AO(XscH2!{2t5>P(Me=7(c87_fWRjY%Y|{pI=6)Ryl+{O~)8FtygXfI@7)CPH;{{{HxRH#G%i3V~N>U#}QFTBp2j?OYUdE zg1lG9h*n(MxODK|Pg=!Y(7cpy-MRkcmpUo4>bN;mNmACe(D><4rj2y?ZwLHld;JPA zqY`B4@z^*l5b9&)tp|d+0{$~z-c}F*i>UOdnS<1 z4;Qu*eIOMtQ$VgwBLD$c**^q-jlu)okDZODyK*iuY=1E@*(|L~+U4MuKX#6Is<-JJ zbU~g(I4eBm&I<_sX6U`ScN_7PHef74vy) z>~^v+&K-1(Y{`2|U#6c|?d!H4k5-@Ps6F5Mua06s_t0}q6<7vr#(624tetaYnapN!8BFWfKsie`>x58ats7Q%#q)mv zT$3))J7N6m$_!d$yPr`lzSCaz{O5j!7tQRA(7H&L%G-k2Vx1EuOvYsHnVz&5(;o!6)ot$jwafr zF`KtyLRj_P2u4P+i+d(90qca81jN z^cvTB^5$tf{5lMWGk~F$@&CwpTihKObZzzwAPKljXCMxeBzW#{t>zK0j}75npnw^T zUcB<@2Cw_)-V72q;RzTwuTuA0H>_U?U>~{v@{+Yw0h@hpAZE~mBl83*JvzKap`mWz zpoEd22|^WJ^1B+hs`U<3AOijhM~Z}(kzLzp=S%ll=2HAJl0hTX_OH%0m>>ux7KVAL z^XQn?ojb_!P(+Pv>r_?GpDBN2bs!uqa^TeMML-? zg9REQMH;ev#X+?aQ>TqiuQinMK=iHM@RhNYq=r9qq=xXUgs5k<1unxbEUw%FnlBdt zK_@TMaT2MZW8}%0Zx>%F+3#DxuI@wmVp%m(R-moRFgU<6+t7+#;nYk%#1GjWuVAs+v@<~EXuHeS zF;;eV3kTAsJ1b08>#tUYO-}#uHJp2WCQSI_9p840`sAtq5EodV=rOCkRTO1$p zIZFYhhxg8&gW>mb^3N-87d2DSU+LZw&Sdf>R>}Q7s8MtJsRLR~1NJ;kPdR6Nr#cBT z85i8M9`4~Fo=vpLoJ~x{;T#BF$tt?ep^=!w2;{s+U8glSlU!#E0)rn??Q?#M7JnkxQj;83cG7Vj#andn@Ec@QT!E^DV zlzw<{Cp<0zC14q9Hr_f*wz1C&T4=Yj2fU~=1ld}>l*CqaCVmSkj1M4@=8&aY%$J^as$G+}nmw_c#O0X! zV<-@#ODqI=30aQjG0~b)QzO4|7QnBPG{|shDS0;wof2AopqLyPpgPQ%pnNE=oCkQH z1zeuhp#J3#`UlM`Q4EDJM_|rsM-6};MHLC=hFNkb7i+4eER!ef{XC)xwcB-A%;ki z+YPnAaAT*2Fg++nOSss?`Z&~tBBWr1z0OE}^uOK@Z*A ztCHlE!hr^wdK{YLIEZA5NN+T-tm1W4dm2|9Wp(KTyojoK^WDPdb)^Xuw$3@6#((a?nh)Y4&hPh zibQxgm1IF*YMw_HZZiQRk8L6X#%-jbVH%ZCcIgfd{G5Dj%Sbc3vkIGBJjot~d3JbQ z5haYcWabd8Oux;84qDy`a#VTPA$8i6vMj*47Lp7M zn!7~Vj90s)m1-nm)eXu)viQ_V*|%d)3p~cs7I}F@P+gj@r1P4*g<)x?ax4A}_*fNLV#5YmH^Ekif2vOU-YKmpYEYA_fX6r!n!YFeF$A~|=mx$-C zzJ$~~1Iicm;i-gImq@ip`crYZX7x64@Txf=p#z;DzdE#1lrpMj%T-Si#aG(XWEB016YG?@E^F<3JuL{<45>&%AQfc z9r_Iiv*+;N>r*&~&*}CpIQ7afH9oBoECjC;;Ls$j9U4`@@9)*Z8=5{P6c^7f_5~-m zff_+XU0Q%CSeRQRwUc}Xjzo(eoQ(30fLtAQkR!@$@4I9P?`X0a^h~u3RzE-5WK6nt zO}nn60x{AL)qLByNayc6AEbb{vh6IYmQX>j%&_$L4?nIjPx5{WS%>vMOKw=SXpZRT zcoG-EYln4%*mG(c*a=U+m)4nT1fF+ak>0sBCYYKB=40ke=ci&NYRS=XN7BD9|6yT1 zUVEKo_Zl&2FJE;-H_Xpz8ZFYYzR)rBLYT-~2hh=)%@w}0pveA|?(fmWNKtyPtCXEO zc9gCW(&Q1f02`NTXpf*@*QSsg$zaPOpDl;1`4*9M4{qbTGX+zvz!W@iasrFg3vlP@ zJ$vK$u41>0tm<)}R5<+Zi-!>93@OeDlthq|(Z-bi6}GR3@gs)V((iUgfglph6J1{- zf?xsbv!0_GGiGV+Q~z1xHu$|ZSsCg?N#aDHr}ef!`)`5(A|`-6Uo+{i8l@}vL0KfW z*YFuWs7lnWc*}~cD}2j}s#|&H&|fiBllz&dNPMdf4DL~*=$8G(4z0=iiycO<@|Y3- z|9|d&f;+@FV`YuVYckCqE%38bQCU%^a(14xh1i(MTK?RB2t^x!?_u1P%LJcv@8)#?%*-nV#7v}{ z=*-N@*3b|T5V+{AKMWB4^$#RygX4&eIHGX!mdy_&SkvQ#i893y&7HA1t>SGCYWw7f zL%i&2}Ve-iXuv+yGzl2F&!m9s-hhM^^FQLkpP~$)0;g^v5OQ`Xm@bF7W{UucY z5~_a*oBtCYehCl1gkxXAq%UF8myr5PsPZLLi8gJm`VTnv1swYVCVc^^zkpvmPgJ5y z0Pdi-GHzJw}YLbd;dV_!m*FX8_&d(Fo}-cWpNDDDM=$CUMvnjgJVXjgLf<*C$|+ThjIkg44cK%wH;#FO|ucY7!^JE`t+MKb13k zm(9_io{o7KREAmHq0&U|fMYV#_v;N1^D_RsY>r>3qc7Ca7iz*Dq$F)0q&;o_RF0W^ zWfx#@VCiiPjYr|g9KeF&;V^$UZZjubg)l#+({*R4Fz;%rT>BhLOzE&c9vnYO97=+8ZiJ zX@rsRlokjAVTIV?5cG<9B8uMs+z$AB^0WoPp*X8qXfeLl(&!#1FmpPW2YN<>e_oF` zhuPGtk=}n~FJzlA^ueC+IkYsRYcpq#sk2T8)#EymY8PffgcIe zy4a%@V)fJ}U;0uUkO2&kdiz{c?>MY)E)a{P}JNe-P@Sz2#1l zjZ>9>wiM8ae=Mq!+yjK2y^!xi5kB6Jf-*fq@%ZAiuY39|YWB_TFL%=qX6>s}DyKc2 zZi+_$>FAu)N}%+w?_-5|>5n*M49Ol3I2kIgdJPNxB7YQPvJD&H5Urefukc#JVX0a5 z%Y*`d=Bac+#dWAiF6f<+$(vy=Ncq)kcmCLoAtb%vi;$HONmiCqtCp32prJ!bZjYp? zsN_IiJKJN@FB>1JABzCb`SY26R~{bYFTL9G}VB3apPkc zfTE{bH3}})goJ9an#(VAbf3AcI8`C6+hx3Q#QLAteYLy0e>ayqFTAz4?;XYi;OB|p zQOz+VOHtYeb8q)nc}Dk*twumPq)pJkPsn8Jvo7-FA)qpdm z`byM20gA=L?po6n(8Km@&EG7w80HG2jWCh^Q?$%guCNWpEIB_7gy~_{3WJZ;f`U!f zjKs!w9rTw9j@2NCq9+xRQeYeKc!#NIT>kr{B2rwiVz0H^NkxM!P`(F=L}ZSPY#7YB z5IV8tz){BScZaTn*sg&7eGPTs2VnSj$KMa%V~<%j&gMN(3^;zoLjvFxj#2)Z4#_qI zwVI(nTz(hMMewEueg}o1%b%(E)^NdKo%wHpMXO=7(*Aq_)GXtg6|@T5cLGZfO&*QR z5n~ymv3?k)Hih}9Uy!?Wg2eqX&sA=8v5nNyMMvxIg3EG9S4*+%zEJBo50EfFmo<0) z!&^r%Y#I}Tr$sDm91|nal7|vgbXvbYu+Y4;>AO}|U&Xy;Bl^OUtzDnSKvN}sR#>kT zQSR?9^Pe|=lg^5`CH>Cba0s;+PQq!e))ra|)V5EWM6e`okF&+z&ruzvizpZWjO;+Z z1;doYe5bE5tW?9Z_R}i;-4Cp%3Yw-^c2d-cb*RYuxBVMkHGgI~+lZT=&C+2c8ZMjdH!J^K}paw(b{6!xvWdV{aa1eRXm&a(O~`G9xrkBA8R%DT>1d5{li&mdPe{b z-1K>f`6@FklU`$~=j7k?8y+ZBExfr1NgA?Ebq z`#OM~N(>9p9Ja8qc7WOR{bIG+LLR{2dx5wQscK7}rvig(#gvE(8O0^?aLPO;fcui+ zO*SlUvmvcKCVktx_yB;b0g)_!m0~nIuosj735j2xVLC~5;fe>3=aig(8BuGIm-(-}A(&l?I3Ah7ijsyxqq)j!} z#&etF+&NlFze9%xlKwhgW8D5jXwN9aJipwW5X`Mp()e03L2}=3q_{G1a`Yzk57D^E zKfgJ1DZ+x`hL`{vk=}i>e+$%9Zi6GvZghnkq{ghCf_Q zIEatknVY7S*R1WkR}|<`%~lzZmOd?l4ZTgNSC1hp+v4+>X4IwUXzpndR=rLy%1|gX z%Mz^F6iw?8#C9Fg2=l3oeb35djaYm~0yf10tropJ*mi)zY4Jv49pQ)*DUZN(VYn>~ zL$(8d!r488vRNYkH*9$(Hl*oo%z4d`Wmh3p1IbxQa6JnnoM~{nc`;1M zb#E)p9eaYAh2||`1idRV+f_u1FDK~Vk66LY zco)X`BuR4Yaap)jG+$jMSQ4A{MM^11Zo+-Z>=IV>RvQbtii|c`DLgT(qUhpeK^zdx z^eRNdYQ6FOs}@L+J2o0DDM8xqCaK)^);t)mdY2vsZBQ2pv0 zKV$)Xd6fcJv^$y-;x_H~3-)RSz6Xag6?N{USbiM!R}!-U8}T79}Ih zcp6yed=iHTU#B?a9EJ2><-&C)mxdBeGXp_chbQ?{@uY$&N-`TNgsP4-L~@|;pegZH zdy{+5<3_A7>_MLlf2{L{sMa26{h-5L_@u;cA3%-K)3f|1|C$=$6GagFhjU*(xCPO#1u`=oS1F@cbKq&7y&C6gzI z;sLutS~#A#yBFC^=LqPFwzBM0o9WRIZ6%0ncdSBqrwnOn z)m>lhtom8FX4ZIhIzkp$C0H-N84Bu5WwtvmXy;ZBf88dW9TBccBSE%J-vT(&USnyM zuL|KKD2UP)=45BEh0H6HjeNWXq(w4?iLZ_ZzQ5pa#5tFXmZ`m|YJTrBRXmC+mr*ih zmAs}#cSZd4TKJ(6Z{cHd;s(+ODScYrGO|;Xyid$wFcC#&k5R-g!QB%dTb870L5xg( zUQcQSl8~}mS1M<1dup-8+y)2}B&BdAlQZU-i)13*i03#=-HHp^N=b-ot%3o+6-iN0 z|GKZ)#)rY*8U^`pzgfLX zPG_(jrfr%m{}MX_3K<*J`OC7F!B|hB4(EPpD+d)9xiNZD;LwzGiCLy3I`RE1a;$nX z%03*`>LY5t3Ef8!|J0^h8{rT)J>s=vjK{)?mVzi||Q{}-p!jj<&^KBv{itZbD>?Z9I( zVAU*ck-~^aT3dI%G=x4qe!<30*n2>rn?2!wKjp-Dp@;Ohv z88N4Nym^>bz^n^N7HjN=`=oq=jl4DwK=LOiIl8B{2m1k`&r*p^YG@!W&pAwcxRevk zRj$D$j;k2fXbyCs?00*lm3BcblTB29my<1~pK&ZLYS$UhbiP}zUL00MXVF$9UrtO& z9^WHQ%$#wp{ETay3U#$8msGz5sWOIIbdRse3{(Ps93!#pp;TiwPSwdDFc{F4<;orlka~ za!_~tKzJKEI^5kn4aGi-T%=#hz&J-j97TjP%ZeN{Ei3-8VBvb-Ex!?M&3fL_fcr zUOS8LX0_=&oE(1~NFl;VWtc@R=Hk!d>@37cG@3p{Ge@TqR{V*9WU$X|v^^+nRI3J3M zYj~#EEIIEBl>}R75`O#vV%nX$urE1~O^Fi!PDF#ueE?k;FF`oa7@~t}cjVSDa~$=? z(#-{Ai7D$zI3Kw~!<}vU`?Bp_Ga; ze!u+=tGyw^VF!WNKR1|Ifn}4kr_u6R9zxP(x$C8H(hawU9f$VrZitrcYBPL~SXui+ zA2o-p@>kT)C6RlHwI-tg|Anj^C`ea_G8!JN3wbI+QWfRc(mNw$4PvPkomRl$r+ zz)~k-hSwjVA-`)TRonL*wZcWkm2aRoYj)h>;~z)zBDP6~^NyN_xs)O;i!ZH_pJ+h( z_Q74(8PR&mOW}k*SGIB+dP5%cBF-SB1J82*=*vMjBm!@iwQ8V?+icm_!}-K5*mwIl zWvp{^wk8??AR@g~jcV^}kWjGElN8L+j43E(wp;mnBBU?GS(ECHn7!I>IN}KR?35B7 zrO7}-bJiiNIP4k`VboS+npY8xtH`~qWZJt+c3=hg5=TDP0?TVbg1pNPvbC@f?J;M4 z&-g>bvtZDXtI>$QOG{2smtxQ97{6wgHQl`FG+Q53+zNztG#s?$gv}?NU%?DVR(7>ox3vWg<9gPDTis7I zo#&gO{d;h=cOo@k?L!UVPF>69uGgTHrV#>u;;2j4TOF?G4f-$z=P4`W}F z(@OaVJ-`_k6}wnCm}YEdX%T*3Nvu=@SA4C-%)${$J2%+G7|iI`Hm$ntR;G?+YL`&o z!rHT418v@P?U>y!9eBaaE!i4sIVfix!^)ZhVZqZ*UGqm57RBSmNPIltClL~fzmEc1 zwfOzTW6BsVZen`WwySOjp}&5CC0!a#tqi?q-}u{MlPq-t&Yw?Ty_}Ju)CEHu2yS?j zNPf&McreP280=3XyQHk}ooGxj?>bQ*wJFHfP9%&$3ooYYqF~X4`^vxb>4e`y`Y-o* zBYxEHGT})c(N=7o{JO5(5?UUv!DwyZtje4W|Is10@ppcY>>-7sYtGsm)c1$X(;{pn z0ZtSc%VPSiykoI^*~JRCD+a17HWoU5HdZNJ#WRRW!%YnyTh%w&Q3t^j#iPIkV@>=V z%p2tNWtM}E$Tp-6Gw06Od7s4Ok9G={$wHF_>&3TdVV;n=`lcu+kScqz`VAt0xnaDi zVhu#ksOe?;X;#Bjk|e>-^$0IhT63d?I!M~N?@b=`IO=^0T*n|v$y28qIel0(h4B_I zvDc8=7imV~JU1lX=m{oY0?+p0d6f+_U$98cPv1ULCL{$pPr9_b$$Rt(cW0>IEVTb8mj{*Q&! zBvO0M<5C$)Dmu#N@}o%)_iro)1&yD{icR85h3eqvf3TaQz$<-0h&v_#__~sm%QE>H zH+C2VVv8Vi&!EHEP{MhlTN*(Eag;##ClDM@7`;GkIo+^z+$DluCnj|PDbDF9cUr_4 zN#*YlBp3wcjqt_t^3@#Gf|l53+Q?3k(l4^cO^W2qWCsf{II9eNd{E`!lf3Qhkn%KL zz9}S$-27r<57Hfov9+fFH@b>F>tQY%_5%qtc@Bbq`Vfa1c}Y<@1}aLR1syfBRZ`~J zacZM86{IM|3u>r=OK%EwQ4yr^K9Tj7EV)X8<&be4IK%rs{gRs#7#3{3!-iGKK)~a& zayMlfe#H{KJGpbZC!{p3OtR{4q=G8fYRlQj?^?WQzR_^#6YyJrhARQT-C1jLu81M) zCA+#&JpR2fx9a8Uh^zB&C~W)ft6BWAKeuH9b(-FDJ08)m0)2A7bHc|Io3U z7EiL5LrJqqw4K1t;RXfK9~Y$C69~Hp_FoJnlZ+db)j9F3^}0hbppq5xRv5+B^(f}a zlBu2P)g%xX&5rT_mAx&By2uPszaA;iYP5rV`PT%^uw>M4#6c#6(1FBJ#|VcAc&=2% zr^zO2hMQ{b8f$bm6beH`RV?x=!M@EJdl=0NL{{O|eV3hbeua}&0Z*rXmhrDUlp@!+ zN0^hPYroB)sS)9Q8p*+AGLgK9dc$g8!a#~vihe<~#-5l01{-!?cMF@okK|xlMcCOe z^5I$!BEI2*BEhQh_+Lj_CcTG&G#Ct{fx6H<6%b++V)CHm>T&Le`Kq8Uy2I$M4@%-{g&>Hx~W#gxBJ&lRiM>Y2j9x> z+zU2!8~Pf!i*8mqlPyb>notY}M@aYqxpn6&yEd99DsseU*L7klL&GJ(oSYo1kz5SZ zp1|T4m)uTMqe3zGsVSNt9j1{=3tI6qcMk(RjBpCS&q`Z1uw1_Tqscp>Tr!*uF|Y31 z!uIS4h`-i?oBtu_0dFoMT|12}207H$@IP7j2vGq_5h1dhmbZzZA#}Z2ik4BT;gYJs z=?_XzL>=-n`S%%BS7u>d{V+7JVwq88sC~?JY%%bo#HRL!{3{RzDo@n=(;0NQz!t#f zi+-*n!lU>X3J+ZBgcYR+OIo+|ZMu7S>a2<@fj@C^odzf8r!-&3HH8+$+mshI-3&%` zs=)%B>r^3j7N}CpYe?=}0wGHULh1@IYi1W^Jb2n(LQ58`uPjayd7=_4P)aG5B!mX17}7ABSUH;O*wXH3bENdPWBq`gZ3u8LMip8HdbK6IeR@jH7b0dDUe zWDw{li)+adBx|qJ=@15e=-Bda3!4f|qp~66{)NfFdG+vW{TTnO{cfYi#y88$^wNfL zmoM$Sy0&)neT2?hx44S?rgpRRH{Feq2-f0;s(N6ND5V(OU{Sk$`RLD?-NwW_aHY(J z+d?*?GCV1It1kL*)qZ{5knxzDDP3E0XE|KD5=>Ct?Y<;j$;$UKLMvK!nE$sNmVkV6 z7I_kr57$+w^4Xb-2m7GaS%0fo5k{5H$Z&ik&!GdlxDQu91g}^}@ z6!|qVWUQa(XDT~`2nrrnd>a>Y{7b_^&{=+KF$3T<4*&PqRg!n2OYQuEZxQ@E+ z*ZGtY`uVjKl6sw_;lp&i0%qCvF@Y(8&CaQ!DTu`aa;P7>|Ry1ZKCERfui6>F!&qt-i#nT zQ;Q9E9t^>Ykb4+R1Y_UkA+VqeFs6|iRHRs&zWkQ)& zs7yL2OK*D}oIE^tC9;DN4SIE8UjPrVy{PCHS!tsnny3QB84KA))RQ6+mQLfVCEihJs*7iq45iQYx za5xEM8RsoDugC}n8gFGlsRwkacQ_J>CEriMX57+!R_@1nE1gLVe`H zw7&D`7(+S_2cOk->Jv-Qg>vY+u8S$K?^W>S**-^-U>G0(+%uddFC2f#{)sRre{@i@ zqCa^&9;|LmGUcRW91#H@)X1xB9OYBqMBGV$C_xuU;OYG4d0BuGS=d-j}98)TZ+} zw2>BKz1}{aBrbeZPAhw2=w2Y8afVIGfI;*5-xQMhXJ(H!UcIc2$A8sc5QCk0X|s?= zKKftd;5sAal9+$8V$H|An;MSx25CwSpLJ$?#5Vx%=-Wc^(K!0Z)y9I=amvrs^t#J2 z!NTE1*DVSLLd(}tu^bc}_P>EG0Rukfsl^Fmta3P+70L*g_eC9unPzWr;D{2@87p{e zwuQzF%v4=CWK>GAyspK};>I{=MWQuw#+2D(di&W3B}nS9ZZ@^+e%ikhoZ_}0Xk2;b zOm%=npSc99vRhYduRV&>DJ%<)#-5zC<#S)#9=?2jkMKdYQcCjusM359B^--rs`$NA z((Dmb7Qcf>V@*BeILD0ehy1yM%KP5A>Xsduy;jbinN`vU`z0>G8qfD?_!9UT+Jhhx zW*~c|fx(~=IQ7~2VvG8mG0;X@?Tu0)dIDtHs{bQ%?HSF|ywXr*)Et<4RJpZPe9l;) zR1}X^I#Y#EufM#NzzEAacs`*|Wu)86-nzVD%EK#q(t$$3%#$=DPHxEfAkIDk)&yLi@`X5HYd57AhZYg87E;{-OyjdcSC$ZC{q%$7J;{c0jL;8 zEs@tOhhDP(?X>uL&}utbK|JgHpv@aUrhjulrI8Y>xmmWb=d7N!<}bb+u}D7d5$02- zskz3-AKyrtf5Z8<3I&;!y=%dpU$pPEz3Q{FZ;V8n_;9hku}NvoXMt>!ani{6hi z&3Si>a~7*<`rdk#@-w#jew-D9TeF!9-7>GK%E@upB(J+x?dKqEk>qakEpTu~@z!c) zqHLIkNNmmr0X?;`i(%E}AI&9=~P`RiN{b~X;Sx9L3 zE}WOh1w*%XT#%(!^s)Ii2U9XF2yxXkp#3H{DYa-*$6}T%8%w=xKR+2g%dLOob-v8h zREsRq4$Mf!g_*)Q91^N>03wUByk(hwda6-vLFA29N7UVu#H7>(NVM!owMEgMlGHmW zUlLr(@{22C>Hd~9Hf38Wc` zCZQFO!feONrY(5ckge5>R{o0T9B)!JB`2SiY9FlTC`V~9`RnEcI9ZJ^a)>uM;|em= zXQI6(+6vwbJFtqgp{t(U#cvj?lvtJ|ThCYDKmE0iMc`pVxiCco zd3K9Wj!c|d{clVhPW;MSaZnBjCp?9()ojTc@E^{ zmPCpYN!$KXClZlH4gPT*v`XQ~2&yUv8wvTR@_5CR&V0NR03FY@&qYZe#bZW6@wi;E zsnajzmXhq$U)VGBz%f?@e|vl!Do{cjSS(Piv55J5Fxq=eY_E+g(z-VqvFrrYBiZt0 zod4j^r-gR33nqRK$694$i)Vd*tt)&n+hS>OSMEq!=*Us{na=2}qKagh>nbvH9vpfq zEl^94O;YMY8 z7rHbq%o=^*g&f8VEQ%X!40dvQyFtz_TJg%qZa0W|WU4f}EcPpZRlz*JNAn@h(;beN z6);t+YUWrndlQSF@h1%(qgFPI8|NlC=E>t~XnU1xwUMffF{QF4o2zu2X$Bzsz86_z z5=kKg$o8A1yRT~RI?KR01(qQ4x^bzrZ> z++V>97jx$`d+H8u0qIU&=yo)lFw0{BSEkSu`?7*mo!{MXG`#sdc*mxET)HY*)XR8 z>wxY;`V0&1miM!FeQ*1ZrKgq$!>H>*e!9{mI~`QTJKpm!NO5F~t_8=YS{Ni_p>Rit zrzLg$3^qtl(KdIA)2*(dTEfgEAxF}*)@H?Y7TCI zsg9ZN7sA?5Sba~czNpdhZBxQ9#+(R;7R6{ebnQl47mAw#vJMeTzQL&qe9N9c5XXunze6!EIz@cW|{Cid(QV^ucv8d z(?(9zd|Bg>6vLd>Kl7#4E91%XMb(Ia9diamv6f7zoa~qv868)_GHOe)^!@i*@Z};L zRoDYRR2spL-^kECnp2d&rp3I-I=J-~+9qKfGaZ@=+7nkZJH434G3y;yT@*62+^Y=x zp-jv`am!2#YYly&2qbF@Yb1Szq@kij^hSGIvR#}l>#^Llhr@@E5sLTfkdGdLF@^WS zh_T1~f>~cX22XB2b6b~^0G~u313x(vTSHv8&{$_49lT#V?Q$7L7h;q{L*WyA9aS#+a zn@CTjLe#AN)jqwt2LeDb&hyrJ~zeT4wIOBQ4$)eJjrzt3+%#L_f#G)VRvz+2vtk93O%3VLs zPL-V32&uzvPQYsI#W*h`0L3xH%=Mt@^tT}iCBe+QNJ{rw0Poz8uhKM>>)bEFyv)t- z37OF0t(VG-WaJO5ba%))G7pP3Ig|FQDV_bIO&GtvCAD!>7YpHBmQcB&R1~PMZMB$N-qZ7M^QrZvM!2~K?OI2AXvc3#_6yU~-Ij2j-KL2}%rU^gs^$!q&ik|i3_4Fhru%iI9nI2;}NObGp5A)a{4kZ(b2*F&fPfS2cC*R*ne6YRlWMFaR%3uAlx6x*Y&RtW<2R@># z9hH69HM!@0oH?!SM@zJTGi0;N~_bBJgy(ckO zKO=Mx%E=j?026IkFInZc4z9eqOz<&SeI^O~NqIl+c&}A@sM^we=3+3XIUI+`d3qwk zGSa~@dH^CiIm%$}UkpmWyA^=YFuf~)>g?mCs$Vv?ZCsf`+Vg1*Sy+x_bVH9%Wk5KN z9RJX2Eplj3W_MqlyFw+HaU7dDtANuy8{T(?mK2-JQ&d-SIA~Dz)|{B;H3mU z6GxzR*GaMT=AezuOn6UfvLUdEPmK>hQr67li^Fu(p*oIJ4r!7#@LRO{yD2`w)uWRT znR|!lUO}WVG=|z}G8fr6LE;+7#zV@F&AM?+QzkYv1=Vn9MRoeo230Z;24go%0r2B>d{v){|KF5?Od2K zhmEy36={|el~TY%fNw?a*VKIZ%j{dBN_j5Ej`$N)(F6xp3`#CQ-9??;cd6x@3ooGF~Ep0s0+gWg-vG#lQlb2vo<;h)E_FiV_q%r z2O3*E{ru-qt))v&b&WcFeTOjPL!$Q?+-F_iU)!y&Sz6xL-219k2KY$8iIlI4 zi-Ib~7#2T&qGIX%vGmzq;U7dO$5k5txUx6z$3*Os;k<_#tdIT9Rkp@Jb%Qdo1jy@%;PzKl5l6GU(5S(6 zS*YNnu3NFvNg^Pi4UCseM)FL}z&qCxA5B9;qfU$(X2^j)3gtitMNTu+Ve+v$9-tFJRFv)KKt19r=)w9q7$FtD6UpxsX0t^7uFHy-E zOqaA|oO@$=@AGh#zO5-9t9t+94dW127Gt6Oy0?3)m<%HIwlPe;YBL3`rV6>Naf@52 zC0nhA%~AS*bZNL}w{?)nJiu|_$en*GFaPeDK9BVC*P2qX->n-tT|uq%jFV(gHl=xI zcqYW(0$owO-55Ci9BcSB$5o*Huc7MNp?Zi|hbV%cq<{5ctAcge~U zcrhmrPY|nIQH`#ofAT(G1JPv8$ySw*3WPQ~X7#$d-;gK%`U^9F-8z4*4W{ItTM7;O;hzT&2jGc2to@4=yuXGs>dl3S44S2NRLcGOGOfWa2n?r)WT7CR-OI?mz#jjX+ z-pstQH3z3&PPGvIZ4-G)RQBVs3!`j#yr<~cV9L5}o#|^juca}(9&mfw3r!RUjZ4L- zG0rphCSJB$G@B6w{BBMI?uq`3VyQb#j>VuGq+C{%b$|XJ07gK$zj?mAseiBU`Uxlx z9fO|yH@O`*-3wsut{F9Jk;4e}qm8|J(04$L(k zrk}Lj4n-UfaRH_J&BMv;0U`bDtIF0Nx!U?k91rOa?)$9CK2)eO!3Lk)_o;`=&Tcoj zPWOaQ3|FbEtiy3@<}nA`Y=5cCa}yEkTxE!ngl1)YWsw~I%HFI?pJVf|Ta0`AWa%oq z^U1W{GiEdzI6aT6q1DS6%0GK|Jml($)5tt6O>rx|)QTC+?lKQL;+B{vHCZ}7&xCO5 zl2HfKfUiQxuRIj<$vI{Wi|)hOpa@w zEO{7h#%D8U_o*C?oykp+&GJH?3(J!Va(dM~v?SIKnRJg~Aj+pf^#V30FaSxxwMBu- zt}NY{S+j&aAC1OiWe0<}`}~9M{hc%)fnQVlWO~R+D%AwIr&8kNNIAJj_TP~Ju)SGF zOp=IeqZGy5(uX)dC4Z+{Tw{wxQ&11k)DJu_mkR*FeLzr_t_qIZbyc3U*&vz;6hl8r z7x|63Q%I7ZsZe~6wGG&X)3?GovFhOCz>0Mom{3lf8n6qeZ-sMH%E1-=X;(}RkOtM% zid0cf&G;MDlU~$nu5=(9Mkl=LDo6)jr_DCNuzG9U(K25M1Ah&(Sa-Bs!7^>NT(&DF zDFT9D+tr)Y@6$+dR&^NZhm6&|wF|0Ex>TFks~yGzy;{{>l2)k5`RMLWQsTBsNfROi zP;PfmmoaTojBkJkU3v05^e@46tg`J~R$o@_D z-iaE#xY2v=ok(Iz(xrEryeAju(=MDB`5JOdBeD$GW784C-hc9y18HZ&e#mJV;*a~_jc2f^@DR;644Y$wKyvFyI9ho|F zq%4Coc(zP!51Xr=nw}9iE}@By9$U}V#dOM~at38mp3c5e1N%nG0X8yb?6=sp86=*_ z-WAn)-+%EYy@2=l2Yt7_zFK9uNEMd+NJ~PbOj+HkPe!xDK|}Xz?v3|y)K$!Zv3Y22 z)RCLX#_E@JV@$M`-!!+jIV7S~R{3669wcMCd$rB();DAi<8Wew&(H6G?2=BTdHDrbg3y#90*Uw=i@`|uwWjG;8od;vx4@_451)p330ku{T- zSK2~?$8JUe@_+Sx4g5ESslzLe zv3r2YTA0oL%@;zEcT-CV#<2Qeczwp2* z1&%`w2S6?@U;icBB(s(lWn=g)KzR)lrX@9go z2tQe3-9ZdBnDQ&pS;sYc!#HrDX;j7~IGW+@w)0{=|M}$=?qEamQ(|j+-V?+Ce?MWL z1X;->TuCH|o;<7TWogLjyBm)P@yn~QA4A7@RCVH?*iRk?9{t1a&C4si;Rf>>_y^`N zQ1ZqT3yDB2XZ+JN=pn!}ubgK^{(m&=d4Bi|z|mj#mg}Mbu{<7dFaL8Ktia=!S6_#S zHXILDc$(-o38AWC&`&)-8u!x*|M7fGxbp$vHt>7^@$2Nuuc22y!Qm4mG@T%!-~zGDc3?`xkfH+xAnhYYs5$q@nS%m2Wap0^DEF}qonh)> z2d#!_a2sPEr7?6|R7H{Jr}3RXNJ$6B*uf;J@+rj1$09x{gGo>ZA)pK`0vY7bisV5* zMkrH3P+&ij5B3}CfWGX~m4BZTwm)V+?zYSI%?16)%Y9^BIRGt~4sXLj;*BHV?ZETL zg&(D3C?1cBFu_3?M@5u|K)~P@@<)&tCy<{Ga8!oj5WYhgez(vqEGvSvm<(DdtKlfP9SyLi1SDY)Rs+xm@O=kbeSq2_#lJ_G7NL~H1MF(-V3Ilj zA&EfDMo@Sh6Cp{cuzw{)WKv=#(qVM#k0R72SWP;v02ph8R4)QF5f~xRJ~0rL#KeLi zK~VONQUMeKT~MIH@`Lc**8^gS6A2Pk2njEKD&;dcTV9_TlqGhxk0 zLac`a7CyEtDqyexJxRPu2Lbs5zM+jCfWi2P7;)6jk-?Be1b=Okkjlp7ZyQ6@9-@lxAvc)5V_3vN4`d@$i&u_l` z>tC*}l^N{y3-3?=WhwBd|1t{LRuN=s*nNR3o)7cee}D1x|6m+5^f&8jb%ePs9oDO= z+Lx0TFKB9izT3Pgj&q;>`GU;Oue>Td+~hE%U(JdPb&iRiR3XpI>to7Svi4jbHm|co z&RW(L4=%^KYNaKF7J5Ro&=anOo)9hcL};NWiWYj(fRo^rb<~p<9o2@6AS7CB@$v~Z znc*%_HbVQFz@!p=fC4}VU^rny5sz*$Cq~;jjBlCCiGL)8&miCf;HjsH^)n*RS2@HT>32;$>0BApA zp-5s{k3R~D$Ba}U1xUaM`!qp10U=b4?l<5<(jyPuW2hI}4?aT@q2~Z>2R#&f@C7U) znFRpehB2b0C1a0r7Mo1m9IT1d7D7qLDUeF23F@OXLT*7?0LjQ^Y!mg3M!?WpoB;$L zWqG){^FVV8-76sP50|Bn)U7pS7t2|463eS+z=)BFRr|fLzF+LBovlK z`+$yh>Lk#SXX_-qwS^0)kEWTvL=C&l=D(>X=FN|jTQW%q2Xu)kBK8{RAmb_w$$Vmj zX=7rn#~{Tc@+*l%77kyWouGy0UpV+lrhh*ev4Xxp;me49UK@z~SdhT}hy(-yAjN1Y zf^5w3k7<=0p+|_|zX_=%3uuQqK*h^S_*fN`3s~#BuScU1#D!D`G!KdY6OpNvKYu`@ zfXfBp2o!M`(**&du5o$=x!9&#TtI?J6;2|DVTA=pQ8lI=6GH1y0guS!pUe^?tc?8; zB_y9@lMRyGz86z8kw(Q z;QypYW2`0NGs4>#C%veAk$Iqvv43f?7mw&%vZAXU!vb)DPKHX6|43p?W~rpl@RL{| zG(w zpJ`h!6X>sBn*r+SoJi%9pYdjgD8YiOb64r2!C;z1hQ92 z6w+A<8KqoRMPvygMrR>P06NB%_aFphxZL1Vg-E6+WatbibPPxaq8Q2@4uyz~FQ2T$ z5G?{F3C@Hp(k7@bLIRDzP(M~*fieJkfWWbRT|%BXxWtG^jlKKx>bO6n)4xIZkFdMR z-b@&T;Kl_bT$H_yybye^2!GTW{6kli!iu<~$W)?BqLArG_#c;Clej{6IHIdg&?krs zvHsmKGm6V>@Xrbq+eq1W@uiIywtbU|?Hg(LM%uhdmF=H;_lNG= zjG_V;^~p9@4El@Ml|jl^`66msqm&p=)Y>Z_=_N1$%lF3AJVrzUhkv-5M`%KrI!7;1`|#I2E?KOheGuHQ*eG!6$hY;ahjc8E~5JE+d8AQN$~uTFV+<*u8t!7IW6!J z3h^MNC_oBslYj^TGw7&zMhRIS0iL4;1BH^V;%MXsWRgZCi_Y#MoO{IydJJSal}wIk zIRb~4a|KcY5;H`30e=M+p#wGWuu|M#g6sjPsDy~qkSwC24}+qT4w)cM$U~jV%12bfx4g1~DI|xG4&Hl8nh<6@^Iw zBmyEB5J*shQV4@0g1?8jt{v1Xa4l<1X@|9@mPN1h%$24yMt=j9`4W3K{YfzYS{U)><(QSCd#=DIIqFlLZtrzjrfVA{|xU9wQ2JfGC zHTPd3_(v!)sq9fw2aWn%#5H5Hbn2k_)UYyFFH&5+q2}scxGAzq(gul1TO&&>26>>rt1-6+P^L-Y3uZ8Gw&oJ6ZSfqQM;zx~PSesEG+sSQ2M24Xp8~k59f^pd3fDqD0LeRa!@R3iSe6cS1A=us4JLI>= zysYxYlV?583ja4~LYaFEEuN^Xi}$fqjgSnjXMaXU2t&W>DOgGBuVhl_? z40$}{i1gnU`OWn6i!ifsJOBCBas7(A`7Kie=@iSB1}6LpiW5t0nKO{fi;#oI>%Hpj zK7U8=FrWWC+r5$M{`;3#vRBH|ke*l78)*LDx0vLuwT&5QEk(~=)w=aBpq2FG`3v>T zJSOpXG4XHt9KLeu=1R>YXTa+dJ=OyOYMfy;PYq=%A!qk5|Au9+6ign)#}D(X*gfrW z02?KEIDfspQL_%a*J=VrY1l0MFw#&+3LJN49P9g>g*d8@8Ci}bNLs#bFJ1(CMPz_K zhjWwURUk6znIhD$%zTt?Dwuk=8Kj?n&J?Mn40Q zZ|Zullan@9B{FYy_U9x~YNSb+pDh;9KKT_R*>acpTr}EfEYqTnf3PzYq-hy zKoZ>;zI+jVEuAuShkty*KKUgsganL}p5bIB)ps5 z0+k*KbWIVFg7`()0YdwBGlSudZ21omhcD-oFIYqh@2=Q_=B&u(Ki89eSXY13Cx4Dc zPsH?zQ37(n?~OqR;B*34nY=qPn^=*5ao*x(FjY%oHii=uU;|8o$npmH_XpnK-;oz< zgPM4t#G~R0(i(+BF$N+@v17l#!IRPx=F18ZL8r0I=^UYM=Xb5G^u7xk8;Z>eSVMie zrA9*o)s+j;UsJ5PRS;RzcG^+@ntLm}{_ksz4z zMRxf4n>_n7zK`ML%jE;Y;7lB;tRcL>uOEo7dv*PT$*RwH2bl8wV6uN9df$AgX#hPI z27%BY^8kOYoKva+X%LdgjB{^RW zf*vdI**NHp1FnGvK|g;GS?_FY{7zwxtzF;Q+Vv>RyofoZEj?t>S0msHVULY9kV*5t zq9ve!!W)6d#+C2=Hm(qekBBYMke(_sHi-#PVwk`f@)B}+X%d%K#(ekDF{Tz6zd>T~ zjD-*x-zGDmC*ji9AyvI3)Y2lrA4L_lDUow|*T%ZbIhQ1Ty!?Nf!gQGM#HM6Ik0yIx z5$GO+{tN(96r|c2lCzzvs7(`nG|Zvxpd4z`Fy2=Ly2lu*@h0?WF3o)BQb(=Y=wp)` zNo*{piKKF&vC2%yWu{4F+8FcQN5vRLXxeqmSALV+1Z-s51xHm#LLbr4PO?5~QAcMo zuZ4G)vo0F-19E??w;v+!nv_lGDY;*fqCHmhvn1^$f`LkwODVPJq>qF{v<-|;4uuog zG|pF~WRDh9*h4cIN|$14(@P(h0IBlhuvKy-*xsM6y%ijSsv zzVaOc6tdy!kRU}v1+PMLDTwQ+px+{80B{~7gBDH(kEMU96m~>oN!xq{Zd22=jBun$ zcs`~^E8?THS(c5jh-C|0s-&&O0P*qlv&E{=ZWg`VG?{AcX6syX z87vah)iZzGPZcqZAsKWHu-RPZ0*!heNqBpa5;Y3&>ww5R(3R4a+fl00m0VrhsS3^` zYsiQiFp{EHf(8RZ&@fO5f|i7VouV^I8Z(j-Mp8SEMs&S0wUMOIRMYi^c;?QrJ>*Hx zAc9x~8g6Eie6hLOA2_!LqM#Sy4$rU`4%z-d7~+3Nf=iwuO=?>CcB5r@eSz2)m@h^g zk@In!Ua}~=0%UiH6;Hs^q<4;O3p+}V(`UruE&#=aNXc(EO1>@~hIBIohU)cmu}ZJ! zMkvF+ksZ%@cyy8xmj;- zyjd4^;CqV{-Sc{fYZl;-7$%loZ-;PsU#F8}T{H(b>k`k!JhzjcT`&=NZmu>qc@#g8 z^^hMrx)bl3liyt(0lSm^U2%UOKq+_!Bua2O9FAHwgVLh2#-jfL2VU{6soI`gJxx>|Wsu zjpB^J29uN%-1;fj8f6`3Tm{hshR>?4hwml6DakK((wiD`e5CQ!o40@O$f^ALd@^?U z50J%s{N^w#5Ols-Ku7)CU%~Y(S5tb7m$9{ekY}`iV=r*+D(j&CWVY ztl-CuNqYH;oCGPatfj~`BYv{GKJ0uhTUwa%gr3V1+^Ac`4~fgioC&=i`M0i%i=^~` z3H~3`-&azYK6Y>!h!TH|WM^T%V;r3{0qY^@uo4P`FTz(;y6CCDE z;V(K7>KVfK$Bd21jZFhPHl6sP9xHboG=FbW_qI*yzW)WJ?ybS+@7-*E`*5jy`!P%1 z+sfodgVeqK5K^bq_^zgpy;JdEscbV4Pk#6Xr1G874?noO;az|CUeJW`-N!79?@Sf= zLxV8BdqiREXt>otA-VyN8Z5Y4k~blHeCf{Gr2Dg9K)N%dV?TTC?%3?%N;mtM#B=s=@tl3k;yE*YfifaJ5#wKK^IimlnTW4RvIjWzg*@A>dt5&J zm4%-8^MC%~tMkH6{8Hg1@ZHU0=?X4EbK62od`uA~D8+hE3HUtbZSM;?OryobC!pK8R7^u6ZX#hS5nWu-E(O-k;(TA`#?~XmU z_BnU({-5ujV34n4-t)FFEPCW03@s1;VAw8)=Mu<%3vZ6}@-}!YNVfM`ksUU5yskQ; zMx;jN8Yxk^Fvg)r{t1Txc~;$ zv(Mg}5Ml647yoz@;l~(s-&^t3QUM7uwat|+MQzT+hZGJIKP%QZTl%~?i}nGEg1>Yg z2V{)NrdXH^vEND50^7b|N==&ZP<68_Z~(%fyK+^|pKcHM2B1`#z;2&GD03ybfo6Y$ z=p)ghl%(X!#jAaGEb~SMXTBYZ8tp&x4Ajmh|9k`L>|dWalvW}uEvFhv-cyv~86Kge z2fr{-U_hTAZVb^kY7fyDwFL7VH9odB_^_0CXFj&3uQcdxmMT0LVrKJT>G|)EQ+jU5 zxj!mC2`K7dm=q(lFbRfCC(jSiM@xS|=hNSXFYzb(Q&UU8IRSQe6 z!AdizzrsxN0Hg8|-}1(4_lMmqzl>sD)K2f;FxPP=NuQXh>lL<{Tf+=b=|4;OPnEg$ zD4-3qL3MdK4A}azF1e<(+86u9qO;S^eN(|C@TR{!>^3m(hPmJ(e;N|J8ArX~P4KLP z1=QxMP0^O$pObH8L^u>;C}QV&iaw`#|I(TKI;AsuO!2%#^e%j}<~@iMbr}B?eq3@D zbd{@LSdf16IX_;X^MeR#{OgnJWh(}sUjv4}PLmvFTz?DshVm5VW0~mu;kSv-ZxbCZ z%-?)$6P+)9o9O&gOmx2a$jtosw~5Yg6P;hfMCbG0COZEd6P=Gu1Ag|~MCZ4O&inEW z&zR__M>4ye5EO6r#GgF=!1&{@b6}9?zQfVrHYA7dqKLlxFd)VbZ5n7hd=&zW<*>qJ zw6w%gP=EdqAigN&%edGd^cz741ePL&2ri0B`sCRhzQ*y6(j7#^L80$!;*q$N;!k7h zQN+aOpmc^&CBD2$0jZ1P7x|$1G@BH|@_zj#=li@ArD`}%Zb!7QhQyOWR|meS_d`B- z4*5uF4rZ`lH1(q4CT;D0v&ZL~^X}F|JB{*T$A8af!LM{dA;n{);}pFWe;9f6q3AG) z`C->MsK_bUa8!}!SI|qWhQxOrRLPinr~{C3>Xw5Tq4gPt!V$qEumhSKhLt}a<560C z)s>{Bd=AKG zh<~3LM+!c1IF5+OgPMSbk#nkH#U5Xe-+dh?i8l<<;lgvhX!Bz6s4h9Zi)JaJ6Aa>$ z-{NtqA+<9;R#?Rt#W<=Gl2OH^dBjwa6TytbUJPS3gdqYtq8LCMZzB(9Fy!>yL=uvtwjrJ_4ymOMgNKg6KNY*(;@2_) z!(Z!?9vSV*DhXFJAN3yP@QY|l0V3%ED?Et87&sE4mj35`nr5N@c6)o0g0y*BYzwz z&?tPc0wopCh{M0}@Rpo6^%5MnsfP`OqA){+Ka%mguT!v?DNdh&T*3`8o3F$aA0t!3 z1R8J=dLvX)A(DZo9*4vg#W5Tu=(FO;!}q0e(BWx#pkzP+cs^#2JYugS96x=6`wr?L zw0c8+rk;>8Y(0ver1U6yEFVQ@-G8mU?#GXwUoo1eEHc8get&%;qTF-+ zg~jA=_^(&3z@OOWW%&^ci~XK*APGygJI+^oY>;S=MQ$um|3A<&-gfu;knQn$7yg#8 zaYJ^OAF4I@W$fnDX1!RDHv=?*`4-vd(KFw*v@pLGyMpkS-;P?(<$LSua*lpSLgs}U zTM4=i+*NxRI?K6d^nv?*BYy&m)HlU0Tc8Ljm$9OJqus@FFqa{=d+FlJxkR}ZN2JOQ z6*->`|I9)B$c+wZevkPcJHXxMuC!m?Ju^auxEkAZfAv4{A_{1Y96Yzf=5=<+#R!&e zy4)1ISyr^(cKPj=%WoTTkG2u#yuV)Mn|%)c!V$!)Ys`jUDoDe(5`V3~j$jQEcU=)1 zB#>WI*ajq9585F66yHkuzj&Yq*QFh*9er$zE)4V!@~;o#w%={b^&Q&%3I&`oawU=Y zmuv&tp1iRjC;xR%!XKJBy618IzcA#5_kX=_Vdk7yv;b=-s}d=9TKNCS;opPzZO~-k zjRC;Sk`PTv8ec)J6@Ny8dGaj@w(cmYejV#jPN?RO7*qiXVKxpI>>gq*Z%LO>29VGc1AhY1Xsc8evE7xc-Rs@9 zfI*U%SDHqqg5GsLc*!J+={%Q^$W`nN@XGyS}6W_4z#d99k~8*p~*nuoc^AB*BiK&X@9ut z+zoD_AgFgfi46_@e|3p-RwB5tUFMCYwW{QQVf_6Dn%T6l^z6)-pp`#fXYTdH4<6JuQvd4=Iul?T4MZs1FhP4Y4{Zd&aLdi-mlCID_s!)?o3zG5y}#J87@|x(3Ft1c&sXsG$rvK ztW%TV;{F@yNPcQHu+~1e+Yed zXB2esnEeIm}mN>VLE;DG1r#|I{Ia zX!>!+eAhEZy0yE8|B<_KqNdYl-a8LRiyRW5Es5-UAW=h49Pd0D_hbJ9$>va4id{HN z>?z)Xu-tgx>HOC?Lt1jzUdEf&|NFP`la;0-4S8HR6Mx`FS1AI?d1J4qfqP(l-ueY$FwDUKporf9m6(;ZU9_~ zA6)4?KoJW2g8*OrK*7H12#e(&irk9+&WL_|lmaUA%k%U(-YGiA(W}1ELcgU@4FNVV z(KN1**-E_cHj);a=&kf4#ljA*=#SV=&*70*nGGK^9rpjh*Gch!zRrhgYJb*<}zB7 zhja_d3hI0IMPKW1%}N}uS&|I|D{E*s(PEnfUPZC$O5m8!uw__?{b_i<(8%MJC|zvj zk+xp@81akF41WSygS_uz%aO!Q9=T9OCy+j9(gRH zehoh`?8$_Eq&J|{UIJT)a>Je4hTvb|OgZ$GXzYe$N`I5W94~b~xk8&Z;h)YAT^xEh zaDa5&3uia-XWiz)cv0U@)UbpeVy93K5#=f$c8Zk`kyhuh1%v4{8W(uOKB+fJEe)R? z{AzV54*}8(8M?^zDXFh;g41R-ID3IJf`u{G9z#5jj>}4B=c}rg3sf{~5pivRc#(cM zTnt-M7JsH44tOiArMNjb%*v%KKyqmYQZoxuu5-@}BG4#U^!sqxwJZ#}LSluCo{=Si7ZK*N5I(d{k2#LcKhn?2H z=z=X@)U7D1`vp(UT~=h3dFBVvb^4@=YKI4yRDakT5iviluhS_r>*NinoinaP+R9{a zk62r#4$AAZ)I<@%XONscx+AF^00&k4sK7(MRO@3w4BAEw8O~$q9c3K%`;tK5D8fN5f+x%W6sb? zb-$$E0crbu6*|MRUCu)^nK0BY6ge%;BUjd033|;1 zltixQ@5{hKkBR*0)b@tAtoq5m207&YNXi*y*B?wAJLpe+&yD;*yX^~BjvoQCXcnIU z$Gkp!SkynnM%5#LlG0lJ6fzdS3mjH+I_zhHrMMp7s=6&C%H3oqW(iDwb$@Pl ze~_zQ%+0`sXppO7e>$50`S(nJG(s$f^RuZ7XIS7w^T0Dk_9S$6V@;)|idH9U#j1T0 zWfT4D;XI7|DW`<~b5FXwt4anXgik7pS6iuwH?y$;N9Mp8`x7{cSX3y3H@UvPjwnTF z@`hh8;_<@yU?9RMBr&HHsMFr-A%DN%ibzoy(jVN9Z7fx{Iht91Ik+%sO#n8zaq+CQZ%zv|N1G5VTS~}tY zjnWYmNM!pqtsk7MR9r}e|4e*MjrQXCOg|L3@Y24w6@UXwbl8+gCFm}1X@v@V$N-j zF~%Il#Uq<0wA$H1yZ?QJjaxYO=ic$!s&J50)I3gEMz6>7-2Fd zEdZn4vaoX?lomyX+=^N(@@t#yR$I*Is@Up^xS=YL(AJK@%4`4u;wt1zlIF-7!}MLWil*>hk%ZvK;vh}(F++QJpQ}NVnAd6` zZ0VeHrf1GjiriqN6JSA}UF{&tN=@h0V-FQFkl=7w#ndf6GNY@|gN|EyVB zOSGICA}BmXi2npjcGCdT9b@d&5A`hmVZ%>+Hku-O<$$Aq_I(J$O8x#zw$zpfoi9IHiQJDtMH`qzOLqUIlF@amT zVwof{O3IE~WtX7l0z2X|2A$QL2TXgT@j*(L z7=}_T9@4m3wEU=wdh@lArR1eqU4HD`i^W$m>XyYUg+K!M}AR&)%jW2*s7>Lv^IYh25d%6S|U(b{Biv$($71T2f|JH{*) zbXcvE`FSCK$67#6{^LLs*-up@@|s+6pKmv!mPTEFvUJrI-Vdj~AB|lH4IeZImRRU& z2*y-6JB#VNWEH4Abp1s9)o25#gaRjO-T0LZGY{eE%u*rNA+c2X;AO=)qtW*-oFD-B zE2QDVC2wRGO!g#aqONcGA-cN+g#ai=psh-@#~y@ck; zLZ^EcIQIKGerLjg@uL8kQR$d^hNF)Ifbk-9112k*a9+}d)OLPzCbPV-V3{R4v?JTh zy5uT)(E=11AQ2M1C57>IZA!lQuy zt3QE5CyHSGge4?5jUS=8JN*67IN@z5a@pdOWN8c7@Cw~Msu8%arEg{}3@7(W!sA|l z3>F?Q&BYI9n+qPyHVYrjwgn_xH-}_vF(gLuLAG^YP_lJv7%^@D2|wEJ1x8xsFk;*S zkzCJ3Mj`L9+>0O2K1T<-u%7iM_l4V!#+Km4(;dLL{-njy$N2GWX7tr;h!L7W zzye$ZQZfVK})mD$h?3s=9Yw;=Jt7se%6Jl4%x~yyIfE@7)Om@e6l?i!IG&^8>J>OqGeA5lA<;3CP(bPY0VIL&0#GP4e-uZQ#8(G;CNXi5aae z;*^1?cMJ{oPm|EK6t|y(!FMFVZv|F6b-N~^3+v)MM zxD`Y}Wfh7^K9OWijtyH{MvtRh>f8!uMu9&irkiQ7NS3N`H2EGd-e`!;tgB0+DheED zIb5->lSo04^IYF3tKwZopIk&C}7H~F_jbe^dbs>)UKDQ&~eM3?5t8#n&mh9Cr4sNN}lbMUY7BSGJrt6u13EL<>2b22eRSc+eOF+Ex zCjQ{P4uCo3)a^+mL%_=4Qs*xnI34wU4}G~;DwuT2UN+OOlFy06!SK-y>%!H_qN59z z@c;RL4C#M=1&5hhFkM(|<_2_KC(|GH!U{i$&(Sr2|2ux+hh0tEG_X>AqO&S}+xlZv zU)E6H^b46|9 z{0|`I{4?Luw%5|98nldgyRUN_?Py;A=`nf9sPrL!p>P3nm|``jT6)*Cl-FLFF}}I2 zF<#x;7_V-7jBjsijGu08jGu0Mj0d+hM*G&rXfHFy25NIF9<%h!Qxd6+S1d6lX;CWjjp(;` zq1bAFn6^))KPUiTU$hHwo?&iyEX z|TjKsJ3NPMdz@$LP8LE=F^5)TlG2j3Wp2l+@mP?31hC=n%7 zcO3+WRefd;V_Wh#p}gjI3P&kw=}~oH{Kr2RhhVs@g1DJgC=T5)vb{l(MsZ0cDr*