From bd7298ac0d37c0f1d5112aeffdd565ce6d055fbf Mon Sep 17 00:00:00 2001 From: Shun Hasegawa Date: Mon, 19 Dec 2022 13:48:15 +0900 Subject: [PATCH 1/6] Add ROS driver package for BL force torque sensor --- bl_force_torque_sensor_ros/CMakeLists.txt | 29 + bl_force_torque_sensor_ros/README.md | 48 ++ .../ADS131M04.cpp | 537 ++++++++++++++++++ .../ADS131M04.h | 274 +++++++++ .../sensor_driver_raw_rmd_ads131m04.ino | 105 ++++ .../rmd_ads131m04_arduino/schematic.jpg | Bin 0 -> 125105 bytes .../config/rviz/sample.rviz | 134 +++++ .../launch/sample.launch | 34 ++ .../launch/sensor_driver_rosserial.launch | 39 ++ .../msg/AmplifierOutputRawArray.msg | 5 + .../node_scripts/sensor_driver_rosserial.py | 112 ++++ bl_force_torque_sensor_ros/package.xml | 25 + bl_force_torque_sensor_ros/setup.py | 8 + 13 files changed, 1350 insertions(+) create mode 100644 bl_force_torque_sensor_ros/CMakeLists.txt create mode 100644 bl_force_torque_sensor_ros/README.md create mode 100644 bl_force_torque_sensor_ros/arduino/sensor_driver_raw_rmd_ads131m04/ADS131M04.cpp create mode 100644 bl_force_torque_sensor_ros/arduino/sensor_driver_raw_rmd_ads131m04/ADS131M04.h create mode 100644 bl_force_torque_sensor_ros/arduino/sensor_driver_raw_rmd_ads131m04/sensor_driver_raw_rmd_ads131m04.ino create mode 100644 bl_force_torque_sensor_ros/circuits/rmd_ads131m04_arduino/schematic.jpg create mode 100644 bl_force_torque_sensor_ros/config/rviz/sample.rviz create mode 100644 bl_force_torque_sensor_ros/launch/sample.launch create mode 100644 bl_force_torque_sensor_ros/launch/sensor_driver_rosserial.launch create mode 100644 bl_force_torque_sensor_ros/msg/AmplifierOutputRawArray.msg create mode 100755 bl_force_torque_sensor_ros/node_scripts/sensor_driver_rosserial.py create mode 100644 bl_force_torque_sensor_ros/package.xml create mode 100644 bl_force_torque_sensor_ros/setup.py diff --git a/bl_force_torque_sensor_ros/CMakeLists.txt b/bl_force_torque_sensor_ros/CMakeLists.txt new file mode 100644 index 000000000..2da295e3d --- /dev/null +++ b/bl_force_torque_sensor_ros/CMakeLists.txt @@ -0,0 +1,29 @@ +cmake_minimum_required(VERSION 2.8.3) +project(bl_force_torque_sensor_ros) + +find_package(catkin REQUIRED COMPONENTS + message_generation +) + +catkin_python_setup() + +add_message_files( + FILES + AmplifierOutputRawArray.msg +) + +generate_messages() + +catkin_package( + CATKIN_DEPENDS message_runtime +) + +file(GLOB SCRIPT_PROGRAMS node_scripts/*.py) +catkin_install_python(PROGRAMS ${SCRIPT_PROGRAMS} + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/node_scripts +) + +install(DIRECTORY arduino circuits config launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + USE_SOURCE_PERMISSIONS +) diff --git a/bl_force_torque_sensor_ros/README.md b/bl_force_torque_sensor_ros/README.md new file mode 100644 index 000000000..f875e60fc --- /dev/null +++ b/bl_force_torque_sensor_ros/README.md @@ -0,0 +1,48 @@ +# bl_force_torque_sensor_ros + +ROS driver package for [BL force torque sensor](https://www.bl-autotec.co.jp/products/index.php?cid=5). + +## Circuit + +Before using this package, you have to prepare a circuit connecting your sensor and PC. + +### Circuit using Arduino and [ADS131M04](https://www.ti.com/product/ADS131M04) as ADC for sensor with RMD amplifier + +![](circuits/rmd_ads131m04_arduino/schematic.jpg) + +## How to install + +- Install dependency of `bl_force_torque_sensor_ros` (e.g., by `rosdep install`) and build `bl_force_torque_sensor_ros` (e.g., by `catkin build`) + - See http://wiki.ros.org/rosdep#Install_dependency_of_all_packages_in_the_workspace for `rosdep` usage + +- If you prepare a circuit using Arduino, + - [Setup Arduino IDE for rosserial](http://wiki.ros.org/rosserial_arduino/Tutorials/Arduino%20IDE%20Setup#Install_ros_lib_into_the_Arduino_Environment). Note that you must do it after sourcing `setup.bash` of the workspace including `bl_force_torque_sensor_ros`. If you did it without sourcing correctly, do it again + - Upload corresponding firmware to your Arduino. E.g., upload `arduino/sensor_driver_raw_rmd_ads131m04/sensor_driver_raw_rmd_ads131m04.ino` when your circuit uses ADS131M04 for RMD amplifier + - The firmware may require additional libraries + - `sensor_driver_raw_rmd_ads131m04.ino`: search and install [CRC](https://www.arduino.cc/reference/en/libraries/crc/) on library manager of Arduino IDE + +## How to use + +To run sample, you have to specify the calibration matrix of your sensor. +You can pass it via command line, but it may be easier to write and run a simple launch file like: +```xml:my_sample.launch + + + + + + + + + + + + + + +``` diff --git a/bl_force_torque_sensor_ros/arduino/sensor_driver_raw_rmd_ads131m04/ADS131M04.cpp b/bl_force_torque_sensor_ros/arduino/sensor_driver_raw_rmd_ads131m04/ADS131M04.cpp new file mode 100644 index 000000000..d9493e47d --- /dev/null +++ b/bl_force_torque_sensor_ros/arduino/sensor_driver_raw_rmd_ads131m04/ADS131M04.cpp @@ -0,0 +1,537 @@ +/* + Based on https://github.com/LucasEtchezuri/Arduino-ADS131M04/blob/ed879ecd0da5ac0d1dfa0494ff65b1e7ad4ae6d5/ADS131M04.cpp + We cannot use it as is because it is not correctly compiled on default Arduino IDE targeting original Arduinos (e.g., Arduino Uno, Nano): + - It passes arguments to SPI.begin(), while original SPI.begin() does not accept arguments + - https://github.com/LucasEtchezuri/Arduino-ADS131M04/issues/1 + - https://www.arduino.cc/reference/en/language/functions/communication/spi/begin/ + - It operates bit shift greater than variable width. This causes undefined behavior + - https://github.com/LucasEtchezuri/Arduino-ADS131M04/issues/1 + - https://mfumi.hatenadiary.org/entry/20111217/1324137736 + Additional changes: + - Call SPI.beginTransaction() and SPI.endTransaction() every time to accept other SPI devices + - https://stupiddog.jp/note/archives/976 + - Set chip select (CS) high in begin() to accept other SPI devices + - Fix some typos & Spanish comments + - Use CRC to detect SPI communication error + - Enable to change SPI speed +*/ + +#include "Arduino.h" +#include "ADS131M04.h" +#include "SPI.h" +#include "CRC.h" // Search and install CRC on library manager of Arduino IDE +// https://www.arduino.cc/reference/en/libraries/crc/ + +ADS131M04::ADS131M04() +{ +} + +uint8_t ADS131M04::writeRegister(uint8_t address, uint16_t value) +{ + uint16_t res; + uint8_t addressRcv; + uint8_t bytesRcv; + uint16_t cmd = 0; + + SPI.beginTransaction(SPI_SETTINGS); + digitalWrite(ADS131M04_CS_PIN, LOW); + delayMicroseconds(1); + + cmd = (CMD_WRITE_REG) | ((uint16_t)address << 7) | 0; + + //res = SPI.transfer16(cmd); + SPI.transfer16(cmd); + SPI.transfer(0x00); + + SPI.transfer16(value); + SPI.transfer(0x00); + + SPI.transfer16(0x0000); + SPI.transfer(0x00); + + SPI.transfer16(0x0000); + SPI.transfer(0x00); + + SPI.transfer16(0x0000); + SPI.transfer(0x00); + + SPI.transfer16(0x0000); + SPI.transfer(0x00); + + res = SPI.transfer16(0x0000); + SPI.transfer(0x00); + + SPI.transfer16(0x0000); + SPI.transfer(0x00); + + SPI.transfer16(0x0000); + SPI.transfer(0x00); + + SPI.transfer16(0x0000); + SPI.transfer(0x00); + + SPI.transfer16(0x0000); + SPI.transfer(0x00); + + SPI.transfer16(0x0000); + SPI.transfer(0x00); + + delayMicroseconds(1); + digitalWrite(ADS131M04_CS_PIN, HIGH); + SPI.endTransaction(); + + addressRcv = (res & REGMASK_CMD_READ_REG_ADDRESS) >> 7; + bytesRcv = (res & REGMASK_CMD_READ_REG_BYTES); + + if (addressRcv == address) + { + return bytesRcv + 1; + } + return 0; +} + +void ADS131M04::writeRegisterMasked(uint8_t address, uint16_t value, uint16_t mask) +{ + // Write a value to the register, applying the mask to touch only the necessary bits. + // It does not perform the bit shift, the shifted value must be moved to the correct position. + + // Read the current contents of the register + uint16_t register_contents = readRegister(address); + + // Bit by bit change of the mask (1 in the bits not to be touched and 0 in the bits to be modified). + // AND is performed on the current contents of the register. There are "0" in the part to be modified. + register_contents = register_contents & ~mask; + + // OR is performed with the value to be loaded into the register. Note that the value must be in the correct position (shitf). + register_contents = register_contents | value; + + // Rewrite the register + writeRegister(address, register_contents); +} + +uint16_t ADS131M04::readRegister(uint8_t address) +{ + uint16_t cmd; + uint16_t data; + + cmd = CMD_READ_REG | ((uint16_t)address << 7 | 0); + + SPI.beginTransaction(SPI_SETTINGS); + digitalWrite(ADS131M04_CS_PIN, LOW); + delayMicroseconds(1); + + //data = SPI.transfer16(cmd); + SPI.transfer16(cmd); + SPI.transfer(0x00); + + SPI.transfer16(0x0000); + SPI.transfer(0x00); + + SPI.transfer16(0x0000); + SPI.transfer(0x00); + + SPI.transfer16(0x0000); + SPI.transfer(0x00); + + SPI.transfer16(0x0000); + SPI.transfer(0x00); + + SPI.transfer16(0x0000); + SPI.transfer(0x00); + + data = SPI.transfer16(0x0000); + SPI.transfer(0x00); + + SPI.transfer16(0x0000); + SPI.transfer(0x00); + + SPI.transfer16(0x0000); + SPI.transfer(0x00); + + SPI.transfer16(0x0000); + SPI.transfer(0x00); + + SPI.transfer16(0x0000); + SPI.transfer(0x00); + + SPI.transfer16(0x0000); + SPI.transfer(0x00); + + delayMicroseconds(1); + digitalWrite(ADS131M04_CS_PIN, HIGH); + SPI.endTransaction(); + return data; +} + +void ADS131M04::begin(uint8_t cs_pin, uint8_t drdy_pin, uint32_t spi_speed) +{ + // Set pins up + ADS131M04_CS_PIN = cs_pin; + ADS131M04_DRDY_PIN = drdy_pin; + + SPI.begin(); + // Configure chip select as an output + pinMode(ADS131M04_CS_PIN, OUTPUT); + // Set chip select high to accept other SPI devices + digitalWrite(ADS131M04_CS_PIN, HIGH); + delayMicroseconds(1); // Should be longer than t_w(CSH)? + // Configure DRDY as an input + pinMode(ADS131M04_DRDY_PIN, INPUT); + + // Store SPI settings + SPI_SETTINGS = SPISettings(spi_speed, MSBFIRST, SPI_MODE1); +} + +int8_t ADS131M04::isDataReadySoft(byte channel) +{ + if (channel == 0) + { + return (readRegister(REG_STATUS) & REGMASK_STATUS_DRDY0); + } + else if (channel == 1) + { + return (readRegister(REG_STATUS) & REGMASK_STATUS_DRDY1); + } + else if (channel == 2) + { + return (readRegister(REG_STATUS) & REGMASK_STATUS_DRDY2); + } + else if (channel == 3) + { + return (readRegister(REG_STATUS) & REGMASK_STATUS_DRDY3); + } + else + { + return -1; + } +} + +bool ADS131M04::isResetStatus(void) +{ + return (readRegister(REG_STATUS) & REGMASK_STATUS_RESET); +} + +bool ADS131M04::isLockSPI(void) +{ + return (readRegister(REG_STATUS) & REGMASK_STATUS_LOCK); +} + +bool ADS131M04::setDrdyFormat(uint8_t drdyFormat) +{ + if (drdyFormat > 1) + { + return false; + } + else + { + writeRegisterMasked(REG_MODE, drdyFormat, REGMASK_MODE_DRDY_FMT); + return true; + } +} + +bool ADS131M04::setDrdyStateWhenUnavailable(uint8_t drdyState) +{ + if (drdyState > 1) + { + return false; + } + else + { + writeRegisterMasked(REG_MODE, drdyState < 1, REGMASK_MODE_DRDY_HiZ); + return true; + } +} + +bool ADS131M04::setPowerMode(uint8_t powerMode) +{ + if (powerMode > 3) + { + return false; + } + else + { + writeRegisterMasked(REG_CLOCK, powerMode, REGMASK_CLOCK_PWR); + return true; + } +} + +bool ADS131M04::setOsr(uint16_t osr) +{ + if (osr > 7) + { + return false; + } + else + { + writeRegisterMasked(REG_CLOCK, osr << 2 , REGMASK_CLOCK_OSR); + return true; + } +} + +bool ADS131M04::setChannelEnable(uint8_t channel, uint16_t enable) +{ + if (channel > 3) + { + return false; + } + if (channel == 0) + { + writeRegisterMasked(REG_CLOCK, enable << 8, REGMASK_CLOCK_CH0_EN); + return true; + } + else if (channel == 1) + { + writeRegisterMasked(REG_CLOCK, enable << 9, REGMASK_CLOCK_CH1_EN); + return true; + } + else if (channel == 2) + { + writeRegisterMasked(REG_CLOCK, enable << 10, REGMASK_CLOCK_CH2_EN); + return true; + } + else if (channel == 3) + { + writeRegisterMasked(REG_CLOCK, enable << 11, REGMASK_CLOCK_CH3_EN); + return true; + } +} + +bool ADS131M04::setChannelPGA(uint8_t channel, uint16_t pga) +{ + if (channel > 3) + { + return false; + } + if (channel == 0) + { + writeRegisterMasked(REG_GAIN, pga, REGMASK_GAIN_PGAGAIN0); + return true; + } + else if (channel == 1) + { + writeRegisterMasked(REG_GAIN, pga << 4, REGMASK_GAIN_PGAGAIN1); + return true; + } + else if (channel == 2) + { + writeRegisterMasked(REG_GAIN, pga << 8, REGMASK_GAIN_PGAGAIN2); + return true; + } + else if (channel == 3) + { + writeRegisterMasked(REG_GAIN, pga << 12, REGMASK_GAIN_PGAGAIN3); + return true; + } +} + +void ADS131M04::setGlobalChop(uint16_t global_chop) +{ + writeRegisterMasked(REG_CFG, global_chop << 8, REGMASK_CFG_GC_EN); +} + +void ADS131M04::setGlobalChopDelay(uint16_t delay) +{ + writeRegisterMasked(REG_CFG, delay << 9, REGMASK_CFG_GC_DLY); +} + +bool ADS131M04::setInputChannelSelection(uint8_t channel, uint8_t input) +{ + if (channel > 3) + { + return false; + } + if (channel == 0) + { + writeRegisterMasked(REG_CH0_CFG, input, REGMASK_CHX_CFG_MUX); + return true; + } + else if (channel == 1) + { + writeRegisterMasked(REG_CH1_CFG, input, REGMASK_CHX_CFG_MUX); + return true; + } + else if (channel == 2) + { + writeRegisterMasked(REG_CH2_CFG, input, REGMASK_CHX_CFG_MUX); + return true; + } + else if (channel == 3) + { + writeRegisterMasked(REG_CH3_CFG, input, REGMASK_CHX_CFG_MUX); + return true; + } +} + +bool ADS131M04::setChannelOffsetCalibration(uint8_t channel, int32_t offset) +{ + + uint16_t MSB = offset >> 8; + uint8_t LSB = offset; + + if (channel > 3) + { + return false; + } + if (channel == 0) + { + writeRegisterMasked(REG_CH0_OCAL_MSB, MSB, 0xFFFF); + writeRegisterMasked(REG_CH0_OCAL_LSB, (uint16_t)LSB << 8, REGMASK_CHX_OCAL0_LSB); + return true; + } + else if (channel == 1) + { + writeRegisterMasked(REG_CH1_OCAL_MSB, MSB, 0xFFFF); + writeRegisterMasked(REG_CH1_OCAL_LSB, (uint16_t)LSB << 8, REGMASK_CHX_OCAL0_LSB); + return true; + } + else if (channel == 2) + { + writeRegisterMasked(REG_CH2_OCAL_MSB, MSB, 0xFFFF); + writeRegisterMasked(REG_CH2_OCAL_LSB, (uint16_t)LSB << 8, REGMASK_CHX_OCAL0_LSB); + return true; + } + else if (channel == 3) + { + writeRegisterMasked(REG_CH3_OCAL_MSB, MSB, 0xFFFF); + writeRegisterMasked(REG_CH3_OCAL_LSB, (uint16_t)LSB << 8 , REGMASK_CHX_OCAL0_LSB); + return true; + } +} + +bool ADS131M04::setChannelGainCalibration(uint8_t channel, uint32_t gain) +{ + + uint16_t MSB = gain >> 8; + uint8_t LSB = gain; + + if (channel > 3) + { + return false; + } + if (channel == 0) + { + writeRegisterMasked(REG_CH0_GCAL_MSB, MSB, 0xFFFF); + writeRegisterMasked(REG_CH0_GCAL_LSB, (uint16_t)LSB << 8, REGMASK_CHX_GCAL0_LSB); + return true; + } + else if (channel == 1) + { + writeRegisterMasked(REG_CH1_GCAL_MSB, MSB, 0xFFFF); + writeRegisterMasked(REG_CH1_GCAL_LSB, (uint16_t)LSB << 8, REGMASK_CHX_GCAL0_LSB); + return true; + } + else if (channel == 2) + { + writeRegisterMasked(REG_CH2_GCAL_MSB, MSB, 0xFFFF); + writeRegisterMasked(REG_CH2_GCAL_LSB, (uint16_t)LSB << 8, REGMASK_CHX_GCAL0_LSB); + return true; + } + else if (channel == 3) + { + writeRegisterMasked(REG_CH3_GCAL_MSB, MSB, 0xFFFF); + writeRegisterMasked(REG_CH3_GCAL_LSB, (uint16_t)LSB << 8, REGMASK_CHX_GCAL0_LSB); + return true; + } +} + +bool ADS131M04::isDataReady() +{ + if (digitalRead(ADS131M04_DRDY_PIN) == HIGH) + { + return false; + } + return true; +} + +bool ADS131M04::readADC(adcOutput* reading) +{ + uint32_t x = 0; + uint32_t x2 = 0; + uint32_t x3 = 0; + uint8_t crc_inputs[15]; + uint16_t crc_received = 0; + int32_t aux; + + SPI.beginTransaction(SPI_SETTINGS); + digitalWrite(ADS131M04_CS_PIN, LOW); + delayMicroseconds(1); + + x = crc_inputs[0] = SPI.transfer(0x00); + x2 = crc_inputs[1] = SPI.transfer(0x00); + crc_inputs[2] = SPI.transfer(0x00); + + reading->status = ((x << 8) | x2); + + x = crc_inputs[3] = SPI.transfer(0x00); + x2 = crc_inputs[4] = SPI.transfer(0x00); + x3 = crc_inputs[5] = SPI.transfer(0x00); + + aux = (((x << 16) | (x2 << 8) | x3) & 0x00FFFFFF); + if (aux > 0x7FFFFF) + { + reading->ch0 = ((~(aux)&0x00FFFFFF) + 1) * -1; + } + else + { + reading->ch0 = aux; + } + + x = crc_inputs[6] = SPI.transfer(0x00); + x2 = crc_inputs[7] = SPI.transfer(0x00); + x3 = crc_inputs[8] = SPI.transfer(0x00); + + aux = (((x << 16) | (x2 << 8) | x3) & 0x00FFFFFF); + if (aux > 0x7FFFFF) + { + reading->ch1 = ((~(aux)&0x00FFFFFF) + 1) * -1; + } + else + { + reading->ch1 = aux; + } + + x = crc_inputs[9] = SPI.transfer(0x00); + x2 = crc_inputs[10] = SPI.transfer(0x00); + x3 = crc_inputs[11] = SPI.transfer(0x00); + + aux = (((x << 16) | (x2 << 8) | x3) & 0x00FFFFFF); + if (aux > 0x7FFFFF) + { + reading->ch2 = ((~(aux)&0x00FFFFFF) + 1) * -1; + } + else + { + reading->ch2 = aux; + } + + x = crc_inputs[12] = SPI.transfer(0x00); + x2 = crc_inputs[13] = SPI.transfer(0x00); + x3 = crc_inputs[14] = SPI.transfer(0x00); + + aux = (((x << 16) | (x2 << 8) | x3) & 0x00FFFFFF); + if (aux > 0x7FFFFF) + { + reading->ch3 = ((~(aux)&0x00FFFFFF) + 1) * -1; + } + else + { + reading->ch3 = aux; + } + + x = SPI.transfer(0x00); + x2 = SPI.transfer(0x00); + SPI.transfer(0x00); + crc_received = ((x << 8) | x2); + + delayMicroseconds(1); + digitalWrite(ADS131M04_CS_PIN, HIGH); + SPI.endTransaction(); + + if (crc_received != crc16_CCITT(crc_inputs, 15)) + { + // CRC error (SPI communication error) + return false; + } + + return true; +} diff --git a/bl_force_torque_sensor_ros/arduino/sensor_driver_raw_rmd_ads131m04/ADS131M04.h b/bl_force_torque_sensor_ros/arduino/sensor_driver_raw_rmd_ads131m04/ADS131M04.h new file mode 100644 index 000000000..8584c48b8 --- /dev/null +++ b/bl_force_torque_sensor_ros/arduino/sensor_driver_raw_rmd_ads131m04/ADS131M04.h @@ -0,0 +1,274 @@ +/* + Based on https://github.com/LucasEtchezuri/Arduino-ADS131M04/blob/ed879ecd0da5ac0d1dfa0494ff65b1e7ad4ae6d5/ADS131M04.h + See ADS131M04.cpp for detailed comments about modification. +*/ + +#ifndef ADS131M04_h +#define ADS131M04_h + +#include "Arduino.h" +#include "SPI.h" + +struct adcOutput +{ + uint16_t status; + int32_t ch0; + int32_t ch1; + int32_t ch2; + int32_t ch3; +}; + +#define DRDY_STATE_LOGIC_HIGH 0 // Default +#define DRDY_STATE_HI_Z 1 + +#define POWER_MODE_VERY_LOW_POWER 0 +#define POWER_MODE_LOW_POWER 1 +#define POWER_MODE_HIGH_RESOLUTION 2 // Default + +#define CHANNEL_PGA_1 0 +#define CHANNEL_PGA_2 1 +#define CHANNEL_PGA_4 2 +#define CHANNEL_PGA_8 3 +#define CHANNEL_PGA_16 4 +#define CHANNEL_PGA_32 5 +#define CHANNEL_PGA_64 6 +#define CHANNEL_PGA_128 7 + +#define INPUT_CHANNEL_MUX_AIN0P_AIN0N 0 // Default +#define INPUT_CHANNEL_MUX_INPUT_SHORTED 1 +#define INPUT_CHANNEL_MUX_POSITIVE_DC_TEST_SIGNAL 2 +#define INPUT_CHANNEL_MUX_NEGATIVE_DC_TEST_SIGNAL 3 + +#define OSR_128 0 +#define OSR_256 1 +#define OSR_512 2 +#define OSR_1024 3 // Default +#define OSR_2018 4 +#define OSR_4096 5 +#define OSR_8192 6 +#define OSR_16384 7 + + +// Commands +#define CMD_NULL 0x0000 // This command gives the STATUS REGISTER +#define CMD_RESET 0x0011 +#define CMD_STANDBY 0x0022 +#define CMD_WAKEUP 0x0033 +#define CMD_LOCK 0x0555 +#define CMD_UNLOCK 0x0655 +#define CMD_READ_REG 0xA000 // 101a aaaa annn nnnn a=address n=number of registers-1 +#define CMD_WRITE_REG 0x6000 + +// Responses +#define RSP_RESET_OK 0xFF24 +#define RSP_RESET_NOK 0x0011 + +// Registers Read Only +#define REG_ID 0x00 +#define REG_STATUS 0x01 + +// Registers Global Settings across channels +#define REG_MODE 0x02 +#define REG_CLOCK 0x03 +#define REG_GAIN 0x04 +#define REG_CFG 0x06 +#define THRSHLD_MSB 0x07 +#define THRSHLD_LSB 0x08 + +// Registers Channel 0 Specific +#define REG_CH0_CFG 0x09 +#define REG_CH0_OCAL_MSB 0x0A +#define REG_CH0_OCAL_LSB 0x0B +#define REG_CH0_GCAL_MSB 0x0C +#define REG_CH0_GCAL_LSB 0x0D + +// Registers Channel 1 Specific +#define REG_CH1_CFG 0x0E +#define REG_CH1_OCAL_MSB 0x0F +#define REG_CH1_OCAL_LSB 0x10 +#define REG_CH1_GCAL_MSB 0x11 +#define REG_CH1_GCAL_LSB 0x12 + +// Registers Channel 2 Specific +#define REG_CH2_CFG 0x13 +#define REG_CH2_OCAL_MSB 0x14 +#define REG_CH2_OCAL_LSB 0x15 +#define REG_CH2_GCAL_MSB 0x16 +#define REG_CH2_GCAL_LSB 0x17 + +// Registers Channel 3 Specific +#define REG_CH3_CFG 0x18 +#define REG_CH3_OCAL_MSB 0x19 +#define REG_CH3_OCAL_LSB 0x1A +#define REG_CH3_GCAL_MSB 0x1B +#define REG_CH3_GCAL_LSB 0x1C + +// Registers MAP CRC +#define REG_MAP_CRC 0x3E + +// ------------------------------------------------------------------------------------ + +// Mask READ_REG +#define REGMASK_CMD_READ_REG_ADDRESS 0x1F80 +#define REGMASK_CMD_READ_REG_BYTES 0x007F + +// Mask Register STATUS +#define REGMASK_STATUS_LOCK 0x8000 +#define REGMASK_STATUS_RESYNC 0x4000 +#define REGMASK_STATUS_REGMAP 0x2000 +#define REGMASK_STATUS_CRC_ERR 0x1000 +#define REGMASK_STATUS_CRC_TYPE 0x0800 +#define REGMASK_STATUS_RESET 0x0400 +#define REGMASK_STATUS_WLENGTH 0x0300 +#define REGMASK_STATUS_DRDY3 0x0008 +#define REGMASK_STATUS_DRDY2 0x0004 +#define REGMASK_STATUS_DRDY1 0x0002 +#define REGMASK_STATUS_DRDY0 0x0001 + +// Mask Register MODE +#define REGMASK_MODE_REG_CRC_EN 0x2000 +#define REGMASK_MODE_RX_CRC_EN 0x1000 +#define REGMASK_MODE_CRC_TYPE 0x0800 +#define REGMASK_MODE_RESET 0x0400 +#define REGMASK_MODE_WLENGTH 0x0300 +#define REGMASK_MODE_TIMEOUT 0x0010 +#define REGMASK_MODE_DRDY_SEL 0x000C +#define REGMASK_MODE_DRDY_HiZ 0x0002 +#define REGMASK_MODE_DRDY_FMT 0x0001 + +// Mask Register CLOCK +#define REGMASK_CLOCK_CH3_EN 0x0800 +#define REGMASK_CLOCK_CH2_EN 0x0400 +#define REGMASK_CLOCK_CH1_EN 0x0200 +#define REGMASK_CLOCK_CH0_EN 0x0100 +#define REGMASK_CLOCK_OSR 0x001C +#define REGMASK_CLOCK_PWR 0x0003 + +// Mask Register GAIN +#define REGMASK_GAIN_PGAGAIN3 0x7000 +#define REGMASK_GAIN_PGAGAIN2 0x0700 +#define REGMASK_GAIN_PGAGAIN1 0x0070 +#define REGMASK_GAIN_PGAGAIN0 0x0007 + +// Mask Register CFG +#define REGMASK_CFG_GC_DLY 0x1E00 +#define REGMASK_CFG_GC_EN 0x0100 +#define REGMASK_CFG_CD_ALLCH 0x0080 +#define REGMASK_CFG_CD_NUM 0x0070 +#define REGMASK_CFG_CD_LEN 0x000E +#define REGMASK_CFG_CD_EN 0x0001 + +// Mask Register THRSHLD_LSB +#define REGMASK_THRSHLD_LSB_CD_TH_LSB 0xFF00 +#define REGMASK_THRSHLD_LSB_DCBLOCK 0x000F + +// Mask Register CHX_CFG +#define REGMASK_CHX_CFG_PHASE 0xFFC0 +#define REGMASK_CHX_CFG_DCBLKX_DIS0 0x0004 +#define REGMASK_CHX_CFG_MUX 0x0003 + +// Mask Register CHX_OCAL_LSB +#define REGMASK_CHX_OCAL0_LSB 0xFF00 + +// Mask Register CHX_GCAL_LSB +#define REGMASK_CHX_GCAL0_LSB 0xFF00 + +// -------------------------------------------------------------------- + +// Conversion modes +#define CONVERSION_MODE_CONT 0 +#define CONVERSION_MODE_SINGLE 1 + +// Data Format +#define DATA_FORMAT_TWO_COMPLEMENT 0 +#define DATA_FORMAT_BINARY 1 + +// Measure Mode +#define MEASURE_UNIPOLAR 1 +#define MEASURE_BIPOLAR 0 + +// Clock Type +#define CLOCK_EXTERNAL 1 +#define CLOCK_INTERNAL 0 + +// PGA Gain +#define PGA_GAIN_1 0 +#define PGA_GAIN_2 1 +#define PGA_GAIN_4 2 +#define PGA_GAIN_8 3 +#define PGA_GAIN_16 4 +#define PGA_GAIN_32 5 +#define PGA_GAIN_64 6 +#define PGA_GAIN_128 7 + +// Input Filter +#define FILTER_SINC 0 +#define FILTER_FIR 2 +#define FILTER_FIR_IIR 3 + +// Data Mode +#define DATA_MODE_24BITS 0 +#define DATA_MODE_32BITS 1 + +// Data Rate +#define DATA_RATE_0 0 +#define DATA_RATE_1 1 +#define DATA_RATE_2 2 +#define DATA_RATE_3 3 +#define DATA_RATE_4 4 +#define DATA_RATE_5 5 +#define DATA_RATE_6 6 +#define DATA_RATE_7 7 +#define DATA_RATE_8 8 +#define DATA_RATE_9 9 +#define DATA_RATE_10 10 +#define DATA_RATE_11 11 +#define DATA_RATE_12 12 +#define DATA_RATE_13 13 +#define DATA_RATE_14 14 +#define DATA_RATE_15 15 + +// Sync Mode +#define SYNC_CONTINUOUS 1 +#define SYNC_PULSE 0 + +// DIO Config Mode +#define DIO_OUTPUT 1 +#define DIO_INPUT 0 + +#define SPI_MASTER_DUMMY 0xFF +#define SPI_MASTER_DUMMY16 0xFFFF +#define SPI_MASTER_DUMMY32 0xFFFFFFFF + +class ADS131M04 +{ +public: + ADS131M04(); + uint8_t ADS131M04_CS_PIN; + uint8_t ADS131M04_DRDY_PIN; + SPISettings SPI_SETTINGS; + + void begin(uint8_t cs_pin, uint8_t drdy_pin, uint32_t spi_speed = 4000000); + int8_t isDataReadySoft(byte channel); + bool isDataReady(void); + bool isResetStatus(void); + bool isLockSPI(void); + bool setDrdyFormat(uint8_t drdyFormat); + bool setDrdyStateWhenUnavailable(uint8_t drdyState); + bool setPowerMode(uint8_t powerMode); + bool setChannelEnable(uint8_t channel, uint16_t enable); + bool setChannelPGA(uint8_t channel, uint16_t pga); + void setGlobalChop(uint16_t global_chop); + void setGlobalChopDelay(uint16_t delay); + bool setInputChannelSelection(uint8_t channel, uint8_t input); + bool setChannelOffsetCalibration(uint8_t channel, int32_t offset); + bool setChannelGainCalibration(uint8_t channel, uint32_t gain); + bool setOsr(uint16_t osr); + bool readADC(adcOutput* reading); + +private: + uint8_t writeRegister(uint8_t address, uint16_t value); + void writeRegisterMasked(uint8_t address, uint16_t value, uint16_t mask); + uint16_t readRegister(uint8_t address); +}; +#endif diff --git a/bl_force_torque_sensor_ros/arduino/sensor_driver_raw_rmd_ads131m04/sensor_driver_raw_rmd_ads131m04.ino b/bl_force_torque_sensor_ros/arduino/sensor_driver_raw_rmd_ads131m04/sensor_driver_raw_rmd_ads131m04.ino new file mode 100644 index 000000000..6e396e00d --- /dev/null +++ b/bl_force_torque_sensor_ros/arduino/sensor_driver_raw_rmd_ads131m04/sensor_driver_raw_rmd_ads131m04.ino @@ -0,0 +1,105 @@ +#include + +#include +#include +#include + +#include "ADS131M04.h" + +#define ADC_NUM 2 +#define VALID_CH_NUM 3 +ADS131M04 adc[ADC_NUM]; +adcOutput adc_res[ADC_NUM]; + +unsigned long loop_duration = 0; // loop duration in us, set via rostopic callback +unsigned long start_time; + +ros::NodeHandle nh; +bl_force_torque_sensor_ros::AmplifierOutputRawArray output_msg; +ros::Publisher output_pub("~output", &output_msg); +int32_t output_array[ADC_NUM * VALID_CH_NUM]; + +void durationCb(const std_msgs::Float32& duration_msg) +{ + loop_duration = duration_msg.data * 1000 * 1000; // sec -> us +} + +ros::Subscriber duration_sub("~parameter_getter/loop_duration", &durationCb); + +void setup() +{ + nh.getHardware()->setBaud(115200); + nh.initNode(); + nh.advertise(output_pub); + nh.subscribe(duration_sub); + while (!nh.connected()) + { + nh.spinOnce(); + } + + adc[0].begin(9, 7, 125000); + adc[1].begin(8, 6, 125000); // I'm not sure why, but using D10 as CS doesn't work. Conflicted with SPI.begin()? + // Set SPI speed 125kHz (minimum of Arduino Nano) to allow poor-quality wiring. + // Currently, this is no problem because current rate-limiting process is rosserial communication. +} + +void loop() +{ + start_time = micros(); + + bool is_ok = true; + for (int i = 0; i < ADC_NUM; i++) + { + if (!adc[i].isDataReady()) + { + is_ok = false; + } + } + if (is_ok) + { + is_ok = true; + for (int i = 0; i < ADC_NUM; i++) + { + if (!adc[i].readADC(&adc_res[i])) + { + is_ok = false; + } + delayMicroseconds(1); // Should be longer than t_w(CSH)? + } + for (int i = 0; i < ADC_NUM; i++) + { + if (adc_res[i].status != 0x050F) + { + // status is value of STATUS register. + // By default, if everything is OK, this value is 0000 0101 0000 1111 (0x050F) + is_ok = false; + } + } + if (is_ok) + { + for (int i = 0; i < ADC_NUM; i++) + { + output_array[i * VALID_CH_NUM] = adc_res[i].ch0; + output_array[i * VALID_CH_NUM + 1] = adc_res[i].ch1; + output_array[i * VALID_CH_NUM + 2] = adc_res[i].ch2; + } + output_msg.array = output_array; + output_msg.array_length = ADC_NUM * VALID_CH_NUM; + output_pub.publish(&output_msg); + } + } + + nh.spinOnce(); + // Enforce constant loop time + if ((ULONG_MAX - start_time) < loop_duration) + { + // micros() will overflow while waiting + while (micros() >= start_time || micros() < (loop_duration - (ULONG_MAX - start_time))); + } + else if (micros() < start_time); // micros() already overflowed unexpectedly + else + { + // Normal waiting + while ((micros() - start_time) < loop_duration); + } +} diff --git a/bl_force_torque_sensor_ros/circuits/rmd_ads131m04_arduino/schematic.jpg b/bl_force_torque_sensor_ros/circuits/rmd_ads131m04_arduino/schematic.jpg new file mode 100644 index 0000000000000000000000000000000000000000..75dae77d5f597d98dc9517bd465226513c898c01 GIT binary patch literal 125105 zcmdqIWmsHMmnM1&Cpf`9KmtL7yCuN`g#@<{v~brzApwG0fCNu)Dcm)|3BfgmySrO) zE8RVJzOQGxr*F@{d+OQzpiZ5$*4le7dDpuiW*(LRLM1sxIRJzL03hTCc$fuV0azFq zm>B3-n3$N@*jSHnN$_xSaBwM!9}|$!Qqj}VQqj;bFmtgmFmf=_(69ulo8Y)s31lFg$RU71bXNK z=#g@wgZ||L{_O&xprWB;U}9lE!a?3pO9-HVP*G9PP|?xR(2#fgA-@OEh|r0j@W^01 zRyW0DbSB{qjQ@tk^s@3NsmACLGv9lcAnZqE5EK#?5q#KzUl-NVz%+b8&ANNCun@Q8%O&q>KCU%sY(&&kcpFDNW3 zuBxu7t*dWnZ0hLj>h9_7>;E-2J~25pJ@W^?yt2BszOlKry>onWdUk$sd3AmBS1%BN z`mbss|Ng6D|4uI=q+Td!XsBqIfAs>Pcp?WX5gPgv9t>g`bxc#|$BevzSR^mwzg7Ok zX5!O0B7N^N`iP8~fBEV0U)BCav;Uf6LH{ky{$IuZr(SRX7Zrq@JX9h;3b?#s{T}e> z|F@&Ggq|2em0Sq~>V%Vdbb2YxBrc~sK%nszz^CJ1# zoY7n_cEi_qVZZIX6KIy@i-g5})zBl@GINTzZ(j2Z7B2jR&{Sc?Z#aERKU2@##K2LQ@arQ1Sw;le&f5A?a_2Whb23H!J|&|@0VVu7>lG<1 z6EKn-e}fonY^@LNeFv>kWOxhrq3w;aMp-9~&he`6L_CRK854*U>sPbL302c2Fm&&2 zRV=>Bk{Q{I!PC*Js7jXktQ;94$25(0cA1T*|Gcs<@pVGi&T#{7X~C1gEtvy$Znb0i zu$r_S+alX0i;N$jC>exjVLHqpMI3bxXEtmXJ%LXsfSwfHEX zN##S*E8jO0I^edcvs>Gq9){F)((COwFy+29HHrG$b50%b=>FKMMr+U*d7NB1UkG}v zOyXh$&?rk9R_xW=>BG5QJ#jvOBNq29O7l(e54tdn03p`WeRh-4^FHP@rAdxMv)FK| z1q;6{Lpmuc|D;k#)B4xuv2xfUXD12okL78n9bT~$R+MwnOo2hx#rc`&moxK!dN<}e zn5nx$1XEEK2;vnXQ3J{Tp9bkGgEWo$ zQHS->eY2(sZN3XH3#a1YS(X?~la2uHQA668lCo_&!7(?^R|a)cq2F+ao#JOXz?Noe zuRatU@QC?4xW@QQYp!6sd(|k1j=+|)G=z1vEjykwqYU=-p|a2(M*!pB8ziLOPIKH@ zW>Pgyn@%Fe%{cbOJ^E>qd7lGhTFmzLb0~cA6H^6&wYM;{j(x7Ot)`5RCvY1ypt!21 z>+u%I2zE7ssV?g(i9T6N3zbRKYlF@$%ndw^@2 zftcdi5T1TEN(AeFd*GH6dIb%4ruxh;aEwt}=rRPMEpnXH&%ZWaJKY|cv?u7+zL`89 z%6J-mkWpm7IPf%Yhpj#N4``x%>%4Qp= zjQ(}#10a7@DNtAKlM36&$#)DoW;}UABzM=n9wawr;<2|Wu7+u}LO=xf@_=J=F*Y=0 zZm6Tz!ipV}tr*f-nehV>6ah1sxlk81#hLy43wu6|&|P`igi~+=|KsmMPkIMyQ-Ji) zt^E4KgVOg+HFcT3Ugc#tu$0v7N~hd}oEa<0$<8aEAz$uKsfh5hVLF(5(RSrL^(cL^ zct8&~a}PF7P*)Ivh)6d6oe8`yRRF|$AJ@5g-MDHg?eW`t^J);Mp`$F71(?LQ!hJAV|h~2;o zwj@Kt!|+;ms~7{I4*@i%-M#qnFdhKyMybY{zqcO8J_>4>bTt=tjxoJ zjm*l@IjTbHIcoeON`)i2;jvX`EaBCctDv1f7NOVg#z&cMMQ3}Ad1D?OaJ;M^Y9=%j%X%@3NJd=N2+^iu}cOrKM8(yK$5GdoD5 z3O$GROLbg|#FH>-eNd%I?|6z9pdC8jw@s`aD;|IjcD&)l9`V7Q=C+2Fs)IY_(q~y^ z3MnU;^~ZLCJcO77pcm_+Zr5q2WvQn>(aZRo=lS%S$K7#op1k8?j1du^@w(PCB$`0M zlW{y+`L(FnIQ{_CI9iZXmHLz>DrsfpX?zTF9{JpVlm0${&mMMu_}D9_J2|*(`o=Fm z%Pk)M^m`AMWr)EBM{W|@rgg98@Ef%;ad4Se)4Q@ybFO+ zyu39zWPgsX2c|Kr$VNY!-^eTQ8hCqDdyylUhbtIw3^yDiAADscZ80flkR)gKe_+xHr-18;70vUf7+ zMN=a9@yrcB^?aU2>#mk`OrslWT&4A)nF4=8&>PscagTnG#~ZC_8sAi8QAq^MCaViivlG4;L){5KfZ1A@6+o&g`6T(=MfYFDzI|!1(~&dT@>*Q)R?Ns) zg>k?o5)bxAd&pdIRa@i%ur_UrHV#=X$K?ub`dqJ>w||i1`*d!cqV9eVT^d`QEdWy> ztmIC__WW3!tSNO?Zx`nHJgjf-Nvfd6kfdqGPdWK=e$cS-oXWBz&Q-||cvR_8e!Qn- zr1O*h)Y$>MF0f~8!EJ*$NV{}@Wm?=~8IMIh+H!oaMYt(SO@TK7{5gtPl(<-tayxbB z&U2~RgvQIeX4_J*p4HP}o^Aa*vuQ)$uc`#BVUfafZggsxl&meMsxqya{6|@PD2-_# z^~eK|K}p9NLyM}&&BdC0AO8y zG@q#TE%9ibs7=uwn`)f%g)WSSsr9gS^#>t?7q$ORT7nf-L6g8R&OLvn2iHs#2mkV z4xCY9(g#0=Z)MVr)=E$f_1=OFj!6>5Jz`M%`4ikdgs;t18^r-(SUbTL?_wuBx-@z0 zpr&eEy8|vr`A#_{Y38O9dwi?{CXT(*DrGcr?h7WJxi44yTs{q>)KhA{4D7L@ z>Q8s25(K%ySUTYst@d;|juyD~8$7?i7&V8{Vrv=}bkXW`!iQs+jyBqhXZ0Xcq93aI zH-)Loo@r7!?|jnhz3pg~8-klx1#+)N?Cdk4=p}Oo&NkvC2JWZ!A8m$WL_RBVbr&@@ zw$Ukf=jh>VKm+0f6FUk4HFWw=f940^W7>}k9o{#IMzb4Z+mrPe36erqZOgUoOIp9@ zcF6Ui-R;B@^7lqf9lmc6ayD2Nu{%orz zO<~VKC1Kd-`tXHccb?X5i1ZK4Oh0z=rTgE;6qOOwDMY$9sS1-sv5%@=DydxUpUj?? zzosL$b)*_z!IL~P==O75+ab#|*7ihQi=&Ay6{W+M-_#W{!O`CRnTinrFOlc^tVg#Y zTwxi~$x*rL2}-I=&-@Jfsg^s+L_ zV^`P5G3bLu!B#Sy!&oqgn&Jr|yG$O4Rhp-hTv+%JnJFLTujqZiqisoO>9=rqhTxXD z=(Da_sQQIsE*sTaS&KeR3F8-2VFJIbtLv{6qN&_`8h)V2oaL&||9{N!v>n=^zIj_Z zo^bzkc=T`VR(th}nqVdd8an3$3=t;UU8M-%q}nxS*I#&~yoJ)1!*gRjZ}Nbt&P!)+ zU3EQ+0mEh1315L>+N{W{XnFLUeV<#oX@Ys&p>0^AK`wd*r5P?BoAtls&*$bU?h6?9f%Cdu2OS?Rgbv}^0w6m*StC? zzVpd_gw_1&5J_LnH?`Yr)IYajMWGf`u;a+Cu9Kl5l&h2r{$3mfx_*=z!3uo;FOGZ_ z;z69Q^`NFCG2P(cUNo2I=cI!zo*vZ(O4u>x)^n)AK`*@brRhvpsnL$k+ru~*N2dll zskFb@^Xx3p0C#K6YaaUK9a;JdJ;-Mad{c!3~%ynrQ20Yc^i7EVKsJW{}CHP zBSVEEgWDnPqBu*4{Jx!L?!I;&tL)|qN_r;L$@Q_^-4qAh6rh>6cMEq%#~ za?ob`sW{Iuz0tUZDQRdq!9{B$%cH6?;w3+D-vbby7yFZHa0N0&wfSl6R$)9ZMt3=8 zcp!PH_m_8hLl6j67*%+q=7ZzX&s7|D-JA(}a6`Q(%8Kx1WyI^}9A16PpU?LLrAhs1 zUtT6tg+*`?Mn?N=&1IYZnl0}~c>oqsrH|EEfUnsjv1hAQRq#7<226K}Sb+xxdSkwe9ca5|u;#OHXiD$a*Yx7ItY`4)T zZ1}2+PkZW~9vl=v@)K!69?VM~s1c0G4}c!GK<%HZN?dK0XwtkiO!TTB#bq+RXqhc< zlc&i&d?IvBlvwmW*S7YI`bo(Qa|yk|E%vpUD-mGGYytl?z?RaHH|7u_jPo4@r~qr#JtLf;0@2FuAw_x0}^ z%V+=T|9y%duS_t*^hZGeU zt%J$6&MjFsc6<2rvvA8S(>isW1iDfL>wJ_@)m55Nr;r2PuS@&M4~__sd* zGI&A{0Dz2ltCPqz^nd+;!G^Y}y_Rsxrt$UgGSl!;j(KbX#&17)(}|iT2$Z&VGpC@d zLyL%ZnAF*K(Jkx$vIqNjo(`3#_Lkp66F(=;$vJ`bKjxFptm*y-%_#$XAF0MnY zsKh6$vg2*T?)i{uK~30iwl|`NM`3dA+M2f&)axv$WzxOEu*E9{yY|h{yaym?APXU+ zwQt^VOfci9KQ{}>vHz{egv#6%_3eq`qa2Z4qz@OF&qmY6kLVO;Vqyrsru$r@4GyoJ zX%Sc+m^apqTC{qT`=r9c<>hzOA>J`*krgQ0d3XjFtK#e@?Y_Y z%i24-@+4T)#`Faw`enBbKM!11aA=!5RcDDjpBGcF2Qm{zhb#@ttd`Ch6DoR885P47dB*tN zR$z)xLt?<&auEhIOvd6X+g=Yk_G65q0!X|Ve5U&`Y`ITwAQ|%=QxdiRh4&^cue4|r zd-PFxY+_d?+jI^2_+W06;ZVGS(SQ~tdgq**OVTGh;u)xp^cTW@g|WdZ*K{kBrGK0@ z3!|+xnGjw@40NWV-L&@e%0-A5uC5ojUaCtd3M1S=<+9F~bfPEX=y_gQw_={NgB7O^4E>ANa^}FOrYJ%vCmwi=flMps?Gv8W3FF80vof z>`=90Dn;XHt`6RoCt~>M zFxI~1)e7e;g@}%e=bU;nywU>|c4*gMDKwj101)4_FQ$0q znZ{G5N0YS7Y#Uc>BE1Ws|!ypxjhF>5H{nw)ZT}rh6!DKZ}3d<03Y-pe?1=p>CQPOW6g=#?z zX2?yZ#{xu)*~JW}_C84D7}_*N<#E1K(=F_OuZmK5pvV9^G^`zt74YMouu1I=F1M?( z3w}BbH%rh}%cN4!i4)mGi{F-}og@vT4}X`^Lv-aY9Ql=hc%QUU2VKcK5I{X1f?O^< ziRtauSN%A(cVfc>X8c7B63@;J65DhK>_&Cl$d7UTSw@F)NSmdN1V1GOIZ0uavzHKV5rHE~i%t_D4YiWtl$J{*|KQ&@q z9DOy-gm&xHL zL`*#ZwlRE!^5*@PKSbDPrvgNG*guWmc@`OZ{hIF7Ss+gx+OSUbrZMh*5&8n3vcn2U z2W2*vg>}JKylgu?Z+^$|Z(9+?^}vD_{$%6Xut&#sOLC?%$BUzj$gBN=)^c8B9>cso z$kSxL$m-1hlb~xye4fw66YA3JydP5os`*7rsp=$$kBxas%g&7;+U34JEP^f#Z9V`o zS`s+j&R4N-TVmhTc)K-gt|Lo8G8BA*F`TDoMe;E?+XW%vaPRwv84aogv^JzMDY z^+fxTg)L~xQg6q_O!(Nq5bWMwEn02n&-cSiIx$Qe96McVAw>H`p&jk%4$Il4&k z#oNzMFY+XGHwaBycu4`g;v?35ho8Gz$JTqtM8$Koa|PXde*Zb5xNbHLz`zw5@(J*n z1pkweqxaE{4}g?t3IexG>Z%Dy(L3@FE}w@j(_#queFYy^XqR~@)f0y|LFs_tjm0FsTL9b?%a2jhR|a-sF}e7Fg%3J6@uAg z5nKV3%Zt}!{8=}rVGn>bX@OoQ?E?^RhRo&4g`sC4eK$Z0&$)bDdcr_S4gRSvZWc9) zQZS>{Yd50(tw6Kw?I7{VqH^;s?QNHA%M}{a1q;LRl^W(}$k>)pom#j3%Ak(Yahw*1 zyK-aBGk@N4>bt1i;{f)uY0C+LMM^y{Rk7<*`-C5hJH&q)6`xXHaM;YhCB|lUjS(*0 zcYqRkrFD*5`-BDJ*gSsy{`O5hVQtMDIq^xmgVjR-!&mF}0U)r|=lYhj+r;~i-)t{9zg?y5?Nxs|bi18b%-73dN@uTRe6vc? z{R&b5URBZQ^3 zc27u0G-LUr(rY_xE$rm?&QS^IHjKM%k0%AT_V_8!mHkw=7U0Ubm4z`nvbYHc@3dSR z`-U+B@Yq+-(@hB6_6_tVIQGwNX^kO0u_(t@Y`$ z3Z5v^jZKMpe32vUuY7sHlx{`YqXLNOJpi#{&>KX}12Fb!*I$vCB2$lojWO9$0-#lK zZ8}pQE|4WDtdhG-F5X&w5}5fyhPK<90MD9DhU!@=)*6v@y8mZjoqm=`KY#p=;RwJHTd?aOTo+t+6!A1u7-}DQRZ0oyA33`x|7(cl zLEZ)TS%%oXqTi~#(c}MWj5G-x^_EN)q=TR_r?fZJFF1UU`?emeo|OZ$vGuW-oRt;$ z_?_}snzsSsOS^^?Tr)_DUf-i2S5X31yj{(iJJmT5{$pt7*Zw;xT%v>T0lb_r{^#ee zpreE2It{)~N2x!WmkBHjw4#1{&}qR7Sk{%C8^H}|yZs8A{z_wUTgi>Pa;8v`b5wsi zt7-d}e-7rvW39bA5i@~el@iE>r_aZn4<{;*`d-l~1<72?OG}^wV5B=73Pd^p31sC3 zVnTMHq?Rd1q_!~gAAluh=(7Ajnu8SyL|REBi#oc$MP2*@5CYI2MQzcap(4vVVyUAX z1W^VmBEZKHfg+C}fp+j^Lq`Zy9)KUnneT}GM`6{FOXc6aSA7|VhJq2EA9VyBeVjE` z$(cP`&d6(UMeT!W&a!tA5ULr3#cS@uwvpru&9~OpuBReJ+!|P~#&^}-x)g&%c+XY> zxc{?vYPE`#iyf)V@{^$Tm~}P%B_Qzm6{Nf-R8_ba(ikHQ_HsA_8FN z)<4Gox_nk^ue5C{{ZvkinM+Gce`=Ne)p3@Uyn7$Y`-$s*M`o>Pz!1^jIh5@pJhn}cHUj30wsE9yM(uO=(Pt3=W#|NZlx; zkinrgX*uhflplI?9Q-$Ult`m{566}X&>D275`@)6vO4D0IPUv4Jk9EVSvdP1y~3xF zg<{j*M?fo5r7BFlVS=eH+L4P?LoeVuL+2pK4?_j;KKyuaZuEFXvLJs~{{z(re}-33 z2#FA#i}z?iRluxHGR1oyIPC7(gdI%s@z$WLx8tK;n!Mi$#UXUICoW!P@ZC3+txYve zjkPfbkwV;#Oa!UVn9z#$cGsJnBz2U(3w+7M2uLKAiarxnc(QS3w80s== zXrWzItu_58Sn4xao1Ag#p3gi9)O)aDDsOBhQAI7*V_amO_mcIJ<#4{_ z0Xz&emlV6ku>#R~-I2P(wz$brnFi9wK_SrQ`h1BJa>XP15I3<0pdOM+n$$Wn^haB~ zYV)@7wmk$ezf%ulK60z(P^jwnGpFqcFd!#dWocvoKIv{i;b>nYa`?2SWs)h$-aP8v zx=uo=jM@)EX%S=(eRf}RT(j<0;Jn54XQPREFq2E%FDMG=j*Zsj^|-*URFzHLi}@cE z!g@Mlx^4{Tm~(2FozK+P=7gRK4+Pm7~Q^zw|Q*R>qs>} z6iHJJIu$MR2=c3fiUP;;qOV8J*|SKiv6iZj?e8;oGlBYyBu}0*Jv6J+5+4p;l^BsxG1Mcnd)!otJR(OYO8oxxMHEBL-H1U-4rWb5=h$t zb!B?TCamTVjZ~a73Dhz}IKVU!lr*Fk5?B(lfLF7Tq2V3o(N$)Tfja3>7LBF6_Gz3V z9W%A!4-s)1I#KP(?$CO_<6t8ra>Ga^_i_6-(NE(VPBBbS(NieOrTuV}5|x6LeX;PO z+d4_m{a??>7!th4V6#5k6|SYM#oEs?=pQvpekW_H?e=vMG{?e<#yIrMbWc2dn-E6@HsMf4X6E{c>D+J0chKu zF3yNaGR+@wf0~s0LSio8H#FMGJnr0V#~SswKW)Er=~b9&&{0ZaN2+-;@#d8Sm1X4V z$r2_4)A*}x4kTGf%DT3qF6ce&hrZQEGoA~bOp`I-R>@)Iitz)k&6=7BY=^Z|2U>Cr zo$cgv0f&F(!m$hPYFi6nRt2jxHzzSF8g{$~y&^+BY&ty=QnI?JJ-o+(r`+GwAtAmR zP>EJK|EnI>olnj+L@?*Hr1otWZ^&!8Z?ElKE7 zTv(Xd+?SZ$_W85tmH#@2JOGP{U_LzC? zIs9Za!X&QCwWkH{xn+;mhpM5xf>|^MCm)4Uv6gkxc^rWAL1nVwyiU);`KO=#9db#G zt)5!Ko8{KU-GsM?eR`^|?3Zq-x5_!sgvoSGet+U?&b8ku>?)L!k)|2SgLuR4OsYlw zi@b9b5LCn|3T6<&w7?VIhIgV-w-GvHwY1zTiy;`_%8hJ#lnwSnS11w(I`W+><<_e+e7Gp ziwSo7nv&x!mN9he5*9hH*)_5|U<+CP!sXVng?DPB6h*S?>g|iY$`W-N^QZLMpVaFa zBsb}db)c_%CVZWec`d8e$O2X)s2vBN&F^D~HjCy}om3AHxgY_phJQD_O6>IKn))`C zrBs)CvNfF7i})7xI`p((EYK;(qoai`v{k<2CSoU(bo4N!3htLb^jv$+Es7Kqb;jeO z*b{+r)K*Y90QJt5Wj=iYsW>QlPK%TM#P9)V!Lu32ft=cS_$0!=HCM^UEJ!PyOa|Zr zG%i3k0srV`(D;S>#7d*P9_L>9eu1`l>Fk9zI^>QCKq=XibUfafI)9a;T~ zH_CCtEX2*Fp<5NsCScc)oD<;eyp=*cUYUIW!tQla+9h~4oU`T2c0Me!o9Q#5FBIaY0&>7e zdtZ?jhc+}cCKm7lWcjp04EI=?PIg&BPaH3Mt7)~&-rXL3G!9BT*|rhor$_l2+Qbf) zAESRc?H-9ew3~F4(C_j9EPP%2x+WD_t&=PC@r-4x=AQFxCUpRu^sF`{oRP(FpD8`v z{QSH`V=L8e`ci02zr=8E)-M4fMAM?j;%K5Rc{hRyT5`m*ot8u!DG2UqN-EXRd)<%b zQMXqal=BGZ2{VDKmN?~#>2i6nK4H*f-x6a*aWXR7%Yx6tEGDwFx@V|Ih|Bn;Mb3uWx4AVegL;2OUdm^0k`7)?YaHWUcA7jct6ko5YnU3~Y4Hh~ za}*1eL*Zi28TY60QkI`Eo#5bi3*Et(rwM}Kk4L$2$oni#)XYklsbqoM1Hcfc=BH5! zs06A=!q+R+qv6Q50mzf%`_b6<^xU^xvlKs8#a#CdHzQgk3cU(e+VXPYHpBU|gUeUl zzvH=#rUw(T2;Lb`w@UZ=>_{zZdQl?+c#xgEYv@(+w*8rk=(Gl6G;~tqaBl#zalm}7 z&MDsU8Z;uWM>r{PWgE znIQfm5j@bQh7@d+#-j%;2deOUoZa`-)1T(^1Ga3<#$GFT~pp z=rz@0`)&_%QNGG7(?Zq+@nyG&7W?)yk)8GbrITps<%y7uWkSVJ$=$h^r zba#mU9?;JCUv9VBl{(%;f*vMQSvTsmE{PvxrW0Q_AHUb#F6f+^wnsInZioLNGhuD> z-?BS-Oe;36Sw=?oB8k$m4*rgAbDwBB9tTRGvc%p_Xl%nMMU4~IU<>8Lt^c*g47Io| zh{I4yT;vBGRw*!rud)3mRW^N_;JhW4dOF)qaaFH;baPdpIp%ijNAJU5hih)o_uc9d zHp}_~FSa4Un~i2H_W|9z5~G(JIDU$DviseQ4rWnKgNQA=sOi-1RRV&mU5$uK17s#| zx_qm6H=x36P^0HC4<6uH%1V- za1M;MDJsAErMo`He~9^0_Yt?ORM zD3Hu>_s!i$R_|-N{p{(;dI|UC3B@YI)JF44ECHnL#Zh~t9I~pzDIu?QI|bqyihDWj;MRsL%g%RZPokORH*Xi++(_#gZhlu0GnoTp1v3uOuo`4ibbMoXHjDXz~Y0l4YJK03K-n8e~Arj4b>KS-IGKCjFu zGfTd){zJMJ?xM}H>Op{B84K3mFNr*6xl1BIeE=E@p>J zyjuf7-q3nX-ALuc3yk?S;~L5gr2{&7M0*uOa2c$>=T zJbLgVz8WDpVo;{)I`s1tU7T11$tMUb_i9^rtbs9g5*nD;_~fcMlO#40z5;qIKDfv* z1DGZzx=)T-KAq7cpXM0xZQP=ElKF-H;`Yu~ksvQqJWW<>a1en*QY_3XtMf*xixab( zpybbeq}o_?8Ua6MjF2<4#{OcXVK`N2^L1p zpp#WfDZXaWC4A>$=QslS?_c>x4LVN2jIty)dh;`Eg|vz+*=73l;ca-C+nnP@VO+Pw za?w-I9A%!Ug`H;ODaT%Y-dWjmw(=RELBtP?(r?W@znnc(`~a;z97;}yzY1+Ny)&BP z?k(|s2PKu#p5(Va*msjq+F;IltE0g1Ayy1^131HsU)+A}vYkn*Oe?9JtjGO~r^8}E z{3K2{!FeJ;Rh1RhfP#WVhsE!h@8^xfH)m6CSTE^d^OyBkBw=Rw*>MeJ!EYw*1k$h$ zYXwjveBvpO#bbkmbQAntUX3g zC!2P86OK2bqx7DEc(lR-li@gi&_-RF=J3;?R`Y7&5wn>8^EK1;wpRo4I6d|h78E$JNJD|4;czDzsv0BqqEK$qB{ zA*v6+iNGRsI=UVaCSjP3JA5VYCUt`fS-g6b^%sO`qQ3{#9NwXWkMg(Mn8yTsqvaOC zE#!|OV-#iaMAg);z2LNi_#Pjs%G{kP(Tx<0y!;`Sn)Jssfl8Zb!9Rf*8JZC^siT-J z=o!X%`w^)W5|8Lc~rwbgOqLv=`|)KO14 zlr}oQP;!!+s9T)(rQr?tmmHQEHH?&hlnx02%@ZI3;K)?0;7SY6s@IryL_lh9U+zNT z;I5K8g|>9;E;kNe9c$0#AbiD$y36_3jmn*;q~a_apfz$aR|=y4l#L1P5c`Il0BWRF ze!Tq`OzIzP1sRp5%=!;i(RWkBu=)>0(#~+<{Qy4ts5ywU;}RMw7xR*%fUUFu&EZcB z)_FEw`#&1xpUhskb}Sc8mt|H6wSIl!d79VSavZdE!t+G#Ep1B>uM=o#^7i)Dh#TC{ z-umU0ts}KE$H&LD(*43TS=rf-{$pwNbRGc0JD&WxUVC>auL|>XCnCE7*UFx^8HLVS zuLf(jTNbQu>yYAc%`3yvXYVzwFtOz27rEyFE_(HQRcPqmDv_Tk!%) z)B@C#va$+psWndIY)r2{0Ndh|?b4Lmf7j{`{rRdbvMw7&VnN85&SZ?d#aOWYhUOdz z29c;E5hJ<>AkJ>_{NDQk$RpNHjWvtR3@#IQr=bB@Anln|8 zen74hYrd7V4-Os~!N~egRyqmjD>7?1_}kvGM*>kG&AYz@okz z=rCQASsNqf&s0e2x>zUWnf_zw58=)4#%m%dySC~oXfiB}{t z^EE)UY#`kf9^m%*Ut&iZGIp3DTCD#5&t^&|ynXHMl+4 z(^R=vrZ1OY@(6FI2lkhi%nroj%B+}R{mDoXnr4LyZ-+ELHJ}TmP_RbLi|sw0hj^rD z>uYsS+=R^4-S{<$20O(kepRMHGkh+-Sr4FLP?MEbul_X*}X}{1B$0UN&sQ z^Pl^vU`8U5^w*irMxiP>9t#b_hT5M0^pn5L_P-6K4dgZmME35Z0SLu=NU|9fX1kE!PpD=l76YMeN}{T7q~-X5KgV^d8CQ?2;DA&A zI3%rH^=c3>M;-$WixHqld1XCK<}{pZIB3Qs!aLhk`b?08IRT4uGt;|-b4BEQQ1j-gygT4Pk{ZVXm* zA2g4nLn1gl>`C(`;u$(}4`2;}GZjFVp|;c5O7*0GGK^`(zAghl$79;%M?Aa_wE|eq zV#y|LUH-O=d#t0(!QQ7!s&5*zGdTGcdGG?Kct8E&`{d;Yxy7G%Q z`y!4Ik_RAXFug*XDb`G54%#GbP#@Uy-*& zjSTHi`-Y#s>M2&BS*qBc%D9L5J^(K-kPHwgXZzK@&8RfZL9Bb>_RZ6f&rKNFV+OPG zk3T2O1!+kO-yf>74bK+bg5k)1aQo?n-KnR6!)*Ghq=R#&vjM*vrhvUO=WuxWf`Q0B zh2AV)A_;T!>FEg{uD{62w_}ecaiL`ud95DvP^Psqz9!9+?A~S~oveQhX{j55_^r>< zF23gK+Bu9J{!-&%&-VzuK-;A22oSIC^r`#0JWS|iuvhNoKWXQ-ud-R4{1o!FrOR(9 z`|$=}Ok<~xN`Z~j71eGx+9kjhbltIJuxswTSWluo zqb}mku9Q;G?7QELsF*)QsLm07`5G+qCFSqtEuS-apAUS z6?Jt&)q4H*?zD57FN=SdeP!=N5ltO1L1~>|Z-F0va_4-{?)`cc{+lU=c=elwEOq4s zYB!)g2A8{PF03i3d-ZLWj4tf=hcTPN5?LJnx2qd0m_gi7MsW1j(DsjnXYi;`-5A>~oRBasdequP(5+*N>_md=CaS zlrrxhwAQHK{s(=zjC(ouF0v`?J_K2pL(0Y)A{~K6UCu61Xk@Ljvfcr6!;5YbDRwb3 zJD!)mHzOFdnSpe*;B&o+GJKr<28RaGGWqn9gSoEH6t~@WM;tsas2NUi1{3iZ& zvao3fj*i2yKX`nx6a-vlr~eg z(?lUieKn8V2d6(B2((IdkvCa%cVVNIps5R6yjeXg>ebXfBfy^BN~sr(s;~D+E^-MH z;pV0x#}dKH21s3pfL&=y6YS4I9s88JD35+&Njv~PXTzbUrd7vy84cahWzFt*-(#EN z*HtGkaP_|yd=PINJ8P&Z0aMx%LXOus)OsIPpd~on3gIhm3QTULa>j<8ec>MzWuk3i zSY_epN>4VMOHh0kz%*&$#eD{0s!v|-UVYCR5$ZUnGVYAJn5a(=pKd?nwlTRpLB{@= zNrT~Q9Bb(L6%v*O3pkEo$fa`?OdUE}Rb-9{)dev>=C}A#q6D6^T-`LTEte$$$?YoE zwWJSn)E9S|5iSf8BY|YrAO1<0cT7_zr;A9a>}SUC13*)BP|D@N!Yf;{Fw4cW-Vv8{ zb9Y>MZ$q$`ws=F~&V74{Y_|0jf-0|URYR1zZi1e_@8ZgH!a$y9YM)3@yyQQ;k}qxF zZ2L zRak=ERD`-&b+>LljvMT3PrU3{k&RjM#V2j8H2$M2N*}WC7K7NcJkA)X1KX1EI5)xhS3M$ z|6%VfqvG1OtKH8KyVKhq;Pi)ZdJGhCpZ;s zzm>i3c_-}s?z!J>@9+1E)?gJi=Uj8mHAWx3_hGS<&ehmBj)BE^Z;BzsoVM*aT22%b zL?}TWmHAe;jeY%u4!=C<>f*rQwTH)At9MFH5LszvG={2K1TV(B93%~F5R1ZJ&L96p z{{H0xGBV@(j&~pJN&$%LG(E6hD2Z(|1fQX!AC`-!8Z=Lfk#Ao6d~&67ggk)jtc!~RfR(-(0{hzlTk zl9dt|VQQqs59q5X4w(78bcs|FCEVe0h{(nX(3nZT-J!Iq(dn-2CevbZ1~H@4t*>t~ z-yvwUuC^JCl^#-?@rR(B)Y-oWw6oMy9IC?vg#o{%KR z?Mnllvr9rX+>=+7gDjzUJ>m027rY*UmF*hbe9RKfcEM?4r+(OBEtwOC|D`Bl)f zb}pGx%k{7fmBu(swQ;j5??2rd=tNbn<5{4U7(c~e326oej^HOBR3?`jjYqQakyX}Rp`)ITTh>`9k$CjykutjMqR>uG~ zg$Pr%*TjLl5;O_YPDW%Y7cxgl1uNiEsny##c81ohyJpEb5l zNtq>d${Dd|?;0qeSIIPacU6y`Rr=$Bwcb$5Mor_&?vNZ ziO~xKAKuowt?B@(HUa~iTes52c00RQWvb8P>OW;9i6BKHNsx&VOjL6(TO4`3D_NQ3 zbVKFm_u$s|%Q_qmjHqLLOhzfOudA(>6b@MyC(=Wx-R{%-q`KKzy;&iVTA3n~A(sS2 zZ6d!(+1?isTrI~cNirgD8ZQ{fs%i&f-H7SNXoX@X4-R=c{Pelpm^OZGnAN-1nzI+l zYBMC9d|+#LX$Mo<##zk%_V#{}H7H2B)cVpfq)B##vXrC;iz)ta`?v&ya5#L;EUb62 zT|!cHx4dGe+E2*^Eu&b+aOjIpucLGPQ)=!&muT5dgPWS*Rcd8}@gGg{PWeBDjJ6*} zcL|<+XRY-)Kz2Y9P)%3X+bTIVWL5q+Y>}@ESJ1Zce5GM3`V3tO6(n6Q_jP+rp**i*`nr`{T%A+}wMS@viVd@n;{2)q#`pH!5ycCblB2TBF&cmNEj? z7&e1^H1wne*(tmMznb(jv^YPn^S->MxTuyw3VjR5pXM?O1#2{vG+!2>StZs-b`N@D zSiAb<7Sj}-b{33<(HhW9apV=0Wxaw-KSwUoj?kd$*>TPd2+IeG8gScWaahleHu}qk z&#?B}PEMqj==R>5qh0Nd8GDnuBy7XJBfgoZx{55pk!#Km$=5xKDCKJ)L^e9~^DpQP zXg|Fcpt}r08YvZ5te|j<(Ek~#Jtz_%7j)27#dR5PjZ6VCMFWDRak#Av*}hd2{EBZa z)aq?v&(JY`D@)TYL&XbAYd1O~^Mw3)q@N$!N^Kt_6Ut7O&GtJMzl~TMBz^Mc%|@;2 z+4JKJNI~=S?4^a~BfDNlX4S|Ay<(@0LV>ycV=_2R4;j4O9(Uqq z$WZyc_EFopeBlkveNAqJOle^xhJix-O7vMtCmbmHkxzT)O&It3ac{nCjqP;cx-F;O zfp7f*;{P60{b_h7R6(+8QI+ z>H(0oD#}rV_{zgd0GOvpzQy7QKr8@x7`gFb>|DSI4xl?g zO%}g)sAexSZGwjGpf6$fRm#jVILF0$o%4p9h&B6c<`~<29YM(#r009aCmft1U`|XI zEj&T6q&4a)Fb0K)?@g<)nWQQ^cRdEVrpCV(a$^b<5@IP!nJLe2yNu|nwXcseMPW&R zqoil35C3KPgI%hBE2T&J7rHGQ*1Ar~e-mH?AWR=@myQWWTX%o9o~GLdgPWlf)mV*# zb8EFVp~pw-Niwi6s9m2EBq$T3IIrc;97UYWd{-<^Bg{H#$LiF7)J{%|1Q1?7+o$Y* zbkm$$LL$8T9y6!b+1vl<0|>9Et<=!UXmok9q)D`Bo@Jz%p#;A&t@4#KzbksW=%ots zLF=mH7cBhYv>di%*{c32hD%&B0OgT&QTu&VQ4ZB3xMH7jn<{_K95=nL3fgB2BsCr0 zkzi)3U(oMOC#-8q>Dbz-lrLC#CX$p?E8dVOsr7S>Cer7W2Wd_;rKJG%$eDu7{4J*` zbu0k<#rAGWPo>Py>%RP^0UNSZ5r6k_;b{Om^I?f11v_$=kh3j?Ql6iiZC9b|ys2V6a-3i(=@BaX5D~1<0p74Mzm#Ly(khuA)xa=fLW)RZkGz9utON^;C zf+_989GuTGZ9{NL+=Fo~I*pZZmFMD_r@JUYSLLFeHs-7795Frq%U-c|WPiZ9=9+K~ zM_FguJXlLZj+fHCbzDL*SAx-ewzm;-4BwjaQJv;(HtW_lqB%T0KbJQlatsLI5wnqT z`Vd7(NBAaQxqNdN0EQbbLhVn>AN&D=P%DVzH4s6g+v&xv1muZ`1;v>iZO3jW!`c^l zrp^qdEp9tz)Ue(;u7#&Pj3cy>g<%>*K5&ZJLaNWpAhu~Z)uPB9vxT{Jy&Mc6x`+N| zhL*LE@qy%Ww6kD|GK%NUmBtJdhgScEtWRpp-rST_$ym>ZuK1z>@{Z()?a=ta{+T$< z)-gg~_Xw@vRlFio?uo(Bd0{@^Y^xYiTGuP=+eE&ol_K6BD8{l_sfKDZx{dW;>lx6V zychzCiw)kiW)dX4RzbxqZ1N4qmyM{n-ak!8<)j?y!!0Tb)897=b z#Ag*PuE^S>!9CEyO;qiGG-z=VOIPgVUgM{TKq4!~gi#fAyZoj0FWc@ZAr(wmg=*IQ zyU;)e@ie`XR-A1}wx<<%e4(>BujF+VZb+g8qmL!@PjMkKR*!ey^!w#ueYHvp{Zu>4 zcs`4HWIWr=MRA&0>m2Pc!wINbY&dMdP`Lkul$@ok?Dgz+uig|Q8i0{;-Oi-hdWPFT z<|#b^?;0K-!eBOvE`>X#w)COnSn^<=)YnLlUZZ)(d#j)h0tnoQUp~T1L>ODSaCgf* zcwg{|BSoPNb=z*OK(C8Z5-p{5y#7L(5|01;K)8!FTM{NQ*>aOTlK2<38nN^ zfzco&jwTjtE5_A8eyB0Ev2_N)l2X$PF`5T$@x#@~5VpJ^ZrX$RI>BXge^Hc%?p0q| z=-Bh}+1&Bm1`8PXcT7#mkzWQI+6X|=(8!r^R8!z_p>TD*O(B#l2@g9VVs9VFPS*v5wFn*Fh5+!$ z%ZVRl`TAQg-jt3{Yx{np3Vd3}7$h#V<44Dw5))aR_|kEt%yyIQrA?$p=UKMLufA8GsopOr*C7XzZftjuvb@fa)z5G#(t5n zRfW8b#>GRY`G8b)2WGXMN%2$|*p#iTi{4b9VINB1(#f1)bPAN42Y1ZZqDQ)qh~U28 z4>+SZ;=H{tew7j^l)@S~`9nmRqnRmY1-|<}98wy;^WAPUlt=||bOY5gJHdKmL8ao@ z2J?tysW4SVJI&hIs&3K7(h6$}8I~>Ogl`xk7i2t0)2c>3J}zrmr4F~9ofo78(gk~j z2DSvx?+@)Y*1RB@-vmWgtT9u6sWxJoI)h-ns2k(pm51W!$(!LD_@$ZFaGA@Q$GsA{ zmy3;EYYRGUU=18|Gt@m(RF*p;sc` z9Mwl&#W|4V44FQ=ce|Sq2t`-drjVVWt$;GF0&$>WjFXpe`6^KU*0_Kz}_HF@$ zh|ZCg(X#3rZW;M>R-4UQn~jE9_vD_9`)`BL)w?~|_@AKHb$dC6@kViX8W9JeB4X5% zU$j)6(1X(!wbSsO2icS)sqrSMjwC2gJj1&5Jl z7I8I6$Ma6@@aIhEq9LiTuM2^ky(b%3)W`2=Sr}*wa0|t__7W%~=df%%T#7NTo`OQO zB@Hr4$4B-mzDqwIuKSp) zpcHhsFii4{pp<2>za?!rb>79YQ+t^8W=~dc4C2zYNIB&?+a%)(ALdu7)0b|j zj9T?%a;&e{iPeaUj5MvgGE^Froe(27-r;`&u_5CA8Q&^B+=9L%0i;oOmmbkScp!wG z2{)~lIXDX&U2=4(ke9 zQf?hfBRR`4H8FSk5Qn)5n6yZnd5U*?YlmD5qlfv*dXXd-ZQH)`JW%RRL=rZSOedG? zRdPvbpDrzHl3w{igGiblce3$=pzyJbC3@wAB_-HwqB8@ayQuB1YE@-jP0;rhhNSIJ z4`p`NpO~UAW0sk90vwgoG@}WvhWf_ZnxGzliK?^QTgT`iPur!uaycziv>HX*CB}QG zwoN*=$g-fw7=t%d@g2RRVy`#j!%2IYqgG3WF|sFIIqhvi_bNBfbWSoC@4PvcH~z$Q zps2dSkyc2Vp=eoZ(Q}cV#_Nh$UGAvCSbomBz9QhIK#dR0@*_RB4P|%9_<(9!a7-7m z&T$6e>`E6nEVyQvdAiV?pvXH^b6xU)N7}uf*0qY5Qdz`xweIJ&Wd7XsgUKdQ-hn7f z+Um|nF=DnEq95a%r9uQ3CWw%>vDUzRh`>d%r3duGmUs#Ed2IeK&8QwPWCYkwACX?a zr>MR00sy&8ijD4lXmSr({CD&4vQx6`T3n~^b)Wh*&jbX!-Dm(_N1PcziYXUtJw=wF zencF`rrqFQkQZFMFyHIsJSI=okAdR#Ok6Wc$vL>$K?O<2J1r_dYZW3y3D@B;CGlV* zuQVh^vTf;>}AAKNv@6)#qey{t{T$bgj z1v8uheRdj%nEPh@esO=60Pc@-pvZ+v^9)qqb04Z4dT4BmA5_FP^FXvRA+oZ{B2WOG zYy_n48iT%*!qb9OYau@&r(fa4W6zi6*=Jyd68YKnx_Im{09YO|2SIs{dJ>AP3u(c1 zlPk@Wr57NEB#{_FXP@E+ZO(G&Dd|%{w*Lo+1d-$uaDRS>4;D4)+{vS@(({x-QxLoD z46PYA0<_-5owHNv8K!n5)`+52o9y%m+Wgr$Tx{e%!Rv1VY&x6KsBYDNJ)z`((?7d? zx~q@=>oNY<;|%<~Tdg;8b6LHCuyLFjBjg4=L#bcDyH^5OM1(NiOMKjaM(T<|me(>A zPDNjHeSQ0+lM?=t$_gEzG=E}$tBOEd>#P+coqTkZ%KgT*MoISo9AA5HmkcH#IR6yw zF*4lTN+&Hx@qj4NV2%0fuosZSyl>)KdDjFk^bA?jQ>&|ctIrvI^YQ2L>9Vw{d!?C02KCnLLD#0OiwanG=BZ`yb3O(F0- z3SaM+!>IA6I1`(((IwvQ-5|FLM1^ZB5u$IG6wWiuYd?gcVev99UQ>eH(y|9#a@*+wE62D74NG!y2o5i;r{-$ zBR+!_4*OWR_%xr`&hh=o%_7m_QP$Wa)V!fq{A+3#>ZWoOEWhsqg$lh5yjXRo3UuP>mp@Oexq*+dNwrVNj23hHNJ7nYMl&r zWYw3=H)I%k@Ii}{21yhNu)Nl${DP3xXgr#UXaX1Xy4>XDFX$NnSQJLkE~Fux=-yL# za>LH7UL|Yf{2A!5nbr|a!b%i@4bLZsJ-AA9ef%Sv%)kd(no1giW|5y)i|4_mo|Ih_ zEc13AdOhJ^7TAN|Z#?I1I>3xdoYH2IYe#X?g>8n5^{xVLiuof_Ggc{f$fz5YHse)n zxN|*DZ|H^0i+1pgKGm;A8DFXQrqIOj#T7@1D>X$N9pqHRttI)jHmJ0{V)-#Yv-ns2buFu^GQrcApe;-B56swxE%l0b5HT@bbo+L83>$5zE$380exoLz50~s*N;92 zJk7Yo{{v(R)P1R}z4;2Vw^M?-rOVKCI6&&SPwVDg#%cp`F*ZMI!b_Ev54%!0;*-W% zjFljeE{O+kS;ce`(tFdD6hRKE2H@)#OGP_;?qVb}P$U!Q=_*A#B5D3YlsC!fS=5cw zKf-(!3lQnwboZLJ)`OnobVG+M1v6s4wEwWjuCC^7%v=-#{wR#U?Vj6^7Ido zTx{^<1Mdg^p@Hn4eNLH5+pNA=oQh%DX~eS5t{a;zTf-k z1F1L41dQ0exj5!Y&Z`CI0$Sr9sBz~ddly>Ik5$Vor@XjoSW5v0N9%$O2zL-pUfP#^ z=+{!7XG;QGcq=~V?r7zB&q#LT9o*62^SV9R_dvnNP0}tUp2_VE{w2jE&3QWs`b%9x z+QrZ zWB^Ih#tqEYa3`8|2vg(0`nAa7gTvuq*sPuVON-cHk&~s|_>qS@2VKW@#&<|RzqojR zFZheDXArPzEL)Q~iwRG9Jh= zW~9Dc;kMF>Z&PVY=-@~U7wv9i&)_)ZmXERTxpLY`%<=$`pw{SsJ#@U=V0Mr;MXsZ|O(zIIn!Sw=*h!E?HkGCy5;_tu7(_iI9G{YKe!4SBJf=&e)Gyf{9zi>{H&J z-{c54-}s&A|J(6gjYOqg9+Vy|YRB4jS&~8<0yR{7gu|X!5}%zO5){w9|5=+e$5&_+ z%8949u&cFSXj>c0I750o&|?gE+C*i<-t$BzYs<)lFugoZ0 zAoUB8ClR0>$GgO6ASHKmvEFjOXbkhkU#uYEt~=}R>EwW3nI|Mi9R_^;ajZT_*)DMn1 zYNhAMP7hIN0FOlEn2O0gd;f=aM+=6}G3zU<8$xnlXUokDY0;%;KHxqh2Cppam)3?k zy0I32gp|5LoOkT_K6PM{$jeF8@90zEo=xwhki?ai*a3K!b_c`9?jbCuiTye%jpOZe z^-gSVU3fnccKLk~i4yx(*FuIMVf^txffzzWeL1xLnmNbTy}@;?@OEtS;E^WDm(GJ1 zn3Q=8hep?@DOX)Wq=6#Lc{VWSIQI!lxYApL$GSSs-;S-2BpIu`GrYGBM4qe+4u*4Z zxZ<#QtqZ5i+pk%g?Z}feB`IThdfRzIHbz}*gK!o#AXel$$IkANugs5~BxnMPY?6+y zg^!|6Q@ZoZSFx_pNRp*N>H<84v7)AbYL2%h2W^FZ0RFPg;V= z)Ip>uM{qV&k0c7TsJ!Z^f^9w$2>rf`qkUWwO&G{r!`+{Jl;>i}BHLzq|2w7&&XRs`@8!@cs zE>3P697{qQ7k#&Tubgnq>jW{|Iu?zo<|2X<2?$W{DO$1j_QG#qn{D^5X>iEda zwcSD1I(Mtm5AXico3rAS(i0t+B_n~MLI z^g`Z*eCrF6+H}Z9Ume)>>D;Dp93EqZsB!k@nBOqSXu@7wxl#`K6YZmo4`*@xgIt#x zhhKz#!yfFXNy8oJs*`2Xzgw?_a7J%4zWTzA(q^9F{P^C+Gab`3sbK=S%yo1XnE;9r zV28f{MTq|f5aQp+|Kf5=X93k|t6#bgz)6wML&7X73s9Cn{gOt9dJqx zC|I6|_rxINs>Ls{x0et^8EX<0OaikYRXJ)T>L;3-GDILz5Filx?E>K8(4)OUbNz9B zU->8#M~IdCmVg~NN`*XbQJE2dfCrNVV9HCT2?Hm50zhU}iWvGIhc}U3CB8yG3NVGa z0U3{4Kosro;|t{MM^T5In99PO8$VFd+Q$FKi+Kpha>(SyWL%C5sV=9L!<)ou-<|4K zpFFL#F%KE)5beEiW?dtvc3&&^PW{g#mu8R~B$77lWq%Wyp)SAPWtcIjxc5}wx}PR7 z>^z1)%uOJBs>D2Q|B=RvIw_qGbRh2j zOq`qF!WKXtQXJ3+27v^Cbt`M!6?(}qnWwQq^v|xwJP^TVy*J0;Kk)D7!oO&i*6c~hiAcqY}6%zZ+ z>V8vW=d*O*Tv~VWPG+(7=`>5_Rdy0s2l(fi-Q!Y*4{aw+JNV}4sF>f7&?7bU9N&uw zml(W<@EcAz9ANZCVC8x+Y~fnpW4Ki!ECM3_zQ$3@1dy%{k8W`}VWg z@WJNEW@DN%VA@wWAnP%M^Mo}&be&03<=Xlr))}?2b~i^xJo@MzYMCEKtYFP)*BgRG z!86LlAVCW`vv2YqW`UWw^0%Kv3-8_hBf&Mqae@6#PdCK*x4>6Ze_sZ!B$u+>e>HQw zrjzBRn~M6C7)g{UJ?#s?5$7{L=~M&AUlzavPYEE603J<1$@y~yuvM$v1W4b%9=V-J=iZZz(N8zmd=R?<#$nqgj6fy43V3 zzwasbL$$HRCjeiTeLml&i)*Q?Y_kZKd4Fll94J+URd0M9cOAUaw=jhhzN}}g*pYt> zrgfIj#7+9=%_-<2c@=9iS$8_Yfp?JfW+vG?LaE(e8#?gj&XT0~4xPu$poT#C zZc{x(Mwb>vbaV^jggyJ-S-8kMy=iT$nvX>m(Tbfou^0mvv{8y{`fyQ~HkyYu5@yIsG6?Ow9U~lkN$qlsIz4z`)udMsUw1zY*G>C~*Es7kzZxiv zM`$;SuuQR8^++9E$0q~dN_ckRK?)U@6 zbv;*Mf(9#LPLZ09?=GI&`lC;UyzO`6NOnP~<&yGv=H;9ljX{l}qQnBQ!zQj}SAU@C zZIgaA;_+}Sl$$3#VbIvq8h}+BB zbN<>TGEj7c`gIeOzto(=gx`+rLwl3g8%#RB#kxKQQGqgWPwO#{C&O(=`5&Nc#xFAz zAxVix>0SUN!p@K(5&7bz58t5VKZY(-N8c&j9$pJ_c> z=5?O2O&^0ubaqnPwZxS#E$qokoJEt@l9ku>aP#>A*~oO$w_|Hw$1s1oltrs6(V0jO zS)P{~A8c|upX|5y@$Tq}2b+#TiJBFCy7(<5X%r9g7{{n0oeO{_N3_3D%}X4~w>;7r zzgCWCA9ug4jcdu&{i=r|9Dy`nabH|$?(UI|j=D-4nj$|Qc}q6FSAF9E(>Y*g)`W-2 zprb^0-D81!dZ?!wAJJrQ-v@m1r6B}AKhaB+VTia6;@WP8`r4VT`hiudYJ+s5iWUg_ zWH?M0x4$!A3CD$Ps1L4wq@U(Z6M)MZ12nT*zfN2-uC|Mx0eYaJg!alMU%~Ne`3-$P zZRMIk_3OP?S>d+U_wROs)H+Q*^4QV2q3AZ` zd$PP%9Y!n_N72C~#ir!Q1o6Oo*qfQQBLJH=iwLPv+8kj86jm3htEV4^tVFMK;n$;- zk(E2<+5Ol1^SOtIqlp#o#$+*Z6NY)b4A1~cp0^h`D?N%t-%KqZ`sXo4kPclbr%?=y zoh?3Ob|PDM#-uJpE}gWeo8lQP725zyx?y$FQBS==|2acmP!Pkz&caTB!~JqHqyYm0 zeZqLdaGR+wNYezpOlQC|_I|q)ZJ(p$`$o_uxa% zM+F!9idRqYiqdKyrl(n1_*l7P?_|)WEWFVrx>{b>I%r-^h2RPcOk+CoQhvv>GeZ;U zS9Tdel31@;)+ky<6=RL*9M^v~Uz2uz{<`f;)XM#<&*{}j+8siV79)6Hx<-oF!dlmcte>*7w(tj=y zV<0sYdH7`)Khq1s{%K8pwB>32c|Y;5`$f8<&xr@yN#~hNSCrY%7%noh#lt74Jb;s9 z-+L1rh%RaPy*3xV3!^?y@W`M)CJ7k;tnbZzqFY0pUe`ud?{iQCf}{?28ak2z0@f8D zDjPcF`y-S=niVtTK)a6iqo)}v2ndj9`Lh}-$j(6aCN!Z5E}(Bx2Nog?#TYner zE>a3Q*!|%u!?o{t3PNGGJi`6~yj=8ufGXEw{rdK`=?tvrM$%29sGvE-wOwz~}M$ru^+I{t~kH|{MbgRssg8;3F>D>pK_WC$N) zRqA%LI4h63FRhgVNXl8rdENj?fL&hXMa#n@v>ILIf)pH;%E30j6z+ZorfKjX(mdjk&gp9j9&qQVBqm80I#MFxpY+EpO3 zvTfoJgsPJ((4gr*KuVHsHf}^Fj1e#BBA=dZ$9R`I9(L?Zw0-sTXLseDr1&_gcCK$a z_X^;IERBdN*`6&0o&9*=rPac8#G~!4)>jEOvw1~FimD{lNNQF~XO3HqRAePQzw2xu z*Jxz;Y*{mY+8s-8ak z-q!x9=@R6j0q-rxc7wHASBwptlg~A7Ij1egB7RzqH8l^@Du${wMy$o;+1nXCn1H_b zA(l<=*i}%bp zbQcsvd9{{Oe#9y9m2cE8o-KZf{p_BUsdTVexUJDby|k-sL^`gnI-Xq%HRMCa8Ern%3y6EI%NJEo zbtaZL(@&vD*iFycv!j_9Dv4gm1NZTS0F72^!|8(<@p~yah>5U4=&w*gDl=(06WMN2 zxfV^(hlJ#2o4sxQ$jtL^v@n-gB^cu%BUBo)iZ#Ad5b1#QC)- zf4Is#D@_A~p;MW14j(ER!pH;!w`50yB+r?0C)rFUOLD6-+!@ImNOXf4;33rWg196T55bZgs?SN-&`m(bpZcpG1eA z+mjRx(^|s?smKI3AG+6n`qh|`T^CkVzE`S@n5OP#pf=d}m=G`jtMO4O$aKljmY?6- zz9`cc3F7dw3_Iy3T{pec)ndI9!m>=PxX|8_vlAA2P2IR&iCc`^|F^{YTh@IFKHBHM58^>F#lA`TQg&)Cez=bLo17+DyqQHSg^50!VyFx(NvU)*EGbeT;KTAI{wZCoUw9_Az@xe#Yv1SG z0zt>h96BG5sBqp8npL2qTzW-q>jl7-8T!vfSfQEW-IE@=n0Y1|4f_IldRPBiKvUlai(-Ah9>(U*NQ5d>3TXk57M}*rt56k%EYVa+qHdC$p9aw(PvA6$kA!S znt;JSAh`LyS7OyPkrh9^D!>Gta%9p;>+nMgt%Zk%T%-k#L8Va(P5;!MELBk_PE(k4;7`O0KN5G@wBYUAC zaaEF+4n#ZxI)zR!%R=R9=>-y z9e&TIacqgm2fS40l`Z_;aqiY?kX0MoJPaiOA2T^D|D&gX#~uOvAP za;9Or`4M$3HAX#%{x(nk-7SfgY39{3*R^eQdd%_yb7u=jjrvWpM?Orl^hM4=47-#8 z(oTJ+4{cB5jd%x)BiY2m!p5A0vQ7HiPa4^e_%WYmlSG_=@^=d4gSW!A=>kqf8+#Yd zz)utRUjrgS8oYiih%n2>2iW(3@y1w;VWP(PX(KzSVwloI<^w$mjOa&A6!4 ze?9{1{*U$MjeL1$OrTmezJUm%Jk7+90ZVk#`z@vU{VRwwodbG9?!8qL4w>#4@*7m^ zxVYf)dKrY>3VIzkHHirK&rp1}AcDnwIyhh#-kqujofd%{o~Txa%0V31%NH5rMc+P& z;_7t-NVtG@fUy@)W0fHT82-Hh_Jm@SQ4iA95Tk!y>uOWbDZ1&SAR{dr8a*G zXk}B?`SjGhx3L+-~j1th=o=MB0cm%|)9N$nj01Zl@HxjV1PeN$^Au6B| z^P5->Q*G)k*g0UfZs}4DI%P{?m{gn(E-=<-Ja^&f4Zp;{^_kSVq)D?2z&YicZ3vyz z&CQ$pD1{;HC31|^4{Vf-PAv}#=D;T5HA4=jcsl_ac7+9@dDzbq`CfPBCecdK;;#rp zH=KjuFAH#ic+9iZeg>zp#N0mdxUwomAcv0PV;AaJFsXh=Ecb>HB+p!4&od0T3%g=5 zSmo(GDy?u&7<{?rwBwbD0oAOtyCH{IL_CRFgLs*7roqTk;N1{Ym^VD<59x)bY*0E-r%j}N0EZ)$$TX&g#Y zZy}dv*X@dv_5+@1owo$!6a1sFN-&8azk+Y&$BS4qnzIq>+owmUwSgx5F0y{Bl%Lc|HvBLT12b)L-99ZbF8X3rtiMQn3AYz&o zH5K4gNkaLBTZHq|{e56e17JYCNTg_gRhGfs@oBD-Wk0;86a2m+BKD)84m z$t^tQctw!X;*TYd0TA66{-fV-NS;w{#M9Sp$Z1*#{!|h=iN$bhzCW{aUYuon zOGyCJpWk^pYpfHVwwf-eGz!=GEcE$-jPOkU4C*SDF_CRL$2fU41_uuqQ*A?{MZ+?K zY_Tmkj^=wuq8czfBg9%KMegJL8D;&7*WG~(Ls6Qqg^zLUN-o1^Xwa%6ZL;Tu7Q9-ylHKpy_r7#V z0j;oS&#WR^^8qD#H)lqHA&*wlfEJ}29vRsPTdyFS)0O}+kw1$fdau~CF!NeiNcTdn zo_`wU^@;f0hgj~8!X02$?TVVm%9#=2xx0@e?DtDJ=;CUz!`!8s0@@T^^fEddqm;YE zo=mHnLMOkcOs~ndqL4SD*#dzkWfk`3FV1?E9LYUGw-4kJ)|J~4is^l} z8|&Ev(U+V7d}0AN2wNC@uaUiwKBqWi5eQ%-zf{(EGH0!8Hakpo!IGn^>&-{A>PD-# zwRCihS-3tWqiLyO3L^{L=SukI4MJKN)463nBCZWNmFH!BxBf9yC#&{-a*CFKhOx8q zNtyem9?(*6R;<(`bL&K}D__^1-67X5QL?|2cyb)q&qu~x@2+`^JYD?W_vh`z ziOg_6i#;EU`e@n`JVg0sI|4qD=>e5xr)ztYzr_XN*yqq5EqwD?~_Rss_a6 z;l5_2wkh*^9BEmphR<&Hs=QoSD`D zLL--zX&d<3PX%<)9vhQ3-JKpaGPJI_P>~hk^o8dnBD0z*6s#^f?ywdjl$0r_n0fL*Tq_}`0@Crf;i;QB`m|LEU;0tEQ z4++e*JX2j|B8un)+IPPA*|T~(`x~%9+d@L1&fx4nT}hE z!<+9FZkgLZh$|gtlj08C8BtYx)w=L{D%dE*lTHD=^exNAfd+@t3h#^x(%;=y(yv$*4Ana%2sFKdoEZk@lE61~fAkGqG2scvvjvuk7u6v!*yRCFYoZQk zGGLc^@lEO85zy4&^Py5+iO%l1F+5qlFP*vCXV-JXxnt47GT;f)RnCB`z?r&sS$R2W zj~Mq`LnZoPnFzU9IrpA!^TEe^o>Vak@4H&@a;nEyCw&EK$L)md$L3+OqSuwh#3uDz z46)DZiEU1!l-9b^pR`^Ph2z}DU_W)R7?dMEPV)|G14MFop)_=pS_6YpN2r~{9!?h2 zHzAXe^7SE;+)tQ`vjjx@+Kbb1nrF&xNo`KH_o)|)*b(M{19CmF6e}n9hoO7^Hc9l7 zFgTZ^f7BVg<@xc)vzhn)KzKIYY9t$+SDE zo*A(qK1&1!*zjhO3njhm?Y`(y@DFWQKSI@-L(+GyKTCBT0M7~vvO(;+xX%T?E^&$t zhk5&(fv%`E_h!2EcykH#gz=AGRuo##Mt_-Q@o_!P#A?MZE93O1wjm{T85B8)Y0)*P z;s^M;%1jNgjazD)Ne#ts4nskXSfhAc&2A3l>#zJ}tUMk^rj4dZ+D%A{o-qRNrTgU~O+822Vq%3yEa z%7Ab2Q+tnXXdQ4^mVLY=Ksfu+eA`cS_~CG1Y8rPB3*`l45}jGPV5#}oK{g@>H;1~y zkWUl?hUxs2@gx|v*SLXOf-1SAoWM5eJjFkC6|2a>bSlRuitpHp4a|zq$kzKg(t)Py zhPC7nb*g(YqXas1Jk(!mBoivjrupJ6D)|<=iLM@h5U_HD+YL0CrDk9Bg4qbxNovx} zEoD*sWSnMG#t?S-yA+OL9La_?B$sb5-(C=~#7ZvC^|gx-rhvA7{DX>U=jauXqrV_Y zblAM+5Uuf-&FNYpKt=qmXOzlc+}6K!V!GP_N`j(VOZ)n_rdW@G^7`MpK-rGz8vpl= zp#Eam{)c8zs5lJI$2lPm930ifAeKKszkfTc6byzX>=rbQ zu^hr(BM{3{F1U;#lxY{H}KXuOZ#h&jSwDzdKU> z*SzlN=K(wF-+NyEYkBU7Ux79E9=!G0F-CCza%@QaYj*$BV5p}4TkSpRs%Z6v5ov_5 zr}?LzENi%#TJJpzpt1SA1^_+$y`O?t*4U5UE^^n0cAV!_GyUZ}aHZk)*QO&cKLv@2 za%=3n;%GTyQZ@?nLuA26RF{!_<58h2D5Z%g05Yz#e8W1mm5EEJb~JOIlpq@VK6{s7 zmmmLQ{Gtyz{R3`nhqzf(kPo2>n0O|b2ZATpJRShO7N$;~`|*+_-y_;2xT(N%WEf80 zd_MwoLW`rTBfkds0k+Pzc8WtR`vygVyu|R*B~T>mw6ob4VQ2Gr zDvy;WwO!K}qJ&){*}f<3cKTnQwDAzqDkh>|+dFwC)KB8nOf8Rs9O!KZ1bC_j!Je@1mj~ZD zaS`4pI-%3giE6<-ue%J~G^`lB(4z$|N+HNyH7PfVUHw$k33_rSjWrD_l@iP5p_^pA zbiqN7ku4)OtMSNf{F$bC^>NsTwhJ(V=Zl7%NtZg(m+eJPMT-G{mK&>Ek$u40{c_?D zkOD(lX#M`*ei3;8Nkw0Lk@bSXJ&i=cbt-%WMFiHM&!>V=^2GJpSMh~A1?1fzW$72S zPn(C5cIiLm-2WDMoViJU9R-#^B?hZb%A~Wm)uew1hx-<;g}q|jw-Tv(-1Fc90Nd}l z!u?Vq#L+-qSdwBSC#irhOPW2##Q^#(&Q8AejL`pN6+w-s;_>EOAsg(N_!U=t`jP?! z&#q86P62;{Ogx{YuntO=d{m=BwI<$tUK9W=57;uAZ2hqT)S#&UWaM4xUEGH3gKuy3 z1CC(gcmIy-vFb|55tC~>*2#Fdb=lmK*uk-4Zr;US*`fpS~y1R1_1f)wkr5lN%L%O74fT6oPr97|h-#%O1`+WC4zqQU;=a2ITYnU~` zI}h(X@AKUEb$u?y3y`GEZtZH+Tu(}PKBZK&Mx+@#gK(M1V)1K^AzgWbNkEo-Yyz)c z4*9K%ewY6@_C&%RTwt0oVzs+eRcmSxYaC$3lkoT*b#!vgt^menNWL+A{e9(edI|Cc zxHZ{+&3{t6DSt`*0h0E2HyWk~`Y3N|B7uNTw(^F7EzwQ5jkdf(ox5ii93Y?jD|3rd zX$gcdsgX@-h!s>-O{w}o(j!7I5+H=Wt+{4a{o_$@Y?@8EsGkt z+GL0K*6K$+P$^Q{XC!DaU}Oy2A%TFR4BXzc&~QMRV`&t&Sb3G?T9O&qR!(D227uKb zrzexNCM*T_Y3Xz{Awfp>p4UY0hI>fK5I&}%K_+rQ_yRg-ZAO_lHjfQxb+%>gvrbNj zC{pX=TSy)g*+wg~)Ke2G zS0v<<;%WIGxSlvrgo=^-EaDNs_9!`#87IZ zJ;W!0C@MoLClG{G4wNS5jC8^-5i13pOdaDE7g@?r)42>p|fiz=E6b zpeeJk$M?)c@_E{leJlMEu+{XYRWs+Z%C~j3)_28jhuXQSB85gjIc~WQUws2>N{v%> zDt5$69eKvuY8*ebj^bIvALEMa$LdMiHb-_a0yC4erOY<7fXK$g-B84LhXFZi^>xNW zL7Q|xKr7CNgE!ubz@FPM9qm|V%;MA>skHJc9w5!(hp7!H*LEF0h?5<&WYv7JZ(%I4 zn?+6@IJ6MMpGS63N_#*azK|q~UQ{waN%FMveaz&F#$2U7*_6Td?RmDv1-gW^^&(r6 zKJEB;13mezZdG)jvksqB&R#mn#X1%oOt8pwf(;jUNLz%WxL&;cTkflD=H@gDg0}D_ z9iP=meH~0SEB*I%(wWCRkJcOLt+8`k!!b1l-aqr#dc!dUe&lb1xT<_oY_8Z0tkyTq zZXb=6q9iKGkw;fj!{2Va@Q53jyI~d}$to)O{K;Q|35gRy0V?KKS$iV;XwyyWTZa0s zWfYZ--9vaplD70qmBwEJYwW)ML(&%LIg_UJ67q|+&~H{n?UwIs1ec+8K}%i)&m|Tc zC5VMyj+erz;3J;rcylA0*PBnP?G+mbxx3=pNfP?2kfev90*%6hFW1k`_R9bXm7w9; z{uJQ3pxl=RD!Hen+~ee)RId-$LUTE*N1rHH1xgv;Lr61DF5KWGBd%60{sGc61y43l z{s8IvUUBywHT8e7nBEKm#cnH9l*dA;lRkv*tsJGJfT4U3zh1*-T*+6AJ`a+d{_vh6 zMi)@~weQ#zo>Ddhi_|1qB7Q}tDSoB7U7;yNO%xZ3P>_7{fdA1>69rHcCle(es5U^n zxlTtuPkVe#rt8X@0&O(KZb#FPV$+WSKJ`+igAS(29GOI#*x0iMHE~S5FsJBI{>UQq z!1*J(N${iwpfMK>+I?{^bp6^7u!mfO0V;C!cH)0XU;X9w`{NsPcYglA_Y75;CN0r# zZ)p@njvFkAYG#VUF*Wf106m>*-o88rrg`#WjXz>{eo+Pg#;^aG zq5i-30}qtFR?M3Ki3*|h4Vqi6((ic$g`YsbQB8mT4)=#!{-4vte?F=6BDPBg%A=}l zh*s#D?Gl8nnhIT;L17X3(k+Bq!UQ)x(Wq3>c!-m<6mzgw>S~zZ@2bmEmH2@H$ta}c z0lA#`BMCgRnvyiFgMsiRHN9|^a?NmxYT?BM66URvEQZ~ov%C}jhbE~+v8I*N{B*9~ z>Qqsxv7+!*>*UMR*&ur`I%N&mFV?A!5hATHtnpB<9<}PFZ_1KDGXt;e(yJ~%2=$Gz zIuP_ysbdIg0djf!HX9+!L#mDlK}-=8r#iPR+dO6YDs2$) zeRGq#s%B4*L$g#oOQxA;hRO3{Y-`=EyV`D;_PZK3rcO?z7i0>++5`jxbmLlL4_r-O^gv7%^k!+OOr%_b1y zO@|V{uNyR3BQ@83O)_^-WCd%tI{LgyUqGRM5_?wiRW(iNqm&l2K9K~30m z+#s#=WLpdHr>NV~lRUI%n%hxo(#T?N-OP2?i2`j~og$?BFN(LjzPJZ#N>=+0#9a5e zWWB?m;?q-dIx>JHjMvS8@$=0rSBM>F4v+I%cnJOHYj(~dg}hZWg_fFpKgz19H%XYNu*9f>+v40*U9YJyosdmclbXP&)pXXa6UIYv zI)^9Y*N~J9CL^!HiEbZJM+j4sZ!xh;&(j?wIC!H)rG_Xlhj#)0%H#!vLiJ z8e9TBL|SZB=}L1{E@ai3*u~|yEakOE_5f}Bzb42>KeNdG#SgrBZYeAdByLFP4 zR?`gUpymD;<@uWzSuC+jqT%a3S2JX`Qw2M>luhC7UKFF_Pmdh>*|=*SD%R8^lC$%K ze*y~4^B2NJIR`8xIF0(Ymc)q~2~N9u@&agx98bN)KIeOoE$&~4c+eYW+~m!ACV}@8 z*l=fdW|_c^+v@!2JjPVP4%Qd(0O~oa-VR!P+++WO$cqJHVv^MWO?^2in7lAo8unYX1yhVBcr;iX2NUV@ zEIXHS>}t4CCbC!}%8ax(*;G`8&3~J&_Ub@RwhvjVH9Qop&Y3e$lqsO0YAPQA%C|L; z&?t8K8cPQnaqhUX6*pyWTE!*QLBHM8leD&S5!%E#WPNKUMuqohdvgLD%e=tqDNw}d z!d*@Fv5ULxIFJ~tS%afP8}=rO6Mx@#t}^e}Wv&FXtA*s*h~F5Obx3G&);ZIRtB_Ra z6iSHNVnTRnwzFgZMPEC+25M>=age5Gg?xh~hhaUr5XL*1^)4#Eg?miWAg;C+H{~?{ zk`vAk)e-Z|jXM*l33TM(h8;1l2aKcl04FEfA?ai@aLZPA`)zu4dB^lDjXr0do7c8; zx3-W?m5+YZv7TB>-2%ePw^I%okEw5metRH#p#EMl#5l~X`E359heY9)N)wSgGA+MM zGOW+t`H9rXw{#pOfnLztg(x?moPHVSwxpQ54zPq&1vP?yF)oX*ANdaNyo|$#tnoCuo#VOXF z6JUZEhP60S<7%4Qh`&b{HX`5Coe4pI11bZWVb3hlZ<|SffF#z6FTeijHTZ|E@W0^G zcay^)0j6lxxmiO(#<~3%wTVj3jSl2IMa!?AbC5Z4rN;2XSOJaV1AyJY5d8xb@@utr z77D(755&cwkOTES7SBu_KuT?t1c2-x@&k!0BqV^@!Qvl5W%dL_my@HbN0m3cal3Kq zv>sdb>phXTSqEqWyj>i`ug05l0hOaOrl}jCauk-4NxvY^XeO=Q3?L0Nfp-e({bSza z8wN~LL(ITJyX8aLwb3u==iSLO`){w9{rgM_8p|key8Ei|yRZ0FvAH{an+ji^i8{=( zpk0gs0}FiaZ0wl7{@g!{_9hd6cNrh35-haJ-ZG2*Z;##oe~-K8(w)6^o=a(a)h*@_ z#dwM3dQBL+@X-ROmZn9NNvv4b;yirG{Ma4ganBjI1r0O4AmREtg=%Vp{^75k%*zg7 zt3}9vL-Yx5Skv4|m5(S~OPy`9F|U3O?8mmp3FOsn(|?3{o_{F5eqE(%iZD@V^xUR? ze5%#pIK*IrsWzy0d$Bi)_|*2^i!GM({uX}e_siFXykB(!6hI*Ojt?MiaP|;lhS@ER zIqkcROQT5F!mXE&6V-~RFrK{@*BV#>$)F)>zp_N{P)Ypeyrf1oT2i@o?+kWu-^7mn z0XgQQh=&LyS|_+t$rEN5?l@{U)J)se|;CJ{ov9*%rDb)R+H z7Cg)iU_~lg8{a({kJnavrc){0(xj@`?LlpuD!4oY|2e#C0ylzim%cTz<2H&pxVzoV zKxbc!kinTG*1a!U>*C)#E&jA-?3%nc zgrfrK{EFUMVWtJT#g0fB!@_kmbxAYeR{5?(vg32YaOxXf>fRM6{7vop;yiaeWq-lO zN(48+MzM;G4OA%G*Zyxv-&Yy#0Lk;5GB{Q~AJEiN1 zLg3&Ao?56fVaG})jeR}UBUeKR)>z@;Uns?Mv4W}sT z0{iyheH>EsYw1Io6oWFp(t@5`pdQiP+rMQFs}Z zSi_NAN);i)Y%W2q)HjSm$jf@2D$x;Y9v5)YaG!k8`6fZe;g#E-%t{AMwK*-sO*x4j zjX4*eUMAv8sD_q}>8HBAn@FF)EpX9kcfO_j0(}5^XG!CIWJy_Jgwzg4=0oJsZUsu- zMGRXx`vkWZSBHCM-HDF8^<)cIwc5Gax=*IfLcZu-mPw``yzMzvl=;Xuy5bO_+@XqZ zQLuM#cChy_b`KEl*l6F$s2YnZY#z?7E$T38g<+htyU9b7n-kr8u!v^llqLB>TCR{ECw#I|)?rhc zb@oMEE7x2Cg41P4Vx*rOc@AwYj?3hQfDJvG~vA4oAW`vfA`R1;qLcrNK zej(vh&j#l^yR>Q*(8>7XtHF!mkLO&LCf*YC2diu7zN<{^k8el1C#r(>;B4i=(*+{8 z75MUu+Ia$(ATXLqWS`-^w`Qtwj8keI&z=#OqTxDmgC6p~>8c&Nb~b)@4sD{tg@u?I zT%lB9P&BmLulj%t2L+~^D&fYq&Z7FUoK?IDr$w1wKkPib7Wa&|-LY|3(lB7wep^-Q zirl_ePn#a0`#HQx%t#N8&l_%X;>mJ2-bHxZ<%GXs1;qL}5La|6&4J+j!iRTJ^Qs#^ z91)Rt+g|gKCg;3mWD~alN&wlL!dF(4#0Z>3iHz(f224p`G8(3VozI8rcGzGb!F(s? z=GhrRQLN2$Ng6`>tAfa=zUcEtca`-Ij{Pd0s%i&&4MURoo0f#gc~A6a+MZI7TFF2c ze7KCWK>$M#aM#rFmSpCc#Nw83U;6aeS`w9Da(kwi``E_U*{g!ft-%|*K*wda8sM4~ zBr+9Vn74^<;cLu26~ssIOsOdZ|K31Pf20bn3x&)jVVYmQ*DQ>F5>4DBfFXYEwOu0T zg5r-T8MPQ8DWUH!-zC>_V z`^l9rCoi}eWgZ@i@}c5%NRmF*h_3?Mo9}g1%?v#l$R;!;FdWDPFL{a*YMOkD>K>lH zF5uq{=YP{a0<6z=wPc97w8Yx$Ec@F<&6US!X)~{0qZoX~NELV*!@W$D zPoJ-i_5T39y&WdmxsqSj_E24L48G;#hmeyIdz8WNUo(abAta`jnrFNCN)6>4isoF# zW~}P@aO_GxeI#>!GlAU6J196on09BtR4D*nsmy4D;UagTBu7R~15{fwP}$2>vpYI} z%QHYwLvCiki(yV9VdaWr=yQZn!w%|tH?n???fXPfbbEF2q9xImYT{fqi?*3CS(X2I zO2XtTZxsF7)1qx+XZgk^|FLNo*yNi=7PTgSTvqZ@8RuFN<#0{?<%`P zdcPH@du@{Cj(GEwwsY|{FG_0Rwkw+9u&bn!7z&{l2Lpv#Bg?Xyp2!NnmQHSCh*qL- zQl~b1EE_uE1_RRuH!~J0zVbfq#UaBhu`(jPLf1N_ zM3=f_8dwk9bIV?RZ5!7OPAs_fOM^>EEfclf?g_^Ijp_!Ku*UY#@Ws))dW(|C@q+@!P(cx$FIBP z;3jA|Iy91K6tn9CTni|Qi*VQ?U>faZnyo$@%ktg@4?v`T((;-! zEzb7_Em`b=5p@!uWU978TFU;L#;I18*o+Ma2PbmdO+kA@mDyEwlq(je4PWdP9LH>@ zONXOl>@C@la54Ngmq`R>D4`am;D#W6Iyz^W=M$+zl|btSS}XVLnwn|%ToH!}oK4Hh zy@-{R55zU=$x9F(_F~gHlyTNsWS#n8Syxv4(qhV5ZZd!XY(;b+&WWJvoWd7ERO zY1$0Z_Yv3+MStDD9OvInL))^7orh^?O*4MiJ6?{6-T@R%I)OY2JkkqbJVgtCzhLy1!aLh**5QU-Q}gB|>Ebl%o!g0Fy?h+KMkfGgyPZnyb*?btFfLBN zZ&9o~u@dGg4-dETa7EtWQhLkvjNXvzJ& z*pv$Bdq3XhIhV#~Gc^cuQ_XM@YVTRHeA-8&V>D)&+~R36@Afb*?~)|_(u=ji*w)n1 zimE*J;pd1baz9^cqJ<+4o)JObom1`nZZ_dhLrPp){ez{x5Ht~U>7hAnA2 zvxf%iJyHkTvP*vrw-PY{8_WUQv^F3YsowgQRrwFL8xYWOX9khKiFOA}J80QIKwi7e z7vsOwDgQT~fyKg|VC})5Gb=Lc*sGrRyx7{dFw#k1uPAzsTzwivD6C_ zx$Upvc;}4~5ziCU{3jyiKO*e#-03f50@uoj*m?j8&<8AL51>{7B^n~Ry~Swh5)F0M zaWXZ!zC0i7o|N*0r60IvN=?u{k%OwWe-qVn1$ zP9`!-Nm?+G4YpufjgbG9gP#f!0YF0RUx-^YuloaI>(iHZ%l2tKLSVwKEWkB5HnnSFz*}& zS9UZ{`E@R*(Q|e(hczCiPIaj8JsCzzb~rY?4YIn0DfWX;r_c8W?9XevWX*=F#w@JK zU3RT4*B!3{0h^tKvq|wbxcB zEPkTTS$P_{V>S@5*iYRSA&HYF0zZjPZ>TPT{}>ZpsxIJ2|m{k4e1F9`I1U|Lb8)mI1?9j1qH zMy7IeJEuf)eNm=@KT1cgRJ~WX9~LJZphMsk>TXPK&VS~amN-Gl*3#ParXJ*GxehTm zpQCK39%H$|6)F!~S8e(@fU_B5JN=q5f&A<2m^Wyh1#V3KZHPv0aAl)PC$UwZY*Tr| zC&9B&I!+Mf#?u-yl5=*LzVhPHSCKvYW1F0P!rp z$C#Q)HfF$ZnGcML@{3bRbyib{as9LS2u{3(FebQDd~t|0YFbR zuaat>j-D)?m6l7*_e_j=tw%<*ZRL1#5m2WDYmFO@8;vT;jy4TrT3MfbXK*usUpa;Q zly>f?^+#FnCw}bT6zNdFAGvsMb2BIBOyz=uZ>Zz~g;!*~zhRtEy% zm1$2j?wgZ7sj4QDikQ@FaYo2n&)KaJ@(q(<-QfT00v#fH)}~u_?nf_Dk$fTMx0hcT;Sz|J@?yAN?njpO>UR zjzp2KF*=l8nyktZ@n_{0PV!AdMa6;F2W#wPNmCTt41rN*#sKpBaZ3%(Tn_- zxZopSdSHu{4;_%^n{IVdD6fn?Dw0zDOl|&x<7}z!6==!2*n{ib&0KI1ijm!89%5qW zt=JoZ5>6jklS@*=Td@E8+mz%0w)jjiYRCO{Mw4g}>~^D73$E8vp=J$n1{DQf zfnDwTeS&71cS) z=2(gpCG}}K%J)k^w3IPuIkoZS+*9bYpZ<^iQ}Ym4r-;fLs{O|tI_(Qytju?MWpMx} zynjjD;fjpLRF`$=Z=5pZH@J+Ue^bY}l(sqXmfek-Tu zZ2zkYkgN`4^Z|Cg^Y6%GE0?qu9D>dOilzihs>jz+BkDmnQj zBSqXHQDW^vIQryvGnxn2Wpr$18IVX~?$j0Y60;XE9%+Tn{&ZXG$pstrU_g~Ne&Z+C zDrlr|9HRl=TBv~flbWX?HykB))*zQakNcS}X48sa469-#=s&c|(rw@)7ZBH2HZyj2 z58MZ-_*0v2HW(IfsPtH-vxQR>R7#X{_l$9x%Aq02IqmK5%Un1*^7}m-c97guKWWtK zr7mW3=HFT~K&3&ricZAD9~D{hss(7|JNue-4m={gV#PIXcCI+_;uricGTf5K3W4`nF# zVDN*(4au6xTH=(thIk8XN^iz^TXXD}%0o5T1->njB>(f4q8R~OnlrOmb&x^o6!FJn zS$s0qjnnl@)c_Cc^bTj!9GwgBPPA6PO|h*tb9a+|?9Nvr;}LI8T3c|1$NfX(wl5VB z{{%U?oey_%IWETspUj(Rqy%4hjef;tOKi#{6w^Cbk%Q$$le$RM7o2`w zIoa1@U2oeoJRm8}pv<5eXI1y>7(eN$l%PDNTE&N@(}9So(+_n5o*s(6XGA2^~{@My!Ci}kds!__8?=}WRxbyr9J3~J{DOwphR|A!Msj7z|X^Q zF;r5x(!XQB6xDBrt(#0@*+38Z#quj9qVZzDvPYAoG|ZZ$IZJjW)7vX)?rTdFO5_)` z`spQt=ggH+v6_pqdgCE#Dg-Eb3@mBh2baOrz7Dq$erd5&4>an6AMs`Y_(G%sb*sH5 z&@|JsLxd0Nnk)CKnyq!jCk?}|ahP=(aoYhNk>S zm=oab@8FYE0uW2u_lM@qr`OGwvZ!WI6`+0ijMn+KIS%MkE&^})laTUPKh#M>r!F)N z{5h~0O*07=wlXn*DrPi8#2|pwEkz>Y@CiT+{J}!~KR8l_h!dhH-V0JUHf%+z*B}>3SOl1baZ|Ro)@sxXw<;~YaZf)7DxQ*nk&rq zC};cfxwVcFb0j4ilm#MjEC&nQt_Kb4ZEnjh!GZ_X zA6DFp*@aW*yHn3iWvhC0hE4^5bo0wBH-a2h0NIykGMkeP zInF_z_;QG@653a#)0EF*1#KDABE>z{bQytF>Xtn(pOJQSfy$3tvq&hzE#{rka`!c}CY`7bT5J5w+;FeXpTAWBolQa(kg0e^Gc`9gd*sAMe zCEPy3rUJKIzQU8fnXMb67~(O{yhzje2!ojsyi%L#uiUAuL0{7yJjn0CKgFJ-i_D?e zpH`Kr#8n?meX8~S2gn`2P(d`RbGSQbqYb5q3F#aVI^RA&M7)-DI9}W*=mXokf*%22 z6b)DAj8-*kPGxdXEhlBsMRdoR#$2`Qq6_2-m85m%yIai8xdc&(teP&0+nMohH_?Qr zarWk=(|(!Sw5HY7obaoJ%LPRpu~CZ1tZ3;9XFc_VbOi}s2@XJHrE~yIE549HIw4j$ zBcyhhcwQ;}>fAyR<=q3aXW#L*XU0f7Y>ROH z2dJshJcA0JvKH@_+{H`b=SiQQEAtk(zt}%@K?M@Si+8h_x$&L_aoCUzV5J$9u$eNpbRkYi}BHO8j-lF2m> zoic>|eF+NnKsy3Tb&mbleT6A=73a&6+?=liRxA^tbZ~D$TJR<4UP$Rk&3C#%nOBtO zxBkSEw>Q(^!vgD%Jkr@0M$nfK{A8B>RY3&C1PVZHS@*FaTB*{SaMNud|K^i!^XTbw zf8ok8OO1!*g5%LV43|Vh_kVzPlIAb*9O6 zmbP{7vLc+{B5x7)NZNs-cJ}z5(G4`s=*pU|96tQJA>P%97e2^6QUJGj?_K?Stn=nRB$0m3G>co2WFh$$3)Dn%7@M@DB?Rcz)nj&aOih*U zCpa@%ha<+!gfQs;cK$eE@+V8KI_PQ-KKw<8s54W_j8o_8= z1coumWN(^lYfOT~qc9+06Xbe2Nx6pv^FUcNa=wfI3_bwJ5Qz2W8bo%BxmAstc?#xUBu^(_l784Sls1#&E5 z2izel!Hdn<0$HZGmyTHk-^@5d8z2}naJwnRJA%c{{^w3FflZizkLE|RhFbT}1_p3} zwlrBW*PNGf4^GoUEcS{{O(`lGE9yovn6=bro(C#B#UkhieE}@`y!Fb>C@yibhgN=Q zz~Q+vVHSmfTqYe=K*^*Vf+Y`^8%7*U@l9dbBU`Eybx-DKFLPs6C{TQ!`#!UgcpBEQ zmXPVY5X#*)NAVFO!%V|7i>n+hLSi*fGQhG@lO0-r${1$^HF*`|A?M*SrKEV#TbeB!hzsa~Y>KG`gBh zCs9%|!$2!h0wfS2nZsmff_4I#d|(H}yV`A3g{%8WHcVVql+1=`VX30Dx9u=fB5LD3 z7L4am!)kN=A$A(c6?Mk=De?2(^EUzVYOuAn^}cdNoHI;IeujmZuUoSf0{E)h?4&Su zr$iOsg00qGA?$C^ARiVRCOKT)T7TDjRSvXveeD`bZlS*X0D3V>7g6exKnw24HU$e<qR0$V} z5+d7tXmh`;XGY1RzV*q#&{sJ`O_T^TE)ToBd29Q}@9^|rwKXr84??nhJHCKhA1)R; zNRx~&hbuM;ek>lwV~@nYeTfF*Sad(uD!L?)&XWL=sIMQL(HhV$CRx0AI2fNF@(@vA zE?KYEl7CUFB*q}t4II=UZ*EEA)PZ_b5R#mF51`7gTnmGCGo1Xo%&$?J%ZoOL$oOU4kN9otrYLFUl?5K+h zo(evFH|WIdTjS8KHDs1vH6|OE%Ow6awzuNi3zZqhL6Cl=LPJN|_-<=%m z85FkNMgHb#zE5y%9qF5i=pBs&yj)(~VoYt|S!kwi$H_X9U(5_S??&XZELG$BY@yHnzFWwRNiI%&-Yek>) zyO>)()d!aRl?m7)c?#>0&mJcd^-(7op-cAy{Cuhjd}>X(rcQ_kIxJCwHcljw5I3bS z+J@Nqx+|)a@8&BjdpnZw<%AD((pW*uian%s?lFQs|23i&^Mz7kTAQY{#gLmSEmtmyBbn zi69(bxdteyM;LbWv<(3l2E@!et^oBlSfa8VR zD=}$q+qIxa=1F5_AiM@W`s%2!nTlH5G}<6r>LPP?yL3x<-+!%lX|=j64Eu~U2Xf|g9KB@1HdqOJ^T^rk1jhS4NErJ z35+t)Q%r5@4WuGd?Kp|i1X$I1SaT@)ce~=qq}|P8qwC+aH<%&8m%e>6sIkn0QDRPA zGF?({OWm==EjC7@A8}~ayCX%tyUJpDLC|bppi>&$plelak7ViKlKmb&S#NaU>UFcl#A}_UEb9i4}EhJ1`3B{w`m}57!=DhgtrKW~v z)$w;}T?7CV$@<9_zy;D)8`bv#SBNlS-%sudVVn_f;nDNveI2woA$~|Z@4L6Vdo4^y z|Ez}DlpTir&=p12f-?&izgTuau09P>QfJ*R)+WZBl9RX^Uo2+N075 z9yvtQ5*M)4A#oIJ%c<2s3{$ivh{uYHsXRjI233B92RCyA7Je3@x3zWsER@c=MB7<} z_fr|S*ho#ke!E+<|1H_fH>%X-wkjN_9#42qdrWaP*X6N%`TAOf2?^W6?ljC|JZoKZrtn4TtG#a8_ONT(pJ}cYj1PLZYQ`7Zou-EZPtK|uz2#n z9?kqRN*g-|^4{_)UO?@4 z*ja0DSZZ?lHnC@@vadZRXY6%}WC>e4ev8t8M9)d#9I3Q+n_PTfaS3E`t?F2>F(#9# z<0()63y>rAfNdwE0I?zV`Xv#dnGRz)ER|eB?tk97nov}owfIxIwa^%f?dKbvP4!Lvx-fJHT5Sj!Fs8Yo$yhx--v*(rY zA(rkDze3gn(MzTXFe5Bl2Ksr7-pVqTP4-1JA-lvUMuonUcVa8SpRp zLjAwK?)BQP0hNc_;LEOWm;+-*&90T`!t&KJ$AsKH$)%y=(VKvT#|sQ(9QtDfx+A4n zm>weeAWrh^pTg0f#*c(y*s@x6l+pyNS`fo`5^jr_r%ddZsUcaU-<+~WwLRbL?ai{z zD)ab%$B&xEEO`?PcvEWCyg=vaXsJP~3sJ78fewcyTj_MG5PkFB#0Y-WL}}XF6^>X9qvVis2w}pH900av^GT#jA?!* zZRmP12a^`=9Ht%bpFu~^^k*-$yV&<;*2+DT-oHWNio3b00(!hkcXe0-L?v;H#Ih35 zhR4|o?w+JlHITX*Q8=OUPFzq*J8^Ecm8}vh|GllMG|ZC}MKJ*wR(0p)8R}NEaax}N z(+hF~4&4am?tW+fJK8LT&{qfWKS06*iG3&0|*Xam%R|WDLBcA23rFE62x+~@cvM}WjbW0%# z++>Qw;cnyqAg2AcwLqczjW4tf-*u*X*%@s4d9saB`pp)H)mjKRzj|O3FU^MSYOVUN zpBrwiiTr@LGbvZo?2_WPBG1fCYIxAx+|k8QRZhSGbkb{Jds0}MGe6^!))7}|$kpba zDMWNXnsDACK_{V;+!Atnv)`f5b)?jZFQ8$+rG&wwuSqtJYcL)Q!ucii< zwIEm^2fV+}f7oqi1XcODTU?>xA9>iFOHA#h*VLsAO``om-e1)|$$PrKw$53y76e+l zB{exGFo9Y%SLjHLmX>^|(lC##yN?9V2#U!5I50eta{!IAH3YQhbCM={K6~ayJ_WBr`qhZP{afsZ`JgXi%x_5GABE+>y(Unl^c>%a{*REL?rFBFvf+=Fg z6yBQPz}`a7*rf-ayJCEx@l-`Y{DQs3B8QlA0ah6Iz{sKsa3n=Ho7gr`r=>f&5boho zr*O7oV?ab8;n>y^^GniBl1bcdhkIUAld|GJ?vz&X+H1!!V9sjg3c88~7gqqAp3~WY zp38~w(7XI3V7_dBf)U}eMJ;rTkph3~?Ph&@PwW<3<@okBjP%Bf|2Dc`^W#IT>$Nd0zg;^C(U1BEmid}&01#>`~d1^2R^J@pMkHT~o1;eRyv)>!z_Hlj_B zD(m=Ccj)Op;Xq#7P({Fvri0*iUX1c^XGr9kzq;g0?IT_)fH(W_;^-L%kqwi?Wwgd$ z7aQQ&r4IH2DL)q#Zd|(4I0xmS7Cg@E{;**CwTEg;`p={Ky&9qMuNZVX7owF!a5sTD z3-;mVR2M4Qzj~qn4pav;3V$QRy%h7We2hdunaB*3ZG~mPZ~j{(Inv+#1wSJU{@s5E zrSx}H;6IxT{+W6AAMor*fD%xoq8L!k!2_SbX+R=L{VO;0#4|i!a}2-Epv<XSaO>*Ia0stD#v=QOcP@cR$ieEVpMgu8ANuor4qg}5d`n~O@W9fgz+6K% zr~ZUoR~hHQ*&dGN+&Al9)NF(B4Idbl8X!)vtO$f&iLYnCcCB)b^&mEh4q{uRZXWBD z`K=Ceg*cUU6fkG-Zp8r2MwElqYFl$0vj3zcJY9Qw64s_qyfYCcxX%3j!;Z3o06ZuP z{OH>uduZi6z_z@4eK1rz2B8(Dga}Kj%aft8Rn#+i7r;?wOcYmIBC3q&H;$dsqPeiN zS4(S8=7lZFE%(^;w%J^@ku~FQ3J|M)fb&&ySfA@IWp440>7Se|}}@J4b(h=N1m z=xOP9U~Ri*8R<_=E1dthr+_Lc=em14CYwYqs4N^_pInPFa~ZVvKXD}RcUO=Vf37e$ zej2*rqYh>AU30b~kaw{mvZ%6f5>R9vK5-+|h;J!Fr9@~*CGKr*TA}lyB>Qb{ylZiv zB@D?`Z!J)*vHQvhd1|JK-q+KBhzm!7Z9LuRUUb_W4j@APQ7yH%8*$(0ql(L_``Vx78Xjj?qZRE~9I zO~T|Ig|-NR8w47U&{Ke%QYuQTU%OiECk!~ z&4Ldv5`A|;;_nHpY6{nHV!2$zHqyir zi67uCzPk*q_slogZ1RYj_ce^$7>m`=G-Du~6*)!9O_^$c>CW<+e6Y7(-WwsU~D7df6{I-X;EmYy6EY&dO zj$%l#NkOo!ng6VCfG;74^R(sB+?Dvg`tI@#oet5|g+{w)iL1w=Esy0@4FT(nB1ap0 z9%9&S3{>s`?Ox28)&q_mA=duz{ROI6*9Q`V^{elHfLul`PGXxNl8tZ7SL@(4PP06!{q#XUbq!zfixB#FFB?*elvB zru!&`ecYUjN^ZwWJ3NMYLZvX1If@}5BhR=A^^9|=4)^i5UM5AS@mG@@Nb68SZ_`@S{BxT!Mtjy}Mz-@V>s?=Y<-4b&)2q7;|j}NtIQh#j0L1uH{W8Z^~4UK(1ltxiN_rXrF@YVq3F-DZ}WauuhHr^a8VMhw?!37X;VVl)Y= zYJG#JmlM;r?*|!PGmov0vxL48X-)+;6k)gGmD`1Jv&^mcZjM|zEGKD?F`&gR^|H)w zDL)sOPjER06hEaj*;#Wja191!r|?;(+h94frYvr2>C4t0>I4xA#ZryUy`*(`|NNnB zY?34+LP7mHx$&2Nv#q-3k1UNE&@Em9Pa(0yi6??ak7uR_lUMxT;fr%Df5uNodrm8> zQG1~`M^-UrO&2XTuDvxN`YDi}hRg#yiCE%w*BbtJ!EG($Fh^4>56;}pOWNr!*QJL` zRghGiXHjh5=Kx^3DBk*v!Ugr~dOr_A053uN$!&aDrq0&T`sJhh+-HZiUnJmp-Jr5Q zJoH6VEz8yDMcQ2F9rC)ZMZP?}t9dvaHW}^WwZ{XUKY^R`5bjJ&=PW>oj** z0O^`~e@!)gROEJs-lHfaXYGN;7gt7~e}G=!X8r(yX@Nk^UF%^1 zJW`7>{tcZm@ct^`WFgMnO$@j}z6`&)2KL0ukY*9kJI@L^pw$fq775L<05I4oyvmI9 zgno^k zl3snc{_#K9d&{V});w>t@FZApm*5^CxD$c}4+NLsQnJF!8dS=$TALg$6eyfF4?b`Z(ehTV0`|DAtV5_wP&hf+rj0QxeZssW4MxNrAuER2oGmc<7fjP=qE8VT3 z9hl7lY*^(oF)Q9aK{FVjr0GB3MW$LO2z9|UDcBQo9MDLprYJEv?t&>iza&X-#TccFg|X@<`Gc2nHtqARHisNDk_+bfq+0~-r=YjAm$&0 z^KVrIfQd#N`}e3an7>eu8h_;`ff@cuJHYSATQs`Q0GG|}BOs%k45fQQHFAJ{R}#(u z`m}!v4mE3j--7?iYnabZc*i2(y!@vXXXszVh<~YyEct7deY|i;q&UQ+2$EaURW--h!-&#)bU3~6$C`S3+`&g`@$#Nz;@`(X51=~ zFkTaNo$mFkc%l7R{3ft=$HVU9S-!}81jLWj=ALS6c2YHeN|wSk3H)g-BFRhI9|1uE zhC{gqbqeG9V^6H0I5i$Gxrr(qNwWYntztvC*=BGgmTYrd;-v@A(w>%Tm79X<=hQE^ zrpepDBj)2Z(PLl=+1&=d6mZV^7c2$8-NsSGhm1Wwg|fDpi(6n>u!Ix)NO?`8eq=kTzR9&=R6jZ7xW>!W@3%JlGA9((}Uq}DiW~MX$W>nB_S5YBfV__M(EN30< zWJWAXzfXD$XSfH-A=HW68z~Am!aI0YZw^Fn^r5Y^%btl4CoHybwd39kqPDR0V(zM? zeBgYMy&YarhS!s?s6cq#rJ+(ExZYODHz~4d8i!>a5aBb-)@jR28TGB)%!_YS=RJw| z!9@A1$nQ~xR|)w39bUG=3UNUa4g_4?^%FRecsyJ zXzh&mlg-yot3;c1TBV4y`c}{UNmkNg{iT$~MARRh1jqdD-?){sRNG~14i*&W_^X( zS5IZ#EQZk93TaQ^{PheO-flYFM2+~w(YZo(HxO|(qMuh2jVK(!N6*l47Uy;Zkfe3f zfsxaOvP}(9yw+cCq_+@a61MHpa>|h?b0rNC+F~)q99*MaoL(_AP?3DX^GF!-bqbaTbI1f#dnE?7boaLTIwI^cjz_Kc8&E^a9RQ9f1cM9Eop7N zDE8W+RX0M(pKrLN@D+sh!8B8apxX%5=8LnFloKaOmE@26+oPIGGC91fdbf8{F;tc6 zFDP2hb8H%XuA`-Pk_t_X)%Rf7Kci?Jsgmk+mas*J>!*!&uU#2-Jtrf*&hB;wL3?;03RQ-!kK z%d-|{rZ@ppOgC0(x`|u-o`!e$ywh)Wl3`p zjLJZ0Atjv-qd-sjQ8!HbOCe>DHqL7Y&H%cHJnWPXHA<%0*_lJkE7KHwyEWevy|KgR zA71Q0RS{f2=wuA@2WWOZ=BL2Mic@FbV(G(3&l;~|_`GqS=U_T!yF#3Va4tyqH-zc; zP)j&C6}1_OZ2i>-lX;*jl8z-$%lO+mg0#qx)ZR1l)MLiitBw=({;#TJoC0h1LrZdh zZq7<$iZzM!$Kl5vG%fF_+XzT`HZw)Ha@x|9vrNkzax!4poWMM*ilQ87 zErIrI8yF6HB*Tva+-aI~e};RMqrGP_2;yeJ7x@(rT6|xHB%I*FSMOKjrS~EE0eU;T zwhHe8K;~4in<5>U2;|(vre!=MRvNpBn%>`VQ_R7{s!EcZR4>};^kjX2vMRE?F}!dg z%DQ5>P{&2gLBl$`i82;!e%4#@3ZISU(n;PkycMb+rryUF_sjGskPkqXXolYTl5AxI0|Ijtv%3D!37l zi=!G~#4>eN=zgTBltb!Kbr=7ohD@>;pqqq8C&7h3*Wei&0NIybk9?yrWp$xrqt!g~ znuP}5eBX2{v+6~vp*~c|=4$bnSb1Zm7Ipo~8S z$S{`J=TvhD7?))?wuqP&^N=W4WNU{c~~7LE|p>6+pc zJ6BB=w{=Ijfg}V!p1!qKkF~TvK-lQ{L1Ps!u|!Bd;tZK360&@cV}=BC47+ue6qC&< ze@!(e%Gb@jE4(al)Df0yZB4M|U}h4t4O$xr=jk&*t-0I=hApUvB9fuF-K?`F2ej~v z1C`1A3T+%J#Z0+5Rp$E0#3dNNRJH)UrWtZTm}w7Q`R3lw@U}!4PK1OSXV|9~VAwuD z9!0Vr>Bw#q+fNZdX4e_rbxU*;R8wWtafnM*opu=AoeZhPO5Ew}afDLC0+Ow8EN&#rJ}EJ{TP3IO>bc4MC#R7mY|*RoM(Y{U@Lvhj|=e zfr*X&AftB!Tl4++D%d#CC|GiGi5{E1N=rhFe&eOch9d{eu;#T*UlU7d>G1buGcu#; z@}(=h7}?WTpR&mqVJ5__uhqIScN7Zr_VAXWgnjuGgDy^+Hx_RrC@3~oRcv|3Xv+V} zWBd-PD*~+!fHmqbbb#_|DMBdiyD4dbI4dlmu<=9KzxKjBLG%9vsMDGz&PRmRCa9~X zN||%O{U44y3Z(7?`U&9j;ZDoKd@&|;2uQ>jQC_-ZXy0)aekT$XTF}zz6v#t%NtTcd zfj5Pz$hU=gHinevk-P)O(+k~hnlSuZPR7XJaxx~ib{jAb1~QS|z0)rzhn<{Q(@#Ia z4d7W6MXX{w1QG}iQURJ4#wSwtr*!DwVD$gu_qYfx)h7tGCCOUTI9es*PO( z`G>ToHOi-zpQrY5B@V*Yt*rb(C$J$rS9Q$~gJw5^YOG8U{yG;B)evOmj)YVkdOa78~Baj5k=y~Jt8w3za z#Hl!Q^^$OC`N*%AVzfUGDk^>$!`oz}Cg{4KME5lUcOIWp08pL3$bXD_4@wjcNj6vz z!_Cgy=X)=^#*v{^Y4)AP9roTY!&5b{b}fY&_YxVmzNNJ-jqqJ<)#qWF&Q5zC7>7RT zjq@TsOu`v&V%LC!6whj-RTrNzS1D4k?PgKvR+Us!6cT)z{XhBwF19lvC z{DB~uc0|zzyLu8cxEd>5;a~7mxDu+7ct*=TRcP-rbQY$ea$gd;UeP*vd?U$CgJkm) zr+T0T{Cv?%V;ZAn%_&@)Q%uvIe66YkF!tt`tuYR;N@355&H z-*vU-iQJgCZ5jw%SQ(`HJbZ*sec7E_DRjgs!5Y0StC}?NBnEcDdgX5gr#&W$%`tVL z^SPh9CczGMyr8=Rm13A{;%FzFQ8FUEh5L7tH8Ni8W*mh;*=}=Vw0_!}b_Nrvb3pXh zD2IMo2oO{cX;N`8%U7s_C1YV_{^~PKtJmNIiy)n=o+d0GhVufmRi9OY8vu3fl2!Y`=K*47g(&0ssfE$o#z=?-Ft z*-Ra9PdeTST9W=6e=)O++>FT`6W;9Q7E;iP|3?yT)>joGxos`Ss#6e@2q6z526#K%illE-A&G_)85MtmszF+`Z7X`{XsyJVa& z&a6)(;X=eeHJz*N5@+1e-;2nTh#s&8vQT5SWhL&U`EwHqo4u-7;prLf;v+~BBMSE?eDch z6qI+hs@eZ~^bQwy5_hPtI5?pJrQcbk505klqNiUj=Cej(C@E#6;n)du`%!{#iqs8v z!+y*D<0iqr>Kj0x5 z;b#A?B-d!E+l&{f=@89HA1E8qYi7Z13$fa7nQsYMqa0Rn1eu(2|yS5SQ4X z4}}1Z+`d;V^J5qrx<=2A3Gy zj26)9I7`UYTI^c1tb2mcnh;Y_8@Dt%30=**+333=2rJ`J1i?X)`^MWyEp!Q|1l~C1 zrr_6>@}jn77WEpm_gnaB#Dl^ms``(>v5jggYEwiFI!dHK(yx1 z)3xbO%FSjOX8{Sagmf)qUc5#z?@f|um{L{_`dP^cru}MYEPJkc_w$1IV;ZC6iE76B zqL`wL7YzyS!?51*7FD5;BMkCV#ovHjfUaND6ZEmi(U!(>n^F!Pc}M>-#n|y6Q=W*LPlw{xJ+~3- zoRFm@(fpqax{Ja|Ha0{ujO+X#C8X~Ifzmg-I#R(nk2Iz|LWIK<{bDJ~isodgpZx5J z;!YplZ<|c@{B5eS5a$j-kv{L*>VNo~{y*ojGS>DPfaC*Ctw_jYFrcFT*nc1C?(^Wf z=(A(1h~V;@j&ZLUB-a~C~Nk7F3FNoYsU(7y!#rH4I&`ja9nMI>sZ?h$J1%=Ftc zwHeP~OmWg&AF7k$sK}aBtcwvdFe!G`%mse!D+dq50!f0;I_e{v&626Vte@$pyAi7% zV8f(*H&YcNtKdpxxYLzL)S$LMm7(<7b{0q!s?GiFUisf?y7`^ufk`Q|zJupyYd)y^ zIwt$@o$r(+oyZ1BTTf4c;$9l-&B4O5C0TxjA3zqBD^ zP-`uKdL=1&)^p9lk6g!#!C@`0*Kwv-xge^qZ8-E!CqBjcX~14VcRmIyjS;JrD2b37 zu18~=@nwXbqoWKKiXn@8A!ga08i9(>BnfY;6Lr%N9iXjzfRZQtg!VoG9e@TJ3w(BR z%Dy>;BSOf;@j!d@)-1^+`4klMVy5_eY!O@KKl$cAbht4dpPpHaPmyZ3R~ zf=4<-c`s|#t~)|*|9!w=?YxwY=v^rW)oS}36CP*oI^+Jl4!f3m3&ZVf3UhOKX1(3p zg0CAdd$9W4fntvXQ=RdH@)Aep51W`)p9Gvws?w@fP$D}%k$p9!GD@dk+m=0^+=W`k z4^Xv!?M3EcnR+j3ui?9AD=*LZ~Ni86z^liCT*I zsuxgHJV%`^E_D@?nT72y-_@L`ZxaQa3wAVvY7a@o(VpW-#!e@+-Kt4f&h`rKr_lHM z8G}>Xu}b}l8j4|y6SX66did;@ce!I1wb&S2-*ls81`G)Gz-hO4kKH`GhCKEWw4ZA` zkp(4?UstcwF=I1Vi`T@0Eqr3k^YDFiSg&;tI{~O`!3ytb%B}qdsCop^LX$W&N1$rYpm(TmsC*gCP zCZlrVi-8xVB@9SIpBl}jg;x3+9?W1jfmx40jqH?j7pPxacLHPzoqz?_4&ZWi0spHm zx85x=&YwFT}VVtCEd8aQh;J9ICW|o)YP_6W)uLYSrny zIrWXTvGp97*)N9_HoQNpapnRd_8z{G&}oh%IBo5pZgCVt$q}zo3~?+eKV2vT_3;Qe zL(w6G{I2XaSPa@@N#4YaJXr+p;>3B#)=xgUd5tKISyd1+d?@oMjutA33?u|~?4{I45hKwaRGFQ9QsOdi= z5QBs7J#5OZ$254aeiegx%<2-g(A|AzmV#1RU{|b&vhyMvZno6Y4(WVFA2#8 z^uXXvXGIBKDv8BjkdvbthRX?R*5i0<-M9_QxgeKG(2-KqJEHf*QiBBiX=;t6!34dI z(7ZMGOh$xq!Jn2%{mWIWpm7e^u_fjFHbC!}CTD+6Z9 z?s`@CwiM%sOiNuyeGbrS8kKfH)V8L^%~CPYyFmuG5d+2F>2EFkfyA zf*B5m5`{i7z;ED^%tSM@0lee51vFVJQL8){Ev~cnLxiXTPpfhwbS(-`5 za>BX2e#OayL#s08^Li1A2BuDxGS^;p3{X`jSQiDJ97hp68v&|>=lHB8<`Ow34_57GP z&mQfSm#&8Z?2NE3cVZz#a$>2OHSKsg%^XBWDr2nw{(hd`>0VQ?!#$z&fxkl+f70pMQAy3$^>j>G-q^)gw1tuQ2@2QG zaB@p_`1C@oC~Ia)vYY*RRgI%xz|0E*Qj2iT+XDuIjo4RBXNtTlsU{Ld_1PfKV1 z>Uak|5tncR4$^*^mi)sKYU$M{O{K*Aiy{Oo5}sD*aRKdHTV(33*myz1Y$`Y zMIC7LOuadfIL2-;6Savk>`#MYOrhPH@C%*YWH;MrH}M;^S?|ZKk(-$r|qe|8W1q$?aV~0S3VI6`2M3}&%HM?wS=8A-ASUq?D?qR z-aVc(M77w-#twUSv^mjifgNM-**Z>#D=8}9)ato6OuocZlmd~r)? z-d>_wB;IYO4c~zBeogAf+cP)cn(OS$&>F`H%Pbk7jxOX9r;XZMeRQk=q|?EzJcR=> z7h*YnY<8VZRxJm+*cKR>t$D^|`YLQmZj0bP^}i8rUF_nL@X@RPDNQ%PkRg7)zJo+{ zhh}kh9W+geT{peh!LN45wPG#wjo$AXQ2*crW-sV!3{oeS3f&~Xa*ShJMTkgJf8SX$|7f@A>7{0Z>BXJEJ0Rw$;kLQUDsk!5I}RSVUF36WyehNp~;_oqNWw zs&I`JtmieT$-ZC5x*&tdvf-Kn{>qe>Alhfw_%h;@e;lE>d0$QlgY#e-cLEnmY7PtQ z#qM!zk#tW5MS4I2I_{98?=6C|N<;+@imZjyEGaCk9&cScFf2z&0zm#{i&93ZegzQ%|y?r8-WA zS<~x`BolCX=2OE8x*T(ooN_{-`|77 zr%Nu=XWRj}b94asL0^HE1-Hp9v#PZEZc^0^MxVPxD@FVx;vA6fG&Nb13$Zjvma24N zl$clVH03CIw#Q8on_)Q)C;T@)lK0O!NZV&!^7n5I5baOHr+vDf#_WM|OZ2W~bSKL= zMr2ebw`&@7sw5z0f}QZhf0pcI;S31{=8V`}B1eZ_o$k6qt)j9)CVGc8nKqR5x(Pt< z&C_@LOXeWxleo>wot5&tmRblCxg04}M#~KMls$!*ZktxXie!&jP43vbd~K1jXRJ)U zx4`^cx3~)~wQ>yH*|^bqzUJ;<-p))*yVnhjI*r~&5Ni}!A+bqGe)bCpY>*HB-dnh* z=1hi>KQ*P;2rkU5YpFwS^@aBzQV?@~<-_=L_2 zWDKYQ&@qsN_~bZzxlR)OAUb%MHE8KA}k#eb}&4O=GN@os_8>x%&!f zYFM+zUxqtCLs;xHAOl?1fY2#G9W64yM+u0 zIAO!oiUV8r#5WcFUlWKnLD^9xuhv3wc_vQ}l(0Y1;bDS6zvy5f|K$+sw%n7FvMBjs z{GKgOJ@T!2K4IWu;n#PhOStfiZ1A8_wfbX-xm)R+`r<>Pq3skrCQi_-hHXyF^Pl+y z42xcjY)+^MoNk=P)opj4F(HILzvkomSncr+ZP^_}i1UNWFLWr^oDRw=bIKBsLe}r( zYGfR%3mXDO;^ATZ2mM_i38$}Rcgea_T%13OH#Jj#U4gj_Wz@XA6PeDhPCp&G)v(Mx zD_z*FC-1xNlfas6+&)g~{zlC%9F%Xuq^>T7F5$e=A^}}0j&Zmm@^wP)0CMm*06&C;jK)ZyW)n+vjrd=>dCf=A|SyKuX z5lAVY!}?NRSDIV5qt~WX!oLNoM7h3_FR93XrWdq*F5m%CDzvCmtyfLfhUCp&eZZ77 zdy6TwaC43KNiIJN5 zzWV7La~n!Nt5F(f5T>_$16+Qt^kp;};*`4imG7=^X(Gpb?1p~|tB}Is32-I_ACgyH zlaz@&?^S7(5nZA1m(g6tpRFHPvjLs_|l(%hck@c1k=N)R_d3 z;l=?tq%EpToT(*q?-$dYhDADN^&fPqi~do7$t?dorEA$$tsFFe1xz`LEdr7zTAs6~Z%Q|x;0?$f&FvMYajXwfh`>1r8FknD= zHRBkGd+%1f8p*XbyQ`qUn*(-2dYpT=y)&~bd>jXeL(j$lQGBOW{~sU>6(;L@{ybeh zojG+~F*`5v#I1KzEDnrlpYPMRfi7CIjyx-wo@CNUN167|R%PG6rk@g^VEAlM83@(x z)P#a=tjJ!0!t|Tyq1qzZ`?;*@s?b`6dqIFJqq2NcANwJZ3!Gn(WRlinG-ih z@bxZ^w?z7!8SnjcUh?+4DlefG`ZI*&ih5gCQIKs8$ess@7g$6)h!^cvrhF|onl=<| zlA?{o`RVd=0NeCuK>9Zlu@|+(qmH5_}hUBf?D<=9V`u$XYv4`FIZ(a%d!K zi4E~PVChOI9(B!CTil7%~TCj=NVL;P*0x-pNdS=|a1BM@z@@fFrKF0#) zCOuj}R+ath_7Bhl{Q2@d-XLJFC{_hhaQ^R`{BPMOC37pYe~Q{FkrbzXWEeI=yLyii zui2lSH45^M;R_I-Og%;D0ftGJHnhC=*RkB6GKujn1CUKd1g^FFSw`1iWD!UMaet?MqvE{bHAU(8D+j+V4a# z^j@X;)df*#=M_%1Q{LRtf~K~1N0p5Et3*W0$Ab_`%3~T|+^)W5*{OqH%#;}OT78ug z0abo}s%HPJivF)<5kRLjZ}dx7lgA^iI!KM6G!v&fIoH^>*jBHAc)g`vj091P=%IPC zLePcj35xqwNG&6{xY<<~S)G}jP5hZXH}?;jH^eYwuuVmDaG?QR>93B@Js1~L|+_z_+ z;}e`Gt{F2x;ec5fZw|#@!J4OOY1Rwq(ZxNUX=`;_1JB({QujzP;Y>pp_!|)6qs`XM zd4xS8#*wnq0IT8hoR(Dm%Mb~4au{ES{biw=1FjzPS$dl-0&QG3YW)DpN~Ry)ImzpI zy|FuOEGMbSr5hv0=9f6Nb=u8%u3vwJ@>i2~CH3&Nm6n2U$$}i`tZPi#>pb>%LlkPn zUc|t%Ak!K2!~5HbkR0G_^L^n<@^$heJVmwnFkKUV_w(0l=30W5t%$*{_fZlO=t={; zh)2y32Suy+w!?m4EyKCRNj)cEaf?p#hQ{Z2`g-MAJ=RoXTrLr8n{DoO6-r^KAZQ%VRRso2a@og=?046ytbrhncS-Ah~lMS zE1S6D>7d;0Bzv#JH^^}yg#6B+i?h>VX1>tyP+s~Lf^J&u`rRhX85dgAYnZQKXn(9O z&T@8I1v+J2sT>2@A~kaCv}h&+@(;7y(wUyRS%_-P95hd7ZfQ{=3Dd>IKwcPYUxd_8 z+*b23zZl%cFzLydzo26_EEsOV_j$Pb;Q7l>;e@e`AHzwdM%nsX@M8CLVNcM4soZC? z3wNNUYvxzDw-HMYy^H~yO}qqfl<=gy_r8Ld0M(7=-R0$eH73zErJw#>*8ZKPk);cg zknI42D6vZ(bz5oX4$x}>^_eTlRPW|W-waU%?Q&DCIPS@5P5%K})AGVCYZ3QDUHJo) z=XRs_2&?dLIyHwx!jCQ1?dLpQC{8+Zd%i165nz&~8rUX=hF{vPSc}9aO#|EROv;vq zvvL_O>=(!SMu|)|P?T(=^s&#pj3sH|JUTWD?ElP4E zUUALWyRm2EFlKa+_4#tsmA$xHL)hD`*4@2Td6T^_lQZ{?mX4O{fZf!*>j)mL6;;k| z9o0jWb-^{Idt7rj?tP`So2ke4Gh|}eJr$Bh%GgO?es{*G8Be8h+VHJ$4mr}%ldKw< z{J6DWz1?qEKrg%)W`oy?n@jEGkhCV-t2xDk4=@;HX~Nb7R;q-M$S*#;5g`%$M}DXp zT;6qaZ_}iX_HH`S)K-oEo|diAw5;_O7lZ3hkx@Fhw(kvYZLdBb56()YP)UqFFkNVw zXP}!PBbW@pvl4xY>LHyOzs}H!?oKCanMoGr=?WMMAto>~z`^!X_Y)yJSHo~vE5~dP zrJmpzdC}()?!jZtf&$57Ex8$rj@gDM1xvm?ksCRz6$&ibHI<#o{;W;G)TN#u&chT1 z+Hob12m|dFlnYJ>7_O6eybDmTJTA*%&gl%Jy-Xa$XT+iW(!q;VSXSNbO%=n4d8+OzUS@wtcn zdENXI5SRAyG0oGgoq1TmP23YPH;s`9poODK{m2gJozZ*N>vO}S=NL__gSU}IpPY@jC1n)+2rphTPj$%58vQVo}XUN9SHY$XWl1!reJ8Av=Ra#okWVN&h-NNsZ#*U2~`WQ?Z3n)?t zE|?XxPc|^cv*-8lDt4SFyXx(4Y_-1GPx9WVAJSSxp!uG%iI5grIoP;ak&Kj_D8L8M zGszREyZiHSGTVE@BoEdsN+4Tt)(n5;e6D&rHgbkZANBlnOz!hb2@r8QW63{)rvB%B z*^9Qg6`vWcXfDU$b{}I&+@R)3on~hm)vP=;KswMQbzIi~j)KHROd1#eE*zs7rbSaH4a{z11;%#3aMIR_LjB zZ%Wisr>Iu8F(f!3)iw_4(~d|FfNix81D&QBc0hxQ*Q2q(v!R@A`QS_5bGOBiFlo#; ztx`LpeUlz0CE%vA{DALNrqLo(;aLAYE2TNVNQSUxA}u zZV0qIoI^)Q4{aYkM?<^Ui@JxE@i`3~Tj5O*j*M|MEn|dB`8&X2x5;@Rbhy5T_t{3j zKK7tg^<04=I#KYXK>I<8v#IHGzP1{d%o|`S$N8^0U(pjZlG$N|@{vx6D3;~o@-Qn-DOzB_ov3qq3`r1*9s zdqb!iP$2ufq5{IqVk6Iv`%-GbD}X(D`b6ij5$y{!DBL9rRfyju(Xc?`^f@9sSAr8h zB}C8+wmhVb+zd*SojIqQpQ2xuZP^U(X4asX>-UJegy>;XQ(h~hfIO19%c_yV@VEhe zhfzV<^=4x`{z_q68{^ayTy*_%Z?*!zRuJ=e4F3H`#EtMk_&B!tbXJC#X`7OJtyN*9 zeRhGSsDvUDMBVNgAIPw%XQychE1qe$C#k!XnLGA+)Ax@~N_=Nv)8htZ0@@ ztU!D8x59jj$B-~)0XZ9cegCz|!%;n&!_i%?VYqejm(Srb1}Fp6eb9wBDA)Dw@J;>z zP1sHA;w8L(q`&Ta91NJtQBACRAIwO#Q=$&HP(V&5JC5Y>XO+j(JJnyrQsanE=aXEB zfOPh?^&;&o=QArziFtg7M2DRscCBOVA$>7EpiraBevcLTp2S}*!5&PR1=$1uKK28ljLe6&|$<6u|kK3w^3%=3RRJSE48OGpH`$2DvyEb5XMqSH< z#iG``AcXaizY?XHm9<*yX04`Zz1mZqhmfwasWO~sb3wqw6zT}p@_O%fv@TWC_uRFI zY#|N?bh6W(UuryeFMaIvu%Q~`>OVe4KTp_5-*5}tfdWYbpY=MeqK75Dl&b1x{((-E zHDJv4P84YhXLpHV>X(x+oP{bhLaDX>XIiM;)w8!^=x^Cl?-Y?lHJ(1kKE8(0Sy*<3 z6KQHO0f#bCn40V@)7?Zj?qAO=KN+WBt}gK$_HZF}YPO)t6{{9U&#XW&5}!BSbT;FJqOrv_#=v)`=HS zp_-uoh??Ia{ija9&@Z0mp&d}V6vju`XA;Vmq6u1b(R>zh=o7D?))6F$sLr2O$ z-A_u?lqIwd!W~*IDKm;4sYy{xL?!fx>2}&zb2^Z>K>$NSHxu40`~i>8p0i(&*f{1r^%M28Dr+I`hW>U~Y8qX3q3Fk`bvtBf+e71#=; z=T=G4LzKXcXB&wi&i!LAdYgMhF zhWPGenIFG&(tfQ|e?65R*ceA*TLlx@;BZHlzet?qEY7IzxLy;N`fNpUhm}fZF*06u z=qcy6+K#$(KV`;pwwFCCh2M(~vAY3CJI=jWabh+mC5nDR)S@s}Y!q))EFWKk`}Vf*;mi}WWUCOyemuO9yR&K!5n|pw zHFuD7K#b2HxolkhG(h?x%W#2b@iabcx0Vdq)km%APBr)Y?v)GC+neh7;yNVJIEIU; zG{f9^WG|u7rAd&(=6p|OnYXWjFOOaj;cSBbargT>lU!4418JF1(~k@S5P^*oHE%+s z4B6RQ#fZeFvPwHQaKon>NsD5`I_LQ7*(O(_F1rCLJydfTpw-AQx_nb>C<~jx7aIkH z1X4saDXK^H$!0F86lZI(DrYjD_Fl8x6r&gL2pj(kBv|YQEcUF>AKS_PrUASC?_h@f zf{2$;M6vQEMuDpL!|<#{u!p10!IGcY`-=%Pp7_tw_cbR=Oj#HAoK;W#GFZ%Kh{)br zpkGVZpx>gIw_oFtU5~?^)8}W%(rlTeziVs=|M4laLOKoct?!#a5>P1vkU@xH7PEU= z($tq8VZ-tju}Q?%G$sI&1&{FyEc1ls1&T@SAK6c~qE|-9mvn}z7x?h%YeN0vZ0vU0 zO2@qurX(JXq^|omk+4B~46PUARa1x7LpCqpP2wOCK%e*TYRi9HkH*<2)TzrhT%o6` zZH$n?O4CFD`hAH>#X&C9%CAgaDcuZDH;fVDd7*X#1N&iK|8HasGsqDt)M*2SW{}x- zb33Zoo{EG83}s4BOLw{>$*0M!e=9Y9(xUx;|KRU!;{Pl6gLa+YA0YPn2jAsCKvu_00hnkxb07egUth)`;U|8 z;H?wx;0(F?CK(OciT7149vyV6jRd6WwRyikyR?B+s=F>-suTFP{XL`zi|MvnBF^AvI%Y(0-w8UIpI!27^eHIN9aJcZxEEYvoxdHo*eiOx)wUq%_AD zt##BNQ1DP;qg*$MUI^vm7))+K6tBy3v|+-zj<+-NiX-%sMVrYEETMo!yfyE7S$3L} zr)JLTf`sqXRu;p8D;g$+IPG%;rr?|8@e`yFj%5_H)4k-9$B#8eD1VORAh^adaIfa# zVpO())9V*v4*8OWB8l}uH!f5W&c&bSVN^`li~lLapxFxk=41sc!0#yFym-uE4HO}floy8tvOtr*UnTpYh*-;MBx$PRWFl7U z%gbPwN+$p8em}J;p@oCGewu|)JsHlqs&dpw>28Kh`3&Z9%3awqGwEIOAH%bmoq_^evfC&w};f zPgDn{0@ZYVFRzLKX9uMH{I!MN)hXbGjGEDEsJ$yrA!zH&E1xrcV|Z{%G8Z{Tw&!|x zbI&lmaP3Qpk-MAY*FhK%=ffj;h7D?e^6yh>noZ75a!85>!C)BXN+_@gmhC#p(v<$q zE>LmyXb~1rt3TQ-y_df-O2@QoQh0y|EK41@z8rm(&f1ydoR}T3k||a(=n6Mhzs!AV z%YAlqr`wM<>w&1Xk^#(hg*a5_ZFkO%6dOvz9;s^#yT|?^^t&HmX(z_Ju2b_w=Xhuk zUDb%=2_B`t2u7WR>!@2V==Ejo(E~Cx>ERwAe%5Pzz`6kc(^}}WJZ$sGFZr~_XyS>E zngcXgiyR(8N^s9vAcGzDaRNG*;J5dT{gg3I0d%cFix~~ljVWz;3t_7v2cRiRp|Qzk z^nYJ14I5u1lx6DeN$+!+Lbt@|f~ghFOa$W#Yx(JbEP?%W2~|e9YP#&6){FYU&!qP2 zpfw@;0WanaTiXo&Qhy=2LfF#erCA-u&)sy)mYUk=!`|n0A4&5cZ1miB z{$xoHz{|IIwXg4PtN>QjT)x=#Ib8Q`>=mZg833(e_T9^`^>j>47@Ycde1x zNkj>8W=eigslEIx&UWp(NMJ-tQMd~OAUXpzWf6kk+eE5s0db{|`Q8LrQ@7AAd!J2w zNBNnou${Kk7u%<;AbnK-8Nh0R~pmSQ1_R7Ks;>b zvy~u5GfIE_S)OdgkT6ypkq)@yG9M`jM>wNaxJRjK-}AWJBS-rMii(k*&qi43p9y#A zfW7(q>^1=i*|~scoahL^Qo{mwJ3=6_n70_bFDTXnIi1rHb-=H#`*1u!4ArTpefs^)QV4%pZ*z^Ve>G$ zeAk;IqsJYgwX}QhWnWX&H#_d6#&LaJUJ&_9w5eEs1d!7BDrEz%4jJ#+~u9Rd>4oze}`4U$8r(w#$k zZ?ALCeP4Kfzw12zJZnAATK69=hgrkSp3QfE_b1+;*Lyki?2C!|1lJug^tBa@JS6XQ zBWV%UYY2$ooff8Ao_3HlQx{o!{9rgXT+;8;AQ7eR(~%MW{LcGB1}0ON-SSb;t-@6l zaTeUD;;i-0`H^vxVabzk=4UkYBIiwo<&n42d80Y4@p+a<2G2r0+vM<|--N2+H*%{`_io#XNlSOkb;lzeX;QaaL+JGUp2~vRu2 z@?XN@pZ7F4ZJ69ACdLM1Gr%H1gC({b7z(->;V9;3T1TOkdm@hF!?MM~{iP-m75d%iw) zi{NUg2DiY!9$T%St0Ne7y9k*>7H!f{8Kvm5glFq|y3=UXEv(f=>=0{NJxF5STxE1+ zZ`XYpb3eY1E)v|xV81fi%DAnS;DlmpCnU^V(U?X^l-*tmCL=z;BHtx$4ox>{s;Ud- zY@(?oSd0NKEMT5v`Oy;0ZH?>l;)ELFyXTl&BH0Rdjg@o_$2$0_9rb$6kNutuhSce? z?8h}Mb=cUa_??_P~}}HM!l+l;2(Dg~sPg zzBgFo6+$ew>!TQuw-XW}o!9!o3j(D>jUUlY1$pEUMi3ADpgOA*ShB0bL@N#T1iY78 zI0j3K*^gvXe|{kITfxc&=}y^|?j4?i!wS~|aGPz%1@Ak(ZC!q@`^GS~E}V^EkzweT6a!nsIo9RAI!?C5!Rqvn+(BdlAP{*+b=xWtfEGdm z0_YVQU!d6X3)C$r?+erNdDeVFb)z)%+Q+rM&3wi6U^hH6We_#8bW%YPjtC+6l((&>)sUl zpV%?gANP1bt@0tFo!3gqHqL#SR+%s4zExN~NsaDGtuxF|p8Q%-JHbp@Q5j@h>yO|d z)q*E2E{6Y`I``0=JK1?(5p8#NuY8|6a!2L4Y$@@}9I20!GR{{tjaz2>XyoA9-wL26KGYNyfc~f+{Gm#U`bS05|NZTMt>yZ^XYF6<*ZzOJ zS{{|a5^4Hw*$);@VSB}@B7^sFe`2a!YJ4jNIMId zw|e*-#f%ok83mA=g!$fc1A7UOU;X_V=?lExJEU{An>C=O5uyAzl(Fr>Gb(pMKm|km zPW~PSmoI9U0)mSbWV?Afp0nxO}|#siJ4%$!h$m7r(A+>s2E zj8y21{@*~D0qK$;iw7iMXOiIk29kWB@n%Zq6hESRavJOETIyoQf8xvh&=)d2$D{F2 z!^f7vo>heQymM&p^*9lI3R9Cix`@l0*$ygec5!ha(cJ;1SNGE$nI=fYzA|<*C1(f5 zR)=aYF7YdM8kt`9|E%_|jS2TrPe}MWGuv&8JdZ11ZE=uF~UWrvv$hxcXJznCryan{lq4JY>mq#a{>nTE!7)sSbTm*~TB zc;G?a$FnOg7Amd~{VDW!S?%_ZavLl}U7kE8FicG^EX6QHF=4k(C@|cB3T7KtcKKX; zLl8XucdW_yet~QZS<6=L5?*L_6Pi#SjYoT?1>U7!7Qjm=gdSiBARm^Aj5!lrR_?<) zd4u5L^A)G8|HG09K4Glw2PdG2cQCqRmfHb8{1KSd{4)=JyL-}1pvxRHKlpC#ssdM1 zg7;czk@t!4755*-jlU}24+|U@HJg8{e*DW9tOAu)&)?qc3Cp*xzinu;i-bRYHIycQAG^zfu&b`qOAkV=*RLUJ^p<{oq3EnT$+f}(-Tf~AO5vsSTA6& z{NAaFRrJ`)e~jS+tpWI#X)mY)BU7RC(X1? z9oq8&1A?u?b2Pf7_t)Ny3k$5BCq3enfy)PJkKHu`3w0qD21nWLRz>2Z3Cpv|pXyvW zI-;m+&%B2~qsgN%Zf7^&6G6!C{kPu+f*jwGY_q@~z8|VTy9l$cC|U8i)&tzS0A!)S z?URN`9`@QR3I~NEKRcS}cc3!(j#n@OrK5v9%w??I1lN9uXz=u2 zPo~+0*47e?+o;22s1gRoP5oxiO+a~eN-**qb`ESN3L#-!5znLsHn=sDsvXCJ z$Y@O)Qg98Rm|pJ4blhgv?*~H66wAX z{2J2{cNox7yv4ipq6OxjXO-ZCSN&u#w;Mq#Q6P4Y;Vmj@4{loOeg@X-07%)JNC=J2 zvlxkNpfgQP8MvSxpSapWeFNXAYZq&N8j;)h%Cv{~2|x8bcj5o$xjc5%qQDUnM5ub4 zaI&_9$Rxa2^Qp2Oo6L!-kkr$>95yHaxf!io)?8bk<$X8mImNRdo|9?V0pk>px5jje zyc74>Z9wnD#hhT9^uXW)0D!J@WnY?Kkfts9xIr`Utx(^B|Ex%a;+Q;fErM%@SfM?6 zfj>MpNX9rY081EI^d(c+v0Z-7wh;#O^-((_*-NMV`O?_xTweCm(1LzGelf8q(AiF|NqtMxTpbHyr8KBF_-4WGpX#Oy+S-K0tZuQ{m2wuy)0PY)^pK$B zXt?kh$Ez~=N==^~KCv3~&0S;}u3|SBKzdhD-{Uu5yvm)l;gZw!^TF(t)TEG zN&nKQ_7G)RSmGk#?jl^0pv4pS^5Zj|Aq&Qzew5iSb|SR4;Qxt%S$L2;rRvDST#_3` z;Q_9Vs5-;0J1zKw?C8hehGcb5o!qlu!(wjv#6Yg1wDP6nn)IpcBGF2#!$g~nmh4@e zCm>|S1OO>M`)#l(jfpkr9!naT@kxeV~9nSv8kD;03xvqRjDNLS$d*ZIoYl#j{MQn{SCoa!!02lT`% z#OH>>S8A2uQ9aE4DE>Ib6b~#UwUWf$@^?h&js?JNPs-0MYA2US!0J=kbw&(~(J$*q zIAr?PL(i5mb?4`{qD#xlor>pMO(Rd%RxPaH&Rjs)+hR!nbo{zCk=(O1O^tPdQj>IG zE1^2Z?+hax$QYD-ls`z7;m@pCz4jI7)(+&$s|=9WV>QI)U$eJjcB@Q{T2Ga^_Ux+E zHcjSw!z(knIMRyI)b%}Lm`GnbAE4;OE6&}KFPdxKwH1OhwY(UvqbY2sEPf*OS0lsq zZ*a1|gUbHZV@$n!E9tv$zd#p3F5H8@!wkPb^%VEt%kumtfkVrTo6&4Fm;2hxetyyxW~P$>0!K^nSpK=ru{YEX75dPoMNEj zJlY@=itZ{z!v@`kkzd$JpDmt*tjmS$Tq|K&^CSoe>g*i-)4HGl1n@rU-dljWRe&i2zqfx1*J#Fsp& zdxN&5PW=~$zk{tsqgPF>$N9nMmal!yCp5PdiN5v@NosuS1@5JjT7a6qj*OVeey_YL zpb|;MD#eX5GR1X0t)X~Q8A;GR%V2csB(@@5TNh^lpC zZ)gpHCCee3c}@LzxmuF#k6>D5B~pxUKb)e$-?uWb1fX1_q>DQOn5BTBkdQ}iIEfvt zXC3O#`dF4seuw{lw!6eeVcb~cR&{xU@+lG%KeYVGf5vxK`khqnKT8sSmrd!E zmLItj3hFvG`mlb~8VudHyHsobXb-jy!4MjG_W{c$?cQ(t@$hn&w@CXrzwH@XJ5CbK zgl(+xbCrJe=!(b3_ai8Ut+YCe{n^{Pxw+Me(o$1zCe7+TnEi<0MM4#fCJ_xXfo1pj z5Ko@PPdXodz|roDu1f@)Fq_M!-hChA;M^2)CbN754HuzWgqWxw%}4O3$hQT{haJ|5#R!-86gf&gNQ-oz{^)2r*M@G@~xYmIY?rO{PA--oI=F}#1o zG(8+8ELt2apIeyeytw0To#GD>eG_flWq0)pWH7qWyRO;#@Wp-{LV9kcR^&*~a^3sc z{Kx?b`1yG*1(J2RN>jU}VW;c-5U#^VMlc}KfAyi=fhQmH3uLvQ*I}RpC60dM&9@hH zjf;8`liZ_N*2#*QzSjMoHb>O$)?=S%{ox`_ZPp|CN@&N0G}g$ZC6u1bY3u4*5umxz zBwW&IHh;k_!c)zD`y+wBe@l1^USdr#(}fZnhOjnkXE4=aM?i%p+})znpEQGF4C z%rsn~HgZNT3xxa66}0C<;*5^TqrBJ9m`KoUDVvMQTKYdPjPxn}NCHU1Rr2qs)`1F#!I1K)1~ZSyRkfZi_Iw_|zw12IEMe7mtIE5L$7 zpYalDIDY(fyqVt3%A1IzTj<*6dlBBI;O95QmPfoFXpZ9VA_jF@GhNp3rU-j}NLLL> z+n8Fw6yYw)l`RLBv-~&|0Q-S3@#GMy~Jg>mLRP=@svIjD_ehvYdm>C%JM@IzD}n8T=V5ay(;VbIo2{ zM|_`45h|o*TIFwVoGa~Q(?swix;WM;JiU>R3$7k8^#g`3aiTiavh}rTv*xhrcsUq@ z5Mq}790jLM$w3pg&9wPjPZpObCvrLG44Dejp7V0rArXo~!m$G|lwr2(Xv9&=9usu=i|aIg%If5&L6W!j&=<5l&%wkZbQ3*7RKo zN7fh=$&Hp35_Xsz)T}Rtp+o#$7iR>aJ|~3cH3(GFr%0&V3GUHAiUG z)9s>$yx5nbtG=49fkOx5$>IxBgJFixbZcT{P3TyF>H_rZu}+%+O0#u?sT#78cy3BN0(hG5UlIB*B5>xB#HM&@OX2bywywqoP2zN zoW${u8%I{*U<43OJ^{zp3@1LdInz;=_pJI8RLjC14VQP8#5$@4qLKT@-Q zZtVC`)j>BK!}~D<3ptP={mXVDrf*C56DttZAL?hOA{Yl0M0)!Y%#tOTE1QaJ5Sqg` z;pstky=q#P@S)8uZAZ&thv)cX+)TR|a^o0zJBBJ?>~`kq$wG{dn^#V&ocY#rtYn$EMT7b-`W|E~_a#My$(9 zb(->5NVK`;E<`h; zto&mdPECC>{uHqaJYKS%r;d3j=hiq?JViQQVF9d4e7suE+x%2Dh-*INRp?L0t?t%C zMlA9>BoB~lwwGN-ZS_PRBKUmZb%=<*zFo8r0^C98QgvzRT6Jyc5&{aY95${ie6Gpp zUDzrK)4uhFdB9{mhm3>_wdxG2zxXqGem=69i*3X@pfL<{Qztgh_omSbe#ZMLAx{1T zM~wd!r6UH&`IDwp&|1XPuCak@kxV>jtOFxRW1T+l=Nm#Fs+zyNh5w#C{JY2S3BN$e zD!)MQMDH>U6dadN=+Ohz?@NX2k z|N2z;l>e#M@Vj@q3ACG^D&+2H>MEw>iR2a;WDi8Uci_rEiQF795oO>(8`)z*DlVRY zVF{R6V%sBG{Nj^1UowBzVs&LbeDphHN^CE!n02K}X z+*q(E1nvMy<7g`GIz|roiwY%8w_H(+Z1~ z-g$AZb{1;4Q@^seXx4-L1nN8F8et&FC_H!hY8!U%8ZvAAK3zp?RZ3q|_2+;w5jfIF zA{oj60Vwa$#hPp@iQcxZS$9ibRerIa67F_eU%dXol3(B`eYwYw(Njq6jwr5`D~mv)$KuQcfEOHJ+a+ciCEc)Rv_q0JhQ;e*jMa0>K&h~kG=1FQc}{j z($nR_WvyF%E(XGGk9cVVgUQ!9$$e2lZD4nM@29f190Q^IL`<{(?YQFZ_D)x zdpH_o>g#+ZL_;Dt4$LYQ6$x2OOdt~w#df#7sA4jZ`+OCS4tjo$ zT;Oo`m{4T~2r*{%wyo*r!kPb4D&?kiCOl{%54)*AfwRr|_i z{n!pmUBPMbFB4wlh!mO}Kn=oO5@e{Lrs+A$JUuAK%bwvDbtCoK&x7KeVlzrN{o(P0 z1>~PsFAA`jYYgAALU}#i7s8P~r>&~93VYQQCrs=Tr=q!o9n5UOY{RGumM8p5t8ZV0 zg-1F>!eyZNjQs|la4G=6llSSj=1~u8Y=6K`3jVl#f&M7?6_w^?B%1GgiDse2^?x?_ z>IBGYPB{NeZvMP;A|_7HNk(rAsJI|7kzDqT>Qhh!+geL$#mSD(PJE)f>PMQt6jJ*m zLn^VnjI}1F4caRzrtPkF{A%b|8Q`!#46+a|%ccpIKDz%fqA1TjkD~>fDn`N zK%zU(=z&YD6hKBWJv@U}ZF2&jh=WoI67WCbO_t*HW6TRaqIT<7BR+mlUG4#WXs(7^ zJNr7Qor-W%`Ym0XiK2=zI;x z0Xf?KC*x{BQz%{1w%H0)S_1{s@A;)~si%!jmx20a`0J`#5*S)h%H z!A)nR+mIG%hogvaR(fdpda{fSGch>2OGqj2F4NyB&5()0`&<>uVaz9s_u3k3VSiuC zOqNwhZ(Z6)Nr(y=TSSU>bbMVOJC9Kr- zHJ{D-P53p*M86RGWLp)@N_(0JDB04zl=*^*f^?3cjFe^||67t(zGmR56lpP$d32WS z#mV)$%`!er&<5d=SV#DEa;yQ)HQQr|QJ2Rnmb-==tFPvdUf3C*K!^NWZla{f&lkIk zw@+slj3nG}6KXfanTuxCpMSZ%c{5o{aFLuF&Rffiy`VePl%2pCZ!AXI)-jVCvRW2K zIwquwyv(p8PSI?a0X5dBzLT2J_!@fM;hZ+DEGPGc1PSRJvE(mrA|%muZ%iW`2%E;Z zZQs*Ttb@vTXoct*X|s%v-}WB!Dk;36?GDaq+{v3B5Bk&!mXB)0T+DfTtJA~O2#8~Q zbtlW653ylbTF1;HugB(>?yB}&Pvl|*bKbBLI9wclzbGc>J|_RN78N2wRW~-bvu3$J z`3cOQP0z|6vBf!2*@-+?&Ll~kp$i52>&%y zCwFJgr|xZCquGL%=8)V+Y5=*1pq`)`l$RCTlDf^&&D8$PXw`+!>^e{kk6X{Vv283f zCRZKY(;uoCQ6FH^`5eIqv0C)u)vEzaOh(s+0JbDR@j2&I^X@m+@!_8G$8T7V0j^+2 zQ98b(-oUy;bQ8UGjCy#z10$S>T7O*g*$=Px-=wbiKdyP;R`g)=i7y5ilMqPVg&LDA zO`5^fko9<*|>a*5Y zxj_3VMaQFn8X+o!<{ocif-YDPNHi^{WpY#_!#Rj#+7UdIk$BBJJC{(#O}=yKaPuLs zQ;Az2XELY>_B+D$?~cgYK+~-)q^G^GfS%zT!B@Lci7A0$l`n}{r#$wwUhy)gPw!jPacjATGTMl-1h95?eF>qLA6uVQ-%xGnqytquU2EUzuxS4)_^R)&&kSr?9qlTGws-z?WtOrrn1B$i0rd1@Rp#w84wW+ z0=0C_hDkOT16@cLi#udMhZ;!`TOCxK_6|vRo8iCW?|<|E>77~+IsF9J{2{hN)|`0e z?2!8Wf?)2C7^E3fQd^=O+;g%kT(~VN0X)qH>0V@N;YJhsLnAz58JCNf^Z zofEn15mOz&?T9>|8tv*qUJbX!rNy5I3EuD}-W4Hh4Q7~|V<;>6!kLs|6HHHERNqUU z^##Ap!DW3u0&$Kod1Rp90%(po4(#95_wwCjRNOK=YP%hex&g9^eN;fp@b?4-SZEga zk_r^}&2NAh<+0fo#VM2T3JMX8chZGC+YdOhQwFp4V5Em%omy!wuK z*ye1WfrVxAhcxPAqVx5_%i>SUkL~wvl=e9b-BB(kuwpiS2@;!Jm-F0lp4>}(h^K6K@@xDxZf6=Qurx|)N#N~(|3^^$aK`6#V7L_oxT{93> zY#e84C5F6R5E`pi5Gp=p{X$&t%RYbaK}w35Pjj{dxAoN;-;EdQ`eY=^$@1yw2bUltAbN@V&;+qst5(Y7YlNYay#6&ajetP7G=6&~}h2<+&pe6?wvZmW(Om4l# zpZySVf_)&Sao}C0*O(i)aI18bmR_O=oxYg!?jBO$VElOSseoA>)PU-U2$bIPC5{tA zykxnew~1?7CdVR%pU~>Fl}&@zmvim39v>6WQnelB6FkuA@0>JqB4`aNsTu=F&^b6T#cy|q%bP{* zb8ZcfT442!jm@pR`^->|glDhblvoQevab6f`8XLSis8|rWCHLU+CcC;^LmS*ze%v z^4!glTnKJf9jG4?mUy<|E?E8o;WTSxZ+9C{y6D|7P_=wP34rnpp7H{?FUCt@2rk@C zV{Jv=mL`UG(NepGO+KP*D#Pd-VWqD{x)fozqH8*|QPNXy8WWx+ew5Wx*{$*8yX|`kUbEC@JLD~F6MMbi@U)_-eQC(yt}64Rknb9=klU6( zvey4u&G)m~mIixPkS#SO`2pmnh+j0(K{vTOr)oa8yMV&B#-0Zq@H}pp*z2S|Myip_ zmE@j0v4*~DRvl`h3>FU#X5IvNQ9=MODg!OqE*&vGuieC^J``_G_)clf(U{QWpr3{~mZIVY^xdqTos(3XYf*;M&JbuX(~LUtmZ%_y&IS^-{=9{jIhA!&E5) zvF)St)*QFuHhAdduZ_BJ;d4w#@qntHC;3hSbTOidhEYi z6<_EK&D?l}xSBWvDhH8!U(}jEX2|{rF0}I6%AQ*a_D0*vGKS~Oz+xJ0lOP6nMn$R89jZ#Qk;piEx)zC8I zr?$gVgN0UQZqL0+9}bH8raACpx%IdfM@xd^jx}2 zgo6B;fQ{qA=Y3l?oCEEb7NfHRh5RcP2uDr;+h-XW?7+bL3th`5tC+KgMs^NMehD%JM@0Vz6 z>%^iv>2gUeF8pmwja;ogHB& zt6#LF2!gtA6BW%)j;ltP9l}o|mYUaVM0`lD>$G$tS_0wkYwxv>UBukLvLgs#-mZg)oVa zaaZo&1(rn7-9GIu?YYq2xX=VKdBc@WeB%@%=4qgD9bc%s*grg2W5l|i7#;fNQ&XA^ zk(y9EdS!^;?BH$v3}R}okkZL6%;5lq)>`FF8xMM-7D#)uc9RS`!5g0 zu$m^zA`7!C#@O2RYM;rsCyKnvhQIvcKFYU34nwlP(Y?G6+Lyn-*YiD|`)@->1NYM{ zKs)7s%R{3cDAmBfs~i6>yrOg)I#@6p78EMe>h{;1Y0SV2L0K~OGrCgE2Ufozi08d{ zl`r&s^Zt`8(DHcz8n*r`Duh$#wgoGEw`rX%TI#g2ZKh9RdSfU2*r=Qy1}GAIm5&$G zLuzhd`)5r|fb|#rqxp^a*Ov95l_JhsZ$PTq?ZkGB)qcDq`oARJ z{1!Yq-whQA**h;Bws&v5ZZt0 zBG)1O&U3TOJp(NcKz+;w<-Uh9Bx?B&H@`Zi6hkxFLe4r=t^AriO;Y?mRKCIMGhSmK zjNbC{8}~*l&8c$~-mPF%r)zO>m?wB^KRfn}AqGJu{3?f6e1GJ5<9+^`;2|D_ox2>P zGq|{+{@x_#?OLaa2U^(MXtmsk8&B=B1Jw z<;S;4RC8}%Zw?Vs#tVwkmvcjJ`FYZh%DG-uG$gD6aB;m2g{THuP1Odz&PVKV;VxWo zzG?uupxXAOAcnk7WldxBqY8NjwZQM`V%|H`rKP|)XLR$F{YrHmGp$Xpn7F49rI zj5IS3Fg+s-?`h)8xl;x`11bC2^RRJm9+P^5(~dB@8hh$iqV^w|-OvZ;)(85EHlM1p zEE@!tw}3oK6Dsm{bl*&tl$UN+FzW4N_o0FWeq8kW$`xnB^2Lu4D!X&6rxPn*acrae zMGIJvr`<6P3aO=dwvlhY@Y(6v05CBeS?}Odiw1vzyn)PN*wv6RRFHxMLcTH06{+UJ zorIiWjvw^VQ1DTa*gn8ZJS+8-n_k-H8r-r=9#>*?AnK2}!}?*R*pP?u&NBFdZJ!e> zjiu^zZ-iGX&I>57e543XI25#X*)6`2^~9={;A}R%`NV+*!%$dF-J!q-dJ#AxvePVw zx$o1ax5j$0Hj10>k;KS>(wnPpORVAcC5nU1-asY&OO4RJgmfG)5?}YnU&=q&{H#xt3}u*# zG?-a|>vaU@r9nzdf7T~;Na7H<3FC?Ni^jhbA^95D<8fxlK3N(rVAd)XV!9g`dC4l; zyxbv(>Akam87ahHZh5`*CC?h{;F|2+$@P|AAM~DF&VR{|_7^CqaK-+bsKoa$`yQ_i zu_V7cA7k9u_?cDdNk2kR~gQrF8~2z*D%QYhK}Zhd6M zVbH^k^1Yv|p5HOM_>D99Ml-Z0xh+^oWmRxdRqtxg#hWEZ-t+m!qgRa)k=HJE)kIbE*t8dGGo``(qJjZ!8tIIeL10e+qZ{gN9 z)16u#oWUggpEQ(G)3c2FvF`1B?IVvp#%le`G=FpweNoREP`5+%@bg&9xbL6vtro2o zt=bm>A|O$6xvTWcX-+Xx-*AI!y=6?;h|80^kKJYYby@SHK{VIz0c(MR3YJHHyIdqL~+)rh>1NCX`6qGjKYss3240Wl=Z?5rhi| zTp<5PwAo;Pl}m9658x{BCIMUbf7`h%R_hc!VFdE2^L3GW$AGG{Kh7`ns)+IjCVjT`QO84^pI?#i!` z`nOefH@)x?UznoDM96`lds+dU2V13(OgmyTG{GKn4O?l(D5@Zbi{i~)pvP`UY- zEAb?0|9opDVs$nU>r;>f;wU}M3qC@s%5(cikU;gyu`D27>*{pKWBk-e>{wk+*|%KZ zDy1G|+-K(m#ajYqz|3=3_U(WH-f53DSoWa2BpP1v_SQ}kNJgBclLu=!-0vM<*+?h@ zJc-J8#LPACr@Fkfme%M*mH6J%;@P}@B*WR=>_T<*E6qgC3?YLq_rGyz2XKDxNyUe^)3Pr#E(c9 z&JO*BI|L5eIw(FX2@;*WU*V!wb+klqjwMS2mu4VPwT5XG-V&|nShMEFBcsfeb6Br~ z`-UwcmlAE$TwwmQTv=`w)@zoRbI(bvhsNSQ(bsBx_IA*Z3gu>@=$_6JTz&+JT-S}H z3q>{@m+5-FIOHE-J9=z-mVqWBaLg9UW$Ok^Rgamq_B*&0Y!^tN#3PtZDe^NCedyJ9 z+tw54{TML?4JbPUkK1tT?eV{Ut39MRBa-Uht1M}@HHTQ3yW57f(pVE8nVz%I?!x#S zvhG;nhZe~p!*||ZGPsPoGe^+njR;k!PVfcHPDL^RRx>^a;i9QTBp%^c<5Z9%1H7~p zpx;z0g(OR??Q3>0k?HEmP}XXPGBOrpHNOX(I7&y6cCPC#rmI%JIR0c~a~@@sDc58t zst*>EOHldtMjVOMxy(}>ns-!Nw^qO=#J|QARkO>n(8-dQL{rg-Cx&eIMSc1(u=-B! zuuFF{^jw~Z>tgbivaZgMbP6eU;Hd})JUh*LEdzWtAT)qSl9dMI#yn|@FEnfdNjYqc z2;RhKKIFUWG5l_f9)9AotJyWvGDu~hA$7R{8O%fS9x{fnOKy?gfN#bV~m-S2p)@}7*%)qgK^4>p>eP^Jv z5$G+!$~)$kQq1xf+TAUL>}~ASsq~v|Dj$Ui70%bulO|`=b{~e{s;xo|o~ljkRTl#3 zoIFgZe97Gmhii2C=SLa`e`xZ~{lmlmvq6gHEQe%1%TQuh-$4l~`&TS_s%fUU8$v6~G&&Ek5oJ#xV$stKA_ z^G%Vv9C-m^qSh_^yLrBqLZX(EDtxC&Zsx52#;d%_c^ZQ+kHp{>S zI0bA~$9VzC@zu5n{PltysL-!);K$wE!dq&%}}I4O3Tw29_U zT3nuAK~Pp*mX1IuXc<&^<~p@e}p1gjekBY1G&ZF6V9tuXWI_>h;9vSd({u zdPoho924%+SF#Ly4J6#6`=YRytZh|1S4lV4-uZ*OP5r(4zLR7)`gcqU@ip#gaLZUBzaJY1Ff1Ma=W-)2YpzuZ|xj^U#vaG}`6eW}iBf9G^wTE@;xZZ68q@ zKxFUT)E0f(_QT*SU{hU_ejkB1r~H^?^a{<=_Z$ZJ`6zMQL%EAeJB_vm!OSYJ?Mc9c zL@pHdDg4RsaFN30=k@;>HzORVJsZN3J-u>@AXBP zlP?ED;}kZu!3l+re|}UXn#99F97VF~VV{Ig{;lbt?pjy4?=~VCzKf|E*yzUi9!5C3 zY1iY>v)@n_=mQ8A#4!Ni6Nm<=7*EfGrUaum zhR)C(vYSd8>Iq@j31d2Go*!aH*ej2*M)Zf=u%7N4zqC6Q(KKl2>s{I%=KbgQezAI_ z*_LmeTr(ZD*0;AhSx$Vs>dkI8Hw5ZgTdxe=J)2?OuZ9`7HR}!L62`8+#Rfd7s-H%U zRPpWtK1ojipQJ~CgSFJ1?|lHV{XGZ}SoIdbbNC|fOnbEEy04Btp-aKfr%c{JDGB5G+ENx6VJdQReMWZ~sO;oOYn-M@S z2u=Z1V>p0W(}NEbBOrKc~-xEh3Cf@r7AIm z(VB!w#)-Aw4>gai@=T8li8u<;fK(;>7QYlZMT-*^-<$)h9T~u;!U19-^6WoO7F-g6 z-tmA!pU5<;C@K>!t**vSQ(;7eP5^t9B;Wc&B$oaH*!OO#M8^+ctJ@nNcJ z{GIT1u*@>2onx~rJUx7J+dq91LSA2t*voM&B0Q3Fu8~FVKitCDeujM} zCxeYF4oEpHmzqCZ*?$}@B4*;sFA)CLwMJfw#X3ZDZkjfj)|LzfH5>lR?Gcl)5W55Y zhiY59Q?=8B>Kj?xobGyYe(wf5tiekUr|G=qa^OZJ0c089Pyp|9k_Ug-3}n-zjHsS5 zSc*~$PpmvvjISN_LZY?Es!&8pOG+AFsa`2qt|GP5t#DRv0MV-vkCEYqJvL zeNGt@_kEpuCUmZ*xu(@m!O97v>(%;DP-mG>R`!HVaC&~XZFAoMiaT;UFz{pF6$`Y? z#7OJ@ztDnL=Wda)oWsv7{G4oTWlwXjd+uGNC@R;cbG<*cm=NUYVr-#O@dRdG z)l&oIlh_NOK;gqY?xj^Gwl=*hC6Dn^JG#C)l{cxuuOC^~IIR~Kt^$3DeXK^0@EnDO zyHsSyh)&1WR+q^3BNC?6#$&#AA?z4+Zl$Ndjk`*10x+l*pV+tY`h00E*PR;=bw>*! zgEJJ~Mbn#Ru3>vJ(-!2VQ)10~NpMu1z!R5P7m3k1#QbPgi#)%@YH86+G(_hZ-G^#| zx#Vyt>GQJRp&R*F&Dw|})@%CT%iVSiOnJDo)z5ft5o zNRrRpv|^9ayE=^dt`Sge%!u zrjpABnvfx2!srFNB0@0r3}8Inf~rze?_Q@+KO(fLBcf2jmtGaacV1M5YWi=~{4e(2 zGAgbuT^lWeCJ@{`L4zi^ThNeT!9Bq}xO;Gi01571xVt++3QOUIL(pKs_FdWCeLK+K z+2?%so^ijvW1Jt1f&sNyHP>2m&i8pAdEXzYu%^FRAS{Lg+{XarPV1_;*p%=KbF#&n zKDl)NDG{1bkp-hts3*4iK1Y-1F2_^Ipl;~$dpe=6c%dFo2H6PClVpCzWRykM5;eo% zHa8g8)gK_$(XWEN{9{PrZs3x}>PGX5D{*PEKpsIhxKp@K>E{7DrH<7@$yUT9?a8Oo z)ZDR%0Ky%qv)3mF-xDqr9t}H}n+Opa=jdLsU*p$u0D-cEW?#(cjl1 z3yS^$QW^6@IeQvL<9?M~PkBUMpgVOY^BElI79O==$42O>JYlXVpCwDyn`qNw{87_Y zc3c}xd~?<=f3_@_fQx{biHn<9`>{R83lcLNfkBe!krNMWcO(N51g*R&V@O=LTV{QT zGxt8Y+|3Yv-A=@4^r{mew%&2YR$)1rhHyxizN6I|!smW{vq47-Fh(CBmh+Rf#?zz_ zM;4kVPM9Yqh}mvP*`R$`!MquB&L*4fb=?)gxp%00#?p5+@b`WR`pe(`|n-=7=FUn++#mf`UwIDrnbCM9Gh6ri9 zY$r(<-cejQ=fCg=0HeBpW?9zQ%ZoJC+aJIQRNd{@^LO0T`C1l+oe7w6V}_%Bq~fSf)h9RU`KQ;7%$JU_ z$J%y(wwv+8hToVQKCL!JeFkCq_S81Ivp6p(Pl~xa z%!JTA7$0i9$x7_^AYK3A^{&sM&SG)SgxeCRe?=-T)4%TIc8^P1o$sB zB@^n9Boiok?0&MQm%fp=ut1DR!A}@xQazNc=pjB)QS?C`d-Ov+W!9YhMfuqNe$Ke% zNy5^Gwm`9sYt3;*6SmZlpQMXWe1PdKiXI$vNfy==%-QyREq<797|b^Bsvk|Y=(=#t zlYwECRdM}HDBE#`nbuR|)eg31FC>tVKQw&JNho`|_HP8gQeB%MA@ur&*bN(uZ!#Q_ zhE7Iw_BgTfLN$|W6h{PC;-e3-mbdMdKb#Nds?Ob8oIK}m@kU(KFN{~aonkNe zyRk*r4+x+-!;lwWoDRia*%8U1OPv;;L~sgt7g+E`)(K7~;MX00(@^jEa3onw4i{64 zsquNU>=kJLp!!Nsu2+_ESG|UNd!gvE%6wu*S9>=vqSCWg2V(P@=)~@ zFT9ams8IHbH{3T|s^bg@pM zAjjKOlfusE#kriLoG^ys6ZCurZ+O+>KBj9|+E14oVHS3kyJ~4vfSH$j9xbD|$)l3Z z^8P1k4S3tFJFO4{34;|@qMe;dauZ6`cxF=#Qeu?f%v*mhO~IR6JnJT&G>F-fJ}u{P#|oiFKG{ z?D-=S#SEieA0O9(y5Rl8v9?^wq%u&h*?%_)sj*=E{Zjve5(X!{*JyyXbLRM0_8e!i zhNk@W$C{~GJqJ&nS*wI9rYhK=09FHuK9se?FGs}-Cw3v52|A#El5pK-qszeo_=c3nk1%kieFFIPfULI4G2tNMlvfkXK1kT4?g}&l%}{{Hl;% zh$hEd>5UmBK0`GM<2V(3;GY%K?&UM5tU8la)CumK)psyGF-T$F%LH7|%7S-?kdlja zJs6s&-?fAYFf&z}(}^)~C)+-8irOQSl%^w**EaSMoQy8g2nM0Wx~q{;bhnUAGiDnV z<;5{&5uTdV_7r2!i7upe$gJ8b2<{fwCXq?Whkp1H2&23rb1Oz$j>;^Be|voG&~_N& z;(G zB+Z5Nkbwg0B3tgTry5)L=kbU=T|5v6L=D;~2M`~*9hC!Tf47Ixh!Rg~5; z105NUBUt-X6QRR=61QIpx6aQWX+j0X@DzDSqr*$uqxr%&8k1ITpLVjccsw()@h?cV zez<~qp1^ZF(RP*Tb|c}83m0SyTX?$Elb}oVV>l^yLcovy&?8r6A#pR@w-0QsmbRnG zm73$BaOey94y&_BoXks&@iNoNR?>)4aywQkvX?rYpW%B zY4tslN>?YWC&6Gc-CjGbso0#0T=2-MlH-hz`D>;Detxk?mnTrZ`yk%#%fWfCAkP2{ zRxhd}x%8FK;MVCnocV>eL<gtef^lMQYCb zqT)ztrG?Qe+NwW5ccKi6oqa;AC@kkgfA3!Yn*o3A9vZFD7h z0KDA5HiSE3*%1`~G!iWbr{U9&?KihyA>LbJ06`Jo``WHLy}QxDin!7I(FE5d@|$|Z z$cODed3g|S;PUU&PeGkiIN}oykL6Vw4=pjJ3@m@_B`waK2Z-`Z_FCfXGomwEfC&`G zF+wP}lnyrveI4Sk#RPaykF~}ivj$L%VExRDltAy+wkgt7{R^qi>4|9co zB6&(gN7!CMX3_1Y7E#trWss@U=lp?F+L0s}#>+J>UZOQj(Qc>m;e!kZToY`_8{@*D zi=eUXnyS(A;88&+mIdJtYGahJ6lY_+5Gxaw2pAci{1I)`N^vl!)lm;~LfX?Sft{u^ zvYxtUpyfk5K9vIsotI@U?3(^E2CmLI^Ign*adY z6qiwU1XjMogPxzPoMHVXR@T+jkwp6>hSuBc2?~ATE53a#Ac%#_~Otq5k z9wSC;EnIZj?IRLqkC0=$XG8b2n5_1GV5*6qm3a1IG3+CvXu_?T8iM|H$(q+Eke2$l z?OWQm(7|a`(~;CF+`#8PsXxM(otM2-5?3RDJcn*RoxBJOe9Qg)RpO7yo!{%;Hu!8( zSAcAHENt(%mNbZvd%}c+xT3es+*iUh-fC4O@rMbs9jmGu>AyPD3HG1^(t$!~nTv~h?&?O_>PNSLRB;m*6iS0S7dX>Rc+>q#Dh|}Oq zg?2QN7uS8JxRX?yHm>aoHOg8T?ohL!LZW09NdI)&H|_J>@X&MNpeq$eexB)ck6{|Q z<};=TAUa0F=3)4te2PGR8iW+Hs>8UF7nZ5M{k1NNx(&)~5^Q#&oRNrDE z>}$VJMMf|rZ?RSLV28co?@1!%tNr|4|5LQ82z+l>Q8~i$tzZwxVq7DQVura{CR20g z%#6e7obr=~5Bl>SS5VBP+jQ!mdosMyi!2IE#ERC#E9xrE*P0eY)L7toBWcF^NWu@I z0&X*++SKXnFR*m~@b?XcOmN!Z z^d{h|385ztev-mXq<~^Rmmox}^^c3JC!I<)=&ems&3tEslw7c5za%n)8HO_65pIzF zW#+0gQTix1vJg0Zqc;Wx+esne17x+Cpom<>$xMV|gV_xqwrY8VKCU=ei?CLOM3mZ8 zsR>%HEXV8i-fu)5$kgy-XW%I0zB0{i=KKp^gt%`Fp(JBF67w(j8$jz?q?lgKQ|TBN zk)z!T3!KgN9fCP~HuhF_nT8=VlMf^@6htW@)vTCMmk^eXicoti8-9^G^b9F}Rx|_3 zSY>i{-_h4&@HJXm?n5`ki#sU!0S6=wb{R%Ie(%{Z$Rtefx%wB~vq||SEdJfbA5abR zA>V*bmaY+^uKyuUHUZdE8RWmZGBE&ij^Z$Ui{bemCxx3Tj&;;lA$ z2Kn!mkLGF2Zv~SB9H%XmEjK9pm`dg@JSVbT28;(D@ip#^Z?%U-Du5>A{W=3eY| zRZ}?=4maEiQ>Q4(97h_Gx%$X4EwceiQlcqi$c(_`1lq+m^J1Owka!;B_ym{h+}EE7 zo9B%BqX{pGLbO}7S4}Z~+3Judv%|(=wY|A?n$pgLOW~>)y#f;$Uj?03Icu^n8i!N~ z#%sXq@u#6S^_5NG)I~Yig!<9#%gg>sE^m9>Ov0;GrZ{Tj1{V!n)ap~riV#LsERnCCNDq7f|$24S^{C_Y^OpXD9c7w|KVPW0dW z(65^^nK&6?RGennt2m1>46A(L`snL0(sw5!PG=x+q2dU8p1Dz5O9xsmo6KKu-H=Ib zXssv4hbhegSEK7*=<@Py{ZSM3i~MUU=NSca?lvC6G@5r+HcF%=ujQ|3TOJi^nom1J zBW@y^1MR7V(eJ+bF_VSeamuQqG4=n?Mz82$!+O7(c3%K|X(!qLv5H+enLHR_;AQ zBux#6N05?}?X}qT+{REzrg1jEOqoGHw^LqHG~xq>PnR{RwPhx`15XH?&8TB2-wx(+ zW4mEA3-dLJ5DAe1Ss22B4uwYJCqJp(c{CRG6cT9Qs8j3!K@nCe{H>3h&FurJTiiRE zMswhP|NW6-*vpN`OMe*nYoQIZeunlAPN<&j0`L9bs=0roI`PjA`L8ZH@Wp=mdlp(j zTbB;p!s^K7_Jr)F(C4~HW}+YU8v?6Dn>O<1EhRuZIJND@`%jQ!Yz#@~tG|U~!H^q7 zhdNe+GemlWA@t+s2VLJA60kj2`lD(KRKwb;spgk9HWUwW`AQ1HmVD3=os|`kqz@NA z+c<_5QnJ;S5lgwml4ch@6L~S`XRodXSh7{?$iAt7?6W%hn;BvEpvije)T=V(_;yh7 zAQyn#)JyJ)q?-^Tmw?0 z5kE4WMuUkt3qPy?23*aa4dse8uI_YdT%XtBZ?Hc*J_}rkPUSXf%hd%&V`JQMa|Y~~ zuXbfrjV(&_`1rdWs-btggqjfHM4FYkj6Pe0DSe9!3B!s3mJhPcC)FNYxL$K%v=b|( ziQeg*EA{8<-7#WeUOU-lbUY`Uo;i_4!mcrQ-tT65=+T(g&jn81Zgf;f3MP z6sKGU$R5&7Hzv`;M_+^#>1mikJp+?JOxL;fW}~OnJv+}(8!*xHEV4Zdq)7{OsxbEF2!Y#51Z0Nt>Fz=<14qSz%f2?RyP*TG^7V$9L#-K3nBg zlCqtoFwow}ri*lRM~0LNP-KM_QklwS(p1sq_yK-b1vUtbYISdvp9xvHzYCJnHtzsOD8Kl#YCDW8vvIfw)959mM~r3 z>~A(!R7taxXu@7n$4F7~XEV7{;;jlSPcgGC_39E&3y3j!uv-*pne(M2#>ibJbp;ry zfJ%FXyV85>JZM(-B)b%*Y8ITdoTpCJ`G;TM(mClgaOcF*&iGQBx#`oDav}pbE+xc(Z;~clQ!+N- z>&BeNs_m(8Js6-)Qje5jKb$z}l#;*rEKKneDVfT`9z;FikPlizYP0v>z0IlxZuoR= z9V&`%nz|21uf5y!u71eg5hHQ}+JAf1Q5T>R;4T+MOE;+P?0WGDtJTX+#dWt=m^gbi z!deHplezFZ;?$q9e2ReSjw!;aBEX&p)M5h~nig}))u~W1 zS;-9Fi|f85(2tgf@_r6B=q_0x$%q28vuF#f0vO%#q?Bz`pM^W7D`)O&rBGTz=geUA{_s1e<;x>=91rfp zYp76SZa{PBoUDnv9>ex{Ov+kn`&vp|)axYBV4Un^X>}WpOR?5RAlK52ZB9!AKF-P- z?=!OCLdd|$wuUCX5OVq9c`yvoK~Sl4f=mT@!B3A_Oxqp)TIN zW!u?$`Z#ywBsL;q1}>!I9IP^KiR6<+B|;6Ep4I#*XaBi#uR~bw1n#Q`VB-*LkmWtY zD|})wW2DUShIq8=Qm{5YKbrZGpnaEK5KriRKR=4J>Jo zF%sC=nPj+DRSp$Bm1i8HezC)rV>xWM#8AHT2K2$}sZnC*5-wd$->ja3uL0xv>*Dng z=|4ce2Anmkyv=%M`F$2;J4u$h6s>^Uk?!`{n+=h&<72Y^NA`a6tAdR6>79Jki}>D; z!AV`YYyr`Y@*S@yyv`^kK%fVD_xp8o{Rc>aT0toI6x7%+VCO`ZE-%ll4uT+lcAZ!s@{6s z(p;g-#}mG~&V(*6BK)W!%Y|QJjAgB*%1^B&hD&g2_<$qVlbe@^ybBj@03g4~q|J2m zIWESzO|xD2DNk@BNqjw_jG;VnR53yxZz&#g*b|z01p$9&%2c-kuVVFv%|7y18ZS9D zv!rQ~G_GjSD&VRhjD7$o1XLi^^zf`I76EPJNz?SXpLMw=6U0KjZMp0^)FTBW?#DF# zFN{F$1vygOoh1Hr`M4WO36ab$?C>-~+zZIDU3m2#;Y?I?WXrDZo$WV> zxbFI6HS6WA%?(`=fMo-oh|vjv)Jt#VPahKSJx2y|K>JsyL3(wZqINjbb!VDd2~ZQAQx>S-^5+aWSQQgjdRFXw}6|Y>>UDm z_xEYcjAP{Af0yYiUkzTqB#`_{djGtlj(Uex@^AdAvA^&2o?~E(e8U^W_$J- z!5OVI)+q9&e_Dwd)Z52_OjyD1y2sJk8E%+OcVR#{!Bd$X;CHc$kTFv&dEv}_PPM7UA2er)IxDdyn~dsadkSa+CH>~xf3 z^{K+Nqfc@!R#2RmN1dASPp}!I$bIKB-YFF9zW7Gdzv8Nlk7BLX1^cm6G9*MN;HE_v5Vkz~h`OybXqfc%Ss8THud+2ejw*LFnFRos*<5I2xXq%+d(QN{Z%RCy1z1Qucf2k{;mm0xl5$Hg5Xx zen)3u=7gFYO+E8EH!lAVl_X)iih*q5mf@`!3FtDT9x82UC1;6s1o&RGIyPO#b1t#& z@oA>C$kAj{3~G~WSf|B8fSoOvPTg;vqoKy?ftFL~26UR!H9OJi<(@!eOb2|vX8V}K z$4L)sXl?RJQ!47KE8K+hFk6&5?#OPdZU7a*ptJ1-wEc;q6_eLCxpcubg5JuIS)kfoc2ZwuKo771Orn{ z%X(2GPrtqiKq0eL8x7=mkmLQ{tV?iu3XVby85eXzp&q6lC?%anD~8^;qZp`o8_s*V z=2YO&VpevL?Z1Q$7`?sJauRoGS70$0^qhJJU;lCP9Du^YWhD0caAqCCOdnoDE$oV)uh{?D{rp8KW;y~e(O`1%m28zLeg0wLG7IH?$Lx6EY zUI`56W#TQ`zW2pC#oePuT}V1$T*7U)T|A_?09a)xUwwh~UJzLC;i&!qJp$dcKl^|8 zZu-NU&&cP{MB!7MdVp;IDgAc@^PkiWj9VXi5CGZ#?|LylJG}Wq{iTM*lan9#5H$dC z@xNs0$o_7uB%?8KjiiA(AWUjgcZ6O^xzwpDCglYg|8)F6*JilC<8nwickD*YWw7a? zGK372Ov7>@_`;&!8C^5nN94euOBswa<$Uujm232P%{yCmTXD37$-P1UAl3kJP)Q$~&C2rB($Xed<=eH4H${kmynd@%T;6ufg6Oe*OZ>pVzL28! zXb6X(edn~MRPd5o;3WonBW#fb4%PEZ1*s3_rZ5Zoi#frf`6?;fRSc3hs6nA`kdP&H z!yieD;=+LscYD>ypG^pWRcY#`pG43ka1vrmP%e;$3Zn1`eIyQ&JVFjRJwVtxPx8Re zyS;>|Z#KqwJ6aLHNS9JP-1m!v7(BoYRe6HzWVEm_-wTZbMt$2Tc5}OQ&6N4|) zVR~YM+pVZaWUXO`bzP7p&3>rPd>xkdy#MhWqb%+82jP!t>~jD#X#vyG{RSY5x+7-J zuGyNX!DW=eSwd^ZkGAVqe06<}QMTV+3mkpCr5`^tw`FdvctACZNr*ujO3aJv?f5Aw z6RAO#1CpKIQ@rvr9gPh8?ThdP|Gm#Pr-rBeLT5bNYG1!Nn=LP)x->}!4-{@E>C~qo z?mC+rC>`BME$Z1Gh>+>|Iu^HKUa-EIvZ?jVTTyRIXi^J$*M147gJ+xm@asV!@e{ID zd!VEyZ{oW{^H^_|DKmdzp-N6R7CXO_7}I&FG_DKv_Y(jCQ*Fy4r?dn|M97 zHB*3iI@v*ky1{RzKX%HepQ$O>kf*QU)TSs1ZY6xN0BkK)QFjoh<+~C@e5agnEH?W>mChy(5yu#K`l@~&rH_bbJ9N91WXO{{sPxV7c_O~7 zJHvL>q91MSOhov%4uSm+ftXOxR+;b`b0)yNS^dSlnQGIXF2))4&XywUuHCmG!S2Sb zyoFgO`;yOxj@_f^{;53rp1gEP=*W6?ZUq<=-6!$-aNe(ul(GMUmN|L(TVdt%SnF0y zliwth(F0$r*>anXlv;*@5JInA*) z4HR1~VLTVByd13(OvOv)PF(z3+r=^4!U``wM|F&4HcKH?Fo5f9@UhqwxKt&HmZ6)m z5>v(h!J}wV1o)0U5xjx|?-dfrAE3=VVEOZBjJjn3R*928KtHz&0Elc5xX57{5C7+n z{`-ai`EILXQgwP<1KMTrz%me5eN{WI21sVOdXxY#-0lz>e^KC;jvpuAwv`E=WW54S z{Zek<@pb$^YdrrCI^3_<(cit$H)$>+3TYEvrG~Xy@FdCjkf~>|q5HAbSgZ)? zb$9Bw3=Ef8iBP)uuUNPhlqSA_MoegW&q4kAjr+>1{^4rnKJE9LQl2k7Ei$vleJ}(7{uNa=v}ThXFZb{leEJ=uFrd& z4byr;R1_!I()^k(L90RCB#h}~vlkZf0sE?N`LuQQgI8l|1|sC15A!TUej&Sb;_SW% zz!Rc#AyX8KX!LC-1h`o;IxfvM+|@H z<;`b{;uC^L2$G{D^v{U;Mk3~8`d&>y1jKDTUcv6jPo+vj}N$ypkC;G&&(X;9A3OtQo`+d4lx!_RidRJ7#rcKK|AEgih^%$yS1 zpwzjkdl6l-sQpMDwP-~u!P~Rb#`y(in%v!S#FaJZmo}yU-S=<*$_Q^A(0?Gd@Jxwf=cd2KKyd- z{hh)5=Y#tnc**{a_z7&{*DP9rg^R@I2HmYe`S;k?qFbuz%)^5q&d0hQxYYqUkGwmB1}u5u;}sR*k~zYK4GTvELBIJBtVL z7!xgja21MQ6M8(wQHF7mD5B+QK6qwjHz@e_iMC(skq_A0S>P z6~06Rd};CPoMxsg=AqgWwl~rTuW4v& zYfISFTgHkqWmqHohaaV#z%6L*G#V|Y&D1)d#c5E|yXLyc%al)2|6tkMGl*3E z>ZK3rbzjZ%EPnqtG4t@0fJD|-WJrX?U4i3RFP zLGw$ag3oiqk>UjS9SSTXW#@_E5&3N#aC3mIC=Iv;vcnZ-V+Z4*WiOCXKT+ZB!kK+k zVee>TWJNPFc_fNp(XbxhS%je^4^n%$azh795Qnu5Ip0KGt!(Ta_Uzx;rD-PsIOAY? zhaWtep~(^6m)yK6*wxlGV_5;$B1McG5I7wn+V>pI+o1sc+s+4|BP8Sh7P4>MI)r#y zT}Q5vJQ%5Bay%;4&I@%X|8!(;Mh2S=S=LGjA1p_P8-(|pb6cfGn~C4Ow9cmMzR}Yh z=jJNRQHPG;g0Aacq(7IzqS%A$tH;Z?DueC{2}5dHIDVE7tQ3bR$}4ml4yKEtP+o3d@!b+V&=&5pBJbSo z;7ZC}s3vf}%&O^G?;Z~_)A)QS^BtLRyT<`g7+5y*zGIF|rOuoDdYmJ-l0eo+g99Ic zoN=CkN|1hxKL%v090A(tH1nlW3zd3Vts7!9d{v2N%it_ClFziH41V&!FMlS<86coKK+6aPK;dGY^K)Ld*++w0B20cEFzK+a3DmA9~$wG0? zM0fis$+!hgm4e`!%F#HC>}&Sp^_CS;eG#Rj0J~`wHJ(-wWcsr0C2&^lG3B272@E zAN=^I77*tRBH}Wkt7HvCmsr}p#TG>_#V}DFRwXTzW`58ElUf|4`p;zT4@6c#o3-*_ zwejyY>F6$fDr3gec)2qf+-Hfq#&}BWUK+@Wu@4z*8h-#2K(iVQ@o?IgC4-WiJyF_f zucISD?TL#0T-;B1^*D`dQNNy3#Odn7{c(@3JZ4|47rPaPOHG2lRAA*Jx*&m9w?sdT zr;r-F-+9^;Xo=T`*)$DWR(_C^L0FxCU%1=Kd6-sbf#cmN3RYhdFTwBZA9>ux+t)u1 zsJg@5>;QL1q31_H5MWy%i3UqVAQ}iOg+!+J%p;YZlNQ=qsW@%60^isq9gAh z2f}wIV8?WI-20T~W1O}a;{!OYcrc7we$Z<^GpBDFAh%IU$e z&QY2(hrMlu+B=sCzGV{Djk$g~Sr+=@&X}!E^~ltiq6ls$r6y8GP5~=rgcqG;y4RWm zTp3ZspHu5tKV=Kk3+`%l=IOZiLfb-P7hN1?YC?Ml^1^!|MX`Id5I+JsctKP6!r!;! z)wg&+Xh!{1x;SJ`@p0Q8?KgpurNyu8>0ULmx)H{ZtdKB7_aPM;!orR;p^tVL^&0@h zbuT3WRKt~+Kd;>~e8x2~N{#ew-9_a~CLJxC^njA<+(c#D3c{iH&7&lWTT}ohfSE7- zbv}Xu;#y^OC=3SUS66b6&T>_KPOOuST7PPZj^w6lxQKq((*2>2JMhF68}S=6?n*QPNwW3~nj)1t z27BmKpb_6{8{r<`KEe7Ty}v#r=E(8^>U;^KFfdH2gx3ZBv)!E>1N>@??E`f1lamk^ zgRXPp=t+~Y>H!;n#<0Zdh+MRKs54edIGTMg;=ka$ch8r&TJ=APxBzCkyP*R2kBA0< zsD%K&FcVI33Ceh^`F9r2?{v4{zki;7E7^2#c~lD+O>CAd;aqshW921VLUNoGbo=Zb zv9!NT@hV^9cL=|l@cv1B(6-w<2gIGHl>%YKu(n4XFtP_0B=&fzvknQ+bpxVMas9!0 z&leX{-WL+qhEt~_Vp{ceJ4p^sMk?r7Q|kD;5atPhmV>k<% zm-ahe!5`t%d$@2RW|=Zpt7P)p?8P+e)z4A;@|;*rsb|MKYs^nHLlXU0eZWQ*U5f5aLjKJ7&`&2ci36O$7Py`4%0J7Y^n#0RQT zM-$p=r4by$Tx{eL0PBaLp+e}!{*J^WzX6Fg_XL7> zm8DU4?&a(|pp0<{uKm{e^Wo4V8CRFma5h4c5I6)iL7QbOd#RxBLgYvBBY_DIkHIFD zk!$T3huIYfaI>Va8ixpb>B^e=y2dF>{V%Mg=Tgj_jA--HlA^p@qQ!rJ4&zKIPDlaf zH;eF51{&gpqX|I}L^e#J(TwD6lyXB;eRr%pTV(}Z1`!mQOmJs3su}s+>H;x8)HO8}`34zqvO$fyHigI0JhaYr zhZUUOP<7knYJ>e|%kj;44AJ$3U#!ORI~DU$_|M5tr)y8uxThMZntFUpbC8}O{1ICa z4AM@^kM-u80A|qSU(EFlU^nXvs8k{-?wtQ)O-9CBY%BO%|0J7R#J*b&@6I0qL28-Kj6XunA8hTn?8=|BvaatU0wkdunj(tl)Ezi=wK{sy@IS#G~05TRixRD+n z=Zaq&c%t%B0b}IzU%qADCKl-@xRAC(-9JFrZnaw(X!76p>~H;&oNrM9eqog2O=_w4 z*jqWE-Qx~KU}FHb>`FnJW_A?fgpzifID7n9SZ8c{W>GO z^(^0e8SquPIHkCA8b!p_t;`M6)|n8R@`;lUvC>?IEC z9QwkrjG7)Z^6O)_q+E+ti=X=fBn2bZ372wh4?~rWer7f>HVSZmnAPVw;eZ>zJ19|i z21G><+aj?x=^*GthkfWuHPddCoo^p&PO>RSsC!+R;;jxd=>1>5e^2tJWP*Mr>}zA{ zb^UwhYMk&`c_R?E{OQx8rrqfRW5>#7(IHU;E1cDvSPg%Q_XI+da1{3jx!~>)m_z4# zTrKd1A2&Wz=1W&FH~;G^@asmv7Nk=26#EMMp->acuc4_B4dpNjiGUQw)c+jVhSqKY z!hyTXBhWSI7CwF)blV0f1WvN}?jR4pvl1hI>z&+4j?4DIoD=X=FURv;4q_XFzdw`sP1g!Ian$m4-z?hH=nx%A=V8mKwNs$idYE zEMZpa)9Vk7Pe_;3--+N;+|p>y#^vT^bm)!K!9Vg|7BSc<-j&Re%Xe!OFgd4u$g1vb zU+t~hC;Z)ihrvqKip_vL%H0+1?Ghu(Q?m#C>#j7&N^1UnudI@wrZJ*c&YmQ?y05%l zpP|gK#l-oZkiv}t>GqQ#5Qq>yBdgr{+G<6Mq``{iS}Ir676&)>nf15^Mkd0c#rx@f z=p~dtSvI(od5uU0a4qPX#OeTg+W!kPkKenPzkk2t@wUuGbK~~BD~-J_a(a+MHq6y} zjS+8_!P%0Ef-NPYVU#j7s=cv){2DJm)f(nvweN^jH4!oKA|7V)6w#XPq2lCOk8^nF z#bRc;9UHs9Tn2{Fkz~utW64#;F#)Rwno_2nTHZC%gDeVVm;Iru)Yy_p(wwTJlGDwi zhpMRV5T5DxFYVv|2!9PG4OnL0>Jjr_N^>ofF_dD^5M{7q<0Ezixt{yjw5>d!F1t2A zViP-*$p1!#hN}X%Asil2Cw%g?No$CAUq_QnZf6Y6ubfGoyJ0cnQe}`HK7R5$i)9TX z>QIEc0{*fLs@#ChRo0v|-MKnwuUC3Uii(bFAI8OX>)97-Gr@lDCHr1$jQ+S%<^->K zurycwL5{v352t_Tb}jy8Z4EV->NuY+LpJrRTv0zNACYClxQirEl;pT0%1M3mh>2pI zvq^L(_R`vXPq{tTW}3SRPdlv6NeSeMS<3c3lPa`!Iz>;62xy_XY+Y9a0 zrW<7Ql(_^w6lxzs9Hif2qyIluOs0LeD}lt)hI z0(+2q7n9=7NBeV^a_=u#&%hf%NBE<+(xodv_qcYd0qEe)>W!0*kFjqDnc)>QSeSD{ zPzP+P@s*HlS>-IUfNAY+18HbXcmu#f%1MAQ&>HhQ?33TaKYjR;{u5a4cZlvk`ku!o z6#aPXk}KBGbkEV#7}~oRUmJ&t&(uK1ZH0OpL%giju_b{WhBYl+#WR zn>&Qn1A9i{CRwFwI&Ds&M)3WYcX2#`GubKf*o=9b#=IXxS6p^RBi>Bdi~pSH@eZE~>;KV-k5koo2$UQ>d})^;e{<=0y8yWRU%@ z<@3zlx-YpyO2FV#z*fO@1M<2gyd4ec2a<~-wDy{H#qscXab8x1hv)I(A^HgJvPxU6ED+A7!o8=mLl*r8 zIGo_Us*We&hop>f@uNg!ms2-5>eWX`VHU;e1QuF3OGJ)P+Y~$DN1(p)+ws_qH`x4N zz*&%biyRe`7?RJQY|wbL19^6k!De^;E|odcNwzh)3OL#rt`sI~T_eo$HLH&$Q@{8f zX78A923^0&y-1qYsNUA|z*v_@82`Kuh`SoM=KV!5?lB;fE=eJTJzr}IBR{IP0Mo;Nt$+M``xqpwTGN#Jovu=vI$?TkP{|DKoo}f4Rfkr33VCW_ z`hTip8~+zAs?q5bF{;rl$=7D|SH$j1SNS4=wmMJE2xfA6E|7b{W6DMEKAeN@~?!?a+!n9OeHYis1Lcj~SYo z0L%!Y-y1Kb3$svj%wQWU{f1z!67%{fQ*rT4)gL=hI;I~@fbqv4*NVuPX zMr9e$PW?gMZG);7?T#G=l;eFCqnvDlrWE};o>3o<#_{k=)m$~E3pT2}n3btM$#+qG zt2%PF*7TA3R&iy^#jlq^a~(lw`GbP2#0|{;*P0vbH=5kxEBxjH+!5!GykRcrr_?w8 zKR#RT08enR1x=BtqZS7Nn8io-aTz?&tepNg;>&B`6d=;v5wWfMQFW*{M-H{{ IsQ-Tx0PZ^=jQ{`u literal 0 HcmV?d00001 diff --git a/bl_force_torque_sensor_ros/config/rviz/sample.rviz b/bl_force_torque_sensor_ros/config/rviz/sample.rviz new file mode 100644 index 000000000..777d94b63 --- /dev/null +++ b/bl_force_torque_sensor_ros/config/rviz/sample.rviz @@ -0,0 +1,134 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + Splitter Ratio: 0.5 + Tree Height: 549 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Arrow Width: 0.5 + Class: rviz/WrenchStamped + Enabled: true + Force Arrow Scale: 2 + Force Color: 204; 51; 51 + Hide Small Values: true + History Length: 1 + Name: WrenchStamped + Topic: /bl_force_torque_sensor_driver/output/wrench + Torque Arrow Scale: 20 + Torque Color: 204; 204; 51 + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: bl_force_torque_sensor + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 10 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.785398006439209 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.785398006439209 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000002b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002b0000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004f30000003efc0100000002fb0000000800540069006d00650100000000000004f3000002eb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000282000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1267 + X: 60 + Y: 27 diff --git a/bl_force_torque_sensor_ros/launch/sample.launch b/bl_force_torque_sensor_ros/launch/sample.launch new file mode 100644 index 000000000..0a2abdbb0 --- /dev/null +++ b/bl_force_torque_sensor_ros/launch/sample.launch @@ -0,0 +1,34 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/bl_force_torque_sensor_ros/launch/sensor_driver_rosserial.launch b/bl_force_torque_sensor_ros/launch/sensor_driver_rosserial.launch new file mode 100644 index 000000000..85c9de623 --- /dev/null +++ b/bl_force_torque_sensor_ros/launch/sensor_driver_rosserial.launch @@ -0,0 +1,39 @@ + + + + + + + + + + + + + + + + port: $(arg port) + baud: $(arg baud) + + + + + + + + calib_matrix: $(arg calib_matrix) + sensor_type: $(arg sensor_type) + amplifier_type: $(arg amplifier_type) + adc_type: $(arg adc_type) + sensor_frame_id: $(arg sensor_frame_id) + rate: $(arg rate) + + + + diff --git a/bl_force_torque_sensor_ros/msg/AmplifierOutputRawArray.msg b/bl_force_torque_sensor_ros/msg/AmplifierOutputRawArray.msg new file mode 100644 index 000000000..a23efbbb5 --- /dev/null +++ b/bl_force_torque_sensor_ros/msg/AmplifierOutputRawArray.msg @@ -0,0 +1,5 @@ +# Output voltage from amplifiers of strain gauges. +# This msg targets communication using rosserial. +# To lighten process on microprocessor, this msg is intended to contain original A/D converter counts. + +int32[] array # Output voltage from amplifiers of strain gauges in A/D converter counts diff --git a/bl_force_torque_sensor_ros/node_scripts/sensor_driver_rosserial.py b/bl_force_torque_sensor_ros/node_scripts/sensor_driver_rosserial.py new file mode 100755 index 000000000..9b21d31e8 --- /dev/null +++ b/bl_force_torque_sensor_ros/node_scripts/sensor_driver_rosserial.py @@ -0,0 +1,112 @@ +#!/usr/bin/env python + +import numpy as np + +import rospy +from bl_force_torque_sensor_ros.msg import AmplifierOutputRawArray +from geometry_msgs.msg import WrenchStamped +from std_msgs.msg import Float32 + + +class SensorDriverRosserial(object): + + def __init__(self): + self.calib_matrix = rospy.get_param('~calib_matrix', None) + if self.calib_matrix is None: + rospy.logfatal( + 'Please specify calibration matrix of your sensor') + return + self.calib_matrix = np.array(self.calib_matrix) + + self.sensor_type = rospy.get_param( + '~sensor_type', 'NANO2.5/2-A') + if self.sensor_type == 'NANO1.2/1-A': + self.n_per_count = 4.9e-3 # N/count + self.nm_per_count = 4.9e-5 # Nm/count + elif self.sensor_type == 'NANO2.5/2-A': + self.n_per_count = 9.8e-3 + self.nm_per_count = 9.8e-5 + elif self.sensor_type == 'NANO5/4-A': + self.n_per_count = 24.5e-3 + self.nm_per_count = 19.6e-5 + else: + rospy.logfatal( + 'Unimplemented sensor type: %s', self.sensor_type) + return + + self.amplifier_type = rospy.get_param( + '~amplifier_type', 'RMD') + if self.amplifier_type == 'RMD' or self.amplifier_type == 'RMS': + self.amp_effective_range_max = 5.0 + elif self.amplifier_type == 'RMSH': + self.amp_effective_range_max = 2.5 + else: + rospy.logfatal( + 'Unimplemented amplifier type: %s', self.amplifier_type) + return + + self.adc_type = rospy.get_param( + '~adc_type', 'ADS131M04') + if self.adc_type == 'ADS131M04': + self.voltage_divider = (8.2 + 1.1) / 1.1 + self.adc_range = 2.4 # From -FSR to +FSR + self.adc_resolution = 24 # Number of bits + else: + rospy.logfatal( + 'Unimplemented ADC type: %s', self.adc_type) + return + + self.sensor_frame_id = rospy.get_param( + '~sensor_frame_id', 'bl_force_torque_sensor') + + self.rate = rospy.get_param('~rate', -1) # Hz + if self.rate <= 0: + self.loop_duration = 0 + else: + self.loop_duration = 1.0 / self.rate # sec + self.duration_pub = rospy.Publisher( + '~parameter_setter/loop_duration', + Float32, + queue_size=1, + latch=True + ) + self.duration_pub.publish(Float32(self.loop_duration)) + + self.wrench_pub = rospy.Publisher( + '~output/wrench', WrenchStamped, queue_size=1) + self.input_sub = rospy.Subscriber( + '~input', AmplifierOutputRawArray, self.callback) + + def callback(self, in_msg): + stamp = rospy.Time.now() # Get timestamp ASAP after message arrival + + # Convert ADC count of amplifier output to force/torque + v_raw = np.array(in_msg.array) + ## Based on ADS131M04 datasheet Revision C p. 38 + v_volt = (v_raw * + (float(self.adc_range) / (2 ** self.adc_resolution)) * + self.voltage_divider) + ## Based on NANO sensor manual Rev3.1 p. 8 + v = 2048 * v_volt / self.amp_effective_range_max + ## Based on NANO sensor manual Rev3.1 p. 9 + f = np.dot(self.calib_matrix, v) + real_force = f[:3] * self.n_per_count + real_torque = f[3:] * self.nm_per_count + + # Publish force/torque as WrenchStamped + wrench_msg = WrenchStamped() + wrench_msg.header.stamp = stamp + wrench_msg.header.frame_id = self.sensor_frame_id + wrench_msg.wrench.force.x = real_force[0] + wrench_msg.wrench.force.y = real_force[1] + wrench_msg.wrench.force.z = real_force[2] + wrench_msg.wrench.torque.x = real_torque[0] + wrench_msg.wrench.torque.y = real_torque[1] + wrench_msg.wrench.torque.z = real_torque[2] + self.wrench_pub.publish(wrench_msg) + + +if __name__ == '__main__': + rospy.init_node('bl_force_torque_sensor_driver') + app = SensorDriverRosserial() + rospy.spin() diff --git a/bl_force_torque_sensor_ros/package.xml b/bl_force_torque_sensor_ros/package.xml new file mode 100644 index 000000000..413ace3fa --- /dev/null +++ b/bl_force_torque_sensor_ros/package.xml @@ -0,0 +1,25 @@ + + + bl_force_torque_sensor_ros + 2.1.14 + ROS driver package for BL force torque sensor + + Shun Hasegawa + Kei Okada + Shun Hasegawa + + BSD + + catkin + message_generation + message_runtime + message_runtime + rospy + rosserial_arduino + rosserial_python + std_msgs + geometry_msgs + + + + diff --git a/bl_force_torque_sensor_ros/setup.py b/bl_force_torque_sensor_ros/setup.py new file mode 100644 index 000000000..66f43a495 --- /dev/null +++ b/bl_force_torque_sensor_ros/setup.py @@ -0,0 +1,8 @@ +#!/usr/bin/env python + +from setuptools import setup +from catkin_pkg.python_setup import generate_distutils_setup + +d = generate_distutils_setup() + +setup(**d) From acaa262086e9d8914cf091a41c7048e6b963f829 Mon Sep 17 00:00:00 2001 From: Shun Hasegawa Date: Wed, 18 Jan 2023 20:30:39 +0900 Subject: [PATCH 2/6] [bl_force_torque_sensor_ros] Change voltage divider ratio to accept full range of sensor output --- .../rmd_ads131m04_arduino/schematic.jpg | Bin 125105 -> 125067 bytes .../node_scripts/sensor_driver_rosserial.py | 2 +- 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/bl_force_torque_sensor_ros/circuits/rmd_ads131m04_arduino/schematic.jpg b/bl_force_torque_sensor_ros/circuits/rmd_ads131m04_arduino/schematic.jpg index 75dae77d5f597d98dc9517bd465226513c898c01..420c7cc8e45e8cb084550549c40245ca83964b63 100644 GIT binary patch delta 81556 zcmb5VbyQSu-|xRiQW~UN7zAnQ4v`iKrAtamx^oi(($dl(-O|!hgNSrVr*sTR3^knj z-skuH&V4^;t!J(C$Np#5%-+|Y>)O}n^M1cyyLKEadK~L(H4mtLG7vNHp&>nI9_Dwb zcyOvtN(@tBXB<*yc7MZQloL{AFMYD@bPt%$zE$Xa?60woLiiAByHg`eJdQ6U!#=f zISmlE~Q^vMWP}73QzzSGGr;8c{VbXIr&fg!g4BT28=`uTDW-M1(PPZ1%N@*Xp5# z@`+-fu@`7Od5&wV>A+Oi9La*IOiY=UT%ytTnT@rYe=O=u1z1;%&)6Thc8WN7&mzR% z_{()gjfSZ`fm@|N%dva4>DlhSaidEh6g4aPtKg*|;T>tpG``AUqs~PCuXk5wj~b}1 zK3J{_N%HptuD)Qrq3+3HXQY)G`)<60z?Tc}IZ)yFHZec*3K@Hm2V&U zw4ux1-j9xI6<3_Di=zi>zM18$e70U{XL_pVPI!Z1jGBEHU95FFagEFYdYealQ&}Tn_3IQaSiVzjme(CUbr$RU4C_zJ)EdLuX%(36%k>1 zi2QRu=~_E#&3dz~pcB{;G|ITclcch6Bku0R0_M9FTaFm*4Wvd+HbkwDYDH*%<9k`r z{8q}yf_2Nw+6Xctdc+6WIeYyigTos%vE5Yq600iShM|pC20bGik~l-#&Mj-`WCqpqQ1;`G+|OV0lPf$7admGC42M5v2;t-5oJbwNqbSd=!6N|Z~ed12c3%FvBeql_m)|d47zF!v24Ob zUba~0XyKB)68rRUuph9uKzk6idEEKLTUu?3o0CWI+j>j08*QoirvtMo5(=_0+l;F4 zdNaCcj*SY9?xA%93hO)cH=|<7sE@2Q^DPP;C#d59?0)j z0ITkS$6UC`F4WJJxAO2Q9~=64uRT|R1w$mAG1*nv^6+Z#?tvd=1^2*g48t{0?I(MJ zIAMrmP_C;>5y&qQT+~g1{cyxic+Ey2rT+O;5$f`NJ0CuJ8yxH?U~Ic0If+>GF-W>3+?SzH<5Ie?dl|CsASOpP!6ani=)Lm?;`-?12PWc_Wmr)ky)lD;d%NH{o75W7^58nv5Ds-m=A7SsyP^lH!&QLE$ zb7hBBwa0qynNVs!WUx-&V02#%)SjNf*uD*GkiNbJ?^rXMchJ~TYo(9*8yA+#WeP7n@z$K73VnwjAFd7tOS*QY)#pVr>^ zP3?6j^JRtb;R9TxgI00aCbmXUm$G*jV~|0?A+Tozu6T!c?R1AEh0JKajCzwpn)-y0 zrqs%8EcA!KHNf^I>R(5mV3o*z$qNb_kH?OVvEK$ch~BnE?ueRoZ%#9iEOdLxamQl( zdNz!^LO1>+KY9J(#~)Iwx~yLizP-I&l!>@x$qn=9b)yoeR4nPkeQ)b)H*+|?&Vn0% zU)%#VTlc_(Pw9h_BwQgHYR!qpY;mIo`zpR8@lqXy$PE5VJrAt0F?7?ULqRHm*YkT# z!nI4vP98Kxg`?<)S=dWbaOkxTS683(Lt|5xEU`cJs?1k5zs+cxzqHUOUsD5<|Ew~M z$uB|t(n)Kg)EEsrd3dA$kBjvG{G6lG&bKHv-h8$-tY=|?gT0|9>!~>~S^~wXheqP5 zLu1H@$ltL7kf||DFVqcDf!Yd;H2)rSo=AHVt0YW!la! zJG5LujYvusEj2Kl5Q^^7*J!pY2%OwC{p*X+g5I^IS9%SZl$)x``gB}lWRD-B(>mK* zozp0tv$=0)%WsZ1)b@|)lLo1;C0tEA5raQ!E5O;Tm1{^IL1Gje18U2A1pX+i1ZQJV zTNb3s;OB`jYC9Xa^BzTQXVhs|fe=3MK^tmUoDH}KOoUdhY0pjjs5j~9Ct?rAhQ+B! zDBpgt`jap+tvyNw9e$$yg{l-o5V#@?aB9}0aRiOj$0rrvD zOjpEt1xV~2IHcQzVb=Oli8L!&a_S}o`<5dBoCE zBQ^zAI{r_hf+>DJE^8kpRM%+u>$a}{&?wUJHd|I$j4?mN2i$8BNbxG}iM=6}Z>_l+ zZK*5j&59b1Bz$g9ErO!MShFrH&#N5J`Ya4`kU!U9hWM)L?uMDRRHimA$yQct$w44< zKXEp{Ox?sSKiOPEhM#A1?PEUWSW(8+>Q&M0nhv*4qHqU>fzHR{#jRq=b-nlp86QF~ zTSPTUKVNyHu>-V^`T?)0Bs(4s@Qtvp=L|2^(GgQ~nC~FR2TeqVL-u)bK31-k2gWb` zfpom!S!qofa<+1>*3R_eIxb{^t=;J5i@)XM*Ot?zo5~jY%pUG$DORHBzM(P%Un&+% z4NL^0?LE-9_#=pwXl&0!c6Hd$r1kHCcyaI=*?@YsKJEu9P3X;w5*yQkWL9RMWcRQu z@vV^(hxfq#_2fOE!dx95L}?z=`-gJ&=R)&4k%5;M6JHv?*4GB-H8g}QlS4nR$1o-O z!ZGx|1ThMERylqWY(IYZ2Ye1RP3JJ*_4>5oK?ohF)cfdV zJ>}TXyz&;!Z)j6!N?%{ZGgm6ra7(~&ApUrG*C+Zb@FW|CGulZI&MkdXfFyB1LxyHJ zAu$G!0ub??dBYEc#dBX}8)buEjVC&btXk%dsIUTA|>B;B9YSr-*sl@%o_3qnppBXMN_xk+J`JP_DMQxSdE7Rx4pG~ z>X-rv6s_b}FRkmdNiwN6uQdkZol9zyqKe%*!J?J;QC$P$<{! z#QN7Hl_%fRCd2SonJ<@oyf`mrlTYY!{)0RCI)nMw!8F^5IeTnN`&y9J{scBJfQ^j2viAl!l;m}9WAB29rULT%DmQz-4 zY|HS-p<%~^rl~CzJ#I#ZE(i(>1ak^_WDmq3J|f4l~Iz%TXq36n-I}r`!n6 zSuyCZoffQmJ|h0veM#IRzIFB#Q;Ps6VG}NkPQ1qkc@KI>I%!NE)|gG4osjjZvSUrr z^5Q|L`Xqe{zfGOD*&Z?l@ThZnJdMPjVgNo^Z(mCCMx6A^S$cF(JZ}!Mm*niXdSCii z@HPrt9%z!t5qnqYmwqh0M$^*LbR$r=R8Q%3w2=58U1uU}(_Nb^`QYqda93gqm~Ef^qH$O- z_cJec5aWtl!H1n*P)lYTBjQ!V@uB_7HAN%O&6UGFFkr6}1#G+fRVk{Eb8;4q31TKL z&x>Rgrf!myLk5n0U33DMq~`<2Q7z~2J&;>(o!PqJxwuXB*DdC66gc-KNVLK}($QZn z@N{m}rf1~$`_K7Mr`+6x&lV@6WQ5U;<7-_wc4F21&}R%RF4+^gDVUPKqfr0u+lKh)NA3H7N`{*Y0Tds{FPPYf)w&6hi1BAl)yW*XT{2|_oBk0 z#Lh`FtCr*C@D}rt2MFXo%kmhZZgmiU9r1nEgnP2uyP;8MhBK*nr*LG`v@kCi39oMJ zYsF}eJfq2evb!vhX-hJ2xncG8=g<*0S#C9geY8(FLwox0*Rn(81GUc&cIB84K7n5D zb}llsf%yf)1>QV8&z9XvjSx{IN9P~^lq5bM%`J98=*pd#uz`fVRj<}xa?W%b%}ju# zt`WvX>J~}yu%>p+wf+;qu*TYsj1g7)(xdeZG94@TK@&>isTl(V+0ilA)~vr=nLV-L z&nIy+X0*;}bhzwnOL2MhY!8}JCxrW#s)J(IH7O45GOgy>(}bs*)u^rTSs zYpzgedui3Rst;0CT-Ssi@%Sr0X)&u=-c93MU}*@!{^I3f^GxY8^v1mI zc6>Z}Yg}$%FzUk69nO}2rT@F$Eb7t9Oc3wE8TL6?+W8pa`vdz>eoxuDIV@@uR_(GI z`QWUAV!r#NE8>=;(1OIC+2w~meA-Rs?SKpoZ=fF@H5UrxWEA%3iN$XWO6W-~+K zX5?@wzDi@SIp;zRy(#Ux>W5V89OGqxfzvM^q3-h*{vA@ zUWsKi=Xt+cdC}1_W!2F()u@_GJm}-S`c3wSJOEVWIAa+AKM^nUJ1J~_ekan=kUhSc zE%xWf#ZUYA{t(9L;IUBZKpHR=&+b|C)qDyZ7GL{wkyg}SWZ*rd7pflr*gRZBI|!N- zG55_?U9`I9#rS)F>B8<}+i}XnH7qL8chJpx`praT0SJ8sM>klYOxNB_z(Yg);thY` zx?|=?`rC{#rx1Qz8;15GNRNp-CPv2Y-7{n*A<{{PW=O_8$0!-*= zAZAQ2;OsZh3fvH85Ie8(Wy`}6Hc)Ha+_JUm&|#(wzpzO|UMZlRl}fMC*WCj-*J((+ zBM|XN-NVeyMKqDitwRf=htz7DZyhLPyX z-UFPiYYG8-#}{hHcX(oHcQ+_SyzvGCyETO$P$03V&T*qF22^SI-ZuRG82xMX8b+rd zBtiuxd^xk#RcW%D*7>Np@e|bRa^J}rC$vSP2Rxpg`OwRMIu=ACI z8>MT9=sfnQx?R<}6P|MQ@7*E$QW}~&p+DSJj{f;f5!xK#&lTQ;OIT`Pnlx6LG)J9x z5dDzq$)Odt%T)01IejX+Kdwj?x=Lr!7r8q80K1)VdmdLW#Sta{%!~(v{~k)5ZPVH3 z*TL1U_r+4H%J#pU{slEAV?)Cli3{bRA)zj-*7?w+q#S4ATVa&p&?CK8C9L=tIex+6 z9y&Z%A2=Sf!OD=HhyN<{K@?lwe;s&9c|HC{IZS^G|ITz*`d8w&y$rte-DV~o_CiVv zs9z(UP};D`o(AQG#ScIFFRKHWY&{UiRsy8?V%z!j`GDfolZ+MJS6|2}NI1RFemhqk zMqT{u9=qkSFZ6!t?dwI+RQR&aCo*WCxt>S?T<8aUst&@{AKG8^Ja0-{=Ck)Jc^$vl z9@&;F_x;v>TF`+(sS|z(OD{G2-fEiEIJQP2fL1Eq8)Ge5t0%_Vo6WBR56oZ7jQj(3 z)V62;VS&xQJX{FfYm>#AZIqV|KCgN{dc*VPBz9@}lZ-wic^T~_BN8jwRdz=S$N&x; z(3wUcPORxbtbg-Lm+MAoTNmBU)HE$ozXQ7S^JrSl(iifSIC*a&S{jgltfqfEFaz5P zWovAN=d}l}E4~>pfi9QIv<#&p(qTTg^M8(N;iKx~xXCl;xbX+7F|-ZuKU5xphZ*(Y z_b}fuH}X!L#>SJ5fk^T#g}-Qg24pl$Dbr+|Sko!M?VSyp)VnDs32juFYl z@YfRW#gT~9OL;-l4S8Nttgf=<9;>Q9-Vm$vljAekc+Nl$c0?>lRF;#!;Nl)hpDzsC zO)_4tS<8&BauBRy)piipIF%aar$iqgrgueq%KS;W8>>^aasiA;kk2>KQ>!pm^AIY! zDxGP+mc&@#$ph94yVu3JCl<r3YQno|O* zH*5{~vXcpU|F6nN{(k3C6s z5b8J2(8f8fZ-{&2Zaktq(Bz`S?JmjpSGRt;nsXx&`HQ#t^EMmh+nYd-fjuewarYs{ zOR1;e6z6$5(dR~*D(&&~fq<|kvOy{hF!Jq+ZrTEs5>sO8?Q{OCI1tQyHiKhEHCzo?(eZ!<#H+-F_U!R76o|V4OmCyuVuEd5Hkp>Io zz6rP}C7(HETQl^#GJo@$Bq^v8Rb9?9IHKTvv#r80jnX*Ab`%sBgSK>c$+PO6Zxqa9 zVwMc?L|C(Q?PV~MzJ{`aw8F7xe*3XrN;8k-)%?`!ly!^+vt{vq_mx+jwgAMT`~9!s z)5qZhksi29LOnMxre?lp#?t$lIX=-AB?&{rQ(XEXiSOhc`h3Q6maB1v&~%|UfE07y z&~N%(i1&~q)xyuOqMN=`Vx|%2Z8aplHHgFw^}kgP%eaPy7_L#YVC=77x3#NyZ*hQb zcxrZjE*ejCySz0)zF+CnmbR9Rg+s#d_vqT)k7d5kW7+*|ooY~Zf*`)k_M~0fK3ZI; zFq9y~uA?9*?cx22jqW5ui#MxoyEaPZZERTwAKprl`edAg>!56@)41rWtp0zjrGc*x8!k%)qW4FeRK(z@g4=za$Tr|fzN;;Kx zt-LMa*D1`ml6-7v+zW47kTb$s-^8q@wq^(~sJ!vdJPD+a;|;pF+br<=zM3B?MmDvC z{Iq>TYfY1YJ<8mnG_O`~Q=rmKzW$hG^>!$@8*7S)AON(zcKA41skQQpuTy_BIflZM zB|UyBNrrOLo=EuP`=itaE#3ip3CESWW?Fs;76l>ePqA0p+b48U%=~g?KmjycXqE6+ zF^0XS3}uE?kta+wzzC{Kuh;StkC3Z1zMLWX#zAtAjvRS-9Bm@*BNp>+Z`v@POBOcj z^a=L+dfoN|Hv1TMo^0ohG? zM?W`e2aMEDb7vsMcXP$8Zo_F@;?KSB0i6}at1bbueAL~OPRK{M7zoY7a7BwW6g68& zV{YD+bWE$XDKYBW^_Y-ma4_6*=YN=*H{2R?)kA-(NP5u7ckUdJQf!Hw)srLcw+ z;+=e=P&Z9-Oz3EBrRu};{S`^-8?|t6mS=;+wF$M0v{${1W#}%;pHr`!Li1s<6}I=l zySiWtym`OW$1-Szi%G$gWde}#ac%dRjsPL7DIJzJt6$MXkKg3{hMryL*n!gkDJqb$ zvRgSN8SC1=>N?A@laRaz80Wh7um7T~A7}xp0DMXfLnW;!HCOoe4Yl!Mb#|WdvdJi2 zM}u%$JhV<|T7w(9nE@@&GX46^7lu*hK_NkgpxSTGI*8r+XWle3*om(3U50ay${lfN~)o z1!(BSy+5R~Y?aJ;RmL#pJb-*4o{{w5MrQ9(?Co+k%VKLWf1JxWtuLQA5^0 z^gu=sL=x}wTpgEzt0UX@K%53<6Fw}!Cms6$8 zB==~D89kP?{+S3sP+aejmSX~;0&|H=T9SHecT!nW{~CN#MfadO9q*bEy}+jVOA5(d z&84*Sh1El;>%PdAE;J$&A2={Un4iET7o1X86e{N9YOD6?*<0b45hcxas@Mg7H&^+8 zRrq5HZPI}(yu<)d%BjzUZnmA@y2v}?#%50w5inL%>G_cOMzlvMuWaxN6!+7KzbKR< zI4Q0v-{au9AaDI-BnQ&I+{OEtsUkI|viUYN29&`c=0sGe&3^eh{UlmvvYP3gAtH}R zg5cYgu`FWz$fbM*8N2$&AJd^n1BKU5koa|kkF#90#bd^Diz)$C0nwL`< z;!-iKXMXgfpg4M>tsrX#xMkfa|E#J13SM}`3|OC)H8|lb*LX8six|!CrM3<)4TlX< zK2v#OUUD}%c0&!+R(TKT)xl?DkKblIlS=acYVe5i@tcpWarc1#^pcvt$J#JofbNaG z`plO`If0pYRBV+aNaavn9rzwCCTh*HrE6M>;#Q`$<7?u~g@ddFxZqmCzA=c0Rr*74 z!G48EAXZhbW3mCwt!yvNxt;t1ZZLTHnQZab8=ycGniCQvZY+ev*Hvwp;)>)oex9VD zZd?hWy4{<$LO7{9Jn9uQNj;)Fq%UtBO0 zNT}ytrS#L4Isp+Ez4FxUVn^BK$sbOC!|bcAKx0u#@0|B6_6k+^)Y=WKtm^+q*Q))M@xR62mM@pf@TwAT|W<2yC} zWk}^MRe57WbHXlpoxz^w0?+52x**k325$}mml5`e7{NQ9KF>@1H9F9=Wp*1o^&-Rl zk{I@Z=%L4&hJ`3ADWszuv3K(Vk$Ua1{umAqM^AOgqp`K(B>sF4xTkcFqA{QBu*~p0 zT9>Sjq5}i_pQNx%a*yZos+1E1emK$FFIw1JA(qg#2*Ap;_9&X~+v^QSAIxIVyw+j( z@MVTGkX^B0ZwOlQa{N!o@_7UWFO|i!TIppp_JElnZiJQ-op(~tOvZr;>sQ5Z1UfUu zoMafrX&BSp+fGJa)ipizkJI`LBodbvs+#g`-B>KLH`(Uiq!XYFbH)&<#@<`Wli7$f zo`~yrxd9%0E6<_$j;VERn?E)oVck&TtJ&A^8}*K+iAFj_jV3?CSX0eRjT?bbLL8|F z6$Aq~53k3tWKlNBV+TTH7sEfLo58`l-}urHh&F-vK@ zc+3C!T~`WtTnG(p)LIircPNUZ@>eCT4AW9;jeZYxcJ>xI%frw8cYl&Yr+u1-qjM`gl`Q;?}~Bg_(?bsvvi zPyi%YF)~thc%P=rZz{q2C4!TL7o$ZyZbl*q!xmw_wcXcBDi&pLP}Lrm^Yn1ZAzF_8 zneKD{9B0|>Z{2wWby0s87IG<#?Y%DO8NPi>rD-y1Er^Hu!V z7#)p!C`H=hlb^Vhmq_u0fGSVx8@nuKt1=ffdhoBrYu_9{^l0ZsdJE!D6qiO>51iT1 z9HUOZ2{JI)Q^Oh^zL+dDR%iOoWFGyArTeHc*Rzl?9_C3cl)f%1@W;W)Fo$Mo0Cd&A zBBU309Yf3Q2@+G`_?&tKTec2&qHTB0XWu!U3)d10!SkmsvaOgOa`R8}-mr8YAtC?k zfO&R09=RnI_|7b0Hx3pgt^)gy+_Ee+^|18$ySfwOKfh!Sc?jo>-F6cwOzf%)ELnTbE(LZWh;~0+9=&54Z^PDA~>6dwF80F4?BeHPhSB zDa`f;N+g!U(PGx3Bnjgf@)xbN&7p=@Ab9$GlUrHNbJIzTj!xTmqEq$FU9oop^R}aa zmCQaVrpb2JbLja zrgQo`j_l${2koYkS8-#o-+9nYa3%cKkEOV(!mbr(*Uy3b9P=IFlYzfNB$zTApE&IM z3<752zx?*@RgNr7YAh((I)gg(F6o5lU=J!8jgK|*n& z4b`|xe-{{rM`$iK6K$XK1ioBR+`rCWyljgKQRlg)lbs%Q^9Kz7> zkV=P_-vgR0s`g6xxxZ4bxgFrrS{NwdVmjIGDuVOElvY#vcAXS^97RY6<_TAm)}eL(u5pvCc#2ec9L4lmter z?%O=B)rqMXrj=;OR2LEb$Ijl@HHghl>2IJAen{K=au7#Y_pvIGG@#~2&wz+1+`GtV zoE~24XdoA^0$c|$CA*njm5@vz;Y^*NI;jov@kvccno?)niO!xa)H~2Bo>z)2{++~a zNe;f7Z{v9sf(AD4e*n$lAxjEO}*)^{Sl`-V3wQ5p|X>=FO46n z=9Sk^_RTF`ux~`ArmTB}qx6L0Hk!Km&Ii@B=1~K?Y?Y$s9h2vhoOC8fTjJ5FQA%4% zGR%Vs*Ohi|$#na!K{&nIQwI)$gpX{;mgl?Oi0WJ3CMnR#t^gy1f$H13f?T>cVupHQ zDZ@jHwJ(U0DH*NN+t@bI;`1x#92+TS4xJQ&OMP4n)gGa-bSis(j0wCf`2nf`ZAtgB z4B!ju$-%N-Goh3K2WaUCwL(}j`#Gy+j3SgETg`3^OVGi>x&)Ddi&hDOf}9e;`AU?bfiPj`D>8 zhjM@6kQLsLT~9e<3(`%HuhH;&zGVH3(OjEVb3>2 zpq3jYe@r6f0iT*k39_=9IDu?cd6{ctSPA}7k<&K_ZSAJdP|}iKI9j5N#MDLAx-=o8 zxvzc!p|h>oH04;3O7*2R{8=z{*^hTvrGh)|8dxlA*$moAePU@ek>|ge8r$0+w71V7y0A!oOY8?ldc`r}M8r>VT= zTc6|nEN-hoFc*Uh}ixE$*0U z6o+O{Kruo#wo*=lqI38c;gE7rh|fMyV){HXf7bCV;E{T}AC32cHhTRa10l0Ghkwf| zAbpLH!WcVeK$Ba$Q*&@S;_`@Aa%j{mjLorE4w5q5pwj!!g1wW6W`HD|0qfdzt9Qn2 zu17CCrl)4%MuTQdoUX*_%+MGjmBd1irFa!!7M@yFA-gWA+mrEUtP^ahixbZ@T;XI^ zN89w@6IrZ$mN3&M_O}adPp!s#)NrQytV*Y6%UcWA`op|1 zC#Z@gt2wO@ryhVL!zMTyyG&N0qiy&y6H`~D;6RwUSy~}F>Di>;&HT$ zG_YYrXVZS2LZG+7DpGz)vTuTUf*I9Jy);w%#jaWP?fR9*u#c>4By9pIoP-WL`>~wo88c4f^6BN&2XwioFXl@)Vb{JzZRkqSm8Cg>AYZz*QL~ zEemHkSo?Gvn~-B&@SHB&!VNAzPB#BW20oIaU>p%BN1)(pQ`ksrXh$~&(CYWmo+oz{1GzsBu@Q*nbxdtBdQ!-?y_ChVQ~k-OI9~8`n9{}I4RDmkN?v#(0Q2DE0z{< ze5U4k(fbojJUviFpJk7co`5o*qtkz2$j`$y5$J4dnmFPb2wTvf*lcq1lwWkgkRec@ z+(d=dz4p{r5pj*VSkG$*tuU5@1unu2dF(cR+WZzaDjS$RsnUfbqg^1iZHV+zBU?)c zp_;ND+?q=R8ML|!n7u1oJA+fju0dE+vl-!qaV9vo@I5Wz%3Nq+mQ|DnQ#6l2g@@Q^ zpPmKom|MZ#Ut{ZAICFVI5VK+(P*-!qEoFw7RfDhGS;ur8yhG7hV-^KkleZLQ-UF&9 zs{5YL>&no9)pOWJj78Nu@U0E8>7KBVG;s|l33B&nD`Zxq`ORMjDrR=| zx29qjdALZ@HxcXcaf}TR2XO39g6>h|ywIW|ij%88ZILDv{vg5s_M(Y;DT&IGUtQvI z7h3EzDwPEy#)EaH^EDyIq zHyOcc?CsQN@IK?iLT10`sEaeM^-w$BgvG+M&PCrM8&vT1<9H+Y2GWZf(2xv$th|p? z&z;Kt^STL8LbCj)Wz*Dqi;jtEnobRYPYfQ=1mxf?2Y>JCo)ih3C&JRpkW1zC{Ail8 zCX-f;IML;dK!|XK|x& z4|H_dj2wfe{xkjma^wDSaw?h&2b@H<5Cxw)W7{lKi)YF*nv^ zLpv)34P2_dGtIu!ZFbaEn-2y1Z|iE)ewk$zSZ@M30F0Lnt@F#bL-Qk)?U+jdRrUa} zrW%zt$eU&f+D!C~n+6h+68ZStMkefqzw2!D7#tpl8h}EN9LVl6Q%4Shl29mgr?ACc zD{v;p(d#}5-?R^8Ma^{mLGHZiLYkq(3cpv{Hw&78OIEVs;h5E&Z+&NRb zrLKeDl(6GWM=uMB^&qj#(JNdV5PFV4F^1}bPP2mLONMhRJF^t8`_Z3zFBGQql>T}I zN%Y>cm-}a-kfUE3%%oU|h9AGKYfi?ya(h+!`}&bal9)Mdn&eN&BZzd`$RG-5vF)Tz z6m5t|Wz}c)8){N~{ptInk}TG@DqmpZz(bsd;iJK=m##*ScbDtlWr_Qr-rtr^3`&LQ%NT14EwsRL*o9<9Y;h4%K;d#%PP@Q+*1 z+#U=z+&E&9Nwfwe!+Y^&JWu7(K#rbxA`Tj!C3fu9xIXth0_Hv>xBa0b_;6=FyEcMUuvH;o(SnkMrpaL9FN>)X@6YbbLr zmn^r6$K!arp02A#XQQd)_z-L-8j8$)zD`t7E=uZIrq5WW@o}f)S`GC|0crGMIucpg z1(Z}0SsGZmdj?kRAi=Fgz>`|r3PcF9d$S{TM&3$ZTiik(Jw=`h<|C1GXx&FWlIh3O z`;E)#ZH~Sm+Y{|LnSr-q-4dQd5aU1L!3DMs%(mBRVVO#8Mhgp2tBCyXRAh9y;qLg7 zmvc559&J7$M!j|)y<*nBfpiM$Qd>b1m%TX@V%r~Yt(*n#++NL9Ddm{tx-%)<&C`B* zv-vmX2IuThZ1hH2J!EWg(bz||d88%aRJx58FT>vd47u zQn4;Z0WB|6DN8i!-@Qm=6NO9>=fdjmfiawm@P=H3$WSpaBnB&rOpA;Y0!X#6WE54j zwKc;4LKzO>BwiacP++HW6rqHIzwvfg5Tv;qs7T@eoFfnSRF-tX|98SgR`nk&tog$K z>AU#o;cPGx0nM!2axAIFq;)64fptl82Z>)?^ZJk7c;j8}7NZa_MdNS#%P8FPLo|vd z$s0*Bu%QIUl_vQ5iFI9u-deCuP53;cus)si!y}*PQ!KJZ0Sxl_s5)f*>K^!Bcn?rZ z|HmH!*d!}hz0+n1++{AAsBf3Q2bf@0D4y62+`)|h_xnOY%^d~9D5#mO(VhzGr>srP zO_a)l4d9*HJU|1}L`P9bXJG9*9Zl~EG^4Z3*1V?2=kx>D8CDWP1N}NBYLA@HFzs0v zK5b~FBY}3rSg`h?$H$R)mcy;behx#fq1kaAGUuaC8j4k_MfL_JEjEq~RnO-y0B4hB zja3G@xQO2~9*x!MHO9SFw%0MbI^1$%3$5+1l|F=-D|&3lYjiE;Y2aqaSAJIoz1y6) z;lE09pJFY=!v{xO1WWXj5Yh5YUlWl520uBJ{_sj1i+#|CbU$|slHDL9&s-lR*r#Ax zP@8pMXba(E3fZOmagCM%L?)?cYJx(_By97_bebqW+#(3rQ_jQEG|Dn1@#hdY$(w@e z6*?y@4%)NJ9K7O%ax|Zea5(ADx{ngh;dbbpirc87Yt6CzKGW7r9QchULoJ{yS%_GX zoe{*CJUp_BI-hEAHZ~kY`%%yuq1iSYH8JgxE&ZZ7EMYy==QewD2leqHeQioA# z2&|(lwm0mbrGFgWquk)`0GcVA4Qs(D2E^wQBRY3Q?WqKMOT$^9;A zc>F)gV0O1;@7Zw4bGX6Bv!N8F@$cvu#2b{FXT^3z-fr464Ttac)u#;Z0X0sCEozUS zDWmALtiL3|IG525KnwAY7tBC?5B%;GMn=aKz$ZEH0djvU$$ZQ?v-)sP)7HuICdC#U z8L1SL{hl1cwkgNsoRvP!A+M(yE_hxi94&jEr4O3V^d+R%4n^M!Wb+|s=JcBSCb^Y4 zeG^qk1{M=-(2Bm)b*(-Ahv1@4L*jCSh^40|AjW4Xr3bg9z)&a(Q`&*F_M&%59QAnLGi{N~K$@Ne)oJX3kYXt%!$0D8Np3 zSoj`zuz`B$f&5Z?B6YvQLAs{GL5xY|$H?JtG;ey@w~yS0*fwS!)u6TsIjeg>LXhW{ z+z3U1wf?J;(|`|X?g3K0-!`pr#U~~{Izq?J`z(cDQ*j=C=guQ>(M#=QJs}G(D5!}P zSitp@G*@RLZ%mmxEN0iYNOJDAe8AT+u<_b^=3>+cj`h)@p<>8>w?8KKkKxa{XWvJ7 z3(sLF?K8iext^JeF~2kWb!k|r3IqAW=$Vqaj`cgVqYIGsQY4R{w{QMTiVBVbgCx}0 z7xETJXsPHvYHOaGV{PcAnlQ~C2;T9(JQ0k`CD|)qpSPzn{@_}E^sIAjL|4RY(Spoy zUGf)oZt%I88K1Fg(PB5(FOBS9IYwp7Az05zA4P?lP79y}52CF*wN?IrB9?Apk3_IN zxX-!rr7$QY_P_{|Qyj!?Cnc@aZe4@`)$3B-Gft|ikLiW_@ z;Zobz$Nj7}4`bnVqJR5b3BS3T4}0_#N8(A%Z7eBv!!4Z88+M`SG2Ht?T* z&aU{rsqw478yw_$UYnfY&uJ(o`IRXPC^FNQt&U+t{F?;Wr-Av>ZAWr)f(@nZwPswK zPNn4U$%6^jgSNEIDweiBk1pHQG+ zkxjF!H>V(?7`rjn`jyZG#l*qH;fix_IG(d4(sU+>9}0ipyh7k!MdG8gqCI(-Cv^EN z>x$x8DJ1ypNB24U%&YX(B{x+#7#?FjeZEApZhKq&>Eo6@wajiCElD-6OE=jRLb|_+ zo_{RqO)WmdFD*Tz+Y{b{z`PK`{PJhs7ZXmnw%6bXru-%BuhitWLR~|E z*GJ_=1yR}%MLS^Mg9ckrjc;GQMQhCXIUM|ffCd-5ADIiGC6Ka#HZIV+f6d zifS*>Z%oob`Uzz;s_w03tmuO$Q@7IgcGT-!u2jX%*{{fS1a&s)eU=dBRfsgB=w1`L zj+rN6TXECE4K^}dKWMG@WoQc!B-i%l~Sm7#U{&#mg z-|NM{-!()zy~)_UgVm!p;Ag47nz>2>ITojcCCFj^oFYMyr<51Vz>k9 z?08X1V63lb8N z87sUnwEv-sVOWY5LB$&T^Cz}cIz1Q?gs&<)d8>R9bvmjYXIr&4{y2fzFp?P(Q~mIY z(zEQKiZCRQX;(}zYDF`e0A9mEBH{bk<&It;ElP&$;EPOFv+3HU-=@X8v?OBdC>AC(&Y^!z25c%AI z;(tpHy^Qz|9vlI_`-bq&x(tWm9n&U5Bg3nizjZNKFj<`eEkXfE`r4gg@2rV*qM;hI z;e?0b{u4s7rG%y^cLgjTbboM!KjxZN_c8pZk3Vs~H>jDaAVohrrRc1;slRl@UULu! zyxx)7HHj=hsA{Pb^L+G|t%{Y?h{J3S;qY@oCt@ZtL}U4!MW9^f4x-QN-%3REP{%|E zyl*;0uc?0rR~AKMMYpubDG-2c^Obi6d)9@&-Y~~zW{hv7J_uy9$p9?_(Wg8_9Nso| zO@1;qFqWrOW=gOm77LPgr2cNwlY&!u{T+Rs(c!h) z;nzp6T@%@^Mz)+>$C>zhUJo0i`}L>l{@;f`sL-kaJN=PMvBfkJ?%A}L^`55B4b0{3 zw1qbMy}Hgf98e7Ws4mXGFw=ifQy_^;;wf0!Mci%Wu~wzBfFkn5MGteRs_A;Lr^6RF zPgXkYv>oKs8>ij(qj7(KXqqMd{6}s{sXLEQq6;N^a-YN7Gd#Ocyfh>HjC@_Rur9e* z_*3XHl9W}l3H^;p21D`oCrq>4^|=P$)#)09?yQs59hf2= zeV*=a-l^Z<#N(zoX_m~r{=b-e%cwZ^t=+egKnSkEAxI#&HLf9e@ZgpN2-3Jqpb5bp zI?#cj!KHC`*ANKq?%o8qb!x5s?)$E_@44rUdp?~HFld?{T~$<9&HsF!=Qr!uca12g zg9HxWFZF0{mp6>}a+H=VTg2g*Tkk!I1JOrOf;y49^_=H^;0W|=|@+Q7^z9xgGh!2ImwM)SE^97^zH~y);jy5 z?YKfcr74W`z|o#NjeW`cIUPI@W4x&WxPNemdfrS<2cLbJa4SF@>Zt~Fxp9A-%GfX_ zQ_XfzkWkNcKb42QLMlce8xw&jAyj4$S8!>GO2rz1SX0alM|bXx43$~;)t+Rr&+J=gzx~3*8=xp(3j=a>KrHF-@BWzQ0M*?D{ zHFoH3O+=N;5w_Zkhv!3hMjz)FUI@k}cV~aW$+B3198Belb9pQgMo%bBeJ4cByn@7v zkIwzky9kqF>xiou_ygpJI(rs(qnkCA!uB(hnK#wSyKiW z8Nt{;Gq)=8DyI5hmKyt06vr0rQBe(@Tx7LjI$U#hZr3`$5JuPnjD&HOD}RNmwgzsJ zxNlkf=|Z1wSI%C4>APGts@bM#IB$piiMA`0ssnGVTxb06J|i}C(bzgXp#=5Xr#G~$;8<-)?t46x7fspb)Fo)FT_FHOVJ&e!(;>-pkZA?H0xznX(*L3)H7 z1>|o7+6gnD{t#mIx(Ns7#@dGI>;COFh zr#Keav8bt!!9utj4J77<_2={b3?iUVS70f#ZM*OjhCT%PI6h!+0JhGFzb6h2t5JfT z^B|u5bILb)>6BC2Y$*AySgZph$Bpks)*~ul>H*K7+SQ}nc3jN$RrXKjY}%#<@ZvNx z?$@3V+(ELw2k@GY*Mu4BM*LQkPpnhad+lU=ld^t zQV2ZyOPYL4AHpy0$a$1-OzaT-P1QwXor11)Wi7LH^!OYc?YJ>|)NSR09nG9G=O_PR zWm-lK3VKJwsKs0T!H=YO%)2CC+3x8BlGf7{Q*zS$0H~(!(a)Ceo&q0-zGA?|x`jwU zimUo_TLs!k_SuJo5EGz%yn9;(gnb`K)7BT?`%!fYIex&leJW>n5JydxqFv*B#HYS$ z#Qg_|(d6>pYaY7e`pY-hz?Oe@*wdkMz=|81hVtGiHc-esOBkr5yp4cm_tnee&bibF zT0bH6aYhrqi}ge2ep-qr0Y9F`hx06JL2Qp76rj|=x*88?uNfYLIR!`b#`DLIR}2oV zOe$Y3lKYdI2;g!)Z%DSsOm=su9q096Uel1)hV7_JcxU1Zj%7n1Thme^qrdZ(XFy-q zd^QZma7i}|O2vQk6aSV4S=35oX(G0oJ6?V(G!G`f%xG%4JIo00=^RusnlunK#5nq5X?&5B397L1#HhV||4)Q5= zTIxfV{sB@ysg2B?F_|?qcocF%=-R3fzlCnT<-r_F4G5Xfzgf~IH0syMzAwjiMssP^ zH~Dj;0O}6FPr>si-wA?_h)A88Ph08;v~Uf{jlUbO-a#jeLuCwCdIptYy4)@VJN)Zh zr;8w~dzyjkK4Y(wVn#3dv{1+L1KnjmxXH2Drqat_LRTyd{`ywjr=6A1TMs*mCmc3BBjMv;)qaHiOIPt0FC z&rj9(vq1-Vr`z_S0YE!(s^+}xiM9W;Tkeb8K=ljhP8>0oBq|Ct8@ffhM4h@5x)6k2 z8OPc&mD2Z_AbrhOMw!fq)%;57IC^WDVUn02wIts!6?Z0FAbDPoBCbnBE z(=Q&z6b~)=fYkMp{C$T*1n7;Mc{M%dm zrVSl&0tFw?zICbSNY5#>6Y%N>g}4o$36>=E#HfyCaO6pBkoUE?&Phdy%h<1wt1kRn z_6ph8^J81w)F@zD(sO-;wy9A9eF8dXV-KDXaC~Y#XEBG!kJz4Yv|r~}vT=tHbqH%F zKq5#mUSEiS)lHG9@T3PaU;8)KhNe}-LxSITO5Q({(f`admy_TvwYU}_K^d_rE`ir% zQ*38%={}5Mjm^A}uAf99L&v27+LK`sUMKkj1lp@>>Gq2)t=Zt<=rVH&Kkv`iUFprSX?hEt&<>0s@5_4cQL#6 zW8=ov1|WlJ*w*LKMqVim=Xkw43CLPBdrxB%*QZCV;RVW<%&Ip{oV~m)PT8ohx!!D} z!=ULCpjHCnD`@ZBNRaN9Z!{mfby>-)QwqvO<3#IATICH3tIX1idg!BBuW<0anKqI( z8n&H4cRX5Bi#iLLqx%w$1&o(MK2@lp>F3*PjU27#rr4q(Awyy8b=D!oL3;iy(yes zi0N;?DLmii{c!68`~yUDoc`RAH|G0>QCinG?&ESccDe8BG?1U7PJg&2^wEC)q^Yo$ zGy2hWoz+9dufW)3PA-4*H4Woe}S$!#|+&4jqv*1Ul&Wt5NoVQ9(- zNuY*DKN@k(mzeB=J6Em-%%~5O)leE&wUfoR3k0HdsB$ilO|;>DL%3IQu$bK{(1%ve zXzEa0wa{x{B}w%ORW!C*qGfRKX*NZ&lcgm+teig}n?ig$6GQ{(@M};)BQLX8Fs=F+ zr7+6~Dz66bT=QVLOP~=hy6xaz7Dj3Rd2iYWFBV*)Y?;(KwI|>3hB}oOY7*7%LE{WK zo?-g(RSBH$NtqF!jDj_X+Wjvl%9iL}icNS#fe|W)DYJa@ZZN_}VM)AG8;? zN2A-dmkK`+O4E>%b{Il|sG#UnA)@E|?i@wUIQPp#HTI{{_dWaxp z1^Q+)G*Wuw7WzkrA4hnl-+ghj!zspz?=zRCp&`-bYO#N`ITh*Xj_%rdIov3s!B@+< z#YlhR4H`vnr3Df{cFX7YfJl)`q>FG#kq^(rl~`I=EcXzqvxYWQ>oReSt>E!@mVz#N z#0E|>?y=jhW#EA8LjzM=&RJ-xmBzOPoO!bUcxPi1z?11nWg_bcI=El6B)10U%4a^)(=bxA36w}d!8hJrb8h$SU9f_o!xzS-WD-9g>5~YRz(uR z6Oi^hYQ+=4gTdBY1pfe;j3ES66ipCirRyr!I)T?7gPu|!H&(a-f0)P!`krA=Oq=C> zgS&Y6ny*4@U5p+F=a#P3X&hanc)o0`4%lb!2Kmu^U07~nja9%pCmcQ0&QAArWlZ0v z{B87DuKr~9V!D6>GZ&Ax2D5(fCZr%x+%Xx%=$(yF`#TJF10%-)~Z{nZR&0m0;=aZ)fVPW`?iwbGtuPcdeC6eJkG>X$2HlLIw`)B z;oQms51$d)K5+xrvJhkE9N+zu7GB%m5(9w``YVyYi6G|deD+`s}FSpucK9kuag za!Kg9r@}8Vl_QE*sCvp|(%zoEOjcC+P&mb)XP*ekeAyGzB`-{Aqqm$N<+2TBn6oSB zn1(1rqQmwOf%$dnfF<~3aBuB$bt>N3Q@rZu&h2L65Whb%l<5?LC^cK1O7_jZ!c;Dw zcq@46lpW5%M3mD+yWqyq_%F;FfLnut*rTrCO#4|j6*BJ5_7~BHQ&_Z1y3vFDt09~8 zG3-^P3Tw;MwB^3>N02(V1{YRCQqSK)~AQNMg-J2of5sn`z zlN;6+Ez1YlwgD3edYwyXFXl?;t2bT=QW=h_|Nnyf@CLBQ*(&$hD ze0F!;=ifONs28X^GZdoJ9HvGQcK|oUn7^0C=fk$OwU_W4aLWXtI`)#_&ZhLBGkUiL zt!Tt3%sN^Venx;o3L}WYgXu;yDQb)fNHAPXt*z}VSEO6DHZ3yM?)-3erl(-C%0&HB z)a1{Ej^e8V)(1u4K{Y2Lv#L&?^KHyyZ87t3)S}<%pml`GpCx$QItqm>X|Wv0m69&h zO{x0Y(1cFi<0)Jj+b~O*xF57T3Ibh_<^s#bpMbC`EddCtD2%{j?VqVkgdwaWh8RY> zNQd8c6178jh7Pc+h@?&s%COjZ2AKLH9-&q&t~Hws<@1!s8-&&wtA<}-FJe7_{UL<0 z#q!eR<%d-FzsW&8T@p_sl<^Z+Y!DICF@8kB62NPC21ALngRR8MLx+tFdd$}#SKn=B zRnw|I*eq$M{l0Wj6W$%G@MoM?cVG3&t_x90wIz$L1#>t(*HXiL%l`fE>BdqG%oG~h zyN@#Pmt=qv{ciYU%5T-`gN3IU9A^Vx8P~_bYSYq_A5P+%s;WFD+}a373cBoBXB-HW zXEoF>p@}j0V=bl;pj9w84b;YlACQN+D!8hgDZ)9oD-xce@$~M}1ZZGZfYB>Vy!hou z&mtFDZq2$XX8qF7I&7`Hw#dZ>J)`axE7?a2GVys&CKH3wCFrH-XX?@x|H%fMmw7Q8BMRSGzAeLC_kLUCT}u|89y;wm;} zv&OIEhi$+)AyiF}Tx=#h3`KSa=O~xQ!VG}hY!XGd!VXKxeoC~y~Fn@ zyGQu`0eX1>oT^aHwyVQG9iN2zdVGb}XEZXvn;F>0(yznsB(JQ|b4)Kf ziz24lYa`J5y<=7;ZX-J>_&TQ{X;DBzCNJ!T8EyXa<6| z{aIxAc5dVm)O_lAv4Gt9l()C(Yv;Gm1Y+?}fSslzuD2E`mPT%S!`&?=!M7w#5#-E7 zoIFpV8T#ncVF3T3iQ`4h@jdn&{Qj;MXw}ugXp?h$pcgxLs6@X#j;lFazQQD%ntyBs zh^WZdPrDz79+oL=8=LOHGayRY*v*x4^`sz_)UzIo^41d|^()S@GJh-x@s)VJU<38E zA4#@-ALnfcZ4L^)AvFDd>7wLLI(}t%Uiu8DVz76j5n~VKw+sKLj9g-4@Wkkd^Quw9 zhdSmgZ^^-73UQ*Gp$?#5HwhL4 z;6k!&S9BE;Q_2a(Xbe(9L;%_-zF+`&pZ%X^Y0dxmcgqOC>u&Or)1DtKu|txQls@BsDWrL?k3x=l&bM>@NC+yp3+@S8etuu%~;ji z6WutT6^D~4=6r^*|2WEVh@*`Xji~vL_X5%V!%6&avfH0vH?Z=}zGg$yxTPwZ1~$aS z(#fK30OJL5?9%yAY!}!QIE|qH4JiS1m7e>Uij&K3r`@{R>B`)o81uSh3t=<~6v;$| zUdptjChov@<6Q3>67~)1TEgVpGoFL3JlD&~>7w1Cb9MO-mjC9R42_ov+|wRGT7=ri z3>H+o6FO+V^W)X`!*fAacdyg2M^J4)Oj#dMsW(9DQuc&X#Tfed#6r-ro?vwxyhvwl zu9>_uT8T7~Tw@QHoVo1oUadgwY_I5(RsrF=8l4PZcr;jlWbq_6uDu?_*5Rw=P3msr z?V|u|t5jC}Voot(?;x5P5W4BDQ&Al9C1Tz^lqPBZP?XMcqNszNW-!p+C;2Loq9Jg6 z-DCth_aTN(s0-=+LH-Gq-KiDDSwCX;D1A$xIis_#a=_ts6*$j&1v@CTELT?Iq>nkkYhfejK71UCRUm_D&zaWl#`PpOpWcN)hKvPhXiX z*m)p?D^6%3?=;tFq*)mcF6(%kRpX=L2xy^_)yHh}2g86q_tQZo2J^+t%#zbRPKVjQ+nY;>IejYmm#NpT6>B9$gkaSd1Ue%(o|N#Szl<gEl-xi)}~8AOF` z#PO*#<@r4>P54K98FVagC_kcG9&xMQ5VJM)?(1gMrco-C$Hwhmeq5(A=AzdveeNan zrD7T$miA4c)RWU?RK*9Z>XVzn!~0Kb*oqV;F>;7~c|M6GwYFm)-I0K^FH;Z1Hnn_< zCPtm7>RVJc;&tx7HwGQ{P>y4qrD<{~d(&LsIr}}@&@!B_j^r40Dbg0ZzUU|seqg@h zG9UvZnM1aOsdDC|_}fc;J1>xiA6b!5=IX~pO%Rv>>JGi4xu^alv2lwuuM z5XvV5xpJsVVlT_3jsimmJ{}&A3!v;N5AIPYS~Ajqj+5iG@G?@#cy&?=&s`W~PM?}( z@WiB#<8eL^#m|L|{smhyZeAw5qj7X)u3nsk4Fl?#)+H@!Ki6Yp4L|Nlr_>B9VbE3HO~^ z-;*{iNPo3ac;4toQ03rQZfg^`ny+HOYgD;#WYqkmbZE`&E>Pgz!oG(zba@ce=8eSf z6nqLZScFW)8%uAAFn$ox1$LNSK@RymdQBkt%IDKF-UKmk2WnG6hOmMU_uY#^1QOTatpB_m0(V+C?=%YS zU)k~h&!3opJF<@3{^o>TPiGI4nON_yq3FT>O>&x?m?9ry-GVP z3O6hO^)bA-2L+d|I1wmj|3+kL_;0u8pN`Lev4$MO?c5H{dpyWA_Ucmf!ZK^T4;}2= zyIvXL1o6zR)6=y0PO6A469ULFGrYaaB*WC{Bw`ht0$EUq_29~TIrM;>_&~9U-ScIf zod@O+)^iAR{i%_g8b$oNWYL~1-Xgwjtn5ir`0BuiZ>m+N+g~3gcr$xjycKhBQIlxY zfMN=roI*mc46Gp8RBt9ZNi&n!%je&J6`N}SI0SH9l|E#VtL-BIdZ}YuHh$9w06RA3i#|dN{+r4W-A|$9}#+oIpE>xfQ zQYk7ebn*_->9QnA0-Td=aUpcUWulJ;P;^2jjXp?zkpg9~4wWTfrqQj9EQVZ8kB}9v zhKzG|k{Jx2xjNWIaZPS#u}DtlW5BKK3m5lz+R2U%%?&md)J~GId!2ae&(4e8P?F0i zFwzLabvB+RHIdF+vy8-oQmOGj(&d_ZH^1y3O!5C3C4=&?a9Dk_K0tBvp$H-c{o4c# zhY@kX+EZg=<#<^lc!I*)q9P0>rZdz4ks6B=|DBoYq$-&f{>f58Z#q2?U4f&a%UlM& zf@Q&ASN!H4mnhMJ(T_hs0sVbD)Hk}5L%YBAITwG#Q7K+5aQs|h_|)&W2s%!Q7}5V# z(?pS1Ilb;=Iys567?Cy;Lsefa>Ng(Q63NoF{+V}Ygz$87j$H=gb+48 zg?pZ@7L9(vIZ0Wwj7h$|Q3KU0ap?BFG94ol5P7UacXpDLCB;&Eme<)?I0?^a!d3#= z#Wbexq*j4&=Y+cojf7xuh{)C(W(8_g7deoOCs~`jtGUn&RABO!W6RF3Rkn$@(fnSW z4k{IF@IO6RWwU06wu14CGmEmW_Vj})*rD<_gdK%DXmDM1%%kW?C5QmkxP;;A)A(~I zl$((AyaQUYTh8+Vj_1MIEfy4uLc{d$&dnKOFTd!Xug?Ifg53FzZDr_#WwRC!&Ort* zn`o;08bXOuxyeG#9bJ&z!h-tqH4yB*P;v{SpV|hQIC2-PXDqhzUnvB4JnUr{wvpu) zF3WRq2<+=sf4tT*HmQESKU*6%4?3qlEB?J;P`#f&!topuwt#3VUu3|+5cB;MpMhY` z?TJq?!d6kH7G9;_$qh)GsD}xP<-cg zh0=YlllV;d%8Ddk{-*GS#P0NsTnOBpL@>jVUy{DM&O~|jO|39FerEumA1D(qDWW)U z4jhv9sCYre30X>MU|c0~q{Ng`BmD?2V~Iix*RVuE|LYq}BpTlB*>ng#U21(VMSROt$X z60E4lcMQ7PUX=LQrWN(IF~gj%n>;F5GcnOp38WcECt3+lF7FsxpH}|zpKxd$ZoB;P z4g1K$Az5nayd)zuogdcID0KIlUd6`L_4LKSg?-jVrIRjm90p!z?;v#LEUY_Ju}J zW5eD7s)7ZMTRju;ZhOx@7V~>03`ndTQtNW`Kl(2+}OXTk%yMJ*mU~?z+F)L9=U3MHBzWK`xs)uF15=*fAa*sx+SAJ^DH`zfv zD^LC)M4rRxN8j{VQ{&d15O%D0&CEUcWxbsg4ufg_SL}h=Y{tnq6X*x~Q{;uftvY<% zF)h7*-D6?$8+*pn-Nwbl(vn)k^b8LJ!@a@9HOL1vMlX)`!e0J9u-UC+w1KCR}K)a%7#ibX8! z;D4!|dOlF(>?NerGI7Awtgt3qB=e4^K5&kmxlWete)=OXXVeBBhHcAqc(YQ@m07o| zZOTWif?b~LI1~Bk3rGzkeF2n(J|?PR<+8N5)3b3L;Xn;K?T(q*O+d-SIVQG7>-KRY z3)z^z)^l1o!fKK(I0xQ2eA}29iKwY(k`DdOPvpsSBoDM-^_zjtel6g?hH1OL;Nffj2j~l7 z*i{{BG(KkitZIBKY+;y9Y^jlmR@XU^keaZGMqN1rR^Gq>H&{l&*9gG>Cw8VG8qd$p z=JeXoKYi$8s3fV?UF7#h{~sVNFHCyc^;En>+hy&kBdexxffjLa$#)hOjgLf{X0Z!r zU9o)vC{1$k@}_|^p3DE`CVT_5 z4UC{z)Lg1;9OsJ?qUfsB*hW>YXu<=6W5A;H%zfsZY2X==$RqB5g@|4t|#G3C9Q z!t6f2CRqbK_|X{;G0LDFL`@TW2A)D`$u~RG36o=~&TpR7x1Ws9;obI~n}eWij^XVxd*Oy8Y5fR2@(5+LZ+$O)hO46XRTaWBSj!`WiB32JEHLC&Z=2ZLaBZdq zxi~_G5plh5PDohS=gIqO*;B4Q=o)boEE)aIUxdKekqo8SqLS|7jeW%J-brZG06s128w@o5dfNT%9w)>nG{->#Mo>LU_6; zP#BHR$hTt}NF7GnwRUSCo+kBaDAq`jk=7(Z**BZ&`bMa@d^5gMr_$Qom<2a0c` zYFgxrIZ@mW7lj(n$$l@fF43*efV{kS(~|!Ea(HWq&G74{w=j0ng8ZarKqg2^{QRs6 zrzo8gir|D8j^9b-EZC-`4I0f!H>J(DWui4mfR3dpQsSWa{qQ8Rp0xx*+jla(CsHo{ z$=CR|L%XjopfhB;LcfmUX0u`r3I>t{MLhZn95Wtn&Wop8pN$I~qPRB={Ltm3R4jRu zWPde>8lyt}>64B?8M%#5-8`dQQ*A?4?9Y@b=;`cgvc@(JX+XcQcmya+-?-;{PeEAt z#F+NS9nlKMmZ$f~Q+#*rx%|o)fE^OB{0GQ(X-<~EB9J^g6jgjxX_<;TPRRY(P*knZ z9>Pz$?qJoow4{= zFd&W;xo88c3ftgSB?;3~Gp4l`rz25uUbzx^UNCAJ^r)+cI+NUu{x8I{;7>$dpcoy2#6pP)H>S>R^ zwGyI)^uj@yn7Qb%K%jR2=oN{y@7OcKRjzxfIn5H3}i;DH86p(8v@jHv~K~xs;|_8 zkoFFMX!`JrgSlnu4C!(4tGc7qT#LG3F+Ls7wa2jH4^X&i@$(d~+WJL_{O_q-fUtw= ziT@tjq_ua+@4v5JS*&%~a(3KBDt~(4Q4q8FSx6#i%@?wB@6X^9z2q#xG2m)%B32XBJ#gl z@$Du>da{EAE6d-b{+`~Ha5jb5OH2oyb3ZX{3w6ik8~jO_Yqqc;AjhQic&-nUz{@>6 zeiiMw_y_bK$OIaz;AYKyuQpkL>1c45|2~>J05dvN=Pg#pj(?D@kJqIttV@^jhsSgR z)cW zikehVd3y8-^3iD*i5sq5=s9VhZ>tH(s$kAHzVCC6wCFoAi0rxVP*5>ml! zXahj0dves^xMqSetydkRztVvIT^aN)g#9NLO$$V;emR)#^tGGW%{I$Jl+VFmU6jA# z27h)_=**Cu@X+i!;@qB|$?>m;2u|~5fddS+Uwr_Ag&yB9E8pv8P=}EWq0f2Y-cNzIVE6|8hieVWUWK4$to2gWj z!1J(oJ5-{7_f*RRCF3(r&xba^ilVfdiKg@?xwZ))*A4+&buxvpw2?X`nuhLQL(kGF zC*c|@fEhCLfdKfzfty62;KDxH%0mAGAOFwH^OR#Z0`v96$7dybdP&6+lSyzl`>3GA z=qRf#>~T+OY6}kp=Ra}^2oodK&j!Da-I|iz15YvQ;(DdumgcHqjR*^%bnJI|#Gb60 z-OEfIT;4bkh`a{WV`#vgv$j|M=2c?;SO41`p&?1JOjbR~`QpL}AmX=|P80d6;dkrE zlip{EbaoZhUNd`L*{CSPI%9WKHu(#tiwkCZl!^BXbRT@1W=V7O8?K+)25Z97Q`1#J zz^b|n*YsB34^z1{X(yp?dNPF+7Q_iM~mjH_Ts~~9SGE)4)oUH9#jY?$;<@OdMl5ky0 z(`4A?f%HVK3>uV|b_n(}-DO!AAw6u57pg#SMUDNsURe4)Kzv(c)NPn*tt@D(qDFta z#ZMlRti*9z5v|VQ;>719iZ@dxUoy0aH+5?=cJ6Jc>6#ZF^i2Pe5fY)Zvc zE{cu3IoCD1-s!Qa$@6D?@hnR4l2uMu^(!S(8aH{&wH_DP#_^uFE-D5jaSf=7`;p8w zS3Q~ch0vUYSvP~M3h#vmA(Uz84{r|h;{`PBkJ3Tv2ro|i5O?OOb+5tuRggSCaJG1? zO9d+x-hrzp5!EwX;xcQGR3!xz#hYrh8?fe|T}wXT3E@zq9Dma@MXPB*+FrqKA%+nL z=$a&YYz#B?*SvLN`lb3-392A>H$4_4rheNvQ~<)R%JvQ;tJth7U)D*_GrRc` z#D3I$UbfPLrdYN3G=f`T*elB#j6MABvVXlPyLQTWot|46bmVTt(puHcLA3XrXucmB zA~P=82V`pss=uiO^DQrDs_dsaNY4kcN*=tu>{ViEV3}*)?!7c+fOnhXWyrL}_+A}A z9USJwJSF9JWe6?Eg`a(T+nP*gI5}~rg4ZS#P$R*&rc>K85thKyO&Dge5QFK|h3*pp zI#XsJ5|>!@l_J?s=WLiLJ(p!}t>YlLrVRSUM*oT)RD!7s27E=|4#m1}E`yF8kGNOM z^&RX=xr{!xz6sc*X^Vt#qo2xT;w?p>10z5Yum~F})M8!OGd9w{n&HqqTTyUQvGY6d zhCQSHPp-FAVVd;l7>uoa&MCeCZRo!To*H1uYB{pP+ zM=<9+Tb}DFICkx;0g7$L_|XkC9axv)d*h`AZx?~-+Cm$#>JpXS%mC5z4)OC+{tn8m z%ErUS{W>COvngY>-^*SRe6oYm?#|XFZTaO-#h0SFH&;!)Wc!{xA=3&G`UE1~4*zm$ zU29+(VZ^?}2&RoF#~2@5FnVl!gu&C~k$S#X+4t#;^kg$Hu(pyj@!NG$&j)8F?)utI zCr`8_@$DAZHk^;D1&jJd)=SU63>1P>J*VpMT%i}m-XM_?kCz@9?YCoI_BG1{cOt)X zDCg%w(>*4*0Z%b>qofjtkw99UbzldWeSATSKgPl7xcVmD8~pf(p665k<|^fS_P_(z z0IYU$)as`Sa&%td&6~p4@G2br=Uhy9k{*PjEqOyaBd zyplXxTJCaRx?WR4eLR{^~9yKMdP<-VGPzO4_kHp2^S=qry`Qf}w!J+9A%867>ajI@` z%I0t++Z1!NYhKzDqwf*d@(gdf*0aQvwwD4pY$ZXX=eWv#GIE=VlYK(?=AKNnp0^!} z=(pzx1f#BI>5l-AP|C$AiqjjG4y=1m$xj@DkJF*L-6q;T9tt%ET8H28!wvGp=e z$pB!^J`xbb(ruSZu>T@N{TmSVFJbY&Cb=;EsWM{dg+Mpn`~qIli+>N&1sb|m4|1w> z56wV1Kl;da6sC2FfUWe=Ve9=P0?GxgH=~BY1r0A^a|cS&uwOST8QQ;M+h|<3lSw6g zy^)%s+_HK$c>uOvdNLVgk*Br{@o4CkUkVSr{b zu`?sD*`zHTvtMBTrYRISw554@u{CRMaT?BB<(4c< z%F!l|?yt}SviW5Yx6d<#7|IKqu|wy`KWYlVX1zrD^57p*y#xAQ4ERA!E!ck*%7l4>~*hNSkd|SRDcjvyn1Uv%01;CWO!H0ns0OOVwss+rn z@>ssJjs54JpvFdvi%Er@>1S7@ah|iY7aW&Z#t}sdSTQ=$b;{7+Lz1Uhkk8vJrt~s! z4|677+Y>DsFSeh^)tmd&amQStf#={T;lP>@WpLM@aN;Zt((y!xrS8|+P^3|D&|4BQ zj(1L23o>)Q9^0g{+9zDaHb`!zNdY(9ER~OrWp9^?FTC$+Wf=nHWkV>?#G|HN?_t1g zKo$?MLir!IT}`r%m4T#?8ny~jXFr!??}7oG@RyH9tI<~7fy*7^wt|;8CGfbPDZyOL z(%EbUtKX!$c9-ftKFivRvu*4PJD&)lQP;7aFzmdYnj`Oc{H-m#fhoQhVh#^iLZO0X zoD)fE=b92JA~A9#f;{e^8*Cuezh%e`YZ7UrS>`!Qx!fW9WmO^x!khXpk5~s_m0$_- zON1ea_0OO>F|_mVKD}~rs3o+-x^|8xil1bnG&|(Ty6@)O$D{c0OEkw;h~Ga1nFeWE z$eKFJ0^m-rE&Fb^FB+1cGfaI^3k$ka!an!`=eaa?tx`PN?h2aaV%jvl>7&x57!v?R^|?jp^uv5C&AVhJm2k4 zb>*FD^(x^VFq_lH0DZVqeoRp(n*tQ4$mF6Zu9u?;Y|4F_Z;9;#^VGqaFGBR^_A6he zK(FRPhwbYyS31oAk3eq`ggVw0cGuJr<*%HUlcjVpb5-aFl;5z>nX98dHMS-70X(lM zjVbf#zb-c@#)4VJwkiJE1v6KlyF7uZF9J)JU#4`!h4uUCn&L$R@%$ZJQ;w`N@witn zVx9A%KkVOv&(cJ1c2q3$8mKZg0{98Ap6Ev%(y%$=+IW(g3L~R8YC~ALwrZ`J**~!o z1k6Z0K*eNjxa0buWP=sBle2jxpIPtB7HgnzAE!q~BT&}&#v zf}SU%Imk(7J*H;D%b;erdbhM$nut9zd`ZzBs%LX6z;e{9@3(cN-r}GsP2qz;v}`^^ z1DOEr&dcaOGXbeGycC!*->aooDS+9lm;elHg$cT<<0!SknFaJv0N&58_+%U4YW>TC ziuNxHYLOnm=FZ={VX8HB&#jL30!CPq0wb)y{%eHwFI`>4Uo+T=|2>%u*APh3{+XtI z!V1fbVG!LCms?#V!pGUG?8)9m_9waWi5h0Iy(D@pyfOv9V-&@_2LZ8D^w>Mrf6OVK z%*2BiilR`{MDuqwGNpu6mSyiAR4lP&3KqPKWg!04hsKmq2!<0pMWHbr!P`l&r5tRH z&9Ch9Dhim(dLkaChDnW+;Ggp!Z!relU1I+KFoka! zpux7lVf>fH7iJwxLioiCA_MyL-6mU{?(Eg}+5cnC)d7sV(yXf)*Q5f_8zi8|NRt*D z5MDvlLYN|002>|&8-uML${V}@(A^WzG%QZz70h6X5q7+&0R4wPp${bh`^mmK$zI%r zF$u}9J=Rr-64p3ngMFUg35|j*UhkOD);p$dy*QgY{iF)&C2~!)LH$umEUC zT8vDQqB}Q_4qKv21bLT+y_slTrM{~5=rDnJuvkt?Mu@%URgv7G+|}H;*l8+S6Yn8! zUezQL@vK9{s#u?764`S4%*&6u+dmguRM#5a{`^|SZSpW8?1&Uk9F9{Wgx}03hD`s0 zGU=sa+&Fo7j%_b3d!LnODv{Rp^05-nV^FAu5QX}OBoq@Sq4 zOkX~HbzS+2^o`6pt6xXJAigCVACe?3Ip|jV6wp6MEbU?6Pp_SQk++X(RxO%zbgE2QB;b*)pzeyn*@!)O}oF z_H*;mAcg*yA-=*7BjW4ey)(cX?ZvNI`!HiPtk!4JfW*Bb9P)O~Qz7BuHscbHVlw~D z0yA-lTpdb#etq--Nn2J>{7n5ha-9{6{)kG08X40v>`R7)tUYQt z$TP+`zdo>cv&h>$os9_^#SUHQMCoJ3(ZIWi!V(~?oz`{_HH7ZIa$6?98do{_0ApU< zzpi^O1o0LAY4NpSp#31b&>=treXb|%fUn0jhn`r8Zk7oxpvZrH{XS5gHp*Yu7W$^|k`c8r_LIJv{iTFQ>^NQ;P5Lb1{hUSF$9ijr2S@3tAh~ z1^T4DRL>SkfbjVm_S@`UKk9giO!&EH&LVB_D;>n5n;o!}(3Hz06@0ryX-W-)Nk8#6~d| z(kaLDG%8y&_sDs03ylfmWH67<(NQIO*u7jjCW;3NMB@Vyg~kL5S&yzswL2f!)Cp?N zb9*6+Eskd0mtRXPX*mPN`T)urOj8*f|Z5Gf&Hap#G2 zf$9+guIx2jUzJ;_#CsSMt0i|lOELjWxR3m&XbK1p8(pM*#TFVaZk)m~MJ7nbXWLl& z-RPh;uAhXjjN@QCSaW|^yBwL6h1X`2?FE;87)ZYon%R!nF_z_L9Z;QrQ*55em|+N- zhZC5hFhWIyH%C9HB9+!&5G0^6+H&CG;WI8FtZ(+@zUwRa;uSfJ&4E*E)13OeG@Dqg zSVXoE+;__0v=)vU%)uK4Dd#gM{)ZE(rQAs--`n`?`38;s)+0G#-fn0R?T;CHADj$j zP@B20W5KMPr|rRsGGA2xoA^{Wdddpb7=Z|Z7%2F07-~^LJID<+?Z5qPuC$!vxy{yG z+~9_@MT{|_1f;#Cb#7w)JlynUj2Cr+oZI=&{hOGUoV{A0Pi?;EBP+k_{;0sLTK@Wx zi6;+Eiww{e6+nTXjA&;7jouez55D(&V%H4grKM(WBag8!2R2sg-q!t4Fof2u9f}V- zrGylg8SgI9RtF?!S0%5;Z*ia|xn0+OYS&zt@(e||M@w$^__NyM>1Swr<r+0yii}oJq$Ic-}1!p$rxU>*s)kj}tT^%J|6DR^K>DOa|J_HDd)kxTG zuSR;sjA%ADs?zEB7K{83>fSOauJv2@?Zz5{6Ck(*2m}cU?h=B9pusg*u;4UKCLw{~ z*1aj^)2Akwt#wAb0WZEB+m^3l;gJ)dz9bM`UHQ&lUxvg<1 z4<|tf+jlwoc`u<;#P&KIF||%FiC45L>?5odr%*L|CaQUi8Ef;UG)S*kW^leMK}HGd z9+#4kW^+Wrj15w{`de=Q22wxga+XZ&6M-jzEPH{6!zR&Bq1_T>bx zAiJvJ*-v9lJqMX3vI?AP!S=P4LdjK*Cz~20h3O||5js^~No?t`I64(9r8?ZoO|r9e z7@};G=HWz&eJ3fBD)HTGX`V4_ek&_92VXr$v{*rgbrq~fRe7kWh@efH*VUYybfwkY zbAsw<5C~(L2m}J+U+$&D*FV`ejvW*(ft1FRhhJ#+s)AJaTUF5QtF38IId{Y_j=>>g z_{jNy)SdsWEEu&35)+Y&XatyouqFi6#>3|@0rcCAq8x53e$5fRIi7NPp2$cT;vpW% z^yU*`Em`n={T~I_zt>wux_>8Bjf4Gmsf)({)xJ6ImjVO^6H}mjn@ha{qTDl!tKG$lokaP6xfjH66)lYusiMT)G z$nHp-f)lPH0f2R{n5O`{iDlc3G;+XXBrvQor0!n$N7xwZaekt*f2HWXg%wPY|^P|Q{ZqWef@F420j ztPL55?NY#P=CzvFDcXq$QKY8iZn*jt$ws}~;eHhGD8>BEBteqi19=Y9o~u~pdi66j z4N7Gccf+372({`FTa!k_`|U5(J?``k7if1b(1_(lPR+}>lHEzAk~guD+qR`0-Bn=W&Vh#4VHJyuSj08PI zgn4BZwL1m)KHMXsbgd7!LTz&k>F8h<^ZuI`FMs-mTY~5XPnxY?y7RQ@FTe=90`UKfxlGaLTOF7a;Fp9C%sj@axY&? z*H#6P!)*-}ylmic59!%MYAc|F6VPy24lA|~pg#%+`cv@r6Tk0RjIA}7H&lPfz%N}M z8Ln{R$|CR}h7MPU(4M1Mg)p$mgp}K_=)fK-7w=o!KKiaeNr0$t`Vl@lxI2;(t|aP5r(J^FsANrYK9^ z&BiYFKDK<(;Pe{meui2hY{^M)7H~eg54;@VIPFUx&9%u}*xwKha0_zsF7-g- ziJ1rvQF9v%Kr9TmRR_MNh)rX9*S1z0g9+9t@0V{dNgl+IA|oH~i<8u-PpS*9?yIDG%^NkA_K^lV8>nZcVLJg@Py5oPZ(f0uW{dlQT)4XGAM z6?$8=0CbjUMW|5e8Ibtxju>S*0Y7thn!m&u9q~_~2W||G#42RYtnEbI!f=2khPrg@ zE88CziSHip^DVxO)tED0Y_Rim{xD0OKk+xT#lLS8|EyZTpS-kxEL#%=66pWPtehw; z`dbS`g33FtnVFWPlI%=yxq7VFw244lPfm}GqL@Z=iJN)`l}z6gVc-+cg!>y32oIyC zk1`)a!;mKnE7|yF9FfDutuuOH_nzKePc;DLJk|j)EIjsm>Oc83^=400l-UD?10 zb}7XA{XmJl=NjwS&K(Hye>-U9(>0w(!+U$N_TyH<@M zbi^eu*N;O_UQfPg{avM@H`Mb2=^*=R>2yy5AdkqNzLZ+w3$ppD+hcA~s539^Y>PQd zZmD5FYp*!X&OJxbe`&Om@Z^Sfc@f_-vcs9TD8KL95W_NuN`b6ZqZYni-2`;<#eP0To{aH#E44M5}R(U|s^X)Q1Yc##aHqqis z`P}|5U0DNAiH=HsH93G#I4lE5VjMv*fngemYv(t*q5_*0TC~T!+aMf#6%KZ3+ayR9 z|HkRfzoQ>!zfs5%OYk0J$J@Hj@CmO9(gRkKLnjE~}*v@K|%yt5m_T z3(C;GeBX-HF4*&+&@qeY?_&?UNSQv?zM72rYcWCiM6v!i#GFz0>pS_yAmHZ%=iiX8 ziE;m^c6Kw;@db`3s%k!YKPci7*0a*mjN_M9FOz#EO@1iYet>q3s%mJhX~=doG+SvC zf56U@Lb3g}{?mTMK%Cul2ObtOE7_&wRSwWY@uI<0TKZJ=g9HuR;klqU;~m9Bl~wbM zY4P^qOozuq$U8>z$C#(GF!KF=#AJ;(?n)T!)e(Q72sceO&H&Ttm49W_T3FGEJf$ZW ziCvS-vxO$HV91F*>h6_z$a^}Q`gQ+PHU62*%4%OTIpeS(D{WWwSqO~-mn`o#k18NR zWfUa7mgi1;J0SHNBF*H|U#QJjd&N=!ajQg>;TM#|t=B-geaRMpHG|83}XlZl)OZ zhNrt%Tx()fw~P)H=5ZO&d+_%FEQU)$<)u5K0=)L!Vobwl%GB;&9YoeoJ2=8KaBn-r zWCvmUCPtbjJ3bJa%aT`Led+7#YsxBPclIrpYWx-Y*h5KFW!2=j^|JtC5%zWJV*7`c zQGVH{liW-V_s1^$U03IhG~Pe z$gX9r$;uhqIRo^DV3HR-bOCg!++(A@oHj!HpKX0iGpyrS5H`@&8Zd!44q|493c2YZ zXJ9;1ejsEK5T`U|mMY2gvztYy%{5UCJNgIgwV#utp+&(q(muT82HUQ*&)mi>(?B#2 zPiHSsJMzEMQqHc*z^0wTu#{93csUu?bc`2q9mMzY4*}O}!&jKCBuI>+ zvZbLS+G{Fy^fk_%QkqC`xRBrXPn!E-#a5~GW3iy3r7?VGCdgnrl?;wXBY93ov3^Gb z^vZU(oIf1^zq_k>H$2~9U1{W!mKnB*l!Cb$*9F3CW~<}HSio62-f=L?U&BqDzuzZy zxq}j6q{oa-QOA{m29g($&^wcgD*InpmPThci(pQR<=|Uws@d-7m$2{Ug3`=$zK*{r zAcNOpEg%f%?IDK#3sf+FAlWlmm~yv3=S##F$#)|JK7COYR~q(}HsJRX2W&PQGyjH= z7w|b*Kl#a7WNWM<_8PtarThg3Z_lp81CW#fvi?ETc!@FqM#fQ=+~VDvC@hHhMR5u$ z%#Z59q2bb>VaV5tsy&m%jw{^r68I0k$jZX>rE1tc(Y{t%UC7ASG7+{Fo+Gi4^MmrH z0$x*4nUtap}e%2@TaUf6)>VTY(w=+SU+X<_8J1N#d7sjcj~z=59iI z*`tQC4h&I)#BvYNB}L54P$j5~Nc!D}dJ>iW_DG78hMEvG8p(>+-Ds=N_ubNhVf03}^e{8kHM3+9=9gIiQ+#H|pT4A9r;!3i;an>Y0G1Im;;N zAU>2h5wf#Yh-=jK)T$bsbR1Gv6wG(n+L4^!6k|Wwa=(X_?i+-2GsQVgYN%MyJ8RH>q@x9NC$tZP+E!~?`q*RJfZy1lA5SwzN z=o0ya*m$@J`Pk!(^cCQwun$oMnUf|Hc$vA?8Sgk;`iLc=iX8p_{v6MA%QP#m4 z0QTVq5UX);wW{w0ZQZ~M{lI8sB?r=gs;Jv-I1M*?s?Z7%i70qMTqT) zzWSZO_^H1_1mUIH!K<PjXdo5ElZkPYXJwCN=;3dJY(I!ptaOcU07Za3B; zbQ>4MBPv9#If(R7Q)qa+!UqPB3(3@?Yg7}-wq&H^^(#;Dq!_Fz@~f9OTDDALdjONq z(+sj!N~V&2pyzf`qbX+QgqYvc*G1~fmKGhc9e2C>w4&@o>r>;48|07NKA+8YSB_SB z={5LEG05Iu^G8DgxWt7ZRev8*z=x;!OXNzoM_#rCXRj9!1ZyuT(@F?3PdjU+b@FA9 zWmo6yLy;{rHK>lKK;J9;ZeQNKLJpdh<3V}$DyxehBiLC{5o7`<54J*qM@BD0x;Zve5PZ z%aJ&PvVaxsXKoCgv-)l3Jo$LsVZEO$q85BP3>I~*4ueYU)Y7X1tA|hI2<~qq7C)-D zEI$HgrhM7!3Lqjjvu4idgTkY}KI>bSub@|JlS50xf;oPIV+r(*yd_%YA zsWI748cc~tr95B(VRR1A;?u5s9s_FH zbaUcFv)lKg`5GkmG3nL_93-hRi&alK9@zk;`rgVdaSGjI@8D#ppj7~#jp{*Ne_FhX zD6pXeP}l(2taT#OdU2gGiskvJ?yN*j)R*aHSwX>7%L7&Gdi#%XfOOmNk&jb1ht#V< z3bxuZ)?{DW)Q`;6LQ|l+7YjG;=5V~_PzNmDyLX=>H`w~M?b3Y?e}pjF`td&|hozZH z&^Wn>l5!}kHI!b4iKQm`_ZujpSFM*C{Dc6Eq-vhfUz!)6l|OlNTd9>$lJNt zXCEV5oIfD`P(*ow{B7F%CARP|CYL-BSz4s+SH0{M#ZFeVcsd-?SND4kCv)2^Hj~jBL^5i&(AEesj(gyG_M94E}Der>QYR;=re7s=mijH@w2n zOg3FpTqPMd1!jXG9i_Fy#f_pX*Lzk>_ITEJbjQnyPl%lYnQ^21PaX(26)5W(5niGy zf7blmgU)I zwqYE9b)lEv^_5>;s1H-nD6guo9NlQ*tErES7Jg0;t)s<^=9m7V7go}wGG4`juRXS2 zHqODBTNOvSYRk8Y>qq9Itb!|5sDJ6)Nor&|;c`8jhYC}X~D-3b$Qq4b%)TzeoE%H>j2737iD41`2wcoqFByC3*%!1X=S}f0)3OFe`-eGDU;T2?A)~pT~;aJs>*1Yue z7+}!L6F>jXEG|<5E{>lN%3#acGvW^0PW&=B!_;kgp6mE(|9kr}Wym&K4cDUt=LBsR z=Cup)6o|teI`^MR$f?a&gBu1A)7yCw+50906zVV#o|Pz84_6ilpEp;R1+e9uV7~$i z0_>lC6jSz !8NbxWlgJ2)sQV&|lb#yaG~Btbqy0Vh zXx9H^pPavXg^LinDnJ+QJnrBnFZKb*)E_+2w<0C_zRAHD+xw$uE^5F;Im5DEGn;2h zhzYTM0acD?pYU(^;D?FoPlp=SDhQfX#u7QS6hr5_ydGsz;Eqa)SQd9QcS~f7byA)7 z?&_8*Qx7z15mawwOKf%2GSE#ucC=kis?}YT8FfjTt-~0%v^8~KVZKc9ZAAr&g;M>h ziW-^IXOSIPBd5P`Ebn_EGv2m#%l9z;L4Z;bNZF!D*%L_<;jlaAX{i2$y^Q{MiPKkK z)*V*>DWtI;k+6Q71N;1*yT&Oh*=<)tYzXYq4J#{xS*_k_H=b3Xyv$VUqn?m=vt~wa z{%!d#eW5|P_b)DBiUkj=54CiaxroAyVrHB-B{3kC%<#$aJN*E$7a|dh4$nS>d!TJ5 z<8uCS$cRCcawLmVq;zKTtd{*(4jy&&nyyLp-d>=Rk!?mQd9;rH%XXe8?H86!%h^rK zl`^jNaD|xfcPQ|72m}1JWAO$G1*C$0=fO!*PGA1ENZFLW?LqgprOoiv@?!Bd8}Osv z?cN2IkbWRi?Y~X~7`k~4?#nsv7Qtzula|VF$T9CCFcnsF_gVB&QI@t%qSv&wYoD|A z8fjQx8{L}A1wah_c=YIMa%lOkJdV9#-_~#e^Qtns7MUTd<|Mf~T5+Sybo<$tC+wb} zuBh^BKBQ4RK8ub-R13P+Mm5g?)Ll!ySz(p~Z&EmKP)#j+20w333BR@|sfcgzd}VZH z13g+#9;cMs;^LhoIqe4?NHrQeQV+a3* z=X`Zj#*VykejBtJ5TfOKyu#678tV6S&JW-D)u=arfq0;3Xu6jLOE-dE5Z1nrrqbasa z3LkTA-hzGCx;V{Akxbsb7xkDgWW>+Bh+V0VJxGw?X+DWjO!0CUDK;KG$~6}eG7GSA ze^-h;|Jenf0~lB9#l7H2?ak5`_Jv*XtH zzJaqIz5EzIucRJvc-mX6U@!@1X=GRqQDCbH_zlrboE#}WBwx`~JQf&2FU=+2x5gJ& zIcy19AD-2023pFSM|10|z4}o5(MC)i@E}ZbZ#=eSsVz|}g*3`WTFR@V?C1$XX(UiV zZA`O|71B0vtWa(72Ujio@yiYjS@4~_mFETR#odGh>6b=I@$)-EU3;IL2TeNSBTKlx zcZQ{>ePd4NRelxn`sl8paABy}TGuYh)QibKr8)R4QC5CQ|Yu#UF zyM3*Eq*Sy_t$C#=^)s@^&D`TDjZN#CU%4ryytLbE%2tBBzB_`n%$`b_ty48(Fy&>W z#?;n#xtj=U10%Tz&B}08wpP=31wCyLzd~4!M!c7WXhC@GM5D@kmMy-i0+N6z2YVtm z?e&Ed0COyek--;F@}7{}M$Ns&kL&^C4^&PsObs&k9eriT{KUT0!=tT`-lTzD zpKSa#3u@GQ=8_R-#WX{jM=utMe{xi51otSVcCRm$1{-Xyn?cu%+e}j-OZZM!Bkol^ zM)xmA&h!d`Y>SGE=qsvTHB>a!r#)fZ|IwNJ9$=pI6-5bNs=8IyobuMly3|sxtsjZ? zA{~cg#aSSU=-Nnm8Jr48MZh?h2zO3~@kaC&YCO5KBH7m?ReGIc`y6NFjhn$*uznXO zE({q=5$9hJPbLrzMRoh>>g*sj%qOQqgeZP3aJqMTAJ2O^Qr%DB;FW@pp5*YV%tYmH z6G(-QL|K5XXg@(Zbkt71b$dLq=G$*bXZ00_fqMuFW!rDatCQoF8??0R^`ue6ofJj0 z(DbzUGW+VUPvAlsam@n-6m6!)-uOtH=vC|YmZ6Zy@A)Y!f7>Yflb;R##T7!KRDfm? zf>=QtK^YLj}E!Az0Y=%roQrTAvjC$eKywr4ldZ>Y)>*@S$&f3o~;(1 zTPteAuhh&}s*kkhhVuHYZ#YMAJ#p;?#37OwulFP{;WG>kRW)fcV-#C9r!AkKL^^xefM<7<1|~Lbo$VL4q$q=w3?X_ zD|MfZQprr?UU;mG6=iWy(Y8oa#;?i6A8&f_Rkq)8iIrtVeE8^h}l%Z$Cl*+qr zER{^Nkxe8L-lw? zl1`5{GjBY}ovgRMLZ1I2B`$_39=V0Uv+C={MEG+DtkB1+m-_PJ=YPCYKPvqIW@Y!9EnE)b%uU3g9p%_ zuysZU6AEN8YhUPmDpMwP(4m43A4-xFL&sDNy}r8lbPJsaJ;Nw7T{aNYlmAGpyvGs! zRFhTqv9A;UYXggb8%f(018QDu%e7AjmN|Z^p97=?%#3#sa?UJ>!^CGOsBDO~ak99= zd(e--dQvCf{maiv_5Su*pQh(*%}bN_aSjQz*4Ey@sa(#8|9p-9Hi3)2x*K{`Wm9ln z%fT`33$miZFqAOl1@c{|qKw=V@3dp#suu5R6Jdd%bT}C`-1D^9Yb8J6P+k-At+^5n z#Kbp)bQ5-O#dK>oltr)~1kBbAJ!JE$T{FEzQPdrW8;Hx*JfMgo9gbyA90R0IpXhmzXwfY4F?3DidGy20uxS&C zGqU_U4KS^uQR7i1Ptr9TB`&L%CHhZ8^@^b<+@D1Dpb~vM$|PIrDzIpGwhoHi4;jGW zU4{kdywZ)S)I`o_ny&?@V9A3^^I8V#*VS+~z4n?Kq;l|ClNcx7E>@PIe!mZO=P+yF z1_Kw}uW*gvb!8Yws9TBjS6=~qv>~r=mle8`a06`hvEuzqxr_%-{lf(q#91*070OI{ zLh(N4CH(JiV?HW3jCF)9am#+^%^h|CE-sg2xQSM+tvjKm6NLn9@mi z>f7j^bAd}Oy~K;3 zGL*9}HDt#I<)-Y)L<~90-I$^>){B7$oNy!Rt;zeBURt&cO7-Epdn&EuOtoyE822ev z`9VKgRH!2Yd^<5*>x!l?-DGPgc*$S64ny=%**lZbRp+85P#5ZgZs3K}Gu7YnE}7M; zM+xksfyx&r(zF*y0w)L+5EU)Wy^?UuQv_3qzi(_@tgF9}Y{pI(ReOzL&iiepVcv=Q zaTPAP-#Llgu?}%Bmq;l%g?^V7|9T^XWajVY!4@*FAAztpmL)dp@~YaXw|# zHWt<`K}Uqi5GjjM%JVN{#70h5qnp=9VYdiagOS4b4Us~$gyF_wc_EqKLJ#_Ur8W3cGUr??T`>Z;8j zR|;~Yk$ZM#V|El+lfWYeJj_S@)ZI&XLgw$Q28T+v$8ID>!ZVhA-uA0=*FHb?0i5ZL>Ie;^|-wgd9{L2xk9 z)@1e7my^ZrD63GSqd@UGMil7k$Y*8U{)$V)((ZL{5#14b29Wx?n%C*I<0-l?d5O@} zX7Fx1Ey)wQDDwclcp84G$nPeBe)u_TV~rZQ(>w1m#*3=RGQI4}go#%72|fkTd@>b0 zPsj5s|0jhj-w>stuK5t-1Kj<`6p{9e!GVcp)e~ChsiT5_=5nZ@0tY{zY>so3yenSv z(>95I_{jHrAyvlDT|besUt|A^-K6yl=l#y9m2>w;h@Y<0md4K@{6pQ?{GuL1%R1r& zRl;H7?aq4IX_xUkPEXR_az`w@blns!Z3y=%@c8FlW2Jj^$Ht==;P@J=XTgbGk7D}H zlvP;@)BrTS9P6aP7o(iwWUq|pnaAOX>Cn;dV@R^%%V4MAMMDkPoh;r(CNJEZsyeM8 zzgw)Oxb_j}lWThtc#d;z>$+?V51881 zSI`%QbmK=$v_8HC7TdvD74f#_9mV12kChW}LY-aBd&kdO83oxlcbt?bi*6JqD|Z($ z47MhLs+&Q$t^)ul+x9la%6pLx4!~}P%xFlV%ql~%ARE>p3ipD zlDar&4^jWn1-&W@ir5&^Tzl%zJHi$p3lwLn9X5X`Gyn}TGNp~lEXrJ7a95-dPShAe zi=C$*mv!;y6+EUYnS3bDo~XO-td$sQ{qF;N6p*d4JXw&d17^AEfg>ag1I@$ISaUU4 zBH$s&yG8Qp4(qV62G^1KGf!N?bc66rx5BeEL{uNxJ!qfgTVS=PG$i53ve6Q^_;A!2 z9EFLLK4%sXn@Gwqn7d3o>3C1s^eboBU~@vYF!EV2ZSm>}h!wDzco-~TqWx7moQG0_ z_zlY`O2O>*q-ISVzw3FVw6lx)+{-B6Q6L745?x!OIfeG<8X{+I45z{-emun(<9ME6 zhMksh^)~5z79jA}8(SOQ2;abER!-V;Zf}be$$s8b>)5c)OfqIIMtXQx0zWTOkRIFL z=kq_YsL^_d_mNR!ms+Stp_=r{C#5M1ve{n~WU7A)>4G@4;P4i)b}R?PoDaMl1m-%U zc<{v%imWrpIp78+E5}m~ZIN>F(4A;?D!zQP4W#w2*)2{aZd=UtMS9~{lgLZv2`7Im?+tT!BYU&#dm3l9#--k zlVKWkurVTGw=kZ?8|;W1OVCZbeq+8mK--om+1LuVgP!=m5cjf(v(b^R59vZeuo(5Z)o>nz^8)vduW}!;# zI=R0XSqFJJ&j$|)WR82*d%t5pa;{vBikc$6LSVN_0qTi7Y47T4t0zi|-jA-xGXxp4 z)jrITxtu;#UHBJ2@4s7q{~O2e|Nb+8|JgSDzkibdgL8nYlmF7c{Qt!Z0sg~D{r~z4 zsk24BGq=Bnw%pBXPJVXgIQV=z`wf`&9@Fh&4D;pcf-5)H025Y-0~3}ksBNS)4(G3SrABO;X&bAm8cEwnE$xgsamqf%EX%Qe zmv5sEXUhfiQ$@Jb#r$ntrudC)TAJ%@3hLV5X*xmLig{U}%IRMU5WfM`ceLUN!MYKst7%=L5IgCN!{c<=k+=G6C zZfyNc*$%h1T3b*mAWe2N5(1D`Ikc%1vz6vOMPH^EN_>Q)XE~B zyPdXu#;Azm@~+prmsw;_019-fqwjpgK1!@z*#pHHVB~ZyDk&KFF0QCW*1_}9RUA1} z>BEBRrFhhwkZ0{^RX)2T1YcWiSSgUTl;j77%iX~CPZf=^)8Og6GU!K-sqUh7yxtt~;-)W>F(v#N;(M_&D)VI?>fA?^j0RJlbU!GJ?xL96Xaa7a+%9v`@eHI+ zdQT!eM(5=jUqR5kKiZ2@77N`|4mh^iTQ;DFv)KxXidccGqPdqxO15#CVK{_&k~Ul1hrv-afq-iURCrdTQpLhi5wT^eB~ABrXWz7@AGllfN~jguLj0 ztigX;q6}u{g^B2WuoVTVw!c(+@LJ`OgC1{HL+KB|ZR0;OPV#FUZ7#I<5QM1@fVv}y z41>a$JgP4*jPcGPVuJp0n>NtVx~q#x#r&tE|snnW>E%go<+~`nAZw)E)IeDP7!I3_#uv3%{YhWnLf@Q zZcDb$<@fdbxP9`UHASdNq>(g%?$UP*Wn&^t9#%HA^TGGu<%=p`Ei|7E$Gw?`k^n@o z&u0wa6*obw{~rm!2V3v@@RnSCb~Wj{ATLVUC;V)T!E`muLPz zEL;#^^`{7lJ90g>Y=xH4z~%uTQ{w2edwL!B3H@g8AMjzVrJfa}U)tf~^{7;G-R7{( z_U$LjeWYzNdAVA83i>xtzLU-7brU=HLZAaWb%&42 z3iNzF>K&!rZp61@6&Y6rEDjj$SLDrCp3=bqk~vig!ZsYuVOg|ig^n^Agv4)HKls9y z_3xsJtw=R%NH27YLhm!3Eo`mVN*gByVfHeMV)Bmu@yGwy!jwO$SejFlo}YtC*30Yt zHlA6$%U+HYfO&6{Q~#n((VnPc;qiHRqE;^e_)U@~+_r}TE zMPMqI4tP*nGo_)mes)yd(e|fJfjAlBfc`n$%g>4k^{Am6Cf6b7rzVcnOK%bO*Mec^ zs}pQW3Yd-dt4((OnpR9Bry2odg`Yyp2H0}W-5_DpWDpvmk&>HdqxTi~0Ws3iJ$87% zj%jUWf>WmFQ(0_6Xq)mtu|mMeZ=uy7nGE3Q#=cBCq2Yajnwl(S@TBf= zS8DW>ZBGis53;?k^568^SlDrFMWx@MRqjHywr-^GyxmvAMw>`2OUnL(xn_j^4mov2gMvmz{ zmCYIvX2pAH6VMXWUNsC0nA}weu;o`L{i+S-nwx3L^R3Y~`EieHDgJS8>K)n@<>>hH z^YiUd87HAKk538H9i82U-G(R1#O1(zC8mnJ-##nmi&e+un%*AdmLQieUbvj>Z}U{I zA)1vf(36LM6Kx<{kPd{X%B^9T4hpLyn^M^o_V6nS0N4D?RPn%J45L8i373{&&yql%RmKskSiS*|w=KsD^C1Tex7kQC zA6yp|V6p9+x5j7*`vwtm&fQbT6fW|VTlS;wq!8~Mjp!t=2Z>mZn}t1&g{!<7X9L3> z8XIayGkVkEL8sNh-kQuIn2^4%pdI2pxyKm1M@BpUy^JQI3u1aBe25=#)&j9g4BPw2 zd%8>S^{F$;;<{{Gydn(I^0^gUILux!G`O*FIdUA^U&gob}<@6M&+}~O+9$sh4$EeHY=t*@5g;;wEK>Y)ZZ0YyqYJ#KQgX0hhCSC zyWIv{A$R+`!39~vr*1o$Mu?(HNAu6>utR&c3JN$ghIA{zL^Hce1J)~N-h~8n$H!zR zk3JZbojptk$r^p4nq*qC?zFiW=`?esr z>O{HTL_!UG?h?$ufr;Zav3(q0zO6Sh`?GC#Nf&JCzHIhZ5?2wfh3xv=|r zQSQH>+Y1R8Nd+@Ord8vGFE~XiSo=+Wc6e1p%6&og>vSREoH+w^_gJ7_jS~S{idCS0 z<&q;DeDUM9*Pw*|KY2vJk8Yr304R-?a5gXI^qpJM*rvUSauI0qlss1-wptH{S?3FOn=V8MoVGa*t*v2<&~6 z9eBMpce6M8^{yS1AEn=ch#7D2rUgQ{%A~da^_X~RvG|raSd5YWhTK?#9~f9d{^L-@ zPqv6F{2ilIDGdK3dc?`p%gU>O1JpNUQvEOzIOSbwDc5YNG)l~U86 zon1uA+dG7?6Ft^abAMQiPbfU+F4gAA5;eN0Syx$IKi#F!{_sg(RPTH#>Q6-}c&^T+ zLU+qdJrA~3t~HW(tl#PZVUWpe5Xvc90fFNbNVc@%NUtsT(vr6EV0iY0`d(D%dkrc= zB(UuY+6PPmo)RjQl3%60HuN}L?BWD6+`XQUq=#?mXiLBqa=n?VwbsKNFR}zgT*x+4 zSq>*Zt&EGBoMmLqRFl{~g8}i`hncKIW7OMxe_5`|JG`&Tu+TC+-_BH+=JzEfz zrYFAib$*l$R<;%@N3TM|Ki#e~z2_SuNr%aJKydDz6xiVEPOZ|!0b(Vf zBFZL=?`M{(Y&oS1J`D*B+@YH|xu52LTM0bH4>aVetogi`IB>h3?8?Ww{Hl;cJ(l@W zRhDrWmQMr$xq3T_e2>2-@OM3wtLs+%K(d*5Te$G}@u>B_sb+zP|7&?bS}$`@IZnl4y1^| z_`&qqAxF3syks$ZqG9b*_#9jJ%=GFrnrD$d<0E2ekNmS_B6kxr!ilvxmegz5H}}7y znCy-r&UiBl+SuQ6s7+wcAvaxYCbc6Ll}jKI4x)-uxwLyBT@!P(<=yvy=}a6m8VWUh z=V74Y?hImSRc6qZD@lFUgM8w5cW#hwXP*vvB>zo-t@u7080j5kp!hEj z|5YGi@LtPrSNg9cGNZqe$bLg)lX6yIEswJACY!)JDc}Wu{4KGIH?Dt4k@svCuO3u! zUjMQM@j{k&lVHm_}Tb=f`e1ECL1Unwh`x+44eP3)WU1%18NE{lfh z@>uPM48>*|3=!`penTkbogaLFZ?pGf`T4(dZU_?A|+qTt@rs^w8}S} zrw)>v8L%yB$M+l{4U%oS9&}mKb>u0zT*J#XzvOI)If9n!d$hUU8UVHppOAg0)>z>? z;0#-oTeBkcMOM7w`EiK+;i$Fdrcr~bur(G2 zCEM{Ht8%W`*`zz0WXs52m2iqmYYj3RI9ce&t$QTk20`(2M11JmSA@L#KL`~R+m*LE zgEf6rYp9G_kxPF5klrtr;ULrbq~;}Z zZ>d%DZz1M?$eL7uhUj>GzLIoy%$G9L14Y-7>i2$pcW~H0<9&u<{7ZY{ozB|x)!Bsu zDA?aLd8_4=^yTiXgfm4R3<|mJ1#gR&+XGw1<1GjCpaPX5zusH-*1w|T9GCY(nP=wO z`{S)y=;d$7>seRvdsTnTrvK(OMF+<$JdnR$ij2n4g6@tX(~noo&y9beY*&P;+Fk{x81HGAgRK zZTo{D9g@-^AV@0RrL?5<5K2f4AwA?qx>GPrNBm^_D;nUE){yfwJh6k9|qQ)}u45P%A*f>HprB zFNvD+mIa&34rI^;8$m>0#1};GhshxwF2ygg!QA-wsOb<7F-y|9JzB<^so?1M(QfxM zP0CgRtfKmH>12Z|@6=w8qk=I{C4E%D87tTMZ~2}j78Un3()-9uL|V6zr62 z0!Qpvk~R$b)%TaGK%I6jRsvWVL8-JN`+L`!Gc{siba|Z4eCaJ zEZPXnd48(Mws~k@{;Ciy=@&$n()o6&>E*R)olBddD^xebuE38YiuPyyMxqcCsVU~D zym6l&SMobFl@xL3!P^4;_MAa&%+3Px1E^dym{yf__ zO|gZ8=Yz$mV|O0&pf&EI;Qo`m5gx=zWGQiPb4|VLnCiG*w~FT8G{e z_Mn?_nzGCx2i82==3Kt-Hk+g=U!Z7aVTsq3X6>9Dw`_Cq%@4AhdI;=*ynyjLj6(Q( zI^3mQc5AX6n0>uxE8DzTbLid(WlkQd!}3{FLhB$G7_Boc0t0INx586e7ZLoa4b+ zfL6D2&~kZH@x^Ev4or1>);^W2u`Y38!Tn*j^`v;kEK_>KhJ6p1kB%a3xYYgGrH`7$ zH_{R-uhQZ;W;nCQiki_n!L^ONPcF-eIY_GKogcvQp3jJl#C7?l;*3b{F5)*b>otg| zCA&(l0nI$RMc?aBUlJ9vM5C`b2@mk^xTs@fz)~%v?JsCB0G+Ax-?ZYIeRvH-ZSz4+ z3yNgp={esjh0*8=1TLbuds9PV_~xf9@<(!ZPuV+ToQ76^N_ptJ#eUCj)QA-xd(-bK z3o(UP^f+Fdyo6mgcoi+ZYN)Gw8JuY;^a`V14UmF8*g9U5$a;H|UVrm&CG2&)b^YM; zPlX%B3VQz6e*lOj+VnC}>Cwi-d70)ULOD0rrqYIIzK7>jE-fI4W&khiTh*P$x+I>B zr_!E?dk+?exdL>!t}2O_Y1DVeDuv=KQv|;j1=dGLXy5vx7;e{>K9axO&D?t(|CD%M zt_AF1MYWuE`oqQ9y^N652;cnG&!z2S{PkrX8?7Onz-`B~be>0!Kb!}89WS4pf@W5L zK(2*q&|M+|&NaFE{QLJfd)&sW4V_o@S4$Mg;~+6ckwLCB{I7EcD#O%ksKmiRF~u*) zFBuC+P^R@^?ZR_)K5pU+t)irvX@!I4UyiW8N7X(XWV^m+Ks0ziTZ6V4Z@&R&C|M6K zGPqtrfzPW>NQH8qcm}aUdRhWT>bYmDl4Ni|YPQwFp#&zN^QOIxFM|3s$h3u#0&+PZ znP`2@=5PoutMG(go#H=`pSoBNGd`8(`;IfBwfF%coPJ&_>M3a8;(eKlx&#Gg)i8;1BDeI^K=K{`& z!Kr-{aB8168~cj#eS@=jUPZC>YMBL3Hl^1}d}R9l?N{o1p%OaFxj&E{7O)Aj(yn$d zu5G_LcW7_>?$$ST*(SX^t5QK=P0$+@1GbOMkR>Mn^<&^)zm}q)?mLaKe>3tM9g*e*HWGj{Vd+M7y+XNc`NKf>1jSPENjvpq6-L zuLO2uKs8(&yGWzTNtt@%9JEE`AX(I#r|xh(XWxiD79@IUlfcj|zco~-N86A4!3Rck zCNt$tur`LHl0E-Bn*BDpvNeo+ZS}S7&{)DSy5Z6OVA&xcJ0tcc8|EpCm`7m5fmjGz z!@D3OihhR-IjKXfx09`k71uHH?Z}6TQ9<=Utg&|V(#CgtOLJDLL@MmJ-HC3nMso^?P6!++ zT2lzDPi>B^t6wL)YMJ5hz%!cn@YTuio+Cc8rTNNYEUv1jjc2JechKt8&NN|r$USKX z2v?$ZSRl8$1>@+%|8W8Us4t)fWv~!6|@J1`_vYxDIp7Lc-COwFid{6Xri2hXu=LN zfhvVm#$VyMQu z(Eo<}K&BAlGPva@0^`Pjb~zOPu2FC4XrEztZn&gYDKU~SldX-NZO;O66$58!GDJA( zkV?=_H5xK#L;)U^oXsxTtICN@3DHj@^FbAa~(U?#Dl(GDGP>a?Ox%@7&MrNpefr<*4Y>`Q{lRdYMq*t z!;L?lMZ%=K|*KqUs^{vgtfGS2o`${BIIs*zdeqgd~%D@cezuN`I8AC=xgeo z67!Mx%ul?g4ChCW88PD1%W1%%AWW8&tg;=)upcT9qIt=V`$$fjw2!;Hw?0^zQ?Ms> zHY;C2QQ)~!kUDJ%6;G1%oS)a!*SU*CqoZX zt51osmG8ruI&ldN(#2NkT&EnM(j8@dgSHlOYl3dABM8oI7Y~vcydrvOZHsw2-m&D| zr%c%Ayl^v9=G8rmxcQN?nTlm=KY4`pj-IFaa)TC=iEyd%f}3zpr2T6EJU?4;t= z2mQ{y^k4=WmX&>2K1(A`&FJ6a3zaFI#RP#c1lN7-N+g!aA%&@+PQpWMuD1(XE4X+= zo&Ms_eN`zi*##MO=h`!Qkesyu4t@vI;JadJ{W3Y`UR3CLf#AhuAItI0Ci}tFv`j8QSAtRQ0Yu|NYG(u1ees{4e|DSsV*!e}f(!CNm`@A;E zZLdpl#sHW3E#X0OpNMf;cl;X%k^K9v9xUE#6W;mJ0#by~{j)_m^APFj6x3Gp;|4mO z7dq6#Km6HD{?Qv*UcPqdy}F68 zN=>{7&bLONGJBM`mMXrI%PRJO;=>{j0beF*fX2yKaBk|Aa%1Wri1rLqQ&R&_-<@VA z7F69Y^exgn{ID>afDNgASyXae4a0+WOE5H_jHGcVI~2^9Fy95lPu7TRJ@;f?xsXWA zSp(nEGdS=%Li*&g<$Xi>pvwdzr>Q1LRYGgAmKVSp19SBLdbY(zarkB=X!kQ8Pl$1s z?s8medN>sIgk6T|xpL7&0K(#mg-7-mF^?AD0_1o6#R&PYdxXkfoYT?|2#G5|*i~y* zT7jCu1vV>c$VpZRDX7bi74K@$)!H0$wk*h$wey6cXv)71Fe=rMM^h$wk>^brgM(JRXD5)V5;YVeG@kFnQjW(|)4Wr}Ar}v$AtNV^{_YfC`RH6zj+E5ze;K z8d-{SYeJ=%vGD0>Z~g3D1J3puk0O~=yY4TtPE9VR%kGI7F}?w95K)bGL3OBs^%N@q z&F0gWSzKI#3X%^XSMQDubY_tTP+5luXyMG5;i4#$RonNyCsB!)b40(h_ zwhyJUWAoF~@ejOQ#6kIaJNQnt7?1Z&dpvvhqqHGq#r$7b^weJ-38VXoD6uojAmzf= ztTuh<)Wi1&g%Tlb$b>1UN?b`ogY$%(9oGMMHV6TnLE>WA*U1ZZP8O9ZI?WlbiA@Eu zRct0$WJ?nUDieyIv&K#)YjfM|<^+Ef!+Dzu{jCyxx(fA#Jwo3QWk3k+5dr_pUNXef zs57gz>)PK9=Vd%=OH=w&Gi3$gF3THA zG$Eqd;M4)nQ28B_XS5F_@(ZYc4XwX@3QtM& zKJBw)7zGFKo0!sd-M{S7GB>xwFQTw#zx`lf=g_@(s^eDjPs29x|wq(F6JWTnJpiw;=8&D98+Q>gCHh#tqtvA zdG#q4vTl)y2OzDTzO|t#75*;8SlJDWExOn-T?coI4ofJB^~aB4NX*;)ZMhDXwLO9D z8Qs}9JGGG9>S>F2z`*InV;U?s&MlzR-0U15G)(z8a4uac^QWlvSTR}M28k2w-aEgU zg29tCO%-Jg2R?87pkTJkN`%~k#*c@}=kHmAJB>GlJ0 za#(25BBp-aHVxI*mlEFUrIQqciH$ z#_IaITjV>@wd?brgqP(tuv*r zT;tYGH}P|2hrm@OcgL;}L!PE6A-Ogh4@0Us~vL%a1p6P9y#$<2CTg zl7%_-FpOn?Lpx5Q6@vPD3PN}B2$U!zXUjnO^S|#Ke1q5dmJex^@MK1DhH+kn@9Bh@ z2Onm9By8Czih_S5oNI&4{s*-bgqCJw8@x}173x!1p3N#$a3|7Ig)zLP+&txpvIDTkSf|h4(fg9uA>*FUqfdhgIg*=D1vS#+l^9zw7r>JWpo||H_YX zm~g@1J1=!rdI^5kXq2Qz?Tl@1TU7>2eF6iMY6x1ujXx{u7}wv#jx=2)S6e|p@9y}u zr-}qc>Qj?irQVGC2PpLKT%RnhFDnx_gq;(Tv3F-$R3nT>CSCL)Pb=h#HKQnOQX|AmAoI$LepAC~6k6J%l?< z>~Zm~zy{WK$dx`gBN?o&W}En+%IrF=;Ol3iwQfx#*EcY0nIRK^Kfiww!+sL$o@1SK z5zNCeE3?sUb`QP7D7j7o|6qs5zCSNTJ(v|TCZ9jXX}opc@zRc=ypB;t%6DfGLU#^b z9r@h$l=#yp5|YXL&M9^gZIp$3h|!GfA8Cu4N21WTU1Ea-6ygsdACm9EzIGs=%e)^1QyOGJIOw{exq<7v&2FI^fpR8?+ zBA-lPjKU1Gia~FmCFaGeaqVsKTbpyu>$qz_{2c!QLVfc$vdrsVx(1lL*uMXy_}7dA z;@NdyAj$UjhF51h9L@FZiH1~4+q4M%<;RHt?A_gjmoz;@FZp0hn$P6rC~))M`irxo zrq#S#Jx1Gou|vs`n*M-1j=l~){^?o9MiXS?0@!A%hmFiOz{odkr_!0Ns@J2 zIKLB1yR1sSD#m1bI85m0xNGDs0h#6-Xz$H|_iInpmb?A@<*2gBeP!mZIV3JDR1$Y5 zKDjb+;IhNT^=;lJZm&YD+9Q5JwX89j<+i{4#b1`Y*L(&}r!oDBKpC$hfBJ{v{DlDz zpt<&J93}H8%jNd%?VJPb4}`e`lnN_x>28GgU-m6MoDy>`fXwMn)L zAINJQh_i{CbR|E&XYm2lka$PQE|(=%YnWd?43z5mT!*(V<5ajg=Tu>^*KSFB3B*Yi+gQhzrOFErw{1389v`d;+UM zI>6(;Xq|v~H`VSc^y`Ej{rJHao81x3fQBC~VP3PO>fB`E_ItrB-Dh0yo&?1t z*+Cg46hIZ!9|z;05M}ih1zjFQ8AHs5i4xft7`tF`NP8z_gm%wg@O9U~H|l-8r`;#Aq&+9bpa+pR z$m!deA=U>Cmp%oTDbuZix7Hy8XB`p4i!BaQfY?kbINtaBpBc6-EiGO+!sSO>3U;e9 zrwZHH#llRfJ^yK>7`V<|z4bBaLewoT_D)3it2QQyYJDnIqnFWMz}G9He&Bcr(hg_t zGiVck=ej%E*JDQrXPQ2ExKd(%kEX36+T%$OYHM#%34r_~yEXDg?5=t+Quoadkfc0E zvqt)umhRfij1>>&T&N!w`+E)tM@Ul?99a=B28cewz<5Iih)&zM17lM^l8uB_Z9E?3 zDjR=q=yXoA(*JZ+D|Oa|fFxq#)A^HX*Obp zHn83y>Vt{GNV?~Ic_CPr7l;t z$`mP;TFhl#(FDlN&8Y)^&83;ZeU}xl+g81hj;^jA-VO-;atjWb&@R1c7cHZH2>#s` z=&E2-0Zh5qC$};gT^)%P>JOYo15l#Hg&#yfZz+z-OF7?1eXU|mkjXk7b_!OPzXkFr z&u$$E=6ABlYnwFJ_V)J9R9fQKw)QlSHpJkl)rA-k$P2wI-)D^z_ssAT`Kj>k!o7w| zby+VF;)msS$y@fl(U{sto+qrRGp=@KD&wV;x7uy~qd!$~6NEG}J3X`BY1K+Tz6N@# zm1$#&yIeV5audau=gz?(j>qAf$AGQMa_`}TVV%SZ`sxW#AGJ=Dir-Nv9;=14_{YMj zT}cIF4mAk~;ey&VQmF-(JvuGp-edNAOEy{RkgvQqXxX3~ zp)N6Rvt&ylwBYC;@-tX|jld>CDI8X`F;l(@&rfla#tp#3)gQ$?`0fE>8l)ccElS|A ztN8c*bR=P~^}5OG*|_HiNBAJ6QI6jQDP;%4Js5*eYBOJRKU063D2>QYxA5Cts@nml z^j^+!KAGCo2~lTSG6DpL3k;ukWy%O+&1K4~!^Qp%a|xK7b%SeYm&F(;ffu@1BWNUT z=-(%+w@N2bbpl>(kLd@sxo)mUS`3LeF6&xlb2bofRR*;0} zHT1w362GBjr=57#Rk5^mJ!x`cGhnFE+Fgj+oWz(n`XWHgb1Zw&K_v%!&zArx8M2ye)G-6n9%&~x9h9mR>mSR%MyVyrBi#)E z*BrIKxI&pZ<_Z`sYfOJTZG+W%aLP!V19R(nf?BV{kF0+m{O}x`0D%rNU ze8@>|fwlliYWZ@iHjF>b%mT@-J@Zs5soFe+0^v*mdBE=cg+a6``h_FDxz zbr$6fy~eaLKrby_ma+$8aWP4uoYZN2pp-%nH+p>*WUqXCI#vu532eB{pW$Gv`M}UA zQ{36OoqjYb>N$=0KG$G0bSz<$c%T21u)2u@vf_=8636@L^` z!9Z{EKM>4{po4RhI;xHuhu^nPCvP*-zN%fdS)oRsw6*F0Sgp!-_8%F7Rg{FrsSni+ zQGQ{UtmvC`X;=w3x6t62)cQlM$v2?Jd^QF=UL5Ih$8km(AwgvQ-6G|Y+&B@xxYCC= z*DcfafOU#(sy2^)8}ECfn%0w766CGU94`#y?Q1^P1w8Sq=FUMwm7?gt1~yWxIxa@l zev@DP)DaBgLs)5&EJSEqoQ2yiCUH)&(D=aK{}&n1e4Fz$Dg#UDs6 zdtE6V*|nP*vGoUoZlB9%+0Eg5!mU{VFCN9fFDKp+&~B|Ubui!Q8TBh#sQiG`9^?m0 z!Si$;DrNo@^W`VatB~x&QOq~0mJAl;xgq|L7hWalUuR^hV2Wf3+n9FQ+0Zu_qT*{% z)K`^q!s2M!rq-DlM?n@}#~iXSstVA`jp?HvEoRx8(M3T#EW3A^PILmkz$}3ITMT_# zm1~v=Xw*T~$U!MY=LXfN!0$br&(2BVFu%#+aDI8QM~m*FAS=c1Hw-Fw67@A>CA5_j zzIHP$b29KfO)%Kh(|o<6!ggY%0-HOamTYqN;us}k>&#rG?2I-fA>nw*kIucwh~|yF z*%uT423wir050z^IgDeGvrIvYckVdzdMPo+)%@&kn=p*8)G5NYRdpL1_g6Fd*P?a}OHOCc{`E$yN2B6=mk%sm_Hq zh}pF4pFTC(ZNZcCa5WyC&IM2G4r4VWssV`LSZ|RefL$TycinU}7YxxKHjJ=+p7?;$ zrDbV*8xFY$-!fUF3s|4_?Yw_7)!PR~yu|R?;q5?=08Y0SF34ZRsNnJW~{p}wm zu;#+Tghj+lfBfB+N&?tw6BiTARD49}z4Fb+ zb;&O0Cg$atcQl@0=2Dy~*ays~zj6Jo*5kg!c47)MrV3FGas@tU>RpgFax6iSei6|; z&Qi3X>-?t;j}deJx7V`??rd{ny8mYwzel_?DKPJHa9;t zV_3ztlbz(Mu~nFvGiMJWG_>J+8l6*oX}*(VFq#<)`JUB-`+_wvF9Z?jMwwJ&0du8) zXqu#6fRQ8NcRN!Cg@W@d3?9YHUDoz`tR9At@16k4o==ctJ3&=FNS%UEw%sYR8^Z*X zuF$39&0arwc8M)?Gbg@673Lb{&_#zp8@^P-Q+7nZ2Ryd&pzSRfCZ3QBD5sgqbZu9W zz6o^9RI35O7)t_i9XyP_Pt=u1ss^lKSwtwzlyRGfT7bz2^e&^~;y1cU@B)D=U-8Me z!0(x;k^6XyS1YK(+R67f*u49x2d&y9ZW00~;v=Qj)L-{tJcLr;IdO8%;N&>wbstCvK)X zeNgAc)HZcQwD$97qPc2d38`cpnlGu$elOx-QkFB|Ts+?kvvZnFQ0iHI`o=$GK{vx& zXjV+$dZon5r2`AP{IjfgbU1lNhY0k8I{C_kkPFjzy|4GBH0F??L#kX>Q0o9t{{7u@ zjSc+RN7CcrzbkE~TikyLw27C8UBRX$L+?Ftv3(39_Qg3SpiS_aUZ-oJOsIBd?>oFXSxx) zv(1rlvSn)K4Mh6EC}+UO4#*|0qp{t(3aq=G>7*H+I(p;f<2yKGYs;L>!#SiN6;)QP z)x>n>?--DdeUWR2YFIWH%qvnP`>Ak&Y;=u8#ka(026by zRpoFmP0%>1&{h|}F!b1MWKUOUV3c>VrY`IH46K?e_SJr~MmJMJw(Cr=<%{8_!-}`& zv4(o&=5?)6aywr`@hWOhyf$ci!b{$*;#3tb*)-2q^3y26cr8fc5TR!NPn_JoZVj@a z#e1Rjx`Li2Dh$7*(Xnnxv+2lpBEf+X*o&dgm!Xa!QFHEco#Jq@aQn2CMf>jFhURs6 z?sw%LcFtn!o$w!May`MD$&Bgd9|L;bKB;3cg8fS@n|8|9_Ds+WWP-^QbRTZ(O1$ z%}m*%OBGQc6z}@J00oh@`lM0N!QWOBa7bie{EbL10?5kvpztnM9wVTu*I8r-RLdm0 z{r^Dr&Z{P$LK|Q+5F|D)8`(ZjNYGV zHJ%)00A+Q3S$42|d5Hv@_;=j(Q5B4pk}r%gBhN8d_~*QZLiHEm!YU2Cjg{TDgM2ifqhMDByfasg&e5V|6 zcI+Z*;W1q2&dY7;_anhgu)=-H@?`8GmML1k^k%=jW(+D-kCm%_{sFG20;?=CK2aY) zV3gfzS*0zm2R2*q(2w`Ho#m|ey0KITxj+TY{&vKV`o0H-S zhk_O8r=Mt@O}qXW`d%vUm_GaJQhgWbctC#^6>zJ9N_~71Ci5k_Q>#|vUmQ0= z6`{aB0p8k3ZEeRvY-rOTi1{q=&jQo_gpf1$(6nkuzrIL_7J5mi0S2!y{8e8llkai3 zfa^s7@_w&xTRTBb|Bly#zxDA`ebbb(&(BZuG`c?dyYpoFJnQ(0aQKaB^6LS35RcYL zxK37$%GFhoHjqR3?KVKFx`gOhSRh&1eE;KED@AVb#VS?xW6@rNF`hr>fnBCg4Rqf3 zq>#nx$B4gA@4H?**Dre_00Z)A$Z8SCg-1{kR7H#tp*o~blEmVfk+0af)l5gO_i-gtC`UWA|PNG<;q!I~K1 z5pa#KRF01YhQN61JAem4T)63#F4)L-SIJn_CY0ecqcxB0B6J3#5584#mTpe8zRUyb zg^4?UNA$9Gq5SHp9uvz9UEl7;`b~OjT6}q>w)Oo&*JE^;x;2Lb*Lm7!^GwX?BRrBY zMs8KraW#tK)TEaD>#^Q;!iI4N(+(&!dD=ejV*@55A&AaCs^LYcJv)?oWRn`5_Bg6G zim3k^nQ5QbY#q?t-dHIs_l`LTXcS@^%Bi>2lG~y2WeEO zC%SWO-Hca=dQh)*2|buZ8oD!lrK)kfI>_yfI&(=pa=Q-Xq{qrUlVVm>aAc-6@B2h2 zKKK>#ERV3QMA9Xu$4vU+z^KF}d*+b(23>X(HT9;keUFIS9n=BLzHVL z%1lQx7J&sb^#r(4(w_Ts>Ww6Nd~p?f$-5}`<%@N2swQVl7nHABo>n-nO-JRq* z4R23#aIU2(3z1&?thLs|M0cL!NPl;(jdz(MfYu~Db4dJ+&J=<@M)Y+pwCOY3q50dM zhuaCKnT#$QsyBhA zR8eyCgH@9{t`>e^OW`*EN9KnQFAO~8%GThM--fokCcBA3*W%Z2WzaEmA@$=@)d1qY(XupC|21)yg&4JZAvl@ zaT72a&0#!&Ek=gkxxqjprC<-tfHH8+uZ@E58IzM@(OG_8r*~QL)t=BvPH9KcO}>jl zc?_^K_GF!6somUxS2`KGZ(J<~c2wyl%0914o$UeNAO*eQuYYwW+FEU-u~6bFhOm*;%JcA*X^ZkBSv`c>lU>C0A%n zRk(X^)Iz@!apgS;UOIVh_C%hxCl-j@X0#z9&?K0xGo88faL6xDUm}aPQzRZTk}{FM zd@t0WD*da!eBph4E$~?1=G%=xU2AoFmC6;Fu47=Lmj6p!B64c#M>cBM@QT;Sr10ji zNs}JX?+(=2Sd8y}`Z2k5?T?Q?9KjztRvAAyIIb|hIb!uo-MkrC9GjX#)UpHdS!?)d z1R;m6fmPF%(R+8hCtV~~7S=C$&biRBUM@H0hxE^ysn^#|pGTR=3uu*9CL z?0rWOuL+0j|I7XP*8%$XQ*Ne?EG4@sy)jP7w-M=Gte2SNh;x%tW6=NUw;0|1v>X%} zE+w8ogTP)stVIXQ8L)JvOXg#Wj2hmNm%&2!6DS#T<;Jverxi30<^#7w`mUmNdm3CG+kP{306{L@FUND#B}z ziFS2N5a?9a97lF!+VWOE69X7bAJbRR$Hl@j)4nY+%&j8<3oypVz_l-jIsFpzjKhzQ zI>@PMPYZQElQ;Yv44DZ?^j4{W7j(P3OVEnAW@d=R8`d^xDD1`9;Jk_H$~IgHpZWFDQNwy?B(I^@i>lu z=CE7kS)?Tf0@Nv1!1)NEc@TSNE-tW}2B|O;~jj>=;3}a+_5w+Mw{RqylIkkG9 zXt_qg-`hHq*A8FenOqk2i%BoU$VS`1??-QLW<^as>Hl~>hNaAI-5`>{6fPaScDNBq zG#~L$44tLJSj7b_E-9`&IWvxG3T$fF)5^q@=ou;jjL$hx#tz7vWThb2{+YmG z-`~I4Jj82Z5V0Qvl-gt=mLp$&j#U`!t5#eNTQT|bP;LI$AR7S565-|EFY?6@)A5}a zl;awn@dDc4`WPYj%dBOf?IUv9mtqHzpC45=b6NSeD(p!R+3y*-Z%S3D{@p^0a}ZDM zk{A@g+Fjxq__l^F*~BepanP|{Oi;Wb*UT+O#)}ZCmAUe%V=y3zwc4vEYH#rbR?F-! zqU30V?cW?rRm6|B-)gPz8(xKaGpx`N7+`KpPraNqk8CT?=RAvuc@9u8w>xI$7KoQr zAwxo_dJs?M=NEn_-5}OPhuQsG0^jsGuQHlYCRIzP2>D}NBrcaT=uJ}+)3v?mU5TVJC$PZ^XMuz zu;_?vRrE|Q?H+P73O}DaRKm$U=J0e7)1ghl2P{8%H4>l;G7az^FjS_$zFM; zxm(ZY?C=+XQHmQEOqo0?5ZAxK+J9m6ru&B<8VuMCdP!<K*0x_vnJW!ZC?^H9iAsD-t{@UkSs7ziP#f+0NQva(D%-3^-lBlCArWrF4=kEqa zXCa^aN}l2g$jxp+6!UgfQ3mjQw=w2^%i4l3zJz_VoMd%vD{&UM-T8K0Z6*I(2n7D0 z5(v`?hisK)BJWgu9p3s=Nc7tU1)H%ldf#mnpUp-3^2_&AE;JJaI@p(eg#9FeBA#4W z=ZU_d3maQC0FO_MMpwV#^T3Ytv}aO;MTw!F3OsV_+lpalOQ;4t8aiV;kE0Z=z8&8^ z(exb)+*`89y56laitT<4*yyc(73*K>CQ2CQv?v)md$@cTy#!VgmDG|qxOEFK5%Hvs zJi}ejKw~>Flq^mf+~Vmk>HTbq;g%}UlKuGV+PV57Yth=kq$p`rx?tK?-(UF59)I zav6mOML!M-v(TpSp(H*{E;6$AeTvj+z^rR&p0ud1uf}+aSYUsS@6|$_usc~@tL{wz z`h5s{uy;K3gYp28VuBX5c7wpiON^t26%T%d9-QU%)Ou@_J(wPSv{<&OoVLqMMOBVU z9B^z<^5q8}3ZI;xVnJDD-D&#vi=cUb-;5p9^lObj5T^cD;0%=$u+v{YRA`mTpA~ZM zWyh{2rwsj|!~dQ`iYc>TA+_V*pmaw77uYZYAtFF!-S&MHKSG!04+MKm>dew2S?g7% zZjyr8w1vXY&ztSq@1|2BD|fGkxr5qS)nGA|?KuznbdOSWhlxP0&VxP}tj`(VKBX2t zXEMY0qgB#-*`mE|>LBg=N0ZGB(O8o0hfRH+x{i{8E{d%j_f$~+5G4!jcR}IjZx=nc z8JU0!{`^8cs7>rT==T9QmkfJUD`Ejf`%XcRag4?C_ce{q24o;bEIfje>0axu-U z9APBIHCFf2P>d+?oLOPuX3J0b2Y=Mt>+&-tFnE%dYLHLgo@{SO&izG65T-J#&@gfM zcB?SewPd$3H8QC9#ZYTM!FK6)`wS-jo%a&)6Z?`K*P&O{Ps^O2n;YU(X_3mkZ z9H3uN9&s}vGmyO26$xZX3(F)w)biQ-JkTO@i_GernZ5SOro%IU`#foi{x-RO_#E?y z!iZ^@Is`*pZwf5_Av+?zIS+q@?;RbXel`c%TH*nYo5J_>bl#vRLTiCheS@rXkhXU3 z--*o+KoB%O<7$}JgsZZL!u@!JPV=pmq}O*IBCMP81)#&cLz)Hz%i zntx_G5fB~Kz~rS1ExzVfoN;|R-C(S5(i|ASt=8=29w#r=tFU-IQ^wdWA{Pb}j9FM% zq3NQf1;<6k2!oTKFPLkNrKqEeyhPxSJFCmUG{q}~K}(2mtiWPt=C5sux(N3I=2i9EwC4p1RYVw1OWDleX7hH=o(L}XLD@Yu-1p}p=HtoyPlNpFZ;Tb6KuO+qK1uN7 z!C38;U#mdx_9(axzkMCOo1(bS2`hZ5%TH3ocsCVEpBI6obZ zD$4ARGL;KrjhR{nwBlPWKXj7!LMM)&N{}EIstpGW@Z>cx55Tp}(2w9PyNS$+K=N0> za#5kdNzI!4l%cW3!?fP1(SZ|-t?kC;Fx=g?wQ1hZ;5emqkKjsm?P}~cTbuuC@sZgpn-2DGD66WcUdG}0GCKCA>c6KqKx~W z|5UNuZpl+Nt3Qy7b&PvI_J3~oe|P&*Yu#!aG70a>QXVXeun80RLnd<}Aqot8PwbZD z_nj!Iz~6!#iLh5jM8Jr~E_ z>*nR)k$NQ46}#B@YXW+aXswE(0mgkDZ~4M~1J$aBL)OkV2(HpTRvA%Z=VLAsVb@hZh~b-9JP!A)@n=%PdGj)Y=BljFj#& z-$L-ZqIs7|lg%zG@ZpZF3~O|_HU@ne_+|}Fm42$pkB$~{rXOj9pwbBKYrx&RZ_0s0 zv$Zlcg_GX8a1$KocX>;dqCIbqmr%YX4R*2wfE1;gmHlC=sP{tx$od8^pG}Y8(L=FD zdkMoADquhr)&N57^?8M2`GZr~82SD^jld0UenIco#ozT?TQ>x(<%G#Ys=jtTr}E@9 zu$&2RcG?K;eXxY2Q9uLEgfrgL#~ zf0H|33>>QOdQO=vtD(hVuG@`SfvQqj6x59FJLBP#-Ima<#Xn?2nik(rTl# zADeW400Uj1lXWHJJLTx6s#kT%0hRbJD{rwn&mM|5TJ=?b3=pl2 zPchZUHa`LU;wI!UR;7qxq3;_fIU{TOspo>sPv65MP|!-zH|f{e2#lxKv-Jv@#)=@q zOnb?olRD-<<4e`OUu2Uq-V&=)9MuHCK75dxq>Qh!Or`0~?|MEa`H7AeW)m4i; zS2*G%>7u>&e`-`9DMQ$HY1Rg@M0A@umMUAReyt=LbP&AEA7ys=1JRS5bz`Bu1)oaC zKW8W|Nk z_0<>$Gu4PeC`U&OZSuzr6e<)*LVFC|zrIR9fN$cUXGr{l`;KA(#Jvq^tlmB+IIiOY z_E;Q2sM0gZRSGap7~}7x3=^;_9}H}0P5e#Uqx%g3QF=b6C`<{;v5yGftlsh{^4b{Q z*tmoI4;!8QWKUC+r?l_8bM&QM@dgC{Pjg=#7FFBsJ42(ibR(s-beGZ%0y2~mQVvKc z?II+l=Y~LSk?Whmf(XPy$ji1o8rPuB zs4Ac-nYz1{{E(gP(O{=E9{s6=gB*lw?1>GlV@t4k+x?`qA$I9321?p2GKz#QM%olG zox^%%E}=%ztSAsxrRP<3lUYy5T@1A2+vRA3s2+xrNKquNQeN3vBAwim#0ndn{}`wr ze{>bMjh0FsI?oPwjDkRday|Ii1P(-@SiooyCZzELE~*z9BKQj;`gll6l=_FtK=;$& z=@5ohg;0hSub9&A=G3N+HqWbVZNwWb78wRrp8!%tmljui_ql=gt_EzSVOQ4Fx9^%w z4AgdN)VD(4yr-M??#Jtbu2WByVguJm&rAxxqE@X#9SF2?ImOuJXeE8F;dZWbr~~9a z8E&OoD$gum$0#$(^OQI;2@}tYEpNZwejNJMd#W}^{M&S2H$CQYA~nKnTC&4i@$&39 z)KKx-NpffR+ESQ&58jUD6Rv%`?26?Frv|U<0pZ8B6#e0ccV)8@QJCZz@q5cuW8f9Nm}vd37_SpUl8km zZ;s)X+B^aCkt3v(3=c$EKByJ#SWJs+DLciL#B!wFO80(6oh0r(O*b7PlX2ojX_K9~ zCnA(_WIpZEMPR^N%c8^77!kM_5y(voowNhqSlfHwFNeD@FLs7h;_N=be5SW73)N+JR}&Il6XNOYK> zi7^Nwl_~uN88-lDYa&aIGh2@R#I0YD@6({c*_RHsD1+*ie^m{|U$8^3#anA{PaFof=R zPFMF?%b1>Z7MXK^+YZ>e^#`=_VmB%L3nE#F`vjb-w`XnieEtJipac;>mS#vh6{s{a zdl^cHM=Wze1&WNtgHi!`Rp26(({m2Mz$zY5CWgQrKP`&r6ea0Zeva0Ge_b_&sYVJ7 z<8P>;>c1!j-A4bFfyn@K0MfDS(R5FCoC>Ua4$B^ZYTlletK(mLF1w-g8)X>U<04qB zZ-sU{O@*m{Q-Z7`zK~lqVC;%1N&|~L+TqPWO(7k^-nzNDFM}l(wGzgAJDM1h;6LgR z5SKC6{{(_6x!aQAf8_OW_w`Wq70&xgVfXDqw~eSq*b6ayi*Oz*pz%=ft%wzcdSJHt zb?!E_p%RfRe#QQAEEp=eQMf&KpG8NC(eY7S5#v(7!tLCW`umvst(7}j(b+3X0%NOy zu(T21_6cs~<+HINeOJ0W^-SxBbp257)^Fs%apwu9X}lvzUTio>?0 z{vmX%me!vXM%cLTU>IUtI$BSyP^BoYtEwSioD>=;eTwMr&9g^`$tVi1W=f4D-ZVfx zpvbA(s;PYB@i{QwJlgcu1M+uTEm}8i0p5pp3~fzw-P}9q^QiaYR@GG&R1LDqftvUI z@lW&Xj29^=1iSJnWJA;%+AxdB(M?#p4QGks!OtW~a#wAhqt?j!6G39&^#Iclk@_O!!{S?3ziMHL0nOt9W$x*cc-ecC>ro-AV9ZZZUEMH%an#A3 zr2foq|Kw$qNzq~$q?bd{ybqg3u8N%-Vo2j`+h5H2k*&31V|9Zrb# z5acw(P$p31`Ic<8^JclDYf6}QfkLZ@f%@8|^yL@V#yz_T&6_ZGjV0LVVJ(aW(#_-i zrLNV|hXu*H&M=peyYGtcB;_RDcMpnAFAUL|=+r#Us4TYI;y2PEh^J>8 z<&m7Lf82=cY42sHtk2)3*Hhe=+IW?or{SipUYMAh|;@ZLd_XG3=MS>{QiG_D8Q!RDY%q4f|TP=+}-jki4q+jeQymtT$XvSRUC=H6&OKQ* zYBm59iT#pQQtj+?K=yLMulz<{N2r4pC zj`%WtCrG8nO|S-s!ycp0YZ}+i6|AR?vdMCpU!~LjAmh_7Kje&{e3efzavQ@RbC~_K zbw(;wdG`K>e5+aEM>QvRGsmWsJQC^e!@T+nSd0$&UR_OXrD~!jvRzFyql7 zQh{tG^_6`tim7oXJmhIlQz-FK9PesepYTm8>fw(Tx<8&PXM&!UzSTc`v#rAX`5vf< z1A-`gUISY?B_0!l_b|X~84K6?g>A7V>m^!7@qyGB)1_Are8GYK15CjCQ(Ki5sp|~A zgfw=B68y_IJVIxrhZmF;58{rzF#?SPe7hxPYYr3nmW0KI&&$hfHC)_2i)>H~XK+v6 zzHugCPrQ>B5YsQ+3ZlunY$t4oWIxKY)!dj*%`2dL@7~g08sE)BH}!+J?pc2wgfIA> zm`7ar0)&TxiXzzQWG0k-#A<&t;gKy7{2t6U2p@2J(sIvS#Bw7gFpx8?!@5=$06X{K z6Ha?_SDI}+d|x@g=%oc#CTAZyOQklI6sb6=ya7fbdt+M<-P~P<_wo)OsIRbh&>NgK zexQ+`F`^0Z9jIN&lZG36AdeVkPokRiTw6{%OGfw!)>90Xh6Hju*6c}l9@op9@i5OM z9_scz5K5R>ka!W2$Y_&BGF-|JWI-C&C|NvUm$43?=M3P;IH8lMXJz6=uJL0~+(E?f zGF@YBK;}y1>tmQcM#rOK`(f`Ce1V-o%TtN+o#6B7t1}E{Sl9N6R~{I`W3=*wp0fVU zy(`O%J67#OnZYZ03|N1)X!=m1P#?h^1~y@93Z9rPBw6=Ikh7MpYx5b~a``-zm<^N9alrwKyP#9!Wcn9Gm%DoYS%Bwmacf(&Tz>i`9ol#%TkSpqb`tJp z-;+ZR=^R@9JAzBF@@s>JWSB$ll+a-*07tze`g5-w_%yZ&A~cN&w}h(s>ZMK5uaBY> z8}T(S(GE%PZY4afXm^P@45gp7hD+!*Hb$6ba!1gq{(|h?^~J}c0A%+7lwEdp6wBRTO;&>lJ0bLH&w4Su9^}zN2R0ds4aBLQJo$O{So!-TN zs^BqovaJNCN4e}TB@6U(q*DbmKG)3Tci#wL;`tPmmE}bi@MO)DIpKspQ+VIm+vg~? zsQ}4hxGIqvo)pkq2-cw?QdRpKbfob2W;a>M`$;DWoM0lsuoW$|5?Qbe-d?|>KFBQmB|G>WmGx|$Zc;+2sGsJS`j^fRH14mDX#tw?K zd7CQ78`=p>*2yI*%(Y;$VDLfBJJX!=(2W1+V2R@fL%e+bzvO6(QkIr@=iC z7}oB@7N=2UEIi;y$OC9Vo$S>~M(?{V5zk2Gk-BDuW;Ai54l|w7`K}Ey9XHbJT;b-7 z-gyxrF4zW28GJe8E?XL}+=h)6fON;9rP4VhEwM$?7}i`UPrZr^sTXx7Q(-LH2mib@Cr`AUGF#H((tHm<{X806VOsc|-iNarW+&kM{FTu?;Es z^5S*epew)YF{ofn937${oq&$oJ^#`*BX!-vx_nkeSlRqiMI|B(GR)7HQ{+nHmdk@7 zs+g`UDd!QXkLpVvN#N)2_Rd-agp;UIahpb);3EZ_#YOD`{i#;7@QH^Iwy^5<(T~w5AGWsUIHz#NOX7w3)jqCn-O#hO2TisNjvU$~!$-;9e zj`lHUm;(L_i<#XVVM)}FYM>anz`e=F1xZK;^y~kn8|v20oF>;4lfi!xv1rjUOX*$E zRwKT^zJlhCoY&7{j$`~^5HuZX?ysH#$nRzl^5+Mr5}sTSLadC30)a2rJFY+VkCA~e z@DN7q{Ghc<|Lb%?N7ow5*BLwFRp4$Io=LjwDRw(WjmRcRtpaVZfy*qogEq=v-fL+| zy3XX>I-hP#N-#1V5Bc(?q8)y)4fA6tC#x$OX)`s(hkkfLBeyfxg-|1AmmmvX6gV-k z(AyE*2?%+^9W~`~ANfrpMUCRs>E>Lq#HoS}Xc(1%dGQg)U_g5YR7Z0_ej0_c@>wj> zLgUVJYJdqdL(qK%y81BNDvizKCzsrov7!J@$=c7Dh#%QE1+r7YK?&HrkLb;FLdm@| z1~6pLUikNlZ(1M+TjfVl@=h(xcG+&1UUhUn9X&$I@v2gEPg z``J}ePh(`Fp{2l}j@kKiLbAg(=<>g=AB@qj&7@Z?V*6^F<*J;g{i-F55+qIS)tyi8 z&9}t~>}=$3>!X=qB_?%JBMYMSo)#mM>hP)@0?vgPJ14b~fhb7nnA zGL4o9?=+pS`FJ|GB6G{opc%5U7Ry*USI)$jAwYwknB!OVO>`JHk_&8H0L;~VUMuX- z7T&5M5M#DYZt!2W-^GK`DsmSsvs$oor*F{m5Y(k%(M+hn(f&wWhC@zC0eoH{t>N#} z$}HH)V{mG97j)lwAlp4s+dS zs;aGV>M(|LKn8~xg*AafNPk(@==AhaE7QB1Ep4qRdbL2GWxhOx2xfn0u5=R6L?Z68 z{oNaoPgeWSnGV2p^xtV6s$n3iq{4%PU}htii;@t{1TC zxFnJc9?`q&DTVkd-8+Lue;Z+tW)1T{y9iwwz*4+=-GHA3mpt&Yo zvsdUb^44gNSBH!Fv#Iz)<;XC3=&mYr7zBb3@uRgMUry{4bo3W4UXDF16S?Y;rXh?L z6GVQM0~#DFebHS6PG#X5$K{cQhBp{5e5;nAdHPZR+#M3 zZPS4GwC6;PW)$BG^saTsTOj3f`v|T^e%5XTxE%=FtG8@`_PW#O#Rbiwgs zdv71;1rf4a=qN|DW}2faA-5B#w212bl%!uTTg(N&yIm%B>mdm%SsHLf zmHG=>q<|gCkXf}Y{q5@kqq_B3_VX4B2gUE>4>lQDEq1GDtb4gLwmmY&Lf%FYorJ^} z9+p@9(Oz674^%Px)-zn;a%NoXhANkmCm$O?Y+sh!ZD+KH9Mvt{uxtyB3kR)l{t2hD zle%Km4?SBxl#Oluosp+MHI2$uRH6JIm?3Q%Y?@%K&f>q?KmCRqExVZ7kSz;Pu8SQN zr>Jkc(rjVrmkfH-FU*lTUT{`JQ@zlliZJiYAa6_HH{sbo=NLrE@VD|a|J(Uu+)QVm%6{^;y^;7b zXc5kWLak#v46vkvm-Zhu^4%}<4mPE71qvTUydzN^i?FWXqvB zrJu-FQ(HBEXR)DW>Yl?OlDlNL0ARLf5{;2uBtE4%?w2{1_nQy{{jm45oUI=cFTG3P zrpQ0F)LK=c{D{rd$ky)?7m%~maez16+V-g_ttYUQl8FxS^>;mi4<}SB4{SRI#~${I z*isU>Jn7Y5;|!i47F-43@*GU=ON6!}C)@OJkDlu&25h=dQ`-+?iHe^(%tDQ36j7#CmTq^{oN%km64YU@ku)ufpfT|2rxBK9tk-rsTxE~SIro9M!%?F< zd72oh^ycp3pyNbVv|D=Wb7UJW+earZGc^1%=?ADA z>kK$8fk=gZPzI@#vXP6WTmm5B8oXupY+1H%RzmnTKpHli}3Ih~A(FkYqP^ zTZTdO{nkfHMLL1-Kr)B>&7h_L&y8ICsJr5AYur7so|himM;>^)9)8(tA{~Yj zNm?taj7J=3ahta`g4z!%H1tBIt^rqq*bVKx072jHk<-l*h>*OiNULQi4IWu7f-8>= z5uZo<-~BhGnQ~XI?XWh7#DxYdmBI5Q;-sL31wR2dcA%@T4q2q2WguNy^7>SL0SLF z8ws!x5}d!4RU0E(>$PjK>T#I`*-D{v+n4EQ%b}2%nD*KWhqgq0Pi*l1BFnkn@|L=B z5Z%XK<@uJmB6oTdcNl!;>Bdt_u}%@=Pf>T(hP%mKY_Qe_9s4hoS#z9&uiZ^zoPWY& zFGQZi=ty=cGIc3TEJWwv%yd8QSxm5j+Wlc5;I*b^Xsg4k+Nk!fqe_P8L%lZ7rtHhs z98GA=(t9&ZHqi>hK^5(a3Z47b79xihbVy46l>qx(oNU(s;zleD!aDH)6Jo?jfPu+O8+S#K@a0w zkN~sdf+SVY;sTW%1)`EiK~(bhTjui}EC%Y-Ha99|j+|lba3&_q*^` z4?HyRkjsSKNr?AJdP>D)q{UzB9`p4ClvWzcwv+X6Ywy#BKSQYA0f5~K7U0h=l=&~IaHxW(M|L`IadsL4s@D~_KU#8px}be@BqMULw<*-83e4w44|D%t`@o7^Qnjzqa|+b z#jh(3&9euM?c8k8iukF5{Xvfo{RKIyvSgl{Yncu-*15z(KgzJ|#FOUq;1{Hl9Tdv4 XK&0Y0{;>>PECv6QF9LkZUmyPsc|b}z delta 81423 zcmbrlWmsHIw=LQP4+M7)5J=GAP9wpC1@{EErg0~WK!D&DAc0`PJrJ74-6c2;G%mq{ zYtYm0-e=$Ye&;^t*Zood)>Erit*SZ49AnJraqQ}G>>ri9fO~SFEFxL1>Dbb6r>JWN z0YNwU*)~5%Ve!26{kHQ7DZKu=WePR4ZvHL9);=*J5f30#U*T*cGIwMK)8a+c zI{^at@WBmMz~-hX0ZTP`SrF~8MwumYgJYOn?VWCt+qOjdDYA{~3a)l^eO070;dv9p z=r34@Z*2nff46&#%f7k9k84W!`gaqK*O1|DnVH;gydV{4h5eoe7poZ8k^61u7({x{ zIw9fJ-kYdPlVgIf?^bVAZim$QO=^u?7Bz>sREEbg0eS74 z5=IHOs9yG&^S0FWEM*o+XL<$X?>~UzHw*_jzde9(@a0aZ)|qC0H?74JI<&q#YKvAZ zbGX1Oql9^$f)be%LXt3cb@@}A3Bc$wwCLSg&yEh@g>zS>^!!fr8t+Z00d2T(&Xu$^C7 z?5M9^T9?XWB{GDQnKL@f!j4wGll2@udGZ$UpKptYoT+i*8oUm0D4_h=JFwO4ob&hX zI){jRx4XaRmXhYNSenJLdclo}$?Wzh$Y^%|uQ@RbCF^>KW)Zpkn+H%*R}L`Cargj| zkE#a~?aY5%5HiP*jj!-p#0)=g+_1xpt| zWMbjypRevlmfS!j59+lEbeClXVOv-jK0RjtbjFC94jPp^X#<;PeQCVBv%6g)%+HcY zm)#N?LghMmsmFq%OCAqX+( zeNTIYxX8>mpz!}J9@~**W7dRrvJOy#1)9WH2;4^95(t&Pe-#`z={(hBRv>dUTAbx5 zrdMIlsWfJcY<-fo!#!yh!E-~R7(2rTm3^ueahmf)E&l5B?%E$WJO3fN`^2Gf#_fd{ zm&ikvKmd05EA`vFe0a;dTeBJ7zOsO~06AEHTG0Mr-&0EUH*2=8fihEIyaa&$8+3-9 zxV-bqeJ6`vjb2(U)rgmkuhV8o@+849$!#iFL*qHR2^AHY0ejG~K*zO9uG>4miazp@ zrZ1cFWD!;bISKWZp|7W%g)(psYlr$>_N{MfI#)km$4T61VGch39{hOl=<+ty_5oD2 zH+uIx3FgGvwS4j<q_ zIB~>LTZZoN)2*0Ym7}*KaLHD?j}FZS^4sn!8LblX1T-U zE=^4A8cFqnn&99>Qz>bRgexvu{A;&%^r+?f2T)>_CTcCTRd)oBg`mJ+TziZ2+vRIb zA&`B?VG~&={u2JYjs_r(4%+^_0&g1y95( z*P640J~<52PjUKZVUr_6t@kWVNJFjk%K$quarE&*XRz*SC6w-b*pZntNX&V4V6`c zeGZ;=9{e3F`(I){(&}!kPl_IDJ7j^6daD5X*h11`>1kf#9!Y*V(`()@dF-=VSZT?C zC^ew>#IDbreoP4bXJ7F``QWyiH;ul0;x<2lKpW?e<3Z$_8Ev=Q;I;a#kF*Ms1Ee>0 zu~3f2_$db)=#pcU z!uM2Bm%cfK-xY0T`sU`wj90V1t>ufn6O>ks>mw;lWV#k&vC`CdrGOFJoEs{inS5d)NIyatnjLX>tEJYn;DPL9jWH#B?;q~6S^uHg9ag- z8b4;vjGX^)LpGe?Z;m>Pm2V`AsL_kiPbw>a@PaqEQM-y*e*o=BPPfTW>;H3@b{Wst zogP5BqsFil=mUtw9QBB~aN9NAId+*0CYiPjb+VrTJz!i5($+gX+!t)Zt*WYIfx|wi z4RA#~&RZ(d$Itz|L7ZTZW?!hrF2d_A7s*i|eY9?bjz z`sgG70Ln?m6{8Z&Lg-bu#O|KCUZ-!lSMI@4UW0TeA$JQPcFMtTK- zt7=48L1IjLUs;tc{aD`?2mj;~1rZbm3;bss`H%0fFtk8ArV=e1sj}5&%J(s0U|DFV zt8pt%YKt&Wczs4{%$!0-2bfnr-fD3N~qI0cc!6={*yI>FDA!)Hd8=LdB6@BmU9%ebF85;`}C-ggKP?#X3Vj^lEy1 zIFzCC&f;kd7-|u|k;@v@j~c0Bf(fujyN1SaR-wV)5-GXOz;3}6CRfp27sf!#56&l3 zax(cFxd%lHL`tisffR5W%ANr7`nDirb>l&6Lh%pJ(iP?3$*s!qiSB&+Fi>8G9E!)6 zU9-TM%S;nNJf9cc32S<0!tjAg*&e+hzVCR^!8=XgSg&X5I&7itI;c@R)HN~rs~R1K z=?lp%c!iTa0}IX6<%IzS|E!~)alrQlr1Id6d`uoEFMdAyUxw!~JL#CIX{%oL+NrfbD=3iF zn!K{j1LQU~)l~)%1Zz_Dn7KBwK|Nvl`6+ZCM_E*^7RbDH@O$x%vF{#BsifNijR$H_<2=q-JiP zYPAgY_2{i15*2yQi|#)w8E?J*;j|h!Bi#E3@ch=@iprrMtb`KFA3%MXZFhh%u=C1m zYz#xw3CbGF(m|>`{w13Kkt#!3wx(mrU05FK#BiYUCfejJr(6`svWrCZB;US9CH8>q z(dH`Tce|if&owvG1@2mv8anZ|%`law9iYj0GK7e)VzS znx1#;r)x43i+y{Q8*qq#{DU1Ra1uAX zBFQ)VzI4d&e)y1W&M9$E0ztnIO^4oN_T38to$5Kjn1?zl)uCWWZ!miht(xlx)Cb@Q z7r%Tl&#!?^hoAg+a#?M1qk)pw%6T$`Fnz4VIW9tUl#1No|C|c=kGaIMqbyn{YPrSV zD8%Jf8qY7qtO&kJ(!C)m<+zMFWUd*{pJY9P9aI#IIPdY#<8;0X_Wb+BDo#<{vIyaF z%d#fLu&y=*3ldgy2>yla#?Pk<*U7?RB63Pg)(D8UojiEY^*7y$r&mFE$aP@SA)`v; z3K#)dJ2l!w#0fDzlD9`txQ^zVj##mX@gp0{*@W3ylW?fFvi!=p*Tl|8bUJ1lzd2zw z6z-`*irXcWnUV?G{?z~daD8o{f?4#j{M_u(!Du%HQP=l*H3tkvCq?{9GWVXJi9gSa zg&-`Q;_z6{DstXWTud#Kr@t{8V#@bIC;=Zy;`)`F^@(8iE58TOQ%0Hx&}^5;eRSOS zqgw6RK%L{*uqZBX2zkL&B2#DnK}G$C*&m>6Q+?NowV%^MY85PNkh)BQJa2@1d*XaQ z`VY`*HhT_v%WCc_^ohyBr)DJwA3s0dOdmgw09rMPb!t{35PC2+NDKR&f(`0d{>T1* zzDkpQBRg|8ri4LT`v9T=O_f&>0{z0!>-%OD^o!(hf_Nym)EjbpnNa_B-jCz_Xe&xB z3fd}=Up@SbHSz$mKxAKQKLa_Azy6x9%xZ5%qDuBz4k=IPDuCQGtP?MU6&v+=5M&fN zyImUJ%M8kPya6OpKPW^>0mL0wRIy7F1p6ayp2b`rX(MwT8jcpsA{tR8m`0NYhe+jX z7VKiB)S(Zc8-I8-_}1;w=4KkUXj9J+mUzc-c19q|S=q4(S0E7Hi*+n*u4Y<=k`D+<3ui0jlbTxeZgnhQBMn+@s@`U_7k| zJg@Jta&5Jjt&kF~FtP_w-pIEf`YiEQZx(=lL=h@3#3Jq^FlpeoA8UE9@1b|>>A^IY z>1V3+wE<$f#0^Ys&-zE7$@i8j)2;m2naRAX2zUU=T@*Zk0PeP{eaCSbx`TMH;+^Yf zVV@fTtegoGq!Q`pq=gVY8PU5#4USP{(T(Ojc$K>C^uqbn$HWEsZC%>MEz8YBPzzfK z;>JB1S+!&$wohe*e3DGY8hd(rB7py1Y%TZLyHQePRb5H1*E*bKqf($z=Om}EiP#|f zUa{%$`nV1iindDAe}5ooVavGqns4arGI0nDYVmOvdWTO5|(u zr^@&Jw6o{F`qt0XXAWPRyMun^kp32kYv?jiFLHFfqS@=2_Zp>0EuHU4@?0eQx)6Q# znFzc@j_^&BsXLYq^~hh8=uL(&8{XeKms1-Bbv*iczKm&f6@IGP*wT zhSKLX*W$GHYD@mOyIsv7q9jFI*?!d3iTpGgfOyd_=*X20SAON}dL*7cWbvqFakF{; z@RJv}C8yu3@%dqvIFj{T8wJ|xDfAu?pg%FMc-2%~TUIBZi=<$P7!I6pEKXgfYL?>u z9+q{`xx?#yZjW$?f#2e>2myLWK|P0&tOzcln??TLCf0QcvSb?6x=GU4S-;D-rAgr9 zFx+#o!zv-EH@@APe!lHBy#(G&T8}FI+Uf1lbN{Ik{~49MtMRwdjS+WY0IGa+sGO*e zhJuz2xx2-IXqcLs(E)4y%N{Z?rv!yFpIpH87#4lj2L>2rH<-`}jlQ@=h3n#|+Vsox zFDX7I^AyV)LunBd;}PZ=W2tT_%afletbjH=7$m@idxe1J*i%T;PD*!KvT~Req#9)h zCMz%dEjCr3m(uWtItv1t#Jm2(B!eeQTh5xX30RN=(!1XqcbFjC9V+>;0B9C?i(J{<_PfV(LhZF;(KG0HHsMQvWM zAC~m#=${edBDd4v;xTZze`<+)h!`&~9VLz!P7a9N;}>WTkfFA~{VdYCPi^?<@gR=W z1IYhuH2mGWn&T&#^*ynbOU;bH zBgyqfgg|9WXnH%HJ3ivFE z)P=B;3fg=rQ`KCsUEeZ?RVk36DekG%HGdo7f|qt%5iO07Jb;#;x4%!pzGa!QI9*2Z zIvts#4og*ReCu8}V%8U2r5`s#m#c0)6P8wmV z-Pa*6EW3FMT(MMGv)iVUR4xS%uawH$wpvk9Bvc~%UQD;P$xQKjLd6Dg4jS^1l;QHe z>QvnZZ>E_(A8j$aA80}Sv7yT5}RplSKAf8LMtch4(u@XeN$W<4sn|Ku`^ zb-?)imlc6Qk%TPu&c0r=`f8*Ql3onrg>D5DE)+~xjDBX-+AVPHR~}60i-`ga&A_5( zj?LlUsj+8uy2AH$>_@+tE3ixXKVSO+1frMwCQ4H0$Wnf|y^(bysaU><;cR#*9aNO{ zZN0)%*c`Xb%yrZhilz;!B5r+S}v0KXRJx?9>1_qT;CaRrF1J)xP1@I zOZT`W_%#Vb=lQ-_ub&E{m5jaBRv-iY?}3)&Nu?Q`+->feKr ztwaI3-;t;shRS34r}`sSPHo43zXOOfj!gpMRC!QG%Bk;fNXZN_?ns~aPU|kO|zt1Gq#_^ zDNEskNM-0_b3Piib8nn75m%+&TppOZ`uME3`KRZFP*vo_0XW)LQ9?MM^3ZhgK^&@} z=ij6LV~ip^KMCz)-Ke6lo}LfhD-G!#me6x-?4v4hhH1-;H1*E)Q}^_xT(`SOx6sts zgp|zDyPx{dE21i`N=rnCeqF0b{W0@G|I%AqHMuFX zD#bXAZTxJXQ!`4*_nlJW5J_>UFVl0~vw zU7`S$lAP!$TN5KO&|h5!AigbMqm{=>bov}!eSZSzBC_sxY3=F^dun>9^f}x??AS~j z8(S=eoEF^{CtQxp=UXE8!S;_HKo_vXJG}X{yIWKmUatk5%u(66r33($hoJWo#F#{K|eOKTmaF!-bJ-wznJO3YLVYCcJujH=8<)l4a6_5CWWZ*xCgP=mE)C~KjQ zw;KVBiIKwDavjxNbA9i`!MNy#0nv+J96i4x3e6oa{9!%c+%4w9DNgA&(eW9fzv}Ol zIvRPtS~G0*h=*nUWG1D^^D1o=5Iy`+*V(|rfh`|3d>l6VsnX_1b%&;$#4!#|@^ilb z{iqMCHWp_`hdzgrl!z8~?(Q{PMwKz1nZ`K4V`)H;Tl4tk_FxyLX1(Adqs+t^4r_$k zPc^R;cz=7U1MT$JNbaljbr?We*_7uC)|uQ)Uodr=Ia-jTDr0%q)xAC&C%e~C?75G{ zNOCpWvkYyWel)+NK*tFMxKyJo-?)+o@5wMEE4Z0crC%x@rxvZMRmiQ~&vCP~)ua>c zTn>I3)=tbQdl!Lm8nthq-0sZ=pmH>N_;G7|kXz*rO{aZHmBWP!$57$V;-?u@DSE92 zOpjg$`If$?X*rrb=E)5xoVBn|PoE`q%Nup(?j9^+*2;PJ>81fYx8jh<-gr2Dv#x1% z@5UGUJs7D5^)DaOq=s}!_~~Oy#v4bd9o@sd)(pKKKqRIP_g)oE9ZpWb+e&Tu#D=fg zsgh_hXfjmNB$KrQD>lbIpUPLKc)c)1M0^BHf^v^Wf}`qLpHtDw>>C*vr$$0nz+}c( zZ|?V*12Vjv>^`hg$gNIODN@UVVz2=<6m z+A_VX3tgkvG@UqXR&gu*D{j8?G_G6h^fxCw-~inPO;kHe(|8*wKQrUh{4!!wXoOTX zaPWPrYbnK#t$_(rs8as1Gp^bZRj^q`6lJ)g$tWYnKI>tS-R=E6W`rRBQB0C2G8oMN zgdLq^*ySNnfSDqn}e^;_@>F~S!*Q;XFQi_Ar^M(qS7?sU{GDwIaXqj-$j2x zb7E|3F^!20^eHkJFwIj?RGIr0 zG9!;(Vi2WE*SqVU4@4BAxOSvt8hE~U*8ux<5BO@#Bi`c!uhCA2Da5Hbft=7m?xri@=*MFFPk5VX+>uzEF(SCq-$aDySq zq{NVe?w@?uN%rV85KAl+I+{Q_DpKv+#UgKn*Td~T7WWRH5VvtO-?LP|vbFbOBC}2| zTtNH#xxK>iIXbD*RORddwCrQl`Vi%d4<9z++UN2o*^r_Z`R~h%EyqrMP9y_Mf#M*-|Kl7LAD}YkZZu3-RoEWuzXi)b97o8b7>q5 z^0!j_rUodIW7bLLtx-Fs0h3~$KaTmG$0228fQu_?yY?-cH?Zc^vH0-bw zEXCOsVNT3;p1N!dG)OnCW87W$y?CL032s!Xrxj({Q7bZH%Pi`!k1kF7`5he~scSi+f^%--S@*JL#5ytvm~dAEOwBV$8z)!V;m` zqSoY0aT1dx%lc!UqT?_K_|J?M*Sic&_wMH)&x|BjaWA%DadD2ybVOBQ`*l<|+_@pq z5`!ZdiIJ79Gh&?cDC&6*euc@soH6BpQ?p7DZNLVt$Q@vgVtzh5E}xK$we9_FJIitm zRcnDw*5Wk{&8@@h!cUGjQWfV*F}uGd%h0C8^4_YPLnYm;0#|L$qO3aMRJo^pluCWibp(>na7o;^mAaE<(hyBMaw98y!rRCVqI!S38cT~H`n|{oHV=s z4B6)jrnDT{m0@RVSTyO&BCT&u@7&(4Q7KyFmrPBCgBw$1_5ZFj!~~oPqRmOAw-#X@ zyVFovf8@2KPe^_MCG?4GDNLs?EEv81r8_@ts|Eh_W$`6|&3;s_PQ#7fE$;3}qfrp# z<=9>9Id!0jvx~!<5cCPF>H(C@v&5e~xyS-MK14D1W|w!qNMPGzy5t}3*ZOVZ_f%VU z5ZcrX1oll|nyoF0E%WmnQrI?gQ*0UR!@3@q$w|5rxAzJUY2^sZ#8CL7rz9z^Ca(g;Jdq$|ms>i^b0XRCl zxKMdV1_b~?X$M8O&#|OTq#u$rtF}f^3~J+Lxbs;R(E|uVuL>q?B!k6uFoW$xRmjN2 z!0b@R@%yQWjwQkAb29~-`%c6gyid^e$jqmSqz+2+xTY~gZt>e_4F%cc4vlB}H2LF> z^IqMrhXAri*dGv#oW-m}vMX_byI8pRn>1Nw_gnn?6yey_5}`v33njb^ zvo{E%riLF4ELbmI4WoGOMt?>t8495)syzyGn&Xx~q>Ahl&{RA*D+~@Gky3m4Fukdy zDy~_qP_q>EsSeju`o*^C<7W?`pFex^xM9uG?N%OrKIMltaP2-=`)_b zibD~z1YYL~T)iXhAnWvA;8WxCqxpFUb&ulR3PcA#(HgNycgXrwaI+9#PTW@`eR3PSmCS)DT^^^++!}R7k%r^+bw!M$JrB!se8oLJQXm{SforFR>o2BWq1`ECh|GnFHUBbuCx~WtwqpHW3Zt=SEl>$IE?+g9Kat;PGcWKPS5J0yEQ^!gvnj}AjXkOynse%WP}^jf zY3SPiRUmX1tlD+-*|;aZNBJzs$olh6y5tX&r5|g*0dy`~VfLGL8_mWs%;m@G>s2Ja z#*=2z-4{5QXoK@Z1tB?QH7kwvlKXpc=hIj6-TYV4N=YV7UUgI4Jk~#(!)Q5@pLRi{ zKN2a;)B_Q%;z##kC<5a3#;Gdf(>&FkkC?^299 zxs~k-NH{XuCcIl!YS()=yDE!{>f8T^)@M3X=8|S`Eyyoe8tXg9r#cQNdhKh&6yH7* zk^Fm67}(;e@XQb!=C5lV#`3^NoK)SNeT<(eHDycYuC4CkjkHWjC{=-LLq5h45MncY zM*I06{G=ly-B)#ROR1(lZc7KjJ)F#Em@~=h7OcFW*0})3j`1FqB#7Pz&S{Q$?;nG2 z(u2j*IfJJTB{g|k*y2}_d(l87q#|kex6@WQnbu~AA_&gzHs6;3ssQ7gE?lL_MQE!# z>A@3z_DD5VRNLDqa%^iR|H6^Hq!L7%(KZhV@L0#IaJld5x}+pgDEdQc>PRC0c=%6K z-7AWPEl^DLIy-%7tvTEDIRx)j{Wy=13haroiWRYGP^M)apS7}e;#)xSQ9eFC+!1uv z$QeBDWoC4)uBm)XQSJ6FsHiiIR}f|AA(8uw)+PAZ08^O>q4F$0(NEeg3aT^uHqnJ5 zZ`hLm(fwX>FbYsX#?1||^49mQ3}-58)sWt>NvQE;&_Z=y^I`v4bXkjIr4wu*uW$>J<>_-JH3El&5D8H35oK_xBO_)y&np#UQn zXcCmpIgYwhZV8gJlx55(**7{o%rC_^JBICGIDdHi-ah-kJq!F3i!hwmGv=Jl4WH-> zR&O{fgZP>EM)anfUASTN+h9cGe19K76_nV6BBw)YHl` zB{+&vna%x?vhmDaa6%nj{DmR>DEGr3CF603M>nuUJMB5!tmugx5z(qQQE04*UGrsw zHZ&L}=qAR*Sk~W|X$&b%N|RgcioAe0kO}-vYEu|##om=c6(mmAK5>VF5Yn#XyEfar zCySfi%1dU=e3^Y*iXx=Jm>_?3l!*S1kdDdnQje<}gry=?;>h_0b2@+Kk1|Q#Q>xuw0ufN?p}WY-zQ@!KFh>j%xXSHFQU75YZj7tl2i6 zNpYTM`Oezyb0Y4RlRtxkl`pu*-yrN(0y`p5$&VtfWXJKX?}0{73Yvsgz&&ud<}>e0{38 zyYa#jdj+@Bste_2ILkDj)NgEPg4c!gp63u4uJqNjx~MRAYp!0;D3+|nGImP~9lhD1 z9ADyCRA-GR9IpP2-C6yoFZ=UpM~>nm)vc-txhl!h#g80;jQm4LB)G|Vpwhv<%MH7w@3D8Ov|DZrl<{` za|myDmgrH@Eeqo1VoS2R&~V*tIgy}(cLSs6PjXsKNzb+Vzqhi5bGJlO%~C>xv9^r0 zUC-jB9kZprB(=zei7if&q3z%S>uSPR!An%jM9d?$gvkvBT<>37(LGCLzkg{ zMjpXs(D=TnAhc|8q0h~IT!n4`2g8patQV`{9@^rfg=XlV8C#gU1`*e!MH=#0QuuI@ z*mo66tWb9x4&3hkEMrH6nlSVHKZ&06k^W9<&Y#dB_Pr99{xPX7wovkGuXisO2h2YCODF_MO?tY@p9NxAa<`1qoW z7Wtaa4jW}S{mT7O`wDBl3ocDL_3Su9;DcwKhS7mq68zB~)x4a(Nqgl|NTKjWv3<}l!KKdq7^*SJj?vWLN!rlt{r5A?INnU7Od5NqREWwzj?4l4pg!p%&BUQdX~y zegokr4hG_%3H`i0BspyA;HLN(Vzjg0JSO)hzs)q$m+WRqp*Hd@oOqYU!*F3I`Z@E` z?^iJgZ*aQk9yMTZa?h9VEwS2rjpAQbB4iNOjW?VMKDOzBF`d+e!};rIxw5p4$CoMo9-fQH@NF}?pE|aU$WzPP z1J7N+U6)6^=s(6KDPvj15WNI(;gL?dNV)9@qHXN~qo%X@R62w0|>`OP@A~&&l&uO2g2IVwSDl}sm zCi<+;%YY_@CMp?VKwEmHq}v1>Bchtsiuye63JMpEO;LOdPRJglF_P@jOBHIfuG~Hi zd-OsCY{W|cm?3#Jmc&8utIHpxR!c+DGl!gDqFg-Y8Ae;-838vPCmxH zk)?~=q0yW2Ld^%bu_@CA9LgOSZbtK4k) zW^wD1T|)D(4QsI$H#&Xk4DrH=WwBt5=BVR?yz0dD)S$LTt@gJZhYQ02G5+bGGk=cM zsqaU)V)R(+Hc+OBay3=`*QYSbpG$4>} z8KRGz(uT=deOVgnAQx>@wcA(ACA-4j(i8|7+B^4|pXyFzfPzRd#)mZQT>7S&!-zoj zqN}W5Mt_>OH$vo}^uUH~#c~n=ypnB{Cw1;09+MLl;uBKC{zup_z+F44*_MQU355_kY9CxlKB z`4hbl59aorxIRFt)x#MmA$Dp>b0c$Z^dj+iNo$-p+tYkU_KFgD1tVQ zFAnzg?n90OP`ogEtJwTQ?WU+H9nVZ|QD->NI;KP_cyB(K_exvj4P%tFXvi2Q4CU2M zRj_Dew@11$Y(UtW1~+acmxzu=Lg#0lykFZSj7Xj?=O>Lm-96|&ak5C(w&Y2}9YkXV z$d~`6$d{$0L4xdxebetvP$niT3hzO4YV=^AUv7!ZiGQcATZ^z_^OhWal!%NwC&BgF z-v~V>f_cWxbyljqR@;ajY8**jpyWuYo_6kRo+AO3c<0_5x80On9~8sV76<&nCcF>j z2Kft-Z?@r`b5=YaQa%DM%3dTPwX5SURqI{;%1p=vO(iMapy-=X!qDO?wf0u}#6@Qq z=MbVv*Rs{wO|WV+No-z2;4FvG=6iGR$qXZb6T`DH!RePfKGO85cif>Q3H=3mkl?$q z_7avUgJ*@P`-4)`J~EFH^4||H}UADi`OqD)ZUR%C;PX?eJdg_D2z_k${YqR%b zm*>GY@%yy*7k7CQEq6huCjXCG2YN%H)u95)3YBu=?7l8fXAFaxy?OS8yP!PjdsbLT zlED5q1Kzwq@i7=Lq4DCL{(i9|Jb@KKc{12*!58ixo1O5;7oDm-hu}JD9Twg60Ky6s zO?);5Fus{)i7`f+itqc`cq17UHI(}YMkQ3rm(fh(ah>3;PaJM%)oTqdTudZt9=#U0 zzgmpH*hU}Qu6i=5*_Bvvm3>b#iV8!3i<$Fj;K-8sY7FFZ(QLVk7<|E#2j91t1J9EH zHbG_HC^F@(6>Te|VKL@33bYITZ$~TZ|5#d4Wv&<04#+b#(c%1k0HI~YH zNd;lr?Eo4d1?i%bv0lt?+7^w$B`tx?5%D~$ZFSkSCn)Dua*GrJ8YqpC0F41CymD0j zJ;7j@X&rmWGe@r>kM8yqgJBJ}jUHb;^~d@BQ>WuaGkM&Gn%c&&eAn;Fh+%!EtQ;bN zb8@xS#r+C+1k{VO>c4#mqJBZreW8Fj^KP|H=QD}qTC5Z;TUwXeCZj+ zW1HNsr_(*zxzOpt7cfE&kl_PWk0oWwo!dN%SwbX;CxS)eNv|5JU=6qId5+$Vp5w*$ z<5LIE^e9TZ4qoBX7O)(d-=3x4bc<64OR^U@%(EwYPue0iKAJu^GIalSVuvQn`qMw# zfBQi4#p=*dBoB}06Ar%(i7XZ8bz7@l6>7FrO*~(JCtt|sm?u2s$&xMrv7-U6>e=r;zLJ$C8ogk=apioM^(biJZhCf7%FE zU@akj)>AoO^~KQXLntwhkzANQsWe!z1+}q7JHiwY=6w&Sb7Cq(1jt&~`#trT;N`N- zcZZq%-?$!6N}nzXgs%Wz)RH&ppwndnU(>xTmgAIm#QBJXEsWXEKWHqH_R`*6RwwzF zz#q=Z+CA`}J83+54>zw(o@MdP%l`X6uKW&1#wNziqfjUrx5VG1FJmtfuU(wIBni~j zWvCF~W45W-lVdB-4i_c+{Oy_`!pF-W&dbs(P7UX6SxL-PJ2?U0(c^x9yIFV5A3~0X zd0CXp#k_|6HTp-uy+p zNQ9T@_vv!$#QkTwuj=ItKQn;@2GDb!+$HCX(E=sceV;s`gxyJw*98SpZMa*5MDQ^N z%~cuFU471C!vPo5-djO;g6euPeMUJ<1K13UxMUjqOV~b~dyv3e{2U!2)gsFP<4LJ- z@ZZdBoPgmu&7yS#_{j$c5r{Kd8O_Wz+P3%*z>0SH%nTdw_gr?5)tO1iBk2)YQYf_Z z#ygnDf#N3`_ubllb5j?8R$xA(H@J&kdSfQjR&$M;V!l)D@43_S3YO39r_H;>*4UW1 zztFH_bd90Wk`m>n(GU@{NtXkh{wTbBAC_$b`$z0)_;_eE$*#kKz#OY`o&&4bD;cA& zaUk>(wqSY%ceg;5qw>k#P_0DE#7-rTXXPd6)uQbQmCJpi6)kpVlagR-o^zA_{ah|$ zHS091aXm#f#_j$AWqf|bN!4mFn^Gv zNs(n`mZEI5!WO4p|G0K+Mjt@5D3XaYEn^fFY)hS#0kQZf8_S7Xu!mc3CbY^}El_jO z@B<6?eZS?`3Mi$iZ#XS3+xUL1S_URO@gVI@l5B&_FOVKnh`>z6;_kfOd464*x4|iL zxPUcEontj+>KudWZ>5YcZ-=O1)@V1s(Tl;^{Fj>o6PuOc+gFHbK-05(mDl;60>R2#zC%;DEcyT%T5Jf{elVYK$HW_3V#{6<`IwYdj0d(==k%+M_QZkU(|E&_cTi9 z7&cyjuJr<{9{WlkYB#k80K`h%3xy8de9PUHTP5>3kC(@-QS@*`?dFdO&!HO=8%reV z>ju{9U6to*jP5Eq1gTMjsM{4jbnokEamCeuGDvt9byK`ecsEslHpxSHKbeEIhfji9 z#Vf0CcnEe73UM<`deb`qt50iCjV3f{_jo+O)uMiLTU~R8TvNFGMo_Dk@hiR*PK@0- zd^9SixFC+v|8Ph@3ePQ>n$&6doE_8{tkPp?e3jj;PZJl{$~x)H{pUPV@{{q5 zfnD8~5}P>nt|tjNgO`l4>gy&*DUWuBr*#um+*L&s{30n(j{ZJ$(avN9Re3h4lRq@d zC6Ll7&%Db=aK4uE=BaDX(@3MtFN96AfXBjGummBg)7X_=S6XBDv0#}?sI#)Gwf9p! zrRh(Mv6e=@(H1`tXCngLGva}2rDf3$=f~mD<7jDcplmFYw@Pb=SjIb)Kgow91iqS1id znm3Zi$k0&SlqtfVWc~>Ww5)=bRa|7aSrzZ-|NiYHMsL_0pn@NlACB!n{YOd2uG5^O z`WT1{r6{wcMkh%^~ZVqmeCjzgh!WwZPuot}e z@^7hhSOZj8@$InF7Z`YdWau2-RTMjYg7w>`FL{aT8BUud_-*;DM#0z2+IJkE{*4c;7o2P51f1airU@-=t`+}#BuLN=XK4gOV!fq5N$>{26LDcv5zo-U5Kex z90;zR6p~^zILgYjvk9>C#^23mN?-h7M0T^Xp?}b_mH{D<5S_t=3eox{L&Y`7R8|K|r#uA1-? z&hKUkPGzYpZt9Mdm^%^@lhhm_sqr6u2o1)THTw|%c2~h#On;n7x;CNJ?L<5FYU={8g+AYYY~DJ^RMH`J$RyY22&m z{OuV^1I;`q@5%kz`piO#Q#o=tix?N0eh2m5o86f#wn=GL%_;|)M~-zrcM|96mRT{4 ztZl)*bVmwC6P{*1`o|xo*^cR9uunDcfB-xk_R}azmcTgND|A*62z8iY$+8se!2gE= zdbTp;6lBuf%5#jB_h?}m=~%OK1Xce{^;B=Zm{1)VDY}=w=LP+Ldx|X`rHQ91&i5*y zo!5g7aFN{ia}YP^mdUTdmyFbyCiKdZV_0?(=TJg3-+L8^U@TN+8e0BE(!g7B{>3;I zK)*qJD*8)c+s!nh>&51gV%X}Pq7l_qfQ2@FhgG7TPkm`yjVPLCE_#7KN?+wxk$lzq z^cbs7=!u*t%@R($KTfz7(se|3o2_udpKlgbJvX-QEB%_0M1OFRw zVw``>81}cp(tFJLL2Av|PfRf((o;^=z*X*dhr}yV?Wt8*$jk#sL)Oc|i|ie1)GMZ# zm*+e2{uR)p&fUrOAHMIoJ%y%dzD&KjFtMC_i_*uJN2N3z&zD2a4~hKrTiK2U4gBBq z*Qi-Jyk(-q)R1eUw1P8P6V#%W*hwtxxtl6CnVa#C%mv{(M3R^2BIC)I{%IBg{=4`2 zA0yGf2mUAlN|&h4M?LZld=07)A3i!nNjI8zekkQC=ka9DqncYK%oId8j1!`|&-G`k z&eyiy2Zu$U)+4#^{dtKV?1?l&Z?ck$*OCNjs%Vu$=*5B+EP3((x+e+3>pXFozmF`u z3hf#LOg{Zi8q~pGk|S)ka=``JJyueMW7MTr^#n1${+p`p8?f(h|2`v2hB_RGwjJLK z)o)w1Fl$M>(7orKu^Es0YdhZDGQy}HuGJK^9$(<>WKJ{*iw+=H%Ie(Gq^fEB8I&Z$ z7n@hiAp;6|X^)QAW4r>NK07Y+RoyjF3sNNqYNr$iF^vrO^&iuEi-}>pT~Dt%=9T#& z{J)5M>!>LEw*7ZTP*6&cP89?tr9rwux?w2kF6q1oL1|$Gq>*kUh7P5Xt^w)p&XICo z-p}*y-*eyZ`|iEg{%8Nea&VSwhOgIfo#$~L$LAcjjbn~mU^z=w<%%QL(H>OTH4ImF z8As;$-%Z#*pI$LKBF-(&Eh*;WIYtkCyz`@q`HjQl(*b)_u*CZg^0&ImOdS!xB&2 zEvv~nYjS6xPHO+41C(!`M>mi|He5$yQHd?sdsysx5{qlfPIb5hh5RFN!mr!+ei0se zZjF;SAhibaQ_u)*K6S4C@~bf=y)LMzj8Li!M^bgtQt7XKhR4b6gDHekh{=M14KFX? zZC99S1GRThD8o+p^|b&xVXU1k*$3?^qQ)1wH7P=XGhL5q97C3Ly>Li z7xm!nYLl9{!@EJxd5nYiVM3M6bKcrseaC?2$%TnXF3(2dmP;)w$?zNR35} z8w=~CR^XEcwVr6oH;WrzXvFVhOeGrt%JPVbQmN+Ygh)Q%)8Zxm>En-nVVT%`&+3A# zd?h&ff{vA0bv_?a;sic2t-wIP^orVo0W-?9z2`!V=f`w!(_IxY#lJ1C_=YRtN;^k0 z-prL~C#b^|I0;9p?J&NOawWJ|==>D3hCF?)B3%y>6b2xwx5z(v3Lmg9Y)$Ntgc6|J zYK21*>m)(x?a!kh|M7gn!nJ$Z)LeIg_4(x2P<(yK%1q-RG>Ej{uM$P!1=YHQ?dc7p zR{3JDm)~h?AM|)hlYKapp;3{skvrYuVxb}ya?v=>lnTYvWa(pHQoU!gnvTH*9aYtI zohn-zdlP-TvPU8Y_|Ok?ECirMrwN#87X9VdU*9dUY#RF#hg{~PM@%@FzB6D{|*T2X9Z_Y|Z0cSFqZJ)*9p(%B(vrtM@;TU~{Md+8{;YzC2* zt@k3)jNS0VfXBdu(wJ!T*Sdt|fodjeP~z32dnG0fTzp7jI4TPbhjhj$A)i>om$xsn4Of6f|$w~m-HVs)i%gCDK_xf zbN5O_n)zP^hX-9rw2mXWTj3Io_-Q??T;Qbtj4UPC0JuvCedih_+clDOs!k!dUYYjd ztI<`5*PJKim1ay8SVWyZ8UqfE7{K1J6!sh~xkkR@h#S?Men01ms)n3YK@{iYC}?2F z&;_OC5#tti>IkOZKeH4V5LH!*I>D@!Cc5i-MMCUa|HEM~wI6R@Fl5O+*U)L1>~<`|g6> zxaqwA{>4d+KLZBQj+1qb)}@BGzWXM#8ot91w zpffl!Ot$~z{d&t}4k!E@O9#%6U&ii#-Vq_R@A^4E$}|fcm_0W&++8+imF|ooySZx>8yh@YFO9NY!l>hZ(01o3JE4#)mha%zj zZsqs}GQd3q0c;3Z+arEt_9+Tzygw+MO<$XGEB_Xls#~~JLrmC^8zdCx$>$sC(Ve@n zc86W!1GhfoT9?#mwgAp4&s0O`xNc7F&(GqR0$zg0&|dIr$!OQ|AZG|@5?C={rH`}a zqh@(M_iA?fSBYG=yK<9IrBLx#lz|)0esIy;3}4*+vy@(1=aKlF9+B9xDn+nyjpAW> z)i!5b{eeg}kPafpP+re9Kr1=sibZRg3wu^7S>X=vQ&@4{_R7RWXx7=@klCAuzld6~ z_cCS8zIbHGNG7*3tM&fxzh*T5k)}(8l0t72orIuxwYMZtDDf@E7%*{ICyFJg#@&k;ZG(Q0R4*&KY8`h>&GWn7l3(-&*vx6_JK7A zu^NYBRGVm}S#>)iB)uTvq5YPCY>an!x>BB)pZB$I<>!l!rqpLcR<|#Y?$!nv^Sa3R zEmM>loECe;i)X^U4EhQ2;>9bjpQDWzl#!^6G#O-D!)`Bb)=&?nyN6KyV(s0p%sd^DRq-L@t_gO#O`IHf4SR$`PHmVz9iG10 z%PXxw#7}aOWilte^)k^hNB6B4MJq&4U5Qk`Mk|`%p{9)6zIEYhJ70g?Df&xGOOp~h z3>Br4g1@Pu|F_#i$fMvJ*VWdvpD3!=&4m!wFbK+V5*xnR19NN4#=>gvQ&&xz0eyq> zhh?$@dzn3gF{dAPqGH-xm=TAREq7w1suJ!+?Wt?=zJ7X~6n28Gv(SV#?A(|-j8P~{ z*|E%n^+X-^`BY^!9S>22Ob|5pw5k$QjuRv7PWUlYj>2gavZjkKg_ zM4Pg1_QIMKH5KwH6n+BivrS8e@*#`T+LU+hd05mr;^}&hy>6+SIAgf|G) zTl0g-rSsx1Hn$W6(|WVpFQ<%j!qS%0`IUxebW&fX0uQAHCi5omE@K%H+N86Nl2v1} za>?IUTN7>3u*e{t{}voez1|jS7T_}7I1M?m?LnYgSWq_h+NxotWjKeml{IR#VZ`i+ z&*{274nEk(~l%|uwF^+A?W!NP3y{bs-tl3v{ zUajnjfcpcxZUvWQ$P!D|oSo<4c6%kPk7H}G-@A)9 z0pAo|U>WU=QOX^{FOaGxi1GDgvOJgkh$aeXnlbUbT_l5tl z?i3C;LP#7-FO=GAo>r&n8(}>9>LKS|r&!Tu%>rJN*wUOtdy73H;Y&ex-u#qT$&u_c z47&h!0bSYcS25ijJ0Cr}?DfPZL4+JAq}fc*>^8C#Jk2i7mMboD9V15eq{Mq#YWD@u_#Uvs2fZQCxe=XPh9jcdkW)EsrVp#1 zLv_B?MkFR{@o5;nRX!U>$k7b}SA#w((-U?L<@k7{-&7-mzAEaUq zOZPumiCH3qj;QJrm52G7mf9rG!dTP3q!@7A>{fZXFv_lpr!J{PM+zV(Lwo^M`i9Gp zkek45t56T*9BGSc6EeC?%l=Yo!mNSW*)hYby^YA#e{1lfFNvg6U1Oy*5E z@Gw5&K;-{k=uN)Ju}X%F&FynVV3_*2N2ExZh!3zrRsrANc{cOOuUbFg)C^QLOU%rV^j-q-zA2dHF_l@_}3tZQuX)Po9Ao3(Tm5SfEgT z38jTaO1^BwDaTGwbieID^!`e&iLNpsc{H5ngD-y86l{BMZMqM)7xvK2-Q*+b#JaaI;?FmbrC6ROv945WDYAcUQGrtpl&Cf|;C@8?3uP7v8DB zqr&VIIeT{nw4!}>xzCe0wG6b67l$#vj2OBU>=+UTcflOrGyC!zdoW)}&u=?hWHGs8 z4ph0%lB{HIawhLc2QFnh*>}Nnel4MWz8#=mtnYG;T%j$6*p27|43S0>f2J21Dj+Q| z%SefJx%zmTwC%kIR_GHY%%Rue?b4HUt%2NlcRgP-i7zVBu{BTle8d)ggc`<>{!jdw z9N=>=C0~C*zomyI%i7FQN)>)xl!k~(&seram6X1ziTpXkE^CT;e}Qih!yjW!S6E=o z@eG(_9FwdLnV!Df=W31DVM_#=To;2%caFBL&{7YTa!Yh}&W&ag)qBzzs(p4m*WR|x zn_B=cpjX*HT=~w_wad!ONxFnN-x(-94VDg<{V40+)oIrEeAkmQ=5<6zD_(Z>=<>KP zU+t*vE4z`|X&IsG%3>npdUo269Q8!jr%`~?N=N#O)+@p=oZA@emk#EAvP8#e-a+5M z=mcIU_2Y4^AARCSciRU%oXx3jLdGNI>O;mkUoaGZ;S=ilUYw58JXv;2Vtul;M>Su_ z3};9Kn21z2WO>{tdc z$uD)K06Csmik0Jg1BhLJ>x8Fb(=cu0;n?ADNXOyCd^UK?Z|xwMw|S($AV!~=w;5NW zixnVq;q8Q>H15kec?Pw#&a^$Lo*XhKI*SM2VME|JJ9>KAyFHtY))?NgdQMmm7gstNu@QY)CGt!p7`! zn$u_0Y8tFe&9Q$()h$-s31Gig{$k)MAeqqtqpvNlt|3j<)0>%0CtE>xP^01F8^m0% zUK+QkLsdBvdOY$AH^RNi6xZLKwbbXCPx{_v6IuuU+ARBgNq~CmM?JU~?{MI-Z(P?$k&J>W&+xlEb?bo%0zbi2mdL-cm#9P#I=T$#-|jHZhEK zVZ1@$**)57pw28cErJCz6RZ-~q?uXBp!-QXPbH6_Z1b3R$Q|FaCK}WbU%tD1cR|4T zQEdKa&v(H`$&k&1zZ2s0k%?5vP1iwhw;&|uVhCpq-$%xB{zcqZ zz4@V=vcCMA4%_!2sMe2n5dN5kq3W24hH^)h$`}eTqs)b;vLTl;As70f+mM^%@IF*euxap z!OybJj20sfyCo`wQ^$C~@nR$?Z9HuiLSBoqv8?nO6OxQ|M8M$)&2Or4o@hkniHio% z82D8TEkHT(zvkyimW8S>3`xQTJk652zF5tes&(Hnr(1Nt(*U;3v1M1cP4=y){M%~~ zuP-A9-5q4EPi)!FDJOf&xn`6GzB`!=DI^663vp`fx#DO!-lu33;I)^LKcc*h*xoXb3+?5lS?BB9z;dUn+HIklZLGWkoDYe-&=~6TtkM}@C6w~S6j*z_(kdo= zy0Ux1@v4{DxtU519WB7y6ujB0>IZvHuV3!3v*Dt=Pjo_&5`?w#TuvSOZW@-fUKr7Q z7p3-S9W}`}@g2RCNH|Q^xUr@|rBZa!EEL!v?S32_^c>A1e4`qV%-WwG$*qUO(!Z6D z89ZCq|CVH-Eq&2W@KmT63@hJQ-U{x4^v%n$-;md|Wuf(Z|M-i52QMmm;tH+i^zUfI z^RH6kqsYUt`h1e|L&@S-Yv05bZ0D18LX@Q>YhO0^C+s{;$_5?`1{`N@kX=W~i{2%Y zR~?s5XZco>zAhi;Td?x}4c(rlVAb=khZmq$^fw~P@V!!^SZag|V?vDBI3@UM2~)?o zn7<(gQ{zsa;d)7y;Z%4k9)ahtv*aD)zv7A@FUcV@SrzI=$?{3|V-n-!RzZnk&uTOP z$`z63^Fjbo4s05Zw;rs4f+*D=g9XzS?BX_LPyY5+4>+0@`TO&@9?PzeSYvW*M%w8P zH!qu8zPM1@)rzHO8_M_*sTPj6ba+p43T)dJ0W= z0=zQ*#aaLg|HWF+W#3BH*ZvK0i23$}jo0ByeCB5u=T2k)pcUGuYTGCeLzMsYslQw2 zewf#Jb@I!`K03WX6$sgof|fki0Um0l%^#=b#G)n`C0=~tQJuN{BXX@sa147T}j$g?dVUFgG zPQrWb(xiC?#eD5Hb^zaQ6Jhg656n`tS z&=RfjuI2=r9Ni*xU3owcG;XATf^Ft{3TTUR{tb!J{F?q7q8RF9F~SC_gsYd&F zV^b{;e*tJ9YEt{A*c({?zpucO=2z{?Bm2O5ojMmLvKMj5=E|5o7yL>)?Aaz6wed51E;< zC|%LNLN2&lu@@|D6W+IZICJ+ore-44nM}#-Wyj(2FNr=K0Q5gya|r_7-^Y{@R}4L-M$f10uE(#Ez7miYlJI<~JI3Z1Mc=POYPqZ8wU1NjgaQGJMZ^)|0(a=o*7|$6t&%^~zl*aAOY%$BL zuRen`6|!iZLCyN^lY5EE0%aBl<`W+7N)2l zR|m#Vt-|K3O=*9c?c84E+M)2|6djj%QcPJUCYspjZjEc;eI7=_3VHjP)Tj+Y=(Jdg z^&}4o$*`f+v(iS{%6=f9F_*J7!;ZW?X4xocE!NbCK*zx}ut72VMDW2z6PqJZep?KI zo@n5cP=nWe!@z@3CyX`C(^6aYR{^U>PmYU_LBwkFEL$$~-F7g5duxuM`XLR;UEyI1h zNZ!g*glbV|M&p2*_u<#;C+7zh;G|y6eEr}jXqu!yPz0s1vvPq6IzI;SqxGnK{@Sre znl)hxmUqyB49nEwO@3OcTJ6%`5EE-)s&(onj$pzpY4;H%xtRyZVKN3E(d0m+o| zE^2@EI1?K{3g7>B4b8eztr~k8EPxdUH?Y!EVblaP~?oO*L3+hH-P9iFE;FJiMkg_To-MHd_;Q;F`wqn8t%Y z_j0wX5rNe_tz3r8_>(3bSpw2%clek{Yzbc2!ZGU077UNDxq5mDX491j$7=N>lu!v zosL|e#paUw+9QEe#sQs~Y}Tl1J|a$8jz8Ql_cAXW@G|DANq+Yd(;~9$9-WHp136OK zy0Q#|!@-zk9g`TXO1+q8wUSFo)STO8IWPBy&kIgP?pvi(CRkU`h_HGE=rY7YwhMHDC z-y@rJQhScsC+4XOGCb=&ZF`2^1TK3pCu?{2>9qN5Y^cLNk~>|oDs zPmhJmAR;RB)oTc0>gYbz`1iDZGP7RS@ zZ)7SgJ>O?tK7R@(XG0aoZ`owkpQ3ahA`J#zDNm5)r4#Y97h3nZIQk%}&X6~{XxLHh zHPX)M)j#vUj#MvjEPFEVmJZ)Ju9K7kv9F?J9?rHG+B}?o!HPzegBIO0iOC#L9N>RC z8|!JAFjpbp9*TP6tQHydpH{$lSSLNyQF9io|o=)fAxvbldlaPjKA*l%y~ohQ`khqjc=zD z7RMFu4)la?W7@s!>EXvX$;7qYjoW%CRyqi2m^V`G7HRagJdD8#zL^k4__N5Xw?yje zSR>1=ejVr3HCiQ2R@vj%K)3m~v^VOitS6PzbrdG?>-9X08zf1w-7nB+MPTys5wvtQ z#PE($UG!)j)$dksGYgEz&7GuuRPHKQgRa%nME5x;DVxpS`4`JPn9$tKEOAZmMQ*xi zc&nOcQL@a3Qv+XF*C?&QtG=t{dGoieDtLsD1rY5GWlvP%f|6((>sY^x*hv#U-cj=! zPBMXCy}=M|QAUBc3eK38SEg$oEpOu>M&rQiTX!cPuSM_ATjEWOdl!6VkS zcl5r;NsKugfvJza4>F$oEkkQRr%E;#R1_Jf1R;dRESKX+fjd0(t=}pkch?M=LiDTE znC@wz(SD&uD0nKSXdv0vS{GRJ^Sdn;B?3Y;1D%KbeuBfbABRR!<-TGi`g%6Rz~T41 zF|FxHu3n_b$~~p?!J0mBL*F>V9X~_e_B9E zmgF6BQ4=?tI@?nv!;;+hOjJd2G58(_$b2dErCmBeN%^vwXWbOc`K15{NjxO8yK@{s z^Ny|vo}eW|gsUU!vuHv?_461(-~lFfbYpg`7{i)5ZL5k+S^RQ2zOC@X5rI!=fpat;R^mk~8pZEXlXY?j(ZJRB*+koNo{2 zO`ptVkD)Z$(c)B96TQ$sQ|sS}mFg0?TyK6PU7I&=o2*pC%+OLf3Tiq)9U>}@SGCUG zm04CGv0~L*Q-DQ%8D}VD@9Z?Ay;6!Lc^=Euk%L_=@O*z>ly5}{ytju*S)hD$lplKf zC{L_}W$D!s8?i*cj^igg2%fJl_!nrDp!+-ZlhKgzSB{ZUr8yTIvtAMkQ9rRGb(WH1 z%5y#322gz+yfB<}AcHDg&#y|gNuJNVkxl~tjnYOpL&)MC4n@eT_V3=B8KGsT{O@W% zE^s#QPU0l7(g97oGXD42$L@fM4BR7{saEh$o`&20nYEQ&>+=k@yafRv=dQi_VjgW_ zwlTLxCIekNgplxVC1N7Ju>;wEPx??dP(9Kz+NSk<;e#(ASG=v&Lg|CWBBGQ!-RI-+ zNMW=;lUPIa2Sk4{&KuO(E)#=XcUrNhHfz-6^UG4VSRxPKG!f7{&ED+i^Y6elmJc0@ zeF~=xJYzcEYXr3!JKwF=l6MHzyedPP=#lkMVo&&#Kk|gj9kza0pWp)RV57z-j~k*W zb|-D5#Z&;00zu~T{lFmV-GN&^Y?cqY7DiPuMu#R!Hcvl{@!@on1*f<6xNNC@_K~}9 z4Nff?l{2!&_CwXtwpgyMM?+F;h#Bzm?^vVnM#7Igc@vyphOAr+ul{=^>dwpE+vH$-l|^zs`BTK-t`9!zV-{Dq;s z`Kv7Z!~XlPFLO_yTd^u&@@(VwlN=23-WsCtYNe^)dQTH=h2{>2<~)HL z^&E-W9B3iquAJZrk&nodh}Nf z`Jxl7aw$Y^C_h0*^laU=g(+hUba|$l3mWHv5T1R0aBaj6+lOhu@8VtQwRnxTHTq<+ z#Z#xoiJxs|Cy{289QENpc9wp`QJp#8dA`kcG4NePF>vL&Sm>M4do>6It@9m30LUH2 z$g;U*wq<#rRlNP;VX{u?Py8q1vIc{z5G7m;Lq>bNPOapAk7XT(v9jv*JLl7f zcdg#?-lHRU@bNx6H82rYVC}R+%|31p&O$!0y2d<&Nf3Gjh*owoKGemcb(%tt`gSz> z^~`6^dq?aj|2;Qm$@;|J>BMJ4ohL@slHXgj)q8xIoYTctX3@UHbWf6eq}XF?OYXdl zbNPFjxXXV4ZbOMK zePHnRKP;HodsczwPzH$6UjYAAP8M($;)a9mxM)w9kn=<;xC@jPG?Z=)<3q}YdoI0yu?m}K`Gy(;&T6;kPUZO$p z^L=ofs8t`WUa9fREb=4>;Cnoo=$Rog`edZUp9bYHVS&Vsea(6&_*qnN6BQl06s%(wgR#!Nw@!fS3mFTJcCJ&8$MWyr?%Hl(>3zRGWY-te*K`+Q2>n$oUkq zghmS$yJSzHAIrwPw@cs5II+)0g=Bgw=Qj9~rfIZaKc z^F4xxlsw)W*h1_Y+%cG*K#l%-5zyi(V3r(RSpXUc>o;V=owRA6sQ-JhIIG+>kAYs~3MK79%;hFmw ztg0Ew&B93R;+F4a=*biy*vVWcgd)OiT~_35=aF+O9PD}KOvo-BvYIp`B}rM4iMck+ zkgh`qHylq|bfL2}ubb}Fb-4wK)5+coBWO1#)o5vVE>mdlklNLf(Wny3Ea_g#M7x&i zX&Jm&9Os&omgJDKFN9U&aYW~Gwwn%9PAY=b`TzB3G(294gnp@L3gxYTfnQUHDQvA< z`C~zyUgoBnJKJShh;_0<3x=J@2)HqIc+m!WJ<%{rIHjbtEVUWN5OU7z%eQhiC_G`? z{aLnZ{u`1|^48qw3wnTnu^*!zA2*fS1Y6Do8}qxB{^)tqrM4$mnFrDW6_F>%d`J8( z+hwb3K~_x!Z(tcV(_jZWc5R-^w*$4Gwpt#SW%+sE1|7I2qgbK(5CgO_yu1FGnV7AK zFJFVfEXNOmin%BY8@D%Zi97&?2>Gq5{q_|OE`sCJ~-@*XU_`DENWcJ?$>vU=Pe zcArjc0xtOSl5+U&Z^+-N+yB62BdkDF&^EahpRnNf-;lC%;MyU7>6{OqLh<0QCU5~=VSZ%pa1*VM ziw&01>$`|#wt4Fu0d?xd)LTMG3-wV#%Cdn3D5L1c?;2TKYurup;Bbt=h@Xw*+*6lZ zj^INW=qbM(G#_Ij-q(WIo4@I}yHWnbd$|cY?Nfe#+mNssz}+S{k58q2-CAE~6)qcx zkBFY6GciiZKO$df{0%^27rI5x(ZB*mEFs|45SC}Q(vkmr;?lgTUrL?i{17|}+@f!f zf`@M~OHPmWQy4-^xIgce)7=gyWg@DgUyl9Q?$3dy0#JSih+7#is9kDBEVUAe=2(+l zy5*4f+wes-A@FCRdugS+Vx_I27w#{>`;lmn-Ur&IdY><5fEhH*nK>u^n*UPe-dRSZ z-G0fL^|Pwxs)o@lP6OT9r(v4z3FyY*U%}D6P@`rmwr8U9kwXYB`2M^&2uh+Mo>OjG zkW`vYv9kLsO`~q*WY*KUqubh(4UgtoF7p$#o?!<)4SwPz_c*#~Jt;eQF-o9){@Dlo zEE||#&Z|mX;G^7HfqbMlfaQ+?2P^cYxwi`)4LD`x)|3_B-`%V zJ`h>`yxDp-sC+|u_VeGdrGM?0x+mPa42EQ692n#yB8v0bXJD}I7V9bOwCrfeYMdxF zLPF^%)q}i)T&Xa}hFoZ^$D)SB_qNP@Tvh&~{U}>5ZZnW@TJQ+wu(ffY zD1-WnDQn`4>gkV**Y8zzrq|au`YP3l&k5{BUM|Le+n%cuCDS(KrJ3e+Pu2=9+HU(H zLDY{758`s-P$4m{5B0iJ^ide_Oy)R((Sxgh=oUPl;_%`XtfhH#}McZUlCQUm8}WLT^LXlry4Za z{A>2r323UV`mb{M-_`IsLaR>ihOE>iTsLIJUe4@!KIk-LCi<{4g?vBF4H}y7S+}BI z!vCrvK_Trt3O<{I{r{~#r1&GQDKy=VjFucUwX*HKq?_SP12gBAtuREQzyoL{948Y$ zQH=&l@bI5Gj{ja;%sB_?h=VGmkCpN*x{RUjxsb!olEL0CjU_csf)`tK`oL|{xe-^- z_Oq^GIqa!vCBC`jGsVA+_)5A^;7${>3PpLX7^yf3+O7LecPn~lHGCV}9t{qEQ^C-~ z{%G^c_ie#~qszlLq^1C4d+Va@5F#hI^DEGHf2r72k$Pe!M!i|=L+J=9Z!FpE3tR}_ zlFx}j$tAgBfgA|rynb-bV#czRV)y+1(C5O)`xv70sV4RIB1;Bk@n#9$KzNg?tv$7S zC(dzEWNP{yFa^4LEmpowF493mG&Aj0<6axLH9T+o;7dXqPb5&b3wS1c6T(oRZiu)d ztVR_tvAfY#!DRCFJ1tq-lkV65l6w}T^&+DT_m#H7JmKhC(<6HO1($QcPD`Ch#KG7d5No* zY&^8l0eR(rCCkjwsf37vlJ_Iq1RV({UqVK1^SNjf87rdM2IExMN>@A73&Io^kws&T3CF6BA zlMB6?Fg`im>9u$(FIZ;CT*cnYurpd;YGeq~{XQ5neXX@FVRl4dkvek6t4Jjy8UpTl zb5iqClklIG>tskEK&W-{N_DFZqBd@x8=HsdZO*DG|1TNuLWXx-g{za(OLS@6!$JG} zm`ulAv=o46&m!7Fx)oY_U8SB;Bn)plS&k)9Dw%>Ltq<-*<#F8|*Cl-OjhnXvQ}S{$ z2sve`X5hdZSw8;|-Bjcn!+{f}k(|-4rwE%-3|i@+eylOJA{pG*s44I{5E}8!I#HMmCk|F=Lels~3p5DWn-6l_ zInBh~(5&>?5fuNbq8P>coThyYPI?;(X%# zih)62N4Mn{zEX=@rxd7-*66PFz3f_-Rl`sC#A3lgq{LWTv1g?Q${k;KPCT*H$5@}~ z+0My^(PE2{hAQ?fdSJhlDagc=%xbD?pC_q0QmS8`Nqc>u!J)VF_B&o|fg(W`x;W&) zH#bwgbe#H@u_onmPo?wQa3t;yo5&Y)^450&Z2A$yzf`fdrpB0F2x zrk41Tq4X$s2LX|a7DRw1-bK{4eWI%(klAcB)}VAcQn~xqLu4E8iK6| z;+NSnmCckjIx_*C%K|dv%%&fY9DeL7Fzu~z*`vr?U5bp#BbtmIYF#kxT|ILH(Nd+? z{<4J8#6#S^TAe?%Qr#?u*bA|AehnF1G{vg59x`NN_M{Or!i8Be**^WL+nQvjWl11@ z72%+b;lyt`=rbvB*xfN5H4#!1wM?dv4A<@Uvvt}K0YDxPTIz)vgY`9DGehW%!4Y12 z8o5|$bAi`}z4%$i#qI09$8GHBXl;?{0V){E#)~&k+mN?JavN}!$W9Mu7lA&m;-EU# zZazpVG=NFW)#vUoTckB3_~40ILdOidG4jz4o6 ztn#u04A28`mSolN?9RBwNBh|V_7GeCk9UYK_VS;N-FIB^M5>e85t^@BM!JFfbQ80! z&SCdr9doxvKJT%7*BSX-0g3ZY_l9fl(6lu~&6h3-F{!l1^flBYqIET}eLF1q_R{Mv zO8;wPMpLWy#G8z6a?sG{_-Grnv>5_AW2Qksl@tfj-PGPl_F38Qf+hh%;^9k^vPUcn z!TWoA*OIJkPwF_WU%gWcvW$FFq!>U{^&>s=&?Xqwb5^(?x=D`StxkVa8< z#;#SG<+yxOPzA%f%o9*JqKcc|c5gG2A&~waF6i)zqw=H14UX!lAW8P-bj&#rX|lb2 z{UnOjvCPmzO6XICfXry!fN6(!Yv?WQY(GQ#N_!2ld#@iFzYBq^j@Qa~p=x72`lOt5 zaZd(8sfk|qE9>FhhUevwSPKP~tX2$!Qvm!mtDI}@BFTH51PKWd4h0XH!LS`{R@>Bupq zx`(+r~hsFtqoH9Z<}pP;p~UM0dT!9Q^-+Qy^DFd)un!N?{IZrM||G6c$s_|PY2m| zjX}BI)8cs=MZv*yf`!i^ZcKyDUF@P%=0qEpl%O^c&2>~R zzl=5Tv}-M?q-57LlB4VXgHcWmmD7f_G!2h@(VD|=3t+| zqx>9B!7KNPU9Io*jm)ag@VzvmB-|?OhS>(IsL*fXKm2#cbJ ztrPz87qx(0{9_K@%k;<`8lc}jXUx#=_5S`G_nf9+=r6Lk8G^Fc382JSuj3E7$iz(# zUt5gxItz0>D%;LvU6TvfvyYvm828^Pm=!rX*iRn&M++CgZB>2P7`N`XQ`f}UoVt)p7(Wpf+9-{q* z5Z%iGXXy%iC~*9u0qxk5>1-iI`pU9gQ}JXw0!6)E*z8*cdL0iqilWJ?u7%TfJle>q z3-1+|c*YpW8jqi8MM;&gHQRrQd>Gbqmc-M8YI=o780&%XR?0n$XVuIlEfU*+`jhE_|%6=xD{wB|e3<;Wxf zTJ@0_?+LiG3sEB8S8&v~gVuenec2UZ|7EJ3UGeocpTl}2P*^*-MVjHnbG2UkH}u^n z=z0s?AyrpOzMjqHv)ify8*hb?AzNEFPjhV*QCG<64>RY};_|$OSv2EKJfWH`xz;Q6$3nZ{4gV+NyvVwlw5uRXKO`GkI(mnyC{)hmm;j^>gUi3 zV1OWmxRU;tSWnb$Ltayuzx^sI=7S)wN13&Y;<~P)xfMJlGVrSYQNiPl^$q^A^>E1Y zEsfO$xfRl(waQ3tti0@94a_#S;Vvc`JLF^ThryB2yhCK7v-wI4>Abv^NzlHnMUYw@ zK_Dhh@WT4gih&y;v=?U0DR%^5b#Ttaf#$a7xB!KYsM@0k6xu`#|9ZG+nd(@=oggfD&$!+SRxJe$cKGhG(eQ&Q~(5d-$3}ix53{#YncRHX?>*~^0Lnqubs>JIcal??&Lgq92|{f4YYBB8%Xg$XUaEO z(5n*j2%X~*wGvrYp!lHwn46iJ4D|Y{%Yb?kDR2sfA!2Dlt2a$# zv;4&QM#Qt|bDfApHz9c6GI6|_nBdSA>O`_mC<9z%{t39cLmIf#__s;$`y({%aW3Tt zLi0%+60Q!9L(DweL-3v!@(Foz7us7A#e|hFhvl2|xDO=ddntJg&GquFZnyToGOT3Qd#MB`qA!m)lS<= zwk1lX{SMJrYPg_MGmb7YO>VyObC&Bd`@4?;m~QBCP;9>5?*p#f?blqR1L+yX3m^8? zaO73I_HM_OQ|QDrC1V;>>#=7q!}sB;6RZGQ+>uhDSKjtVtUV%xGLAA-4vA$XENg-D zu|I9NoDvta%%|PkAZj6s`k>ugXg%?ZoH?ELtsRadQC|gxVBHL5U?Vexs(1`+QCP?J z;qCLp!nj8k5k<<54%qAlAcT=wTlLdH0h(??rW7b7Gr9A;R*HBRm7>^{ff4vwagvr)Zl>DFDm37pvUndB>I71B6J7Rx- z`^HaZ533b=UGq^Y@)J(C{z|F}hD3?(d^@xDD{&}S>`j~~--G;pVUa1iqs^||rqT5I zw*D>W@@dyYbj*Q(tw@eX`vR8%K3XMlIqZU!FLg%#TI~+x)rlQZZ*dj)iiw17M6|0l zETd+>#G6_?sI2DeQIoxW>f{m*+02khrn*PE^yV_E(XY^KtHn2NA=o@|b36g2XY-O` zPU;LZKkaA73m-0Vx}hJ9ssUiv+^uGP>G6RWG@Ui9gY`Ds)pJpW&SSb0m0AU75IJ1B ztV|;D#SaLY9voFv*BCd5`!R@t)<4bBuX9+0p)N{7cZf{m2#G(#Q28DJo={{ErU+2* z7=QnT-oKCTKTfVhUYTs0r(rE2e%TM>>czoSZdyOD$ub!ony{{bMzLw0j8Jh!CN_)7 z;5nH|{piE{IWfC&&~KU|&cM;_cZL{guG(qM&Qe5#RZ)bqP3WBD`(O$P|JnBk^H;J5 zx_c`(tVWbSQLqlbGB4jHXF>a`I&$t=b-s4q0*vU}c%;fbmi_p1gL{0t65InZ2a5~| zUiajN8rQ%mgXfstX+jG^zWKH7TEl0rC_?Qj$qKX{(SmPIFF7OQa3n0JJ%2;w$D16| z$;V`-dxCW78>MeXUlCEmQjKE<2JtA}7@}A>JFp5+!G@!^Lu-Ip?*lUVRk?LZxF$*UEC+Yzog-PqOmJzULa9EZ8iUF z7)1G4w&0xeFE@}p?Ek@`?moddwTZcb4B+_am!)O58)cnjgkE+3RqaZ05QMj9N(DWih3>8 z3L3H%qHkrZcZw6|INR>r9DDKEPq6?e_{dVvMrBTY`Y%PcldnA9mp-Pq+FkcF^NN7v zrU~0;IuUwsr!DOmm@3yF8HH0wBruH6zhH3!>QN^1v{mDdtZEH0j2y8j4B0 zF~nC4bb7FS@}5{xYH&7peDUC}!1+=AS2;8xZ=`aNAX~{#&mi`aHmR8Rd#e@y7jsH-cb^idWcXiR-yZ3(Iwbo-3rWTkxECVW^1IELWxp$WRMF^RCIC5XV&?;t9 z)eh&U%snso@eh8*dxN}#_Ath#P^E_E5M3=3O!OX(p_2qOcZ1PZrbOIr&cv22b3m%Z zV{}D%dTZjqrBy|}C6GRKi1gE;*(OfMtP%h{|H4@kdtdC^9ilGwZEZ*>#3 zO3DiOnynz}oVgjmVC;Z}<7dc3KAVP@8Ry-+6z-N6`K4#cO=4RY4;aKn*lfNd|>iZuOl=kFX?; z5?i7;9ZpDIUa9z1I&E-OIU z9|c1NixH&;EgG}>V;=x7BtetkSLsI;fvjZ^mTrj&;!HC%8c(sgE&0Nme|b+=qsmi7 z<3sw#8;evB0bf(UB6|o-H>D!Yf9>=cr zDVQJy_{;K4?;$GxxN}~!bz`WHl}J=cR0+{Krtxpo2)jXk{{#q{9 zGr?O9)=la28PBl}Iq#s;pcw0JM_cZ;B^V8|Vs)#$R%HqFsTs7*$@t88nuW1Kd9Bk{ zu-5uyUfLU8EaA6G`96?FJ6H7cnrx9BOJlj$en%To+ce(W#vit3tx9R;@7*!|k&k8( zt~I5^$wiy(G3%?N_G+<#4GZ{6*kt!*2D|J;UlP=3rvJ5N+5tw%i)3epUyoH(n;k(p zR_n}JxGR2inFZl#uw|;EYj_`pA84MccJyXX2dZZU?>8Mp?yY8-ucTt;f(QMQd3TGa zxe2f{Iz-*R`%)|*+P&PeqY7t?=2pRa5y|sv(zqHc#FlEnk=qdv3Wg}OqewJ3)`Q{S zHMWFezmO&gWi+CROjmlUuwG^AFHX%XeN5(k#^~z(nIi8CEJuhu-5V=t_DN4QTQ>|AWcBk)2KNFpMrB9uyHvOX@#yii5ptULBv$lsx zx_?eo<`iOeu9+qvS(=>`f<{Xnu|}l>=lgKp%D&R0>86vPRJ6$U)j)TF%#&@$zJbJ@ zgITW68xTG5=W=bO(U+!$YWKFR=`bWx7(0dIFa8hu&U%VY&8-GX92#W?pX!a#;Itm&Pz zWr0fFBPwf?vZ}PbhESj(b5cc4A{nBO_1*(cb>`8hxTL;!Ld?| z)`d#g6qKgTZ&`_EF1AraRs+>3_&A<@6Q@4k7pIs86Oo8Dyvl2R$zusq-scODGRnVL zcV6>Gw@% zn!Dtgx6f}X^5|iAO6L;B0@XEU2|q791#cYi?!@kg z3mNIFZvED^|6bw#J1gK{i=p*6g0@b|em~d&tD;iTABFe#+M!?aNH{?_ z)K?Ok)PT|NCf-LxnF}*Cs*nQKDNJPLOtoD)L1ip0^txEfWH(}X#-({7Gt7W+%E-Sp zFP*4FI4kOzYZPOoL?nHFBbJQlJ#Di&eK44WfPlnEyw!DJ5$A`Qr!bxy$uAtp9^z+gz zmbFD<)nTHI4(n5g@PmoYvDc(vUeHZS83O`IqLVXmBF8WqfF-rgo>^>7Nz|$<@@`gJ z+QN~3JVN+8FCKG5|Kan_MaKjV6oGQ!U9!fN_UacldXM$#Or>uPma`?Eto{v1E(34G zNY60chV&J>Z<0PBzpCf0>Ixo(m`kGgRzbhC9VZ>Y{9W{!pRY!0OlV9%J$2cLG9d=7 z7wI^Y{31fC0E)@3o9NT4=&w3IlPl-6_X*wA^cEy}`*a92Wfvyh&@nDisvd~0@)g=K zJ>0wJ={Ocgpw?B^&I4Bp?^qW!5tHMav4UD%W=MHkOFW8K4B*JENpat56P8CO=GXGC zH~X$hBFgzyA&9WlzVS9nYXj0r;g_y?X~eZ<0+?-CKyj~eOTed;H=Rye(`SWj3+A7MK z!AoMIYtr$~M=YU~_*K*A#I?_yy-f;bNj~Unjchf`rvI`-Gs^HJ*EqmONc(E3Axia) zH<|g?Kqgt6-swbv)^`WRO*mP!HZL*Rnmt9N9svtTE4RBv65?z=sQWagc>h)Kgd&5? z9#zlKP=)4B9`EJB;))GXc1*9<4gPITK)tOu%J0&Ynad=Sj|!DO9h}YN8~frUkJnjP zECNX5XGb9XtY(vMP*Ik74%F^<0 zV1W?(nkwMi%nxi1*5 zw$K+*H8dz>3sB0g`g@uvi#95-J&cuPh|Maep0zhv3|x2I4=d~q>#JlTt`O{gR7K*` z)VSbHSkfOMCp<3lq>m3QX4;b%Vfh%l9vYmUQ#-P$k-+h;Ew#_I-q_3UxO~w&gSn!Y zqiWX+Ij{dN=&%-8kh7P#EyJN(YoB8!;>p`!*;?y;g;z16JKj@$GNCigc)q@)cs#K?Z<9Dc*ZQd! zou7U3wS<$l|DJ=gGRyF}uaFXa8WjB6&XBN{*_}ZPY7v0%B9-Vk(Lt{Ca^#o2V5j^T zbEc%sLrP)hQGdm*&X4*wi64JJ92o{R?^DQQea2DET;Yt}8Y!167mBXpWDaY% zm4QTjHuQ&fkR%WC@JWWhBc^#w$b*(#vP`+Raadxs;v_2;Ffe(7G5-(9YMaV~i25P- zh~2igyy3gaZk-{s6dz9nY~V))s3(01j*~k-WZs#VELwXl)m+4jrW7PMeeC&QjqNY_ z^7J<2lhoC^KdW!1AxO*50ADfiTI}jvyE;})*2LEp$`yYS#+FKh-N?lYye|8V7|&xq zswBM>d|p<{j5_qb(Mn!)wXfmc^3fJposei!od7($pw?`|6>PFPb!wA9JvOZY*!>vr z8Qzc+lz_308g8wnx>tZi+w@^$$OK{1M{>fBHQ7df#C>s6ZVkp@ADIlsAAU<0n$;Ns zx%G{;@%7xeIZuaFHvK+m^5lUqRFB|D_!RdMqMqKYX9CSoYSgnd69OCB_vddx+a6?q zU??_>RLFzN9*qu82BHcL37D2!om=+jqyrEXvT$!RgRkNOH zU6(BFP`p|t*mOK3F8Zl+pm?4!=Bxt8BmY)=$*HH`PG=t@ycw*vMtXi*3#P#YjPOk{ltsu&X>hXvi-alVoz(@(aLgw5s_aq zvJKe5p<8aMG6HlmOJKB}izbdc95ef2ytQuJp8ZUO*F5A%E#?*3YjU|k5}_}ejg+Az zy)N_ljYheaZ}y2^nve4L1SBRh`2AE{tfWR*j0e9OO$x@?_1Lvs(U%Wn&g3O{=!V>; z_DLqUvj@#0&s{5s_mT}*?XhBNjGz+E&4Ll~b7=aEXz zb*|DRic{zl1e9FmWAd)NN?t~EbMiUAww&#(UYw?Zwewv$$HV)j29yCL-}y7>{;fW5-}c3!A^Y+?L$di3 zt*;0P4qRSOdTNeQgG&KdrlW(iumsCouAb(_ezMGUxxv|jMFgF}9IGFDDP9Tl1@ng+ zS_N?lK0SJ?PdyI3LHqs8m_d&=cviY>VOGfe=_skj84w}YZTZnxWEL7w)^ z(dw~S?9R*~)(D^0Wae1^-QB`-*E=1N4zHxLd!Y^k;t5x@qf(&e(?$laqCou8GsdE5 z;v|(TG=jX+pMr*AwzM_Vr8&)k0vcxWFa0<8g?&|a#7U^I&q|{Cy5dHB8m4MVs8n0e zPtAnFz)-p95)c9_|0kIB4?wGD<%AhZb-p3?;1AWPY5~_6ntV`SZSWFYlu&9d5m`XX znG}a-2%l1F8NihY0!DD1@T>r^=)e4@i^0jlza!VN2|Yp|aD0)^In7}<^fC0orf6Et z!Q^p{gISnOED?W_SmKHt*TtUb@1}Y>#ClRpX+FkMMsO&2=Db2sQ3BPOPFjssKJM)+ zuv6umr)de~89WGm4^VkQmcKTFFy7T?syoemCEz}d=cAR7WQJ+Px_%3x#@oQgfq~Wa zrY8_4a7w}o6cz3@`NcyozP!Fz9>v%g&Jd5xRLnSAdZ|6hQ{pU|QmC`sQ-E=CQW7j0 zN`dK2$?>CB-bX5Tf8OtlZ7DkOR&>pN_$$++h1-GekD5a`$EGDEIA`JdEc);4@LpNhaP&hY(QX zz+tU|IqzX%SOsSYEs!dnTTo$^cQ+H3Sr|M;m4iWw>$>DF&$tohtZudwOIpJ7_mVZE ziEcXW0l|T{`!(t6H>aNdHCH)V;WaKlY_b(VA#2zLK^wiF*63IRM8AXY?IZ!rN|gQh zq1j_5Rigsx?oeoIx$YB}<*%|WyCY8cJL!XT`+S#>0!$446J0aLQ6PW3@e`Hq7R&nd zDrAZlziw)&Lr4?MJFyc5K0gn*0_RBt!8wZt+Jp4TWun)q&s-8XH&7{!?{Q)`zwfG9 z5y3KTB6J6d7xn`3>NG%h|0~mCKhCwvy)v*XCLkD(wX#O3HRR6QVpg|@Uz`!!J*EJ?3p=av0?wEgO> z?b}x^wJ=s{CCYgPT}#3ft~7F{9Y$eWiaj<>rDMB_^(B^`v2v~6LaWc+((Z)xZ{rY8 z$4xg1bausl56rRD)$8?yVoqVVk;I!uf0Nmwr9S-yl4F%azxEdGX}VG26iiO4HbRTC z>RRg1Tm1o~z#$cJG3Mpt-Q(C0o2|ex{pw`ha77pqAKxzB z`_H+r)Ncxi-)0^4cOPnA+&tKW?hCb0BE#DHmZl%JhglIG2G{kn%qVXoJ;MfsL6$^q zqFOXJU>}kbL-A}qoRELw9~wth(*iCoYT>__dJG$KgbD=)mPHPF@gFajs9h?s`yOnOmNO8n$t(RHNWhUDOaP zo`{4HI2h>hKst4$xJ%WY=I*90-PBC~X%*ojoJHs6R(z_UI^$&MM%yOuv}|#=p1SX< zPX=$IapyRt`!hY4SV)06tKQ*c`2bz|4nXE8PV7cRN&pLOG4w5?D_a{e?4i_qDcu#L zhO}12(Pq5kUTd|lur3C%I^G+<%06#>ZV~a)sOVKRckv;D7e$brJL7sBQq4@FA>e7x@w3tNhEpYb8 zpZ==S%B~%|Hmwp#5)}XQexhD}r~Ki$h{I!HZF$)vx}+?AKU!JwQo{b;d=;$u92Bo9)aI~d6j2+yF%XY zQ7JVdYq^*`<0@Eu3T6{@X;kF;NCI%mU}q;+^Tyhc3+Q#nODAn4E|aYeL}rM=~4C*24q z`|<5mzL}8u5%7fZfy{@3uuUq_+7g2?91-azU2cci+ckHfW5gX}nb@06W~64JuYM}m z%AQuxc9g*lg6pT;fLM?xe-Vp?GO1;C>A&k=mdw2nzZsauA*yl+2d}2kL+Yw4igIbU zy(;bU0_1U%fyCjIEzwPY>%q8aVXUOXN5sC^!$PNZvc{KvE=!j`$2IwAP=5j((KQYr zqHfb&5KJyx`8}E9F)7x!tbe0lUD8Y;_>(oNl_ZW~hIT4Q9|6vgE`cHE4xmPa^|u1A_C8)$UFx-@s6R zPRl^b(U&@T`_&}7GYi&-yNn&sL4v9y-&Ua~l``5zq5Xqx`PWYwCnOj+z$TrsXzgy@ zJYkZBA8clZqt|8G$STQUWShfc@F)S{j)i^nw0qw7{v0^Z3*O|@94>QZ-c1qsSlGe1 z`RnoB-sK%#DsXo?1sv;wja!c@N-M!<`-)k;B`KSBYk6~e6Flvar^fh|BxZ>GZ@ezb z1R*TU-jUyzB%v%MZqrocK`%z*f*%x_GxT?Nf#6l!-)> z9Ah-Wto!T$zQt@%#%Bts#^a5~`iOPHCHz7PVs|7{(k*tjmY446x=y3Ja#Mlx~1||xV@(1_^8kA@XgDZd+UPVea1D)@DYYB9iSE} zDMM4-=Z1CqraY0AW0?#pH*1{&)NbUa=Q)Z&x`H9q)vA--=y<)$N|AB>1EKM^hbSDJ zW7O%V0g0rG6ruw>)rC+Y9!z157X8iHMhu@YPpY<66GZZp$7B4YhQIg!GNA708Jqh< zdkQ!*SOdvoDV=@@R7fD>3?n7e5A^UU`7uHIvmD=xItMiGHAVqtRl&x)q(dJF%HJTPeOHB@3NY8VQtHn^@~k{s z)VyOmQro@4()BiuaWZ6a5{Fi)Dk0|8x=3RqLz>7b^#Gs=f(1sSJ6&Eo*t~;BsKIvJd0h zoA3W<-dZn#CK1;EP+=U?-KIj*{F(_dF0@-`JFjH7K7(%RS3#&^+=xA9Qnl>%_nN{4 z$ziWY4k#!}u4)Ss=yoy0KPsb&{jGHpxn^j9VY?Q!!dyOg#-5bH4Y_k#BvC3PPu4a& zLa`V2%qG_@!wN zk@xL6(IG7S^6G1R)VSdMWF@& z1u52Y!-`+b8w^^?`2zB3R_1i&>Ys+mU{fRbJMXWE)*SHmSj{}Q-zL!`^rSZmqOD{d z_RCG(AnJ|(3C2yOrPvcpY5!)bCh~Un*9*2lQUh4}EavzAIzcTLP>2#i6C^9)zmcM~vTaXDRkqn!OMMDcqD zkKkCLbY3$#ML*}u)~zlHZ=#l+ds%|EngmD?X^|)e?)*h?K@S8hzb;>|%Q2a@Nu!L% zicYU=Ol{mzMI8p1CCJ_L>D$V(emdq@&jWL%Sz6t^8CzkhkX=5yRhK-`E$Ga}zr|f+yq&>fOfA^c{*Gjep zc2li@C%G4$j0IDt8ik~wQzB1w<uOeAC~ z=1+ZFbdiN5_$z*Ceqk)f`f2TOh7O@6u>}cTa9lcsOPQL*xXPu$wCT&acdlu&*@8VD zmQiRSlAHNzW``TdpJ7SN<|8*?f`C0^e1!@~HX*CH$9l4H#OcMO9?v&)ZKlzu$!S2nwmpS_ixpSWxnHcE~xGb!?j*zfgF_j!Q zFuf%>7Cq9s$8~lSURTO{T6piEp_4z_dq>d-(8f>r3wg1`O#7%+Fh*{Vb1PAf!n11> z3KG_T^>)8xhdl9Ro(WwqX)be8Le-sUujY{sJ-}gBWQbT7Uab;Er9OZ2Qk+5r9A6{< z^`nWHf7RUEG@-Azn?W|YT@$#c>tH&iXt&MF>@h1o%7obVwZXIP*@xr78JRRX8DR9D z^<38~6Wbge*?a(rgY08W59RduRi=JycLrI@bgCGCSI|%xIf)yCXVxZ z1#Wvd{SWSuCw<h0G`MuvLUB6hgB}fQmsUX} zKWhx+rw4UZ1Z20cLga_A$p(e@EA1ey%H#4(w%pDL#*5@ZVip20B3S^nsJyz{kGc-d z9+Mhe<0R=`^HzeXyPGDRi{l){pVa^u(3Ju&46xD!<@|o%Ui@xj{nwcwN%VY4k&7Uk;S{GVvURqX^t7cI zDTS*b1wCg~CeiW=v>oDem)_$0uV-AD+rU$TL_< z|Hr2NzgfsEIS_vPz+%gAF^;(V5KrMbZuqO&Mcln&7?imf> zRmP(vsc-UtONDo((o^r%l&lMA(Nw>+Hz7Ho)H4g~(~HUoderI^0Xg|%(lH-WvJs01 zoeAe@D}Y`IoOv#VMabj6Y?b>d(Kq33UJ7k0FSsvRYsb^}(9}tM8?lsdI8BZ0Q-npy z)w3yB6=J|43yW3$>MwlM%LkjUh~(B6HN@J-&ehiI^`-COV0p}d$XNtjhY%>3#WJ!) zxmUdU8UfkjIS@VESSR{mZ&V+DP^NLF!W^3{0x#6Nm*Z(_`cRsD!qQ_79+VkSPfz69GQRL*7LQ|>41ByG?wP_zK`q+Ishu}p#Ih6?^w za@X_h=>v8)JMM5gW139B=1CQU;L}+q6+4mr8OtneE*Ou#3>B^=CBx($OWBC`1uf=5 zlWvqJ`y6L7V>r&F!v+#%4v&40drDJ9%o+6Yok&Ste1X2K>qX&vjD$skE?jra!n8rg z1i3!`!82wiL?OMIUp_)Pi`J=8`9hWuwt!?~Nxc^c2Jv9||k0uU^@L7LBS#cNWHphCsR-@d`v*zJ|M2%pL=`UY{OPQmpL8?ipl zheWz(V~Ps7Cz}+?oIFP1;!ScTriF=EKB@?7qqdx9$jO>BC`dCZ&#`Gn^0aJF%?o%S zTt@LWuc@e2P(dF7vUWMNGnpSY=U?G`qwRXRxs!OQvZIG{;sY(ddb&6Bjks0>_jnBH zwK~dXWH3?!=RyVtbKI1D>7DMH80tQka8pcDu{nA&75viDC{C6EXyL4F?e~KGBI?)a z-7YHD*%ifVnxdX8U!KqnJIan_&%z6K!j=>hTsnqDun8*x_D)8D>l25gh75jUJM#34O4blRz#Wra-3~!0e!4xmYDFdRU7Z1;``W^;@=5jTXt6qn)(ETjcLR>7Q zrcxY7^_Iq0MfrVAGSdSFUQqT4Ugu%+H@TC*9P^_*RNjP=>BAq4p#w z5GEE$J95){UmFOW7qZ@78XfdTshJ?(W}1F$1fp2}5qvkhaDWe=EfzLG$lB-mYMp8Vx1 zhG?xZ9|cBM&3*}YyhM|f!j|Mrzg0z*(Ef)O>0f?t>Ms!V7gszG#hY5pq2a7F7Up{^ zOxLlE`&ZK|*uVg<{mlbtLN^i4gm8I5zu%EzNYIm70YF1Dhh#+=&{Hes`810X40V|0B*`Ks2h-rZ3; z8g~wHXw4mm_GV(l+jbp0Qcz%GCuW{qqrRh$>6&Uq9){vG?7^dX zIa&tF_>7-Lnwo7XP~>(8OOi>=LVzUu3tz#Z`B99W@Acs(dN-?2ARuq>A0rh5;CNqs zvb064uxvRSipXB#p{2l8gg7Fco_hAA3qZQk&<$xw>`qk}{-yur*9QHk6ZwJ7aa7JV zD49J0Uv$Nj4wN}g-&n9FyQmh8akUe1ghaW6K^ z@fu`G@a)A)lXJ4F(e#sI7DsU4dm*SFob9vdeot%mmZNEGVz#4~>#%wqh1uiefb9j@ zD0^XR^Y8-Nx3^7?0Rwa`;p?&ojp z&u-wW;zx(0ZlSX8x%x{;GjAC#A3`V;9_|+acyY$Q&P1sN$I_mg#z{aXyVW!qm83QH zm3$5M4HoE)Lqv5oj(GOGAXAZH+dSh{V?*Td`>b#BUr;3dUj|b^%9ufcBaUUJzQmb8fTme$9{i|I)ALh0xpLont3whojxyaV5)Sz-l@67m1#zd(sz9jJWb zs=xPN`2%8G0+nh^zU;oSojPc0SYE^M*wAe_UudQh7=x;<_~Ug|i+2apS|bT%MlHxP`u8%a2MTCzyA0^yNRs_M zlr(j|&p&G_Ud-^yFr*`X$@^aU#NlO3ZFcdM-M#D2+7;|&o%v;SBP(t`j+79s&Y|O6 z0x;wyrk`N)hd6Nt$vBl{Z4)%DqIP9PuXcKIjh96LVx-CV1OmaxNU8_FC#+@+YrbDJM?gj3uE97OBSCRx>6NMi>3T&r z+&)y8kCktHmy+T5ytR)04F(Z_`6$L?i|mPL0fF(vHca)ZB3BO~lJ|HgGruItC{?1F z>cD0mblL&U1XmQNc=&7PY|kkKPaG6+ta)P*(#XGjh{6?lnK}+f4dY(HusqpIEqze0 zF~#_^l!G8PmP31WmX>02j9p(mk#a7OEfPNBEY6v&L-o;(-F<#A0(bzdkmxEFw`)|SzUZ?g@{Py9s< z8W>Z-47z`~Hvs<%irzlopq~87$=nin0yA#5MY@Ks;spg91)Y_QIj=*aWK!}IP$AY> z@^@=g!>TB?Jf^Z1?_ABLYW)S69n-0l(eC!stCCu{>FcN1NwrcD-Kr`_P1SCvsotI< zJWP7MwaH3(l{)dTd2kC1`X+Y0?x~{6Vl}zb1Sb3i-|y*Vz1M=sjZsr(4otvUpmcEx zRAF;zgKa4`Ln`QqMn*PneF$RbKU!Jd-pZ;qrkWIJYmeBIhrHl|)<;#p!1Sjv@^=!v z;6||cza2F*t=mw0Tarcsv~}iJ%vroNIXI!1i=L#~^SHgfWB$H)xN_LRB>mg(9$3&V%P*#j%s>i`xI;B)oI;ZV?mKtUuZ+yHmb2 z&A@eRQUUIfnn2W_(4V`n(oHXGoCmk#k!+f69Jb1}?Juj}vq(w@a5q#EFx_^%csA4Q zX-#_Mu5cV5`iHP@hoSPWEVo@JR>^LO^C3)CBQ9_v+CXufIvI~q&tAxji`t`m^!b$g zyFb^h8sHx(HGhTFAcCT>#3z~LJlv4MTJ*>;N|HOCLIwN?^&j(dNdbFkTqi6EDv&E} zM%-A4L0nmjB#g6$8myaXMaL$ZvHvsB|~UmJ>dw0j27#(K#t(NePz!3NmQd ztBd{vfILf6xsCV(vTLmQR-8oVZv}pJEl4l|toD9DbqtCebM`rv} zIw)l&MWC`8pu=%;Fes)P`O8MR4B~h}`J~0xX-o@_9adf&nT9)JMI6kw79Q4V8-AIF zbfV%lJ?_JY5^7SYL*h3{032*yD$_~CE?3e!E;>gnfNk;3%+bNSL0-F%XcIo03p4N0(TW8tT=)EgC;@^2Z#%l&`-}@4I!}ODdrMV891ot~V>;PWXAl z+>N0jDWkQWH0dqmFY^lnf=yuwdm!F@oR^k~ZsnFNxK&!YsH51Z)=ErKkn!OW^VVT( z#jYPsW{($gYgzZ+)4ryd&yE0JO5?bZfdGX1Db{3sATmU4{26Esuz_X*`ggM)%)Clq z`9kx&rT26Hvm^zds0N!=Co#dD7QA8u4-56i#@5fd7q=1%E4mh>yanDVpo6um3g>|HN{i|j0E-lU@WuG3Cu zduIkICRW5pJp}xnNG?3F*#17RGqGFLzb>g@F6R{Lmn@7xvcwk73T9_v4g@NNg{NtR6P$c#Tw@xF`#cZNHjV$s^Q=ojzeB?sN1WPAk8g?V{qASn0GakogdrU z35&2+Hf0c#ytLsBvHq%uBL`(7D{ROg!R~{{2xvz6yUYyW+ z0Kc5_N~PPNZVA$EQP_uDTCs}j{+tgKSE$`yEB@RgG8dhxH?DE5U3zk{@w5;b;`jc@ zt^l_E5j%I8f^u6^!l5ngo77G_Qvpvk4)sr${O_?RDuvl>H^wkMj3=c+yKnSD76r?O zo5BI~Qz72hNTVo+{xIz|Ds1_+5t7x$1|q&oO04nG{;Sw|5S?kevR_AM z(8!|oK>QZliPvlI%pdy?3cK=T|F5;;fAt(C7DcnxLJ!@(wys+nKs!PRzr2Sm4-iurWdlY9kIj})sKK1O*aikHvc#H;>?feL86RGzrDKn~Qj zuaS(4{X_-p*i||J?5_WS^a?2eSDJp$T25$gRc00a+&bIMSKSWxqte&E!XuHU?$CzC z4G&!OGCp(2LCV1@SrN2>9CTUuZkjyw?qnISE9q?g>+~7hOZ`cp`doqk(AJ5Vc4vz= z8_5an9F-fPdvBtjv1bgYSg=|aSW_)WxGfltTYW&H>MOZI?0#Sbv3RP+&_38xFvwH6 zE=alleNn)P9ZLhe&kJT%;33w1qmpXlGLUVR&GEXU(&}k?Tu*wvK|$)&x5~OnR_e;C zV57PKBuAN60$B-hLMCwfIdpt^7X*&GD)z_jnG#Z64wTXN=YCZj(8h@EsXdo3BbCgR z37?W{@$o-9QVdd>{?$`Czo$V%l%btuR_SKcIyXS~8llrz@JY%q@E*HI0y8N83^4C6 zgd~G$kts)@q9CQ*58)}o|IZ)uJt{9?Z!fUYOj)s?G`;1<<{kSc*IZY`KbGz|QNRDC zy(Llg%GueQxp>eqx22RQi|sKZG3_Y^K;u(1B~>5ao`Qe$prT-Fv3{tE6Ah%{TS7(Ce;}gXnGY1Jn(>DBbayi z_am|w1pW7@=Pz#8!L}}16*+=gvi-M1YWKll7bkJA@NiZCSHo!>QSl##{_|bDOBC0m z2AI*m3;9Y8c?&fpLp{g)S#5uOjKX>QL!4ah3Tkm-WWvzC{@5js7j$ZAT|J2a9KJMP zm_*r?wc2;38Z=u$k#^ad=hEl(bmWYaXE&&5vCct4wz<2ekiy#0mj7 z4w9#V}x;HzIh0X9g8v#@>IC(B&vg6(pa zpCy^8m{V=W_T@I!*SFRuOl%R#ZR!b|o)gdoWDw%W;mj$+`WzfP!B~1RysNjbk1rDQ zXLp0kTU=co$#nK0nKgq9$EL|r39pRYO({7+^~rGE#U){tb`y)_;8u-qU3`?^yX53= zvva++XbboXK#j$9rr-ItlgC#otUFow2YH<4Y5UYJGIWCXWx^Q>?qaU8Z~C+Dn2*9% zo8T{^?m!=0qd+a5k4+)j_V%<$jjqfkl!uSSl^y$hnGna{XS zOgr%z(0J~vd61}QRc}TUAriNc<#AjnKzI5b4-{aitKiFK`AEW(@>;}fX6%nxH!3SN zpO_h0=T?e!MF=qXi>SsS(D|djv8q(UA8dP$D?JK+>!^`L>w)AQuxCxd{|CgzfW3V6J{jQ9 z=p{CxKAwp4&Ir2CyeveNQi?dl6hu2J7yaQvbXj$P=rq8&k`1r<;&!T9Gg;oUTXXGG5(7Z6tS$yJ1XRmFHBP35Rm>~BXG=Kul95xZVp5vd#>=3}j3?Y_kY zLa>}sP$0GlnwTU@B;2kbch?XTrg+?mLLuo~uuzszlgGz-8c_%g@~hqpf!C3)cIBiW zP1_d}i$d+))Y^1ox|W&*2s^cYgMNnvXF$5U4&>(!m`w8XgxMIDup#5eVV_X{Ko zs&X82hACEWdSP;H{5^S&hWo(=R=0whJd5NGVI?*9F_=|ItnWP7hz`|6;<1|{Xr0F<=-)NSYUMdTU4gMAf(yIse$201MXK)R0FXTMG zoOP-lrWBrh^i(y8PV~%);mg1v2GIwu7_YJwkkFdG6BB^(V?3)@ zoa@9YblXqyFeiOzA!Lbes4 zBz?ocBj%~Bm5U+jZlbb+eWlWc)&mDoBn#`ykp}vbPMR`2xxc%v9{-bdl*saf_7RR@ zYPSW_r$nqhY(T(B?GmqKlU~SLKQyaNR0&pD#2jWtH&};i+hf_Y2#L8Gafa2ZQd_$& zn~vpMd)~BdK6M4ea~Lm4*9pC#uKIHc*nWIvrNl1XZJn+kEw;iTUcWnb}k}t%fGzm1{h< zdCzGmLp{%KZ`BY-{JTNqISI+$S=vq=XPAa37aPufG_2*)eU)^H~~ z+c0d=(GQ<+?K2+&W*?8N_V|f+UI;myV|EgJp`UU{c>6+qP%EzLF$e=3MK5V*&|eHA)y|yly<+

>`yRI?13uULm=VEkNCv6pzH0IFSJXf z&c_4g;SR^GJe#W+P&xMmV}45IirTL!LOrNV*qGE>@3;=-RhW^BtKq(`m9{sB-ZD@R zRxttfghAP*r(ejeH50T??_}y6uQfsCRNH7#f$gRG{DH91C!m3=>*q$iktMyf*Mg)d zm7Gw8W|u$P$wMFvI<%@YYhPaE=WRnQ^b@1kLyj8>5eKkLooKBtKJcD0MZmN{u3!ZL zrpOEZ*Z0|S=$??jAUKAQE6`Ya^G8`LqMD*`F~Uc;fK^$>sAomJN3%mp`5iX)Z^C@= zWJ*=8ER6cqaB7}{_0>&HRE3m;t@Z`=%GkOg@K05RBvGoP7ZNK_x;$LDur$|wdC%8A zBNQfK7U$682#(i{$Cmmxb=t=&!6uEWGH74%&ARgr;1)IXgxOG`!7B|O=8Iy6WRMpZ zd6mgGk*X~mzl^xv6ov5~KQg@r%hy+*I-U88a5A9lg96S&<>-k_+h*TiGBz(8%1rZ( z;o7FD+{MnB`p)t{`p_+yty1QS8 zts5TPt0`LFVoGt1HA8itZQi~3P2I0~?Kz-MVPNl>>#&qC$?ecz zG@R9!a|$qqdzRYyleN^J-NA%^S1>KjiM&y1^-lj*N;aBYIS>8mtC%~#V4A=1;alc{ zPa=|Z^)p@Ux^@+eI`V%1eK6+TcJ;!~6XojS3OTOlZyuF3h zwF=T@rD`@7xMTmTJyKtnZD?0x19NA~6~QcM(TfYH77lLkqzF)P?&q`o$N0I1cVe-V zezH+vQ{$)~6k{txte}xnwWs_cuK6oph)KWy-k=f2lR?$+2Jj?HgS%2XoTiUW_O}%; z$mwg+t4y17Le~SYVm1*7qvIe^!?Jzvi7+29evXn@2Nd>a+HDYfg>}DVyZC)sO zbTYr#?-+Hxq)o`oM0s5yRX1WMm(@eYk>i`1s@yQ+u%e-|%`5L|ynfLDNG{YuZDJ_fIS2=Cg_120NH))R{KW=3{lrNp@%;|froKkM1JI?%$L1Hjz&!Aid8F6N4rKALT~(D z+A{T|oY-Phr!`ww$vEP0({cC%@8+{{mXnP!ghO>mXrh8xqfEmh9k5aioWl8F60hSD z?9Gxfvc+`xE!l!AAy-Apl?SXFv8eM#GQcG@g4L&}y;j5&Cq4)Aatx9<{%fTYdaKhq zeur6R>+PG%+5!!h`zd2~gq$+~A}BB0u_nu%&V3@a6PRm1(T7gX;s4A5T6dyS=%RL- zF3Jq9!eDh5RXoGI1ar#;O9Wk#mhOlFQ9K2@wzvBxbkpvB%D!UjUTP+<@argLfjCi* z*Io-q>-nPVKAx9#RAm5lPh%}(6SqD#-ttQe;}Pc1j2n`aEm*j=keLZyatF*?`NOl< zpe(FC)Wk^}P ze;~y&O@^(yrPLm!HEIW$3F6qVscVfK(c0E=vKo1OK|I07dVu|U61%YPIcqPkPp6z3 z6oq@e*@DVOlod5^Jquf&?SSE4Fw%WXTCCqcJk10{1x+GBH)%StO{uRKT$D2xYN|h}f0%!^su}(iLGW$gNQBtM z8%R`NT0Wq9-gsiqb#13z8>>7`3pyQ&gHULhOj8r|y(9!wGVAsU)zEO)C2&~wA6T=r zCvzpNXI2b78$%3zE%6@Z$9zF;(aVi_lEQ4Ru&EyMN)1BwU2`}4QMJ2*MO_A;kCs&m z(V{a!%=@qsh^OUNY>#JoWMz0JL0w}SF)%}>j!cwh=%fEWf@gPssp zu#MXKh!qrc!q@nO9>@jeWA~BkuE@yNU5+PZP7rQ2z6U%#56pisgx`wbnpGMz74_Na`tP{7*Zq5>%b?I-UcU6r6wz{CG zvs1GrIBHAn@$_kCNtx;gU!L{u61`5kS58)~hR~m2OMpr{5&|7V=Br%q!0+F9!jX(% ztZJ|MI?z)4IcP#0i6VwnfhI^8E^ut5kjP|NNU3x|I$#)Aqj$?*cRT@AJ+`!YZfo&##`^nF8 zw!a|n8h%+cFQ27i5oVL@kZ$c1)781vZLN?srgU#uW<*huPTS`w<2ziwIptyb{WEG* zCOt@T%tcYK;#hWCRLR}<^ni>A7V=G6N3Zg3!;lWyv2#&$rw(EQx&(lK*#zvq!as(o ze0nvMKt607bxb;FzW}Gah4t=k4 z^z*rU3FySXD-9HLfB1lUc+O|~&zNZ2Hj3>puvN(_rBa)99lf8A-L6K}XZr8z_mW93 zOIA|f8Xyq@GIpi5R};J`vj$ql6%z@~QRy!Q>F#CO$TBNk*-m9F3tGP4GN>01p4B7u z-^9vjTfMwi?5UFL>(fK=K{FNR`z`TIy+ORRy^gqZ-Kl!jD51;RKx9@bW6F0Dm0E|J z`7elYZ4FH(CGu&UV5|FKU;C+23oA+;PAK ze7u&T&^~9bYjKGA)|I799gwACdf7Q!I@ocJU?^Lk38}8XdleZK;~ayOjqac5&`6m& zzK%r0^dIe>QdnVj>U)H*L@s9H;Ai7+uHb0;j7O(Eb=?bz3P4SrU67626IOReVI{vB z7&D@#4Rx@U(@j*IoS#Z!{5^=acqOX&ABTi;>#GD?GKP@D(lUnLT9Xh$Jo%gVC zbiRi7_{He&+a@Low>`ZMe6pjR?o(@zM^et^OAPVxgjp<%+w$U_NYv48pmpzGyrdz> z*((0Ex$((;%Gb)?3Zs2kwn8k?=b8xaw}Og9Z)|aw5C~mMMGjHJO_9&J@i|#CVMBgl zxMzyrfvYWNM7Q& zr?|>jchAelSw zotO797glv(lvc>VK}WklQA5i#R{A3t00VG*RAa2Ba!$_Ee0g}^bXX@xirAw(lI)7Q zNlP#$xZ!*Z1~z-YV!v<7xB2$|(M!j-XYe0^ZMU&2ceiHK_0KNT3Zew+1@M;)ezfGJ@Fc&Lr0D3HD+pV!h@_Yh)p)YXye~!F>X;3G zt6h69H>Le8;-kM)Z7Ce|Z!lfyc8q_Gt9!~O z{$^rv<-X?7(k0m_m+aXDfeO4$k5v= zwrmkUq^;Sa%jm4j;wka*EXS9Ad4ms}oF2=oZ%!qt?6RTnf2m(9um3&_tb?DoT@iEA zBA#E>o7?{d!HjuwLp9TIQmXXj)g6zYyQdXbfyf3}6X`He715fk4iDQ=+_`Z=P-kRDkSQx|Denu73Lf4 zGc&2(F#nB#>LrGxulnA_bSSae^bbT+Q;eY^;CaD%Rv}*_CW@O>p%cYh4Nc&EclQeV zr1?0nKA#{87p;`-X%4fd$e;@nFnBPkXb;b_wUVFp#RZ2d3vA7PN&f7iL)%?m0tj=? zV=X)d%oIAv=4A7=FH*5hykDgBX-rv>jS-^eY~$;Y=~3TNL6WzNvo77WPeEti+}^m6 zaY+3P-HeHs#V>}&3`1uQ)vH*ecLAbTJy#9F&jMPd)*KApC)f$Drz$l8alhPccCwMh zmc{ojJFhBM;15dvV9(u*MB?0aHY~aovk_o3y#c7}Tuk1ax0ZKD zFbC(I%FRR82Kh3_9ztiL2mjT2yxzCleV;mrmE8-<%04H|5$haBPBtgnHrAP3$!Joi zJS(CVxIi{k9Q&DOmJVstG^e|<0kntR3p%7vhbDrr1u4t?fM&3l7>G{;{JPidqhgxk zT|CBD&Rvkong5}+xFk}r6^}M&LE%8UPk2H3n-FQ2P=ggsaua-p(zZSv_n9zFxlL@a z%gEN&Pl!)e@#V)Hc*oZU@wq%%Opo*Mrm98S<<%7`gobVdWC!Au?V-#I3(OVe89ZOI z?L(QEN*nvBax;iKoZUCc7o$-ZNYX}!2CcvjzsnHfwy|IEHoNMM`B6veaRyQtfa+M2 zZ6p4?&d|YBHRy~%BZF@QF8awKe)qWA!c?| z=qIxso|iCHx%$S&KCDKTLosv>^gBCM<;mK6vJw09MP_#P=`DGT$D|jVC0AuhYLA@` zZ&eXIC0^*4Q@HUvz_ZjAkJUmja)1{^XWsmKCXGf%RI310-F?i>a>71&kH1us6>#Mz z;NxEGUQIlNN)O?5KxcYrr>kU)v(@zFnx+X>B7mycT{SHR7XA3QFTWHJ?K0(t`% zkQODWe$m^ogv1kle;)8QQ))mWu$=n(O)INsNqzKvT@f(scJ!8iThdcNI`iXYzrlh| z#N`iO7vfOpSw$F18O{?4854&MV+ob!N%nR!=({D+iCSgRvR@n-WQ_pV;)6E@1x^wD z`99L_H(O#)0k{X=XsoOC)3HzPvCyHN{m1gfwg&G53(3oFzxt3fOB$cOd}S&rkxlf| zyC|Y?+@ArsE>fw&NDD3D$a2D--hD$n|0((m|435%$gjq*xgdDyPW2=+t6T*>d%57( z`$L(VCHyFqb8W+9ua1&+FpPs!$K zJ5CDAYydJhe`Rbw2{DFA%hdraj^NP!W7t4Uj-ky(L(Xuk`f}^4}jW4lZ78i}r z2Unf^Xa?hI+U6i~EN*Tbsk?)b%2o-d{5zAAw(G{`=GJxr1RIE_Ilq= zyBppz)3#-x2f_J=e+hti3YIG|C?V2*bA46et`4?e=}M=SeG#f+I`f#BnCiDu1M0{- zi4A>*Sos;V=9K5D;flKI2Xz60SG_J*^#J4X#$}*o*=u;5zV+nNBJWVPq8q)o)dIx0 zQ$Z9*IO1#nWeM7+R`SyMY-P>ccdW*{;#LjrPJF7x5Ua)0Y@EwKU1x*t?i=>{Jm3F&Kpg03sE(kwr9u*^fU`kb zZ+^{UL2og&L!A>pR=T5Lr_5nD-6>j~Y=JD_^qDREL#xJ*7Mf70&``D=kaHjkat^XF z(;Tx^3I!;u-nEvTc>|bEdP|G*{B`iZo3P7Zqr2h4#hZMKVVWk4Lo!C zfPRCl0+vys!w*nf(`&XSP_X5$bHwhyzuo8b&8F;9pZdq#t#6ozxf?hM6@LIQ>Mo;! zhd_`3h(!;6mKX8|yQg4v9cDOlZi;>&oIk7MJZxiq*7?(jw{fEr31S1wt+;STNg~yG9ElQW9HW3XApEg9vXoj|rVPdmVwE%3xci3d zwRJ6p=p1o1uOn)5_7+~HjZ{@%CztLg(m4@ZX*VQWA}5e)bIVsSBik;Vu^vA)9VQqp zWkaMsl{}?5&Z-G;9y3WABRq(|cIqaJsbs{Rf6EpDgx|0{uu0z8F8)u79I$#raUtI$ zPEGY(*xqI7Gs1zB;7Cu}YHWU}L}<+lr7?U`OnPq8iFF)qVQo(2W|;K=QPOBGPa+ilFJR z+MOEVtX#sxgf<}8|A`YNyf)cDwd+6a5Ydd+T9gt zzMi2g_bjCME>*?y?6hW-%{l5<^h)byoj8E5zXGMD#xfB~A%W2~=zm}6jF;4ZHXekO zjRmZRNSwW?HNDwkdWiBqEF!;B5z-Zuaz{nQWV0~1eYM%*6kVQ=DW^F#spRAat?k4}@hu)|mtC!VjP*FwC1x@TZ zvlVu8VS`y>ry1s#7tsizq!|5*VYS``^_{-*mx=L3*onj zR;dZTYQ%kTc`W1I(_UELrQY_X4usVYsbcCok0=>`6TQdeQo|+U_z2iw!M&Lp`|;hs z4weU%n^HM>WkTHQ>}UHNYVltAYd4n|w=*1GZ+)U0@~m?K)5gyGDq!@NS2g48?^v0^ z!K-6Q+?MHzn3BAz3C>Q#`sYfWsp7Blkgqbl#st@>uF;%s4Xz$S5K0dZhQR5<{}Nyi zr8d1nqC~O#!wPGB1yaNQ=biYUcS8@eZD1Sue^g(vJ@|0(d}K(3Lc8bRzM1%;mm-Rk zTIY-~9o?{wEpmZ-zy#QPl>|u@`VOXlfI%RCyuVs}4tC1p_U-efE8R8@txR87%^bxZ zn^rPigF{b1?Q}UStnT(2ao)lT;_;CmEp8{jv2KK{mGad4ffA@*SI$%1&eMGfGXURa zV-rY`PvZ|gXTOrVvm0CNg$surUX+YDc{M+D%6)Yfewu(1P8#RA&5xbs3YcVOl24>| zOUz+f;$Er;51x5M7dS`V`|MPBWn(6SuGNK*f{$?KRNcUl)>pr1Br(l*pX45ERDVmG zB`^CJq15F2nW%Z-n#ua=J0F-8`^zns=uRZI+oP;3(#LKWk(Y4J9FL+N^*dic3NiYk z`Jre-%d5+>If?G&S)hJZX< z7YMrMagc;?gOLEpmPh}?mPh}?manR~-t5jKYgb}7)ig8=i+WxB&SNM+Qb?PwSRxss zHvlnl`p(a945mVl)YnEFL_Ru<0ZaT*(4 za55U{1e15B(796eqzQlbg?8cHo1GsdG|3{8OqG1_J0bq8lS@rWVdz$+i)?yKl zEN_`Y3mSs~iPm2l?5oDXm2D7jSV~plzJb|vc_nP8ip3CtKY#%d-n#4uUYF%v7fGF> zRQKkCV5aI<+zu=UUeB)V@ec1grcJ7{IFk-W-{WrC zs5BK~f3Oa{A*fUG1#&t5LcXKKQ8!~IlDX2kGoyg@_;5u1-4{74B8S*_O8&K?GJ~lnWVKNvIc@A zFu*Y@;?b~bQ%BQ`!$w_wlbvG0yAO#kI%SSnN82gvsMu;xv}=V;Kf;a=XE$~%hxg0S zfz>97=Q2?gF>N)564;!?)VSA$x4JQ`0DIcSIh^?nP2ma6x8;B*6u)AeCCO8=2zLlTF43#$rjrf5EFo#73Ekgdtu%G&*ey$1DON24d39`nNuSI^Qn zD_#nZqva}>?~U7@*l-*7@u80o0+fwHE_r2UZdBW?@V>N;P*L@Dk!20T--qsg?DPOMN9&$(&ZZjIm zRmI482EXA&N1|%2Pw#C5HpUmUiK;Y6S)uJZ!tKCVP9b-;sM;``tsC1lb%LycAmv3!K+iSbM&$IM15d|&Q>>RhF0#7 zmLrCDfcHlB!{8K9D^V*^gAfOc7741?zq77pc_b--DC1hgRh;Wlcf9-X-io4z+{LjF z`kRl5Z}0YxyIb^4rL#<0_@q;t5#6=~sQd8^_)Oz+&wlaEjG+j;Y!$$#uM+I0k090a z37*X?EzZ%FE{%eqLI{z-+ay(02`LG%GviBw1W2{jqEO#l$9xOxhDnQ2sp3d&c+s6q zhol~6S!fFP^fNx^KW-T$Wl<3vakBgO068~aqw6B7-`{ME_Edgtq#^=@B$ot9l|AENXhXoeNo#n#o*hD`^H+8{6fy zLf#HIy26Q8K$FA!f;EIA=mDDb-nh;iR+7aeD%;!L{{m5vV(;e19f=C~AXqUP!Hi6< zK8~8R;rG;_;j0JI4JmLSZW?aDtEsRJ*ATYQrGB5NO$@4l%NP+w?CG1HgFS(X+ivgMLoSk?EI5iCkAXLKrVIs{#TBSLFiV(ek4mo*;D!L5L}sFGe69DF#1b z4^5>u_-whG%4fbCLyxk!lsKj`p%f=9)cDtVAVR;Ez~uMYh$~Yv2oxbruvxt=&a2!N zI~ev=1O*jVK&-DJWk-fhfsqnuRNw!GXEOSf)TsDS#s3Q2GDv&fb?aZ+WIerO;z@B3 zw1E?+xF|mNYe2Je=}E7laa0`a%*Kx9?AJ+M_#rI&@TFw;>I%bPK}?!RU63L!s{DJL zaMX5l+WG@+7bl1B3oEDK;tWUhbugH3)9<+w%<@%j?a!HR`B~e?HCsIsKSnTyVj4 z46R)VsE~4V5P5Z7m9w~4?`$Y{<8T;5XJQ=Ln_@nlm)T<`5KR=2i3oI+pK5qPDA778Te62=O1$+WGZZ0? zk9_xGzsFJZh-)Xo<%2CiEzQZ-fx570wvSof@6zIb)=5_NIZL)v&2JzZX9GN=WBI6F zC+)+`pta5H>?Mb>Gn)_g5^E;OjAgDogH&JM|KzAZVh2s!DfqZxpVege$PcMZIQbJW z&6Y;FErf(inC(g)qa8N>U{0GmS`edDPR{2Nf;mo?p$iKdYauF$eL|2Ci$n)lp7z%pnv}@B#3g4 zR0MR%fCC;;KF&L0BXGde4C$JA`fAb*TUERH#2!!H-2N9LZDsK)L<$g*>$87)#EQde z2YaSIfg8>%fvsp&_JjTPg3UVBq=&{pewD~Hf<*<5Z~VGTv-0|xY4sH1m}+ZYK|{#? zXQUVMbGZvrCX(;vly*Jdy3v)bbmlq6{hlBA6x_)_Z3yvCyec>RLH*rD`@;uCUZj?d zVF35qy!%;m#~od>{V@hm9D#2~@{9iclgM<>_e9|iRvghAluW9pjIrxwpZFY3d)ZSm zX>UdMTP`Vk8(u)xPF#ewkExAiDxo|E!HVWyp7~4N^dQXagLS?lske(q5OhRqx^9`X z&!7Dyx;@y3=w@N5J6Sx_|kMU6f@D3D%l+n`;Fe@~u9R_b6g z7rj9&JWuB9W#cgYRt$?scKG1ftXOpjF7|f8kkBnghPLbxgd%#SPAn{#Z{T>%Ps*2pJ^RD^7)o;U>MKYJ4Ru#z zD+@6ikdZfOlVO5$)qy+bwj*g|->x?5w6btR5@jAsj*$qF*1uth?;Ws)b$g~NT z7{4`x`!JC*lPf_h4ar_60~j78f-jf=^j_Ay&SooXO7*pP+T=-xbvjv?*mJ4ApH`na zVdS-7nY;X>Q`e3Tm4;I^E9s(tHsGbjiQn>Zcg9oICAJF$%Pd;mXFOkUMvg@w$nrt! z0)^@#3^jh!n037{GDmN3v>}$hV}aetoj{RLPRF6Dh9CK*Q!7stI4`?4?YVIRB5MWf z9N3q>ZAtLQLoGxW|~?{nH>&RE_OQ6cm4{>KNAztb=cUwz^|Yp!{LB-MZNG{HHh zF&pb%cnnn3f7DeUr#T6qKsh4(A5Bxa0g?XO|yO(=j z&VK0Uc{2VjUJdnkm}Z>U2=`PUkiyen0_z1;hAUqk9gAw3qjfa#P>zhabkI;NsM?%$ zeR(#NMS9aHgzG;ankB{QNFw)jmwrQ8dl2h|*iGnXQp4F>6>|*sFKu`|u4t0<18`pU zdO_l+y=OBZgz8{)@7Q%NHQwW@_LE!s8iO|mcBJ(9uq8_c*2Wl;4^pClH(bidNCN*| z^R3MMwRsN+925CIWw+{aU>5x+)3Bi+lo1bViwHeSzP0r7D~j z#FT(Pz*5<~crPtHYLK!%2NGSNKAnS7WkG<$R5G8TGDS~`_Uv^36s0s4ZkOI%YbtVh*rbp|R@P~@s957u|!Tn$P7|J~`(rve+dajyaR z&!UGUd4r4i4b|T$Mfd&&U{k~miO+d~DFmxoH3E!on^CSPDP0;ZYoweIUxxL|^vQpa z_23(^_2+4*naQ7YyBAQKxp<<*d#W#2V1^doHW#8HFO@!y#tJ?=AO{3C{+yG(vM=M^ zpA+(51qK781cI0JAFYJQ)#AM4{OihyD>sMz*xj~IYF%v=GBx%e-AL4M^@&d6j*59~ z^3~;CHxKJPo2Y~ROumS4YOHRFqA$%SATf*kzP1*u0oCmFwu-9Np5d)e99l7l{)8x! z$_^v63-onvTS{P4(7pcy~rvxga*?8JQ&sB6s=LuJ{73dHo$z*t22VZ*40{YKMZ094OW>(_-YqHQ(spxp z5IlrXlx;Zp^oo^U z{>;;cKAuK%s8E2w8@E+LxJ8mwobu!-Tq4x1#B$>NH@%Ob{xU)>g#qa`eYy)cyui;u zehBb(dUz!NKnS&ZkX5FBXf*@H`G0Vhx_5NKX!j7%#CbiuR$zRT*0 zlT2nh*eaTFM_V(uDU!3So8t$dIVI`z5+e24N?@HkXiWCa?%(RY)a!|tj`ZKpd&{5~ z*!ecy@gP8qWu`x%wk3-Ylpnov0{9e;$5L>Uy?3KZqF$)aKnE$&nP!{QKzRRkc&Vwr z^@3mM*AKG|-hFvE=?yQgvULZoO#MooFDiU`#PLpW!(b>bwl+Bj+;S#xjg;TL{huYG z5>^Gr)Tc6M=B~TDqc84$40wk<(_0wI?n_?j654A+NAjuAK+Zq zw+@e9w$lWiZyn)QCpaY*CcIhNmTAO-*6A`d)=S<&5-`&#UrN9H197amJ+X@D!Z91s zRksw&s27;&ziMaLb-xRo0(VN2b<5AkZB#uk+ob2dAu&A}+%CQ_TMAsV%KT1v$G3Km z+j9et;&6`?Xi8&uu{L+ARrsn#i-$T(IS8wK+}0Pnv5E&(KH6!ns!`x5H`tJ&kC&$r z$z$`PA=(sOn_=f(?K2^p6_sZ5<*@_9wS?1C<5h0bx*4{S=t{}n)OV_7DEmI z{{`%c&Xh@#np(rb<^ky+CP|m-1J4^7nB39n9+?JDdJFrnp#Ie>idk@>Brw7Q>218t zm@4?tz!@aXl)3OULzIDBLdfX$qVJ~jg+wC^>{QT?R1%<1o_EQsUVoOL{*C&T&JJ*e z&`-J*LAFpkT!RlDa_hkro+V&RM?G&~fANm&vLW~9Tc{@wN=rX*WE zQvt9sw#vD_{lH;n+`}CA2pNBsR4^Nttv(GvxAlM8Do#CJyC|Y3mkc<&yql+0kkS#M z{M6IrnAKzFar_|fL{C$he2FRp5cXa8RRmc;8#G;aW#Ov!r+=f#DVMqa}wyid+mX~Z*Ay5K`` zM?c_j_`a2%82cs-GL)z^T~XWd6bh6X zegx5eHr$Jb`pAh6jzpi)#FoPc&-e5Vn8ne)om_p|cgM4Lp zBASL^6Mb4}bGjneAe_GE={S2^kGQ?qjhzg1j6cOg0@ zRL+q`eL;0-f_W|g7m_$Phg)j#0?K4#-8W+O$whe#utrw08e$p(Rm~%1)BnPVH+Fi`(^{r>tr9ZT z_0O5A1)8&7y(#+{t^mgFn)B6d3bmTr6!qIx?x)$CP`889Rg=9-KzUoT^6ZRq0K+wC zX;X}~F{?|M9^4zTVQJk3+#xT!dc9vdwz;4wJ+{nx)B!RQj#BmYay21#_zr%v5oL3;XpN-nRY)6eoTA|&5= z`Sm+o>_r8wPs=wX@YuMRwgZ#uy400^B=c0fS|l2PD9)Wy#phs-t(=`cW>y{Fs{(YD z^u>@$VivuP*ej#!$vQ(-@*?Jmpdfu`{t|bRbZE< z5{tc+#@2x8Zb>Kdd8X?lLlT8$c(3aUMf4r@dL<6DYldVG&ac)9lMWU%3IBjrx`TF~ zcn#0Be!!aGRjqA&zLmN7EHndLSMK!6*igj&#Due+xw(hqLHWO+~` z#ZQX|54Rl*l3;PfFLuE+vxqft|G&gzu#82+Kj|s8ZZ2re2drhwjQwh<+qOy3QSNme zu`Qr6(!RjPi*kz4hLijnX+_tfWwDll zyzF=Rj(4`R@#`6Mucm;V>gw7@tU=1%3VrhF@j=F)6Xvh7apbkyGDI=g^mVpn6MPWt z#@*=y;VXV8MLyZcJJk(-+d6e8>sKf%G*bt#q6Ov}237r7jc$%B`Vv)tw;EPDXTb z@$*NSM~V015e&#}iKodpjUFQrWGaGFYzGJ;1e6;(PN}=gTJl5_2Xjb`M|uKka;3G> z1xkc2j?*q8zJKjpcr%zA(16b$6(k}=n-QN3QLl~jHWcTAiySS;3_G`oZ< zv^QOZ^f*J292K2PvGa29W;S(!?=Q#=D#$i|nfMnZN@HR@>o*ZEaB~_A-c>~Zdym)Q zEt}`Vq!!oHAw{X~*{y7Sl)z0vffd{!_Sm?*@*li&WSu`+s=tl$;Xu&oC5%0#F5ke^ zw!xb}_(L^$wJw!A6|{8e8F&j?BJ20Mud7aVfTDcpyMq-`DPdg8KA^IooKco96z){AX|w>+iirddlRxOZ1HVBOPd7;%&emDEBlmRey*Qy4mt5c5Ab#JT3}S_~=}} zQ~Lp!?SoatZX?|YPw_?bBceRX04aqE(Hi^Tf>efX5?T^3FPB87Q*X?BiwwZtl3ebl z>ViXDI;t9f64Q8vJRGeK!rorX2xt1nMf8avZe&4T4YP8+5m;s4Gnk2T(>2BIwobrp zkbboX&Z{$jv+3OuvuC}h&8t2^B=?~1=uNThbYv_jzNumh;f6{o?B*c@C)wzAJv>G> z#C`gkF?Le?mMHRXxeS3iAoNVqkw=!Ns^NiMFCNA5|x}JgNRL#93%)M z8Ob?0Llz_pNE{e&$O9@tU{I0>c-!|~_k8+(Yn^-7y62pAfAp*gHC5BqQ`J@b+0Wj3 z<7o(=zkB50J7m1f(eDc80~;fcAAQWd=b$RB2rBp0xrHBM3&9dwHg!$tO9;L@Cg&eE zX8thvOw$5Za%{@eJ`bu|H(SI#Hw8z7pnL-&Kjjn8vp_8|kVvv7`UOJxBYM>A433`dZ5TYs7hZ=b=#Pnhn4P8RBq4dU<#- z<=d~;m2q*3UCU&ha{-W%Ath)|Hv+xmfmHD zexK%paiPKwLDjk~Pj1T2)ST7ru2D&U;>XJkZL=@k%;;%2&bqBmxZm6{(NJb^k4D_p zW#7fcy}%GMi~u>J74+`48>bYnC(WyV^?H*!FtDw3+hR0YQqijmZKerEEgDB0Q&O~G z7gzw&p!7P{V5-l`A{1h?isf^!H9b}+S#FU=#@r$z*072r(NettRN*%JjM*jP$Z)NwA>`kLZ;JLxW4dn~T88?|Wm z4r4jjNNq6}_H|ZJhZp@w`B{#{EQBFBV=b*dKoF4Cu%llvv8RcAuT`j~_UB2)EbaagS0lQnJP{%U%F|UOazA)C}rKq6%_*E0(Y4lCja; z5sOO;+j{A~|8QSk=|E=PcqHA=acPm%zf~h@plm(EvMGmf)6eOF!S1Q%g0;tv3Y&F^ zPeljSk?5@{_lBV2Ws{DyR^v#Ux5t1bok#BZk(~(Ui)<@Uh%AY{Rqn5V+pnP8uj6Bz zc8!ymGib!lHkLfM0Z(e%QG6%Nh7b(4DCMlrnz(dOfu^+>+LK2(4H)?Y7#@+MEm z$AKR@6}CGSl44+MHGjHYS)eOuN5KM3ww{J&CN`Jt6s+r&a!+7Ff)gh%xTE z?<@mmnufHGC^VaIF9h>V>|dG^&hcr;fh8lBI_yV9i= z8jXp}LQRc)BTE6^iYPh}W}N0JDt65w}ksnC^{g3BzZpRmux&=emg z`20-d`H{xnPuTbMQV91LT=@x$%{%|!Pzd}VZttJXf&b0t_s{lzYmWFA)T{X~tas7~ zJ#LEWcE)pwxL~qkk%EN82Y!&G1(W~KQ8gUvnUu4Bn6tS3F$AMz;ulhtGRQb(vS)N$H}Sdir? zp|`wEPHqJ*&)mbU)Nk{CIjxpS2ScOH6f-^E$zOkH*DC00G`|uqQXIOlU!^|TP{T>d z4AN3hJ1E!}1$>{{QsQ3FIFvqUcuL!lC3jtDuzo`~zVn{m0F_N5rEuJ?3R^-pmcDIQ zGfFc3zE=K((fqUCv!f(Z*5e0s#ywVImQsjWVfHB>*E@HGgq9QT)urA}O9B@Ysh-NN z363ZjyO-;%xHHaabU2JvS?gsQ*T*FZzvq%jHBf#={$6wU0Uc@s6OmNpKihT2Yu>6p zUV>WawKNfUTWy&C#P@n=^P0>s%t;kH?4>>JA~{O8Zsa@eWDsx_j%FYivho$@el%F5 z-PyV3jHt%%_e+y&f4#g&(G3Q;AM{SEEWhea@# zZRW^XFMQkRj+}+ny{MJsO9Sz`SKiCaC#16-`%3j3h0`hV`Lo@=7T*%`mJ#B0Xj}TX zA*GAoS#-JeJar87U!awlZ>*N+bHGonJqoj}IQk??xnA3Lu%I@fxJv+PjI!`wX6he~ zpG)e$F@aK0bANIjt0?DC5W&W-WjrE!7}mqX^Eo6At&tbY(Yr%g&Tq(kYX(LJeCxH~ zh~}K6jDKPiz(tx%{$bH%sKTT_Nw~+_{$^G}d6t+pwsZ6bY%iDU=nEg zhD{De>ZOnl^XaEAT+dD8kMcG^N-8!W2h@Lc%l^aH_ z&!Fu}N*&FldxA)N+yk6i47ZcL_Y$>U+00?Ja@mq^x|_ zr7NuaSsYmHXOvg{33D9c$1h`2{N?KiB?ea3kU?lk88mM(OviB?!+zxtj-JG1D4+Uw zLf{PvY$`>So+D)o5>+cd<3_*2?Lbkz#YEv8gIwMZE|rlm&#N~x<#;hZ;PsWqIx ziB2507tD$cY=~os%IW-Wd-$%31JA+NY_!`IPiKaC)zremLfyT|C0SJ{&y6@NZZ~HS zm^a&Kv0ccSZUFrbQcO87l|+Xq_;gu-WHrX?j?WUa}sq^x2w{^WVJh`h%;N1K% zwW}PYG|+e&%3;q5aoU&9}0c zK=v2AUXE%&4_BnI5m@?}_t3gaHFC%&hr2;Pq>wsS z!3ump6B#i@ryqYL@lJ+lQ8|BOhx`AOf>BcpIZ$ zy4+^^D3b0-fdvLuvkvpfXBVm0TAs$U*Z7s07iV79hsz&o%(mQ%!v#5I%&xc7H?&UG zh=L6t)LzD~atI@2N5&HhJWfIrrarY)tYtKIN1!StGlxj|Pi~P{^~Nv53J|3ud4g0G zKi^ zZlm`aU`(Y^`M|FY!zrqslz)oEy3+R4Dk@;EmbgAnO5_-P@?!L6Lcwme9mjVOjzb~7 zvlkh5Z^(=|7*4o->|)tQ3dldcSyl}b(q{A#-i+v1+5;BhVmik}-!mO}0GaXY~^i?>Q`&VF9EkzB?&$Y?J@a!9CiJD%ry~R^mhJ9|(t1=${ zg3P7x?>8K?L(>&a=Sd&HH|^*QK0Y-ih9{pFM7Debq5o)`F_sXA4iU-Yl$L;Nxo&lK zrWs!}^qNiij&G7;dZHTIyHAKllx>ec=`I!yp%&Y$d$`!D7{Xn3cb6|x;l>%$H@hil z_hl30UTUt^5bNGL=u-bkSDRpE?ta;3yA&>`(U}(PQmrysRI8-#dN)koE!+QYJbZvN z?y)BbWr!$U*@XnnIwC||z0n{1lSfNUTEYZ0qAHg-cKC&YcFpAuqjMM)M12ZJFF;;x zC1m8h^PS7yzAIxV`OWd-!nb{tBVwyaBRZ(8g9^3?Ua$5j?JDjjATui+;q6SjV5B#r zjs2MYG*^3_$HY`ER_kf{qoJ)F1OVv*_=BxhyP{FTh%L{-zUf=7Cfo_;lrpvaRmpzO z&8BgE9c309$7vxo>TWGXp@sR*_tgBT+I^ddd8kwg9`9A#Ywr4nFV`?0b+K8UmMfWndqsBPMyl-+LMv(>G8Y*M}-k-r_}tGVtLmI^dU~!QYHx z5odIe7(>%kt{Q6gHhISu?+1n9#f1@x+^0w#t9Uz9esnBh;E>@Z#FrDvX$O`jlq z;U5|rFyvKu$(+TT_Xk%eMtO)neDpU=f5pcut~Fo~FgsD-u}pviPf0R3&PZQDBid>4 z1TJ6&uqo&huGS-Buvo0Ti9ujuet^*xX3GN7rhOL*qQ^!L7btLVdLH#lN9+aA5PqO} z6Q`!p%tu0k6W4ybeM<*^(+c3Y_yU%4WZpe(ToLGzx9&M#J^y;Zo<(Lhxaqz`ACaP% z*%VyI3gDD}0X)``H?7WVNy9KSHO{XNz9a2#vT4YH1TPa1q%5jWr?F_je>^JwZCpS& zFfu>y`#H_~4GnIPF z2U`@}u;CDdyK-+xzhYB)3P&QliVD^6(hlidrJyo&3Py}4rC~EYU6KRx#)5AL`0ytu zQT`9Q51A7u?Z*%U?qPzla726&Srf*OIxCLMtB;W5SMvnFgtk*u6FDyG6II#%!TR9% z6X$vkH*NtGz{*A1qo;b*#hEUsLSKEWelH(ti}WekyT|mM$~Pu{_vWdFbVsorB%N3` zJZBa!y6hS6G|a~bOfhQr2Iqprj;6pPb+?C8`@`4Fn;JJVynSsADX6DR=r>Wq6A--u zKi!>pcK!%&y6bRa=c_PRh#NQKWiEb@l=X^U0rB+KCoK)>cPo5n$qwE^0PG{8rGOBS)Fj!?hY7`2K!e<}JwvR<)Z z-k2nMyiLB?(Va83a*L}`gb4qFN^^g^pvK=I$S)v7Fdp8`4&esz*ABsM=BgJ)$IliW zat6=l3)No)GmWQ)Fui@JxLKbcd__TG`2)gkQq+A%eY>peM*X~Q-FL^YrG|zUSui45 zS;;MKm6V&id{I(H*_Kk;7k%PH$evo*$SQt|LvLLGq8(ppyRNY5Sx8h|`iQu4F7#`$ z_}u43zjae)Vn+cGu%#UAX-0DIxItvbwuzMXzoG*S)y zlnE`lH&K{W7=t;R%C7RG(TY!vFy={Q^f1q1z+wH}b<^lu0*8jmFrT(J)Jg18Te2v^ zf?;0>UB^`}xc>=pnEd1J%MGcEwOxmZ1vB90@hGHd!ws!-cPUT8Y@jINrt&F&LNGa8 zuN`25e;onX0a(hLepWnuL3mOzzzjj1vF!je2(yd6;I(#m<$cVqc7T6%oH!#(G(cdi z=)UCYr5X7}iG4S9I3n%**DCw^gw?l{xPm$YV1^Zo^p5w^sz)|8woJL)OBby^)D-R# zB%9OHP?cR%t@sJUr8scxu|kNbi1Kb88R3zSJwqf)Csx13k>$?wyUndlJ;{3F^>uuF zc}y5$HpPw6=WWC`EA!0qg6SD(EW;wr*!kb&6`j2xak%kkElVEmR`8U?e+ zDM<$9Cg2{Bz&0yvz$Z<;ebG zrC5L~w{Vk5!-WcUasw<2mi2O35k%N)=l-JE!f)sR@l-FFMu;BUrTxdqN>NX~2=BQF zu-yOG?&+`1Q)yM3s?@56c@U|AH`zPgA0DBFq36U`J;{wG+(q|>N%|&&h@g}_B*H^$ zNVt8jJXnj@3L*e%svDx*;RdL@H(Ivgyq1H>!Hg6=OG%?vZ#Je<>TqngA1tgJPdL?E zn_8Q9e^O-?Nimn~@W={1=hMHa^yYHz2h8VFLdl&I1}MzUUe&^nPy0h2;`rwkXF~~Q zhY;>Q3EDg7?p;82;H-YaP98U`!G8<`oV<|5nwauy`4OS zf1b|sFI!$`p&5Q>q!7>JxuG?UGrS>VCvwkHV(5p_E6-60xozrMjn+b?o{x7;IPO>q z!|wm56>MpoR!;CQ$BwjQL(ZAP2->)0JzE%!-ac1(>n6I?&ZoXjbx4)Km3HMc*))vf zK7-OEzyY6r53tiZVdi=Roax?^w_Ls}m#gpO^mq5MX+Rf+Mv?n=(6tflH+^KXys4Rf zB1Y0SIv!P))bxE|9n-J|aS#8Tl90}VJ<4CnBhNY@f+6Hx50ir1%mLzX$96zewA{?D zgd*2n5jotRS5G>W_FeM(92KhdGFhoA0hPbv#?J4=UZbiMp^o~LbDiobZ{Nm4hcV@g zqtN#p`*QH*VheD$WfHzL3P>tI!J+enIp@Fn{7Mq}^)@8n9eqEUGJKTm-S`kY$aXVYwkSw2+JI7wnYF%|~i=7XyiT!Wo%P z53K~iKdzEKVYxufUwy_4Gs}m_*MIy$|Gc9ADy#p0E=wTyyRM8S`919dr$%17=E+LT zg`CUj_v>x#W;T}aY-I*+&!A7C(ZviJNDvylSAjiD!PIi@PKS#i0UP2d#DGYws|ot! zdAmK8#d)39<9zre;F8LNjfzc;Lfw+bEeiIBoaaSNKraMn)UW&{ zY(v1+$W{CS`}4p6vO9}{=eQj4-hB+XL~LLj)_=n_1LKgS>gpH7Vr6v$47jX)ZdyDk zC1j5k7=xr#Ct)xcBYs|ft=oy~vN=n$tH_CFk*Wvnh2+a_GZ8$Y2d$#%o~yKegsy`G4l5KG0{a}m0UpT9kM(CZf$bF}cP)>B*} zOgE2GX;cy1J_hH?k1EImv)%78uB82351*VHy_f4kAoKCz2t zadob@){FXcPN2QaTWq82z2pUewegNcgV(2N7H8Ip)pKmz!k4{!B_?mo%rsMM}!e*01Jcw_^G%_y)y; zw2xuumEMjK4)Sk^^Z#G0T7J{`)2M>nt>M<~!1>=+F=F`Hfq*zyUo!}M*XHl&c!3pKMz zyOJJF91T2?EnZWefp)1K&8Xs#$P*}lDKHzXba2;((T5n*qD+1CbhPJK2xGgRbbGKx zht@Tj?@p?ZViZ?%86=sX*{X?hQ?PYB;Jd>zr&$bmuK9DzAK+;+;V%TsTGKj$V@E?q zIDvJDkN?`yPg*W$wg0e!>s*F3cqdU}U&_;(Mmk#b3C*+)T`qzE8tgpw81Clm!{Oy@VOq?|Lgc$IO9H=C2M%msMt4vRh$ULJ4f zK6KUbZ=SHbyl?>sZAVqqF3znxaU|py0WTjAIimX_=LJy8TXcq z=o^v$ZA`<7=&}#)>%yFcwNB|q#6>$?rI&WGdnv%7!CO5Xvl_j-bRlMN$m(b-OcIz=g1jy_G^XB4?#KNSx5eCl| z&n$sb423^_c0antsii6*y4b?WEWXPeqY}QFG^)D3t*0VC<@iLiX!gif;kt*%>Us^H z#d$Ve-zGwT*40%qkiyeL<${Y1J2yikJW-p>^O`Vse3QfO`)7eWE6RKCnI#tyPMBck zXUbnGqVp2PPwL;#(c`1;5d`WOthI}vq*}|ixO9e`-#ws}s@i(pc`**hDhQ;GGO-;` zozj{hc8Ox0D@+)i%?lTqd>}_;Ph}EVf9=_L@~2xg^66FiAgal^(9k}K<>d=^G8u~q znGND9NATeSl(WzcnGv_TpGn=7%4JzMyILyQA@DMs_kKsRIEo*aODwO{S&}JO7q8NKekfnOeI;`#Hl`t_4a*Ad_ zMw!8cXGU)>0I6^Q4M?yn8zEb>zwp&-@uZ*k zh&3<%eAYz?ZA_dE;GJ^-4=;(CVphh}Xd7EWL2Y+e)|AKvEa%)@y)3xvO$5MQzNa3$=sVJ&l?3VM~53<*@T2@vaZm* zcY5I0y%@2!xB;!IZ_tE|RgVA%^9^sf_3L8|P;QlcLR`(^%bt-0f_M~)IA^)fT^QHJ zXUn+NO~DV>2_E&$?s9#<=klnV@!nn5ggqb(s|UxzpWU>O$2gIKSLOR?#3i;`>3W|C zPwgO0+NAR>hkOcW%w|rDC#2*lN(WcP<|xnQ&TV`cfGly|aCFgQjEY1`JW4m1i}P@& z*>3KIMh@5!-%>+;@kiQy+H@rTq}s99#=V=0TH_ohDjSS%Z17$?KPvx7l^|3slpkMu z`Gku+uy4pytn4ZR-2T|U+sI!`c|;-oV7I9D8Atr%wu1*$rH9}9- z3^&~Y%&dRY5&VaK(4GtDFxi@Y13C z_%4ZQCiEdE|D~fo?R6D4!wZlc;O}SIch`H(QCF8zG+6OB!xmHYozf&0 zSY(CWxI>*y-w#goJiPP5n=^Ruv8-a?UFCncco3&7C9uO^DFK|x<{W?~yn_K?#hZks zTzt+7+=h25K@=t!e5o3Of`LGQ1Ni@`xID=dsk}O#wG2nT Date: Wed, 18 Jan 2023 20:51:39 +0900 Subject: [PATCH 3/6] [bl_force_torque_sensor_ros] Replacing breadboard with soldered circuit enables us to speed up sensor reading rate --- bl_force_torque_sensor_ros/README.md | 4 ++-- .../sensor_driver_raw_rmd_ads131m04.ino | 11 ++++++----- bl_force_torque_sensor_ros/launch/sample.launch | 2 +- .../launch/sensor_driver_rosserial.launch | 2 +- 4 files changed, 10 insertions(+), 9 deletions(-) diff --git a/bl_force_torque_sensor_ros/README.md b/bl_force_torque_sensor_ros/README.md index f875e60fc..6d36b4b6e 100644 --- a/bl_force_torque_sensor_ros/README.md +++ b/bl_force_torque_sensor_ros/README.md @@ -31,12 +31,12 @@ You can pass it via command line, but it may be easier to write and run a simple - + - + setBaud(115200); + nh.getHardware()->setBaud(250000); + // cf. https://arduino.stackexchange.com/questions/296/how-high-of-a-baud-rate-can-i-go-without-errors + // http://wormfood.net/avrbaudcalc.php + // I'm not sure why, but 500000 causes "Mismatched protocol version" error nh.initNode(); nh.advertise(output_pub); nh.subscribe(duration_sub); @@ -37,10 +40,8 @@ void setup() nh.spinOnce(); } - adc[0].begin(9, 7, 125000); - adc[1].begin(8, 6, 125000); // I'm not sure why, but using D10 as CS doesn't work. Conflicted with SPI.begin()? - // Set SPI speed 125kHz (minimum of Arduino Nano) to allow poor-quality wiring. - // Currently, this is no problem because current rate-limiting process is rosserial communication. + adc[0].begin(9, 7, 4000000); + adc[1].begin(8, 6, 4000000); // I'm not sure why, but using D10 as CS doesn't work. Conflicted with SPI.begin()? } void loop() diff --git a/bl_force_torque_sensor_ros/launch/sample.launch b/bl_force_torque_sensor_ros/launch/sample.launch index 0a2abdbb0..657bf6fc0 100644 --- a/bl_force_torque_sensor_ros/launch/sample.launch +++ b/bl_force_torque_sensor_ros/launch/sample.launch @@ -3,7 +3,7 @@ - + diff --git a/bl_force_torque_sensor_ros/launch/sensor_driver_rosserial.launch b/bl_force_torque_sensor_ros/launch/sensor_driver_rosserial.launch index 85c9de623..185662358 100644 --- a/bl_force_torque_sensor_ros/launch/sensor_driver_rosserial.launch +++ b/bl_force_torque_sensor_ros/launch/sensor_driver_rosserial.launch @@ -3,7 +3,7 @@ - + From 17101dddad5b658bc562e1ddfe6e110b0eb476bf Mon Sep 17 00:00:00 2001 From: Shun Hasegawa Date: Wed, 18 Jan 2023 21:13:28 +0900 Subject: [PATCH 4/6] [bl_force_torque_sensor_ros] Add loop to wait until data is ready Data is sometimes not ready for a while. This causes unnecessary sleep in previous code --- .../sensor_driver_raw_rmd_ads131m04.ino | 59 ++++++++++--------- 1 file changed, 31 insertions(+), 28 deletions(-) diff --git a/bl_force_torque_sensor_ros/arduino/sensor_driver_raw_rmd_ads131m04/sensor_driver_raw_rmd_ads131m04.ino b/bl_force_torque_sensor_ros/arduino/sensor_driver_raw_rmd_ads131m04/sensor_driver_raw_rmd_ads131m04.ino index a3eb62b91..48454d301 100644 --- a/bl_force_torque_sensor_ros/arduino/sensor_driver_raw_rmd_ads131m04/sensor_driver_raw_rmd_ads131m04.ino +++ b/bl_force_torque_sensor_ros/arduino/sensor_driver_raw_rmd_ads131m04/sensor_driver_raw_rmd_ads131m04.ino @@ -48,46 +48,49 @@ void loop() { start_time = micros(); - bool is_ok = true; - for (int i = 0; i < ADC_NUM; i++) - { - if (!adc[i].isDataReady()) - { - is_ok = false; - } - } - if (is_ok) + // Wait until data is ready + bool is_ok = false; + while (!is_ok) { is_ok = true; for (int i = 0; i < ADC_NUM; i++) { - if (!adc[i].readADC(&adc_res[i])) + if (!adc[i].isDataReady()) { is_ok = false; } - delayMicroseconds(1); // Should be longer than t_w(CSH)? } - for (int i = 0; i < ADC_NUM; i++) + } + + is_ok = true; + for (int i = 0; i < ADC_NUM; i++) + { + if (!adc[i].readADC(&adc_res[i])) { - if (adc_res[i].status != 0x050F) - { - // status is value of STATUS register. - // By default, if everything is OK, this value is 0000 0101 0000 1111 (0x050F) - is_ok = false; - } + is_ok = false; } - if (is_ok) + delayMicroseconds(1); // Should be longer than t_w(CSH)? + } + for (int i = 0; i < ADC_NUM; i++) + { + if (adc_res[i].status != 0x050F) { - for (int i = 0; i < ADC_NUM; i++) - { - output_array[i * VALID_CH_NUM] = adc_res[i].ch0; - output_array[i * VALID_CH_NUM + 1] = adc_res[i].ch1; - output_array[i * VALID_CH_NUM + 2] = adc_res[i].ch2; - } - output_msg.array = output_array; - output_msg.array_length = ADC_NUM * VALID_CH_NUM; - output_pub.publish(&output_msg); + // status is value of STATUS register. + // By default, if everything is OK, this value is 0000 0101 0000 1111 (0x050F) + is_ok = false; + } + } + if (is_ok) + { + for (int i = 0; i < ADC_NUM; i++) + { + output_array[i * VALID_CH_NUM] = adc_res[i].ch0; + output_array[i * VALID_CH_NUM + 1] = adc_res[i].ch1; + output_array[i * VALID_CH_NUM + 2] = adc_res[i].ch2; } + output_msg.array = output_array; + output_msg.array_length = ADC_NUM * VALID_CH_NUM; + output_pub.publish(&output_msg); } nh.spinOnce(); From 4b416fe489883743c2ef4c1d9359d94b4305dd02 Mon Sep 17 00:00:00 2001 From: Shun Hasegawa Date: Fri, 2 Jun 2023 16:00:24 +0900 Subject: [PATCH 5/6] [bl_force_torque_sensor_ros] Add an example of installation procedure --- bl_force_torque_sensor_ros/README.md | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/bl_force_torque_sensor_ros/README.md b/bl_force_torque_sensor_ros/README.md index 6d36b4b6e..1b5e7ad79 100644 --- a/bl_force_torque_sensor_ros/README.md +++ b/bl_force_torque_sensor_ros/README.md @@ -15,6 +15,17 @@ Before using this package, you have to prepare a circuit connecting your sensor - Install dependency of `bl_force_torque_sensor_ros` (e.g., by `rosdep install`) and build `bl_force_torque_sensor_ros` (e.g., by `catkin build`) - See http://wiki.ros.org/rosdep#Install_dependency_of_all_packages_in_the_workspace for `rosdep` usage + For example: + ```bash + mkdir -p ~/ws_bl_force_torque_sensor_ros/src + cd ~/ws_bl_force_torque_sensor_ros/src + git clone https://github.com/pazeshun/jsk_3rdparty.git -b bl_force_torque_sensor_ros + rosdep install -y -r --ignore-src --from-paths jsk_3rdparty/bl_force_torque_sensor_ros + cd .. + catkin build bl_force_torque_sensor_ros + source ~/ws_bl_force_torque_sensor_ros/devel/setup.bash # Do this every time you open a new terminal + ``` + - If you prepare a circuit using Arduino, - [Setup Arduino IDE for rosserial](http://wiki.ros.org/rosserial_arduino/Tutorials/Arduino%20IDE%20Setup#Install_ros_lib_into_the_Arduino_Environment). Note that you must do it after sourcing `setup.bash` of the workspace including `bl_force_torque_sensor_ros`. If you did it without sourcing correctly, do it again - Upload corresponding firmware to your Arduino. E.g., upload `arduino/sensor_driver_raw_rmd_ads131m04/sensor_driver_raw_rmd_ads131m04.ino` when your circuit uses ADS131M04 for RMD amplifier From b79f656a930b2c0e1154875e3fe468615e763169 Mon Sep 17 00:00:00 2001 From: Shun Hasegawa Date: Thu, 12 Dec 2024 15:21:07 +0900 Subject: [PATCH 6/6] [bl_force_torque_sensor_ros] Remove unnecessary catkin_python_setup and setup.py See https://github.com/jsk-ros-pkg/jsk_recognition/pull/2851 --- bl_force_torque_sensor_ros/CMakeLists.txt | 2 -- bl_force_torque_sensor_ros/setup.py | 8 -------- 2 files changed, 10 deletions(-) delete mode 100644 bl_force_torque_sensor_ros/setup.py diff --git a/bl_force_torque_sensor_ros/CMakeLists.txt b/bl_force_torque_sensor_ros/CMakeLists.txt index 2da295e3d..6eb814fc6 100644 --- a/bl_force_torque_sensor_ros/CMakeLists.txt +++ b/bl_force_torque_sensor_ros/CMakeLists.txt @@ -5,8 +5,6 @@ find_package(catkin REQUIRED COMPONENTS message_generation ) -catkin_python_setup() - add_message_files( FILES AmplifierOutputRawArray.msg diff --git a/bl_force_torque_sensor_ros/setup.py b/bl_force_torque_sensor_ros/setup.py deleted file mode 100644 index 66f43a495..000000000 --- a/bl_force_torque_sensor_ros/setup.py +++ /dev/null @@ -1,8 +0,0 @@ -#!/usr/bin/env python - -from setuptools import setup -from catkin_pkg.python_setup import generate_distutils_setup - -d = generate_distutils_setup() - -setup(**d)