From ab5f4e9194b5e767d21a54c10c37c907bd7d2fb2 Mon Sep 17 00:00:00 2001 From: tipouic Date: Wed, 27 Jan 2016 19:40:24 +0100 Subject: [PATCH 1/9] =?UTF-8?q?Suit=20du=20projet,=20ajout=20de=20la=20s?= =?UTF-8?q?=C3=A9lection=20PPM,=20ajout=20protocole=20H7?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Multiprotocol/A7105_SPI.ino | 11 + Multiprotocol/Bayang_nrf24l01.ino | 6 +- Multiprotocol/CG023_nrf24l01.ino | 14 +- Multiprotocol/CX10_nrf24l01.ino | 62 +- Multiprotocol/DSM2_cyrf6936.ino | 57 +- Multiprotocol/Devo_cyrf6936.ino | 22 +- Multiprotocol/ESky_nrf24l01.ino | 12 +- Multiprotocol/FlySky_a7105.ino | 4 +- Multiprotocol/FrSky_cc2500.ino | 226 ++++--- Multiprotocol/Hisky_nrf24l01.ino | 44 +- Multiprotocol/Hubsan_a7105.ino | 17 +- Multiprotocol/KN_nrf24l01.ino | 397 ++++++------ Multiprotocol/Multiprotocol.ino | 697 +++++++++++----------- Multiprotocol/NRF24l01_SPI.ino | 2 +- Multiprotocol/SLT_nrf24l01.ino | 14 +- Multiprotocol/Symax_nrf24l01.ino | 18 +- Multiprotocol/V2X2_nrf24l01.ino | 10 +- Multiprotocol/YD717_nrf24l01.ino | 8 +- Multiprotocol/_Config.h | 234 ++++++++ Multiprotocol/iface_cc2500.h | 10 + Multiprotocol/liste.txt | 65 ++ Multiprotocol/multi.lua | 91 +++ Multiprotocol/multiprotocol.h | 202 +------ Multiprotocol/nrf24l01_H7.ino | 151 +++++ Multiprotocol/nrf24l01_hm830.ino | 321 ++++++++++ Multiprotocol/opentx-multi-2015-24-12.bin | Bin 0 -> 362852 bytes Multiprotocol/opentx.bin | Bin 0 -> 228420 bytes Multiprotocol/telemetry.h | 162 +++-- README.md | 97 ++- sync.ffs_db | Bin 0 -> 656 bytes 30 files changed, 1901 insertions(+), 1053 deletions(-) create mode 100644 Multiprotocol/_Config.h create mode 100644 Multiprotocol/liste.txt create mode 100644 Multiprotocol/multi.lua create mode 100644 Multiprotocol/nrf24l01_H7.ino create mode 100644 Multiprotocol/nrf24l01_hm830.ino create mode 100644 Multiprotocol/opentx-multi-2015-24-12.bin create mode 100644 Multiprotocol/opentx.bin create mode 100644 sync.ffs_db diff --git a/Multiprotocol/A7105_SPI.ino b/Multiprotocol/A7105_SPI.ino index 1698725..e3b59d1 100644 --- a/Multiprotocol/A7105_SPI.ino +++ b/Multiprotocol/A7105_SPI.ino @@ -196,8 +196,19 @@ const uint8_t PROGMEM FLYSKY_A7105_regs[] = { 0x13, 0xc3, 0x00, 0xff, 0x00, 0x00, 0x3b, 0x00, 0x17, 0x47, 0x80, 0x03, 0x01, 0x45, 0x18, 0x00, 0x01, 0x0f, 0xff }; + #define ID_NORMAL 0x55201041 #define ID_PLUS 0xAA201041 + +/* +static const uint8_t a7105Regs[] = { + -1, 0x42, 0x00, 0x14, 0x00, -1 , -1 , 0x00, 0x00, 0x00, 0x00, 0x01, 0x21, 0x05, 0x00, 0x50, + 0x9e, 0x4b, 0x00, 0x02, 0x16, 0x2b, 0x12, 0x00, 0x62, 0x80, 0x80, 0x00, 0x0a, 0x32, 0xc3, 0x0f, + 0x13, 0xc3, 0x00, -1, 0x00, 0x00, 0x3b, 0x00, 0x17, 0x47, 0x80, 0x03, 0x01, 0x45, 0x18, 0x00, + 0x01, 0x0f, -1, +}; +*/ + void A7105_Init(uint8_t protocol) { void *A7105_Regs; diff --git a/Multiprotocol/Bayang_nrf24l01.ino b/Multiprotocol/Bayang_nrf24l01.ino index 782d3ad..84907b4 100644 --- a/Multiprotocol/Bayang_nrf24l01.ino +++ b/Multiprotocol/Bayang_nrf24l01.ino @@ -38,7 +38,7 @@ enum BAYANG_FLAGS { BAYANG_FLAG_INVERTED = 0x80 // inverted flight on Floureon H101 }; -static void BAYANG_send_packet(uint8_t bind) +static void __attribute__((unused)) BAYANG_send_packet(uint8_t bind) { uint8_t i; if (bind) @@ -112,7 +112,7 @@ static void BAYANG_send_packet(uint8_t bind) NRF24L01_SetPower(); // Set tx_power } -static void BAYANG_init() +static void __attribute__((unused)) BAYANG_init() { NRF24L01_Initialize(); NRF24L01_SetTxRxMode(TX_EN); @@ -148,7 +148,7 @@ uint16_t BAYANG_callback() return BAYANG_PACKET_PERIOD; } -static void BAYANG_initialize_txid() +static void __attribute__((unused)) BAYANG_initialize_txid() { //Could be using txid[0..2] but using rx_tx_addr everywhere instead... hopping_frequency[0]=0; diff --git a/Multiprotocol/CG023_nrf24l01.ino b/Multiprotocol/CG023_nrf24l01.ino index 7236dd0..6810652 100644 --- a/Multiprotocol/CG023_nrf24l01.ino +++ b/Multiprotocol/CG023_nrf24l01.ino @@ -70,7 +70,7 @@ enum H8_3D_FLAGS_2 { H8_3D_FLAG_CALIBRATE = 0x20, // accelerometer calibration }; -static void CG023_send_packet(uint8_t bind) +static void __attribute__((unused)) CG023_send_packet(uint8_t bind) { // throttle : 0x00 - 0xFF throttle=convert_channel_8b(THROTTLE); @@ -205,7 +205,7 @@ static void CG023_send_packet(uint8_t bind) NRF24L01_SetPower(); // Set tx_power } -static void CG023_init() +static void __attribute__((unused)) CG023_init() { NRF24L01_Initialize(); NRF24L01_SetTxRxMode(TX_EN); @@ -246,7 +246,7 @@ uint16_t CG023_callback() return H8_3D_PACKET_PERIOD; } -static void CG023_initialize_txid() +static void __attribute__((unused)) CG023_initialize_txid() { if(sub_protocol==H8_3D) { @@ -255,10 +255,10 @@ static void CG023_initialize_txid() rx_tx_addr[2] = rx_tx_addr[2] % 0x20; rx_tx_addr[3] = rx_tx_addr[3] % 0x11; - hopping_frequency[0] = 0x06 + (rx_tx_addr[0]&0x0f); - hopping_frequency[1] = 0x15 + (rx_tx_addr[1]&0x0f); - hopping_frequency[2] = 0x24 + (rx_tx_addr[2]&0x0f); - hopping_frequency[3] = 0x33 + (rx_tx_addr[3]&0x0f); + hopping_frequency[0] = 0x06 + ((rx_tx_addr[0]&0x0f) % 0x0f); + hopping_frequency[1] = 0x15 + ((rx_tx_addr[1]&0x0f) % 0x0f); + hopping_frequency[2] = 0x24 + ((rx_tx_addr[2]&0x0f) % 0x0f); + hopping_frequency[3] = 0x33 + ((rx_tx_addr[3]&0x0f) % 0x0f); } else { // CG023 and YD829 diff --git a/Multiprotocol/CX10_nrf24l01.ino b/Multiprotocol/CX10_nrf24l01.ino index 10b9437..044c20c 100644 --- a/Multiprotocol/CX10_nrf24l01.ino +++ b/Multiprotocol/CX10_nrf24l01.ino @@ -46,7 +46,7 @@ enum { CX10_DATA }; -static void CX10_Write_Packet(uint8_t bind) +static void __attribute__((unused)) CX10_Write_Packet(uint8_t bind) { uint8_t offset = 0; if(sub_protocol == CX10_BLUE) @@ -90,24 +90,36 @@ static void CX10_Write_Packet(uint8_t bind) if(Servo_AUX4) flags |= 0x08; // Channel 8 - video break; case Q282: + case Q242: + memcpy(&packet[15], "\x10\x10\xaa\xaa\x00\x00", 6); //FLIP|LED|PICTURE|VIDEO|HEADLESS|RTH|XCAL|YCAL if(Servo_AUX1) flags2 =0x80; // Channel 5 - FLIP if(Servo_AUX2) flags2|=0x40; // Channel 6 - LED - if(Servo_AUX3) flags2|=0x10; // Channel 7 - picture - if(Servo_AUX4) // Channel 8 - video - { - if (!(video_state & 0x20)) video_state ^= 0x21; - } - else - if (video_state & 0x20) video_state &= 0x01; - flags2 |= video_state; if(Servo_AUX5) flags2|=0x08; // Channel 9 - HEADLESS - flags=3; + if(sub_protocol==Q282) + { + if(Servo_AUX3) flags2|=0x10; // Channel 7 - picture + if(Servo_AUX4) // Channel 8 - video + { + if (!(video_state & 0x20)) video_state ^= 0x21; + } + else + if (video_state & 0x20) video_state &= 0x01; + flags2 |= video_state; + flags=3; + } + else + { + if(Servo_AUX3) flags2|=0x01; // Channel 7 - picture + if(Servo_AUX4) flags2|=0x10; // Channel 8 - video + flags=2; + packet[17]=0x00; + packet[18]=0x00; + } if(Servo_AUX6) flags |=0x80; // Channel 10 - RTH if(Servo_AUX7) flags2|=0x04; // Channel 11 - XCAL if(Servo_AUX8) flags2|=0x02; // Channel 12 - YCAL - memcpy(&packet[15], "\x10\x10\xaa\xaa\x00\x00", 6); break; case DM007: //FLIP|MODE|PICTURE|VIDEO|HEADLESS @@ -154,7 +166,7 @@ static void CX10_Write_Packet(uint8_t bind) NRF24L01_SetPower(); } -static void CX10_init() +static void __attribute__((unused)) CX10_init() { NRF24L01_Initialize(); NRF24L01_SetTxRxMode(TX_EN); @@ -199,7 +211,7 @@ uint16_t CX10_callback() { NRF24L01_SetTxRxMode(TXRX_OFF); NRF24L01_SetTxRxMode(TX_EN); CX10_Write_Packet(1); - delay(1); // used to be 300µs in deviation but not working so 1ms now + delayMicroseconds(400); // 300µs in deviation but not working so using 400µs instead // switch to RX mode NRF24L01_SetTxRxMode(TXRX_OFF); NRF24L01_FlushRx(); @@ -214,7 +226,7 @@ uint16_t CX10_callback() { return packet_period; } -static void initialize_txid() +static void __attribute__((unused)) initialize_txid() { rx_tx_addr[1]%= 0x30; if(sub_protocol==Q282) @@ -225,12 +237,20 @@ static void initialize_txid() hopping_frequency[3] = 0x4c; } else - { - hopping_frequency[0] = 0x03 + (rx_tx_addr[0] & 0x0F); - hopping_frequency[1] = 0x16 + (rx_tx_addr[0] >> 4); - hopping_frequency[2] = 0x2D + (rx_tx_addr[1] & 0x0F); - hopping_frequency[3] = 0x40 + (rx_tx_addr[1] >> 4); - } + if(sub_protocol==Q242) + { + hopping_frequency[0] = 0x48; + hopping_frequency[1] = 0x4a; + hopping_frequency[2] = 0x4c; + hopping_frequency[3] = 0x4e; + } + else + { + hopping_frequency[0] = 0x03 + (rx_tx_addr[0] & 0x0F); + hopping_frequency[1] = 0x16 + (rx_tx_addr[0] >> 4); + hopping_frequency[2] = 0x2D + (rx_tx_addr[1] & 0x0F); + hopping_frequency[3] = 0x40 + (rx_tx_addr[1] >> 4); + } } uint16_t initCX10(void) @@ -247,7 +267,7 @@ uint16_t initCX10(void) } else { - if(sub_protocol==Q282) + if(sub_protocol==Q282||sub_protocol==Q242) packet_length = Q282_PACKET_SIZE; else packet_length = CX10_PACKET_SIZE; diff --git a/Multiprotocol/DSM2_cyrf6936.ino b/Multiprotocol/DSM2_cyrf6936.ino index 66b582a..e6769a6 100644 --- a/Multiprotocol/DSM2_cyrf6936.ino +++ b/Multiprotocol/DSM2_cyrf6936.ino @@ -110,7 +110,6 @@ uint16_t cyrf_state; uint8_t crcidx; uint8_t binding; uint16_t crc; -uint8_t model; /* #ifdef USE_FIXED_MFGID @@ -121,14 +120,14 @@ const uint8_t cyrfmfg_id[6] = {0xd4, 0x62, 0xd6, 0xad, 0xd3, 0xff}; //dx6i #endif */ -static void build_bind_packet() +static void __attribute__((unused)) build_bind_packet() { uint8_t i; uint16_t sum = 384 - 0x10;// packet[0] = crc >> 8; packet[1] = crc & 0xff; packet[2] = 0xff ^ cyrfmfg_id[2]; - packet[3] = (0xff ^ cyrfmfg_id[3]) + model; + packet[3] = (0xff ^ cyrfmfg_id[3]) + RX_num; packet[4] = packet[0]; packet[5] = packet[1]; packet[6] = packet[2]; @@ -154,7 +153,23 @@ static void build_bind_packet() packet[15] = sum & 0xff; } -static void build_data_packet(uint8_t upper)// +static uint8_t __attribute__((unused)) PROTOCOL_SticksMoved(uint8_t init) +{ +#define STICK_MOVEMENT 15*(PPM_MAX-PPM_MIN)/100 // defines when the bind dialog should be interrupted (stick movement STICK_MOVEMENT %) + static uint16_t ele_start, ail_start; + uint16_t ele = Servo_data[ELEVATOR];//CHAN_ReadInput(MIXER_MapChannel(INP_ELEVATOR)); + uint16_t ail = Servo_data[AILERON];//CHAN_ReadInput(MIXER_MapChannel(INP_AILERON)); + if(init) { + ele_start = ele; + ail_start = ail; + return 0; + } + uint16_t ele_diff = ele_start - ele;//abs(ele_start - ele); + uint16_t ail_diff = ail_start - ail;//abs(ail_start - ail); + return ((ele_diff + ail_diff) > STICK_MOVEMENT);// +} + +static void __attribute__((unused)) build_data_packet(uint8_t upper)// { #if DSM2_NUM_CHANNELS==4 const uint8_t ch_map[] = {0, 1, 2, 3, 0xff, 0xff, 0xff}; //Guess @@ -187,13 +202,13 @@ static void build_data_packet(uint8_t upper)// if (sub_protocol==DSMX) { packet[0] = cyrfmfg_id[2]; - packet[1] = cyrfmfg_id[3] + model; + packet[1] = cyrfmfg_id[3] + RX_num; bits=11; } else { packet[0] = (0xff ^ cyrfmfg_id[2]); - packet[1] = (0xff ^ cyrfmfg_id[3]) + model; + packet[1] = (0xff ^ cyrfmfg_id[3]) + RX_num; bits=10; } // @@ -252,23 +267,7 @@ static void build_data_packet(uint8_t upper)// } } -static uint8_t PROTOCOL_SticksMoved(uint8_t init) -{ -#define STICK_MOVEMENT 15*(PPM_MAX-PPM_MIN)/100 // defines when the bind dialog should be interrupted (stick movement STICK_MOVEMENT %) - static uint16_t ele_start, ail_start; - uint16_t ele = Servo_data[ELEVATOR];//CHAN_ReadInput(MIXER_MapChannel(INP_ELEVATOR)); - uint16_t ail = Servo_data[AILERON];//CHAN_ReadInput(MIXER_MapChannel(INP_AILERON)); - if(init) { - ele_start = ele; - ail_start = ail; - return 0; - } - uint16_t ele_diff = ele_start - ele;//abs(ele_start - ele); - uint16_t ail_diff = ail_start - ail;//abs(ail_start - ail); - return ((ele_diff + ail_diff) > STICK_MOVEMENT);// -} - -static uint8_t get_pn_row(uint8_t channel) +static uint8_t __attribute__((unused)) get_pn_row(uint8_t channel) { return (sub_protocol == DSMX ? (channel - 2) % 5 : channel % 5); } @@ -300,7 +299,7 @@ const uint8_t init_vals[][2] = { {CYRF_01_TX_LENGTH, 0x10}, //16byte packet }; -static void cyrf_config() +static void __attribute__((unused)) cyrf_config() { for(uint8_t i = 0; i < sizeof(init_vals) / 2; i++) CYRF_WriteRegister(init_vals[i][0], init_vals[i][1]); @@ -308,7 +307,7 @@ static void cyrf_config() CYRF_ConfigRFChannel(0x61); } -static void initialize_bind_state() +static void __attribute__((unused)) initialize_bind_state() { const uint8_t pn_bind[] = { 0xc6,0x94,0x22,0xfe,0x48,0xe6,0x57,0x4e }; uint8_t data_code[32]; @@ -342,13 +341,13 @@ const uint8_t data_vals[][2] = { {CYRF_10_FRAMING_CFG, 0xea}, }; -static void cyrf_configdata() +static void __attribute__((unused)) cyrf_configdata() { for(uint8_t i = 0; i < sizeof(data_vals) / 2; i++) CYRF_WriteRegister(data_vals[i][0], data_vals[i][1]); } -static void set_sop_data_crc() +static void __attribute__((unused)) set_sop_data_crc() { uint8_t pn_row = get_pn_row(hopping_frequency[chidx]); //printf("Ch: %d Row: %d SOP: %d Data: %d\n", ch[chidx], pn_row, sop_col, data_col); @@ -363,7 +362,7 @@ static void set_sop_data_crc() crcidx = !crcidx; } -static void calc_dsmx_channel() +static void __attribute__((unused)) calc_dsmx_channel() { uint8_t idx = 0; uint32_t id = ~(((uint32_t)cyrfmfg_id[0] << 24) | ((uint32_t)cyrfmfg_id[1] << 16) | ((uint32_t)cyrfmfg_id[2] << 8) | (cyrfmfg_id[3] << 0)); @@ -513,8 +512,6 @@ uint16_t initDsm2() sop_col = (cyrfmfg_id[0] + cyrfmfg_id[1] + cyrfmfg_id[2] + 2) & 0x07;//Ok data_col = 7 - sop_col;//ok - model=MProtocol_id-MProtocol_id_master; // RxNum for serial or 0 for ppm - CYRF_SetTxRxMode(TX_EN); // if(IS_AUTOBIND_FLAG_on) diff --git a/Multiprotocol/Devo_cyrf6936.ino b/Multiprotocol/Devo_cyrf6936.ino index 3e8ec7a..e569cb9 100644 --- a/Multiprotocol/Devo_cyrf6936.ino +++ b/Multiprotocol/Devo_cyrf6936.ino @@ -66,7 +66,7 @@ uint8_t ch_idx; uint8_t use_fixed_id; uint8_t failsafe_pkt; -static void scramble_pkt() +static void __attribute__((unused)) scramble_pkt() { #ifdef NO_SCRAMBLE return; @@ -77,7 +77,7 @@ static void scramble_pkt() #endif } -static void add_pkt_suffix() +static void __attribute__((unused)) add_pkt_suffix() { uint8_t bind_state; if (use_fixed_id) @@ -97,7 +97,7 @@ static void add_pkt_suffix() packet[15] = (fixed_id >> 16) & 0xff; } -static void build_beacon_pkt(uint8_t upper) +static void __attribute__((unused)) build_beacon_pkt(uint8_t upper) { packet[0] = ((DEVO_NUM_CHANNELS << 4) | 0x07); // uint8_t enable = 0; @@ -116,7 +116,7 @@ static void build_beacon_pkt(uint8_t upper) add_pkt_suffix(); } -static void build_bind_pkt() +static void __attribute__((unused)) build_bind_pkt() { packet[0] = (DEVO_NUM_CHANNELS << 4) | 0x0a; packet[1] = bind_counter & 0xff; @@ -136,7 +136,7 @@ static void build_bind_pkt() packet[15] ^= cyrfmfg_id[2]; } -static void build_data_pkt() +static void __attribute__((unused)) build_data_pkt() { uint8_t i; packet[0] = (DEVO_NUM_CHANNELS << 4) | (0x0b + ch_idx); @@ -161,7 +161,7 @@ static void build_data_pkt() add_pkt_suffix(); } -static void cyrf_set_bound_sop_code() +static void __attribute__((unused)) cyrf_set_bound_sop_code() { /* crc == 0 isn't allowed, so use 1 if the math results in 0 */ uint8_t crc = (cyrfmfg_id[0] + (cyrfmfg_id[1] >> 6) + cyrfmfg_id[2]); @@ -174,7 +174,7 @@ static void cyrf_set_bound_sop_code() CYRF_SetPower(0x08); } -static void cyrf_init() +static void __attribute__((unused)) cyrf_init() { /* Initialise CYRF chip */ CYRF_WriteRegister(CYRF_1D_MODE_OVERRIDE, 0x39); @@ -201,7 +201,7 @@ static void cyrf_init() CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x28); } -static void set_radio_channels() +static void __attribute__((unused)) set_radio_channels() { //int i; CYRF_FindBestChannels(hopping_frequency, 3, 4, 4, 80); @@ -217,7 +217,7 @@ static void set_radio_channels() hopping_frequency[4] = hopping_frequency[1]; } -static void DEVO_BuildPacket() +static void __attribute__((unused)) DEVO_BuildPacket() { switch(phase) { @@ -302,7 +302,7 @@ uint16_t devo_callback() return 1200; } -/*static void devo_bind() +/*static void __attribute__((unused)) devo_bind() { fixed_id = Model_fixed_id; bind_counter = DEVO_BIND_COUNT; @@ -311,7 +311,7 @@ uint16_t devo_callback() } -static void generate_fixed_id_bind(){ +static void __attribute__((unused)) generate_fixed_id_bind(){ if(BIND_0){ //randomSeed((uint32_t)analogRead(A6)<<10|analogRead(A7));//seed uint8_t txid[4]; diff --git a/Multiprotocol/ESky_nrf24l01.ino b/Multiprotocol/ESky_nrf24l01.ino index 77452a3..1ed7d3d 100644 --- a/Multiprotocol/ESky_nrf24l01.ino +++ b/Multiprotocol/ESky_nrf24l01.ino @@ -23,14 +23,14 @@ #define ESKY_PAYLOAD_SIZE 13 #define ESKY_PACKET_CHKTIME 100 // Time to wait for packet to be sent (no ACK, so very short) -static void ESKY_set_data_address() +static void __attribute__((unused)) ESKY_set_data_address() { NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x02); // 4-byte RX/TX address for regular packets NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, 4); NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 4); } -static void ESKY_init(uint8_t bind) +static void __attribute__((unused)) ESKY_init(uint8_t bind) { NRF24L01_Initialize(); @@ -41,8 +41,8 @@ static void ESKY_init(uint8_t bind) if (bind) { NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x01); // 3-byte RX/TX address for bind packets - NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, (uint8_t*)"x00x00x00", 3); - NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t*)"x00x00x00", 3); + NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, (uint8_t*)"\x00\x00\x00", 3); + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t*)"\x00\x00\x00", 3); } else ESKY_set_data_address(); @@ -60,7 +60,7 @@ static void ESKY_init(uint8_t bind) NRF24L01_WriteReg(NRF24L01_17_FIFO_STATUS, 0x00); // Just in case, no real bits to write here } -static void ESKY_init2() +static void __attribute__((unused)) ESKY_init2() { NRF24L01_FlushTx(); packet_sent = 0; @@ -90,7 +90,7 @@ static void ESKY_init2() NRF24L01_SetTxRxMode(TX_EN); } -static void ESKY_send_packet(uint8_t bind) +static void __attribute__((unused)) ESKY_send_packet(uint8_t bind) { uint8_t rf_ch = 50; // bind channel if (bind) diff --git a/Multiprotocol/FlySky_a7105.ino b/Multiprotocol/FlySky_a7105.ino index 452b5ff..8c5f956 100644 --- a/Multiprotocol/FlySky_a7105.ino +++ b/Multiprotocol/FlySky_a7105.ino @@ -73,7 +73,7 @@ uint8_t chanrow; uint8_t chancol; uint8_t chanoffset; -static void flysky_apply_extension_flags() +static void __attribute__((unused)) flysky_apply_extension_flags() { const uint8_t V912_X17_SEQ[10] = { 0x14, 0x31, 0x40, 0x49, 0x49, // sometime first byte is 0x15 ? 0x49, 0x49, 0x49, 0x49, 0x49, }; @@ -148,7 +148,7 @@ static void flysky_apply_extension_flags() } } -static void flysky_build_packet(uint8_t init) +static void __attribute__((unused)) flysky_build_packet(uint8_t init) { uint8_t i; //servodata timing range for flysky. diff --git a/Multiprotocol/FrSky_cc2500.ino b/Multiprotocol/FrSky_cc2500.ino index 035383e..449f954 100644 --- a/Multiprotocol/FrSky_cc2500.ino +++ b/Multiprotocol/FrSky_cc2500.ino @@ -18,9 +18,11 @@ #include "iface_cc2500.h" //##########Variables######## -uint32_t state; -uint8_t len; +//uint32_t state; +//uint8_t len; +uint8_t telemetry_counter=0; +/* enum { FRSKY_BIND = 0, FRSKY_BIND_DONE = 1000, @@ -30,114 +32,9 @@ enum { FRSKY_DATA4, FRSKY_DATA5 }; +*/ -uint16_t initFrSky_2way() -{ - if(IS_AUTOBIND_FLAG_on) - { - frsky2way_init(1); - state = FRSKY_BIND;// - } - else - { - frsky2way_init(0); - state = FRSKY_DATA2; - } - return 10000; -} - -uint16_t ReadFrSky_2way() -{ - if (state < FRSKY_BIND_DONE) - { - frsky2way_build_bind_packet(); - cc2500_strobe(CC2500_SIDLE); - cc2500_writeReg(CC2500_0A_CHANNR, 0x00); - cc2500_writeReg(CC2500_23_FSCAL3, 0x89); - cc2500_strobe(CC2500_SFRX);//0x3A - cc2500_writeFifo(packet, packet[0]+1); - state++; - return 9000; - } - if (state == FRSKY_BIND_DONE) - { - state = FRSKY_DATA2; - frsky2way_init(0); - counter = 0; - BIND_DONE; - } - else - if (state == FRSKY_DATA5) - { - cc2500_strobe(CC2500_SRX);//0x34 RX enable - state = FRSKY_DATA1; - return 9200; - } - counter = (counter + 1) % 188; - if (state == FRSKY_DATA4) - { //telemetry receive - CC2500_SetTxRxMode(RX_EN); - cc2500_strobe(CC2500_SIDLE); - cc2500_writeReg(CC2500_0A_CHANNR, get_chan_num(counter % 47)); - cc2500_writeReg(CC2500_23_FSCAL3, 0x89); - state++; - return 1300; - } - else - { - if (state == FRSKY_DATA1) - { - len = cc2500_readReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F; - if (len)//20 bytes - { - cc2500_readFifo(pkt, len); //received telemetry packets - #if defined(TELEMETRY) - //parse telemetry packet here - check_telemetry(pkt,len); //check if valid telemetry packets and buffer them. - #endif - } - CC2500_SetTxRxMode(TX_EN); - CC2500_SetPower(); // Set tx_power - } - cc2500_strobe(CC2500_SIDLE); - cc2500_writeReg(CC2500_0A_CHANNR, get_chan_num(counter % 47)); - cc2500_writeReg(CC2500_23_FSCAL3, 0x89); - cc2500_strobe(CC2500_SFRX); - frsky2way_data_frame(); - cc2500_writeFifo(packet, packet[0]+1); - state++; - } - return state == FRSKY_DATA4 ? 7500 : 9000; -} - -#if defined(TELEMETRY) -static void check_telemetry(uint8_t *pkt,uint8_t len) -{ - if(pkt[1] != rx_tx_addr[3] || pkt[2] != rx_tx_addr[2] || len != pkt[0] + 3) - {//only packets with the required id and packet length - for(uint8_t i=3;i<6;i++) - pktt[i]=0; - return; - } - else - { - for (uint8_t i=3;i>5); - if(pktt[len-2] >=128) - RSSI_dBm -= 82; - else - RSSI_dBm += 65; -} - -#endif - -static void frsky2way_init(uint8_t bind) +static void __attribute__((unused)) frsky2way_init(uint8_t bind) { // Configure cc2500 for tx mode CC2500_Reset(); @@ -151,7 +48,7 @@ static void frsky2way_init(uint8_t bind) cc2500_writeReg(CC2500_08_PKTCTRL0, 0x05); cc2500_writeReg(CC2500_3E_PATABLE, 0xff); cc2500_writeReg(CC2500_0B_FSCTRL1, 0x08); - cc2500_writeReg(CC2500_0C_FSCTRL0, fine); + cc2500_writeReg(CC2500_0C_FSCTRL0, option); //base freq FREQ = 0x5C7627 (F = 2404MHz) cc2500_writeReg(CC2500_0D_FREQ2, 0x5c); cc2500_writeReg(CC2500_0E_FREQ1, 0x76); @@ -196,7 +93,7 @@ static void frsky2way_init(uint8_t bind) //#######END INIT######## } -static uint8_t get_chan_num(uint16_t idx) +static uint8_t __attribute__((unused)) get_chan_num(uint16_t idx) { uint8_t ret = (idx * 0x1e) % 0xeb; if(idx == 3 || idx == 23 || idx == 47) @@ -206,7 +103,7 @@ static uint8_t get_chan_num(uint16_t idx) return ret; } -static void frsky2way_build_bind_packet() +static void __attribute__((unused)) frsky2way_build_bind_packet() { //11 03 01 d7 2d 00 00 1e 3c 5b 78 00 00 00 00 00 00 01 //11 03 01 19 3e 00 02 8e 2f bb 5c 00 00 00 00 00 00 01 @@ -231,9 +128,9 @@ static void frsky2way_build_bind_packet() packet[17] = 0x01; } -uint8_t telemetry_counter=0; -static void frsky2way_data_frame() + +static void __attribute__((unused)) frsky2way_data_frame() {//pachet[4] is telemetry user frame counter(hub) //11 d7 2d 22 00 01 c9 c9 ca ca 88 88 ca ca c9 ca 88 88 //11 57 12 00 00 01 f2 f2 f2 f2 06 06 ca ca ca ca 18 18 @@ -241,7 +138,8 @@ static void frsky2way_data_frame() packet[1] = rx_tx_addr[3]; packet[2] = rx_tx_addr[2]; packet[3] = counter;// - packet[4] = pkt[6]?(telemetry_counter++)%32:0; + packet[4]=telemetry_counter; + packet[5] = 0x01; // packet[10] = 0; @@ -265,4 +163,102 @@ static void frsky2way_data_frame() } } +uint16_t initFrSky_2way() +{ + if(IS_AUTOBIND_FLAG_on) + { + frsky2way_init(1); + state = FRSKY_BIND;// + } + else + { + frsky2way_init(0); + state = FRSKY_DATA2; + } + return 10000; +} + +#if defined(TELEMETRY) +static void __attribute__((unused)) check_telemetry(uint8_t *pkt,uint8_t len) +{ + if(pkt[1] != rx_tx_addr[3] || pkt[2] != rx_tx_addr[2] || len != pkt[0] + 3) + {//only packets with the required id and packet length + for(uint8_t i=3;i<6;i++) + pktt[i]=0; + return; + } + else + { + for (uint8_t i=3;i0) + telemetry_counter=(telemetry_counter+1)%32; + } +} +#endif + +uint16_t ReadFrSky_2way() +{ + if (state < FRSKY_BIND_DONE) + { + frsky2way_build_bind_packet(); + cc2500_strobe(CC2500_SIDLE); + cc2500_writeReg(CC2500_0A_CHANNR, 0x00); + cc2500_writeReg(CC2500_23_FSCAL3, 0x89); + cc2500_strobe(CC2500_SFRX);//0x3A + cc2500_writeFifo(packet, packet[0]+1); + state++; + return 9000; + } + if (state == FRSKY_BIND_DONE) + { + state = FRSKY_DATA2; + frsky2way_init(0); + counter = 0; + BIND_DONE; + } + else + if (state == FRSKY_DATA5) + { + cc2500_strobe(CC2500_SRX);//0x34 RX enable + state = FRSKY_DATA1; + return 9200; + } + counter = (counter + 1) % 188; + if (state == FRSKY_DATA4) + { //telemetry receive + CC2500_SetTxRxMode(RX_EN); + cc2500_strobe(CC2500_SIDLE); + cc2500_writeReg(CC2500_0A_CHANNR, get_chan_num(counter % 47)); + cc2500_writeReg(CC2500_23_FSCAL3, 0x89); + state++; + return 1300; + } + else + { + if (state == FRSKY_DATA1) + { + len = cc2500_readReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F; + if (len<=MAX_PKT)//27 bytes + { + cc2500_readFifo(pkt, len); //received telemetry packets + #if defined(TELEMETRY) + //parse telemetry packet here + check_telemetry(pkt,len); //check if valid telemetry packets and buffer them. + #endif + } + CC2500_SetTxRxMode(TX_EN); + CC2500_SetPower(); // Set tx_power + } + cc2500_strobe(CC2500_SIDLE); + cc2500_writeReg(CC2500_0A_CHANNR, get_chan_num(counter % 47)); + cc2500_writeReg(CC2500_23_FSCAL3, 0x89); + cc2500_strobe(CC2500_SFRX); + frsky2way_data_frame(); + cc2500_writeFifo(packet, packet[0]+1); + state++; + } + return state == FRSKY_DATA4 ? 7500 : 9000; +} #endif diff --git a/Multiprotocol/Hisky_nrf24l01.ino b/Multiprotocol/Hisky_nrf24l01.ino index d7a3fde..c6edabe 100644 --- a/Multiprotocol/Hisky_nrf24l01.ino +++ b/Multiprotocol/Hisky_nrf24l01.ino @@ -18,21 +18,21 @@ #include "iface_nrf24l01.h" -#define BIND_COUNT 1000 -#define TXID_SIZE 5 -#define FREQUENCE_NUM 20 +#define HISKY_BIND_COUNT 1000 +#define HISKY_TXID_SIZE 5 +#define HISKY_FREQUENCE_NUM 20 // uint8_t bind_buf_arry[4][10]; // HiSky protocol uses TX id as an address for nRF24L01, and uses frequency hopping sequence // which does not depend on this id and is passed explicitly in binding sequence. So we are free // to generate this sequence as we wish. It should be in the range [02..77] -static void calc_fh_channels(uint32_t seed) +static void __attribute__((unused)) calc_fh_channels() { uint8_t idx = 0; - uint32_t rnd = seed; + uint32_t rnd = MProtocol_id; - while (idx < FREQUENCE_NUM) + while (idx < HISKY_FREQUENCE_NUM) { uint8_t i; uint8_t count_2_26 = 0, count_27_50 = 0, count_51_74 = 0; @@ -41,7 +41,7 @@ static void calc_fh_channels(uint32_t seed) // Use least-significant byte. 73 is prime, so channels 76..77 are unused uint8_t next_ch = ((rnd >> 8) % 73) + 2; // Keep the distance 2 between the channels - either odd or even - if (((next_ch ^ (uint8_t)seed) & 0x01 )== 0) + if (((next_ch ^ (uint8_t)rx_tx_addr[3]) & 0x01 )== 0) continue; // Check that it's not duplicated and spread uniformly for (i = 0; i < idx; i++) { @@ -61,7 +61,7 @@ static void calc_fh_channels(uint32_t seed) } } -static void build_binding_packet(void) +static void __attribute__((unused)) build_binding_packet(void) { uint8_t i; uint16_t sum=0; @@ -95,7 +95,7 @@ static void build_binding_packet(void) } } -static void hisky_init() +static void __attribute__((unused)) hisky_init() { NRF24L01_Initialize(); @@ -116,7 +116,7 @@ static void hisky_init() // HiSky channel sequence: AILE ELEV THRO RUDD GEAR PITCH, channel data value is from 0 to 1000 // Channel 7 - Gyro mode, 0 - 6 axis, 3 - 3 axis -static void build_ch_data() +static void __attribute__((unused)) build_ch_data() { uint16_t temp; uint8_t i,j; @@ -144,10 +144,14 @@ uint16_t hisky_cb() NRF24L01_SetPower(); phase=2; break; + case 3: + if (! bind_counter) + NRF24L01_WritePayload(packet,10); // 2 packets per 5ms + break; case 4: phase=6; break; - case 7: // build packet and send failsafe every 100ms + case 7: // build packet with failsafe every 100ms convert_channel_HK310(hopping_frequency_no!=0?RUDDER:AUX2,&packet[0],&packet[1]); convert_channel_HK310(hopping_frequency_no!=0?THROTTLE:AUX3,&packet[2],&packet[3]); convert_channel_HK310(hopping_frequency_no!=0?AUX1:AUX4,&packet[4],&packet[5]); @@ -195,7 +199,7 @@ uint16_t hisky_cb() NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5); NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no]); hopping_frequency_no++; - if (hopping_frequency_no >= FREQUENCE_NUM) + if (hopping_frequency_no >= HISKY_FREQUENCE_NUM) hopping_frequency_no = 0; break; case 7: @@ -213,15 +217,19 @@ uint16_t hisky_cb() return 1000; // send 1 binding packet and 1 data packet per 9ms } -// Generate internal id from TX id and manufacturer id (STM32 unique id) -static void initialize_tx_id() +static void __attribute__((unused)) initialize_tx_id() { //Generate frequency hopping table if(sub_protocol==HK310) - for(uint8_t i=0;i. */ +// compatible with Hubsan H102D, H107/L/C/D and H107P/C+/D+ // Last sync with hexfet new_protocols/hubsan_a7105.c dated 2015-12-11 #if defined(HUBSAN_A7105_INO) @@ -55,7 +56,7 @@ enum { }; #define WAIT_WRITE 0x80 -static void update_crc() +static void __attribute__((unused)) hubsan_update_crc() { uint8_t sum = 0; for(uint8_t i = 0; i < 15; i++) @@ -63,7 +64,7 @@ static void update_crc() packet[15] = (256 - (sum % 256)) & 0xFF; } -static void hubsan_build_bind_packet(uint8_t bind_state) +static void __attribute__((unused)) hubsan_build_bind_packet(uint8_t bind_state) { static uint8_t handshake_counter; if(phase < BIND_7) @@ -98,14 +99,14 @@ static void hubsan_build_bind_packet(uint8_t bind_state) if(phase == BIND_7) packet[2] = handshake_counter++; } - update_crc(); + hubsan_update_crc(); } //cc : throttle observed range: 0x00 - 0xFF (smaller is down) //ee : rudder observed range: 0x34 - 0xcc (smaller is right)52-204-60% //gg : elevator observed range: 0x3e - 0xbc (smaller is up)62-188 -50% //ii : aileron observed range: 0x45 - 0xc3 (smaller is right)69-195-50% -static void hubsan_build_packet() +static void __attribute__((unused)) hubsan_build_packet() { static uint8_t vtx_freq = 0; memset(packet, 0, 16); @@ -176,7 +177,7 @@ static void hubsan_build_packet() packet_count++; } } - update_crc(); + hubsan_update_crc(); } #if defined(TELEMETRY) @@ -192,8 +193,10 @@ static void hubsan_build_packet() uint16_t ReadHubsan() { - static uint8_t txState=0; +#if defined(TELEMETRY) static uint8_t rfMode=0; +#endif + static uint8_t txState=0; static uint8_t bind_count=0; uint16_t delay; uint8_t i; @@ -276,7 +279,9 @@ uint16_t ReadHubsan() case DATA_4: case DATA_5: if( txState == 0) { // send packet +#if defined(TELEMETRY) rfMode = A7105_TX; +#endif if( phase == DATA_1) A7105_SetPower(); //Keep transmit power in sync hubsan_build_packet(); diff --git a/Multiprotocol/KN_nrf24l01.ino b/Multiprotocol/KN_nrf24l01.ino index 6c89ff1..53e902d 100644 --- a/Multiprotocol/KN_nrf24l01.ino +++ b/Multiprotocol/KN_nrf24l01.ino @@ -70,6 +70,205 @@ enum { KN_FLAG_GYROR = 0x80 // Always 0 so far }; +//------------------------------------------------------------------------------------------------- +// This function init 24L01 regs and packet data for binding +// Send tx address, hopping table (for Wl Toys), and data rate to the KN receiver during binding. +// It seems that KN can remember these parameters, no binding needed after power up. +// Bind uses fixed TX address "KNDZK", 1 Mbps data rate and channel 83 +//------------------------------------------------------------------------------------------------- +static void __attribute__((unused)) kn_bind_init() +{ + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t*)"KNDZK", 5); + packet[0] = 'K'; + packet[1] = 'N'; + packet[2] = 'D'; + packet[3] = 'Z'; + //Use first four bytes of tx_addr + packet[4] = rx_tx_addr[0]; + packet[5] = rx_tx_addr[1]; + packet[6] = rx_tx_addr[2]; + packet[7] = rx_tx_addr[3]; + + if(sub_protocol==WLTOYS) + { + packet[8] = hopping_frequency[0]; + packet[9] = hopping_frequency[1]; + packet[10] = hopping_frequency[2]; + packet[11] = hopping_frequency[3]; + } + else + { + packet[8] = 0x00; + packet[9] = 0x00; + packet[10] = 0x00; + packet[11] = 0x00; + } + packet[12] = 0x00; + packet[13] = 0x00; + packet[14] = 0x00; + packet[15] = 0x01; //(USE1MBPS_YES) ? 0x01 : 0x00; + + //Set RF channel + NRF24L01_WriteReg(NRF24L01_05_RF_CH, 83); +} + +//------------------------------------------------------------------------------------------------- +// Update control data to be sent +// Do it once per frequency, so the same values will be sent 4 times +// KN uses 4 10-bit data channels plus a 8-bit switch channel +// +// The packet[0] is used for pitch/throttle, the relation is hard coded, not changeable. +// We can change the throttle/pitch range though. +// +// How to use trim? V977 stock controller can trim 6-axis mode to eliminate the drift. +//------------------------------------------------------------------------------------------------- +static void __attribute__((unused)) kn_update_packet_control_data() +{ + uint16_t value; + value = convert_channel_10b(THROTTLE); + packet[0] = (value >> 8) & 0xFF; + packet[1] = value & 0xFF; + value = convert_channel_10b(AILERON); + packet[2] = (value >> 8) & 0xFF; + packet[3] = value & 0xFF; + value = convert_channel_10b(ELEVATOR); + packet[4] = (value >> 8) & 0xFF; + packet[5] = value & 0xFF; + value = convert_channel_10b(RUDDER); + packet[6] = (value >> 8) & 0xFF; + packet[7] = value & 0xFF; + // Trims, middle is 0x64 (100) range 0-200 + packet[8] = convert_channel_8b_scale(AUX5,0,200); // 0x64; // T + packet[9] = convert_channel_8b_scale(AUX6,0,200); // 0x64; // A + packet[10] = convert_channel_8b_scale(AUX7,0,200); // 0x64; // E + packet[11] = 0x64; // R + + flags=0; + if (Servo_data[AUX1] > PPM_SWITCH) + flags = KN_FLAG_DR; + if (Servo_data[AUX2] > PPM_SWITCH) + flags |= KN_FLAG_TH; + if (Servo_data[AUX3] > PPM_SWITCH) + flags |= KN_FLAG_IDLEUP; + if (Servo_data[AUX4] > PPM_SWITCH) + flags |= KN_FLAG_GYRO3; + + packet[12] = flags; + + packet[13] = 0x00; + if(sub_protocol==WLTOYS) + packet[13] = (packet_sent << 5) | (hopping_frequency_no << 2); + + packet[14] = 0x00; + packet[15] = 0x00; + + NRF24L01_SetPower(); +} + + +//------------------------------------------------------------------------------------------------- +// This function generate RF TX packet address +// V977 can remember the binding parameters; we do not need rebind when power up. +// This requires the address must be repeatable for a specific RF ID at power up. +//------------------------------------------------------------------------------------------------- +static void __attribute__((unused)) kn_calculate_tx_addr() +{ + if(sub_protocol==FEILUN) + { + uint8_t addr2; + // Generate TXID with sum of minimum 256 and maximum 256+MAX_RF_CHANNEL-32 + rx_tx_addr[1] = 1 + rx_tx_addr[0] % (KN_MAX_RF_CHANNEL-33); + addr2 = 1 + rx_tx_addr[2] % (KN_MAX_RF_CHANNEL-33); + if ((uint16_t)(rx_tx_addr[0] + rx_tx_addr[1]) < 256) + rx_tx_addr[2] = addr2; + else + rx_tx_addr[2] = 0x00; + rx_tx_addr[3] = 0x00; + while((uint16_t)(rx_tx_addr[0] + rx_tx_addr[1] + rx_tx_addr[2] + rx_tx_addr[3]) < 257) + rx_tx_addr[3] += addr2; + } + //The 5th byte is a constant, must be 'K' + rx_tx_addr[4] = 'K'; +} + +//------------------------------------------------------------------------------------------------- +// This function generates "random" RF hopping frequency channel numbers. +// These numbers must be repeatable for a specific seed +// The generated number range is from 0 to MAX_RF_CHANNEL. No repeat or adjacent numbers +// +// For Feilun variant, the channels are calculated from TXID, and since only 2 channels are used +// we copy them to fill up to MAX_RF_CHANNEL +//------------------------------------------------------------------------------------------------- +static void __attribute__((unused)) kn_calculate_freqency_hopping_channels() +{ + if(sub_protocol==WLTOYS) + { + uint8_t idx = 0; + uint32_t rnd = MProtocol_id; + while (idx < KN_RF_CH_COUNT) + { + uint8_t i; + rnd = rnd * 0x0019660D + 0x3C6EF35F; // Randomization + + // Use least-significant byte. 73 is prime, so channels 76..77 are unused + uint8_t next_ch = ((rnd >> 8) % KN_MAX_RF_CHANNEL) + 2; + // Keep the distance 2 between the channels - either odd or even + if (((next_ch ^ MProtocol_id) & 0x01 )== 0) + continue; + // Check that it's not duplicate and spread uniformly + for (i = 0; i < idx; i++) + if(hopping_frequency[i] == next_ch) + break; + if (i != idx) + continue; + hopping_frequency[idx++] = next_ch; + } + } + else + {//FEILUN + hopping_frequency[0] = rx_tx_addr[0] + rx_tx_addr[1] + rx_tx_addr[2] + rx_tx_addr[3]; // - 256; ??? + hopping_frequency[1] = hopping_frequency[0] + 32; + hopping_frequency[2] = hopping_frequency[0]; + hopping_frequency[3] = hopping_frequency[1]; + } +} + +//------------------------------------------------------------------------------------------------- +// This function setup 24L01 +// V977 uses one way communication, receiving only. 24L01 RX is never enabled. +// V977 needs payload length in the packet. We should configure 24L01 to enable Packet Control Field(PCF) +// Some RX reg settings are actually for enable PCF +//------------------------------------------------------------------------------------------------- +static void __attribute__((unused)) kn_init() +{ + kn_calculate_tx_addr(); + kn_calculate_freqency_hopping_channels(); + + NRF24L01_Initialize(); + + NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO)); + NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknoledgement + NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 + NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5-byte RX/TX address + NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0); // Disable retransmit + NRF24L01_SetPower(); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit + NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, 0x20); // bytes of data payload for pipe 0 + + + NRF24L01_Activate(0x73); + NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 1); // Dynamic payload for data pipe 0 + // Enable: Dynamic Payload Length to enable PCF + NRF24L01_WriteReg(NRF24L01_1D_FEATURE, BV(NRF2401_1D_EN_DPL)); + + NRF24L01_SetPower(); + + NRF24L01_FlushTx(); + // Turn radio power on + NRF24L01_SetTxRxMode(TX_EN); + NRF24L01_SetBitrate(NRF24L01_BR_1M); //USE1MBPS_YES ? NRF24L01_BR_1M : NRF24L01_BR_250K; +} + //================================================================================================ // Private Functions //================================================================================================ @@ -145,202 +344,4 @@ uint16_t kn_callback() return packet_period; } -//------------------------------------------------------------------------------------------------- -// This function init 24L01 regs and packet data for binding -// Send tx address, hopping table (for Wl Toys), and data rate to the KN receiver during binding. -// It seems that KN can remember these parameters, no binding needed after power up. -// Bind uses fixed TX address "KNDZK", 1 Mbps data rate and channel 83 -//------------------------------------------------------------------------------------------------- -static void kn_bind_init() -{ - NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t*)"KNDZK", 5); - packet[0] = 'K'; - packet[1] = 'N'; - packet[2] = 'D'; - packet[3] = 'Z'; - //Use first four bytes of tx_addr - packet[4] = rx_tx_addr[0]; - packet[5] = rx_tx_addr[1]; - packet[6] = rx_tx_addr[2]; - packet[7] = rx_tx_addr[3]; - - if(sub_protocol==WLTOYS) - { - packet[8] = hopping_frequency[0]; - packet[9] = hopping_frequency[1]; - packet[10] = hopping_frequency[2]; - packet[11] = hopping_frequency[3]; - } - else - { - packet[8] = 0x00; - packet[9] = 0x00; - packet[10] = 0x00; - packet[11] = 0x00; - } - packet[12] = 0x00; - packet[13] = 0x00; - packet[14] = 0x00; - packet[15] = 0x01; //(USE1MBPS_YES) ? 0x01 : 0x00; - - //Set RF channel - NRF24L01_WriteReg(NRF24L01_05_RF_CH, 83); -} - -//------------------------------------------------------------------------------------------------- -// Update control data to be sent -// Do it once per frequency, so the same values will be sent 4 times -// KN uses 4 10-bit data channels plus a 8-bit switch channel -// -// The packet[0] is used for pitch/throttle, the relation is hard coded, not changeable. -// We can change the throttle/pitch range though. -// -// How to use trim? V977 stock controller can trim 6-axis mode to eliminate the drift. -//------------------------------------------------------------------------------------------------- -static void kn_update_packet_control_data() -{ - uint16_t value; - value = convert_channel_10b(THROTTLE); - packet[0] = (value >> 8) & 0xFF; - packet[1] = value & 0xFF; - value = convert_channel_10b(AILERON); - packet[2] = (value >> 8) & 0xFF; - packet[3] = value & 0xFF; - value = convert_channel_10b(ELEVATOR); - packet[4] = (value >> 8) & 0xFF; - packet[5] = value & 0xFF; - value = convert_channel_10b(RUDDER); - packet[6] = (value >> 8) & 0xFF; - packet[7] = value & 0xFF; - // Trims, middle is 0x64 (100) range 0-200 - packet[8] = convert_channel_8b_scale(AUX5,0,200); // 0x64; // T - packet[9] = convert_channel_8b_scale(AUX6,0,200); // 0x64; // A - packet[10] = convert_channel_8b_scale(AUX7,0,200); // 0x64; // E - packet[11] = 0x64; // R - - flags=0; - if (Servo_data[AUX1] > PPM_SWITCH) - flags = KN_FLAG_DR; - if (Servo_data[AUX2] > PPM_SWITCH) - flags |= KN_FLAG_TH; - if (Servo_data[AUX3] > PPM_SWITCH) - flags |= KN_FLAG_IDLEUP; - if (Servo_data[AUX4] > PPM_SWITCH) - flags |= KN_FLAG_GYRO3; - - packet[12] = flags; - - packet[13] = 0x00; - if(sub_protocol==WLTOYS) - packet[13] = (packet_sent << 5) | (hopping_frequency_no << 2); - - packet[14] = 0x00; - packet[15] = 0x00; - - NRF24L01_SetPower(); -} - -//------------------------------------------------------------------------------------------------- -// This function setup 24L01 -// V977 uses one way communication, receiving only. 24L01 RX is never enabled. -// V977 needs payload length in the packet. We should configure 24L01 to enable Packet Control Field(PCF) -// Some RX reg settings are actually for enable PCF -//------------------------------------------------------------------------------------------------- -static void kn_init() -{ - kn_calculate_tx_addr(); - kn_calculate_freqency_hopping_channels(); - - NRF24L01_Initialize(); - - NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO)); - NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknoledgement - NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 - NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5-byte RX/TX address - NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0); // Disable retransmit - NRF24L01_SetPower(); - NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit - NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, 0x20); // bytes of data payload for pipe 0 - - - NRF24L01_Activate(0x73); - NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 1); // Dynamic payload for data pipe 0 - // Enable: Dynamic Payload Length to enable PCF - NRF24L01_WriteReg(NRF24L01_1D_FEATURE, BV(NRF2401_1D_EN_DPL)); - - NRF24L01_SetPower(); - - NRF24L01_FlushTx(); - // Turn radio power on - NRF24L01_SetTxRxMode(TX_EN); - NRF24L01_SetBitrate(NRF24L01_BR_1M); //USE1MBPS_YES ? NRF24L01_BR_1M : NRF24L01_BR_250K; -} - -//------------------------------------------------------------------------------------------------- -// This function generate RF TX packet address -// V977 can remember the binding parameters; we do not need rebind when power up. -// This requires the address must be repeatable for a specific RF ID at power up. -//------------------------------------------------------------------------------------------------- -static void kn_calculate_tx_addr() -{ - if(sub_protocol==FEILUN) - { - uint8_t addr2; - // Generate TXID with sum of minimum 256 and maximum 256+MAX_RF_CHANNEL-32 - rx_tx_addr[1] = 1 + rx_tx_addr[0] % (KN_MAX_RF_CHANNEL-33); - addr2 = 1 + rx_tx_addr[2] % (KN_MAX_RF_CHANNEL-33); - if ((uint16_t)(rx_tx_addr[0] + rx_tx_addr[1]) < 256) - rx_tx_addr[2] = addr2; - else - rx_tx_addr[2] = 0x00; - rx_tx_addr[3] = 0x00; - while((uint16_t)(rx_tx_addr[0] + rx_tx_addr[1] + rx_tx_addr[2] + rx_tx_addr[3]) < 257) - rx_tx_addr[3] += addr2; - } - //The 5th byte is a constant, must be 'K' - rx_tx_addr[4] = 'K'; -} - -//------------------------------------------------------------------------------------------------- -// This function generates "random" RF hopping frequency channel numbers. -// These numbers must be repeatable for a specific seed -// The generated number range is from 0 to MAX_RF_CHANNEL. No repeat or adjacent numbers -// -// For Feilun variant, the channels are calculated from TXID, and since only 2 channels are used -// we copy them to fill up to MAX_RF_CHANNEL -//------------------------------------------------------------------------------------------------- -static void kn_calculate_freqency_hopping_channels() -{ - if(sub_protocol==WLTOYS) - { - uint8_t idx = 0; - uint32_t rnd = MProtocol_id; - while (idx < KN_RF_CH_COUNT) - { - uint8_t i; - rnd = rnd * 0x0019660D + 0x3C6EF35F; // Randomization - - // Use least-significant byte. 73 is prime, so channels 76..77 are unused - uint8_t next_ch = ((rnd >> 8) % KN_MAX_RF_CHANNEL) + 2; - // Keep the distance 2 between the channels - either odd or even - if (((next_ch ^ MProtocol_id) & 0x01 )== 0) - continue; - // Check that it's not duplicate and spread uniformly - for (i = 0; i < idx; i++) - if(hopping_frequency[i] == next_ch) - break; - if (i != idx) - continue; - hopping_frequency[idx++] = next_ch; - } - } - else - {//FEILUN - hopping_frequency[0] = rx_tx_addr[0] + rx_tx_addr[1] + rx_tx_addr[2] + rx_tx_addr[3]; // - 256; ??? - hopping_frequency[1] = hopping_frequency[0] + 32; - hopping_frequency[2] = hopping_frequency[0]; - hopping_frequency[3] = hopping_frequency[1]; - } -} - #endif diff --git a/Multiprotocol/Multiprotocol.ino b/Multiprotocol/Multiprotocol.ino index c10128d..d075ec1 100644 --- a/Multiprotocol/Multiprotocol.ino +++ b/Multiprotocol/Multiprotocol.ino @@ -1,11 +1,11 @@ /********************************************************* - Multiprotocol Tx code - by Midelic and Pascal Langer(hpnuts) - http://www.rcgroups.com/forums/showthread.php?t=2165676 + Multiprotocol Tx code + by Midelic and Pascal Langer(hpnuts) + http://www.rcgroups.com/forums/showthread.php?t=2165676 https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/edit/master/README.md - Thanks to PhracturedBlue - Ported from deviation firmware + Thanks to PhracturedBlue, Hexfet, Goebish and all protocol developers + Ported from deviation firmware This project is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by @@ -23,71 +23,10 @@ #include #include #include - -//****************************************************** -//****************************************************** -// Multiprotocol module configuration starts here - -//Uncomment the type of TX -#define TX_ER9X //ER9X AETR (988<->2012µs) -//#define TX_DEVO7 //DEVO7 EATR (1120<->1920µs) -//#define TX_SPEKTRUM //Spektrum TAER (1100<->1900µs) -//#define TX_HISKY //HISKY AETR (1100<->1900µs) - #include "multiprotocol.h" -//Uncomment to enable 8 channels serial protocol, 16 otherwise -//#define NUM_SERIAL_CH_8 - -//Uncomment to enable telemetry -#define TELEMETRY - -//Comment protocols to exclude from compilation -#define BAYANG_NRF24L01_INO -#define CG023_NRF24L01_INO -#define CX10_NRF24L01_INO -#define DEVO_CYRF6936_INO -#define DSM2_CYRF6936_INO -#define ESKY_NRF24L01_INO -#define FLYSKY_A7105_INO -#define FRSKY_CC2500_INO -#define HISKY_NRF24L01_INO -#define HUBSAN_A7105_INO -#define KN_NRF24L01_INO -#define SLT_NRF24L01_INO -#define SYMAX_NRF24L01_INO -#define V2X2_NRF24L01_INO -#define YD717_NRF24L01_INO -//#define FRSKYX_CC2500_INO - -//Update this table to set which protocol/sub_protocol is called for the corresponding dial number -static const uint8_t PPM_prot[15][2]= { {MODE_FLYSKY , Flysky }, //Dial=1 - {MODE_HUBSAN , 0 }, //Dial=2 - {MODE_FRSKY , 0 }, //Dial=3 - {MODE_HISKY , Hisky }, //Dial=4 - {MODE_V2X2 , 0 }, //Dial=5 - {MODE_DSM2 , DSM2 }, //Dial=6 - {MODE_DEVO , 0 }, //Dial=7 - {MODE_YD717 , YD717 }, //Dial=8 - {MODE_KN , WLTOYS }, //Dial=9 - {MODE_SYMAX , SYMAX }, //Dial=10 - {MODE_SLT , 0 }, //Dial=11 - {MODE_CX10 , CX10_BLUE }, //Dial=12 - {MODE_CG023 , CG023 }, //Dial=13 - {MODE_BAYANG , 0 }, //Dial=14 - {MODE_SYMAX , SYMAX5C } //Dial=15 - }; - -//CC2500 RF module frequency adjustment, use in case you cannot bind with Frsky RX -//Note: this is set via Option when serial protocol is used -//values from 0-127 offset increase frequency, values from 255 to 127 decrease base frequency -//uint8_t fine = 0x00; -uint8_t fine = 0xd7; //* 215=-41 * - -// Multiprotocol module configuration ends here -//****************************************************** -//****************************************************** - +//Multiprotocol module configuration file +#include "_Config.h" //Global constants/variables @@ -126,17 +65,18 @@ uint8_t hopping_frequency_no=0; uint8_t rf_ch_num; uint8_t throttle, rudder, elevator, aileron; uint8_t flags; +// +uint32_t state; +uint8_t len; +uint8_t RX_num; // Mode_select variables uint8_t mode_select; +uint8_t ppm_select; uint8_t protocol_flags=0,protocol_flags2=0; // Serial variables -#if defined(NUM_SERIAL_CH_8) //8 channels serial protocol -#define RXBUFFER_SIZE 14 -#else //16 channels serial protocol #define RXBUFFER_SIZE 25 -#endif #define TXBUFFER_SIZE 12 volatile uint8_t rx_buff[RXBUFFER_SIZE]; volatile uint8_t rx_ok_buff[RXBUFFER_SIZE]; @@ -150,16 +90,17 @@ uint8_t cur_protocol[2]; uint8_t prev_protocol=0; // Telemetry +#define MAX_PKT 27 +uint8_t pkt[MAX_PKT];//telemetry receiving packets #if defined(TELEMETRY) -uint8_t pkt[27];//telemetry receiving packets -uint8_t pktt[27];//telemetry receiving packets -volatile uint8_t tx_head; -volatile uint8_t tx_tail; -uint8_t v_lipo; -int16_t RSSI_dBm; -//const uint8_t RSSI_offset=72;//69 71.72 values db -uint8_t telemetry_link=0; -#include "telemetry.h" +uint8_t pktt[MAX_PKT];//telemetry receiving packets + volatile uint8_t tx_head; + volatile uint8_t tx_tail; + uint8_t v_lipo; + int16_t RSSI_dBm; + //const uint8_t RSSI_offset=72;//69 71.72 values db + uint8_t telemetry_link=0; + #include "telemetry.h" #endif // Callback @@ -183,91 +124,96 @@ void setup() CC25_CSN_on; NRF_CSN_on; CYRF_CSN_on; - // Set SPI lines + // Set SPI lines SDI_on; SCK_off; // Timer1 config TCCR1A = 0; - TCCR1B = (1 << CS11); //prescaler8, set timer1 to increment every 0.5us(16Mhz) and start timer + TCCR1B = (1 << CS11); //prescaler8, set timer1 to increment every 0.5us(16Mhz) and start timer // Set servos positions for(uint8_t i=0;i>2)&0x07 ) | ( (PINC<<3)&0x08) );//encoder dip switches 1,2,4,8=>B2,B3,B4,C0 -//********************************** -//mode_select=14; // here to test PPM -//********************************** + //********************************** + //mode_select=14; // here to test PPM + //********************************** // Update LED - LED_OFF; + LED_OFF; LED_SET_OUTPUT; // Read or create protocol id - MProtocol_id=random_id(10,false); - MProtocol_id_master=MProtocol_id; - - //Set power transmission flags - POWER_FLAG_on; //By default high power for everything + MProtocol_id_master=random_id(10,false); + + //Init RF modules + CC2500_Reset(); //Protocol and interrupts initialization - if(mode_select != MODE_SERIAL) - { // PPM - cur_protocol[0]= PPM_prot[mode_select-1][0]; - sub_protocol = PPM_prot[mode_select-1][1]; - protocol_init(cur_protocol[0]); - - //Configure PPM interrupt - EICRA |=(1<PPM_SWITCH) + #if defined(POTAR_SELECT) + if(Servo_data[AUX2+i]>PPM_SWITCH) + #else + if(Servo_data[AUX1+i]>PPM_SWITCH) + #endif Servo_AUX|=1< led on - else - blink+=BLINK_BIND_TIME; //blink fastly during binding + LED_OFF; //bind completed -> led on + else + blink+=BLINK_BIND_TIME; //blink fastly during binding LED_TOGGLE; } } @@ -314,34 +264,35 @@ static void CheckTimer(uint16_t (*cb)(void)) uint32_t prev; if( (TIFR1 & (1< micros()) { // Callback did not took more than requested time for next callback if(next_callback>32000) { // next_callback should not be more than 32767 so we will wait here... delayMicroseconds(next_callback-2000); - cli(); // disable global int + cli(); // disable global int OCR1A=TCNT1+4000; - sei(); // enable global int + sei(); // enable global int } else { - cli(); // disable global int - OCR1A+=next_callback*2; // set compare A for callback - sei(); // enable global int + cli(); // disable global int + OCR1A+=next_callback*2; // set compare A for callback + sei(); // enable global int } - TIFR1=(1<32000) { // next_callback should not be more than 32767 so we will wait here... delayMicroseconds(next_callback-2000); next_callback=2000; } - cli(); // disable global int - OCR1A=TCNT1+next_callback*2; // set compare A for callback - sei(); // enable global int - TIFR1=(1<PPM_SWITCH) { CHANGE_PROTOCOL_FLAG_on; } + #endif + if(IS_CHANGE_PROTOCOL_FLAG_on) { + prev_protocol = ppm_select; + + ppm_select = 0; + // protocol selection + // THROTTLE up + if(Servo_data[POTAR_SELECT_M] > PPM_MAX_COMMAND) { ppm_select += 18; } + // THROTTLE down + else if(Servo_data[POTAR_SELECT_M] < PPM_MIN_COMMAND) { ppm_select += 9; } + // THROTTLE middle + else { ppm_select += 0; } + + + // Elevator up + if(Servo_data[POTAR_SELECT_V] > PPM_MAX_COMMAND) { ppm_select += 7; } + // Elevator down + else if(Servo_data[POTAR_SELECT_V] < PPM_MIN_COMMAND) { ppm_select += 1; } + // Elevator middle + else { ppm_select += 4; } + + // Aileron right + if(Servo_data[POTAR_SELECT_H] > PPM_MAX_COMMAND) { ppm_select += 2; } + // Aileron left + else if(Servo_data[POTAR_SELECT_H] < PPM_MIN_COMMAND) { ppm_select += 0; } + // Aileron middle + else { ppm_select += 1; } + +// if(ppm_select == 5) { ppm_select = eeprom_read_byte(30); } else { eeprom_update_byte(30, ppm_select); } + if(ppm_select > 5) { ppm_select--; } + + if(mode_select > MODE_SERIAL) { + ppm_select--; + cur_protocol[0] = PPM_prot[ppm_select].protocol; + sub_protocol = PPM_prot[ppm_select].sub_proto; + MProtocol_id = PPM_prot[ppm_select].rx_num + MProtocol_id_master; + option = PPM_prot[ppm_select].option; + if(PPM_prot[ppm_select].power) POWER_FLAG_on; + if(PPM_prot[ppm_select].autobind) AUTOBIND_FLAG_on; + ppm_select++; + } + } +} static void update_serial_data() { - if(rx_ok_buff[0]&0x20) //check range - RANGE_FLAG_on; - else - RANGE_FLAG_off; - if(rx_ok_buff[0]&0xC0) //check autobind(0x40) & bind(0x80) together - AUTOBIND_FLAG_on; - else - AUTOBIND_FLAG_off; - if(rx_ok_buff[1]&0x80) //if rx_ok_buff[1] ==1,power is low ,0-power high - POWER_FLAG_off; //power low - else - POWER_FLAG_on; //power high - - option=rx_ok_buff[2]; - fine=option; // Update FrSky fine tuning + if(rx_ok_buff[0]&0x20) //check range + RANGE_FLAG_on; + else + RANGE_FLAG_off; + if(rx_ok_buff[0]&0xC0) //check autobind(0x40) & bind(0x80) together + AUTOBIND_FLAG_on; + else + AUTOBIND_FLAG_off; + if(rx_ok_buff[1]&0x80) //if rx_ok_buff[1] ==1,power is low ,0-power high + POWER_FLAG_off; //power low + else + POWER_FLAG_on; //power high + + option=rx_ok_buff[2]; if( ((rx_ok_buff[0]&0x5F) != (cur_protocol[0]&0x5F)) || ( (rx_ok_buff[1]&0x7F) != cur_protocol[1] ) ) { // New model has been selected - prev_protocol=cur_protocol[0]&0x1F; //store previous protocol so we can reset the module - cur_protocol[1] = rx_ok_buff[1]&0x7F; //store current protocol - CHANGE_PROTOCOL_FLAG_on; //change protocol - sub_protocol=(rx_ok_buff[1]>>4)& 0x07; //subprotocol no (0-7) bits 4-6 - MProtocol_id=MProtocol_id_master+(rx_ok_buff[1]& 0x0F); //personalized RX bind + rx num // rx_num bits 0---3 - } + prev_protocol=cur_protocol[0]&0x1F; //store previous protocol so we can reset the module + cur_protocol[1] = rx_ok_buff[1]&0x7F; //store current protocol + CHANGE_PROTOCOL_FLAG_on; //change protocol + sub_protocol=(rx_ok_buff[1]>>4)& 0x07; //subprotocol no (0-7) bits 4-6 + RX_num=rx_ok_buff[1]& 0x0F; + MProtocol_id=MProtocol_id_master+RX_num; //personalized RX bind + rx num // rx_num bits 0---3 + } else - if( ((rx_ok_buff[0]&0x80)!=0) && ((cur_protocol[0]&0x80)==0) ) // Bind flag has been set - CHANGE_PROTOCOL_FLAG_on; //restart protocol with bind - cur_protocol[0] = rx_ok_buff[0]; //store current protocol + if( ((rx_ok_buff[0]&0x80)!=0) && ((cur_protocol[0]&0x80)==0) ) // Bind flag has been set + CHANGE_PROTOCOL_FLAG_on; //restart protocol with bind + cur_protocol[0] = rx_ok_buff[0]; //store current protocol // decode channel values -#if defined(NUM_SERIAL_CH_8) //8 channels serial protocol - Servo_data[0]=rx_ok_buff[3]+((rx_ok_buff[11]&0xC0)<<2); - Servo_data[1]=rx_ok_buff[4]+((rx_ok_buff[11]&0x30)<<4); - Servo_data[2]=rx_ok_buff[5]+((rx_ok_buff[11]&0x0C)<<6); - Servo_data[3]=rx_ok_buff[6]+((rx_ok_buff[11]&0x03)<<8); - Servo_data[4]=rx_ok_buff[7]+((rx_ok_buff[12]&0xC0)<<2); - Servo_data[5]=rx_ok_buff[8]+((rx_ok_buff[12]&0x30)<<4); - Servo_data[6]=rx_ok_buff[9]+((rx_ok_buff[12]&0x0C)<<6); - Servo_data[7]=rx_ok_buff[10]+((rx_ok_buff[12]&0x03)<<8); - for(uint8_t i=0;i<8;i++) - Servo_data[i]=((Servo_data[i]*5)>>2)+860; //range 860-2140; -#else //16 channels serial protocol - volatile uint8_t *p=rx_ok_buff+2; - uint8_t dec=-3; + volatile uint8_t *p=rx_ok_buff+2; + uint8_t dec=-3; for(uint8_t i=0;i=8) { - dec-=8; - p++; - } - p++; - Servo_data[i]=((((*((uint32_t *)p))>>dec)&0x7FF)*5)/8+860; //value range 860<->2140 -125%<->+125% - } -#endif - RX_FLAG_off; //data has been processed + dec-=8; + p++; + } + p++; + Servo_data[i]=((((*((uint32_t *)p))>>dec)&0x7FF)*5)/8+860; //value range 860<->2140 -125%<->+125% + } + RX_FLAG_off; //data has been processed } static void module_reset() { - remote_callback = 0; - switch(prev_protocol) - { - case MODE_FLYSKY: - case MODE_HUBSAN: - A7105_Reset(); - break; - case MODE_FRSKY: - case MODE_FRSKYX: - CC2500_Reset(); - break; - break; - case MODE_DSM2: - case MODE_DEVO: - CYRF_Reset(); - break; - default: - // MODE_HISKY, MODE_V2X2, MODE_YD717, MODE_KN, MODE_SYMAX, MODE_SLT, MODE_CX10, MODE_CG023, MODE_BAYANG, MODE_ESKY - NRF24L01_Reset(); - break; + if(remote_callback) + { // previous protocol loaded + remote_callback = 0; + switch(prev_protocol) + { + case MODE_FLYSKY: + case MODE_HUBSAN: + A7105_Reset(); + break; + case MODE_FRSKY: + case MODE_FRSKYX: + CC2500_Reset(); + break; + case MODE_DSM2: + case MODE_DEVO: + CYRF_Reset(); + break; + default: // MODE_HISKY, MODE_V2X2, MODE_YD717, MODE_KN, MODE_SYMAX, MODE_SLT, MODE_CX10, MODE_CG023, MODE_BAYANG, MODE_ESKY + NRF24L01_Reset(); + break; + } } } @@ -612,21 +610,11 @@ uint16_t limit_channel_100(uint8_t ch) if(Servo_data[ch]>PPM_MAX_100) return PPM_MAX_100; else - if (Servo_data[ch]> 24) & 0xFF; - rx_tx_addr[1] = (id >> 16) & 0xFF; - rx_tx_addr[2] = (id >> 8) & 0xFF; - rx_tx_addr[3] = (id >> 0) & 0xFF; - rx_tx_addr[4] = 0xC1; // for YD717: always uses first data port -} - #if defined(TELEMETRY) void Serial_write(uint8_t data) { @@ -641,21 +629,12 @@ void Serial_write(uint8_t data) static void Mprotocol_serial_init() { -#if defined(NUM_SERIAL_CH_8) //8 channels serial protocol - #define BAUD 125000 - #include - UBRR0H = UBRRH_VALUE; - UBRR0L = UBRRL_VALUE; - //Set frame format to 8 data bits, no parity, 1 stop bit - UCSR0C |= (1< + #include UBRR0H = UBRRH_VALUE; UBRR0L = UBRRL_VALUE; //Set frame format to 8 data bits, even parity, 2 stop bits UCSR0C |= (1<> 24) & 0xFF; + rx_tx_addr[1] = (id >> 16) & 0xFF; + rx_tx_addr[2] = (id >> 8) & 0xFF; + rx_tx_addr[3] = (id >> 0) & 0xFF; + rx_tx_addr[4] = 0xC1; // for YD717: always uses first data port +} + static uint32_t random_id(uint16_t adress, uint8_t create_new) { uint32_t id; @@ -694,6 +693,7 @@ static uint32_t random_id(uint16_t adress, uint8_t create_new) /**************************/ /**************************/ +//PPM ISR(INT1_vect) { // Interrupt on PPM pin static int8_t chan=-1; @@ -722,53 +722,8 @@ ISR(INT1_vect) Prev_TCNT1+=Cur_TCNT1; } -#if defined(TELEMETRY) -ISR(USART_UDRE_vect) -{ // Transmit interrupt - uint8_t t = tx_tail; - if(tx_head!=t) - { - if(++t>=TXBUFFER_SIZE)//head - t=0; - UDR0=tx_buff[t]; - tx_tail=t; - } - if (t == tx_head) - UCSR0B &= ~(1<>8) ^ rx_buff[idx++]) & 0xFF]); - } - else - { // A frame has been received and needs to be checked before giving it to main - TIMSK1 &=~(1<=TXBUFFER_SIZE)//head + t=0; + UDR0=tx_buff[t]; + tx_tail=t; + } + if (t == tx_head) + UCSR0B &= ~(1<> 2) + 0x20) -static void SYMAX_build_packet_x5c(uint8_t bind) +static void __attribute__((unused)) SYMAX_build_packet_x5c(uint8_t bind) { if (bind) { @@ -116,7 +116,7 @@ static void SYMAX_build_packet_x5c(uint8_t bind) } } -static void SYMAX_build_packet(uint8_t bind) +static void __attribute__((unused)) SYMAX_build_packet(uint8_t bind) { if (bind) { @@ -146,7 +146,7 @@ static void SYMAX_build_packet(uint8_t bind) packet[9] = SYMAX_checksum(packet); } -static void SYMAX_send_packet(uint8_t bind) +static void __attribute__((unused)) SYMAX_send_packet(uint8_t bind) { if (sub_protocol==SYMAX5C) SYMAX_build_packet_x5c(bind); @@ -167,7 +167,7 @@ static void SYMAX_send_packet(uint8_t bind) NRF24L01_SetPower(); // Set tx_power } -static void symax_init() +static void __attribute__((unused)) symax_init() { NRF24L01_Initialize(); // @@ -219,7 +219,7 @@ static void symax_init() NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x0e); // power on } -static void symax_init1() +static void __attribute__((unused)) symax_init1() { // duplicate stock tx sending strange packet (effect unknown) uint8_t first_packet[] = {0xf9, 0x96, 0x82, 0x1b, 0x20, 0x08, 0x08, 0xf2, 0x7d, 0xef, 0xff, 0x00, 0x00, 0x00, 0x00}; @@ -247,7 +247,7 @@ static void symax_init1() } // channels determined by last byte of tx address -static void symax_set_channels(uint8_t address) +static void __attribute__((unused)) symax_set_channels(uint8_t address) { static const uint8_t start_chans_1[] = {0x0a, 0x1a, 0x2a, 0x3a}; static const uint8_t start_chans_2[] = {0x2a, 0x0a, 0x42, 0x22}; @@ -290,7 +290,7 @@ static void symax_set_channels(uint8_t address) *pchans = 0x39194121; } -static void symax_init2() +static void __attribute__((unused)) symax_init2() { uint8_t chans_data_x5c[] = {0x1d, 0x2f, 0x26, 0x3d, 0x15, 0x2b, 0x25, 0x24, 0x27, 0x2c, 0x1c, 0x3e, 0x39, 0x2d, 0x22}; diff --git a/Multiprotocol/V2X2_nrf24l01.ino b/Multiprotocol/V2X2_nrf24l01.ino index 35796b1..d761c57 100644 --- a/Multiprotocol/V2X2_nrf24l01.ino +++ b/Multiprotocol/V2X2_nrf24l01.ino @@ -75,7 +75,7 @@ static const uint8_t freq_hopping[][16] = { 0x18, 0x2A, 0x21, 0x38, 0x10, 0x26, 0x20, 0x1F } // 03 }; -static void v202_init() +static void __attribute__((unused)) v202_init() { NRF24L01_Initialize(); @@ -108,7 +108,7 @@ static void v202_init() NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t *)"\x66\x88\x68\x68\x68", 5); } -static void V202_init2() +static void __attribute__((unused)) V202_init2() { NRF24L01_FlushTx(); packet_sent = 0; @@ -119,7 +119,7 @@ static void V202_init2() //Done by TX_EN??? => NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP)); } -static void V2X2_set_tx_id(void) +static void __attribute__((unused)) V2X2_set_tx_id(void) { uint8_t sum; sum = rx_tx_addr[1] + rx_tx_addr[2] + rx_tx_addr[3]; @@ -134,7 +134,7 @@ static void V2X2_set_tx_id(void) } } -static void V2X2_add_pkt_checksum() +static void __attribute__((unused)) V2X2_add_pkt_checksum() { uint8_t sum = 0; for (uint8_t i = 0; i < 15; ++i) @@ -142,7 +142,7 @@ static void V2X2_add_pkt_checksum() packet[15] = sum; } -static void V2X2_send_packet(uint8_t bind) +static void __attribute__((unused)) V2X2_send_packet(uint8_t bind) { uint8_t flags2=0; if (bind) diff --git a/Multiprotocol/YD717_nrf24l01.ino b/Multiprotocol/YD717_nrf24l01.ino index d2a3f1a..1d9ffbe 100644 --- a/Multiprotocol/YD717_nrf24l01.ino +++ b/Multiprotocol/YD717_nrf24l01.ino @@ -41,7 +41,7 @@ enum { YD717_DATA }; -static void yd717_send_packet(uint8_t bind) +static void __attribute__((unused)) yd717_send_packet(uint8_t bind) { uint8_t rudder_trim, elevator_trim, aileron_trim; if (bind) @@ -125,7 +125,7 @@ static void yd717_send_packet(uint8_t bind) NRF24L01_SetPower(); // Set tx_power } -static void yd717_init() +static void __attribute__((unused)) yd717_init() { NRF24L01_Initialize(); @@ -162,7 +162,7 @@ static void yd717_init() NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5); } -static void YD717_init1() +static void __attribute__((unused)) YD717_init1() { // for bind packets set address to prearranged value known to receiver uint8_t bind_rx_tx_addr[] = {0x65, 0x65, 0x65, 0x65, 0x65}; @@ -179,7 +179,7 @@ static void YD717_init1() NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, bind_rx_tx_addr, 5); } -static void YD717_init2() +static void __attribute__((unused)) YD717_init2() { // set rx/tx address for data phase NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, 5); diff --git a/Multiprotocol/_Config.h b/Multiprotocol/_Config.h new file mode 100644 index 0000000..4c58806 --- /dev/null +++ b/Multiprotocol/_Config.h @@ -0,0 +1,234 @@ +/* + This project is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Multiprotocol is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with Multiprotocol. If not, see . + */ + +/** Multiprotocol module configuration file ***/ + +//Uncomment your TX type +#define TARANIS //TARANIS TAER (1100<->1900µs) +//#define TX_ER9X //ER9X AETR (988<->2012µs) +//#define TX_DEVO7 //DEVO7 EATR (1120<->1920µs) +//#define TX_SPEKTRUM //Spektrum TAER (1100<->1900µs) +//#define TX_HISKY //HISKY AETR (1100<->1900µs) + +//Uncomment to enable telemetry +#define TELEMETRY +#define HUB_TELEMETRY + + +//Uncomment to enable potar select +#define POTAR_SELECT +#define POTAR_SELECT_V ELEVATOR +#define POTAR_SELECT_H RUDDER +#define POTAR_SELECT_M AILERON + + +//Comment a protocol to exclude it from compilation +#define BAYANG_NRF24L01_INO +#define CG023_NRF24L01_INO +#define CX10_NRF24L01_INO +#define DEVO_CYRF6936_INO +#define DSM2_CYRF6936_INO +#define ESKY_NRF24L01_INO +#define FLYSKY_A7105_INO +#define FRSKY_CC2500_INO // FRSKY2way +//#define FRSKYX_CC2500_INO +#define HISKY_NRF24L01_INO +#define HUBSAN_A7105_INO +#define KN_NRF24L01_INO +#define SLT_NRF24L01_INO +#define SYMAX_NRF24L01_INO +#define V2X2_NRF24L01_INO +#define YD717_NRF24L01_INO + +#define H7_NRF24L01_INO +//#define HM830_NRF24L01_INO +//#define CFlie_NRF24L01_INO + +//Update this table to set which protocol and all associated settings are called for the corresponding dial number +static const PPM_Parameters PPM_prot[15]= +{ +// Protocol , Sub protocol , RX_Num , Power , Auto Bind , Option + {MODE_DSM2 , DSM2 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=1 + {MODE_FLYSKY, Flysky , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=2 + {MODE_HUBSAN, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=3 + {MODE_DEVO , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=4 + {MODE_CG023 , CG023 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=5 + {MODE_CX10 , CX10_BLUE , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=6 + {MODE_HISKY , Hisky , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=7 + {MODE_V2X2 , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=8 + {MODE_YD717 , YD717 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=9 + {MODE_KN , WLTOYS , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=10 + {MODE_SYMAX , SYMAX , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=11 + {MODE_SLT , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=12 + {MODE_BAYANG, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=13 + {MODE_SYMAX , SYMAX5C , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=14 + {MODE_FRSKY , 0 , 0 , P_HIGH , NO_AUTOBIND , 0xD7 }, //Dial=15 +}; +/* Available protocols and associated sub protocols: + MODE_FLYSKY + Flysky + V9X9 + V6X6 + V912 + MODE_HUBSAN + NONE + MODE_FRSKY + NONE + MODE_HISKY + Hisky + HK310 + MODE_V2X2 + NONE + MODE_DSM2 + DSM2 + DSMX + MODE_DEVO + NONE + MODE_YD717 + YD717 + SKYWLKR + SYMAX4 + XINXUN + NIHUI + MODE_KN + WLTOYS + FEILUN + MODE_SYMAX + SYMAX + SYMAX5C + MODE_SLT + NONE + MODE_CX10 + CX10_GREEN + CX10_BLUE + DM007 + Q282 + JC3015_1 + JC3015_2 + MK33041 + Q242 + MODE_CG023 + CG023 + YD829 + H8_3D + MODE_BAYANG + NONE + MODE_FRSKYX + NONE + MODE_ESKY + NONE + +RX_Num value between 0 and 15 + +Power P_HIGH or P_LOW + +Auto Bind AUTOBIND or NO_AUTOBIND + +Option value between 0 and 255. 0xD7 or 0x00 for Frsky fine tuning. +*/ + +//****************** +//TX definitions with timing endpoints and channels order + +// Turnigy PPM and channels +#if defined(TX_ER9X) + #define PPM_MAX 2140 + #define PPM_MIN 860 + #define PPM_MAX_100 2012 + #define PPM_MIN_100 988 + #define AETR +#endif + +// Devo PPM and channels +#if defined(TX_DEVO7) + #define PPM_MAX 2100 + #define PPM_MIN 900 + #define PPM_MAX_100 1920 + #define PPM_MIN_100 1120 + #define EATR +#endif + +// SPEKTRUM PPM and channels +#if defined(TX_SPEKTRUM) | defined(TARANIS) + #define PPM_MAX 2000 + #define PPM_MIN 1000 + #define PPM_MAX_100 1900 + #define PPM_MIN_100 1100 + #define TAER +#endif + +// HISKY +#if defined(TX_HISKY) + #define PPM_MAX 2000 + #define PPM_MIN 1000 + #define PPM_MAX_100 1900 + #define PPM_MIN_100 1100 + #define AETR +#endif + +#if defined(EATR) + enum chan_order{ + ELEVATOR=0, + AILERON, + THROTTLE, + RUDDER, + AUX1, + AUX2, + AUX3, + AUX4, + AUX5, + AUX6, + AUX7, + AUX8 + }; +#endif + +#if defined(TAER) + enum chan_order{ + THROTTLE=0, + AILERON, + ELEVATOR, + RUDDER, + AUX1, + AUX2, + AUX3, + AUX4, + AUX5, + AUX6, + AUX7, + AUX8 +}; +#endif + +#if defined(AETR) +enum chan_order{ + AILERON =0, + ELEVATOR, + THROTTLE, + RUDDER, + AUX1, + AUX2, + AUX3, + AUX4, + AUX5, + AUX6, + AUX7, + AUX8 +}; +#endif + +#define PPM_MIN_COMMAND 1250 +#define PPM_SWITCH 1550 +#define PPM_MAX_COMMAND 1750 diff --git a/Multiprotocol/iface_cc2500.h b/Multiprotocol/iface_cc2500.h index 8bcd506..cb7b623 100644 --- a/Multiprotocol/iface_cc2500.h +++ b/Multiprotocol/iface_cc2500.h @@ -16,6 +16,16 @@ #ifndef _IFACE_CC2500_H_ #define _IFACE_CC2500_H_ +enum { + FRSKY_BIND = 0, + FRSKY_BIND_DONE = 1000, + FRSKY_DATA1, + FRSKY_DATA2, + FRSKY_DATA3, + FRSKY_DATA4, + FRSKY_DATA5 +}; + enum { CC2500_00_IOCFG2 = 0x00, // GDO2 output pin configuration CC2500_01_IOCFG1 = 0x01, // GDO1 output pin configuration diff --git a/Multiprotocol/liste.txt b/Multiprotocol/liste.txt new file mode 100644 index 0000000..3b9583e --- /dev/null +++ b/Multiprotocol/liste.txt @@ -0,0 +1,65 @@ + MODE_SERIAL = 0, // Serial / Manche commands + MODE_FLYSKY = 1, // =>A7105 { Flysky=0, V9X9=1, V6X6=2, V912=3 }; + MODE_HUBSAN = 2, // =>A7105 + MODE_CG023 = 3, // =>NRF24L01 { CG023 = 0, YD829 = 1, H8_3D = 2 }; + MODE_CX10 = 4, // =>NRF24L01 { CX10_GREEN = 0, DM007=2, CX10_BLUE=1, // also compatible with CX10-A, CX12 }; + MODE_HISKY = 6, // =>NRF24L01 { Hisky=0, HK310=1 }; + MODE_DSM2 = 6, // =>CYRF6936 { DSM2=0, DSMX=1}; + MODE_DEVO =7, // =>CYRF6936 + MODE_YD717 = 8, // =>NRF24L01 { YD717=0, SKYWLKR=1, SYMAX2=2, XINXUN=3, NIHUI=4 }; + MODE_KN = 9, // =>NRF24L01 + MODE_SYMAX = 10, // =>NRF24L01 { SYMAX=0, SYMAX5C=1, }; + MODE_SLT = 11, // =>NRF24L01 + MODE_V2X2 = 12, // =>NRF24L01 + MODE_BAYANG = 13, // =>NRF24L01 + MODE_FRSKY = 14, // =>CC2500 + = 15, // => + + BAYANG +AUX1 FLIP +AUX2 HEADLESS +AUX3 RTH +AUX4 SNAPSHOT +AUX5 VIDEO + + CG023 +AUX1 FLIP +AUX2 LED +AUX3 STILL +AUX4 VIDEO +AUX5 EASY + + CX10 +AUX1 FLIP +AUX2 mode 1-2-3 (headless on CX-10A) +AUX3 SNAPSHOT +AUX4 VIDEO +AUX5 HEADLESS + + HUBSAN +AUX1 FLIP +AUX2 LED +AUX3 VIDEO + + KN +AUX1 Dual rate +AUX2 Throttle Hold +AUX3 Idle up +AUX4 Gyro + + V2X2 +AUX1 FLIP +AUX2 LED +AUX3 CAMERA +AUX4 VIDEO +AUX5 HEADLESS +AUX6 MAG_CAL_X +AUX7 MAG_CAL_Y + + YD717 +AUX1 FLIP +AUX2 LED +AUX3 PICTURE +AUX4 VIDEO +AUX5 HEADLESS + diff --git a/Multiprotocol/multi.lua b/Multiprotocol/multi.lua new file mode 100644 index 0000000..4b18f5e --- /dev/null +++ b/Multiprotocol/multi.lua @@ -0,0 +1,91 @@ +-- Multiprotocole Midelic et Pascallanger +local debut = 0 +local tps = 0 +local tpsact = 1024 +local mix, mixe +local channel + +local inp = { + { "Protocole", VALUE, 1, 26, 2 }, + { "Switch", SOURCE } +} +-- 6 7 8 15 16 17 24 25 26 +-- 4 5 12 13 14 21 22 23 +-- 1 2 3 9 10 11 18 19 20 +local out = { "Bind", "Gaz", "Aile", "Prof", "Dir" } + +local function run_func(proto, sw) + -- test mixage lua + if debut == 0 then + -- passage en lua + for channel = 0, 3, 1 do + local mix = model.getMix(channel, 0) + mix_source = mix["source"] + if mix_source < 33 or 1 then + model.deleteMix(channel, 0) + mix["source"] = channel + 34 + mix["name"] = "Lua " + model.insertMix(channel, 0, mix) + end + end + end + -- inter install + channel = 4 + mix = { name="Raz Bind", source=33, weight=100, switch=0, multiplex=REPLACE } + count = model.getMixesCount(channel + 0) + if count == 0 and inter == 1 then + model.insertMix(channel + 0, 0, mix) + elseif count == 1 and inter == 0 then + mixe = model.getMix(channel, 0) + if mixe["name"] == mix["name"] then + model.deleteMix(channel, 0) + end + end + + -- delais init + if proto ~= debut then + tps = getTime() + 500 -- delai pour mini 12 cycle PPM + tpsact = 1024 + debut = proto + end + + local gaz = 1024 + local ail = 0 + local dir = 0 + local pro = 0 + + if tpsact == 0 and sw < 200 then + -- reprise valeur input + pro = getValue(1) + ail = getValue(2) + gaz = getValue(3) + dir = getValue(4) + elseif tpsact ~= 0 then + -- decallage pour position memo (centre) + if proto > 4 then proto = proto + 1 end + + -- calcul position + -- decallage pour > 18 + if proto > 18 then + ail = 1024 + proto = proto - 18 + end + -- decallage pour > 9 + if proto > 9 then + ail = -1024 + proto = proto - 9 + end + + if proto < 4 then pro = -1024 end + if proto > 6 then pro = 1024 end + + if proto % 3 == 1 then dir = -1024 end + if proto % 3 == 0 then dir = 1024 end + + if tps < getTime() then tpsact = 0 end + sw = tpsact + end + + return sw, gaz, ail, pro, dir +end +return { run=run_func, input=inp, output=out} diff --git a/Multiprotocol/multiprotocol.h b/Multiprotocol/multiprotocol.h index 3fab255..ab72a2f 100644 --- a/Multiprotocol/multiprotocol.h +++ b/Multiprotocol/multiprotocol.h @@ -21,20 +21,24 @@ enum PROTOCOLS MODE_SERIAL = 0, // Serial commands MODE_FLYSKY = 1, // =>A7105 / FLYSKY protocol MODE_HUBSAN = 2, // =>A7105 / HUBSAN protocol - MODE_FRSKY = 3, // =>CC2500 / FRSKY protocol + MODE_FRSKY = 3, // =>CC2500 / FRSKY protocol MODE_HISKY = 4, // =>NRF24L01 / HISKY protocol MODE_V2X2 = 5, // =>NRF24L01 / V2x2 protocol MODE_DSM2 = 6, // =>CYRF6936 / DSM2 protocol MODE_DEVO =7, // =>CYRF6936 / DEVO protocol MODE_YD717 = 8, // =>NRF24L01 / YD717 protocol (CX10 red pcb) MODE_KN = 9, // =>NRF24L01 / KN protocol - MODE_SYMAX = 10, // =>NRF24L01 / SYMAX protocol (SYMAX4 working) + MODE_SYMAX = 10, // =>NRF24L01 / SYMAX protocol MODE_SLT = 11, // =>NRF24L01 / SLT protocol MODE_CX10 = 12, // =>NRF24L01 / CX-10 protocol MODE_CG023 = 13, // =>NRF24L01 / CG023 protocol MODE_BAYANG = 14, // =>NRF24L01 / BAYANG protocol - MODE_FRSKYX = 15, // =>CC2500 / FRSKYX protocol + MODE_FRSKYX = 15, // =>CC2500 / FRSKYX protocol MODE_ESKY = 16, // =>NRF24L01 / ESKY protocol +// Ajout + MODE_H7 = 21, // =>NRF24L01 / EAchine MT99xx (H7, MT9916 ...) +// MODE_HM830 =22, // =>NRF24L01 / HM830 + MODE_CFLIE =23, // =>NRF24L01 / CFlie }; enum Flysky { @@ -78,7 +82,8 @@ enum CX10 Q282=3, JC3015_1=4, JC3015_2=5, - MK33041=6 + MK33041=6, + Q242=7 }; enum CG023 { @@ -87,101 +92,22 @@ enum CG023 H8_3D = 2 }; -//****************** -//TX definitions with timing endpoints and channels order -//****************** -// Turnigy PPM and channels -#if defined(TX_ER9X) -#define PPM_MAX 2140 -#define PPM_MIN 860 -#define PPM_MAX_100 2012 -#define PPM_MIN_100 988 -enum chan_order{ - AILERON =0, - ELEVATOR, - THROTTLE, - RUDDER, - AUX1, - AUX2, - AUX3, - AUX4, - AUX5, - AUX6, - AUX7, - AUX8 +#define NONE 0 +#define P_HIGH 1 +#define P_LOW 0 +#define AUTOBIND 1 +#define NO_AUTOBIND 0 + +struct PPM_Parameters +{ + uint8_t protocol : 5; + uint8_t sub_proto : 3; + uint8_t rx_num : 4; + uint8_t power : 1; + uint8_t autobind : 1; + uint8_t option; }; -#endif - -// Devo PPM and channels -#if defined(TX_DEVO7) -#define PPM_MAX 2100 -#define PPM_MIN 900 -#define PPM_MAX_100 1920 -#define PPM_MIN_100 1120 -enum chan_order{ - ELEVATOR=0, - AILERON, - THROTTLE, - RUDDER, - AUX1, - AUX2, - AUX3, - AUX4, - AUX5, - AUX6, - AUX7, - AUX8 -}; -#endif - -// SPEKTRUM PPM and channels -#if defined(TX_SPEKTRUM) -#define PPM_MAX 2000 -#define PPM_MIN 1000 -#define PPM_MAX_100 1900 -#define PPM_MIN_100 1100 -enum chan_order{ - THROTTLE=0, - AILERON, - ELEVATOR, - RUDDER, - AUX1, - AUX2, - AUX3, - AUX4, - AUX5, - AUX6, - AUX7, - AUX8 -}; -#endif - -// HISKY -#if defined(TX_HISKY) -#define PPM_MAX 2000 -#define PPM_MIN 1000 -#define PPM_MAX_100 1900 -#define PPM_MIN_100 1100 -enum chan_order{ - AILERON =0, - ELEVATOR, - THROTTLE, - RUDDER, - AUX1, - AUX2, - AUX3, - AUX4, - AUX5, - AUX6, - AUX7, - AUX8 -}; -#endif - -#define PPM_MIN_COMMAND 1250 -#define PPM_SWITCH 1550 -#define PPM_MAX_COMMAND 1750 //******************* //*** Pinouts *** @@ -508,6 +434,7 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p -- JC3015_1 4 JC3015_2 5 MK33041 6 + Q242 7 sub_protocol==CG023 CG023 0 YD829 1 @@ -523,86 +450,5 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p -- 1843 +100% 2047 +125% Channels bits are concatenated to fit in 22 bytes like in SBUS protocol - - -************************** -8 channels serial protocol -************************** -Serial: 125000 Baud 8n1 _ xxxx xxxx - --- - Channels: - Nbr=8 - 10bits=0..1023 - 0 -125% - 96 -100% - 512 0% - 928 +100% - 1023 +125% - Stream[0] = sub_protocol|BindBit|RangeCheckBit|AutoBindBit; - sub_protocol is 0..31 (bits 0..4) - => Reserved 0 - Flysky 1 - Hubsan 2 - Frsky 3 - Hisky 4 - V2x2 5 - DSM2 6 - Devo 7 - YD717 8 - KN 9 - SymaX 10 - SLT 11 - CX10 12 - CG023 13 - Bayang 14 - FrskyX 15 - ESky 16 - BindBit=> 0x80 1=Bind/0=No - AutoBindBit=> 0x40 1=Yes /0=No - RangeCheck=> 0x20 1=Yes /0=No - Stream[1] = RxNum | Power | Type; - RxNum value is 0..15 (bits 0..3) - Type is 0..7 <<4 (bit 4..6) - sub_protocol==Flysky - Flysky 0 - V9x9 1 - V6x6 2 - V912 3 - sub_protocol==Hisky - Hisky 0 - HK310 1 - sub_protocol==DSM2 - DSM2 0 - DSMX 1 - sub_protocol==YD717 - YD717 0 - SKYWLKR 1 - SYMAX4 2 - XINXUN 3 - NIHUI 4 - sub_protocol==KN - WLTOYS 0 - FEILUN 1 - sub_protocol==SYMAX - SYMAX 0 - SYMAX5C 1 - sub_protocol==CX10 - CX10_GREEN 0 - CX10_BLUE 1 // also compatible with CX10-A, CX12 - DM007 2 - Q282 3 - JC3015_1 4 - JC3015_2 5 - MK33041 6 - sub_protocol==CG023 - CG023 0 - YD829 1 - H8_3D 2 - Power value => 0x80 0=High/1=Low - Stream[2] = option_protocol; - option_protocol value is -127..127 - Stream[i+3] = lowByte(channel[i]) // with i[0..7] - Stream[11] = highByte(channel[0])<<6 | highByte(channel[1])<<4 | highByte(channel[2])<<2 | highByte(channel[3]) - Stream[12] = highByte(channel[4])<<6 | highByte(channel[5])<<4 | highByte(channel[6])<<2 | highByte(channel[7]) - Stream[13] = lowByte(CRC16(Stream[0..12]) */ diff --git a/Multiprotocol/nrf24l01_H7.ino b/Multiprotocol/nrf24l01_H7.ino new file mode 100644 index 0000000..e2c9e75 --- /dev/null +++ b/Multiprotocol/nrf24l01_H7.ino @@ -0,0 +1,151 @@ +/* + This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or (at your option) any later version. + + This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. + + You should have received a copy of the GNU General Public License. If not, see . + */ + +// EAchine MT99xx (H7, MT9916 ...) TX protocol + +// Auxiliary channels: +// CH5: rate (3 pos) +// CH6: flip flag +// CH7: still camera +// CH8: video camera +// CH10: elevator trim +// CH11: aileron trim + +#if defined(H7_NRF24L01_INO) + +#include "iface_nrf24l01.h" + +static const uint8_t H7_freq[] = { + 0x02, 0x48, 0x0C, 0x3e, 0x16, 0x34, 0x20, 0x2A, + 0x2A, 0x20, 0x34, 0x16, 0x3e, 0x0c, 0x48, 0x02 +}; + +static const uint8_t H7_mys_byte[] = { + 0x01, 0x11, 0x02, 0x12, 0x03, 0x13, 0x04, 0x14, + 0x05, 0x15, 0x06, 0x16, 0x07, 0x17, 0x00, 0x10 +}; + +// flags going to packet[6] +// H7_FLAG_RATE0, // default rate, no flag +#define H7_FLAG_RATE1 0x01 +#define H7_FLAG_RATE2 0x02 +#define H7_FLAG_VIDEO 0x10 +#define H7_FLAG_SNAPSHOT 0x20 +#define H7_FLAG_FLIP 0x80 + +uint8_t H7_tx_addr[5]; + +uint8_t checksum_offset; +uint8_t channel_offset; + +#define H7_PACKET_PERIOD 2625 +#define H7_PAYPLOAD_SIZE 9 + +void H7_initTXID() { + checksum_offset = (rx_tx_addr[0] + rx_tx_addr[1]) & 0xff; + channel_offset = (((checksum_offset & 0xf0)>>4) + (checksum_offset & 0x0f)) % 8; +} + +uint16_t H7_init() { + H7_initTXID(); + NRF24L01_Reset(); + NRF24L01_Initialize(); + delay(10); + NRF24L01_FlushTx(); + for(u8 i=0; i<5; i++) { H7_tx_addr[i] = 0xCC; } + XN297_SetTXAddr(H7_tx_addr, 5); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // clear data ready, data sent, and retransmit + NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // no AA + NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // enable data pipe 0 only + NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5 bytes address + NRF24L01_WriteReg(NRF24L01_05_RF_CH, 0x2D); // set RF channel + NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x00);// no auto retransmit + NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, 0x09); // rx payload size (unused ?) + NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps + NRF24L01_SetPower(); + NRF24L01_Activate(0x73); + NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x00); + NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x00); + NRF24L01_ReadReg(NRF24L01_1D_FEATURE); // read reg 1D back ? + delay(150); + XN297_Configure(_BV(NRF24L01_00_EN_CRC) | _BV(NRF24L01_00_CRCO) | _BV(NRF24L01_00_PWR_UP)); + delay(100); + H7_bind(); + return H7_PACKET_PERIOD; +} + +void H7_bind() { + BIND_IN_PROGRESS; + uint8_t counter = 58; + packet[0] = 0x20; // fixed (firmware date 2014-03-25 ?) + packet[1] = 0x14; // fixed + packet[2] = 0x03; // fixed + packet[3] = 0x25; // fixed + packet[4] = rx_tx_addr[0]; // 1st byte for data phase tx address + packet[5] = rx_tx_addr[1]; // 2nd byte for data phase tx address + packet[6] = 0x00; // 3rd byte for data phase tx address (always 0x00 ?) + packet[7] = checksum_offset; // checksum offset + packet[8] = 0xAA; // fixed + while(counter--) { + for (uint8_t ch = 0; ch < 16; ch++) { + delayMicroseconds(5); + NRF24L01_WriteReg(NRF24L01_07_STATUS,0x70); + NRF24L01_FlushTx(); + NRF24L01_WriteReg(NRF24L01_05_RF_CH,H7_freq[ch]); + XN297_WritePayload(packet, H7_PAYPLOAD_SIZE); //(bind packet) + delayMicroseconds(H7_PACKET_PERIOD); + } + } + delay(15); + H7_tx_addr[0] = rx_tx_addr[0]; + H7_tx_addr[1] = rx_tx_addr[1]; + H7_tx_addr[2] = 0; + XN297_SetTXAddr(H7_tx_addr, 5); + BIND_DONE; +} + +uint8_t H7_calcChecksum() { + uint8_t result=checksum_offset; + for(uint8_t i=0; i<8; i++) { result += packet[i]; } + return result & 0xFF; +} + +void H7_WritePacket() { + static uint8_t channel=0; + packet[0] = map(Servo_data[THROTTLE], PPM_MIN, PPM_MAX, 0xE1, 0x00); + packet[1] = map(Servo_data[RUDDER], PPM_MIN, PPM_MAX, 0xE1, 0x00); + packet[2] = map(Servo_data[AILERON], PPM_MIN, PPM_MAX, 0x00, 0xE1); + packet[3] = map(Servo_data[ELEVATOR], PPM_MIN, PPM_MAX, 0x00, 0xE1); + packet[4] = map(Servo_data[AUX7], PPM_MIN, PPM_MAX, 0x3f, 0x00); // elevator trim 0x3f - 0x00 + packet[5] = map(Servo_data[AUX8], PPM_MIN, PPM_MAX, 0x3f, 0x00); // aileron trim 0x3f - 0x00 + packet[6] = 0x40; // flags (default is 0x00 on H7, 0x40 on MT9916 stock TX) + if(Servo_data[AUX2] > PPM_MAX_COMMAND) { packet[6] |= H7_FLAG_FLIP; } + + if(Servo_data[AUX1] > PPM_MAX_COMMAND) { packet[6] |= H7_FLAG_RATE2; } + else if(Servo_data[AUX1] > PPM_MIN_COMMAND) { packet[6] |= H7_FLAG_RATE1; } + + if(Servo_data[AUX5] > PPM_MAX_COMMAND) { packet[6] |= H7_FLAG_SNAPSHOT; } + if(Servo_data[AUX6] > PPM_MAX_COMMAND) { packet[6] |= H7_FLAG_VIDEO; } + packet[7] = H7_mys_byte[channel]; // looks like this byte has no importance actually + packet[8] = H7_calcChecksum(); + NRF24L01_WriteReg(NRF24L01_05_RF_CH, H7_freq[channel]+channel_offset); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); + NRF24L01_FlushTx(); + XN297_WritePayload(packet, H7_PAYPLOAD_SIZE); + channel++; + if(channel > 15) { channel = 0; } +} + +uint16_t process_H7() { + H7_WritePacket(); + return H7_PACKET_PERIOD; +} + +#endif diff --git a/Multiprotocol/nrf24l01_hm830.ino b/Multiprotocol/nrf24l01_hm830.ino new file mode 100644 index 0000000..0243695 --- /dev/null +++ b/Multiprotocol/nrf24l01_hm830.ino @@ -0,0 +1,321 @@ +/* + This project is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. + Deviation is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. + You should have received a copy of the GNU General Public License along with Deviation. If not, see . + */ + +/* This protocol is for the HM Hobby HM830 RC Paper Airplane + Protocol spec: + Channel data: + AA BB CC DD EE FF GG + AA : Throttle Min=0x00 max =0x64 + BB : + bit 0,1,2: Left/Right magnitude, bit 5 Polarity (set = right) + bit 6: Accelerate + bit 7: Right button (also the ABC Button) + CC : bit 0 seems to be impacted by the Right button + DD + EE + FF : Trim (bit 0-5: Magnitude, bit 6 polarity (set = right) + GG : Checksum (CRC8 on bytes AA-FF), init = 0xa5, poly = 0x01 +*/ + +#ifdef HM830_NRF24L01_INO + +#include "iface_nrf24l01.h" + +enum { + HM830_BIND1A = 0, + HM830_BIND2A, + HM830_BIND3A, + HM830_BIND4A, + HM830_BIND5A, + HM830_BIND6A, + HM830_BIND7A, + HM830_DATA1, + HM830_DATA2, + HM830_DATA3, + HM830_DATA4, + HM830_DATA5, + HM830_DATA6, + HM830_DATA7, + HM830_BIND1B = 0x80, + HM830_BIND2B, + HM830_BIND3B, + HM830_BIND4B, + HM830_BIND5B, + HM830_BIND6B, + HM830_BIND7B, +}; + +static const uint8_t init_vals[][2] = { + {NRF24L01_17_FIFO_STATUS, 0x00}, + {NRF24L01_16_RX_PW_P5, 0x07}, + {NRF24L01_15_RX_PW_P4, 0x07}, + {NRF24L01_14_RX_PW_P3, 0x07}, + {NRF24L01_13_RX_PW_P2, 0x07}, + {NRF24L01_12_RX_PW_P1, 0x07}, + {NRF24L01_11_RX_PW_P0, 0x07}, + {NRF24L01_0F_RX_ADDR_P5, 0xC6}, + {NRF24L01_0E_RX_ADDR_P4, 0xC5}, + {NRF24L01_0D_RX_ADDR_P3, 0xC4}, + {NRF24L01_0C_RX_ADDR_P2, 0xC3}, + {NRF24L01_09_CD, 0x00}, + {NRF24L01_08_OBSERVE_TX, 0x00}, + {NRF24L01_07_STATUS, 0x07}, +// {NRF24L01_06_RF_SETUP, 0x07}, + {NRF24L01_05_RF_CH, 0x18}, + {NRF24L01_04_SETUP_RETR, 0x3F}, + {NRF24L01_03_SETUP_AW, 0x03}, + {NRF24L01_02_EN_RXADDR, 0x3F}, + {NRF24L01_01_EN_AA, 0x3F}, + {NRF24L01_00_CONFIG, 0x0E}, +}; + +static uint8_t count; +static const uint8_t rf_ch[] = {0x08, 0x35, 0x12, 0x3f, 0x1c, 0x49, 0x26}; +static const uint8_t bind_addr[] = {0xaa, 0xbb, 0xcc, 0xdd, 0xee, 0xc2}; + +static uint8_t crc8(uint32_t result, uint8_t *data, int len) { + int polynomial = 0x01; + for(int i = 0; i < len; i++) { + result = result ^ data[i]; + for(int j = 0; j < 8; j++) { + if(result & 0x80) { result = (result << 1) ^ polynomial; } + else { result = result << 1; } + } + } + return result & 0xff; +} + +static void HM830_init() { + NRF24L01_Initialize(); + for (uint32_t i = 0; i < sizeof(init_vals) / sizeof(init_vals[0]); i++) { NRF24L01_WriteReg(init_vals[i][0], init_vals[i][1]); } + + NRF24L01_SetTxRxMode(TX_EN); + NRF24L01_SetBitrate(0); + NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, bind_addr, 5); + NRF24L01_WriteRegisterMulti(NRF24L01_0B_RX_ADDR_P1, bind_addr+1, 5); + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, bind_addr, 5); + NRF24L01_Activate(0x73); //Enable FEATURE + NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x07); + NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x3F); + //NRF24L01_ReadReg(NRF24L01_07_STATUS) ==> 0x07 + + // Check for Beken BK2421/BK2423 chip + // It is done by using Beken specific activate code, 0x53 and checking that status register changed appropriately + // There is no harm to run it on nRF24L01 because following closing activate command changes state back even if it does something on nRF24L01 + // For detailed description of what's happening here see : http://www.inhaos.com/uploadfile/otherpic/AN0008-BK2423%20Communication%20In%20250Kbps%20Air%20Rate.pdf + NRF24L01_Activate(0x53); // magic for BK2421 bank switch +// printf("=>H377 : Trying to switch banks\n"); + if (NRF24L01_ReadReg(NRF24L01_07_STATUS) & 0x80) { +// printf("=>H377 : BK2421 detected\n"); + long nul = 0; + // Beken registers don't have such nice names, so we just mention them by their numbers + // It's all magic, eavesdropped from real transfer and not even from the data sheet - it has slightly different values + NRF24L01_WriteRegisterMulti(0x00, (uint8_t *) "\x40\x4B\x01\xE2", 4); + NRF24L01_WriteRegisterMulti(0x01, (uint8_t *) "\xC0\x4B\x00\x00", 4); + NRF24L01_WriteRegisterMulti(0x02, (uint8_t *) "\xD0\xFC\x8C\x02", 4); + NRF24L01_WriteRegisterMulti(0x03, (uint8_t *) "\xF9\x00\x39\x21", 4); + NRF24L01_WriteRegisterMulti(0x04, (uint8_t *) "\xC1\x96\x9A\x1B", 4); + NRF24L01_WriteRegisterMulti(0x05, (uint8_t *) "\x24\x06\x7F\xA6", 4); + NRF24L01_WriteRegisterMulti(0x06, (uint8_t *) &nul, 4); + NRF24L01_WriteRegisterMulti(0x07, (uint8_t *) &nul, 4); + NRF24L01_WriteRegisterMulti(0x08, (uint8_t *) &nul, 4); + NRF24L01_WriteRegisterMulti(0x09, (uint8_t *) &nul, 4); + NRF24L01_WriteRegisterMulti(0x0A, (uint8_t *) &nul, 4); + NRF24L01_WriteRegisterMulti(0x0B, (uint8_t *) &nul, 4); + NRF24L01_WriteRegisterMulti(0x0C, (uint8_t *) "\x00\x12\x73\x00", 4); + NRF24L01_WriteRegisterMulti(0x0D, (uint8_t *) "\x46\xB4\x80\x00", 4); + //NRF24L01_WriteRegisterMulti(0x0E, (uint8_t *) "\x41\x10\x04\x82\x20\x08\x08\xF2\x7D\xEF\xFF", 11); + NRF24L01_WriteRegisterMulti(0x04, (uint8_t *) "\xC7\x96\x9A\x1B", 4); + NRF24L01_WriteRegisterMulti(0x04, (uint8_t *) "\xC1\x96\x9A\x1B", 4); + } else { } // printf("=>H377 : nRF24L01 detected\n"); + //NRF24L01_ReadReg(NRF24L01_07_STATUS) ==> 0x07 + NRF24L01_Activate(0x53); // switch bank back + + NRF24L01_FlushTx(); + //NRF24L01_ReadReg(NRF24L01_07_STATUS) ==> 0x0e + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x0e); + //NRF24L01_ReadReg(NRF24L01_00_CONFIG); ==> 0x0e + NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x0e); + NRF24L01_ReadReg(NRF24L01_01_EN_AA); // No Auto Acknoledgement +} + +static void build_bind_packet() { + for(int i = 0; i < 6; i++) { packet[i] = rx_tx_addr[i]; } + packet[6] = crc8(0xa5, packet, 6); +} + +static void build_data_packet() { + uint8_t ail_sign = 0, trim_sign = 0; + + throttle = (uint32_t)Servo_data[2] * 50 / PPM_MAX + 50; + if (throttle < 0) { throttle = 0; } + + aileron = (uint32_t)Servo_data[0] * 8 / PPM_MAX; + if (aileron < 0) { aileron = -aileron; ail_sign = 1; } + if (aileron > 7) { aileron = 7; } + + uint8_t turbo = (uint32_t)Servo_data[1] > 0 ? 1 : 0; + + uint8_t trim = ((uint32_t)Servo_data[3] * 0x1f / PPM_MAX); + if (trim < 0) { trim = -trim; trim_sign = 1; } + if (trim > 0x1f) { trim = 0x1f; } + + uint8_t rbutton = (uint32_t)Channels[4] > 0 ? 1 : 0; + packet[0] = throttle; + packet[1] = aileron; + if (ail_sign) { packet[1] |= 0x20; } + if (turbo) { packet[1] |= 0x40; } + if (rbutton) { packet[1] |= 0x80; } + packet[5] = trim; + if (trim_sign) { packet[5] |= 0x20;} + packet[6] = crc8(0xa5, packet, 6); +} + +static void send_packet_hm830() { + NRF24L01_ReadReg(NRF24L01_17_FIFO_STATUS); + NRF24L01_WritePayload(packet, 7); +} + +static uint16_t handle_binding() { + uint8_t status = NRF24L01_ReadReg(NRF24L01_07_STATUS); + if (status & 0x20) { + //Binding complete + phase = HM830_DATA1 + ((phase&0x7F)-HM830_BIND1A); + count = 0; + NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, 5); + NRF24L01_WriteRegisterMulti(NRF24L01_0B_RX_ADDR_P1, rx_tx_addr+1, 5); + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5); + NRF24L01_FlushTx(); + build_data_packet(); + uint8_t rb = NRF24L01_ReadReg(NRF24L01_07_STATUS); //==> 0x0E + NRF24L01_WriteReg(NRF24L01_07_STATUS, rb); + rb = NRF24L01_ReadReg(NRF24L01_00_CONFIG); //==> 0x0E + NRF24L01_WriteReg(NRF24L01_00_CONFIG, rb); + send_packet_hm830(); + return 14000; + } + switch (phase) { + case HM830_BIND1A: + //Look for a Rx that is already bound + NRF24L01_SetPower(); + NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, 5); + NRF24L01_WriteRegisterMulti(NRF24L01_0B_RX_ADDR_P1, rx_tx_addr+1, 5); + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5); + NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_ch[0]); + build_bind_packet(); + break; + case HM830_BIND1B: + //Look for a Rx that is not yet bound + NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, bind_addr, 5); + NRF24L01_WriteRegisterMulti(NRF24L01_0B_RX_ADDR_P1, bind_addr+1, 5); + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, bind_addr, 5); + NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_ch[0]); + break; + case HM830_BIND2A: + case HM830_BIND3A: + case HM830_BIND4A: + case HM830_BIND5A: + case HM830_BIND6A: + case HM830_BIND7A: + case HM830_BIND2B: + case HM830_BIND3B: + case HM830_BIND4B: + case HM830_BIND5B: + case HM830_BIND6B: + case HM830_BIND7B: + NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_ch[(phase&0x7F)-HM830_BIND1A]); + break; + } + NRF24L01_FlushTx(); + uint8_t rb = NRF24L01_ReadReg(NRF24L01_07_STATUS); //==> 0x0E + NRF24L01_WriteReg(NRF24L01_07_STATUS, rb); + rb = NRF24L01_ReadReg(NRF24L01_00_CONFIG); //==> 0x0E + NRF24L01_WriteReg(NRF24L01_00_CONFIG, rb); + send_packet_hm830(); + phase++; + if (phase == HM830_BIND7B+1) { phase = HM830_BIND1A; } + else if (phase == HM830_BIND7A+1) { phase = HM830_BIND1B; } + return 20000; +} + +static uint16_t handle_data() { + uint8_t status = NRF24L01_ReadReg(NRF24L01_07_STATUS); + if (count <= 0 || !(status & 0x20)) { + if(count < 0 || ! (status & 0x20)) { + count = 0; + //We didn't get a response on this channel, try the next one + phase++; + if (phase-HM830_DATA1 > 6) { phase = HM830_DATA1; } + + NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_ch[0]); + NRF24L01_FlushTx(); + build_data_packet(); + uint8_t rb = NRF24L01_ReadReg(NRF24L01_07_STATUS); //==> 0x0E + NRF24L01_WriteReg(NRF24L01_07_STATUS, rb); + rb = NRF24L01_ReadReg(NRF24L01_00_CONFIG); //==> 0x0E + NRF24L01_WriteReg(NRF24L01_00_CONFIG, rb); + send_packet_hm830(); + return 14000; + } + } + build_data_packet(); + count++; + if(count == 98) { + count = -1; + NRF24L01_SetPower(); + } + uint8_t rb = NRF24L01_ReadReg(NRF24L01_07_STATUS); //==> 0x0E + NRF24L01_WriteReg(NRF24L01_07_STATUS, rb); + rb = NRF24L01_ReadReg(NRF24L01_00_CONFIG); //==> 0x0E + NRF24L01_WriteReg(NRF24L01_00_CONFIG, rb); + send_packet_hm830(); + return 20000; +} + + + +static uint32_t HM830_callback() { + if ((phase & 0x7F) < HM830_DATA1) { return handle_binding(); } + else { return handle_data(); } +} + + +static uint32_t HM830_setup(){ + count = 0; + // initialize_tx_id + + rx_tx_addr[4] = 0xee; + rx_tx_addr[5] = 0xc2; + HM830_init(); + phase = HM830_BIND1A; + + return 500; + +// CLOCK_StartTimer(50000, HM830_callback); +} + +/* +const void *HM830_Cmds(enum ProtoCmds cmd) +{ + switch(cmd) { + case PROTOCMD_INIT: initialize(); return 0; + case PROTOCMD_DEINIT: + case PROTOCMD_RESET: + CLOCK_StopTimer(); + return (void *)(NRF24L01_Reset() ? 1L : -1L); + case PROTOCMD_CHECK_AUTOBIND: return (void *)1L; // Always Autobind + case PROTOCMD_BIND: initialize(); return 0; + case PROTOCMD_NUMCHAN: return (void *) 5L; // T, A, E, R, G + case PROTOCMD_DEFAULT_NUMCHAN: return (void *)5L; + // TODO: return id correctly + case PROTOCMD_CURRENT_ID: return Model.fixed_id ? (void *)((unsigned long)Model.fixed_id) : 0; + case PROTOCMD_TELEMETRYSTATE: return (void *)(long)PROTO_TELEM_UNSUPPORTED; + default: break; + } + return 0; +} +*/ +#endif //PROTO_HAS_NRF24L01 diff --git a/Multiprotocol/opentx-multi-2015-24-12.bin b/Multiprotocol/opentx-multi-2015-24-12.bin new file mode 100644 index 0000000000000000000000000000000000000000..fe1836e7e5e2ddc5d8ea5bdd6facd0cd5ea034a4 GIT binary patch literal 362852 zcmdSBdwf&JwLdzu_twLbjAhFZTjsGP8IUa#Yz&D5Nf46R7z<)vX?dkccG5_Y6ai@~ zNK*tRsR_v`2{Z@n(2|h$q)F4nqVB1i5<7vmNt3n`k5dClqcmwv?4*^kjkX_H_d8oQ zb<@wezx%oOuWNty*6cN}HEY(aS+i!%5WFBQ@Sf_ES`)sxQ0M@@mr znv4r#-0Ud`9ML2%6nKzI%=2FB)CZb0x#w?U-&V7?CP7wDtfu9S8+n|Hu-g@X>y<=&ozp6@R!&2=!|H;a+V+mA@uIsk4g`vc!0bRB%pWz@x=u#8XO~ zorGK=yNDYr8U-%nK!@y(V|3Circ++j2vgF^}{QsprkGlWgmFKFd zSyNU@$ZXHv*UbJjHxX;2H{Wkb?AvDP3zy}4i+n3)JMwm+Ng~lqD|BxMDslP)s0^6wcwImPouxl z+lW$#EB$+XRiihjdcBw75Z-P^efsMCbm+nakMkt;RTS^$z>{V4i?SHG6&oNhK z?=<^==QMkROVag*cY>D-`v@ucZ=&-M%NQMxqBYjUzU@|pRw|`+2xEj@ypfmT%z22_ z9Lx){@;J1E2UV>JnR9iulRTCZFzQi4Z5UWCHPTbNIcN@YQNhkdgG*Rm70L)M364t} zp0LDaY~h~WpmlZ$Uh1X`7Ip2-adq*P)U(l>9-m|7dQonMhW9M$3L8($`^Z?^#^U{m z9}6!-m`4v<6Q9*)yS45kqd2BvA=kgdc+QwkrSuc$IpQY?!;L!9`4az>K7A1m!(h6w)Q!<>)efA^VarWJu$lT z?*AfPZ$}@E(bYLFypb+(2_Ey7jAo;o#;sk1k1Pyvp7mRqlv~fZ zK^gCt{dq1!8xg5EhAVhN!D9mAwJjx{BQ8~pid0G^OH)*=irW$Ig%~NUWKn_eDN!tl-=sjC3S@A^DdxmY z3M8yRdPc%xM%)O9K33Bg4zl_?M_7nhPF>MDQ_1)n+Eb8=gmV%B51ad$4#4LBTs(Pr zCgTw~=d4c?i?aNnowd=)b!k-JbCt%{6Ta}UQ|fTI_vtr{q88d?hl^z1aI}e~I(= zJI{DkgWT0KeyjT}FD*AZejPh?C9$XGT51RHB{qJWdt3ds)7yee_P&OeDE+5*vtB&y zd(+3>rvvm5d)VB?2lD^fSAlROxWqjU;#45CKDcBN9$oWTXc0z*JFw2lerZC(zoRAH zdq@+>vK)0bI*l#D=E5#YX)WEH?WVQHQ`(k^V>DjDXnfxYqb{&pLGbmJHzpuf!+OBU zVyjsXI5Xn9(L6+fE(DY~$NHrr-7lroNh$!nojCOk#+GFbT!YR1L<85iXqCRwG zHuo|-PvChEkICH>;luR@Y<;AzKqxTO*XtkW_Zm;tA4s&=`W~*cC9?Q5oU`%!4)`BE zz&T!tR74+dAjL)1xozAGI^(dvkmE1l-A9DO-m~&PC!XLc|A%rzJCn=58oGM*Om9Q( z8uxE|x$Qq2y4v@y+>o?_hLlaIO|xlhRtzS^;7t-`+^^d}h3fy=D9^TLRbk9FA?<1>OiDdOyi3}@Xv6{7l7Ui~) z1L4P69-_SK5vywk)^QuSbPv*GWKi1yXH&%7ytm=$hzZ!UUuzf7*CUqS|Iab}O#jg~(v+jROdQR8sPEfw4 z@0smicGvXn+WwzISCjPCHuMB>&)j#S-qsM<&-je;wy>??C2-Lmj5iMbs&f|@7zf+J z#rt1Yc-gi`^;+VT)0IVzKSs%-s}1E$w$+D$$#%xippg5m@ObW}3YSoYOIW{;a&=$$ z3*0saCkmY0;KH2dMW6|d)5Hj+7$;-t#&f?iD)zG!z%?<#>)i~4`u*wgGaiHSn0;|v z@eM`ITf5xutzE0pW*R@;JAog?xRuc-th6M2qa|!))gKU|7=v!c;aptdZg)Loa&te~ zIyUM^oiYmQ#zq0+Hr$O?eIB2%EM3eFX1) zoE&&MVoB_FySj)o&*?U=b*){5lz@X;fQgCS&UA_75Iv;Nq6f(#(u5p~OwF_@x15X9 zrVK-#GG7+>$3{G>jg9#|pi6y2`0*x;bFEVyrHQ!D)RnzxOwSohL)x5)HZSLK_L0&K zFKF4u)^Klyj4gafcXCp7W$3J*@A10NLSN^sZ}kZDoro|Ot%NMK zCVC?Oo~K+I!A@&YMb>rMg4Zksnjp>Ut}MZhvJ$6rS~F$Iro*;N)2fF|}n^ zm!Ck#ujyN1tLeLfvU1TYt7Mi_6YKV?tk3#ukvpB2h!v+!`-un(270v-Jdpmfj((+A z1hmPGan1BdU+?24_WPFK_yqH>r>PVGCw0&exm8t*dRUZMW9;W~qF=(-wn!x1W}UmF#;fzE8{Am8WIH zN~1-@3dxyb?~N&IfY^XrnaQ`>_ms~PIOnSk9dc!z6}s!Wrvq3A_=)`|SasDT4mypn z%Nczs@u2s!PGb9Kx>XPU@9FetS$K!u_c3@xh^ahI;J41LuVb}82s&3l#_*I9KG5Vp z-MfhA9I7afhdTHuFJk7v!{Olr#+GOOdje;A7ZIJGv#Z;9(c7!zw&Kxw*MrYoeON8R z>QLIUJfsiNSr`Ev>8=-4F%=}-3xPUNNEN5k+1I@f*7Z(v+5A(4%=1tB@9Wj^zYo3B za9{5sx3Bjo`XRj94ei1Px)bqYKXD;+JD6w+B%3FXpsx%>a6+@(snd|+$uALkmp z7m?f2#c?dR+;Ue)CuM}_&8q`g)zHPUCj&+P66DSiOs!w-eZNv4f5!iVe7f+zhpt^? z-~WTO+P1Iue&wMO-E0*25U_Y-AzE}xEaq>D2DFiC;8y_?U>U`$_ zQO8#AG(p=TD`}k7X&SAwp12>(2j|GAk}Xfkw7oj;s~(zlM{Hlf=ARKD&-6!r)2mtH zYOU>6s~+e*qj^#$E1s0OU{?G;{1MmVpnzJ%;_mWM>zz_O#~)F%R;AwOcs%`nvMCeiV0`e|ms??;nw0 z_iCgk{nf41dS9ip227Bl!X-BHX&h<%;4~9U8C;T1_YT927~1v*Tn}=$nG{)d z_v#~Uj4RXW_&{Tz19FELFyn%kJP&dhJu3ovPBu=C1TG`Q)+J2OA&1&+Ps)5LwPHN* zz?}!~rFnp1r=ijPpjn}yI!3O(w_>f&3^~PYuS`FQ%6Vm2b4%|wqdxyx&BP0Pcg=5x zM9S7-23drWN0gDL5}ABo@8uH9uiFCaVew>NSo`kUfSgVK%NorEI@fTL7}px88Tj2MIMtlp1}hB!69$ zjIg2@VMY1#ul`Bdj97i3z<-p>J`aofLPJ}rD1xHy2Mhd-T*fG@rq8(otDO~)&WMB5 zM2JZXgG6U#g6fa*`q;66vDo3~Vf!dW4c0cX*bpr(&WhjjV5C31$>GO*f&R*iW97X` znLFxo5O!`d#2Pu(1!Ak)md=@v{t_VDiJOb-z}tT;cX&%7>lj5-$umRLMy&hL`h9Y) z#fJ9V(f*vX)KV|^8=WG-Z=ZNV9u({4By7#YmTYevz zm{aZ z&Xn!fyBX*60bX3Mj372$^`1(8e@NR(#G=129(Z9$EfIS%+TPplB=(vpgZ#*x?^D;0OM9i649g5wGD$oiHUm$RcqVKMY#Q7@ zlpnZfi_m?5n?9)Te>(6vecJzdB-1_7c||k%0-O0Wde(0dC2JQXR9%OhSGrC*=G~3m z+6@ZEFS{~gtv4_hMls%ay-34fV5zmhxl5f68xh_z8g?T5;%FMyt|ImF3;!ukE90RR zQ!6)^an%-Bw}oi}>+Aj`&n^3tTxvOM{*zo-*66BeGf8|8Z(!xubUkZm3N%IP78hMa zx|K**cFbivYdVRvmU{}m=d!m=lvGH~QobDdlWflxrS;P9WuZNl{Kf#j%N&)z#hcYK z1);esS-Bq|zA13FlZC^;FQbQM)O4-aX?p~%{nmA$aRhzxv7fW9_mP|PE}hu5p!xh4 zB(^Ppnnq>&98jz&fIh}-L0s#7R4iA`g6w-z&MG|&nI=jsRK)0tRJH(QuCLMmv45TK z#IDoLf6`34a9EyLMjbh^V@St4Cd5!%+1QRC`{kiSo3XldCDfc5<!11|apZ3Qg3501%YkW?ulhdrQ?U`a zusW^^b1z_Cn!er-K2m17B5>x>0h?6(zs_QGCY!(RhaTSOyC0gk-ueM%H8W;gQG))O zWA>(!MZ=(GUwGAe-z=q_@IF{lA)OSaTwt6Z9{d<-KLBQ126;PXYugE|PRWiF;S8G) zr}%Q(PK4Ro?aAq^9J1;IFBRAOl3d1x{50Lt{nZ!FVU%kD+?1|ov(k@!M1gN385c4Y z_=Yq*5mx$lyG9R6-{aq+5iY2d_$DQuiuZU`uVJ6yyNr%TtXHng6C{Q^Z)39?lcn00 zg9wFXQ<-36^F2$$dXdRSEpmJ^?{a`|9{*i{vi}*&FkxR~r8AzQD1D+*IxEfC(i9M+ zBTLSsEK%CvCl;0iDJWJ_7GsNE5+o=3{>kC6#c9P1XiFu(GtA1!DLaq+$3txVGh9tA z0i-2~y9SQQu%*H}LLG*v`Wy!y6{P@TS_UV?)1e0jGDbs(1_gv@A`Hp@_AqvBUNd5z zLODfCVh17nILEEAs9a%*DkDDo;+vtfW?Iw^hyb`fTVL6ZF)K>v5r&OE@wPlI9+huj z*)r67jUSryrLVLeb7h>1%1%fF)!8|~;=koHveRdXvld_WJDM@-EPOEqjz^ZDeTj?m zVR;fpm@$@7Z42c1*Tc%W4-hTN{bb&TfUOyQf*d5q+8u;mlKWHEe}c5`b%rtTC-m+~1td*yV^P5%M(>=R)N(+q;68sP)@P3wZ6 zwC-r}galAM!$Gc2+VkNRQ{uOTqq+1F$)#T-I=oxSlVnSSSx4uqi^)|1X>t-8VkR?@ zF8v>sKbx1?qoxJ^aOlXA?glD3v7%?Q19i-Uh3yqtU0SAa3rp3snWf@v?jQwK6RN`a z<%kNk|0(?86+Xdh^jW5xScx0_Imq)F`f-Btd)cp3ehUI><#$7XOUDOTsmDlK&b+y zH>RW}G;=lrnaiZdlh-sPI!z9Y-vGNd89oKRQ#% zRlq&nc01Z#+7fLhw)Z2n{MUICWxA2fl4Es~HxN@;ALMPGAg$nRMw!l@-@I}1@78=0 z;mV2iazuA`UnjF(!&7EiUMPnXORO{FX2-+P0*603`7d^)xfoV= z*zo&!csky%hO_@N8^42l);k`G79)>tZ|z4;{8+YWk>4Mr|*pp*5hv)3fDL&F>4wJ(F`Dk_Mvc_=!>z+buf&X%V8=~_ZJLl|F zl^?>4Ws+$8>&rE^9o42VadbxMf~Lr)8@E)))+9T>#=ORg%;EPt=I(sZlbfKzls0Nv zcXzI|@$Q#DB8A64y02PmGllQ3X1QV;zk*!Ek&K<`+@!#3N8xKn;lJo4Gw;5O*j~Sz z-fEaV5L@Z7qxJO18~mHmJB$L(#9zZ&TW=6PF$>HS=4>+?wr}g*X4Y}G^6jK4!oIin zZa3?ecp}@Ug##ZsJ=HY@{_4B5=;hm_IX6mqD}0-OzK7nXn_v#=4C{kBU1M;L|6(wE zLjJaF!@6zRx=Y)RZo9>!1*N2qK9u{yM_>VZQzDMCSn;yM0|v;*;!8z0dWT_lB-|4^ z8OjhAb@9F(JFo7{cbD(9OZc)lJo(=8UB!2~yEy9{Xs_)f#NK|@yoa+jpj77ZSngl# ze%@d1ZFJG7_hIcvH+iNlWBRQ*Jj0*m`B3&Be+GRq30Cb($nl}PG5mAv6rYui?RH7K zv;(%brbv7VvCp_qB0Tr=q|3p{HdzBhgnRwz4mV8W}ZrNUoc z-4p@EjU&mmsSWXYca?*(=MT>HoBbEjmYDQ+ZFNX1 z@z{Ik6Dh&etg;kZGvisFeDt`v0rrsV#ICtK!819mirXQFM5dEpPZfG299u(thxO?% z&_}GF#`<}z@0fgIeH?6=;1MMA! zOD1ysCu~RK>v;(E`~vCkUhP`V^09KDeWJ|;Xcr&NJ|{SI7qP0UUiom=oK$i;qv<79 z24!|C4o`LO8W;6tlM{|P-=Tq^n3VPY4+Lrmj_ z-(4GODWwZIhwb7`p8SUW%_sa3|4~>u^wL>##4A|At>Uda?C2|FHOn)Sob(1pd|Wfy zo>M4Kh4OA2EwQeRVVmx|QM$NUA242E{4z@0Wj0Vp6=NKr86h?sW=5S_eSvvYGp&~S zzuXC`kT#ZAwCTg7D!Ak@`q9|32fZLA z14zX}Eag{~lov-(26lJ!A+=;mcvS|eI4aJnj#Y<7in(a2I43$azP#bd);~7T*%M-B zwc&y|YCV~@v^}B?ip{0ce8~~7ZpcB%B5C5kZy>V5t`Bd@`BQu~46%BIJt#MCC z=a?APJMyqMRuIeBIgH8^`#4OdX9j;1_&ats^sQw2P4SPh!!#J>o?w2GjjsOaZv(f=6Uo|UCMoMu z#Qs_IW9(!fb6q(byqnHTVBd7d-SVm5efz+-c{?jn6{~tg_Xxa8toU;0Nx>x*E%lpK z(ovT|%8FWH?JJ?w<^&z?9U%6+HqdHrF1%!k_>)@fokB|{*h%5H0bX8T%lP%fRQUD7 za`BwQvV)ary~&dk!HNe~*n7pp@_nVOoqX+Kxwh2oJ}lRj;>()lu_kuA8eNmHLJO0_ z@*WYc1YMl>u>5V&h*Y~pe2L80rQOVYbd9HYJRF|8UrMErp^Go7S_B>oXD@!CSGTZv7M*n-|5m$1m_S(P*KNmw2CqJ<~fH~D+) z&#_ z^{yy#-cfp3zEfm$H)*VUehY}R{jj_cB^zuL@O2mBYuXD0cbB2=u)M4tzx-i&Is3I8 zmKTH%%k$eec4_S|Maht6K---&`Mt`z#V5|a*Uj@MhkAO6<5<*rt$!P2^u?NM{lR+I z6W9soM65_fRkxOM zn<7L!8U8pN_p0N1QHUEvF3zX%V6%BWX)A?%;RD=l+=8R7JKFY!+?%0^mtqcILW^X` z)=X*BMLuxUwec(u>0N|X?tI9$yJNI_rTWbP?fw#^c4)-d%;bZ7>Z8CnC;z5btDaGb z*{=J`mS^M=%v*kFOMj33wpXjUz4EYJLb^3l7ZI1Wkqma4Kt9FFnTT@MAl;?dgGAMr z`g&b{N#!BA1U)f}z=sPv(=62mtjQN4)o)|3Ak_#`9g=60L-NgHN%@8lQDX!+ODdgR zJZM=`n&%c1L8p9*BDdVK&kvuQk_pnMVH)EA;r-^oVb{RfHLd0lv&)$`TU*WhpK&G5 z=53xB&y{`n)b;+^YXyJDTGE^P%uDPSq7Fal zo@7)fvebOHWGX4Q`?mNP-mLau%dZ;*iOzdDqHh(j^5hkXG!bbh$KLeQa^6S$`K|o^ zW3GRkHO1>gbb+aBqG>`bmAoC}i%QuS-IKH76~%hu&u2dZO{b?spUwZ*aJsHK)D*;6 z52Cgp>~hH(J*-2s9SstVZglW5Z4cGLpDxb(FZ)k;+5A7vv8p3&i`$+ewmRRRKHBJ5 z8a*#hK1gi$Oy169wPBilNyjw%6K!O=Fr7N4N(ZHlu~z5?Hy3+j#9Abq#ODHyu97xU zyjg6(+E8D7Ep{TXI3cP&*q$!CGPSmqNnLP9hHc++N%UI+pcwR_<@_)ht zTgU7%CB!T~A@C#-3lr<}-dZ2C`MeXBr1B8Mf41Y5nA|zr-V)ttKN)T55AP<4Z|#ap9mp}+8nHr2-s&&ZhvZTo2aWmjEn$HSh*-q@|7Oxw(aQ$rVSa^p0it|meB zk9i8P&)<_*73$r{xSH*d^gUGndQWCnN31-wPVMZu8cy%C{XL9)iWTkCuqFQWRt|gi7wMv|)qL|t z^i8F{7#cs{A3M5uVc()xpAVedWrFm`i1low#H+51+lPmy+(b3i0yIW$ZZoumH2wx7kGEqWwq*p&7TKPm3xPed#87*Ai;_4 zxj;s@#1+Ytu+jha8d|P*48kIHn`|Ch+f}iM>yaqSVS=aLxy9Vsh-+f(q4+O*^jSiT!D|wF z-JEy?t1yk8oav-@d>*;AQ!VmJOAp8Pck)bvf0wNtQZrQ2TuHDM1xV56s2w{{ zuMQD=Ft!EQk>V}Ui@W|>%uWT~9knDxjdu3RXjajJ*h=&nmuM5Z8ou&yF*x^m*W%dv zha)am%pA(Ju+t25{yzfMjCUsx%gm~5oLJ$z4dkFq!zS54oLyS+4Ym^-9VxbV%#?G; zV-lUC@aea_i>JkCS!U74v4YSB^~?(+#W!^j8`6|o;t#Y^iIdLL%C1%1#*MVhTB$GM z5-F}f_KYhp$~e!lkF6(Cg?4aX?R9S}FFnoFFIvm3VA9QdA~czPtCoYS+zp8896DV85(qu9??SYqd^z^ORJh`i8@AK z3?S{cAr3Pnv~N+s&QN+@OtiexpY;fR>L%FDJJ?4%G_)Ep40+; z*J?*WBBj^G^sOT7@IFXm{V=s>V1Ahu_4>}s3*`^R{1^PTP#g3&)-lR@F*_ude(;J{hzoXYo2n3&^+Hi%R4-L_w}|bP{z;F}gA*h^NPnD(zQ1Qs z1&iQL^uFoPq?dCKWj4))6)Ee`2lDM<=9RH7n)xDI$zo5+z9PnQ+&rQ|j;dH@Q_fK) zApp?OPjhMyq_N^U~zQu1V)Q%~t7`E?CtI;GbQYEpzSkD8;+4 z^Rjz#C2g8*HQ)WiPUMZFHSz4}wCU@uKXdUhz@as2qGuV; zp748p<=}`{3c5Q__#FuS8vH{X??EFPKBR9_ubQv``df9q@npl;Fv2jYLQmT zlNS_AYeS3+pBXeNTo^p{Lmw2}a$-2Nbv0hBb$Gt4&^U7ePq?C7Hj>~HP4$7u964Lu>*Axd zEL?OgriUL(n6NV*Ov7)7%*1}DO;f#*z*l`+8D{3P<_1`UX?b6#wK5{dIVKBPx*XVJ z)E-SWR&jK-Ea(roTzJC<(!f=jU{45R-pYfmM?gBx!&epfc`s^ddwLX(F}qAB2~`%@ zLY82cj+M*OzlZqoakq_&`|B6t9OL4;zYsTNT%7!cxU6w;e2|EG54SFm{hE3wVY$}Vw@20^pSk|iPC?0)Jz55+ z!RkQyJ6fnXWf_%*llKnP^tG=h)5#%z2D4@b;ISi=J}IlbPs(a|-)dG2C*K+rCA~#w z9Zudhq=VOl!7`kjI|O`ouyk01&453|A>>1PHS)1MFAkPTz{WY8tQ!c6WvFSv0NV*f zJ5fKlrUmtShm%J}-0&6>N_i_r&xrN%RaYu-@C8G-M*fyMe zc~IjKoAYrNrl@&+kdK=~Tr2EkkVk7nI0*-wE3k&8Ro9d2enr~edxMCY7L`X;g|j{u zRkg}ll{RS(YJd@6GX+Tpo`i0WY4WyDMQ;OYv&yD*>&|YneO2Kx{;P#*MqxYE%cB22- z`Q%c9cy$$r)=U_*H^Y+?7A}Kge^Aa1A`NIx_F<0*UcL#QUmA1Hx1G~tyn6g@+#OKw zeb;~5s}Jx#Pr&Uv5UBUP8#wLLZ{}+~o87esHrLm_yZLmjehXjc+2XD{u%*84-7Tl< zoTbh(=lsiOOXukStt?}yvCKHX_pD)#>fB0MSO5)efiQpItT0C#J*%1A290|G!9&mK z8~Csn_BHf>vFY3aO>@);41XFu-6Qa4&6mfeec@c0%qz9i(Ut1E_NuX(B=}zt8)Vsn2_6O;cr~+n zQ{wJ&2GJ`J`PHH1`RiQbO9M2aOEKCper1mVe8=|B+s_b@3{w%jD5jDlivMs)v+Jrc zIFh{MI=x-)WR}zE*lEBWAZ6w-EVN;B1GwAybcCJ1GULm2l~VTQ#1~2Y9AiJc04m;WT%;Bg9+7yvttJ-Uh(Xa|WbV!*6( z-*tPoGhrlb^)3MBOn4Dqe_hOQCW7SDl?rDnxtfhePXSiWLowEe^FbS9wFx(#7~xNz z<+?92}M0B9aYt)U~mb;i{UpWgIT#d zTJr9y=@Z@DbW*5{u2CtcVv-JHl#S1FxfC9MSr`c~$;DEsl!?#}WxeNK^uw!*F4g8g z3Q4ypzy4_bqN_%lzwg;P^S#vi>|S$tR35VNq*cb#XsdpT{*4c_6YM-fddQA6E;W5| zNNQS04&_yGHYTZ=gk};`gI~cpl>9tpV)D$**N?`nFfJdJ%?h^Y?=KBuzcVcjhLRUj z8Kd_d39+x$vw8pg$j$Ymc#X~#%6NyJU)xg3Zc>8R_Io2YkKK}llg7^g(mFC5m_9a~ zi}%TqLcGJnpW^+<@E*K(4Y%U`&Ee zIEweC;U2s<4ll%e-LQ=JmxlZCUJbvxR1#AR-phxl;axr4hxZZ%UO9XX;YGve@V;~S zRlFA{lw_EF^^FDSQ?_TJZMg}w*2AOxaB3pBUzhHMh zeAfui+nm1ermSiM>@Y;k4rHja137`UIE6|{hKBuW$x4kmP@up#vP#8ZMpB^siUcFn z2pWLLP0#_srQlY~+BV+GX6=9^+PI(ORDp}dN?CiyQ1Xe93UKxW%&SAm$3|RNC-4Eu zpnUBfsl56GzA}`r&zamd4#X3zkmcAkzN->V=UV)u~ z`!Pc9SL9siA6w-L?Ai?{J7v41wg}cC_)1}K)T*%zC6A4?kIvzvwV}qe{1{4_M%2v4 zvWKjJj1)L$*sLZ@COWTvI#*Rygc9Ez$ZLgs$4+(yEU(z-X=7>sHO;F7SpEK6nqZ3> zS^z1{#O@orZw0>p)4v>_rOfL;kV~p?7Xaq%zNo$Gc?*Gl_lj%>tR1kfsI961M*RHTGgkK;pEf-3m`uQq$6rpO4=po1M)*a{urHvk|;`Qkn;d*O0jk9nJ6up zbTLawyHC!J(-J<0K82ioL^dK-19C>9nyTUCRhizdmZ|=Q2r21~@k)*_gPw}sh&EHg zlf6Vk!g%)K;qdLm!`jK(SStNE@_ZzftWOy+wz<@`&LFJfX&M-$iJ-x~j0S~w#6_j- zDe^SbUxoVnq6MQgaL5IK-3eG1T4MnXekk7r$UHzkisn>(1R6Xmn*b>Rq$5fSKaL!8 z>7r%#=+T1j$_B(tOVPQ+el_+^rw(6vDdyjEI?CEJr1-Y}Z|(VKJBlRcVfviXj_;4K zb{JbSmHekutcJgjz}nEPRd61H50@6OPXHtK?$LT)$8NPUCdSc??d)Dw%6w>Kpp)&N z!eS?!>2V65M4oqPuwI-fk+Yvg9%!zRnj=p4EIrd9D_U}J z3Ot2*%NDTVPAHqthEt+M`L!ivUipR>iM#99s_9BxxZLK$y%sDz;4D6!4x<8PzScvw zvi+niNr;p@%c&&4q65_<3PIk8sjq&1Vos*T2Aa-^ZC?S>jm(F}8 zq!vHu%tPq?m`3dA6mI!Bb_2}O+~uj{_fif8Ux&}3;H&&Xzi{|oUw2|?fH- zg_hN&ZyaE2Y9`YfUc(90=@{ML;AYONqD&I4rO@!TkYX9ZCuJRU0{x1iE3V#|Zs$x>kiF-f1?iol!q1|YaljVAQ$WoPQQ9+6=9G+G+K?%(tR#_)k zWr2t1A>F9)%#FK+37tbW`E3z5&Z5p0{b@@>8?&}6f zwV`C+uny~op=22QGy@p@LrM4b_6SZWl4IDt(57V~(~Te#*&RGoVk?fJWchWrE*VPR ztK{PVnTdRub&)28KF7L_7+ciK=Gbgrobmwo_N7vGE^5PROF3pd<;1+KZ4sa+g;x$G z-yBNc!}OOnRu9gr^>GieQr=F{+Xs;vy`*Ly-kFl-!Z&dm57sE`mEF=IBz6l0qh&ld z#Li!*uycTui14PYIK?!n|4P{>z=Jo16QxerkJvBDeKvIk^66;GSt3NMN(^n^5vfSx z-$TrIQ_D&y_TrAEbcLy8V~WR_B6@o+{HKyJMdkxPQ%f%VTP|y~=Na}nXnP&%Za^EK zNoC>d;UUbNppB&TDej-RG2?1RHAYP-^uIwH&Zbh{7G$$#9BYg*8sFs6S%a8+CP-%Q zWVGSSXq6hCK#X$m5Qi^J@YINXAXXwV8r_l-gY0)s%B%d|oI0-j7N>-{0(SOZ&OhPm zLcY1cZ%&FL@9m(yqVE^l?@1*mr5yS2>zJELW~Y9p?7p+o^q^o0-dj50lExx8g?q$! z6@01FG=|(|G{$-K1SrF1MAoOt7UrpVAS^+jn=0ibxGWmY3x(rsXV~S@6`B9)Tdu>%>P2YuW4lmA^0(KLyzc4~yt+<=c6-s2BQiAT{ zu;5oy`jTTx%;C44{1hkR!;8RoBZ=l~ofe7dy?-5{*wLhgT;UUKi)Ma0)8Y5DI&eB; z1xhE|SebG&DV!3oP|jff0efHnh0JRFGri2q7 zFhZfBFv~L;nrh?7z0Ktz9(To*2Q%PXhg*db6`U)fW$i@U|29$@YL76V0CxUZ>1&J= z)(@3<@>+RM9^$bN52-@hSbRlGzDETgvs|eF`rT5F78_zK(WZw-I$D`cf#Kgh5{CYF zCXyRpg_y661aHLrd4%a9s($kI{ur?=L+mESk9*ZfDp@%qPG&wMP8Z{6R=>8z-&%)R zjD*@Xy7O8oTQZ}?Z;ammradLV$A|g)FuZ~-b`Nk0fj5EIT^vrqOOs-2VOvTiXN}}x zz86N){4sfi7M8_FQ1@T2v)!HFjAA=8Zc3=L_~@UMJ~xf5Q}Skwyp6nnyUt_;*45W_ z@nPhATgmz38?E^qoNyj#{usNC*jD9K>6PoatM2+(o7kMr+O)eRS7KU^6CTj2A|p=6 z!@E7I!pR|L;zwa>TOAbQsiawB3HkQlMXbY&9%*ZQu*7k z>A|g!knN+gX3Ib-dGPvcJt+Z{EZiAis&LCI*V8rrFzm;fXq-?0_w0xri=(%8n8NOO z-Es$b1ovMhQgo>K_e!2ake|-P6Jh8?*VDNOa*;%RxO6(b18c796B8*F<2qfb(OQtr zZilgXOQeOU6YIF^?Cj_Rv2@OlQIBb(|Mh z#&JTc^q8y_o3g3nn4D3H-L`U^g0Vgwd786&f7pr9YD6o@enQJ=_tQBT#YUVZ;jy}+ zT=yR9FC>s;3&lk@tCYH4KyE z?c(=m;|9aq4mfSzxl*JPrP2+6zsbMVyN{#g+z?-G^9s@rI|aq|IVNivpX9(!iPIPy z7p3#hM$E8W{Oh;Dlex4Ypu_%})7I$Hd-XBhQhn%h#M;a!hIlu_Kh7rxcs*(gaO6AfWK2U{g>K^^zczL_jAwUpUN zAzQD}7ZrOev<79xg8AcZSh|(<7NK^zWrCz)_l?1y)p^zJHpSsZ8)#DHoY%w4n?a}h zXG(WKK2QtOXoDl#=ILHOz5pKKz&D;gd%*Ax!4`x)LXQf*e$1Ab!g^C1F9jbD*Z}Wej-7!4HDK#SysnbXWCrP($j@BG(Oh6Kap@GS zJ-C=%GA+%Eb4n;@sVVL%(R6$?)h;dNfbsTJvST1K?!4-9KkLfq@Nu+<`0Ubi{pv+5 z7M{J=>0Bn?UWni(UCe2v58-SF=vca)?J-ch0q5YD9OGmAG1LDl#ia1v;O1PVMb3zk z=@dn5x0PYHpmSi)#8w=uS!96LJ?+V~@i9+isQqkn3cnu_F)u<7*CnAG>vH(QD0v9j$Dq z6n@9CQfVC^)r0E(@HeEz@ffQ$O)XX{_ko7_I(wH$f9RyPa_>u>oU)_*A!x;RRY}{o zSl{i|z`#kg|4y&%3cWJENH1tL%$i6Ne}9A74B35ld1rGH#wUvLFo;32I6t zlu#B;&;R*uA-+nptc~5nx6Vlw-Vpzji0ACami&%|MFjrS9^?5!VTdOgo@{uR=2dci zK?@(v(7)LOGfzCj@McdI?$An~h&v6>VOBr0;C$z`W3tnmeXLRHopRX-zpF!6G?yd% zQ-`EAZNKhyYRF9PPz`MRn+6-Mu8iO`J85vWUwt%uuH8hXgDWsN#Q_%tmeIVe;^y$C-#x8zDgmg z#aRce7%7FXAohaV1S>oH^raNek{dP+J~8lKC!MRS&i2!?Y%lYu`gW)O=0pdX{r4!} z^scM>Jh7e!q_ZR0sZo4OSbyBwqFuIl>U6I-pB}>gUm=G(T+Ef^unOmMmttR~6f%pY z3w?vpUat8-wujXiJx!9fFMc1_lbTOv@;#~BaPohEILf1DoTIv_*(i~j#qrvc(~8v> z-LTEz?t)alC(kd&r$(n1n_}?p+Dc=_xf$^m+(k@dhPeVlWOr_xcCKdb!jcK^UxY;= zBR-{A51ZCP!fq#|rQtkiQ!_o%Z#qjQwMSLW^5%JsUZIVa=6TaR&T!oaK7q}vkYI29 zhuB{+p3=0CLn*ZA`=dKW?DTPe8;?_sbU^<`mvJciNfQH)sq=j@EK>SK=g7Zw%0Pl|ul_Cnq& z7b)Q{Su4@wACSW5@|;C)w}A(^yCDy7HY!Wo_L7b37ErtKM(x@t{Lhuzt48j}xw*@b z-mL!5l=|U4=+-}bOtuHrusIxsyd;MgNDaXCR4SOi0QR?PKxhTCKiD)I+vqLa9op^; z%53cmSj=tE>rV2h6js1!>+qof9TAzpWbdIy`BQEUwKzk1^QQBN> zf-W?Ts&CU2!RydMEqh!Tr$lHo2AS9OD)b!}T1C!AGMZiBeRqh1w}LxZAKKDf+gj() zL}xFZ?O9}A=f*oB()=K?Ar|pkaGs`v!WTUY+TN_F;8+qXj&E|9qg;p4F+Cbw;&Z5@ zwT^iRW#L4k&o(zcxq7l^uX(+Dvd5M1a^_$`HNmN}P1e0Zd)yroA>&P+cC*Q|*6mH~ zCKKa!tU8RgytpegyO_VY!C0@<4v*Rpoo{w!#k5GRMQUflNi@o>$nMZW2Y*p(OQ#Gj zv7>!2zx2{eteu5;N?UjdyILD2OIWjQSls+*-cKO);m;qmNi=SQ|687f@dq25!9xno zAv&E=#f)92#PDw-+NyajvC^Q>k;h7|HuWIMDfv8dH5SB}{nk+;vifu$*VU};mueT> zI6u(17v5~)#{JA{jyvJ@@NAa}yG5A2MOaF(S0q%M9%nWbcH5+BZz>6=H+cRNr`)0e ze==L^_2dEA7gxMqx66I+R98-t`I4LA|Mekf zXuF(6ZLZ=;GFO5*!^U7s@kMWZ-Blco5yu~(CCJPt$~|S-)S6Nov4o{5RUiBQ%XdAw zB4v@x*wtN@%7aDYIEYFpT$ zyUS2jCcW%qc7S64Qn^qRTX*cj{g87tC7(l6hV-ac=1KTWhe5lNmx!3a?{Pc=WKAA+ zwwWejlo+Ryw#kh|tb-m0jS0F3u^fC2c7av@7klp>A60eskFK@%o@<6=k_nK60DES* zb z8B3`Tt2AZ_V~{)2d>T<1RI%Nq;=Z0j%oIX?y}ah02O8KolF_;pWzA?xg-M*p+fyWM zYk$w4-*B~x997^@1o}nf@rdNw^?2`VTqkTn^;zvQ@J$w$efK$e51!r3&2T=0 z6|ml(2O__epU*@va)$k-NFS~WUF{ju-{14a72IUPT(JuJ26+1u^O!F5*RSp`W2>TX zUuD1R`l#67v$eOsr!b29Owp=Wp??6g^iQwgyh4nOea@a|pJabmh zOnL9ie_8#eUi>~{He5{;x8nJOt6R%N&{TKzxl9X2%_IA!iQk3$#;a>43IT2c2|w3B zr!4);YS;*D2OH?Diocj9TEb-wW1A>ko@mgHnfn(yhQ|n>`qgdaqZxhB3V@!Y1i>vU}saK!rG@`$v&^wUc zu<0*6&ToE!Gx(9dv34)C4$+{HXAQjGsZ5&eJB~BIN(~t^zjTP7K*!ob$1gH@vCzat zg~A4l89n^7Q9Ah_?aJ_<`O;i zYn}!!w)J^&6V8O(&X7mbiZP0yYa;avV=(F(n`e)6Y3J2ij3WH|F!?}FdBc|NGjvp}zbC}tzqZ$^hXGUjJU zIjyE^<&}Wi|L4fP2mT!K?jpIx;N1iLxGQUU$1Fe(>3euvX-h?`fg7dWvv4n$t?7?O zBP|>k$$gZF0n`!J2Z)g0zvI0RW=I{zMKG)$v9@g$-eo+XM}tCB#fv>%=*BUYu-v-=qTHe;>u2DRHWi!~28s`%Uuu z{dk`1b`Lq#ryQdibNF(25}WsA`Pe%tr>9hTNr4%t z@gti0d$vbejTXge;9h3bHBsqDiTPDy8lbIFJ5W-rj=dAfM;$QaaA#>@hLg<)X+)Vf zySw5g4SpBCgfm6`e3lUC>*iaL+g)vXI$J?jD_Kua^9pHN!D--OUGaX3+=~Zlm zo2MmdVbX%{j(AnC@(Z)DA2IpXh%o!HInP+H1hfki7WDO8?PI>`fAYn?9NIT8(zxD) zU%5|Z^Dh}ia&GZ|(9GjLLe(geH_e}F#~INT`&2yvJ}>9o2hF7+#n_}g{FV+q_jIRT zHCuxdgGyzGYFLJSsPk6mqs}uTDRWU zp?BaieWqUBB?CLXuA3jy<-yE9*rDT~*_}%Xy`LiZSPUV*8>8Y_(rC;O4BhqR@-LgG z=CeMW;E!^=z>HF**8I&)#0@4Qwi?k_!TcHPAjNpL;rVNrf57y?B*4uG!{QUA{CoWm zPoSH>VO!&U_doDo+js1I@S%r)^y6K-_w0S-(VzVEvB!VC|Dm6~^yC5KQwN{^l<$#IrEq-CX(K1eTjXu> zTk;Nhm%K-QN8TqNkl&L(5I+f!Q{*)HkenfZBp;Epb%=IM+kq+`VREYmW{z1Z|lUyQQq?=qOUy&XXAy-H*iIS_N4-2a?;v!X~ znye;k$erXaA`v%POV*L~WCOXI)DREZNH&qpWDB{6e3yKW)RH=~bs)#TL>^!MUw;3_ zuT#oX1yxZEO`t<)5>2KCI+PBl={R~ll8&ZE9KRe($J1<@ODE7tSST%`Q|L`N*gccp zLM?#)DZxN;E_Kiaw47GZN_s23oi3v*=qh>#bem~e~W*c|1JLx|1SR? zpDz>$g+dWFlBNh#g`0$F!p*{TRHd21Ea4VmwqOy81*>2aN`z9uF3b_;3T47Ps2iUz zED#n7ORg;4yAAZZd8*ZZY0t{I2nP##&>Y zajWtB#(RxFF#gb3Z!C^kW42gHtTbki&56y8mBr@89I^Sa1+j&(^4OwSMQm}bGPWdk zYwWhz?Xjh?Wigz7B*nx^Y@~#g5<8hg=8`fpk2uJDvVbfkq? zRACuePK;R4{7dZf*e9`1WB)t({HAo)QZykHS~{tkYN?JUQaw$9o~B_mjb_kHI*N)o z+BAla!!^Gg43H+$d|F5+)2Z}k9EhAnXVYQ;UX{{0bRL~g7t%#^Fx{`i} zIsvt^n%+qzx|Xh|cT*4DM7PlI(mMKmilgmxH@}D9%Rjt~RbQ-f6tci0gpHwZ?VE^~MdxyNxwQW6XqQm@%=jv2n5Sv8-5jEGL#5 z%Zp8jO^i*7<;MzQg|VX8!PLP#3S-KdKJ%8@_tul#ycx4rtRnVJmFw!nC9X}byWN{bYfa6T z^);^5Yc|C_NdC3I0xMZiX%lTVci-v0OMWf8d&`oac#A3XKD4ay)B^unuIYx#ANfM#SA~jg(P$wPkrRfLgh+`D1;-d*?6gjhn8|&o8 zd%5fbT<$S$LXew8_yUnHvhY)!{7qi|<^%kUWBjZjKbr`}qF}QKrA}dvS13CmIF1Pm zf8)cS|o-fS<3Oh ze@>ja4El=VfBe6V1OG4cr(@=>o0p19N{bhuRMqGp^u&f0J|Ys!b<|}4zISEdwz9=b z?6RbY(BM!|2+FPt@}JlL4|3qv=ZTl&MuYNrUn5@YZ5F#$yK7Lw1rzi0|3_g+jQ!QX zsE8_-mY=3ms_X0Pq5Vv~x@v0Kt)@jW1rOg$Q*kU-Y|4zKs&7%Js_~Qqy4D*G!orK)2btBrLGs0>dYDXREv|W_q-5H(l9Cb;KXdD+!7WYwLk;D0ix)4xrCu!vwXu>PSU_LNtXRE1s|4%>o9@Nn zsPPE7r9rfQ&ZFKWp3)ZNJSK8msrG^7K?aqCg{tYX%Q_mOR|uHZqcGeGfP%4 znO~w;>scw(vm#oO6;rECnQC>WNv)nV*w9y!N%20Rl4$4FtY0mzC|$T@mAIuw+`PrL zX^Z&1P3|r3yYC{Jg*975m-t=RdiQGaPWPq_-*atRgO~MdjDt-RBzo50bC>A8 z8w5d7mRRkoS`S)kHi;Wtn>T~-noX{|)(~3a-n6C~mO2sRtqtzYn~@PC$zWf>+r)_z zN$S8m##$RZ>(^{qLx!;gG4i?_G1sgnByqfIupto-ym_T4*Z7$-{1fmUa_y4sNIME*<9boviHF-?0v}7M7;)P(Cz>3GyOgK-=^{S ziFlaSKXYGJKZVR8eOLpIDNtfME;|XllFe&D+U(^^T zw)~dzP_a-RvMC-3DR7cxSBS$(`H~RP-5TO_^`X@(>qBc+lJF+8M^ zR^7*WC0^iYG=zA5TZoWGobVd7Po1#cmwz-lOv=kcv;h0qne#)?z3;bJT^+?ZBgWkM zqWK|15$6Z3IPb~6Ov2B4pYEi>nNBfr$OW!9@v5m;amkxj+({_kn}|1CucB*Nabob7 zouVQUp=b`=uV(q?hdCYdJC;__@##hyCZ(z~88tM zwC;47`i@XODG$xm3HV-lsAO@8<(K|x( zb(Z2{qyvoh(TvJ31G~cnnt-UCh)ul>U230Lbg(mlKinyDy7Rh1^~YRis_sOmj-$Q0 zu(6lx)CJ+fo%NmQ6m`JB>J)o*S1#}HK8mkp+wzargal#q%*^w;$%z+* z&Q#nE5;?I~2qR7xbe<7ouh3N*;z8BPPThbn2VX(<&Bj>~gb1_eBcQOc+iOtz8oIs7 zSZnva!ew*Tw$R`^+Y3%+!_9`SaE_@q%dQG&B6$oZ0$ihzZb6=yLFv*P@t zsh7RNOdq}MP0k1YEh#Mx_ZJs;dnhtWMs9_SqQu%0?kf@F2WwzxB2Vwy}3RMJ1<0UK^QAa@e^7eDuCfU zqkSpB2i+U4FK-AtD?D@d;0vifW{-cvxrNbdL@q?c1y!8dC;Q;5+ThoANNy>2CN8am zl-&{9y>fQ<#h1#lV|7R9q7GX53J0HD$3+gM%9CFHs@TiQg73G4piT*;oLX}Huf*p8 z4pU4wzdN`-GnBk!q%SjMxb=~cF6mJi68=*puLSi-X$;M;Fo)(>f|4m|GQWyZZZ?$Q zH2;Ap_j|^jzeKsumAKy(jPjquuKY`szwHU+GtIXU8l0ZSx%5|Yf^PL?%NF6(9ifGZ z8;b26N~JaQwy`*LYejkJE$EN@&Z6?r?uXL;wPWV3T&?$;TLWSojqYV@!(wU^|1#fES)TBS*bO$(G?15wwL7X`S zGCX2Xh85Vd?25~=;u1>}A+1J))_0utKw`hLb|~q0LbgQIq|j*(OGB1!#1jxt!6bYz zo*aj@3*QVcvTs~k7~&G~oi2)Z=vm@fZD3U4c}c`~3BGrIJXTAR0tjKZpvK2*xY|c& z_V|lKO8ThGTVO@Oe=)H^_oD$V0Q_h5_-%k7g6>+Bp$_Gl=3}L)^Dhb&D_QB;lz{-_ z8~Zl+gflP9M~SmT>2~Iuj{2ud;sPk`sfGZHs|cWuOwE)-Xs^XBzOH_O>$0tuvU`>P zPNtrXJl&xX@cl$q?^rub!rRe;^F`%h@2#aFgTWR`sYb0am4=dsmWK3e%0pyaB53^? z@GyU3E$QqN1V|BgYK6KyRLH%Wv8IDp#NW%iy?UHO%6qkgOT4FpPc->n&A7*I3F*i{ z*c;qe{tNdf{)PKRa%)JL2rXeD1t=SKPkBf=tUT0)TZoG{mxoTE{$*w!3$T_rAprdr za?1k_&wsU@xuH$ALG#Bo>7M=7%P+Nb@MzsYukQM`-E$QAUAPc^Q|iBz?OlH@1uYN% zm6b3nFST6Cv%6=!%xqd#dXwwBC%??fufBWi%dB+s+L=wsN^{EW?!K3po2mV4xv1}c z>m}HP`tBhwLlPAA-5oEbw4*dMuv*&_{@Bw;f^up^`qK8JS!`?>t=^@0| z>6n!1Sewepy*ADR%+W(T6?0kYW4NZfpttet@S4!49!r=KAngsLB}?5*;FKdiOYx74 z)|sdMz;sPud*b(@AE>fF1iGtnGJ*Ig?ya&r$a8%xeR_03ME!SmuTSTrSVveDQAdd{ z?iPwo{wKF!?2&(R`~A1Lo%}{z(8{G;CMiQtC7-G3uHAgNqiS)=x$@9)V6_sPEwrc- z?R2>r?QI%*1mum?u{kJ@d_@307BxFRW*KxRzIi116iYAp)R1fGC4P8)dMvHM@GKn; z8VX}LBM?v7i_}=TG@y=H$!Lrciupa@bbZLQzCL7LzZUYEQgy1sP<A@pI;s?vL3SmR4IL4(26a}87=K7 z2cG4T$)0(=(a$Iq{4Au}r^YGBT_Kv3iI(3p2fc5(fU!arPHQvHr*x7{Gkw^O2Q4fY zws60N@xU_&=~WFwY@}FC?N(07xM^l7S-QRO2gi8Joxq^x_;F1ELqdWb5EaoSVSCg*ywy{1=7hvz~p>KXlQ<=#A+zL;l61(6a|B z_n`Lgg{kppV2n(47HINC{*0q=2Y^&Va`m=QMe>0tEzp5a7?UR5;wvM?q0<{zpyVj2 z>a6Gbaz>uT{p0J(6r2Xn5o5j@w*u#f7NIAv5bLL(@SWg2FBwDp?`1%v3CA|-7wNUXdUBQk->6yxT7LzjPGDa1^BlTw%xLAH*8P97LaWL z*e;S0l$Bv-W-!o~GyAJWFF$Dgy0&@duu@?qQeXJ(rEydH|CYCpUgNDAJgV>h!OM(G z_1&JA)%NeUvv&a;o83Jh_Pg7^=KFgAyj$zLSH6r=u+?|ZeEANHb-@*`xwF4K>2!Jc z=ltQ0l&T?UNpWr-Ve}}C8(YzoPM2IZiU53XXi5M7q*Ll|_5)vp??8=$>>a|}=XN#P z1S+yV5;awq8CE5Y4;<~(5BcCruJnU1$z3%VlOw!}_`+Xs=FTs;(xNs%nR0ovOE6`_dj|+X~$_dozahTZ)8zK$h{-<{=I5{(ka{#_}v}7d%6yH z=ydwP_nYGOr)0Z2Fk`^pEZYe*e=?m|-$q$7QZGWe3Q0+RmOf6%Ili67z20Pmdfbl? zE8_Wi{#)`=7ht(O_$|3{2R>^z;`H8;PA*CG&psbd2j84g9vV9K`rN_xQ(`vcIHE`1>mBca-zKcc;8%dN8zuJr$X7P5b`dnE$?vLH%4R?CCBkce2 zax*Y@vl25Oe9)>rN6Z-*k*3>Io8tXC^z|fp<{a*Aj4*Ai7R+oOv~s7nS;?hOyu?gR zU$m#RQuE>HrOPe7_g^BwAgdpdr5oLQKd>fWi-tQ%H2HhFD7^$~=gtMSZ&+2JmUhOb zai`uuDkr_gb{{AWUn0>Ik1onxWt0-jeWj{%7M81h zm8`1vfpr6*Lo925)Pnw2GahKS<9an$ern0mHATY_5=~2HwCJMhuCkB{2(amM=70}C z66oc=V!Tjy#tOHddeB;X?zv7*on7*72I6&*sA0G+%3m6dTXu*yKsESQ-~`p*ImgYI zRN~99h19l(+TTH0jm7!{->bel9xF$z%v8PV9`xHdJ)2o}IC`a16HP7}-TP3lHcF$z zZPRtu5O3RGs_0dR)#nTyIv)HeoN{V^Y0)|E=IRn?0|xHFl}nmvN|83o_4=BD!Z7EJ zQuVpv9Xb_wQZ(Y!8>Q*zxaoJ5fG4HDj1u}@hf4Khwpzn$Pb>V;0Nh?>@B8ZvyS`o7 ztN!W%>*Z5xM-g*!dxrh<_5}NZ_GJ6-+IQLitKDX|+Li6x^hNF5&67%QZfDZTZuKWZ zB5jb!N+yv#w>SN^Q&fu3rA2#HU0koKoAjzKkFptcuf}Ea&I7VcPSVW@DeZ?LkyGWe z^M?DphaqLXUT*rhlCLrlnn|RKN#w6_wmB}58YYobz2PrqiTvv|iDYsZm%j(C^Up#C zzakUM1B3GSv6uNV8D!xw25zNefaBEtO7DG;LrZv@S2JRq?%8H)hOXSOGOABjMG53^ zC~6HY-U&I>q!ZK{?$l1m;XBZixC3SX)g@tGZ}nZDAOQDgF0UJAV7{oZGhm&cG7 zYlv9Crf#s##A$sSYo=IFg*HoNw-GBbv{xC$s>zgW2cr(iLTjmT zZg#o?l2CPeq`eepv0seh_AzAONhSk|d8h6EDtoSdRr@1yy)gD_uI{#os2SsQN1|Uv zl+m>JpKVsjwSwUyrx!z7=U10vyn0!4F0(_>v3fD%RCVdia=m!Eqz!!`Vsn}>{}Uwh?RIXOv1Cd+!-2}E&9u{;#DEq$7jS4dK*BkF z>TB;SuMjiCKEi!HrddwmajZ}hE88N)E4uU)=B

tev}T~lY=_(ALBYo#FKzRw5H?*#;S=+=q!F9}YZOFG&VFV+6C z?j>tGS|}1J(tmm?DM%+I1+o~f891UoWxkfe7{^FxkGarK#!d~!a*h6x*L+5lKN3-S zRUPjrp08ae4UbH7hCDNxGU}SG+^NUwhS|ULj9B{>ZbKdIhhP3-XnlUJmfb&kGG^Wy z%l)H2ae<@quAJ84pehpQ{9 zQ~IfS^TvGpEl!4NGBmi?ns9obb$noi15!|$!G6tgIT#sWVLt0;x7NnT9zZ%Xq_Yv+ z#I8%J+ilebmhMObJ{t?4l4k3myteE(-f=_IM#9J6ly7RvWzWiv$uG-`6NZ&PlLaOd ztW1a5KWfJ9=I|e)BNuq>xwW+DLUXQXgdpUr%to0+V#ms&4s}fnKb+W_xC!Xn}#!2 zZ#+;J=QE>=)ek-DmLZam$wzc~f=COUT|Cv~*dqFwK$^&8xJm!O?cu$VNA-=7M?~hU zoYx2&F}6i^>Ere7Go-`H$j{Pi$-E{rTwR-_-DIsx!S!1W#{S2hqk|c4ZIi(sZBKVO zT+p_WGYq$CFZp$K8Ff!t`E$pe39e->9YWFW-lZW-(;?uZ;(>*AU!TtG422t+;T z_K53VxF2sp|2t)17Z zD@$-b*mTi-+`YWYSaQzARcV8Usu@lE+H-I@;ntR%2YsvsK=~H6x%2~RP$r|)Gl$8K zz9q>)q4Q{et1Z*uKhVTledsC`wgF8j-X3dEQ(`@P(F$C?%Jlv5VjPW2e{?9`m^?C` zu{H{KwHD+_?>BwwezTR;R1Vq!nBL|CZeUdaX`E5+xqe(UDKUa zpUHPtS^gAq4OE;H=25f3gB#jdwZT0zxm;M^Vu2Z57H&x!tB8`JYk~AS)t~9etfiAb zYtEEqezaZJI?_2lXtuAC7LQ0jv&x+|Zc39fN>cM&Yg}g6N|YRIhD_HCXSFL0x2B1n zcQ2E)C06G$X=lcAC-gD6hcxA)KTKooq~7LAb6KHxA#4HC*OBniTF}Yz{2ZS8mJ~-C z?qZVs9|lj_||fl72jL#MCrI}uDJBsk6fSb zG+<9=LWYhsRY}jcR@dgXiqO^%opI)a9!-$uY68rDEOt;5YpcP@dt#pgS29ofYx}gL zjIM9zMySPVYy`a(wvTQy|{NOyuu6HI{ojc8Srz2~fSa=}WcP0Db#NyN0z<(cy$ z(qwwo(4NKqCIM#-JKL;uTl-n59(3V*(i6blp=cL4V5%{FyIIn-qf9QQwa_v5SyFIA zFw;6RV7BEtq4jk@y1tN{P29bWQdMh?lwpAuBHRG|T}mi1;-0G@D$wJSiR zFWZq8WSG&y_|If_Fr6Wg0ZpF%Y*i-Hu6rP=EsL3G$4UOYhejrg#JJ3}&$A4g2m zJ-eegCpu8q_22{RA0p5_%rrhP4NO9sBE)^pe)#w0UQ8+96o0F4ntac;v5&Q`DRRBX7z^$3I@~i~?^Fge*2Y`BOt_h< zpdS=>uc0dwW+=?{b&=(X^?$5QVr>TNCyWj+YC7xF#A|#TRX*CG0^0L|+AJo;MQfxO z(2$3=uJJtOF$F)V-G+W@VqI?CVf4+<*Nw7&;+e3PO!z85f}`qUkVW*+deqOTQzB!z zwN*~8P6fofZFNt1lp7UQrJ!*&v;>^(jrYmC+!GDbIY^_YB@;RaDKve=dOq%BqsnyI zJ`(ot%LtokK@!f7RM!d}ZQQWBTk9xrBKHD2mT7U>pHb~W>=|Yc31>$5iA?)atmmzM z4bmXFpJ3E#h?t>?S&6oUA+(aP=5?%Xq1;&=NQIHdtgm|JY=Sw^nMu4|n(Y`f5$FJy zIOv&4$4C&TFGU>b0p>!wlrS$v+HED_1n)n(G+q%iH?=dvsh6;Rmc-%$s}*>!3&TR9 zXU^c*lgTUAY@w~HCQNx~W!G6T?zBcSGoR|5iM2PTFM4>{pv(m@4xoj$PQtShK?>+_ zG@Wd`ZYD$tn@eH{TgfUSsTmR z2PPA^Y-a?^Ax<(pUmYMj6z8==`boOwm<(9BD( z6`M3oY(!3tT#&XxzXXtV^$dx@hmyBcfLDuPz@zX6;4$QVcq1MI4f_Uk+N>;7sF}a` zrl9^C%p}LQLm85+!^DZ!)5&z$-?!1&?JY=mW|u8v_HM5+-Fe*(Z!igbPCXECG^tHq%kE}nYpj_-DZFB#iQ2zz;eQmdBmcWKC_LpD4mIQ ze(1Bp8dHScG8gMWbmB4CQ_t>>D2_cK>98v_&hmis0ck!omOtRMOXETcMXB@QI=l2U z%deZK*h-ymNqLqJ>P|Wpp!uX^vYl|!B7N>#OjmgW?@qTu4~@uH$0-n1ieYG2#lNd2 z9SvkZNisfe*=GR?%-S(HRYI%i+GHE8(jQe~TuievJeWTK>xlDv=A>a%!?4z%7Z1E1 z35@7{5*OBSLJsd&!(=$pf*FosL5vinLsf#e}&gl<~m57&5P|i#L3@l9xWU*qjeZC%d+dNnK@zw)Xp+JEY@X)`G<=Pg~lY z;4HgqKL#6WBVHpq$Sr|>Nb1l1<%~O2>ZI>#qyH`nvGfxi7uWJ!9>4 z;pI6kqaW#C=f3osyG=uLRr6@TAn`#i7s#SDl{L`uO3c03v6D{<#N}MwG8CHL5};qu zyNE&yg%6R+RL^uXa1LATe!e2>J~nRlyxqNn z@s;vsuX+3P+s)k#)p0ZrtquC1P#R`$&W;y$$Zrh_=(c6pJ_jD4WUxf2Tq1G(QLID; z%fY*um4kQlU^xuB6WN_yb5Ch1M!ta<8SbZa+ja4)<@mA`uymOp*~xV1Zre#7+|!H` z6*jDdTGA}Gi~)_^gqP7rcs8SO+MJEfHYe{gnr*IZl<;sr`yJuW!mlX*j`fendyf1& z(LWCFh4SxI|5&{9fmv9!Q|Ec+m|+tj{adPR5fOHA(4Jz8OoM%7+#Y8Bi(t=?W2euv zMOMR>Cfm|ryBD_MvTYb_kHE%i9gou|vliPTFT$>Oa+WL@3(Qg&56pI$127CXMZX&U zFcz4lFdi6OCKb0cw|-=*TN37lRekr zxz2=o$2&{h+I7EMJ0`3W3^udP=1OqefFjh0)|9oAv%Q&NUP^9avVyvVU*3rlAzFMz zJ1=4W0pKDteOV8Z`97P(Lz=@zV|ZKgU|o~@Fyw)Nwj@TUS(A0XneU`LcTPL)SaVN1 zP7CT;`SQ^0+6d&>BtklDaeOoLwnKF95NN$$tTcRxxmMwMrv^6qI0uX!C{fr=AIHhx z+0;*RF8R*_H_oePx|rF>0Qz|>9KxD_u6~|T4EwZ}r1|fetE(zu*lg|(F`&#rb}als z=TlOyWUw7{z95-hX7^eN`%^Zv3uE#a6{#Zz{B_K}kOq-yN_4yjmr5A+g#-A)AYIr) z8=wpNYzF9xnT~Z?^vkOT=`zh@y?H{d&R$;oquM=^*qVa;j19c!F$dWj!P{&O`!BZ7 zYe(7a(8Dt98r{$h99!C?2-oL}I6)y|y!#MVCtexQucebIW&L#;@>dq~LX#VCEn_NZ zS_E!O?DJYnNMQl$C)WN|V^6d3j-0195AR`G_Mkb>;b|Em>FjM?3Ts=JavUG7SMc3l zeuPfzS?GD#^E=PdRz1?nf_8G2<``%vXLAlQb^xb3Fkc$_iBG!n^;@><~itE zXZS(dqG}I|+t=^4J28X50z?Hy-({SqwdcpF62|JU%WHrC(x$Pf@#gR`p3U@!A+NaJ zn2*t*sJxcfkz8qrE1hL44cVta6RMmiYUYt2n}?X&kSkm-L%vqX`BEWY0`fIm(bi=x zdQZ+(!a%N$_6Ox$wf4tz)zUBL3OpL@??sYmRkyIV0jDQK)IYWN}+lUkG-!0J4iFhQl5X86c)g} zi^q6T5!BE@TN0mPgGP1qFZpsF8h6OO{WtpZM)dK=yVP01yZ6`^@*f@b1g{t^u|?m&1T1MoW=cOu^w4m#a!P1LN> z@<=avV2rCjn#RyQFhl%*f;k4n@hj8Ag;&OeclI(F6ukLZyYxey44WxU*iVGdM;jx;|9ih-tA?$ zfw7)n_o7uAnD-6h1_JZo%D=)5#Gc5N>v02PJ(~u?ej9FJtY^bO=zoP9$TS_?fE!3s z%>N#zawf*>W5Bx`aVj$h+`q=6q~X_qu85NKvG5Dwf4$$YuJc=SgWvw^{MOyz_waRo zwKw?HU+32dznidcrUwcO-OHnl?~Ub3bY_N|?lJi3K9bXYp6+9FWhn94m*G;*OLs#h z&~DC8AAeUB`H;n^jzPm9>PPVqp5(WjtXlRRn-1G z;tG`aACEjFiiJJxe1|X@;TH?gfk*96$-V-7-xoQ!e$~!jc2*yY=nAkWDa);Zex2V6 z4(FDKiLfZ5n=~r0cb$9d>Mp%a(}WSRVQ=+msix}zLrvFDDr>qbY&Bh{ZKu(j6vR5P z@|GS@n5(-=gbt}BEDBFJlYk5Omh*eC6GX%;nu*AT5S<_FO-UsS0#R z3eyu(6=KKZvNc+)8jDzwV0u?E?ugq=12$Y;2Itv2hAoWqzj(U3b{g38gk*539La7d z43f)#hjO6&`&s$p-Y!hUDsE*lesV)3=lJMgU4`DrR^T1-{w)@C-NX#q3Jk7F*KU{5ecDx3yVsg@O6X|h z_FyGn51f-1v93`b-eu7{iKutQ#9hw6wG;E#;TCWB*WoZ)#%w3S^(o{58owPD(6`K% zP|axAfV#`p>~Twk@b3M<8Yt$uT!o*9!HTb+7cswq;b3^TzU2w2!F{r;m}n&~OX=gW zOQ_{)V6@KVkSVN`ZCZ|AEx%2ixim)m@{l zW@)4_2dYlqeXaU?)G?pOTUo$6kX{h|-yqVg9t z(eWyrWD(qVuA5?8Q!Tp&1ozX@XNo24&RRur*jtfWTO1aO3Gnuwb{n06TADpI5Rmpa zr(l%1x-UPtaKocgfi&5j+qwqyP}KK}CE8$a37v5`dbx|)+PXCSDjV~i>}o?QXA!cb!x{93jAo;yg*gA4$#Do#22{!Tc7wsOc7aRo6-7KnN$< zXL6mWr8$a#7PM^R9(8NoYhAXmfRby&`u^;I!%cE$`n9#xi1X{0c=ytEoNak^Q7~bE zcC$3rO&i)Cw5JjQZ?`mU{P_-gy3}4IwiNjg|CWJ>=g2QQURYuH-3G| z2Cciwr3JQ;U}JrdbpuYYplu2tb$~na7l|^k&22z?DV%3Dp9T>|f}|N(NY9*jxOW+C zMCaS)wr=2VHpp$#t(A}Ym{i8Y@$P-@vuJaO4lNC2$+3Y$?OEhbv#@&dnEL|W*!s`5 zLj*cuj{${=&!;BT2OhNZpglhgZX}=Vvu((bIj9VfOYbjQ>S73!UbHZ5CWes!>S!I# z3=-3Qk(7e_BB@5R-Bp`aw9}e$iW(aum-QBmvl}Db;=xF-*cj>2w?(cJAVemktx2YZ zU$mR;#1xN_e2N$?2s7V&FtXU(7+GLwjFcPNB1`zT$WlC=23q)KJ8Kob!cH=D*5jA0 zvK0Yq1sIXdVjWX$lOi@^F@Ns1Lg7sWOVylFL8ZNH4G2_*wJcH9F4% z&rav>Jc_3Gy~sS7eDrtChIo8Vk6UC}!cdJmG z>L|l4Wg1~uLnpKPD2Kkl)ulBgO9?oACF8u6vz0m^%3TF+p_u&%D~kuNGVGlm|FN!P zxa?9c@ASUfKOX0Ee_@A=Y1x@nn?DVD`KS5s=-nAz21Jrr&kOy>RSLU!=KCAy*q=E+ zseK-^!3_7g$h}1;x>B%D_ip5&q8A;aeT1|O=CL`fzt9BUKw8ScBa!3+MJ|WaJPeQO zc@>9LIHZ!RQk{8Hj-wvCA923F;b%@DU1-ZgOVz?nn$9fE>+Mv$hqrXT>}7E`_8+is zg9c?#sbMLT@KfFl&`F?$*z5*+Lp0sJYMs#WAkK~^T;AjUJKZDwy?KajsO1Y)<{8#= zXgZg#6YVD4wOL+$7RYnU>_2nXW1nq>Oz{htfwo?wSQwyqW`DMdKf^++K{GB*%I|u- zuN!!`;QhIQFf3o$$^~bB8W~-{V+2J_T(9Pm*}ZHX>q(YZe-xQq@KGe+cq-$g$e4nC zxY=O<-aW5l>6eF|(Cv5cZ>}!QK8J7>2v_hktNE1SFv1#Fjd;|WYxG)GIEhz8`O@EZ*=!hzTwZlgieH&K3X&&WdcQ)Axn%Il3+~@`X@}1!dBK%} zdsoLWhhckA%5%m=aU$k}D;?5|k`Ct!?$ISLyFQhuxDT|jZ(I^4pE0}1*yR%B zNajX1B=f#rGms=)wF25!<*B9an6bf`wt*HlIJ?`;ZaSW=?cIfO+&0u(Mm5K5!E{^Ow6O$oU)r&P}r)7Dk?7lJAUuim)GpGDnmLrXIoWJevt0 z^lHpPkiup$AM~U^>CUq>2bcr%d6X)!Z_CgcSHO;Yvpq6CbIiR zqB%1}c3%;94}0bE-K0tYr&meqRKgjB?7v_3r{XH7LdIcXeAHvS`^6N&&S>Y&tj}Ss zuexOy-n$VQ;rx(G0x(pjW^f4SUfZ_n{?b zXe}P}z9f4NP8dRWMD9%ie`K1`FW30wbH{5>Wzg(na1r31m7Gv=40Tqte~9-z&FnPQ zXh43>tZ0dLeZ@zI-S(Z02vUq&d3AXNdy~SCr2Je==h)B`&sT&#Rjun)68hFzxqp1+{yi}iegaM|{gk%DR5_+rZbfpU(^UA)xQ7#|2obEfem zN@R%LVCPKUNV1U_85YP@oWhv~Ds^xtMiX4R;KJzs+T{-eF2o3xv%up)?1BV@{1cGQ zm~QuYcw$t1!}k^0cZlq}EAsx71kbL>2U8sQ{lnN@k>5`N2A$dA-4zMI=9g^`!gdmW9G8M-K&e!-_G%3(X3A{Uh(6zW~ymDj~@* zoTa!zN(gcDVKpMmNK7iK!s69_da zgPchS@+K}Qm`G58S&!0SzJ39%17wN*q1V2uJIhiYf_~*>Bn@pMYe)A>*=SAJ zn4a};evDSxO6pRan>mTLehHqe&6p;)?t-1q9b(r766!GOJIiVvt7#qEak3F{H_2n< zmj_1G3u||7rxTeho^ICr$DigWE@C_}ayeOkK4)%V-u8X1-%%#}8K%{3y+as{@XLVT zbodbdlQ#+T1v+G&-j97B zo<@1PJ2I*u0qf%=$gnL$yRwY&`l~)=5Wf80$ajnWfz#?0pxtwHCGwo#;%_46i_Ns? zt+b&Lx{^$Y1gbMv5Q8_t!*NwvH^HS82jelgD;m{-e9*W?VBCjTWUcGiw^D1vGB zk!8x@yzQBe6m5nxKbTRLhPg53i+wrp!>PVLZp^sgyjpEex<4T&)33}K4eqCCO_;5} zw_RU0H7CnA)uag;W&4ma4eS~d4H|)wfRut7U`NJ!7WWCkowZ6wh7fDUQdj z!UeDFr!Hapg^%Op>oI8zN+?CrIrdyplNA|hSqc6WX;)pNRdrGASdqbZwDC9tPxOdE zQA)&j^9ezHt~DGx3-b|-24{dSzoC4W05j^-BZRR2EfGkMyX-1(`_)*YW3qIQRJirA zQo&j3Qy6>V;Mb7iD}q&4aD^N+H1cRCkO-=wh$^)`2-w7KPv87cDw z`)#%#S?O+tJMrS%?&FuY8267@Zo>-sMn&OHYvRR(GWt9h9@0CvmF|B^Vq7wmtd;gz z`BUqhGzcjVQn^(Dzkc-TH23>N-6oxmJc2cdNAx&j(8O#{kU^dt4tCNTCoNHe#5dlaL|A&fdmDVYxtgNW8B1-RIdM0VjeRxrVT>yY z7t%`_r3W#p;yX3mHk|0o*z{F<1Ln?+QbI{1o@{)=aFD6}prk2y+^RX{z{!K+h+<~K z*5ZgJk4EUs&UVd=gHE>2z;@mJ{lAhLaO+cNUlP$wsFt)&hZDD*XC`bi+Ap>LN@DSC z&V;R;lixJ$sMg*f>02~6v#(t4$2SI25`b%m^G5wS(Eh;s@o5&|as4Jv&6EAVkZcks zIh_1ftutX0VimFPtD)y)cfWw0)C?csA8^uuwI1rDOcqg73MwN;@RIl*d0SAAM%eH7 z@4BMSR{&Lx{z?@F$b`J_%*sR|ugJ6X&cqbc7#cMZDQjnlr)3y!GRAsV^%r2I%y!0? z_9r+v`xDkA|6|r6ewN}RSJZlWg*;%itHV37QpNVOG0KEtV@*cSXy6>jdZx=1P`d*C zA*10p;B!`!4(+kosRgI_pwJ|uREU|~3=}Y~F30y{J)>AWAX6!F;_;s9=k3#)(xhcl zw8z>v74eI3UN*5QAMH*);#rQ?%kjAD;_>+21BiD>jz>&G9MPV$5uF3~;OPqKaHo;0 zv{n`?pXabjS{X^x-I%HpsbVjlOtUS8Trysr?&G&&Jr^sf0O*kOtj0d8`Y7X^2S~T< z4k*s`_i=+96%Q>LT}XmYomh^%cnceXft<=CD>e zC7GORNuTdID%w4AS?|a9c+7ZJ7@KIoK_#%DcdH)j&8H(8%Oh2MTLIAv=wz&KU+oLLp}e5D2*({i)=jDn}92<|O!q(`h+s ze^!ptuL`o;S#kONy^r8l0BdC%akC&}QzPV()u9GRs=~}9bKxEIZrBV!UQ?zlXKTY{Z=1_iZs* z$Q!@*9mHVRnC#5C5Wetc;wx>^@BxZgiVLqQpBL?l$LSs+{C5}mX_ z(rnFiu5zYt(#+^=m&|H#_Aq#T7!m}|7ofHoshs*Czu5`!Hi_MdSKEhls_5y+7_Tb) z=oMD8*hnneb5GRY`p1acn{QWlYWTy>o57FQuD%l?gs;oCv;D&D5p}+ZkZ(j^m3Xr~ zqR}bQs^M;y(Sop3`d^V0b|5Iqae-|be(b8~9E@w;)GPrDb-Dr4uI}U5ia|rXExY;Z zQxb)bi1`)ck}4cI!um$RJ{*#ma}{);Tz@Gk!=9^INUuPqC3n+PSP$XwwS!I;FI=n& zUpx{|QGfLp5|K1FE5kPpw3Dp0=C8HZteuXxuF+_=ogn3p`o66_{kC$i!hAs)-T^t8 z1Bqm^MJA%>;L$rc=|wU@`LT#wxVf@iD8rk7r!1o`B9t4*UcBXKmT?79=4*0Wg#5sLW^v2X*|Cg!1b}e;}+&kVL zeFkNpEj=TruM8iK71%4#_c$S{b0#tIn{uUn8xKkbU}aV)6V6mdG&5J!?NcfJ z+487{!#Wq*GSqcOH`5Qt=KissY*5b9E(F~y&j-Q#f1k$RBj^tY(qQeaI{E_mX1GG< z>zeS@`9%Y5CWn$p#0;TGdcv7{xVmn?YN)>ev@BI6pJDCqyOANX-_uRipi?FLt-va8 z7Dl*y_}K_>^Cb3`a)l3uP?FY&+42I)Q8VKO(2qTyd%3Wh!+kqq!fk|oZmn}~WGwpM zNDCWz)P&WF4H?QO8&JZ-?Aax=o9=&TLaW0450}FIf(yu^SW&`CkC}$wkI|`$fZ6>N zdbizJFJ6vPmB)`b#l-6FaQnxR$==*1HecG)`>Fd_2Ehnk(eai7-{79XJ-K237hUfH z-$a@9kIy8NOVe9Qp_Eb}X_4{S2AT<(cPl zp7Wf`_nfCxwUey+ocDDpvxzL+G2U)B(=>uK%Y!%4)X%Zv+wvHHmOF0GDJi|-pzEr8 zB7Zoo+O=KEHm$=xql;^D7CV<5dfJ59XH*}0Vmgm#1#y*p=;^sUA>R%?VXLlM!cP6q zdTMB%V=vOjA=il=>GLl(;DB$4J&?o4?PbONK=Ltfwh9=h zhYvxQO!L7iZGNy?D{2O8Zk6yN$W5{_QISf#AQ$pF z`0awn2%pj@B=bZ2+1z-3F0=y3WVygSZS@H`coO^nLE0hw3329=LTvUTXiKc9H4I4^ zX`WrdSKfO+lhr6qt-KrK!C)4~N~A$gwU_xBvsyeN&GvsTv$EGjy;~Sjid90qf}M!f;y+-sn_TG` z^K-|~XQ#okx3Ti1w9zySXIpT##bm@;6V94Uu~bT>9-J3i6>70SVzO92WWC8&MKWN; zgTW{-+|&=wA`o}gihl~W3i|e#0>&SeF&T!Om+O#H~R7z$t zurgqlmk;vKR69Lgcx(l5Bg1&6nQbOXczl00U(K_J5S!Ys<^Am~0<*iNFGll6XC-)f zCC0GA2`zg@RQgR@SqVx=8>9qw_YaitG2*kyYN4*vVE0Tl@DRub>uy7ihe2$$3Gy)M zVhc_P4g6VYQd1niu5CC!mp?CYKp$zv`C*c1*Fr)?bhmSq_q=3kxmjJw2LlOVjpakE zk00X6%~%_6RPQM(xcIpEbP3ZuzG5yAQSE}ZFIN>~QHwc|HfNTf5ia6cCSzPhFwhzr z2T4-}Ns~JWS(B@BRLzb`n)*AHwI7=4R>-)|;p=-GCwz=)I(qlBAY(lSkDb*|(!q`D z=N(4`O;>U$V`e8o8pyxZGea=+e!%`lSeW{7Wzov}oyp5lV>?@L8vhnSqcohGKG;ty zFkjT?=0c7E+Bj0lE3@@k0kSN~v`+ko2t(~z}VjC4^N6a~E7Ydv}a?i$mvqnYG+pbuV{w)qR!{ zwNvZY%u6eFh$B^wYpau3Cu=f7{=|U|`&KbgdA2Iu;KlCk8KkRtvG=kSUX*S4>UBiZ zeyGuZ+$4>+lg{6S$WOMY0sq#{iLKLOmHr)`{5SIU=}{;6O;IC!`<@dwHY78)q3}o- zTL@oHo{4{yWR$9fHP@~_@pA9gCtknB%(^J3FCG{4<P6KpIbU^M9&-FfJhJ4i z$uE)2NU3+#fcN-S(j8D?!s| zS8<@s%L89J7rT3f5-9_}9_7hc<;hs(Nw-_mH%WQ&^nd_QShah%Q02y2XLPzt(yLrF zyTaHQUfT&vDe*P^|Pw4rT!Qj(6nYxzJANyj8}OVEYOI!U$xwx4fwF@5Rm zpryMr8Q1n9u7PAsBcA)Fllp|>U&t#%`32>IsU4@>y7Ch)>ZK}Kbzru{#gq1ch-8`F zMXLeRIlKXTsC1~Fe_366?Zmw!N@ibMlN2p+UMES@$$Xi6jXRFt;mE(NLT@&doe|iX z_efbz=n*WJJdRXkBQCkhhF^Ng@kVDH-^!{% z&tq?{dH{J`W{fU*_eP5Lk+N4hPxk7#lf7{qf9>Rb4k@cx>xZnqje`e*Es_I=(HfGW zlRNHBj{`=7*)~S;P5en|CDnEIwY3wGJZE)RA~-S&($)NaJ;qi7{Nf&p9D4*PL7oCS!$z*@kT5YzDt# zwguPB{6RtIKlhc&LQxZm;9M#tCZjWw0x9|++Sz5ft03uwF~ zk=ZfMnAZ`lSh3H4f0Z-kv$0R_<1r0Bba6ePI>+@U1T9xqQrYwLSd26%nl4!!`stki~&B&JCYSi;P6pikv0{Cr{JEjE|OrM3Jo zT0mOAxR%B;)<*Lqg&zib*bF-kXu$;gih3x#$|dek`dBS;JrzJk99!ZVX=ZkwiH9uY zhcyQ+Aeveb!MrljOkk%|wi!CZ=nWhan4Km*oi?Nl9Do#kdt9Fxv~|#2jz0Sw>=jf} z&W}op+HB@`7Q&NBdeX^=1*=}7FT-8s-s6DW=rh7fvIDClFxVGq?E(H?Rx7Iy_Q#f6 zVC#vk(<8Fq;I69gb*57e?0(CR@;9{67p}_|&=;3epwO3EtS6#q4suNe=qC6)4{dpY$7WnR@qU|nXDMWcDY=!FTlHovj%043qqU!hlw_J-KHK!@H&E8j3a z0s1BEXSPgV5}x}cv=0`LY+j)X%)PB|(bd^9`~he$Y$N7YA>RMt$|PO~*+M_gFis9E zmiMj19JVt})0DaNSJ;PsDB;yN0}9_IEqRne6R%-b>oM%YvkRh@7Ps3RGmrzDM+M&l< z6s3ozh$=d}@~z;@L&1~M25`p>?D+uA28*i@v>2tY?I>3bG=;&Y2RazXU>T3047DHh zMsrOm$B1&i3t4#=%86IXsX{r%j?IW~+Ps|l?Hp*;v|5jz(pmJD?&UGyYf=0AP(C3$ z9W`gg;mUtQMk@d5i)Ym0Q_{P5LRrN(Bu~(JhfUC6w$r?RWRPPqdKw=&@XN?*{_QgGz0361 zVZ>i#^PHcadk6-2Mq>l1Twatw)#%3|`Xv3eEq?VzFuf@unWD^$4B zze3M}zfpb^;%|Q)h-ONe8Km``);glAXM@zHg4&7h74AZQnXABsRVIihK_jt2wLhO% zL0h!TdTQ@#YOD4S8ni4O^zfKM4-Y8+S%3M938(2e$3sV2t7P&_W%i%1+5*n6^5}Ei?20+ z;wEYM`^)a=3PIw@qTXRfS|JUk+r8X*&YIvIZcX)$^^dY$DW5clhW%qaO<9GDvY^QE)oPw)&Yki>BiIBg=zepNh>kql%AFYgUH%?~!mieTs zh)^ut1)j1WV;(xYE$f#T3eFOCK&HB7SPkNm_KG7HOi+ijg(^VQu$-=f~SR!yCP8g^ZgGPyXlkSg*E%_2Zib z7T7T%J7edBTV8ctmF>E(R7rsV~75t+RgOMIiw0e?=NQ*ze{~5{Ic2Qz#i&i3s=5)#&B~oc%AJMUpM88$(lcwGKC8P2Hqar0 zPhhvofs6>dTg`s}8aI)I$!H7Ht+PPo@C7GMx?|EEiK9&!nPaUvcjV^Zkv`sj#~n#Y zcieHu2!^p({CfVK8ykj<;4P!%z|csRfA(CbGsCa3r1-U#p?;lZh+l6p`eQ5!euE{> zA8RrA<1BhVXVLoOfk91x#X1ov8rE`MD40u@th3U~c4I*mAwNtlY zcQJZ*40_QH%iYihjd)BtGU%5%BItPXhapP3nPf&LvsYN;dETM#dJr}TJ2<-fkVgCs zc;5A%xv&*u?mWwMj==n=7^~6uV~%|L9;Y9`FN9rvnq7Blc-|cq}OItu6-KO1v>TiiRaY9 zXyHix^N##3ZEvG$hF;*Lefzj_(mIP}wemYdCTzrdy!U4uT(;Cf z(vjY)%}($oln>9~#8<;)2j}3mJu9`?lbs_Ko4DS;23`huE$06m>pweVlJiMt!Sa|X zZ;`L2^ORB#HE74uKH^uYqgZn=Fjaa-cxl-gX_tLe&5riE?MBRnMx50)8n zgA8j#=Vg39fad|W;?=^!(JH5*{L!4-}UV8%hR*HdUdO- zRT#T?(Z~^{t)7>h1?_u;yGLF{md!oRkyx)R?#=BF30K|aBa@KrafCp>Bb>XRejhx4 zH?HD2*Iwc4s4ccL{k>)BQpb>anraUALDgj~MnaBk5Z-ksRJ=7(9nvPd8BM`f$9_=s zZb&T6j`P@aPJ3BbE(e~2Ca1-30Q!8?()oMrAQQzi=}QtB#5%#}vPMw5ZK%;+%+f-v zOH$7Xw;nMiaTWKLum#PbzP=Hqs%pc;`_jhc#$MLl+3L{4-nhTh%x`t5yP|f?#hpfs z1I;%oA8T+4@7W8FA~Sx1w@J#jR~^x~H-LwErSvB4wl!{K!q$H}^6wMg?^VaJTSx3r zT^fpZZKf=h{ObiCCn3zU?T4Nwi=PS}!8Qe@pKb3(rqvi#Nolnc*+-tHEIfyv7^&Ds zB-j|Ob`75_Y7@2Yc<)|Bd7N-#?acp28d)nk&I}-`z*%*$4#ruQvv({3kH6N#*ff`8CIOc%vFU74pl9s0FMh4< zeOH@bdeF(*2mPpXNa`5Q-*BJk)f;v}6C&wdZz~1rg;2lm`%{6CvO;z^)c_xm{Sq`) z{1zW}9}&)`{oSU%Wap_Tv~q#_ykJB=NKTadZ@BHQdrQ^8ap=~(UQmMGS^EUIse+_tVIZ_879WkX%RKJ?uU!#WfrecEJXF zChZp$3rjXR(s>oWj@+Sff)m_q^46un^hXv&F?2BRBos2nY`Hh}k z(tOj9qlUhim{dQ|9!-SEJJB11Z5dZP66xuQc$$0NnT}YGq0alA=__LjhAxNq9$x!z zdJ5c^gmk5S&-QctBo{1UP2<)ew{Q#UWCwQ2MCDy|u^APm`<|$B9&!G-#V3PkF=G^2 z=3#iBId~>oh22jlAxl!c_o6!)UL@-G(XjEgKFyg+Ap5jFLHAl-lsk47$vu+YQqNB4$7HVrl`^de#AGb1+;)5a95u`9&|iK{G;48^-a5vOrZ_?NH0pl{QhsfT<} z+i_|O2hHNu!|&yd=1(=oTsWPl^2KBJrVjY?R2OL8tHUWrTeq+Ut&L3d3+B> zl&eLpjon+=qVC4pW67A;n1gflFU+YaTf*_9d9P$_!8~kg16D^4c)}WfSNm1BiBBno zbypODmCXjXhZSJpB%Z|FYkC<^(pSC>Ke9y0$+>|6UaxV>wzl;`(l%qWqXwwXNsW!_ zt;qkk4SxTFspT48w>@UNVSC*6`0a_?x$WBR2>92bj z?RHjtPLA7SQ2ri*{Q;ZgMCHl&-SpS*5n z_NAGbhI+RO`{$Tk(lK3!>JX?a-ax2f^w(E|c^BzAvdb&iIb6Ryczr6Y)f}IClx^b7 z?0y5*Vf+@b`+<{emIEKi>~5?}3`K67#2ZnoAAOstAuMBE4Qb>)`8muFIy;WD`O4Xw zIJ-+Z`-?oo69!MC`+vtO_!2|C{DSgUQ=kI`2L%Sjq+4b=|PCEg#Zv?gi| zGj?oh(>2HK)imjw1t4JJ_?TwxHjVfzN#HdHhkzD7g=DKaAP170OPR>WBP`Pm#`TLNaBx@5B2bq)Ep*KUX6HT&Z)G24g-zpq%d~?=-i2Ci)B;#6SWL(h#$y zxf-iZI=RJMRjI4A>ZGf2af5Vcaf37;$6dvZu9H>VlF}um$ns@8X7JQ@Y(u{?miJLd zR{VWxSfN<}1+$ibqX!p&#D$FqR_@V^^a)4l&&7(xt)rC8^aF%VO)}c!O=0*Kl5En}+pV3(G*^F}=+W+k7m};%sT&g0m@z z@3Gp(;_q%DsbB&;Z07a~;K9hFabCV6WaF=0Iy{4(_R1D_YQZS~W+83mJzC8r103{dWXoV7B9{bhivTH^V*zWAS(>=6(d)%*{?@*NKDTC z@EOslrRI?%P)%r2;dboS!)8Il6*4Cc3^27Fc6G2NWc|n}j_~ zSh0Fw!r)WO5y?Z>Iq^#=OF2`E^CKpI>b00ev(Hj*uqFGtA(eA|h3w;^N=0L{8nQF6 zw_&oTOtG^VRay;&VC=P+xI3>I;u?`Db}Y}%+5jYh3OtbU>I13_ zvNdqx{R513j`y}a;_xvU&q-68c1qbT>w%}+AWbzL5!jWSP$rC6PV&eL(oo|OLH+zg zPjD}skYb8o7fwj=m0aHtU}v{<9x3D})XnLca5Pd_vDr+L_A+hCz ziA1XuRJoxOnrN~Q5f=jH1on^?hWc-zT5qxBdP1E07)M4Bs358$~^poj#K7n z1fEznhMjVa>`VHw?m7GeW#i85gePqzq*q$MM}wlYkc%nureLML{XwnqT!F9%kv0jw zSj3DaoFgRYUc}uHU45dIhdAqTqtPufI^nGLB5Oa&kMTZJpa zi6z9DUsO1AY&dFni0vYa!wC0}xpa7dog((^WsC){;XP*Ti6vyANPunYUA3h&?YBx> zff&8r*3a?$H^|I|_@siJ{%+3~=zsO2-BsMu+qF+Q(ki^@h&@xVa?xNb|1jA9?+wJ@ zTRULar`+9^YAU6+V1?gOeHEJT33XcOPRETijD_q${XMMZSN_(T6H6@Bmi9$x3HF}F zE&wiA^nU2e7Y8sp)igT$enjKZ(YgKAEvPZpyRof!F1D*1R=O$5%5i(0dRplL-1pFZ z3+|6q?%!^4&EWm3o}G@kuDFclC9Uq=5B_-VS%fFP?P>LxJ(P=gL}`_0=tNjYs@dKW z^_A-6QbIAakfNfi7*X*LGmMG+G?h#om<10jahPCOmyS4vaj+PVOPLb+B06i-Jto{I z&l(#Ee-WKg{a+Bqw7X_xJ8|;|BKDRfF(%KrQwatDMNtSk#`1U27h$ zA1bP`Bf9x$8c+FxzVpTSOGQ2R@UnF1)f}`?HR3<}&=Nwv#q+1ybKSl5G&9w6{*LTj zh@i6Hi?70(0UotP`L1O-wg2953gq}#-Jb(Br*IcRWnso?;31f7|8o`BSFEM}C9F;` z)aC%@O!u9)WeL|eL(h!0LNBH}--L?Gv_PGF=XEZ5V+4&HN?LGASl32W41Xb_vw%u9Y-^*L#maW7*7X2!O(cgdlpy-Phye@wf@p&e4L{UOW|cl8hR zYcjm~6sb@D?g=rLb@-0e&0guP$%P$@u2zSwZf2we{{h{rah()a)SKLUb;tV{y&CH{ z(aaEF8*=TxMARQn0+BxmQZJpQrNXkx^bz`OV#IVm;THHa&i%wRP$ zX%q?UxDbojU6Qd>=abOx^uIMplZ*@NNzNj9i)5|ZIrHjIAO{Vnnzt6}*|eKzCKO-sy6YmZgbFVu}jtoam^Dn|_)=VTLh zz&me&rHNMOie*umK3-V`_v&IGk6bv4TKq`bu0S26j-8O1(qS)J0em>3_+EHVz}^;e z$%we4y1p44Bt+BbWh9+1T$Uj??zUj26T-EkUI$BOYGNFJN+|Tv-bT%+ZNbMzc!17H zub9;0IN5pRv6??2vyy^^K;NbY+Z>WtSfc5h0j+Z%FjmQYuqOk1_tMY+t_cxN)yxd5+r@Lcm3ei)BWs}>yQ+0OOnJtc;x4UPw8W#__N_# z%H5NYsEJ16VecO9Rb|Kc$ky|jd=-cZe6KROw8{l*5iH14?67Tw?fl~+VR{Lr=mVls zQgmUIP@BMyKy)WP$NBNEl0$fJFdA(^xhQBAR-LE%*P?|ce5D;0jmJe3OBk={mHo16 z0_n|EhkelRlseR!_z|VxQNi(8fmq})CY14Gep0c{f(rZz1xrB=X1eUL%DF7tOP&axpf*N z>Ml`<$0E0S)Oq?#QB=*&es;3uF~)Ywr$)TUWV;6Yr%A_1Ha`LVXsXEoB*(T+Slxi- zZF%c>zbqpT`E)Xnh}_we4{t$!%XjVzV1+_70Q6HfQ(pm}Qg0(-VYzg*ctCR0H!fo* zIYg6cc&=mFx4yz-PrS|Pk*^%MX*Do<`b+WU#h#?n^13^9cXq~>V@EUpJD;!kj-6uJH1L9|A*KC7-!Z=aA ze;7XlmKUGQ>~wmDz~5Pg8TfZu%YW4V_|0cm^rot8kHF#)a~=oWGLb31n1dMMrH{Nz5ec@iEztdyaJenl(SdAY^&pPskWI*g^* z7Bo4TEVD2(I|;~EvRVH0bI;>BcJj5JcE`}pFJU)P>;bU6oP_t!%uf~@LrqvkNp5PD z_j^>r-J@A&M!Q3}JAJm(sC?B=U9V)C`(`1Dv(6)x3Y*ks%U`2hs@zw<2 zen*`5r`wc|HdP7O3$CEqQRP%$h9|t7aHWL`jiwwY{j}6W(Vr^udW50?DMo*vlVW>K zd^EPVz(Y}SF+haWhbSU^@ln>y);em})V@>8!gCt+w@}ZnLkU*I5Viu-LNSl=JSz}# zGWNgpcz6HpHo(4w=QhY@!H}KpjlEQnp6|=4$SFrWSY9gpb_;GkyBv~ZBtARM`}6Ef z1 zZ~qkSY{T2H_gwWnF0$$r;U3}Q$fN0ylS);+B`P`Kl94YNv^W9%$m76>mtedzC}uE` zU+Byd^76{O!!N~wU&Q9+cg5t{y|zp4bVj^uEz@nv%l4`+#ph*sgI6>17%^-0IQ*Nj z`o`56_F{ATat&C`~{ju8t8Te=yoCK_94)%%HIO-^XUFOP*bs}Tl>>*C-g7E{dA?@ z`AD}1dzFp;xpU~nD4H@xroP*`tB2DWFJ) z84=ZJ4keII@MYxFE7-G1d~Xf1Yn6Y1I{nmWd??LSYWez_pT7U5gf?6sF|76KPv1W@ z`2P0)^8Q}s{gK1g{+IVR55E7ze|i5YyuaY)Gf!6im-jt`@89=d-e07=|NAFP{>%Fn z(sZT$lm5&5MN0ig4YPn2viV$p(dGE;4DZ9)V|};BoyjTmMn^uSZt?iBPDcE;VdkZb z@r?L&gZ+{LzpESK$N$#5BE48V&|rpzo#@SweZg0Nxftb8Un`hwbNHwFm=pVDlk;lN zy!5X@D`U%P-hK{>9idU+Rk;`-0yvcCSBv>~4R|*ysH0PO=Y?*8Nko%!zNvF%|3q zb?KtI+3YQx`qYWq(zCu_!D0#2 zc-S!ZvG3{7_B|!jeBs3PXr)EiGcT?5o;ss$)vfB+3^wp$;PmNTOIZAVrZG8R4EDIO z?z5iXSBx%QUbmYcBB~NqUS@0?pN6kd+{ea>EI)hD0e^Li$AFy#wNuoB{SLyBto{Dm z)C#I4690QG@QSHb_tb6Gb$^WfQ{qe+Ih4i^yZk@M9LOGUpcb72y0MI3KlZ1`DGM!# zYJ4*W41@WnrVjk{vx%7BCTH`PS_WlLQ~^Ky*+3y?nt9m2QG1fp(*Dbv*CQt9eV`op z!3HYZP5j+heeN45zCL^y;WZcB-16i{{_=Si*fkf`?a>wYz1NTh>5WS43;lFm-jCSx zXx*DNUyEZTN|H0bh^Ly~DaXjQ28F=!c<#>O{Lthvw7LK^5ZZxQYO`HPVnbxr< zQ7^<>k5)VX2HE1?^b+uB?Axu#Yp;P;-@|d}pPc>|`1Rv(;poQk1rAP}j@sKxOX~LO zKE?WGLY=kn{KaFm)b(21FyFfR7uq$q8lD{TJ!RiUDUqziiD`HrUW=R0J_&r~&88=< z(TG*Vms5nncr#jPB)vvH~|u(DZ}dAgE(Zu%@%f)K(<-yR97E?oNDkgeMSw_XHqAAxb92j)PaO) zq1|%&QlV4aJ77{`6PP|LOYwvi1E$3!GwVCp@^E12fCTv!YwsM=fW`?-y>WyTKQ1{2Ox^>$l!+#F@X}tI>Q; zi17`imuR0K1}R3Bu^szm?tsLhz4%9m{$gCY4j%b%;9RJNQRTu)pGh7PXZm66UDD)$ zc5ngmimVQ4u2%uI*CtPbq%a0Kc?uCL4~vs#ol_-FgLI}=ux%D(DbiUD7Z^*THM*}6 zYcJMIJ^I4pYbTJ;;5c$pTd*&qj?p82c2{xj9JUZrvQ>3KpU)VAJ*sm3!$#!A0yY`n zKwr$h{FU~Rq38##wM4m zQkd_1b$4~z3yVb)^E05|i5H{Z3pTW|TOTXe0xL9GZ0?7p(Bwnpo2PuTxCJwb5f3+L zcIE?(_sE^eyfd{Jd(1K->}H~@X+g&2>%P2fwJ#Z?&H~YF%hn_F?;*@hdrq;qtzjYf zz`s-v;(SYkx=&^B@l>M<{)65a%?OG8P~RJ;y04BCjU3QLs#lQLY(WL$Gmd{3utzTA zm*bs~X=xwz?*ea!e`xpP1DAUK-Zwt+7rqaGPH)DOC{cydxFvOjG5Ab7>>QIZW3ViP zQWnLfJ5g3W%G#@xbs1N_3zQFB?ukFjf3CFymVW={MUSDBmTd$=wySLIU` zuvwhnmOHc)xT69lE4{9?bV=RI$oTs_cG0M!@B0baukTHW*)6e6Be2$RUIX@N=03B} z_;-({eTgHZRMSkTYGB3tn6hksyx1cn;wbN=k9tIn9@iY0B2EZt_P&QqO-CHFZWg_! z*=3lgt|LyJh8z&AUDI@{huu56bnQrr^S_Pnb%6fLaL{-%jJ=p-Vl86RDDIj(MJ7JW zJW2e&0YY}I=Fg@v)*5e`f(=q(UZxD3M9)#ABdnDX)ZVltC*K=)J}YOQw<_l@Uy-0a zz)GnzXN?Cpi_YstnBC-D0g+iK{@CSYuI5VKJ%p7HMx}28f6ZjPWsPgH8 zfH#H?%owG@m&wDGhJ4;J=&9jK7QW;N_1ZA-qkr`4`&9avJ{7mICrN1;i@$Ht>fc}u#h7seDHVyc(u8A< z4D2N_a^+(54f>1Iohby~iZV3?0;*tcsnO50uN!#`d245)m!sFe>(|b!8j-YdTb=9P zJ++t8v6Ii>_eg&_fc5NYv~fL-6TnrBtZAr5?zqx|{v>0wJI=&}SbOc9P0J~ZKE6`vVFP2SSgv-*I$7+nt?y97B1(H8`>-EUG~1Tcp@y!)dp0{yJK=>dV5?Rm zZhEye0mt~t4_)e-;mBp|sM)+YR>1BBuK30C7eBKu-i3YEG7yJtvcs>T5=;6C^X`OJ zoQ51w|A}bJ#v1S@*7RwJ|Bc$S4j~FGP_m1kk2q8<5B~@B{Cu;(JvY^>n=^eVQw z*b^fd5f$!5{-$w4Hd~ik;F*KDdK}rIn$b%23JWyp5v7K`70};VAp8{{I@aNTBIm)*jn#-=i36N8&?Tyqz|>Ymkg&^?m%J_vl5QPrz9u;P#iJB6`+4Fs_2=EYq`yeqVYY-A>T z6Fqf1D_ba#OOg1D!-IW+wlE&HVDI76wzG}u%csp09dHQQ3pU`pL~mM;j-M?2r9anx zPMXp1JHDihtGPWZ##O-fuFQ%9?l{bfve1549M&uSjjuc#%MJof&X~NFr2WKU_bDnP z&RkLAkkn1PC5@f(MtNZ6=g!r6viW&v_2y8=Gl#1^=||Sl+}V?MI)}S#=TDpCQ72bq zp8z_z7^}=grdeOXHrK(FP$ z3&bY8D|p&HD;Kqg0;?iA@BYN4EC_b)^6Sf6g<6F_yfQ%ip}=KFKS8P?uM=o50Nvyr^kEAQ$kQIiY`~nN z{Uj&h%L|YTLk=vGSGX6ZAMR^dF!M}?XD_pjvGP}-43?NKgG?Myee?fJNvwQK1>SzgxX9z=g`~A=RS5%wl zwN?>DnUoS#7pUB`{Z~D}UnV4kRM!(i>Ko*bfz`C1o@;S+SM96bDNV3j`HRdI_ZjF{ zZ}Q69HO-q)SG8LxTO``Boyev+{J#xc-M_zKRh)PkpXHT!1ZehN6eh< zNQ9+z-7=2n(epo3G-)~TmQ0#9_M_}43qOnK6LSqH7g-tNCKllO#sT6rG}d0!I0x%F zjW_YIM0gt~7&$@C)&L#wr)rhYf*IH{(2h(wa>fZ{${C~Nzq#V(`m8EFX5d`(FcO0g)+DJ6rBV09E!{X8or?&yxf`6Cr`;d z8^!#-5mNIb5FyQqUn472pO^I$MH5zDXUcFbcA0AbN{!Yq9pxUx-MD zy^JIlz3ER*8c~2Q2g?&XNSdZxB7Kp`m_^etx`>#?`@7{fL~XE^_8OwsZ89<%fGWOG zqWigKO|zgD`UysG#Dc<7i@yhilR@b4F&8zIVGD^8}LV2=Se00qSSTQj_)XerOE*&TnM~JC{PnBQfj*$-)6*^!5T!LOdZI(`mtnh;0~}E#dwEy zg^UDNDRa>n8HdP|$zusEEiudMDAU)OL&q7_FE04|CA=z7yGX@sd?f46Gae#K| z+y+_iD6W;Gw7ZeLlj?jWOkeJda6M?LxS~TE`|D)96DV#l79*_F` zdaxD=16)@0TQh>xvy}f(2R_!K$RWUAgjgVX7TjEqaoQ3#93c6HYh%PS1BOE?MA4Z% zu#tqoEm4OjLeROJs16JH-qDQs1X@8ozu;!$a_afoP%%FV9O;4b%cvoZ%#%Ut+Xjph z<(DuVU^3{e2YfCP_)rif+kWk(iGqG#cGq8ZG z&=!-&fXofBJwiglzG1=7{Qt&U9K@kLMS8k8D+#}59CWA?;qtU@S&{DOUWML^cog9>&`1eZ?IT?kj!J z^Ye0jpHbBc{<2qMc?p12X?_T!M7HZ+Ah&_ZU1W{g(_afq zJ$Pn9uVkjJ2*rr@EO`xgu1>ijrW_t zg`e!FRT4SU2F9X}aR;(I@WqEL?wRl#<2}nMue$KC>MHc zLc(tBVUFl^%A{pM9<34_4*J^zjS;)X*-cfRt}VcfHzw2ShFI%LjN`9yQ0}lS^a#0?fF@w9mwhG=c_-uhcSEzA%dbQJ z07wYX7Yi}E+4%BU%t7!Id9k3|i@m#m-CDb>gyuLr`RV-@_<~;$vdo@paMz+x;B$%A zu>#i$SFEL=w#`X0MksI*>j82P28Su5Cd+DO#0SvvF>V`iko`=@|E?_o5)^W&^cT7F zY&xu#iCFs>G2CE5?urn_7C}mhz_&s*ul~}JTbowh=eu27l_lFx9*bt=o+lq*vxD~) zdXBn7K)m06hOkRJCVhX0MHYkGPpJo=%JLV&+e=v*MjkEX zD`7$VEzl>8v0xcbfup<}(cv0Jh7|-=%3WWm z$o&i3RPT^Wc{U#2#T?rNugzxjX4z)?xXfSrXW;KUY!kf`u%nJT^Ji$=2(-xpI(cSQ zT-T9X8&{1(JBQ=iaQw3PHT&W-OYq!CoF^;K4ZVEi*6&vh^BFRyqW35JRhb2TP3A%yIs>%q)LGrp2F_Y4)?3WBjS}harZcq|AJ|5IKZPHJ?gc zQzY=~keM&^>RDbwh+Luq>{sh8>K2Lf=16b3@~KrVUmg#P)d6i?PTqhc$So72h}$0j1@~THZh= z?*@Ll%j8+VL>2oS@tsA8N~E4N z_#%PU;7lu7Y_Kz}pS0_Fz(>*VMo56fX(@rcXvah?L6GKoP7Oh{cBV@>g$e|jVK^lX-f9M|q@EaQAS z)A=X%JOK|}f-YOL)S(Eseje?7S{1NuP&Qu9@?ofGmzD^dxOYrLa53h zGJaKgOrDEdY^A4dWJ??k9nl?MO&Rl#}y75Oy|`Cl(SJ(GPNrnzYUAbYyB%=#bl{?bEZWgTcT@ zax64slAXwYY3x|vMtc?_G6Iyv*dcWwQ;OQ+=JlPVNrwW-l4h3{F`M)xr;O8Ve8-Kx z|2m>l?$|px&$>1iay?1$k-#nmr=Jg=90^=T##VcD-pt`(uOaRW`OJJ-Ds0$>oL`Z^ zKj5z>?KA=#zX_Spm_&`&j2)NE$a4KR$oauQ*#MKF>8MWRP0ax@`M7{b5tOwkI z3|}ztN7$dJKQJp$o_=>E&>6Wc^GAUERb+nH%t_{t1bzu?loj=#6Sg3(3?qa%EgjnZ z!1twm8;p68B&m%-dafXBfgNrQ>~K18&|sirP}dCxo{RHuA5vv1Sf_ zno+QZJ%`Nca|bi0??d*2Rwa7@`t}ku2Ykh(<6pgBYMjYzTT~7F3D7tnNiR2r13#D3_9M6C!ARgpFn%u!57T_iBe@`V zxAq{ocr&~>phN5yvlH!&r0ov}YVd{}7!w@5H*G)RB*+T*?6OGU^-v_R5VnU23Xdkc zv>tUcKu>;sMHoJ1tHtlKEM_vg-Mdp`5cPTZ*6XWcmj`@i#7j|3QQowq(wAJ6wZgKr zYH6di(EgHh-xAsx)nfn30TV0~jOYfxV#HFE z8V;<+xvo43dQV&bDX9fIL=-FN zD&YVlXSlu2HBKhu9VgjE)ov!^0`MhW&S~u*L7%pwo?*-#pcJ6zoPbT0<5#pJW13p+ zqTI|G7^f@lXe>2Z_QQcs-=er7%JO|m7zp%&qQju;Zj_Z)y&D!}D(_U}tH;k#%!P&S zz7=7{e)-5LsnJPP_>nw85MX;;aPu8lE#8;|KPSb%&Ng6{u5Tl6E$*yf%s`!FAubun zhV>2b(JwP&r^A=+Okb^@wUjJtK(?2)jT&cz^ry<>Qe49+m&T=8tXXoZv8)Q2;3`io z)>N&lTDPohiS7{|F&}zlm!2%TBJ3e`^TY}j&o$dC*e0V{wI9|$jLP#8*Y~mdB>MQI z!Ir9axK)~%16#vX=o z>`Cbr+;79-#qkD?*Kr)j@pl~mz;PPK$;!`BGs%8Z8oJK2|Z)SpCtdEc{m_AL{w{-2>n~^lTbtznQPa=#tke z92hu8Iio0(letshvC;945bOOAd!ZS8#)(FIzW9pd?PHlj?6ei#F^YbHY^vAPzv77X zAqSSPB#qDvh0uxrHMmz7Bu-P|F?&Zv%)DZ@0K1c&Ela(RrF{vx-fdiN>Ehz|({A(_ zdAkxp5sx?s?6eLJF%DFCR?W>?z|e74r+O&0}GKlnbgm+-wn~21Cp>wOWIiMy@YO zr8Q&4X(>i;X(K?|JK_IsYLK)o8NAUxjn6H;h0LDV-LvHec9po{O7q{Fo?O6Q2nSSQ zcn@Gzw>PAilk!R8AHd2!SVF`4Wk0-sw14aqkd28?ZivY8EQ+(x!>gY!-W8$z+2n^I z4QNGYQs2l#%F~?!>{b{U0?JYmV}`{`WkLP^64tmHo$oqT@RTHXP=@1#3L`Yon}OOO z?PkX8LB_09^|_0P>0m6299Qd8Ozd>pZM!*iy-yWNDlog5klIL@9mw9cq61iZ#EYoB zSOM&#{bd4n49rNZAW7|JfDgw1|Mo~z4epVqud(C)notHb`yS=PMfXXw zf=?nB{YoJDk?BW+y}KyizxF(9J6@mT&hm1$ao&mk6kDPn9_LOWNb}lMREjIgU zKe%W_&@-K_^(99s&&w6WXUOnrvd9J9x~xF>vVO1fbc&xXFI{X$R6khu-|U&u`lcY^SaHg+_BSsO|%2rZ{?EFG%NIH!hu}_$aabyG)n1TM5j}PI^kNd z6C|v4ln0nWZV4mas)AjHyBu=w!pvd|Cn}mh$)_Cu|7d#?@F=RRZ@iY?vvn3ABmp|z z1Ud;zCqZOWnod(>QQ5>-0mo)>rlX^V;1X~lfD3N#06_;58FAFt2rdN73=uIPjxw&@ zEHh!##w|)l=&V(}|9_{d6PNd$=l?z5_q^~_s=Ds2yPkXRx#ynqJKF-OCbEtNN|^`G zwxq&LFXY`OvhOU$d5a`LKg=_wDpY04D!j&SL@8~lKC(4dojNJ$O(mEoE_+T&X?A8@ zyVojMfGzqRNgr&iEmQ@(DD`&WuLa?UK+hI9Q8E*2b2Rsg?*!Ern`;%Y=tAy7XO1rk zm{^CihFSt^N=sQEYqJQO9NA~40pWP4DvQ3G$Bggsq>}fhxeFe+)?HjPt%|Vh(w&3| z^#QO6J^(U7_FC4o`fiL^lXU3CCnvmZL%$NDh(%zwX>(2Huy{u}X4$w3UP^O;EaG~9 z8Nckvs?uddU$rs~Bv%5}1$q`cfc^gUnxW>!rL<<<9{Q^40(481wJsvA05_B?m6vyZ$w>Nvy<#W~ZCQ-5_Vw*jS{?D67rks5{Z@PwzPASWEYs5MT-8wM`S7OA zNJYTTkWdYvq2cjJX_&NnyyTaa)&e?LOjrwUEKc28&@byLIe3*%4=QbsP4kiOHpV<6 zK9XLLa{k>&ddiOSoewA@>6Nev=K!-%mkqJZI8`l){+z0G(2Y}Q3Fj6u9o8xpyaf@p z{L8BF<6cEQ_32fRfmZsxYw!Hu%J30;!$ zes%}!Sv71CG<$@e zRZ6J(itA_JvuyMkM>}#Az_P7`2EOA1I(>Mz)OFAQ;N~*&#@$T4p+!xI*5E8od z37uY3B@5)rUF}nZF0vEnR-hJ{LBC7i6~lT#s1ylL08Pzs5O~YOJX!EEwHsP`x5;S& z2e}?dL;<#u#twOP1y1b@z9s?R?(Q0D_@+Z&xqY_5L*>_ZQ~xp+S*v4iMEtH*euA8w z&fkgV-~Rs32|&-NQeE>RY`{KVLtKRsYs0LzfidBqo4)qNz3V~qn}vkdd&&*46*PF~ zyN$4{<1sW*w_IJFD8R3Ct zLjvj`j(B zNLugixx3_^)%TRtXn;7EW}6M1w+|41j6f(^?Z8?iB&^kU(=VD|Zqm>UlW+mZYvk12dY?*;FMD6pCKf5`}m0hZDKonZjO31ot~~&g}=M zwh@|GN0Z;^(kC-{OJ?iO1>CF1tCEpzX0KpNlJUN$W4?QwGvDcuRHK&9o_o>GeBq6* z8ERp#UR}!M?GdVTjF^`*on&3+Xx7{2%Q$2I3bT!BXF?a7z+OFc`oB8n3wDg43*kKH zi%wwU%OTur=@?sV-krurp+$DRq`FL!1@-w=&SuB4wgTZ;TY|72EqDj>V@GNh>?ZFz z*2eVJEuSis2}e5SmokqMwgHV`@)dhHqORQN&_E`m zc*!B#*1)f`TNM-|Bq)azG&1n_4Go-i1j#ji{OXT+n&FrN94%bNO z&^XKl-*!wKzD}p0D_E59)~kfE!VIA>n=SOWn_wGFbs;$`?LkHg$AMV@UX0%)fEONH z;(|V5GuGK=lbi8b-J6?d(fky-v6Z!yxW+cS+&!>IBv~yX?$cd2$#_La2NT!lHdX=| zeG1`5F;`@OCt~-QtKGmy0v2D4ZA@t9fnm(hHS?L$Dw2kV)wEZXAh4LnRC}wm5&c=cL zX1s*8-l8(IuaX?g2Oms~l|KWS8ovA(+QjtjH~99-!8o7A*oFoO`KMxIuM6HuI&RzsB~t4 zHLA+@YO>soo8EKr8>;7A0`2$Us>Zm=to_fub}Q?-$_mZg63&+mJ;&loRTE#&ZsE2v zK<_+G@^G6Qetz@VR3MU#wgD?3s%p}|nr1HYuL0JxznOli@T*2LHoLK#(E8|&25+h) z=;M^T(SFJDH;H(6iySMbytl(GWS4iLo+JsM54^koE{nw84zfs+VLk-OX^;>(F-|DG z8PQAb=G)kO@@f=>wEqL3!IweeTnftq!k2{}Aa;sD)Khm1HU+rMxMtT*4YEaq(eswOuj(Z^pX=d= zl6;8*6hyU0T)*@6>DOHM3T&H`A^77w74$$Oa50 z6U~wm@Z3Ie!&*(l!g~p=xkdi2&}Lws75Vd`yP&1*$|g_j(xE2oyI7mXIX+A49G&$; z2c;rGcEGQN6bm>m3OZW~yp-KWTB6Kp%y|z*?9GIVV{x&KD_mG3YZ$DNl&`G?^{_p@ zR}GxOL?P8n9`4n@)ZWYbupJwb7S)I#+0$h(5-;KPQLU!uG^o z4n82rr|mc|GiFRpI?&<>C+=SFFn16ZhZ%+3>8B;5OAmU5RzKS-4hw|bhTZ8-UdsHv z)vbCpsVjwp53le}DPwmIqU{`pL+cDUb30VtC@#3Td98rxy>oGcuzsbGgU@) zH3evmtP?7m!I2VYYFgnUuG9=$lF7a^7~!O4xqb~H7XJujeE2sokoPd z4P3-j*=C?8P$wk#HUi78`{dVdHur?ogi?1y+hpFsA3A79N2^BRT6p?4(K^9c4z4O( zdy}U4R3Y&28nhE+{<{! zf4pOG!^5^C*OT1Jm_`ACR@0TpG`Jam4z${At-T#Ogdde9$VT6O_{;z@75axH3^DP# z$bQT%Cd@4?%`MF|pHyQ$(UKoCL5~!rLr<=0)C5oRkjkEr4w%%?N%%ZSrvrY^8;%?g zGyY$mH`aX6V;{;)=zuMpbuiXDK@PFbL++(B61D7b{8Qee$cQ;sFIEGR{gMnpD{K

ctGFt~qQ9D{SA6Wy40&CIIjH;!;1rWQj4PC&!7lZ`*@gOoPoEKY$%ZwYuD z^5#Hk3sTxOi(DF%>)VbYPIi)Ww&835{-dV|4-~<#gp?<2z_?_9slEdvNGVBz_a;d{ z^^6;qxBQaq2FF+Mevu7|Pl!&Dbz^Tu`F`}C?SNE)@5vetuf2N4D<$q_uQC=b#x7w` zlo@~8dHEde)u!M?vqI?4ii&rJfAYfoeizGccf!XvzqAxM)RQdE16^#&LDx+2<~J4T z!GB;Zi7n|eozW~xltv!uMqoBQ;I=}eDJJ$vJ>siUif_Z36Po^$*c;{^m)^n*aREAk zds~0(NQbA)9ueG_MX@-{fCmoJZ~I!FEeGZ~4MzTFk)LKaqN&kg^7L@0GQXET4#`9^ ztaQ0ohX6Zkr(~}Ne-*A1c0pD}Sk6bnwatWxIxzPh7)8F)!qAi*kYFbIm_L#p9%28} zylZMzeg(u(MA0t7Ix<&V^~~NnVLH53Y3t8oj@E7dCp?XWsWD!1${D;-|uO(w>dCCtN0lEFOU&_K&$R#t)&(vcYr z4&Gx2;#WWvVqaGsgRa$fNdwHPRBv)KmF4RyyFeKCFFwHLu8?zu1%XXJ-Qo)1ES~D} zanEBJpbB*Yq>P46wPsA=A24^M`^Pd9m>JA$Wd~6H7tbz9==?ar z(3!xh;c2UJI{nh)7p?9UlG?Ny9v4b#=65JQW`lmkMn=+@H%|Q-0a-Oa;pT&n>W` z!=8z+bgFzG_vm^XswOQ$DBdmbsCT&4r_8-|H6+chaH7$1U*L?_Y@LSc z6^gehucn$M#M_&<3o|L*CEA?{XqQD&p>ef)6IQ=cSBWfprE`IGeb2m63{T!WwKID+ zzfrknDUd#%dc%&h%Ei)S-zg>dzt5kvrrr-NqjVO6TI-`?N_dVLeaaNqaE<8GNgIXq zR%RUI|L4QNyA&fa(i{nabGb?2!QI%Q<KYjH<0bw64pY_hx3E~u_d@) zv;=3D$NJ@9j$9+J`v15_>R+Uzmd|P+4F%U{SC7+pjqdrfccyOf%dqZ(#$vcYEq3C6 zA^q3G?LMvL4E5)NQ~wL;7e$-kmut72{>lG^^b2FP@cFe?PT%u?p8l^W8trdX=jVDM zao>BeOP!K~9$4U}eVKZzYBTX5=YLSK-H-zm_{YTPcQGsk%9R4kI zHRW@OYvnTiztTivoF;UGG*Rfk1*_~Tm-@Q|*qhJ^NTD!{@*0>AIfa^ZvTPj~1rEdJ zgsnDLjqAQ|6XRc`WBfcEKJv}azT&giPHSchwBBs@39Q_ZZNg(3G>IY2E^)Dzo4$?5 z1ftrmhl2mE zfi0zt_?U$An_%k>zf$xKY#^W=D%}r`UuUD0WY<^DX8QV|yr;FpP9XpUIvSUI`eM`J zRk0>iRqy0GpX6tMg_6ww82z6M1V3e-N9k#o{6EiVzZ%E1&!tw|4*9elZBrLicvu1Z zKqs~B{LlWc)28&k3*^eFeER>CN?%}?BUA-n^CfA%9QXV1)?M06tIgY0FQNtQLMqy4 zQtY+LmlA?i7T~OH1C-aNe-8eOo^80cSEW55pp15bGrqCyB$g8eu8 z9DeCYu27ZTtSSy7jW-WwxW~ygP}-DIOc+ct;oqj1@T(Nln?vxdbLR!323nts>EyTS z-__-_=o-|;;#_!vX7pP?;VO8?qMOln%(IZ&Qsla&7kDR8A?Gc4y~cUh`3}YoavX0%B|M-~&s6 z^7IAHf{oRTb!PAR-O5OTB>8RH4W!MrVZNfdX_dPhdgdhpJm$iuxjrQyI1ReZ`g&-M zL6+YQ-(AoqRhgP;?mGX2&cgff7f&jLor*B6D&d=b%($7oZ|%;i3_=dtIDLssO{yL0 zhR`y#r3iCLNzDgRw($dLl<84O;vrprn|A#g?1j{@v4BJeE9}^qvDFTrdI`Q~<@4<{ z4^HS979m+N7repQ1qpaKOdH2UXR^2+05ARmu4e;TI1MLTm0ZMCK|g`g*;n4tvBGV3 z+uT&Y`Gb779U9^DrL>85p%Ux&c+&?`k!}A&MZ%-N6osC^#7cL~^8L$KKTr&Bw&QH8 zvG2@gQFc=$xRuG1HB$NvqGswP))EkJ4c+f1dLSxMI7i~h!P5?fv|Mw8v-$yQ`?0$z zPfEMkwc2H?d8$%rr6Ba+lucPM|rcKw-3lfW1!uRL*}2gyxY>)egd&Int@(7CVO`MhW6zuO*eNy-{O``vuUz zj(;({z0vnU@t~ZK{^|=I12pnkt9B=qu@gENMlQQbwRNFXXwSWk$!GjK>lpJ%$$I#t zl(RQoSTVbYi?RY`go7j(L7-n<~zyCDFAKSk0m2RmQHN3u7tQo-Hs<59cRh=o(g5A z6TzTZ70O#aurjO@SHG&COub@9NPl>s9`06c!wmNcH|FFe^*eKo92U!y%4f3^033&h5^|Q z)*gg46K@3;C*j`u*_Wye&u-7;=a<^m`&lYV}@Gc`m)0c*~XNX4B-h#ueUjp zPLCS5z0EXwMGg;5F<3tb^ll5*S-LB6pLdsEoW)U*D}!Hpx$g&PFbX-K1Ur&h53nE^Yj z+id=;!kIXo*L5=5@z920uSD8$)=Wf}a4N#)a%jcpq^9iZ zL+6o)u|;b}ALEO+0yyo&{V?u4?(fL=ez6If%51JERswB`dV3)LbMg31^1WZ&CdccC z-r7%8(JzW&%@o$EI!$S4kn=6jOC?&mAlvo!<3vWLl{UXz7KM`5#Z$gNz~Ow6Vr$~D zkIS(YiqnG97RU3xAzsE00;X1KC035dp}ecneq8QQVL0;6M{G(BzAbVS1ZE3ghq64`vheb(78wbhk6pUB& z1oex5b6}w7zrk4+eQ|Ht-OP+nI8P}t{xv8Yy(NnT4!uNnE~K$3idVHt7@6h@OC?S# z{V4%+C6^1SkexAOZ24CPNW0SpOse-K^*A-2@;v%+7RVj);44UllnzK*oDy}3=b+^^ z1?M4Muy10_sg+&Obr={GUE+FqheY&y9T3x};=VA#K~hV#3`Gd(x}UTU@P=tCL%W>A zy!g$>WK%tFW;O7%smJ@p%n-Hw&CNx4_MvU4MsK0MBvp|${TI-Q0A9^$6}nogC}xX1g*@Q946tWS&Ht{&Nhaj`JH;# z0!r$a(Fmyg(~w&~Y|0H4jAi{ub}QiqP+tAe(flbVq9xLyS_2&_%15D_esM{N`kg2T z08z0knziFq;FY-CMAYmMXok&A07Z`sS|PjCms5`ebK+g4exJwZ>mwKi(64B_1$DRw z*Lqy**Xg3e? zD!P@`aX^}*cSrHA9q&%z9qEDe!=hg)Cyn<+iOR2(dRmZXpYcD$W+C<66!VS{pKC#n z5j`^g#W7W`R&J;IAZtr(W5%e)P#fReTmVfu!qQ;=$b%|DF%7K0JdgoD>qF2(SI2bb zI=QYuUyRQlsvu#)B$pS!7cgN+T3hc$-;tE-^_T(e*f0JU+FmJFPLPB2mPKn~Jy?GM zb@>L@&2oKc#4vucbD}m&jnFLBFK!B{kcKk5L#qn4V%n(B;eF7Yj`#FUPjp}|c{f01 zrnPzB;B1YT5Xy}IS>mQa=n<}IB!yu1T7PfM^TGaXd zs0IjNG-i#U#kq&*-Y>3eW!nCQa^wNmo-xymln!bDIydH$bfC0wpaCQ+F=-v+(7XnFI0f8I1p)JZn-t z_Wuv@?Pw(pTIFV7hvxd3Qkq?#M?8C+*JAwhP_m(eCEFsWF_4P`VWz?KH~u1QQZ(OR z7oWZRp$khj8u)GuzS}iekKf5*K#+y^f~%qv{f|i#{ZHe3R!0_LbJn9oTO~Gk1M~!e z=K>uSPDgg0p4nxB@f@^B{jmt~HyUuTT{vUbwT=-c5|X2Cl5myK*+F6b;uXk)PF@F6 ztQt(whu!P1Q~bxzQrz@!QcR4eI8di|BKdy%U|U3#aRI(mn!7=m=+BexLhEjZPdTRZ zXmzHuOZ;tUa=b^o!Wx{&r=XN0rHul19x3zSgZ*F^mof@}nUwin(%&xk-GsV69%0M{ zl~n&Ou_$V4ohRHRjKzrfLAFAmRk2HaK9uhd!3NP(S>U5Ky(>cTDJE>aB6Yy)BMNr_ zAGJ$V$I}>!G(MEmu;aY0OZ)4Cgl4cj*#vb>9$df%76`fTk2f_<5K2{WV2GR$cEK;8Z-=d9H2{ct{bAEf6G%U@BsFN3=!%N1p&+!bbb=ll1|p)^W;#I^3| z2SNqaiF|)4E%4OOQhhWYo9g3`OGfD)mD3%d$GgM%z+WGjD_Y_lwUXy=5%#ChK-eq4 z2)hwsGX}pS+}EGRZ3V)*k6`6RCDb6zzGfX!l}@aQhJ*xmvbPGj|TI2E5wat&objRXNl$(IF!=- zv29cV@kso+Q+BWY){87_5{Qar9*gFb(oGlxTTp^+Ar(NgIXn?+^T4Vq7x%-NxF_RJtv=nsABnmbee4B#wmf z*M!*J(B8oMNj{|6omk;G_Nv|XLgz&)F<_)I*v2V3Ds-DZM`r4Lo`WZB0j+$3d5aDziC z93rrNhP(Om>3E;uO7!VQ%hNUM{w@+s}FXD8tYiZ$d`8lePTm|crPWaH=HTYaWx}j z@bF7I3CepWVgO%DsgidVN^oYpmpN|^8WhjTXQnsHJKkydLXC8xErOE19%l0hhocYsf07^p8Aj%hbS*j| zyLD>w1b-7Ghr=;ab@mDVUGETQKzr>ZU}fJbG46@}(ZPJ=juj7Sycf|_l;$wc5{>tX zyHOA77aUhMtK+fGum6(t2ExUa#e##K1F^%Hq@tj{w{pML*Jw@W<%+TcBt)b5yq!4 zQ*EYJ(jh%nBY6uOfxS)w%KS8RP}9Ie=i)gC{{S;_C)p5{r4Oh#%J{l2T#U1CHOkS4 z6M%u4lB_UZ#GdG8d_#T;Qeh?BCr%0f+`jX48zbXnlP%$R|HCmgEV;)vvskAyv5S-r z^@;xxu?j--ME{h49!R=m+tw%kEu!{K^iPzryZXebPvIL6vtlah z(Q0_q_a-ANg0q&ae8A%%8)iT_sb|1jME9 zX`j(2R??mi{JR7@1*$`z_;;*tI$3LsFeCfK2cQKfdPwh84;oB~;#;7gD&_e{h_G6j z(d4C#sDA=-m*o6N|BSFdNT*pPn4qsjmRhiR!Wbf*F-TU6R3xPp{}ObeM&q$FRLlEu ztWNK$;!nrkrG5ClXn&GdR6`m|8m4`sJG9H8!AT082Pk%>6M+~^Hn@oh1s<18153+X zfv-^3pu=)HB$KF?eRlQ%WsOQjDQGaBjVP6(GpE?V^@&%aW}0)ig3c1rcPk~UOCwwF z6~uQ_*NyfLnJG8E0aQb@O4L6E)PJdU%ApPJROfmZ&Y{~x`5U5a zAc$Zl}`b2Q?pnHGI>)n$eH6S$cKG7POjkIrQo(RN+KJkVS-$XW9 zBf)zsJCT_9bhy%Iy^h<=H^szP!n1NFc%Yp*akC@I%QbL&=I3NNSJ!e|Hb_>EDg2k0 zZ{o1B)Q2tBR6NJT{|q~FSdYOf$-f>8b33>_6*=5iAlaMOOF(nV(Rh@1!=2n#yy1Ro zA5$;^^DeiWq)2_@jtF?aCX4^P+&X>YkCIJDLQVXjw>Lp=`*1zDn$?YJ;kRlUxGl_9 zzMKOsJP0fuct!}_g)mw_Xxv{W6(Dru}Epo7T3w{lKS zj*2W}DEB5Q4>D+~S#@AYgpuhrJQClyaugCu$EW=NKKR2d$?NcVTVl znMD@Wb+9D754g*WsaISbdlWOCT^NbJx+#?6JN%g$Gvie3{QcsV$dp!S&i>9WWWui| z>EV`z(qy@c9i^BSu*+>iBYLp}j}O9jIi(b&G%2Ko96+J@KJj6*nh$%i_A2}v*&oV#%(iy9j_7Zk3=w89V;NGR>;{4L9-iB) zU!_pe!(n4Njo29Yi;~*=pl`mcFtIJojJ>GOU?y&8r2j>Sb8&v}- z&?=R399o&0IXIQZMm1rG*$fFQ};W!snaR41|xGPWd@Q!DIVwD#lk7S4_88%+7S$YZ*Te|JcftiQ(fTFhTlq@Id>?oW z5LoL2I=WWOE<2TmssLivgL05kQ8r?=n9S;K^g?x}ou;ZdJh0`=hCxC?= zHW2#ZQP4ZP<4H&2aeet$OZDJ(%4^9pHwQa$)3o=lXG<=3(D=JQ#Ky-JmGhVBt^8Sf zjq&u<$Kfd=Yxz=2p@-SEP?%3W$kaExA0U>hVLklgn;^3MZD%4(%zivLzdd#=Hx-cq0{{*aHRj0Q&M{~ zw5BErggNB*TB}ruxkKvgs774k{oTh^x+ihb*m}KB^Wbeb`=OTX2+&MH?KnHgV@z8r zz#Hy?#3sOutAqT-DvZKTxmVm4E%EJyC*kdx>f?}(&uR|!c5QN~PFOLQL)R0l>GIOw zj^sm{F@&f|E4_$QAa+J3W)-F(#pA~=kZIsC+k!OPyyi$d zr{DJgh_?U?*MdaAVD+wxl|!;&u2S-tM&ePw>A1uE~b` z?m(U39yxaDY^TXtguV6eV=IPJDvV{tBDwCg_nP~9U#eWD4$Okw?v418aFq!)`e

#@ODYic>fI@OWb1pa;%wI!X=w9j5IkVlwV!ge4_K8jWHDq)-eM6c|r ztzTyY(F58zTY(6Db4=~qQZ^pIQH=GHx2xk1*P3e!-Q-VlfwruTon)@1=Xvqx2?dGX z6xv&D3TPq7PJ;N@nD!30JRrq~Z z!Awueg?kEScxvH4Zgm0UzgVZeFiURhwbOuO*Lwkyam40y)v`-dP(D(4m5Y;x#!-x^1WrFtA1?cxjak_FU zo_cjW^&8~WvwxQQKT*G#@zjR|ro>a9fz3sv}N*n z1LZW{zaa8a2fte>#lK?I^D5yd3VB=_pb&Ge_jFEMUT5sn$5IH*Do zX+eLNBU)c_V~#US->>nOP86Z_TQ|bT$b30q4BhQlXPDL_$TDPL2 zEvC%2K)H>vI|zG%=3MZ##e}{2UorMiGy|TGk*_^=^j_%4+k}T5>UKxYvXS7=oN3wc zSzB%eUG<6|WBs7LxH3l)FFue^EX zG2raL)*bb{KQhEOGn;tA1dR3VKn{4h78s)k*=h6~ga4jv#oqG}&A^J>++MZbp+9S?N^MOQ z8nSYHMo7uXe)Nh%s?H;tzN*`D;7Ot?5v3a!G5Gf6=)C)?;Ps)(o5dDU%w93~psA|4 ziey;yYZ~+tT2P*kanZWx1j-B{5M{I`(rLtKTU9PjTB48wGkGrq|AJ&V)1ZYB6A#4L zEBasutkmfXxlTIs>zL6=DjXFHu!68yNycDhA@tz;AYap!-v&w<5+#X%24y@G=6!C2 z6@W{pwZM32>?5qsFP8;g+29*>@ko+TajwdPd&-%rDCF{^eXDDi7s4Y<-ToYQT0Q1( zYt_q0>#cBZ?f%*)9pqj5S&2XVrkk}a2Uk_+f1%D*>zZx%KVQdAr@!1J#{b86Rrw^ludyzdRGJ3r)~TZYlVCHg3gmBZ=~=8lIE1+!P4S(Yo@wM;<}cp4PPSnXKW z;md9M?aR7-?kaXNI|Y)sv+B;n{8=Cqia=wxR^5ekoJi-e_8|J>>#R^bh2O_h_(vU5 zF9|L4`c?zMWQlhVIGjWv05PMF`Bd#McG)<6!T8g2eZMWd*1NwJCD$z}caPnLX|gtFp5XI{ta04)vHO zjPs{r&*AZYGyF5pUvnm7&q!lCAtd9e2-nZvEHQQJ_~$ns&QZoZ3I zgY&8@*y(KjF$-7EG-|e$I92s*BmZn6yvaf**+4r~LV3&C1>aPWI^kF|)z;`~%|=@m z^@@LiBnJ7iy<)S(HO-f?6aElO45`GC0sr?9{?hyOj|Ef--&rA3cK#jiuU-E?A39_Y?P*Nwc)^@yWm+J+4R zTWmwSN5vb$e?%Qsn^8w@o?~~Hnx8j|FXT6q7B-*z5N6T`f;M5^t5_w&d}DUAu93Zx zovuT@4fWc_yg{T3D-kXPb-tN++lwq~x*(}(=eh3^=_+Z5voEm{v_Fl+V%w@t7(9Cl|m(S32 zldNxo^O-RGt$=EV1Qz-9yJ0ULTQBGv8g_k>EZ8!yfvxpkZ}i#n)!uoiZ9z8Wp+iZFrYh2~2gCE4u(pLMpVvF6 zrm>X_v{005s&7@J%o$a+GBf1VLenMrUxZ~rtxkooiQn>H_=I%sz%22oFl7UyP4!>MBTp&YlXVz_1U{g$Vk2oF@ zJbihO_y+cjL^tpU1vGbdlCPsI&WHRHGRlA8I)%$nnFJg|#>Vs=TG;SVdI|i-GkWiP zJx*?TfvP=oQyj5F=GAt+!kCV(IRh(zx>~iB^BwJRGMUz=WT}Y4%`w)bu;eBMgl<8#F82vLD@O*OEroS*I-m3GeE9<5EZRvhn z3Uo>#^{Squgx}_2OzJ60Y-43st+5ig&L(5!zD_>zTo=PFfTc(ZS*`F1?Hldsy_UIp z?+%UrWV)YC$!IeQluD+cl*EYpX-LMIB;>G;*A3=kQ_`=V^Yi~iS>XCSpDcYJQl~(N z@et?S?BG1GFU$^hRL?omqqVHRSD(n4s7H)lciordp6?Uwburp?_3G*BHF?HVIw|V@p1e(xMa6* zVbe-;q5rm+`Ej<<(QUj>8{#ee7^WflS{{~e`$PRb>JV4#7ND7A%9Z0@A6veOZA84W zOry5*G3{SN{r&0?e=87t;$C6xjuiL?W^(8D9$3zmjq?x3Ne0P-iEfFmKFm=8X@&GC zRPaVO0xPi&K8vt(GmrQ81-@Rxj{j}XZ2s$2{AtzInhD$6*u1aT+zM;huUExsqeWGj z2~8fAjm^D`xu4R$rUrSm@Rh@X7GjK$h8fc)t)X#6^4lKK9!bRMNRK!J=YjBD@2@NE z5qn5hWY$(<&Xu3kc={o%roBqrQ=`GIWQRFM#wOP{D3!8 z5wd46WC=o25poW1iV*Ur!I0|^l8BJc@g^T3TjC*Tt2sU5%y)4Hje5L@>lIvka8*F3 zY%lKcEh1}Fn6B*sCaVcjz#j3n@H2tmFpF)M#4jN0$f>*}-WJzA>=Bm?=9z&!ha&bf zh0I0HmmV~;)MQ1#o4X`QSe7s1)$OzS=ES63#C(S(@EbV^6@ zrbIM-bvI0vsc1OL|7;);shp9|)u_Lphyd|OT`Y&|5nff>gZ=veHQXP$y*2@R7Gojn zNiH;cU(L~(Sx6@y#0jZM7*kFd$35bYh|j)CWitEBa!O?R(-Pp2)60WtEsEsGVgJCJ z{53uBmokt`S%mbE(3^Nug^(u)L#Cq-jOc@R@aEOE=!?OS2{>7&Z*E09kOc?RM(fe1 zX#bPAPUBh+In6MOTK5H>zrjUgn7I9jI3dPbHNx!nFQukBfiO-V8E7roQ}w;FNTI0> zp&uT=80g_sdql@zzTIH~eUXVW)!<#x{XIAV9H_@PXuouX+=@5(5B7*-2SfgekR*iM z7tt)sdP(8}k))sKk=`BW<=nq)ny z98(g)fWX;Z1T>(6 zKM#g2Kv*uqPRL<8gl!uPqp_Ebu)pDrLZ^=ohD}D;5QLFsXEP{a&0t7ALQ)X28*jQ0 z^83M%oOrt~M7^sI(b`J1F&yoggKHG7lbBP?xLa}kL?0ugoV5zb*#_ZDskctUQoC#m zX}U7CI7>%P_aKMNfEHz+9M4PFsa5xgMD>LTzcskK_V(HzYD+J2mePytEc!louvA{e zq8WBU&muN(09+oXO2(e+U7Ji)Ua!#adP+`##Dqhn2D=(Zck19)+pL}7pIj1Zo*Ds#MHyc*JE+yM^me=7! zXIPom!oT`DWa_U=iT2lli}1RXhARWtP}l2H7V1jl5klH)Y|&g(Y_ULpsXsO{Hl%e zF}BR@o^Ya6wx@x|r7h#&LF;Kri&Kw%Axmv3_)tqVorJxGJ=j1S`&;Jr$5wCIs}?4e z4HI66O>{DP${H;~+Ii8UN@g@yKeyLjl2EU*B-Zm5cAIXSew${S`j3WfN%hIwQno$V zjFPPw4QkTX^Utcb`Ncm(ljx+Y-fmIVYqur&m^~v9%Gax&(LMt~UzFa{H~h2O`e6w1 z!@og>+{4dB)8+ei+)3^O3JIr_rI!1}9Wu=%l+E=YMjvj)F9{SxHQx}`$oGeE=b_sG zx(lbu^6nd5oV^-XBItx@#YFYC>dzk4YEP*uvp4PUbp3*(|L88p^wC34KEzvTu26f+ z9yC1YxX76CtCaY3eTA_l9olqk$;!fXm*KnyUQ!uLuXq}B9%*WlU!$H@i^VF^Ni}nN9Auwv|I%xMAy$Q7}(ovt_AYq2Q*is4KZX^RF zjn0D+#&pqlZ)G-UlIhx7muzLaH`S5elrFV#WhZtj@)A6uqbqnAoWwe zn~d*PdMEqlpbiPu`gnQNQTIX2*C@-Fn0-GpdZe$y)ZMXG8UGQfl~(z`M_h~8D^%kH z-b)=ynJz{)w?ZEke32br>SJ|~7`(ra@u@JLKfv2XK9y;qk2lTtv7`Iob&|2cbE2s+ zl`Y&U>7kno*>ERk-nwrqXLh}UaIFzFU>;}KBDQmD+D=Jh#J-xBwG=wnn|DfTEItv#lCOqlXi=1 zlCZA>DY8rO{s{kG&%+$>mqR@8AXLK39mKf}%nd`Z55<~OYQ6R`pdM;)BBaI0Y7b~3 zg;8VFod{rNu&`rXW34#ZQ05#p%{%tFexr{0Bjz0!#&tjm)!HF>!)m0$yWis-twMVP z%F2<96@ylf414l5i58r=V^vABeG1e=zgUeuLJ{J=A0=H(dv_kj{%28jr5(QA#;jiK z(vlQsBSUM36Jz`W(9&BtH|>q}XPC~7s+H~+uq)=z5=yx|24vo!t<0>wEZ*?$9qX{y zmY)yH&mX7k@ARyj3$)8Eu<6TaJK710x6I9toM4Z~tb2T4 zY5%j99gd7jww*QS`Z8;0jr?R^%D55jclDOtJ!JUn`|REKUjMQqz5UPK=N7QG%{sZNd9fILNV#0?l|U@m}HOHPAjfYCo&h zoK)k<5@h@gXkC$nZ2A!VFzAJB+)dCeEA%@;F^gq2t)iQqNTTQ7?TaLR^eHE(q-n%U*)>0lUGcvj5yFDlwGPgSzNFL;aS zWi0yt_D1vbH+PBN>N&1?&=t#OOxuqE8=y>GuCnN}Fgm*)2Tw(I`V98(;Ml<5T^5H( z@JLXRR+(0I8Q4~7*h^(r5Bxs(tKa+aJG1(-I6j;z-}A#p+=(;1ERH?Ew5fYBlUo>5 zewf#_A7M-ekCu53{K3m2uX`DHEy7n~TrKM7bz%H|q!MEd^9k@xAS){LL%+IG)um&y z-JE&2dz^m{JOd^$#zTw1&lBD1TFBasD=&ootJbDFv<&alWxrkBF?GcP_{b>q-xpDp z(|NhkUg-b)9j0wunOb)T;?X#p+nceR@_9PIX;N*UfKA z?=+`tPTKpUHINpbw}aDTe2j$$RT5Tlqp(-fY~CvgwmNug(d+3niQO_xu=o6>&hta^ z?4xT7Vasu}W*1`YlFDocFn=GAobZ{G=V_9huD#rk;(6$sEUWxcToYYZ$z6HuheV)> zjb$#0UrK-JdwCr!IL_FFOX4|c1Ef?_@KhL>kH6Ny4ds{Mdrm7H1B&i;tlA~bOZJhp zP}5nefn}JhwabuFc&`12#NW-mSZ@4LY?UocNkjNYadE(Acw|m>-tgL3_aRH#JDar9VfUyf~WlvJo87;$_Cmi`V9usR+xB(?6$a0 zfyaoi{}FiJwu)kmvP)gFNu!?F2P4A)5z{yj9D=TuK_3*Rw~LrH$=MRKZ;xA zGH6fGTgIG=7D*AG5IOy zKk70hJ~w+?+csdT@rk2?PlZ>^Zj#Cl>)KKByU~ZE?I_1R;4tuY@2+Y>SitF>{Y(3E zHIRSpJ2}UYL2|Io_9-o!rN5WJcdR1`_UAfqLs=19^ERny@*W3=T?WZ1R@A-#oq;5e z4W}QxW5Jr;jvf!rxXtja=jTGklC%3RchD?IH1nmzY$4629TEdx!{!<#)C)TUlj<%* z^Z)jd+X}b0J)1WatBS^NWD`6rd|G}#NI4P_Hcarz9sv1JDI{!!6$;MGe^5v{vg&g&ZlbzBHF%D!408ilzaP>{RdV3 zpq$5Q1DWWFJwmca)%Sr5diG%st!106 z>Yn5RA}C<+AC`*l9qoIuHp6^V&X!PjfC~*Dz8vlJcmP_%@SJFacQC%f(4|t7=I2y= z{{(iI2Fz#TQ!0zkUv^#*xOVNrtSUV3jgu&QnjvnBV&5X z$(VNT;B+ReJJgOgtiMn1W#Dh`FJT^__EsTPUk&c(LaP4nK{L3^Epakr zttHDRtP{W&p>m|R=%K&LSdIXTfONJ03Cjv2aAVjl@Mj~eghg9jl=jXx@Hvop!{UeX znk47-y`0w@@wESIFzsjJY5QBAhL>Nqi9Gr7I72A(KM@3OvtStWR;a&E6B^>&k!hR6 zPWz-fb;N7?db}#^i5W9_R|rOvu#>IAoKJOxCE7@`%Tt}X$CQfD6R|rSb9!*bV~31i+JnqhthqZlD67|DxNp3Hd2lF;~Ot1vwN>-tdjA+be; z)Q90LMRmq)8ji1DjIDHN{Wh&}=FC)PV%~XfqN>ec*%s>Qb>no|U@q`i2X}s-$}r+jpB?5*?n*ItzDOO*4|xN`kX^| z9$a%ZlS^ESl1gIeR{5*tG2*9@V>cg4b7s)#^`s%b730#+e>hHaex=Ok)a|46uZ^vg zzbKEbq!P;UnQ`BFcFCbv$F6SHblu62)gZ>1o%9<>C+?>fb;~VU@NZgFcZ%vqE!q~W zGUehvBsRlB?T(h!P}`??24cJsWG7^_-EO)~j>pD+C*LFR++zhLQ5rjg?D$+EqwNmU z?}4&G*0q=39ViLs1b8X>Q5PEK)OOvrC?rDCmOJ9SE@)h;s zncHcnv_zc%VlD*8|2a2++UfK&fBl5y-m@?F+;iUdd7rmqz1XMMUFp-yTxk4F<1vP; zFC+e^4jk*NT0ZI=n&r)(l6UDf&EN^jXF?z9orga%E#P;O+jO zBb7^x%?v*zeh&?;6Tkb1n8~z+(Yf$K|HiSn{-IjL!MceV@vk3@&qi^4I)=pY;nZ_d z;)yBc9BUeVBGaLVrBCGR!b{(&8Hz)SMk#ddqEB2kaM?#j`s~UHweB^;7XoY!t`umLc((ScR3XcYJ`6wR?a;xJl+!v^=a+@zF-sw@D}C;pr#c zEj}Ut5_XDxKW8ZNq>QYUT(b8@a2jLx#YDHd^^s@u{{+|Ze0wC_CqjdmZqm^6&2(hw z-ih$5TUOvnBIyRi3I~5Lq}z9mJjGG42&GRIoo)5-5FzQfTO76U;C)s_z^pjXtyWZY z88vit3eOz_7m%z~mHvFFyE{i5y_~?w@Jrtn5i%uFTuy^Y>-U7&09;>niuk;Yf+70;GWm6w)RA>0Y+^lCB3Cdm9BUXN9dJ|#D&(bac`hM!`unlkR($5ZI~yBq1; z9$K4c2CKz1I|i!_yCduGYBJ?tUV`|C#2AkZ-qOrW{;gNuJqyQLyvgZGjHlG~eq^+% zhC?>;oZc;tbJgHO;`LwbtEr4H(aTI`@T|(QB1fK~Vfezi7tc_nePx69i1jEL zoC?Ou8@zLAZ3GQcav{y?iQcT1NzIWJeA-~-Nd)^aR^?&X=ifh;OV;3hVlMi@izBfo zLVHD~27PJG%oL^As?k+qICwPd8cV4hd;lpUE#uyw)IuhI@1;9C`nh^OU%kfvJM`0Q z{4mZWKfcCOMDgev|5@njHGUX6_a9&5kA;4Ejn4^e8@_gp2ktf;S>qc+*RJt9q2r3Y z)ra8??WflG;h-MQ`~IG#QS%1~szmxdziJriQ4fa?HpBeU$~;f*6PFAYRid-47M?&#bY-P`?Z z;J?j@$lh)k{-J(+Z#NvgZ}`gIZaBDln9hS>u>{Z7cyV|4fVe6h8K}0(0%le{J0YIr z;$4z^?Ykr=P&f3_cMHiwSVtr8k>Q|aSl0cUk@v_hSQCY(nZ$QVJbk0r;{ANtY*&OR zDu=#zhH>VOyh|P%h;13qXJO?K-{i{Op?*P$=TXsJHImzX12dZ8uXGA`_K>(^yK~@y z<_r&$7u8xz=!&t{Y{45s+`Scpz5QMB*On{27TGO1{%fyAc1yrrj=Tftj`-@`5}yB| z(I+VzHk?;>OT%C(5m_Kc_TCSPYty)&D2eX9frA|S;rNV>+)G1|+#~UJUz2;J9pCo< z_tB@jK5BRI!xbU2w*%+*SUXPiN7|7r?)rv$Q++O>97uC!e(Ft#T;f*#)^1l`+penhc$xwl>+Wajv*qbN4o@+I#EWsmpJ@n=wN}MQ&ZSBsHP* ztY_=e6w|a;tvyB0WPIPLa%D8fI+xuY>(shu9)Gww%6Z$}QP9x+NxRQ;7;h`t8EL5k z_DcK1j5E~*WX16$oWlYrZx_y!1oG7*kV8`Ww)!Xs4PDfGki9YbiE8su@QuM&YJf^x z@4;JXaWVbNhS=_8Lo=j^G0rGkOqrv2QMxD8-Lp?y-19keIMm(ylzvIEp;GSD)~F0L z#Yy_Nn+wH@Qf>F{J*4X^hEU89x9MY(x?SmruTklnLp|Lm>0c@}QMYN^Jj^wSP#Pcn zKSC0`Dju;;w{sn;%$j0mn$Q`Q!*~%kdS%mI zpY(_AWXffq68EH^y;#!c`+Yxap5eI_41|{h@O<47NySVTIs?c5Tqp&H%10Yv(T*Kb zyzdY^sk)k*l;Vytdt)&ZBHeg?nYH2N)*45__ptCj_@H&0$Gz*kOPM zFGZ3P-B6df-2m+~{hjE};wPZDM&e&`TTcjEb!@lW%J$i;|1C|lqo}8+`1JAd6X0D2+DnByCVanwV`uB}XhjQxKr zQT3xG%0^0DOiOH~<%s1%mO*t;jM3=3QUXd^e5Gw0#I{L)q(78DT9SxXK-(scwr!*g ziIc$gJ6bQ%@2R@2O1o9m6G#{f<#!;)5}%{gl72DBf_;lKpa!ewms0JV)J%XAkpK%K z0~SPXxfnbcDk{x~B-S6YIJMhp?<7bPqP6bQ%loYzt00@SHdawx1@c&@-D=jqxaFnI zja#%&>I0HU%*_$ag#?-l?e?9X++wYJin9Xa4}AzU7%7GYyy-_yde*Espb2u_rW1O*N zbjFO#t<6u~U7xyrRs8nF+s~|8-16gdN$fxLog1>kSZCZd>3zadLw)K8!cy*k$OG-8 zc>tHaCgGC%jyOkjt3*e1@oSW__%#V@Zf&(df2owyZv|N-*RDws@3CaDl-^U56!BX} zP$M<^3(xmBr)G_IjT>R{h~L&r)MII6G>wGpmBlzCIigg=iR5%8cOBU&mS`dSBs9!T zb8i*%$6QonwouM2#?WNZSlXaTBP0eKr!NC_Y9X5CGro$QIRSW!g1Ucvrw(Y~y6igQ zAS=jSq?SBQ_K-Kod*mZ>n*5V|PvBsa8O9(dF%uaRV`io>&!YCvI!QoB4h!?JhH@MS zd`Cm3)__@;~%rj`#eArvZaB}j;jzh5kYMG1ewy|!LA`Gl`=thp*> zTk&Yx<6_!(-Cdn4k?Ia7xkN0q4kvnz-|%IG7ZYO)BS6ORD|N+Qn#JUfq} z%@_j*8NJ-R#;!B4ZzYuCoujh}it8^1HwZI_IkbCXg=Vd5U6*yho)Y?@~@EfNoQP_iicph$8xbiUi2lzvyn0+*VYbx;8r04({ePb?;yfG&l#GMswrv$SXYqQ*O^}Y$HmO6wRIQ~_jwWn zQ(@^E3Bp$c5r36QMb$>ovyb zi3U#LwDjDPuD#b9P_x?Vrao06v~b(btZH=YuAo0=vX*#9Vr?%p>4`4Pj!PR>j?Tgu zhp+OG;MTWSF00hmFgj}>9(z=b9mRoEX=|*Qk>Z=YGGZr`i284@#QdP24a6d&`&z`& zBDEfAw3U&RVjU5l<8&R>*3c65w1$;gj_d_K#LX(B?__P|bHYqz#ijHOk`P(COW3TJ z^yxORxmvr@$BKQSZDq`D9*w=pRfm{}J?lAPRvA*bNQhflFKk}LOd01x*etZ7fX#3V zo2}l;C6&=)E6-FW))WWgxx~t-krug*vnJ#TeKIjLSv!0(C!PVE97o$kaSK$>McYQ( z8aSE(^qJfq1xcS=e*qX!iat|eR_=nHz)}S?bQWmREeeg|&n^UK3`ZL% z&kRMBu`m1(Z+0zceB|Bx1OTSFgxj5 zglCf?griDhkoMC7m6OR!b+KMHkMqtv4vn0JI3nRRnjjc23ye=h{p$7=C zAJS6T;)W$oaSwfI|Ki3vYJ(!qcf?^zF9u(JHxgg!RO_`{q>igkM&kI=wGfy$Af%mJ zzT=?V>>AB4;Ku4g^ZOiS(Kx4J!!j=?y4|VxoND-q)CvFZahm1ea8i;$9NmM6>xu4Z z%FDE-Tq;_W>S_YPnf-EOK4b$X7rlCDKnGvY3{!byfb!HIHj7tM{Xp=YA#)8*llgM| zJ~U*im7C()%}B9gfMi9|1U&)ZFcr3Irh zQh9(&u`UDPb*zMKLprep8A^D3%JEvtrO}-`wKRHGnRI`A@>lDra=!) z+h#;xuL48hRE*VDq1sHZU+y=Gy*Cb{wQNXn)oA@=Ffv-SFV76_5~^L&sZs5lQfbOa z2t`pV`eUxM3D=QGF8_vC&A*O~6EH?7U*>>>1X2>LdX=NU!}N*98o3TS>mTa-9kG~? zSjYDrN~t;A9P7}&8DGO5C>E+GCRUyY@4l`@0h_$b!9NdCq_G#Q;!;OqB`4;eBC<|K z%B6OCz-`v_2ebY_>p_n0gEjc6Z~_p$VN;qn9(eG}L19qsP*)ykR+s%dI3pbQgVM0G z1#I8qX=>)RU`1s@uIXhp1}#x<-5l+V7VmwAdw5S*D&R*+Q$u?=8@9;c zJq>gFSd^YB?ssT8v`osK=sLRpkYr~i-tGyt()w^N_gvI^r)!FLxno6HV&w{_La(Vg z3GX3$hi-T1(3gs_zN`kHPg~2Pm-rG;n{i=Ix0Qz%KEo21d|wIe|HdUi0;+K`c^oypwe~^GTRP{c2SK_j+#}2` zr%y8dodvHKkV1GP*F+BtN_aY~y3Yr51S85TEE@<$!)jjzmYn>u^YD#Pio26>ml;Cd zl{AlHAq}Cq2#tg179HMJ1Hqm_uCc!I-<^_uTbj-G41_U)rbV&`c={nZVyBn+g91EB z(mNZ5$2)2Hni^n1h7Wa;$&FrJO%k}E1JHw#-OO%XO+HrpLR|l0K;0Z^tFjzBlA0)# zB@F6nSV&9*!COL)cItqMrgLEw(@)1n93#wcI!4>@y#t?J_%z~UKB{!4*3$P|REOM= z%-p2ev7B_zXP>h&zM5Jyu#w%J3=q1OO+=T3cN{qyD?SfzHpg5uL;bAMJA5@FV9VGlv#s5nmTZiS<_JIC4C8pu2^aiJtbvW?_OJD9!$`AlEi zT4rvrbE$K$ReJ8%xbtgz2aL{m>#c(1lUjqv&(*)_0-8wteUD2&QBKjxy(hqia$4Kr z$#KQY9If)gH`czn*3#p7h~#CTH3J*VviIiWp;?nQezi3VEc&+I#}M%%R$sW|`NevXuoHoWEcK9XpG zA6V3@iemQ*B|60D`OtrQeU)vF?Js_rjMk0~$!5gbrr92{Ki279#E{4FnY~P^;0XMw z42Q$O;)0igS|7~>az+gePN1T`pSYesqh&1BDT!;fBktt_?9AuE2c+x;<;wDUDq=d;db@R;Nqz1_@kjoqYLa)Xwc0u^j|FZcY_8{JFSh~5c$ZD~!aln!`_F>q zPzN|XrX7lUL46?pVD!t!=2L5sJfC{slEZnxyS>%Qz`i>Wy})%C1z=ZYF`LGEex8rxF+j?Rw@;7!%w`VBiZ?) zRn}3Js^m5JB{^4>CZX8PVg`K11UM#%H|FK{t#Q7kB{5#v%kgh=f6BJSHA0I49+?T1 zX87YStb?}!KI&y=UepWoF0K6?`e47h;T8L)&T&+W3A`Mg11#piP&oWJQ^r!>z}7EL z!>=3m#VT<=nEwC<6YL*_*7MMRsE=+3woD3klS|>3`p1)(`jge9{-yqL_@&V?_?3iT z6U=Nq({t}y;6)1tgYOB9PJy=#hbCr<>3&9F%!b-$1lC-& zv3d?Y*&8-8h4kF_HSWsH7lQW>0;Q(A0RAd^Qm6AX*|Y<7*#YL_N%k`EW^j)2vA}H# z+#}%Ni;DI&mZaHZPv0@{R8ON-<>fFdzYTMZ`VD{i>M%}hgE(tuZ8+9l5Epd@2t$>` z@8GrwjQeD-%vc(5E4B!%+wjOfa9I7mju?``H?HpBfJBr)HnzF;j;>RwB=AO^rIrmm z&RV)yeY}k+Jl|Ogwinhg9NY+x0oQ${HLdd{K=W78l~BoEdYr+h_*F-m*X>b8r>H77 zr$1QrprRQV_YL5|FrQW4>@_^Xn3nix|JuS$k4Vr1$!5c&40=Rku6pztVS>4cN8HL3 zmA!YX%xojw8kvUTBIrs|S@n?N5wI|TowMmd{=xKz5L0(bY4S3r95GLASpOKts&cOG z9j(3it4A?{ZCFVwKk!FKlTdVJ6+)9LFKdyn@mQa+|H2Pi$tlu)O|3!oTuRB=yOW z)E~KNYe=BYZFuT$ow})vZ`I}&J{_pSL>2cSV_5Ydx1pKWPgVO0fsI|P^LwnYXVMgC zZJIG{-H8WHD(<1#ykV-uhZGNOd5~mHwQ}YDmHf&mzG=;> zHB~FMwy)RlE1Om(+R|+AC@Av9uqkX(_*PfGR{0OX?8axmqR;!tc)kj3tje=Z_}g>t zwaUGCy1*X;ot7VQzwe}SHu`KYfws-{IBXvT`Joil!|2_E=TU0P@a;kEQyt8l7$BKB z0|&mE#KOHL8s9mgl+Ur>G4RXY0gnYMY;@ajaIn8aAUgPUPGoJQVIgd<{v>MmvWCwg zT+tn);7e59I@OG1>AESVKfE9R^5R%dM;dTsq87CHSBE3!l{3+@3>yD<5D^nK#Gq z`}TC8Y2{5-gSgB~AU|&C^_)$HqC@pKH{WDrGx}HHohc)Sbu)Hz{F9iQO zKyB`tTrXiYtHNK_Y`|Z+xw^1wEv)Ix@S==wnfYtcF81-G6#@4`CjESngc;=WH(08l zhYea0{$|5!aKKvuiR$^_d$7$s55A%c!B4@T&NVy^dseXX8>Fxvc)7m@JLPx7^e=p% z;mMSXCl@-NG0wxn;w)85T^ix*QV$CYvp(^}+fEDRSvx%SsZGMd@h60GS-hLZqLM6z zZNe|te5%KA!3IcTS7xbok^m!p!wQyP_*MY&4ZFhAVYQCAp;}FGjJAMV!gzDxBTo(4 zO$1#EI~l?`9hbWbP}U5Cz~)8rq=>5-kipPWxSlEb)%dkA3w0RZB;*&5=}uF+w?p{|@zx)mS#U0>;|j2GqF z@s(zz{BgY*)xlb+RL@PNZ*J=qJty}0R8~arkwkQ2qTU*E@5($TwjB2epM46~2~6u;Wy##>bDR-kX%{*ZPvso3Bxlu5A?_DDg;-fd*LFo| zSG}gRSE*q9r3x;j5GuNAG@3qAE6%CHJtY!4r)G+_H*nkotBh`1&ipQ;k(oy4!lZ%i zVDZP_;Q#Z{kXfp5@V@Y9JaCPLv2LJ#g|O9L1j_)5L8J5S>Ul==n_VBeSeMnsu7ym5 zz;93auKwFBjNitTlQXh!JkrnWYCmX^))v)1V@>igwObLt$d!m5Pq{Upr7~1-c0^Zy%Eh#zi z?F`Qr&hSpiW6!vbPsriG+ZqQ?xE!B?-%^}&)dmAUIj{H3)I3@H;8ZQ-b`)-qC1@G5>&nJgO^X3vhSH&4L_5v>=HK}I92 zOK+`0>un75n_Ft{f#>=yt^{Y2j@tgvSyl{82UmD2W&73+>cj2el#X4;~9K88SN$i=J=7y&h&J{8FIbR;FEqrJoe6 zbJ9F8u0vvc3U8NDzli<8mqJv^9u9sQE=toO^fW@n{dCdf@`_6<*1;+*Jsb9fXRz`n zL%KKDEXChV<~IC&*o;$B;a2EFH{r@sScJdVoBxTwKQp)E?;YlN{Jq7@;qN>%wf?!; ztkQ24Hkhg1)DqoRVWXL3O1m>;Ny2zDt6v3%ENM5Rkl+e)JwRnXG=!O1*(>GfT?zP) zstwzOGINPtGFe)|`)CcG5N4U55N2aMsST4jCI*dN;?UYW0;gjO)i#aE?YRtlPH|p9 zJ_oC{RoQ_l$0_F>l|l4{@eO@9)$=6Vl$$<*e2^Hv^lY`pd6PChjq|}${8jpt4i#jM zDp4jF`AzLj=Yri%!*=@AA`jjf*lRxaPmBwm$E)p)h#?9!@_`XA?o0XE_}Yjsg(9qS zRp9qaf?ewV2QK)ou*1>1F-DB;8Dh}D<}SziFHd2AlFsPFU-M~gck}?kT{#Ee-aBiMl7XB==bBVyg%7*>g^eIma`FO6>WFZh~Wi zGpQ!IW~Ek@lVne}GwllCCFzbK#=&)4r0_F$&zn{&{`UJ+P8IH{ueq19J<+YNv3OLK zbWJFSzIG|(h#7d-WkJqF_iP`bPq2qDC^N=8awyA^p6%PcIH`d37s(QY_=W3mZj#GN zx@4KB6eYm?P0D@SljOZw{R>zL8a)~t^2Pq=6u8(YdnDcAX{D{VCsU@9fakA1>Nfz^ z;v*b{oL#9q-JFxLyqM`$;H++CqssL*Pk)r<6;Foe2rMteg+ayW0BmGh2aZhbA z@f?74w9$SDr+l+r5c#_(*Wb9YfW z4oR|x!MvIe`|Ia~O+;%a0W*oS%W{dYw0UybqMJ!hUfCzhBpo00xfkv50C8jg*D|Ic z$EM2tYBAT%a^L$hofB)PH@_fka%Yr20C^N-Fg$a^XV1#UJ;|C*;~!mBfMpfmOoSYkdnia!;{4 zLxY1^;Dkor1^@000>znRB6zdGj|B6nZ-hxfe0G~{us4GYU_0c7_o3Z0FrQplyMKYx zeXM=S;qeRZwi|2K)NmgjsDYJSWwf3 z2ll8k`uiCn(VQJvGh9`xC{>$)18CLhiM|jLrfne^B(0=%)IOTpIa6Jr5(rA=%oIE= zuKCx&KaV0R8c*7#Ff`HRqh1c@-;4MyrN7mbCmnkX$MTu5smRh< z&;~lI!Ttw3yX?U41_^{rh0D=p%r> zeHsUq&KyWlC6MOsUZetp+{FBF@c)4+l{t73*08Kj3Y*GyoTKQuiu!7n;N5n+FbT+` z!|vtIn5!7=F2cH1rkC|3uB7Lkrtr;Rj=Ko{KcGPHeE`~i%2akSm^Qpn40(BQw-7Ua zw-7yp3CJ1j^3scXRgBL5>%NDfZM}IczHGQejQ<4U$0B|V;?HBsn4+%JOe6&(rnr7A z#f72SVv75bA|5H!V}!X_YW1;X}(zTf!f#vK^d2F!t?-Wc@l(y>?)#JUNww&Bk6 z{R-q@9}Ak8OnlH=gz{3y zLO(<3^$1;n(0ghbXplx*MLnxU#`9gonT|MfMslFD;lNlZW!jvA&^$3zsk|7xFv13R zG58X~j0j6Z?C()yek`OOAqIrRBP3@N_J3m`TM#l4ArgeFLC7D+LLNeh1|dP*If#&! zv5+;eQ=%iWAF>N6@Cu`I=TpoPA3k*MP+rD%eE$=l3-|=_0cVN=>~D&3_)Nqn8=tB8 zT$xw!VS-&Qd@O-8Ix?@Gg-kUvuU-v3VO@SIUz}A**UYNc5N1`+(Y16|HDE+@Q0o^5 zBC~4GSgm8xo(zOMJFr`Ld%|wvt?RCyRgSTE1L%nq#M^{ByZaAMxEP!}7Iq$C;}CYA z7n}<-LXs!R{J-G2{;(wu*sF?yxWcz z#L^awvvdDXQMkS&7cGFEJ>7`?32lWitkCC=wBj3h1Wy=k#lq}>ZlDItBDs)Omk3~d zZq2hR_$WsdwPXQ$Daw(GzuHPLg^K5V`b>?s=hcz+ytCv#@eYBbQ^5N3q;>CdE1`TW zbkD}+?f}o&UR@eB4f&#-i5Mk|_lIqqKmD&_8`u9&ZTtne?iKKFL`Q1f5Xl&8 zqa_>uq-yZA>Y@ET9gd8VD$+(>q>UP}jgfJStQ(_k{OBjz2u3{gQo7xxPbf`wWd%xx zEHTTi{{M6BK7ZcpTF?Gu2r~(5aC#Bgv3EV{{}WLCD3h5&7xz`sm5jtUey$#G$fu z_0dTg(y@3QzzZbdB+~~^7V6_PTyll~ePJSU`ULz!bgZdvOKRVCC>pyql64EPmC*`C zNH)`GZxahXY1AT2h2CHa_X*MJr>qI5 zSie$QASiXTep;K}{d@4c>`%>4f1@TlkOlT&)Y1IgPU=D7ShqCph>v9bLwLmfn#+RK z!;W1<>0w1T$4K8sb9(6Ub{)W zcXEb;H^H+{-3dRKG|tMg zkiQ8kG2~V%Tg1-e0vK3EQ+)#6XdG7IJsA<+Vhh&b{oNIu#FThc)xO9$%Qp!p#H-oh z3;F%sPEKjcJF~z0R$%Il_+HM*P0IEp$L$1YcurFU4t$YSej?&-<))g(BhJUn9XUzu zHFi#)75GdbFT(qPID_GRK%9L~4pZM?{qV_z6C2JClp`i0@1k?EvN@s=lscK2V_ply zboc*(z7J>|iBWk@=9K;*{AYh)M>y*vahNZG9Yk-t<|je|%*>o*l(bWMrrI(P{MoUl z?sO(6M~!;QP|sR{?3?M>BWj%*glfX<+hTnSX&K#0zNxzc3~%To(=wm=2Ys{{q03o$ zuDm_RxtQ7?aB8tn^tiu^os^r~g#UuQ)&lQ@f>+?l zH4m|?5nI)M+LP?yfG0_`X~r1)bqH-m4U*3^iG4d^q;J!}h@d35x5QrabVphUo|ohO zK@L3(Bo2Bxf;p#a4?XWwu6fE+O#2Dr#ob|I&Opa7(pS`0V>Q;YSH;p~VriKH@Wt)v z4|YHzEXwe}_ddbC*Zz{AbH5~H>`!l@99xOL1@=syWPT4mfq&h^%nN%S^N=aBvqLRS zD~Rc`_tDe~o@D+vE#GyPVdiE9)`wO4ccH`O@Z>{_+a$r-VlI@x(~F{;l{#G)JokAj zlkxOCu^%T%3)a}Dh5a|3>b%3ybkqNJ5|Vf{5u9XMfeIkxu5glN2UZTmIi=|h!W=Vs zZW(yw&U%=JD5r+9Bjr=JvS_{1N#(s$4V(*de1Vx4>7UUvI_;w~kSpB}%);ZMv<7Qt zxZI$aEU|O0=yNKp7i&^811rMpKCaPRXfCL7z2f>hmF4rNZ%Hk2NgW#dVj)YN6=1_$ znFMprWyuOG`@=$BBJ!LO@aE8c71Ca0%OCpupInqnJD$+VObenb<8Mr5;*SZ zI6o65Rg9Kz#`6#lTUanT;BQIuHqBd9@1|eoGJto>U=KiEWj-z(jl+pv3ftrIU?&AT%OT9C6D!9qq*%w`Z`HaR z4|4~AM?lEG)@24Z!4ok@^I6X!=W)o{u%4!QVC4SS;{7CAqIkaw_jPu}-@qX^!v;Ek z66Vpf2@#?mP*7P9s1bq{OUqgNE=ZFp6J( zx=k@%H`&;#%Vdq%>2YbT^P%T*uBCg&E9nj{pNx?{%*_D{`(dv;L9}+S7!1Dg2PT(>J^CYIJrSFDV2J2Ern)Gq>*O~O-Syxt zZrH&E6x=?Kp*iu%$gk5asrKs}&+RCM51aTW%jAa76Y;(ofUlhV@}?d8aM$qU9{Hrt zrvRnyli%`%_Q_N7*`KSAe|}G{Xh-s@rz`l!VRMTSsN2)s3^%it82;Kx44-%Iy2s#n z)ss-m<$mG&qO)lSt1|>x(ekya&hX^uZ^LHzpdLLri|NkX0yi zxVsW{z`^M@cX5Va;||s7(0-%3&cM-l=#!kVjbIkDeWmMvwLM|RuiU2uUDfYXKNNK9 z8@Cs@8@DT3VhaeLR)AQG8r?oYSJ(*qM4h2o$S`Q#0qkdKez5Wp%Oz&77^4j_Y(2|X zQFc%oJ`-5KSX$b8E+koEZays-4U7)>2l~z9FGrar-T@bu7~`fd1Y@BD?;@i6x^w18 z84;iH;9&_XG9|E2%ePZr!PU z^8LujcP+jNSZ>r7a8JW0m{9T2jgi`rD%c%oHVGL^nuM$+s4G6YLh21J4F9f?@7qSc zZxX+MzaSi3i2WA0bHb)%%_bUif0*iZB}zg0Y$tUsqHa5yry{|e8g(RJ}nVD_Cw-hM;hu6_x^8;!* zLd>_fh-GYvl+XYaATgb6rJ*y$+WssY;ni6d-swyfB=t)8jZF?PN-da$uB61OR8KPB zv`>IFJY9G0_M+Y+dG6ilc2Kz{lOy+0u1#o|A6igytToO4H=ctxuLUJXu%40CBZ z$=30MT4a~~R1Mry!WuZ?_2sT)3ujk0O;Q6 z9YS=qz>d>(_{{rscF|`q7q&~{bKG z&+PgI#OU%_($|%C1rs4D3kPq2=T=v#D!mK-%uw5^QMAfErJRUUi7;_P`(fz{9to|+ z`m;fOwUxiEXW^=jRmGS0=&!c&M^1~cU{$6Itf>Q7l}6~s8za{K&@VOC#feCj#bX=} zi^@(`E-H)1=ef!+u0pE(6k9+9sZv6%6jy0S_yX3_eqURJHvSrtFxWv4ar*0k$LWHG z-2DSQPX0A`oG#ciOdDyVv}elnD~OyQwo~#Sh#a(X1d(%9E64CSy0KPHfOY9av~uDP zTKWGMk3)4(be@Pdj(9gwo`C(p;!rzO;BlhMaZP~75ivWG2$#huPDg!|nT4G--T#S9 zzb;^ZV=)`z1~gNE0e(CAOYQ*m9qJDo>`U|<#*b?(Dp=)8bjUy5_MMza8Wjf_|7Mo% zx}#IG0`vPhyPB85rtY=wWCr`c{v`%kqroNJmtT-y_==0@t6cxYeqB`opVYftp$Iqw*73s(E-?+Mcx+!$suNT$w`V_De6aCR^C1UL|^58c4C zKz^!iF}@Eyy3(&aqy}ph*KSb<7%~m9!ok#mJf54H;L|$)>51e8Zd3!KS6h3F5)vP0Np4( zf57)1(o&9Aiou~Qt-$Oc<$XvQ;qx@04-&+bbZww%Tt~ykUqWXCjbLETX2#fbqr81L za@Z$}`Qq2kBv?`@`TgjpA$X#nkk@_Y)$UX-(RASqjYG?b;Cz(8`DlUNVS)1@feD)_ z(kJnsQ}bflb#@Ll$P2@Bt^V0k4kxDpV7;XXlb(6XxvX{{kUf^ba2-4M`aIGz09Jt{ zz&Gk}&=W8TZyG{>#Bm>#C zA2w4aXtmQ)aHdVdOeqysj0mVoR9@8hTQ{m8KH=Ly2&GzKmx_ zdP0ip8;ff7hj}_r6%uiq-a7*e5r5rET0$-Ig00&?c`3c3x!3CB$69Ge%7+&v8H~tz-vCgZs3jfQ zw6!$1jX?L@Am+4CZ$yn~Tec6-vDN2ax%2n{Fri3SDCT9+XBbu>9hW&3*O%js`h_FC zaL-6Dk{HXPFE>QuOcQgC731mj2Mme43Nu$#O6M+}Gqhexp2d8X;$HN~Jygh{Z{qu0?^PnebqlDSEKXa5h>q9Gou$n3gD4qAQ^`-I;)Wwbm6l4u3PQNjK`8 zyZdi&-TtIoe@F2Pp`PFz+wSZ;ic`u{9fsQY?cs#+rR;Tz!dW(H?OD$bkHHo1p4cLH zWxB@UOq3XyCyDoc(EBmNxRTseExUnOd&;UfU63O?gO%AL)6o`#7xFkgKaKjteA~z= zmMsLH3v-dqONvQZgYQ=!5ashlZb*gJ45^zBbjK{1`61HP@BdU#-|R+2I{*73k-Q(3Opv!=Dn zQ9kOyb_P#{&LJ;}CB{Nya$xaEsX^Ihlx5IcOqRu69ErQCoxdDZ@U-??^vRJBWx0;A ze+%FBIU|yH()vCyKeTTtUTmZ<=2JZcn0TO{S{E*W-ZKX0#&}%aL$8WsidkI}uBu0_ zINbzXtr)qI=(M=HIV>rjsEYx<(=>8ls?*`V1NRN${Yhc7Q&*f*d;+@%k~!6$XP@k- zB0Ggm>f|EP_f3x7wI&!l!D*AHwh@H@y*3uTw)A= z#?$OiofHjra_BJH=5o-Iq?iS}ac2qo&Omztu^d@3(*O>!hTZknS;ial0}Rbq6} zyxLJH<^iukiLs6Z!9Xbc50#9={_RU@2}fCp7~oUYRJMdR)3&~jj{uqNE}VBLZs-&6 zsm}z~Q02%;Uy&NIP}#HO){W;qR60$u+#AB07R6+EXMj#nXQwg@dTzR1#O15n7dW9w zVLtI_YKP#lvW@fy%Lji6%?Z`2q_od>ET>u(gT82|obeG|9iM9Z2AITHv7L8?i1Ft> zNq3xhRf($$6z5-gKflGOYR{h;DSsMttusogrK!7eCEs9-YcE8ZTiGY_3WWqBZJ*+- zo=Y*FZCba7cr2uXKWvn?n-FK01oz2&{(Ymm-QXnMx8@qI!Wd5DkAsU? zhq0c@pFrtp&bjH@nlvZuYAGwS?hrf^==nbyW$jwz{E>w7OOp22B=d**8Xn&XeFD`i zaQckE@eq7Z>`8C{n`4C5p5eTZf%>-BNchqkmiOLDc&?O6=4s#4IYVakQ*eGPj| zU@7UEN$pRlohkJ#NNr~1#@I6|e4>o8-dLmLj2fR9AlO{FX8C?oyRudadzg*QG@PVU-G_bnfb}tNQ|%TiJ9LrB zwZ1!D5AkEAAjb6JZPxp)ig6cg!>U}>d{pi#Ur`xqm_ScS9@Oy8)Pz1#A@!{SI+kHq z;Y4(|E4P-UKhO)|lf`kZo;4osV{!MBjiW*SSv8`YE2>r=jzr&#(fv>6FhQ2K&?cRU|zla5Ho; zzz~;VeNZ!gHv>;Uy6rBV>4CuG4KNBoC>R^S1#_`++(hjM<%# z_0ez|mH>VllFnT|Z=GmodX`p8fzH)IpC^~8yv!7-uc80#Xo;EiTUZ(YKrc&lYv~=S znYBqv*+Pquu4D3bIbT7t8CgHTji}Q#bI^z`5p)Ezx70PC-h288eXj%V1tjC;;N{RH z_?sm?@3~3(KZHGXu&V7@dZ!K?1#9|cz(vaHn7-dGlIGVy?=m}d3pB;&!AU@oJ?De- zgovJ40TlfC;Nkv7V(2s>NAwOVXZ%2>Mq-=~zS{2)Lo>xtiX1#2+&Pl|eDL}HsS}IE z@NvQm{R|L+(tLmLi?P((`mYy5W$`q{ACF0&(r`J`XQNZ`*Lo}175 zgU66^d_R-ohsDfj4XXOPI;k%FeDG)erj4A)nrZbJk*`140sj_MhkibI5p^Qz{@@Ep zN531!(iiuWOj@_6Qs1)NP{SD3$_hfKw4X)F=^PG_DxMv`C{vb(8%>ca;`^wBlP*2+DT422VkKl&6^kwp1Udqcb4dB{L7uAJs1a$ z6`J33se56=>C>FdWC~XlOA5e7-%~x?x-=llM8JvGT?~F3}0VJbq>X~q*e+&Y{Glg8yaJb_pv6a_fN}j^;DVLdYavYuQoi_ z&yeT(@wW81wQjb$P|4FPdY75w)}GY6f%NX}rTnph<15nMfD~CyCi@s;8uE(q!iN~k zm=Xl8JgK!h^To^>&ni#7)zZ7e&G0W~RA(mJ;`^EC_tUdF*z)QO`prZyNtJnTN&THw>b=1> z9%vqx$5{sLuz2nS{$6?RY0WQhPU>gMOH!t#yvpth^<9GWD`SOcoArisPiY$ZnaZbb zHfnpd`&jTZ^s0GUc3+$3NVO9qk(zQ^`zpInOpCDIOUUsF_>j`W|-(2c$?z23=o|E`(Byb#k)#Jf+^f}I7jBB+$0K`xL_6#_E=mN)I%-Gk7 zU-aEpvBbFzz7Xk3rLc2YtKc(s2&=1N4_4}3g5;2@TdKMP-ix9F@~AQ=tZxssz}n#e z-DRv%b%*D`r{R97eJ?Zud+o#@r6L*2OCIXr8kyX9UtV)#KOsWU7slGe&%TjuY)E_2 z8sE`~aTVZeR&I~sJJ}aPq090dXul2cCzuxD*OO#jN)m$Qh4$gVDrKIdj<1I{s z5PU0~o4m!2{z3ZJfPvB5H`^(m=QD7Kw5H^M6;{o@o7}UnzSBGW+0V0(`fu z7j<5RG47RxxNfkiM1#+xJ37RTn_}Bg3}%f>j}$lgw6|`y-RzWgygT|bl6kxk?^T@`lkCuCw3669E6Ppe9U+YlN0-u=nGw#^tmhD9@=lD@;%QMD}6JX>{9!`+GFUwJD(2?^u6tQ z-*W_W5j)F}w0ECpqU~)@K{9$%U2scSyF*)1d_g-8K#(6DQwP=%njKwH{0-OhZ304+iHC3&CgLVO4UDk`z*Gyfx1-Y|oANTfZ-T9GF#s->nvu^djOj7`$QS*%NaoQQw7 zc75a8@BfBg8$UGAq*^&Og>_vrftZ zmcE^qN6%pkT4}7vzL(A;s+YVAIt8k)C$p4&AFNTrb5*qc;6}N&9)v_4KBTKJ}?rVGc3O?*rLC@B;zR^lN$}s`%JnS9TC>y6d6odp&}dKU zb5Et-)#UKP;@nWy-+evmd{#0^+!qD{3_|&p2?nji@%C{ z(pIfi`CoO=^fd3C$Z@B=5&1XTdu4G>dcUxL0vTPSIezG6uq7f`L;(#wdr6<695wjBI;R+5~4BUxqUoyiCoK=?#JFhnRh&F_B^> z3gh7g^8|Oe|6VeIUt;9ifxTm5oHBl?F~)lf&S+6MN!rli#j$*trP?wKzb`2bT0+?L*@eThbg7UIIS03B`oMZ7uYcr>>UqIh=Qa|Wzz;2M{ z1J6>rhCe=eoUb$J621*S1`mkao!l}vrjV{E;yCK&wJ&|jdF zly<9$Bo$!_WHV6bQ?-!1`@mp`Z;yr+zQ_YO$*d>foF_~v6-HA`TPzoH2;1W1`9 z-`~O)L6n`fn^CuYB8MM~o$AuT6=K>i1`gDG8|)8_roC|_ZRGpg;L~GiA010OW3WO@ z`}+YY$~_x0J(^W>3(B20k~Z@FEqoD-mJ8%P*yw1vn!zG5?cRYJlzV(Et$8GE>+JVq~J_oLX=3ScmJIZ(E4?Y_rS*AyRWu4RU^VFI4Zy_&G%%I*OrNE=o zo-qs@s$E}8a6X|=^|!(2Vfm=XXr)JdNFqkUSnhuc-C%F;{FeGIo19T2v%`jcauQ@F zz|!*7NDI9d`mi(jC`Nrth?b(W%R3{SrN8SXZi0XAty4Z2`7RRqxfVvw+k|9T=-gk0 zJ??UR?!{*{K7`z6iTG9gtS*jG_~p`jYBxjj7}bpP6aNq4{paqy@e?46%{A3!3VpTV zeDIZFUOw#$4LCvG>z2h$ZQldrL{#qzhq>l+4fb{J}u?WcY@+h|?fu@4?6DRaZjN5a9!hUNSV{c81l{jn%1+2#*|W9qu7?&zp* zJAW-7PfOFuXP@@WgRg@Up!VsL$bnnAp+6d@?&09mcyqkwHP>8^veS9JT=T_TaCXdv z968Z9*GW^S)Xpz#v_|{PHPgiUy*yy9S%k4&4nNWr0Y;(XtK{3hc%z2oZbm*P@VWgG z)^YpoW_WW>g5Sq#i~;ztpbsdr6N5kaRml8a^IM6X~E^$nOgFhBf8P zb>@~c=(jsfM_O5f#4v7zwT{l2dBPizOEd}h63P>&tLcJ_^6#BAcD3oVRlvMh#d?;GE%otE*AdDCC+=mSQ(W23Dvm++l7#aw<&2A9 zn5Fiv-~re%FkmuGYVHd*4Jy%^zTjMNC{aZIUj#)n@XL^Jv8{&_m8bFf(Z@hC+sDt zoP0IvL-!NmVEIs0+9c6m#p#=gDf+C!!J1&3Y?k?CkUp1zn~3qYY1PMJ_lUHMfL%C% z^^vv>@7CgXz(d|9pJbb}aqh%@GI(2l7(Q@}HZPT_4dXpVj5qk^;G8*+OE6vMeG4pn zk2BiZH=Q!Sm0HuXU_S(F$Bq1N9Iute*OoC)CXWHbWM_<J4O|2t_bpHB{QoMbKgZ0A|&_^HZ zX5!ZSz-Ex8#z1ml&;8K>LZgu1!4Hj#)&Qe+(;<< zcHO43O%7$P%wIH~_5XrN5VFXo!|H%6E*iT`Ci>o9D`9bOCh*GhNEGZwNag|;jnxJx zV9aEdZ$a(#Eo|nUBk}l+r7oOp42S{QR}ssi-hX$0y)mkVF`VI@wZt^w`#&CO32T)2 z_>Jo3(ps3$`e=?1jO0P|4%Z3(|KsdU;G?M0wei||OFE>pLH6_#ARD0}0m7nW=@dzK zFbFuJpay~(bw)a%GXY0wzy)=@0|XEP&VZugP8yjZDt6paXXbVz%!KXQuHh0#yAwiH z(nx~Kw5-gBKtgFa}VJq=%6k-!0=;V`hxnEW+sA z6AeD6Yj7?0ZwJ@&G%ThfxEs3_+>N8bk7G5bCpng` zW%B1kf_g^oY1B^#9bJ~C6O0jU- zTwJY2PMd(g7F-8|Z^B1G8!L1?LsDzZg9)8o!=CuDSiO{z0nEpvo?n$eQ+`r;P8xj% zpNagK&X)2>NhS{^%&hs$_hjciBD<~u&5o?5cy~*A`0|O@S<4g~)3t%Abp7=GthF>> z;^E)@q%)c9bT-l2*Z^dPq5~+ovOSs! zh|$XHbp7hSFXj7OLU0)aFO+>@X-PBNgV#9U_T{^^EZV}`aM?EZ^ST zjPC%s8tFLfpf9w4-8`S!vRP!e?SY3(cp^o(<9)wy6xlY(8rSo|c)_x6kB$)ezixT} zeaZxyfre$<`lhThAd;{(r3{F~Y-wP#E2(dcen?sgxjh3wmAWPi_HN*9w9xJipMT#O zG2IV8@BaEGGvu8-TYix>f1I~b)SiB}X&bxnVl$uaslDhb*cjFr;!qRPh8^zsy z%oaK=tu#Btq`qi<2zWFSqLu@H)a@K=DI5QqP|kS0s3D*#xO$TF~=roAgj}8TY-ee=c_wb+t*ab zgPv^Uo?6EEGeoDo+?M!wY8ICl-ElAWj0cS6{n}wP0?v1!*R?Xif0tbi4nb{dg+wDe z)##=(-4mPbn;+)l-1WH~o|Wc!H^~qVxXtc(jE?H88~-1tbKgqh)PHM(b*opC&-zxD zA8_ADJCng6eyW4sW0C+|$ph{$<%a!va#HD?Z?oo?OHJ;`De=7?P24tjZY!H>^x3O* zo1@Cpy@zDGp&WBOs(h@sQb~*V+3fL6>)O=tRN~DXzJ8A4t&$1}l{#pGe*80b5ct;o zq~ea*n%hpYlM8{FBS{a17aX1eTgBOjt#%-$@aRD%9(V@3b(!8T<#T@8_kd*OHx|*3 z3jWFXLDv|5Q3ab@8<+~&Rd>%+U%Ksp+u}|@YprKtA0Cknt)!N)({=EL;Y#4BCO(9(Bowc#k6g5(=L(>?;4+yFJrQ9$(6}4H9}w09#qT2Q5Smjfkw$wzosmeF z#Ah0g7|+H<_ys227mGftGRA8Rr<&#J(inRp){@q7THX!=ip+F&0BFAa)NA<9ojR;BVAyK&?+>O3aRuW#va8i*!i)uq$ATqHWj_-j%ERSM_a$d= zAtsJ+WRExPBJRV;8Vm8eBKRWdJGlJuUPo(^gX?;qOSKuGznIIArZvNVb0(X|pWYu_ zgs)3DeZx#`ZhVK3KgP@D>%DiiMky!^tb)R@wJ#kI4)m)LPb9Jvq%j)tKO(K^V;%v^q!ltvGe!=Dv$H0Om9&d+D4&Inc>>9^w@=vQ1$ zaD*}NT6wixIA;_O%`>!7Br*p2SSQIlVGp;fT4h+h{W}j5bB)hrw3~8} z_8;LK;M*CFO+>2J<1kP3PEhV@&1P@5a<|x=;k77tH<**XCgpC4Il*gG?v|Oycr%r| zhs`=~2JSfDcH?1_w=)g*yzfmjqW7TwWIP$5DIPcMAvYim^uwwS5?HO{lj3xgAb-!F z6#vl~#VT#e4&bHgRod!HtTte0jL!oL=tubHn&79@0Gay|=&El)+Lxs&ZTTvdb`$&! z7ym<0d=9lo;*>99%_-hk$qye>$QD28uXiW?Bbqpgs3V8+IT^fY5F zG-J#A`5ub1!-7(=dn~QbqffXwE3x_u#PRSBr8%-3Ym?>)hw~P$I$ATdFCT}FfyZ1S zs~yhqE;J|3d1OoT%k}UJM7rRpkj;$X@F+P~>})9CaKzxKH>a+Sg}-%uTWs}aymw4B zo2`dEBBHEdRzz1vJ9&R}wSKd<`Y+IqoOLHSb@p=D3uu)Z4aX>E488CE1-#aX`}3dk z+Rs2w7@UzJ?+`>wV9wCQ9Bqe56sjx%W`N{+Toqz$dkn|+;`ezZwVA=GIZMrf zUJpsa>Hd3ZDdMv`aR%2$dK`#V=^-b}u zKxHan{m=qvA^Dc4*4FlK?qv=qVkZ{vVmVX8zm`w&)w@bpN=K8iG}7HFU{EYuPi+hsXINHI0K; zCTjYP2FM^gWOaMPT77`mFSw|OeGEK{yd`U~a=h`auRtG7wI-t0qQ+?d80@ICfy$5z z`y%p3k)UgRTxMJ>taHKlD*qc4?mD6;Ap2Ur_vnfgpm%9}yVovLa7S$5o#y8X-f=)I z2x5IkY*WZ@vmE=0z9Zrl9+9@~dZ@j}##E#(DPK|+v2396NdZm#Pfr^D|K4LbqJxGw zEPWLQRy{E7Xg-FeGoY9xLuZw|FO^nc{0X^udAp_gPmD&QyS?K@8BVSnvoF$ zM1eoa4>V0*OIp2W5N}nZHl4UR^Cgz_DO;zQ>dJ0h75GH6a>{#M8{#Mi81;qtmz z-~FvS%JpYdwtU(T=NvchVfo(A7YRkgM{F&!)B%U%*of}XaAccoDrH)K*~%1S56OPG zJjzFL94&!ueGy4JwSX?_q2bbPi`zy@Ylcfd(AOS&r5wYkf3_~TqQ^C;9VcwrR(;tmba7f+Wh~yy#@1e}*J!*(aSCuA2v>4m zz{NBE5Y9aRB>o7vb<~D0auDSK(Ne~CI1DFgRWmdT=q=nOrzz2+i`MB?jzrIU!2tVS zFqTcWk@nzspjeULmjM4C2$)Uvt*q&i^hSuotjQ5CNiRe0NV<}+^f&ZPiPATuQ+(`D z+%tlh1X~PlYqQ8VKO>jA;=MO2J~5>{4@B2BttxoWL0aR1Z^{ICM51hMfYI^(k9tbg zjK5XX1~vRyUrjQ&{h1 z=j8kOKOQa5Ima5$%R>7<+;>(+pGcEA;HnzYhx{@BUv*<&-b& zIcBDBUeAYIOfXr$!WJ)U^_qZ&D^-v&SZ++~M%dWUX*mu!#@hCzOU$a}Ho>bEnLHp) zve1y^!Pdb86arXn=7-rCVfW{qY;g>HG}tL|b);Y104YdxY_NkV{K?Dh`MmsxlZ^R< zlGfRA8IoFzGxUzMKh}V+oN?s3n##=ab^Im&?MJ|k1A{J5D$Mjg8!QmU6mT8S2J;2I z|Jh)fkfJ@GlXy5YX5C{2Cp&iKCdNE$}`ziON!5v7j?RQR>}NrZrUZd zh0%UN$z@3(Js_ax7vz@o3_-|2bPHD_!4V+{bx*itHwlV%IHN`14#SPb_$tKHt6_7t) z98wU}vUhbthl2k575E!3_^nT{XPpFZll+aK{f`Ef_7&JZT)-ao$Q0Ofz@M5pO#^mi zS=tq5f>w^nAw-4~?nFpt84K;jVQD5LGhu1E;#;@}aR)Yt7?nF>#2eF>LQjoZt>vNJ zB?$(TU+#_ClcrXk8i$iYNE+M6iL8H|%oZqTcyFRoy1>8ga8{n?H0byqI>YP2sg88W zrZc^nc?rHhVVqc>VVchWC-g4s(@zs{$E;8EXs2nW&7EX8cSfv1l#-0RXpar{%G7&o z@quKVP9dviXDkx`+*u<6Tft7hPp?a?6Fe+9QS4oqU(`49TE-adNH`LMaRi^&ov;#` zOH)YNG02N0t+khotC?*JjI7CwZ-c%8)_akC4l(u6-(l$iB~5dLX%3@b?gMrmbXg%- z2!J;eKwmyr=*#*(&ZI$KUXs@J@j#Vh%yb{uHyi^5_xt*$h&(7>3EtBI$|K`FM3;Hk z6fvenve|ftF&cTFc{p%uEMjSer4N;{c+Vpr87J!P!FLFrra;U!hIIw1pi1?lPd-LI^wbB+JCs=C|M0+<{+W20b&L4e*Nngy1xGPri z7w^!bOtjf-Yq9)Y#sxya9D^v>tS?c1Gk<8mPa< z!Ind+NQ1pW{$bhy3uVsaQf6qb%n#4iY+1lurJ0%~s}xMJONcO{Hf>PSl4RI<^gz?I zWhU%XrXr3!#Yn<~=I&hBR`7}y0Qmp64aY`SNzd>qAzA5eaVlci&`GNHVl_`E zsXZD&j1_P2>L4W@l0K0S1sQGTS)+pcM6~A|?A6-R^PpV{OMeevn?ckh);k5?6iNFF z@MqmwigTr1>Bai+JqEt(qa>2^!kCEq^RXn1S5Fy@ z7mxAkfhH_6UOlkUi;P!~R1=PjSC2F=OyfmVrU!O@Ve-$pYLs5XC@Hmqm!ff61G=AV zEU$o#Re;t&a-GqZjdc?RkBk3I&oC3MF@+y$g<;|;4LF{g)Vh=5VZSPxy%}Z=N+1pr zWR$dL&p485PiRfzp<>n%-uhX!&=wuto;ZnOm&mV`P}Q+T{U9!19Y zz&V^WgDUJGzXVg03Mpl5G_Zx?g+6G)=^5TaTSiKSB}W7$)I;ZIdS?U9edlm)#hfbp z0(PT%QTc5P2OG<7Eri zC4dVxjB=q`_#~PXF7$Z+oj}lsZ@0pS{-E%ow0>Y8hQ7VQk_f!jV;FM{dauA0mfi{L zU=5@V3EgDpwk_1#?MvQYUJJeYaV0`d)YcL)m>fnVQH*T`a6>&<8>or)kUxy>A=H-i z+8eWl@oGdVOdG}Ov3UR7r>z@nQNyzA)(Tic)sqi5JN>fz<6wyv2#v~F?eF2b^vInr zyl?pKFX6h(S*ASTe$ni=KtK6Uw{DUq$Z3S2Uih3mBrqpPmPqGldVglEkgYD5;uQ*X zUQL1ERTtC-{#_-UhAsPe6MV4w@$7`!{zv5;yfqVZW>2^Q@1nb%VSJ@E-3he(i3^oFWo`xG8)vJ#zO@m@WR+t;2bg(|n|S34O;JV9AaVQ(I#q^X^pG zEGYhb4e7io+DzPzIK*VXS*|&AFx_Ya<{0X{Da;l3V%<1F<7sZ79kpYKPg%b8P%9+g znyt&rmzPCv)$HCXw)XD3b8Y$BGCiL7fR%&I;cw3c8TR@vJu4v1Fbls}cScExV&mgt zwk8C$Y}B@Az5w?>)T;Q2y)$jnxB<=8b#YtZ&Nih6V-bvDw*!xu4-}2!6>sSaC7Jxc~1KjQ6IEM z!?QkgGbn4m5~Jk2Tmk_=Nq^LCbqmEL*;;;&FM9X*fR)!Z_qDznx#Gt;`V% zcGM||LmCGDWrjbdWtq4{e4_#l7Iw3TU(&>$g0tGGbkw+1 ztvgkMx9d^k*r6uOY`TjZD#8AtW68HKEd6$Xo}z}I?jMNqqZLG;K!oq?fp;D8 zowOg!92ns`d!*Y3u5g{OGzZs7`vKw~;1r++<+F$_jOE_v$vFFqAAHc4`0)BKd zT2g>$zcCaAuus8ZSsgZsv&=aSVd({w5UiLXG7-iJd!Sg zhVa(>M2`{tt)+raoAK@#)Se%%S8GqI9J$~_e_pYJa4T32%+m(T)8JeN-Wcj~z-@j{%}t zhKM!m(w@9Y#hxmhBlr_8mE!D_JtuVzGdcFm-73||B&6s)Dx(^9J6fYLH8S7Az}H+~ zK2w|nWH3|U`aYcTZ{u1j16y?IwJF{>Q8+jUl%lea15zr}3@f)52forVILlmuZ&N9p ze6~z=t6CC0am6t}_+pxkFliv%gBgQe0+p+QT?Cb#g?SJobCxm9Y6ss!t*Z)b;T0)B z1x_r-sDFq@k8>c(H|Ez_Wp1D9ADP?U{*l@B`AAen%sHu_7nvL*Iq6 z&oJ3zQ!cN&w~d{X7}UqgzDn#2h$*;3Z6ArY@pn%p&Q!t<{qRZp)}w^SM&m_(tYa`% ziDGIS(_Ch^h)#cea1r#}O!KwifbN1sML5Hin9PWe7G7DNTu^+@1Z2mM^w|)%cZLHR z7Ts=JmB^d=r4I+bl>M%%R=kU6nu!+KMLLm9l*jn#X%VQ&5czt78}5)9P}>u3N|}$C zq2uk8a$*_HE|tQW3`u34yn^_1+`$7to={`V9Wvj-?BIgYJl9epk_-brM*I|UoE_ec z1>CsmDh1)#+LsrE_bJ zBxaHpLU&fc_cF~I_zIw{?YV+sEWHS@;U`?-1 zXzojfe&`x_o@%wFK#1*^elu7_l7lr&^HyNVl#5!#wYxK{@zWC`7s8&J0r%A&uDvv7 z5taEW<1J7r^HA5?gg`QUiQh8<{f}K>rgB4)Yv}C;CO_tkVUz=kAR0VjT%I`xKJmbW z?_;NPg_@uNey#?U06l4|Z-l=mKf5{8f2*wCE$;C#T7a3*;_HEb~>MW=H^{`f* zBHoKtOed2|gTHiWgUf-yOzWoIzc8-=U*ym>IJ8|=qic{09c?`tar^@PkdXQSX%)#uSdT4#__tV;lwEud%Ye0@ggHs*b=MYkQaHtu$6@%N+kZ1waqA3&Ht#1Fh(r2aEk5LoO=>Z{eTnBwtzXAdm5z02ISm%iseX88NP2TH zLOmFd25Xh(`~#pFw10d6IzqIX=*e8n|+@*;L_LA zsrEs(gn61G4~C^xO6e;l=M4~dPo=3OTcRz#`w2)M`!7DY1kaH-+%Wu`SxVi71I*KT z5793uA7`?kJ zUzOauM{~cEm6`N=nlm(isQ({3lqnwTE47}NZ7v=foRzv~<)v?mvVJ42 zd{L&~5X$+buxbxQzvTDe{0A&+UXHTt3iTjA3unorA;kLthl)0cM4g_LtquEeCIU_9 z*M-Jyw4#td(&e`!JS@o!sJ|xtXSgg;#B9AYLwpzahu_1w6?gz~|fEO&h)6?s-keK`UPY z4j&PrV1rzNNQx;1YGt2F^jJjJvSL`eY^o}}(bh86m2AxKI<_oMuWCuxUn(zSi|cVkhD8IO+bt~ zqMEY@Ns~GtT^t-~CFr=)suQ4Vv%!7E;r;L7Oh*zlmFQjDyw=5*UTkJ=bc`cwn>syW zzOTCUAfk@3!@;N8wYacE=V#Uak>siKm&#Z+Z~N z%y=NE*5;&=&2H_bcJNxilvP19L(;H_D z3`zS3s>J;nSDtqd)TdV=;@56bg>{iLbbH}J&+YK{F*4OkO4iVy%ahI>H*31)B`E%w zU1A(Nd#M}t1Ks2m6gJUJPPUy$-Ji~bAM6@XLDpe{oMK2~hi;!CcyBMv_oYl@CXDl| zg1i>U3_(Hn38I7_4DxsftwtaX%qWGXgzneN{A7|Ub@{&ToS5NBBYut2*U0Sj3+a*j zU&(wSqQpVh6OqZ2y&&IXNYai_Pj7wtN5Q!&gZCbHS{e)MjuMfFozRdp zSyuaBg$-V=cvt$0v?1yDgU0E9a{sCK;Z>R-t6{wbhz2^$qcT>^)<+J-RFVGg4MdOR z4ic7HPMF)p7B6WHLsG@>CLJhmE=^-+CZP73fgd^}F*x2E$6;@jDx&v7=I&HO)3h6F zjM+Y0+>CPafHP$_B$IZeuq8uMV8EhT<^i{SjkZh2T0vuHQ_jpG>7@{%-_di__J~w= zNc!X35r5)G9gkt9Kx+p-F>V8`m8TWSh844Y8zdV7yp6i0r$QRD0M3E#!9AJiuWL{R zZ3*2y6jDRK!kFp)<oFub@3#l&Tq4P0=(f@ugdGy!gs?`pQ{iG*%VGICj!5 zyX8VkZ9vfJEV`1L5CsFJwqX9D|EqCUx***lQ(NilS44WQU)aq-->KR)3GWj0|Fzai z#EXo)<*5sd8d}gHo%upaf*6JRDP>41R{GB>E?3?#P3fD3O6|2u?W$diFk905uCZya z$q~OwS3^=agjfcM3YihP-;evRhVS=4GBskOKy>Wqx|wbul0|eg-O?sVCL+A#Ly%06 z{H6V`F|5x42Zg7+%XE&-FxT2PDHe#)i{ejV7Y6lA05a=QNBd$t;L~6)j zOon9NXrb9_Egh0xKf2~fLJe7eTAF$wNsOyD1)>IVru?-^Y-;7x%%Z_)G2vXZv$UAj zdwm+S(_qXqy$tE50DTnYnnik>PB{@Xp2r}mGg=hey&AOx>tVdHAp;V)&%>rdt!KOv z(~#`ps3QWPWU^{|aDI^~+ zIYFhR?^_RkpT6PK#St6_=MjC48a8b24Op7O`LSMIH9OvlbvWNCLI0s`8}D=;Yj+dn zc_GYMEO=r(cJMF<;1@Q2R7VO9P1z&&49gk1rJay7kiN8A+N#JI=VoSnke5Uh@)h zEmpp}4}RTip6mK{%{>*|gx#Ub&`n+LNw77C`ucW+F88Kj9e3eNNK?GKGKa7a3jXf7 z#a3ziv`eLWImii2f#&>IDLF(`_mU+^Wgy zu8*UNQKtbKY>gIZY*9o3$UAV6xXUbvnZ_aM_C87@dbEfr+m=jt+w6i&Fkuju_CRWQ zJoI*@<-|P5KN8wRN7`oCj$1124%r|r6T7)!^EewjN=*;ruA$|)pVSP>1YuhixGOGWKWgc`q2){DpU26E9{bQMGi>m7}p5GO8 zFOm(*Wa+&@Cir0V+rj?W?TW{hA?S=1L~fh_XJ1+xxge-q(UtQi?`*vI?<@d89tx*N`5$dl;)jujunM z<_np}gXt{o?zhNH!SP_0Msuc0JRUT%JXX-4!q2&i4_8U0r+0 zP(K8JtQ-B$2h*52`1+-oRWF3A#M$^}y5EQUYliPz!j-nLQEwsJEFCk`bRmRUnE_w#_nK`CgK;F`+pV!_b)!b)g>Y!*{UL!_u!qLgD&L!W+?a z3i^EjIKU%5C1vn+9fTbqolQvZ9|Kteu-L5@^Pm(zNV}2P%Aj2=r1iOw+YLgGtM=o0 zXXH67RfR}CN_^xvF+84`kcCy80B-B43w2CvNiwuWGhi<~LFt3-a$RPTI1%@Q5)-~o zIlF4jPXh&=-3AKBsLYThm%JAok8ux6X{edbP4bbH+LWrx$(#qgsS_QLcdayxZJKvc+mN7WX9>;&HP0Q+RgMPPv-d!(2?>+SIO;zEU>B*46ap zaM{T2@dpp}3H1YE;*qYI@c$Ph?f_%mlx&dM{1X+s$^oN`h*yX#3Y*h4M~w50*D={U z5sAeJjsrF#+c5?M>5k>bRJ{8doQhk@f2XV)jDKhcB*SZ3$2#^ITX6FJB9>_eUmUs@ z)?^<0U{-BQX)T3@ zZ=Rj?&$G`m4oZI?AnfyXVP?YJMy;s?rPl8&G_Z8 zjNAmN;h^-7klJq&RfsYak$QhVum|Nz!E=+1)hzJF)@V)e4*qjQ?)a>WkGdpf08xF* z8ctlEz5r|QfxaYs)1tOySV=^pl;C$bryzcHJ?Io{B-m!+rWw})@n*bH16#OT2H0t3 z1^;wE?Tg6I@76r&0|seJsx!jf^|Uj_g{y&^2%nUDtST+x^btlp&6y#rAyba_2p>zmKnQ`FuN&3lqSHW9Uv8|i{pHWzkX-)}U z(M)3s^sUW<(*1pi6f<3081S*hUw76b63e-f{dv?5Lifxzyfdb?vXVJpDcVv_7LdJm z`8n8YtGFUa=AyRA?3S&e{{B?kNl3?|qG;!=y?B$3nHX|ADkq&thJ_*D6{V+K&0p?- zUy|`mV%4MN#uH?Hop4K{H(eGEMF(P|qr3PtJ?_=PlhK(b(Vaf>=ikgY+9`rtk$RC6-2QzN{vt2 zX?6@s=8#3a));SU!c2c-;96sXX(QI16*KZ6V#PA9$-n_zB77K(6|ygWdtbH?HJR!D zhwIA=nt(cIR?W)aKDz5bo0_@SIM&pJ8kseNQeXeI#!S=w!%y9KnqXQp{M3b~LX&g& z>03NaH{Gi|9fb7eT5$09*lm}X`>+oCZN_ZVUC^xzN?zO-nC`T%8!mJEaG4L4GWANC zca<{B?G3|aZW}J+R?6I>lzCMtvsAf%0r$nGo9qjQ%ilO$zC|g2gHmR@Qht$g|8Gk9 z>+L0e`pN}L+QUlO>+Gq+b<_;k(WIo?l`^Z9I;!mH%J1eWX$}3Nomz*Mu8AA|ZTawT zZ&rR=s+3#YKNsZ+Ow{R*GRm#p&HXv0Vi|j!NL}dIDx&m6qrsXQ_ z9;|?yIh#^aicOAUWE?N``ma3$mZ zx2W%NT>T4GT0Q8C5m(DiD(wrneg_-vZRCT7>m{6T+Hjq~^(N}pfD7dVS*&`dCKo%6 zi8XD2T^Yj&9s|7Go%4pUr*TaSnG9KBhXKBm&Uwr8)!r457CPs} z=FRji2MT<;J>9V}_2!CnM|q%*OLe9Zf9kr;ywRECuV^v?K{vtCo|@oTQc(wFmn45q zeumFrN%ogFO@_ziQo|4!iDw^iz^QX0zNJ-~B z@>hH1<(FTkb`oBOe54nCKpMtRtu=Y1*f+xq??M0kgMYQD%!E)D$2bq{p96gTGPnlI(e z8;)CU0&0x0;ke8=FCdcg-3`WuUsQh&p4SLX*Z0yhkl?aUvnFFh6eLug(sX#bGdXty zir`*iw0e-vw(LLDc21xC~U_M8Ur&z+(E=0X$(vE z$_xB+?1ZI~;B6~Rbbe~b2p-HmPI&CX_pzZV2UZ_Lh>1$k>r%0p&ZT(ymJ{m4Q@QrcSK=Df2P@>283}b?OPdBu z+qhj}DH@s@#DuLQeEjMD%TguysA>K^8Xlf4%rK8tHhGGDTXbJv-OkV`0L_p_rVuU2xRf8 zSuA`ogn*xOXHyOoWfXm)BPd+vPo3ty>#6u5CQE$;YAz#tcpqJo= zOhHN4N9&~`lT)HFHbR~SKU*dS7_u1+nb2ZH4Sncd40(?I^2_Gbx}t`qX=ESV4O;6w z2A&$R1G55``vnK^A|Z_-n+5n~l+s$FHE+O~1^aBN!3?cJhzag5-|SgZ%Fcox0MC0% zFY@eWcXy`})3Ns7ntqSi%6d^-$aJ?MYR1?=B0KW$&#aF5Gy4+bSV!ydqdK$LmK^~Abn+0YJq99X>N!uHUY#pd4EA$5|K2T!_wnX6-`-FETssZ+em4`Xd_ zQ3uwmt1qha{+2;Lg*#<#%TAd+qzkOqIWFpQKdVeR>utp^DaVDJEgvi8w1M^7>WkVO zO8HaMa2*p4!8-Kz%HwC%{#@~!&KyzhTp(UA_I5J4OknW_O`g`P%}eqUp3eLYnkhW6 z3pu~W3Jh_+rRkO?4j9D|`w5d+d66@-mKk4ZrYQLgmA$EHBVvkFD&=_CHJ2f-8kOTr z4D6Ck;)&GnI2IS%IADTmf351{LineY-O*}cU3A#ZA_pG zc|mW~K|)UJmR>+aLhUY1%O;$p+QIFA(8cfzt12oMRviYeC=Z-V)t+YLy|3hPyt-vk z1#*C5$r%3H`rNu|du{_eI|hDRyoK*Qwy5Qy2518M+y&j|odB zfg}qFIW&1DQD@ob7Yebb>huaC72gc+{qfBB&&AKglGp_j4~by|D}$ zX!^R+asj9ktah8M@#}rxtR3MVj@d>zwHN;o z-wTO8SE%+8hSFH?BjpDnLrn1V!znRHIf|4hzsjcdlP(hRLz&X@Scc9p(CxJlcfYl= z`7B$gM;%P8;3Mpn^_TMA$nvYY8dN(%a<2jXF-FNv@_w^6N5s2Xpu{x8I=DL;EBdZJ zmH5rt5|O@(PQ~<9&VcZLF&%ewz!`DWSnS|)$3mui)lG4SQuKcv)aV@&e0kko>wzgg5ad6~AgA85*D z-CtO~{>4hu4HaeGCoDTc!S1qd-}rBSar=$8Ry0)X1d2Z*7z9wWY56jCCZAga)J!(O zrA#Z=W;esX)n!6tgJ62v%2d#$Mv8Laa^GM5NNS9W8&8)195nFXq?-NOY+%}=G~xmT z6NgK?+<5A~tNJ6QH2Dhfwr5lKxVO1?CAXwjxt?$(`BBEby!zo(&Zc*5bMJ9`lfOXD zlP)cCmR4^>=_uFx$?d6j*Jc-X@8TP)7?aDK6<92D+kr&1UA0}<%S`xIP;bA!hTln6 z>MCGrB)8SVdhKI=SL1=8jy%E--Lp12z(+5-7@dE+H&NEjA>Yn|ejcaHC8x#)!qB^< zxAVv`7POS}-fQfP2{;0VmzwSYO<>tY@bK37cJyiYr2V=sw&sH#9Uq&|1HGU4i(h!z?k|fdEjQoVp*Cv|nr3DO z^stJ~w!;=GVJXUxRXhW^GB|4GeQj6+Wv6Ktr{hFlS||j^36J{Nz4c^ao)3LV;LjVV zRs7!ci=;==wljg(H!#`4_Fr|c8J>4W$#LKGn+qkieJA&pq+kNEr%2IYM?_xED$ z5UvmDQwfWOFyyGcRLA=r^i4~k9lv|%mEd+rQnO+;Vpa$B=+eqGFKcAbrwp)%=}WFJ z*I#59(sz|z)U(?1bWhDi4qv8k-&4tcfl+F814AU=IX9kGCF{%Te@uR(3K2|$48{(q zVa7e1v-&p<#Jjm5AAM6L)3bELv$&&CHv4XZPS7e(H!!(cPrXRL+6p|a{Y_sr{lU(5 zZD6Z`OEcZTb$!e|i#@5?waY$LDP0OgHA<}zn_Y`s)Sn5ydZ3?K)-G**r3unip2JCi zzDVPBv}K9#1NBF!hV2dXLo^RAl8LT`{Re$VnnF?3!^lnR5&dzx^-0u|rh^sKZ1^F- z=j*(j*j{syhlh=-`8U9JqM6y!NV4QuZ%RM_jvLBDf;=)dGvO^r)Z@(ojqR5XvK43s z&q;OxKvU>B0viEIa`*R0azBj;VZL75VO|^GRu7c3nch0bA!ZS8T>iy73byT_Px;PC)oZ7N(=i6 ze^k?o))i|Pwyp~3*q`T}*L``j1*Ys6LBfiu`v+O+p=(D-m z_AJOr$NR8GoiqyTFa7%U^H{-pptzlI&jpU#y{{Xq$03qA7q?ZeG3+j1f9dwuldBmc zWKZnoMs`+LC$tWRx$$c&9*?J$e#7_l9BZQ*YrhwE=~8uW)5WhEX$}p~PB#xrM|xN3 z>ogCzPWagGO?O75(2R%H&d9p?E%;Q5O+x$7oH_p9u@byo=2R{j%VU<-?5@jKD zbeyE{3@6c&mBY`#&;klHlXIQ7U;6XF$B1H`cbd0+at+xdSR#_hX{z31HzZ8^=h~Nb zNnS253bA+}D*}E7P+U5oM+i%Q1r;cmkst_CIV2(2JpwGo?Wn z@FC_p+rgLw|GSgazB$Ia3f43g*5z;XJC7ZMH4x5ZW)19dxQ-s_d>?9owM-Ord_B@b zC=sC>yaH+zqp%ij)k2F}_eee$lNH>(gbW8u}1Aqr>ihZk;-^fqj8)vz)$ z%ub7g_1AeWU+_d(wugEynZyQY-ZKN6`<}UAV5zS&ft0|QHoy+D2NIF&w$;X5+_ek| zexrLe^uc6j3@PexiQ@jF%>C9}AkyGORM8_n`fl>%h7Q*9c4>({wY0k};nKsCSNhIs zZau{or21TitZx;Njy4u9_BoY$?*#_=60e8R1Xr_0HyapY^M>mpYz4NU)VpBICy`85k9s+>4j_a=)=(t9NJyJR~;{htIqh;U|= z(*L2smE|hYRf9sXeeymRwd>&sk1z&V_koMtxKearL z+T64qTvU#z4JB1lGzXd;tNMOrq_Q6k#&hUmd)$bv;I)5hL)ad+KQaZ}TXl3Y5eD+M;d$Ym09CFD=Tvszs~+FIuD?Zqc&; zwMCA9X;H=hp+&jFE&4yLpNWKjHQd^(*H0Q+`#-IpjKGEPf46>~mq*r5|GhfnC7)e_cTi8LJ20e(Tm3kFK9R(2V@wub+np{$JKlWGoCv z;>37wOXfB=m&bOnR=q#U46Cl`Auk1Wo;Go8!`6c7EJPIgN@L#p7u zVLCaF;)VW?bg~<97$S6XO6Y&1lg7}`>11-~f2Na=nd4+)s7Q7Kf2{$Rg30y(_!5#i z{q~cHtVvg;_(CvD@394pDZ!cU83_C z#RQ}JRN_yVFIhQE_g`IiIuxXmVv^J5z^o^XPFPIf zuq*PcMyWPLgrdA0)OBj;#%i_rl~e?5^aX7>WZ^mGC-{=7AshB*T!ts*@BLP>w)!h* z$6TZN8DStaBWi)mZFE`y1<>BZ8IvpOoNH0G5@q$FqoZXtC`%CzTyDq$5id)FcvK(&FC8uIL9KN?AHXxsDrO?@PyJP+d96yGkWk;4 zh}?0=eX+l3IQKj0$v#6HV|lJo?H}o<-9xN(U*kwm$Mo4cX~a%L&N;&GQLH5U-vq6Q zYrj#YJ&4PV>lm&NagEH8M~3ENOgFo1^P}N!!`z_ib={z!#sGUfGjKnmJ<+((2%iNG z1HPo6qBGIx&I5}3UEurZiN^MGMN$t6iTlpMsmj<^_FI9C78%*np&Ur|tzrS%HuI|V z;-LoTT%=D#`lNoE3nRbya8Qf6a41jweT$LU@l+!pC z>0^;DT$LUkY-o%^dK}W_K0B(ZHC+S@9SM=jaT-2W%J`uFz zV0-u_qvG?O*P{(qv|(r8=F!}($o;P~G2hwXoQ2ZkQF?vf zm9bbi*x(xJ(KT14-#d74v`6o}Dt*OZ&gzjKU3yjeF9r{e_Gs-@J!&7k&=_gww~{CP zh|;4^!h(e6CdG@R{!GCfOvjal>m=r=8Gmzd$-}g3<{+2zV26gCJO4@_?jA6T*Vw+3 zsz!TJKrh~TRWEKHp!pb?g$D+vD80yC^~Hk&InHYI2+hLFa@}bE1qa%DG?oS@{x5yS zdBHgYWoZ3=E0>Oz`EtPMm~Gotmy5hCloVxYVa`L5Cani$@q^j8mbH>B4fze$>ND#Sgb`A7CPQ_xRyaoKS}u31KC zgFi|823TN@+|x0mR)pM{xu0epVoqQ^4#F1dJLxr9)%zmOqeo#e8d<})4=_0kuIj!2 z3|;9x)xd;m4d`>dd}R*aIzV$!laTM63_o7#gT?ZewoFH4gqr(iJAZ;ze3~N}lteS5 z-95vm?Nak4Ym(Q%w?|ozbL1-Yv&oqSlX!J$N5o$Be)M)c2rOic33_YS(KZWSDUV2q)R|91)(%zq> ze+#8ot3KSi_9}(d|rcclSary`qVMf94)UNH$}~`JjijBvjNpS<7?xt+ag8Xj%6L zQxRzAEvpk9-#dY79>sTQbj*ZZVw_`QSv&(UE-*y((4+akVj$(n!6ksmuA5ID`6vWNt@+`rJLj$ zV|IWSHsQWmz6;L_hM(^=Zjv9uwZkZwS^TBEoyKO_g>p~h`FduPTn~O@liYy2bqv+Q z8>xjWO`GKPNOP5LlDFb7m98~xlJCIvAg=8O!?0`vzVEOh^tw$Lr&Dq+qQzBIz7=c2=XX+}fQ%jNOj=j7-G)VA`_hg}~kxz8@r7M)$IVC*|qn$w9FQ*5wl zY%W1J`ybE?(wID*;}W-tuXI&P%U6aBN+V{}bW5+w9|z}hovnlvs20`T zuR1?zQuoTs@2g43>;z%U?m_b!+TT}np4IRHNrne?sHbI-pOktvPvh4t_?Ab+c$q+9#RzaSua zq36w2?!E~>S}vS`b(j(j`Gp8iIm}Pa8~t7R@b7**`n#>ezhjl(J)!)LXq_HDSo5yy zmWt$g^FKtJN&ZyeO$0WZaEH3L_m1KWleiA8NJb0Z01aSFv+(_ffk{mbZXt&|mjhi< z{*YZk(6=_$H?h}P0z7y(gOOH}WnG;!vWiw(zH@%lc)fpIq~>6a5UIBw^%89%zpjkH zx1pS-ip)pl8tZdwOWlOZKU|xouJO6X%hE5y##XFOSeRHE^Zh967VrFf<{cmK2Nmvb0J56#M8eK~b{@uW;pA zeb0d_uT$FI-ot|L-`98qU*Cxa4Ul_rk!)`QTfrYJlqa z05OW^Ah!^?Pha(hZOR)o2|smO#T?{4e$`h!Ec;gzmux}$gIA?D$;LIr(`6#P@v8J+ z%5`gqOHM)h?E^WZy-_FcTN4@IZ>3ZHy3WXM%y?*?(R`!5>@)1aK3sI(AilW+f4|1{ zPh1i%oI$lQxRP*X;F^eQGOoxxB_8HlAOI2t`AM1yuTPq%YhYCrnWvivBlC2Fi^V*x z?Vp?TKu2Ze+K$P#YcNOI(K-6V;4BBxLCv%g&hbZ_dJ!`h_|@M^d82#r_gGmskMaXQ zN_U4x_<X=?>N_aYY$&6k)5ps@}_-ptcjAstU zlgD_{9Bpt??^AES8yew#ew5n67nCzfBGTPgrN0(#xQ}{27U?g9M$RZdO8dh(qa5Pc z{%3}J|9|Rx`N%ZKwE3w`(}2VTaFFsmgP1TIc{xD#7@Nmll+a}>@6p6 z$gn%cS6G$rCv6O+*EmPgSzm5dmOt0Ax196R{~54v>X%-^8lUc);K*`jBTengZ(@t` zofb#xW_XymfLj6_p^1a3j?^lqFd33=+B^EC3rEvXTJX~UV|=tfvX&Hk0^(#RW6w=S zZSkmK9PZ^~<4{J0cjY!kY~?q=4|Q=3AILvsUXT9+ znF;Io)lvRfl+yd6s;E>ltOj)EjKFKyfwjt;zkQeD22k6mjg8<1=v=iOcANA)tMN=R zf}KaEpf{&DQktefgKIKa9lK$t8O>{alWVx~e2B9Ny{^UjV!>Zf!z$0~iz#Zu7++pB ztl2~!{s-oU_hi<%qT%K`^W&)-o?X|n+IftkH0XR7>jrb(%?&H+QXk*5&b;Bd)fRsi za(Ex@y3yuTf4WjGdcynIr}w3p#MKq)f$y*qqy6KM6X%QM7{&c5l+zK8ht!uLoR zS4~mqHkWfEAJp?4@mLt)c*H2s`B>aD<`(A}Cx=sp0dFpPm!cN{N5c#WQzPYccj}O$ z_3-8kUMkZkZF)EIZS*~N!gkgPo7#_oX`ER_=U8jagv}Gh`?InpEjdTAsRiGpDw@fC zh^tY6=S1HHw{Y!{G-fEPu<~4vqBB%mNye98y)5m=`kLjnY-WorV7w^$^fcdPAoMah z{@5_+NMAk)Y@3HGy*!UzAWldQq3yvqsEAW4xFTN?&nFtGu(nLh7PKy0& z?1wvG4fQZCYNd=;wjYbJkAc*24EXrey2!nJY=UJr-Wh2dt*yJ-c%@INoz&+fV|=R) ze>Y*?L2vrZ?ueh`ID0a!g3TJ=IQs|6>^`%W?0dyYBhNvk6B{leRf@pITAD{~yq}s$M2H8Te<*kTHq#Wp>0|SElUNIG-*SdAT5i^ zs)eFcml*@-Ou%snn--TDpolE$Ak}eUP#UZQDi*~BANBhrsLzxFPL!DkrHV;QdvChs z`~KV%be`|?`{(!SE4}xgd+s^so_p5M@_s7=D~i&C6;&yrimD{=ys*Mn=`Pz==~wtQ z;CDCPzI<@9j}1kM%QhD)cUW}KsDU+3KeNm1EQ9CCTMhjpxSVjclCJLV$2zLiT_zYB z^|0(_cJ+&oMXm0Y*RRvG{o=-`8Cvy{MrPMa*aobR8lBsPd{>`%U;kIqUDlFDqtgIf z?e__PX+ghuPt@e*gri{hm}zW=m6QPQ)HB?%wjB5qV2mA53OPozsZT5!N`MU@d2Okt z^kMz__hK=q${XR%cN&(nli!cbWcx&6NbmlvDBJro>?UcfW~ZDf{t;gH;S;x^uBgAP z!M=fP$u}P6G@mU|%Cdw%Vl2%?zuJj;*allv7rt>1d`@Ui9y51r&3{S1_o;h-sMmC| zV1lH5mip{yfq0KZu@yTOtUEUni-iPCjt?SZc^)2pw@SIfo(k6aey4`ZugD2^4l>26 z4sRCI+gZmL@3H5EtA@q`p$GA-D|0LrP8`4V11%HZ`F8`v>JZ)tJ7;-a;b|S=)S3i$ z0byfLR`l#%m;p}Xaz(wDu$LzVZr4A8{#)-o?9Y=W!XI{Xd7~Y7dd7yB{B9XVHSAXe z7mP^{$GCIB46M3$M)M7N=-id(Nb~+OJaqbi1FNa3_x`&~nMz|tX)preM{PfGD9#(q z!bj<032SDoaupkyaEKRRT^RF0&a713_@iH4Tyyyrm8$*sup)woqv|2|bIX}fuYbM! zH0|q5e%m_tx|%Gn&SCI)-FugN-8Fq1`^okqM_d~%Fxedm5e@N1@iXN8>n105 zuuNhIHYNuqIcu?tnE;zRMeu2<3jBa4Ie224o(8*8MK`BlC$I9a$k7IUmqQP{(21X( z1?SDnZ9*;=f}K;J;wn@4Pk&~cB6pP^Yyv=q%FX-$n4B;8jsDcg?^ARg`pCm6HNBfx zf7S+Mn7q?%iO!DWs?hr5I@IdPu19?fkLTg-Ps1khG+G<_S3y_D2-t@HzCd;1;rut` zr;fEf4EtRs&jikRw&USK{`__@xIbKy(1CIa^Htne^v2A&Ei%hh-v-q=v;Qc*$Z7f_ z55R7#H*u9*Cw*I@W6u>}Cf4<#P7-vTZf<%7;cy?6vgO%udH;C#zUA}$?{&V%rc|hV z4&D}h=u_Yvn_)L?cC9j|dX%ABV2`+9iSYNK+M~zucB=DuzcpDnI|haoCiHNw(fM2%~0T z-MV8_8F-f6G({Z<%l|ms>a@2>c-H5?Dt+3!IBXu!5qvf7rBWIPSVl&6T$9 z-)>3(qx{uNu#x3-K(z0W6xL_#e{E|Xj(^wn_$xLYs`Pc;j`(Z>#n&=gwDDVzW3vnV zAh6=9zA!#4a2184f@)Z5+hEm_1q2;+;B==FX@A+)RFM$TC9ok%;jW`pj;gm0RepCN zCsbKz`5(`Gfbl_B_;Q=h^nPc8{7h^Hl|TP_dCVyPKRYB~Vg4x=A9Z@+7kJ943LUEK zKA$O%L%qOMTzDK1yRd8K(J919+l#yLtLKbkX*d|4wrtk4^R9xJ@*_j0i4AYbz zxW9S_MlYr?`9jElRW!w_j!R-ab_8SxYx8Heob*S|W7HRBnUnt77D^)% zPkz>xDP#@5fj*|ijvrVdQJ4Ev<(DXX3^s+VW-~0xxKJgGYw9Js45zc?=DI??j&n;(NpFQI8B2KUW$>l}7T8mJE+fafXa_T#N zQG!2J{b{%a%MfQN;xx)}8h;U|vFefGI9m{BGvaKJ<81gv9ADML!*O;YP7~t%R*v)A zU&QfNJun>SjiS`^M-k@@;mGW|miy$G_sTJq@;m>g>K-}f$3ozs@vuGTqtSsU+tHJE2>wzQtRN&g0{|tn|%ulxxnq!tT_QP zDYP1ElXFjqm0Q+RK5ALsjq`)luKqsA?3de>HTnFg;^YgJE@yT6FWORNRmJcdSn!sU z@CIa!o9dbQi?^I!HDfqVX_4;yykgCT(%dmE#2-iOzwG1%MPl%^mIZioVg@djpNFpt z+H3sXr&L+w=Rb`w48@reEUBJ=x0z54>v>Q7oo)!+QMfyZ7+lk(x6w!UI}2U)#vN8!;`vZ-fCw2fqyku#(K{m&JzCnU(_FClcxT6s+?P@oZAVx=0;bg$hp0FiJ9QWi#?{m z>=2Am_(lmg8{JO#x>8Rj zJX1N#h+xKC7G9|t?u;6&K81{`3^$YaH;nMK7Ui}B=l&_;A9{6Qil@wX4ae*nt_rRB z(=eyKfIjyQ-r-}s&u7^G(7Ofjj=qnv*T!1?zcA-Xtt1=%QM3&+1pEl}t<1SVCh`dg zoe~@ARvI(q^NFzxH;Z#Z@cL2w5S+Ma@UqIUll%rq9#_W*mBQ3Ql5xSAT+N3p4T3ZK zcw+TM@v(j$sL71}qUgr1$Wq4&(g`X9m4(Vc<)(5HCd_WEbNAvWwOW8n;{?JRV=Xo< zaVX5NP3f8rztT-udGGGab=ypt4VgyH92MCC6Y^#XX9Sq>V?Ba9(+j=FFmKnC(IRXD zrUO%z^?c#KVf0=*7hySA+=aPB<+P{!2Sns>@*mlWu&xESXCfV+hV}h>3;%Vg6f#|C zUo0u`A;$B0GvSnL|+mhRLo~)9nkxm*Ve3eq!_veP}DR9)&$j&C~g6 zpin3NHLjI-+_~#JE0^*dn4u0tfs9Ggadm)Db;>X=*`4PwtJMxZ*OKV21uqORm0-Wl zLQj#{#F&$s)b2uOa+5pWwt@70=xyP8I~P!Y^i64B@W_$GX9!1*7*#azX-vja-kb&*mf2bAV47^e%2MogIiupy{#)JI z4az2_hzURMo9|lS#@b21p03c=-Q>#)3w*^4){-SD4vcH}k(Uow)AyL@cI$(WUcR*Y z`OZtLxhC@0%Xe1$^HI7>eL%`SZ@2&5pAxzjgYI*{=c@KwP3sZotGcLJJMgg{_el6@?pO= zU~p?Cg@?Q+(6R&$JEcDk(mSenT`;ve->LIL?$mfyoHsy-S~jOLl;~3I)qAHq`F_S% z)s@D>H=_^xhFmZv?Im4YR^2t6D;i%2+i?*6fW8s6Nwmk=zyu^soDY6p9<-G@vUA>x z@9&#Y_GJgo(iF!7o=u$CvTlvLoPw^dHQj*KSy7k zyY6Pxo{%~9ExWQ)rP$|u^|r(|2mD^|6&52#ZhyV^pqKp5E_&^kdHX)J2iBqh(u*=M z1MOH5a^OE3Dkp5W9nZ_pJP@Vc$b_HtQEbMd>wsVQ_$R+>WbP4YPHF&3P*gMyI%G}Y z9x$2x?!rNDJv=3lj~N~+WGi9DZ+4xh*>lNbgiMdgW6&m9 z(@kdfsVeZ}#2_D`dg97{uBjP@FAN5S`pZ+@YE!)j{~ZTC7d>3)PS1;;e+^?^{G}qU z-A z{jVbRLcE}(1R^uAz@M5zx-=4qA^Wo_ub(0 zGr4U}8YeZJ79+xE(ue*#Tki8SMY@h(+mDT%2Ta?g&dC)&Vh-3N0X;OY*KwbJas}{6 zj+DW(GXr?Red34GsL)d2d(OkC85PsuQT$K~AyxfbWx;181RN#s2<5z6p5E?wB|tM%ubKj$&NC5}RE! zHv_n#>E7LFsbIsZWeOA9fO7+XM3-w5wC+*yO0=~FcV)kzROk_&{7%DGxQ$*8-jlqU zW}KU)a<|~2FP6}UOcE)P(OtmQ`1X*3z-{(|)NGM|Qd zB0X)@MFfWOvjDlQ+DWvQ%^0&OsU)D@}8yR}ovTJTJ|b z#Oim5y@PO;v~EhB-u8ajHVQx&`zlr!j|U%fvJW_bH4c3P+9Rz4KN_tWJ{-eq!r+Hk z;HCLD3ET{X>zn4~3ky**T$od48w;EjCN@;ytTdT1CTxkVGCz%yR)l>D`u1EC-^A`Z zGP(fyQq4>qg6wBkfm4lo$c?H)OW+M*j-z2i+XLPg%+gF7khQf zw_=6sr?(iLYXz{($b1A*@vSyU+n8yspFTumx}(L1+B^u$XXu4F4MsxneqaR zy@`QcQJpm%K1dqtz3}GFYB+6ffrarowdyMx@#83jG4Z{&c}OFE6%}7SMz*yc;C&_{ z-88Pixd1Dcn7AfZfUlwueupd4K19W}m?x&Sy1WTqrIUk23QB}rZ@~Qm^ptlb^Lhs? z@*r7ENeC?UGnNZ&nXXekd)J;>R&4qWa+F{p^M<5^RmU!{yi++9)}t-@Uz9UNE+^sP z)~{dti?`L{Z6(M&6rlx32WvLz3j9Z`s7tcLq4I}Yb;6D#k~l+}2H zc)x#SM?CI_5k{GGHhVa}VL1Nh!|~xeMNj%7{gZeB_S$5rf${%1;W&{$8qIU`?zw%jn5VVyW_s^a zL&4^8W@AOVFME@}NlH}#G2m7PyNb%o zeBLRPgfPm|{12NKIH){6;jq669_*Hi{eFW#4ZZ=&bAJ4%Z?%3ceXC4|Y-^sO=y`9| z%Jt?oCNKq_>gLGSY|T&NA5eM^WUhl^^Rc)u9hE)Zl_BeWMg-G=8&A3^9yrWwS7QA} zDRJE5bxS;KSYlUpD^d-zCT;QReXBjQwa^K1!FJd-Y1`D-&o_XhdnU#$()m%^o_2-i z2I!p79vnN4{3K2ru9s0!CU^GDAwSiGC}v8Dse8^q#OGhyi2FRO6@TGYicf+CqKL8*X^%G zG|AO{$wSFuKKWg+OK5_4{$#QL&I;P^KGi?aGul@ZPSff7IoG@3NZ2Qp)y@y9ifhm7 zBDTb5Bvpvy6xzUB(W(QlLQZ^pC4WvA(dllj)LuvfM>7X|X*T&UQkCx!$r+;9v6P&) zEBfxC*#LsZK}l9-(T}oUVr2#x2vNbVlQA2S%-;oe@w5W|QP(*ix;9 zjc_c7x#?1{IkfD0TFHZ%!fnXm?!iS!t3=}NzvVHjzrbH^h@(rC6l7hfo};4vS6(8e zCE9YI$J)y0eck(@{9tA2Nhn+n`D z;Ph%dBgayDstBh_?*Ipu?@h=}*iL2g2NgA!@5}k4#GYiQU=|ei*zztj%9JV}O2?I| zP**Csu3n0ysSgIb#r8gp>!5T4!(ybY9RhPeDE{U8u-26M6lx@KmyF4O6?4v1{2C$8 zdJAJt>lmeG9Q2}pfGkV#TSnLlov9T^BY3_QPDLOQxPDWu3X3`jhFi#?bkOJPZKC+= zwrY$y8kZ!lgOzfhI2tw%bO-XKcPS4_pY*OF*eTGwrgYv{B?0+wW%0c=|BwTo}B&YFy~fVl#H|xxrt-rj#sZSHb@EPWT*_4(NY#eElNZ z53FS9>|chIuhbXUiu8#8-N%I%Rf*!5*jTyM%pJJZeVZ%0;kG$v3^u`M9t%mK3D`#q zU1QNsa|T8V^U=0u4A_KG#(6RxoP-_pF^Lg$z*xS=G1BP63QUV9Mj1J4^>B<2`lmP2 zU7vX*((99wgbJjRIZ)D=VfI6!W)qH>lW^xpNocqUb_}K#4GwmJTJvtU4VEW z{ad_O5O0z(cQ~dbuIm3u{C*%;&QXwa+#{t4HyCs9HFx&YT&>0zo&4@UZc%Cmu!eR4 z(}=$1HGTS5f8;cNthEy%4`rY&CK=rgpD8qNBkW`R&fup9#@YoOpO~oBgmA3Gn*5(Q zO4+c}#BtAQM)(28x6t-#kv-om8HWzjiu-O%X0qdSGu^#CD5-MS~lB% z2*w2ciA<*+>q5nPdM?F%laSSzjCLA>jrEX?1JiK@)_1V!5_Hhu%@BBC>1+Z*&pFH^ zDLiBs=932DatK~h`V(_7-%>jCZhCNms$Hzd;o~NyNk$vjxsjXi-MpGo+vMY5v!y>l zaeqMjrrr?~VNYkSUt?Y);~teKJGFCeH12_Y6%bm*E4a5s8nPg*$ktC1q|20^w{b=vu(Y-Yxmes zw;hnLm^N*g^zz}F!#y7@fAoj~EC2G|cRAI|7l2F87|VMXqzO(#IC)6*N+P)Az&HqY z$y}=xe*w16pb&X>w&9gEmf9$K}aK@~Bm-d?rg>hE7a;7p2S z0!vi&YBJUw>Tz#IUsA=y|1(5*P3p?0q@<}n|5hnc^|SxqRw+sKX7m-rdV45-|Cc_6 zxI6VJDS7J8euZ15WYwF}Usd4B0D?wLJb z#Fu=O-zud{MLOelONYmu^1t8hOQZI%73omOIsX|gR@CWqy;pi;>RIWvag9>i)Z>zW zsxa}ils@idY1CA0Bw4G8Bx$z6%T{$b-Uc${Ht>}6tFoH#2;H^1{p+;7(&1?%ro?Oa z@HEvS@VHJ#*!Z`khBDeG!p9No&W&hwkEU;vUYoWJ_x4Hm=Og!N_HHFws}kSkjcKjY zsxoQ?f05pu_LNj#mNE4a=@p#aQnpQcecDseTQxCJGxUh`jQTCCe-yrC4)$C*GHGdSlvG($cbzq~~$G1IHJqJrhjoZJVd){i`FXH#UEsq)6C77H-WW(QjOJzfLf4Gx8=pMoO)6%7h2pdz=w<$Un4C1K! zWESsNe)*57RQHH8=3bBL6);o4g7awfyEeY(5A`pCgWxD64rBWsj~wznE&VtPw&cts zQWw&@GV2kk8^@nse?+?a+LPa@U?W^V@GOqJGqZ)52-y6L_I&S0;M0XP75UM#w#$Fi z@6>RXe9t|eiNR0(@vm{OuOP&S`#Io*1xaqZ`hWHAYw%b+SX+f-;tKfl=|gHuvK)KK z{~DWo0ik6;Y!?viSe52k zcs>VouAgSWh^((&y=y2>auG?sTc9pBEU ztC8}(D*4`D=OJXiqUYd(Q6<{abh435kZmNC~zfYGc?o)=t%DcMNBR+p1U2-f-m&)&BqzWAE%h;(5LY{p1 zu5M2GWm?ooS0#m0t-L;8RZ_n^&8z5nt#)PihkQ~`>%96~aweTLDXka8 zNWX&oe|p}ZmpsX5NPNyq`dftL^YmZiBnHl%@tQWr36SiAvyUE{tD<(IkgBv*O& zD0W9(lQhw)brDZxQedZ4gc+(BGtvYBIuhtfI6LpQcaP%st-!iLw$G;gu%5}ybeq`p zinHrd@nmLTWc8wTx{9oII~!0kVedNIW!7fv9>whN!y-8Fez)3aSdIU7l2&loOB71% zWUlCZP&>!mxS&PjVudsCMN6o7A9kGsVzvYyAD{jNy%*(2wwAPxA|36<8pgcQ`MC4O zv1}8&e}k*$GM~wTTZ4^c^3QoSf2jV$In)p&SC@JCmyuQB1t0LXiyVIYafKx<08}$c zkuzS>6pfcuMZ85DoQ89@ghHkv#8pAzh3l78oblHe7Ot^%o$%e)a98ycb|(CuFQbRF zPA7b;rWdYJwM@=tftv~@>>!~Xl?1FI-jas&R7goP6D#(}h62^uQ=JYl(Vt3VCsWFd z89B|&2`MakJe8E9y@1lqEIrPeP%e~7GZV39QW)wb#8^IPQ((Nafz+u-gna^-zUdxo z(IVgcpeizhZ??Y!|2RB7QwSv=eZxNHoUT*DpW8rwIl%P_Vm%19Al`XJ96gkP5-NhF zRYl-DI?xAOb=hX>s`%RhPELUd(Occy@Ql4Ya9>?Kr9&Jy`ML zI~(U+<{e`KV~W_|L}6qo1IGzMT1Z!vah@wgzA|!B0`mQ45cw7=f+MPmk?$(xTRfca z^nrL;m#Vd2%_Kym2;ZMto&_He9iIEwAiG~bjV%RYQxh?vZn&y?UB<+Lt;lJ#3zBKY zVjGxToF~GnAkl4VF?e05OZXhlHjsuPNZ7I?1VxBSMByWca~^!#Gn=s9e!zN}F)B@l z@C(PvT6yrNB{?m}IV+El{ZgJs7di!W&CMP|1;6f;C%qz}V!y_?n)lQLll)mbbLLJ@ z*$I7XntSOw%kfl{VP6Z7k3D+mTvOa6y;Ds3RQ85UlrbhE*w2z=Egbv~SXu^eT0Hg% zwY>X<9KUT2_A{4JCbD%Q+wd}AzRp7!Ebn2_pNvw~LXM@a5&(&PMdSwG053f3mm$L- z9+CKu_Ar#rwdW=5wW`sF^sOT>8ss?N?|zTtV7o-j0G|);!U#a?YR&>XXM}t(7!yy& z666#UT&WHC)g`#negEUbWTYRrrgLEi~CgPj*{d z_t-}Rj|=;wKnZptIZj28?3ArG@LZlC>waSEv)X#a6S8f8Y0x4|2rTfwAZw<1Ia$7f zssh=1C?1kqO%{216jB=xfjJvO1PZZHh^jqX4jEmQEkBptm|!urk8~~0N%dt_k8}|p zn)SrU>v@B(uucDqtCjK<8`M|vAqrOnQ}D&8j3e5tCpJUg(YX}9_co>G-BRprv2P_C zx@Me{9n;ge|258v;`*2G8F%tjV#*!bmw`oA^Q3E3ij>D$P{3b09iLX zJc=0$6Uj>EUck5A#Qu)?l>L;wRsN&1PuXYL*I7TVTiJKmHWo4_eTJkg+Uzzww^`Rg9Mb*MTBGAuzwHChUau5eJ{&mumIa?NKG80k0MOUMn8AC!90W zDrZu472E4Ik{1ReoL;S217v(T+;Kg;C8}m%H-EpP!&YU5{4y>-6fExqGcX63kE67S zRMvSR4t7mta=8uO0_Yz!GDh&^YKlQ?>I6Mjxt4<91$@P`-*aZpmSCF?>||T`zkP*n z#CpfzT?__Ec4wD(Ia*+>k}cvft?7-e&ID3k7C>niIko=z{*kZ- z;~1oH-+{;?c+6w|XxF*nMI|k|?{Dw`_{YE%*qE?>t5Yvq1Pq8@ONU@n`q#ff)&=+!8z;=s~D1jUA{y@x5*ClXWp36Al#B)ymS(jI(^ zXYji=PTOW+e8xA}f^j+r->CR|3EcHp#R~&lUEl!nZg+0BZ=Sp5=IMbgu9zjQp`=b3 z+~h_ZSz|`M7KePU0<>tXFZ#jO)bn&L*YouJlk3vfZ@1^SaZZdaeTv8)8(Xo>pWkS2 zVI2j&^4`6v#GtvhTIbV-gv$W7^!=vV2puV1zdm=y2Z0G4*GD`)GdA)o9vm;_?x54 zFlYKqS>ZPam~ls(g^k_*lJYa^?5~>bx4LK~WQD}G8{lD=?&-srIQGBqN8fCRbs&3753ALQ5BdBU&3+v9sN>7%W^>C zr>m)8E%L3QS~8J(F_iUI0gwVuyD)|e?D$J6~mkPaP?Dx75?w)+7QgIecy@?1v zsU(co#54n)@AO~O-+U1)gk(|LOh4ewpzYk}1s@sO47H&n!+OP?Xg{<*--Y`Jeizrj zlD>@ETI0uzKx07}+SfI{oj1V47oMHdaMb-q4PnUt)jqE6!%hX5h}gU?Q78Q*?&&Y{ z28J=EuZq6|Uc=-%aET5v#Z35#jW4-qr~1V*rDfe&6~=k6{z6N}7wUT6yGIvMsE&ZU ziQO*C1X$bUvy7~R^zW}`V3RaSO1HfaZC~6niSg^s?so64CT%w9vLoV#n9jV&0enWF zUHvG22L3UH)#ucP)iQo?JS9r!-_zLY-ujC)mJg>vh*>|vUUTibjm~yhqQFN(@kysb zk)?jYuluS*wpfMKSfEsY1TU9h*y8`BQ==g+=zNTCr7gMse{#?yO2C`E`hq{#Pn_Kl)?h9erl6)?(}Wqfa-(>{&Etkt^;mnGUbX{r+?x zG^LQC=z|MfJEaA%!kAyJ^_CQ9&dvmiZj)VcK`pPVfeScvGuE|xoN4fdQp4wRpIQ+t z7{2Ei+5@f1eysJ)jkG&~m0z%M_}&!x-lFUGfRP%s4Bs0+bVF51V}V!E2z2dkNB3vR z4^$|8*)5aZnT@P9(^u-wX-uprt$xAZ0t@aOUvlTpWUFgz-yetc-scg*MA*bT`kokg z2df~ieG@Q&M}@RydJjes-*~sqm+5`C|LRbA&L{p)3$i?oZKxTyd5)n`foD?{;FpCL zHf*6ir9LKijQip;#!?X&jkjchyc;c?h8mq2qWZxX2db_YC?* z4vybro})eOUFb{HZ=OJZBFtR!9hBG3STobw`IqZv@*|939bJcK7}FHFW(=NgaW5=E zxT2%r2wOD3nrC>R2Y8f~b!-~gA&jgY5#Wnd!NjT`#V-d*j}{hp9w&4|P1V<80sQxk zvUV*jE;wFub%l*${3y0z|6ohv85ri-RPJ;sv8Xwc$eLQV+sWIvH;7t+t+Ho!)i(;* zeizB!wy?q^M7>D50zLv#y8g8PB~KDs<3D07cHuJvs`ZZb)eYFQ0)t-wZ}Sgg`%t); z55n#T_N*g;%o{;_P`BS7eu#(WWBp5O$VN^V${&uS=M^F2@Hq=)o>U;>!}8d)a!vD^ zZ`YXDri8Q;l7c#nyB@2%<>ES>X=QgMe{nS*BA&Yl7*{Zc**NH*evsuDalMQVBfcJQ zr&lb&+o``Om6D4#+4(Q%ogahWr@r*cr3~~c{fVL+rG_;#ruUYyrMe2P(`3?G&iKWk zKN8~?*%y_QUWNDGZW$MJcxx@@;AXFHhQcy7zGBs;WMwn(4aSaiBzC0fp#+@s=uLzc zqrtfnzF%rrK;reObt)4Nem;0nnpnclf!sxp_V7=%5wiQ5R4wBL>Z!I-&vK0$*Ef4s zcF#^VuE~eBZcJ>F>%1bMddTt6wtuVhF+(+7EM$K1dROo{A!YASJz*GYhHD~!k)CI30)IqMwj z&3nPH*68GSGUjjBol%ea($r|L%m|v+ztuT^tUh?q>#9@)@-Yfk31_sL0KY#UJP$@- z@J@%Xn0Jshn_NkgciF+@t^7L3SW1IqU1_iuhjnigxG4G*W4QgsbL0!D3A_y~adWWT zIp66ys$xYyt*QZaKj$D*vd0!J29Vc`yU3F@m4jeH$ z7rtkmeCJQs_U$wV5Z~P2&|k@Cf_%Jx>EAsoe*-jq$-s(f^)ca}crDheM|?Thl^ymS zh@_z}@Mrb;Y+!mmJZ`bxSl}Mx`*SEeKgpR8tbs3Vx&`|u-&}b1W;e2(eC25Knvfws zAy|cbX}I^8Z}#fR`Y(cfw&6?7yeL&&-??8j)`ajLI(xWabwK zM&?fl#9%Y6Z{gS5)-xgA$wQVjGfxw`p$O}6?2x!~f9dJFlMU(e9(2H?Mu7e6Q$|^; z1wQ1V^bjMA#afsV#+b8nuUvwafmw|!lleQGo8>!#c~tHG1h^9XDAWtHy~!@1tp;c1Ki!t-X3Uu$ z&J3xNMd#*&Kpchi1w9o$PFY^1o9zU~gg+Cg9f`2OV%i?Tm)L^eU$9=<02!0gIcO;W zW5`sD6|hSf2di*r1l-JKC%c>51^n5eL*VIo^1CXgOAe*5dxtu`CWK`&0^)^@6t-e0 zvFdy8kk~ww0IV$ob`MU-ugG?f2M1qs&eH62{-bvO%mI|-@mP=i_9ROpnG*H8N5SFI z2%Yj6wEA^}4M&v^RXmhcYzeBuDTy_g6CEFQ^Vxi7LcOv{x$mRy1anPTsXN-=2aaK~ z@8x!}0x^8g01Ko3WK1*+fwvrZ^lak!%CwHDNpJS|^(yzPdVEvIRInk~s}isAQ$Ify z6WO8o?gV8iU*=ZBi-!0UE4>ws*)8a0LAi7;Jo?KU$)xByn{>)4PTyMiI; z&DMfFU|qnhQw2l*zeN@Lc%CKiDtc^d_xoAPy=UWT{wfepM;V;#Ub>C3+!2UbmIoB_ z$jMt?=&{!CX}fWqCOlR()}o5AD*o&XJ*D+27F|1`ca%5}K~^yvb}TH;Er~NjFZ7h) zE+OhLY>Bh9{lo5)4%q(=$M~?DSr8K^;)+B354&x+%EuKiU-@ul#Faw6I*BU-u9Wf> zQxA@1T&d#E;VKbV>iBc@Ovpk$8>m&b4abe~d4>7_wFk}$i%3&u*!V8PSYfYVa6XQm z)rZTJbGBYi%bP5Xu(73EV6U)~*qEHw6Jwm@_myJip|78vGaBAMpWUt;_X2<%dao*a zybt`2xMc;}D)e_%E@ zdx&lJB&@Hc6J_8!{{uqQ#uyl6>OC>>4PXj=x4Jp!!Tm!@9v$^JXZ3dJ}EmSerZx34eGZ>!IP4JUeSp)(VA z^yc3C3cK99q8cF{F8>eQy06uz@?eiEs z*6ZNktnKl?KAOo@o6FEMJ70yQ`iy^UVQTySISbft zGPMuI3K9Z7Fh?mPMTmcKktj|Xr1G$cU*5INktOjqrl>5y&ito;Y|-R)cv|~wE>{>5 zI(2;ZLotg*F2`2aU1lrFA&GkiH_IzYMJeI1=u7vnUn=QB`?c5!1X%Kb8fJNtEk$=h zYqqfY50t+u0*qzjbJ#D(d5T=IwV0Zb$(By0qv_=MX+}!sl z&=i_-FNjRk(~>ZbdS<vD|G8{?B1vfSXVW2>@Sv`>VBW*^8n4;7;%DX;YTq& z+Ay4RrK?oVIrA4e&+n^rJLed@g)O^aso@~$e5op^!FPKeZ&c>eno~j=v$l|FstG^O zKyJ)(?WL|%%t+~llU%#nvdl)j^G^eZ(Nb!zZkgW;yy;SR4D8m4Ofph92LGsDaYx@o z_&(guWP5c+gJH>Zmt$A-j=C{Zt%jZb;jT0OT0fJ|pVI>AFBP6PjB%HAqX1SYd$oTu z^zJNLVCKLcNomVCN}7b)A)Rpx+Bn^zHuMHOGi7Z}O|PhUhiXdaiq{ouyb+~4fZd1I z=)#(+SL}!;&Rlz)+m^;8aM%bDeTKKTese+^2$#x5_-a5o|lYqs2#~3XitkhW$t& z=7X=!57_goolLPSFuStqf+C{Qs`|BiwVjHDLlI>H1Mf31WWa*FUP8Zv#GXlf@;fG@ z+S#157rmaCenj!lK<~RM&hK07RBSJF`pn0Gb}?o^v4?ODW8%v(;s+w0uFoaKNi$Y4 z)tEt<17n3=_(N60SIB|0fArDW-8k#$`xE9_6X9{fmyeq~G7_7*|BO6y!msp2=y>V< znB2#YD7S0JA8_8$x25kb*b@`avQ1lawejw1?6niyraRYCp;a=0c~Vh?bTt=<$E51uDSI`#arz|V1v*FzHnihVWE(bBzlkpoa)R7!$4Xs#QA8b>~|F}eLP4O0dYS7Mpv;g~7M%-nr z-k0kLII0^P!P+ zW(HK?O4bEd<(Gh)Ix(mZZOYdNHs@;t8}pUHOnAn;G?-u2BL-llZwjGb4UP$MxubEm ze-J*WSRaAM68bJ>J88RwDkC&tW`;sk?K!drY;<*wtO3h$L8?)A?h>1;$YUWj0OFii zhjBkC#G4XAToD`Kay6k5^4=A?LdZFLFH!n2*ap@eXK(yx5aVam3cv3pSC6sS@w<)$Ng&)K%KtyN4FZdR?%ey-99n!E0 z&kC^9gZ{Av8SQhcT&!;qc_FZqXn&@kv~B%1Emwefq9CJfl{`%Z^a?iv+ z?C8H5Sq)pEGi%@PR3s<&^WC`y{2yB7c-8(KtjraWS_RwjGWPCD6M3_1Ls_Qv4qG;j z)wh(abgYuS?wbvQ0130eZr|otRT013kK#WhLavIhaj2cs_(`(=_uz}NpW`Dw2aO?}9<%h`#i zaGuou=Z2eXiG2$3xw_{XZgMXThd@aw4KBEI>C z6^!YWqyU%X!BTx`%~f}ap-$u4hhImX&a|XXXHq@n{4yo>v-Fs2<%)G_*hPp)h9^4XK`zBGzr<$|s;NN4$ zC|AbW8tYJY{A|T+vgQHQ75z{q7UQ1M=?;#YGk&&7vzGt$D+y*cko3)8b3k(d4A${A+!)|#s-P&cD2ju)f~c*^?LzPPD*qxmtM&AXn$ zCi7$FutNTRKuFrQ-|xUx^TzlYi!+To&$pzGNV(|E=xSR2)w53(I9Gc37n zQtKT+2+i`|K9|tQs*aOoS@$wWH=oXyV*Q$@$twdZ%nkF8E+cz!7V<$$Ts~N=&Q~%_ zUS3F*XAZS4tL)}Sa8sZSDdx{Au-{PRA^kj;dnwRHs@;jftcGfr_IPSTR$W>{b_1LH zg<+MYtWA@r#dv3^<3dWr*W|IeEc}v-oU`1sT-jdoPfcH*iCBm1lLFWyT2ke_lN36g z4*K*TfwQCwT@jDM^Yn@+NDBO4AhGyAHG1PMh+mw6_{y+ep;oJPNlX`brbmQ+f*%My z<&0+GJSA2ViitvOGD6l$s^Tf~6B89$tv0z3ato5cM#N{{ji3D_KJ=~uD`MVa3}&I7 zxF1yZE2cQf18CK zSHPZCS+X!s;~9NcgHgVpS>0HdS%(@mlv!K3dxOF#e)Sr0hxLj`Z ziFj$^BiOYb!18?P=l7yD3AJ~6CmY`B+Iy9?3Uh>;X+*SROgp?XCjQre8PdS(eG9$w zlm0{Z?8|v|C8U(5iz`RVy)xivzTPVj%Kh(J?(`M7f9s3fa9;#E_ePc5?57i0?hwhwOf-tq%>bGpBg?A_HP8!kkW(OgnL4FF;~KN5cs^UJ-NO)|EsyI4T-m!=mac4^!50%J zgYC;#i?B&CaRSbnx{59qGe-VEMb}E~<_^@t4`3h_-<+{8!RY%%14ifiFY40eV|rZ@ ze4^tmp(gymiXf!Z2K@Hn*CCJ3HCMl!za&0)%#4q>GzK4|aah4Ji3k&(fILXvtM&&; zHsZ$qOYcfYuh8@9bt&$%Xo<{SnS`^US6^C@+TcWjGt9yS6oRZp~G}0c^xvtMhKi@}HCxwNFY){8TnD+S|?pQO$~7 zSBmkxxUjDfC^JbotLY<|r>*Pt@{W~R80k-zXKmiQxx7oyW^H+<-mr=_J+sN+BiYLE z9I0V2$DNFiJ20QFU z0n)f#85}jo)&hhM%*VT=Su zVqF>b^L5NF>GzN|>d~IwM7yHn2W`~HXuP_5GTvrLH|VNG+kp)Y?^d{$VC~Xaf_aF_ zHIuWM* z0qF!D0b^Uw9q=VRJ71*t@IttQ00irM04Db!!@~kV`~pf z$yUaESkhY$ONq1ssXr{GS-Dqm<~S^6SkJ?@ftX{@i{HS;L1k2!&Wqn79fe7aHhw`m zX{P+BPsq6;$7{K51;eu}#a)OuRbZYms2Ex`*}A@;tgI?PiamXq$Jv<@5Twhnuaw71 z#Qpa;7r{XL|HkpOs+@RNYZ6dl$QMm>oXNW_R17rk^WxsVqAKWWfbMuTkY9BWzUk+| zua%FmlL)&UFjp1m&V#Er7a@N`$TxwpRp0y1i?8$<5%L;B+5-kTr3d=55b`2I{xdKV zDX~atQ(q>+_Jg^C$^Rh07L7ccBFFthUuuXg;-SZ8P=??2=@F|DPx=Gus`KK*ee6t? z#3sA|e3s52FF!F4^(ps#yfe%2%qBp8`taL=ABSrje)OL7j#lR@{)3RwZ;t69;oxHE zGbhxo8`+bSk|HXGGsVQqu@e%!PmU~?6#Wb%wvKdi-qCK3{QtNwyeZBdUfBb%u^c{t z`+@ZEoV~H_Yrn!d#W~p0+}PQ2aNT}(Ue5EYcjTNb{luSDkrYug+x#q2J`sCXQd`v$ zJEM8sjTYru=wDYKXp8~B^ni~A{_WS7>Kh--{?5-=)ca@`M?QYkHmTQbhu3iZ`VTub zz-V|5HdkYu-YiHijibUh_0_MRQt@1NFFelgT66o`h{KuJ@AU6OEQ51hmH=OLs^@X* zl@(JB6l>g?k6?8TrWck<^~V@&2%wwKQmMWIVnG_c-Aec)etc<(>cg*S)~jDLZq3O{ zGLOnePpb~AfaMQp=bFHaLHQ3wtvC+Aj)zdoOj!BR?AZ)?3C)MOqX^3`;bwRfW|)B6 zs+}8u>SA^aH1) zD$x{|JKWbsZ9e`?<}aQ(@^8<~mY>NSerEplXUNAv36`RepKQ3<$uaSKY-UkUkjCk= zu=BXqM-qYD1{uc?`bh4LAwh0?>gZUs&oam`t_HG)`^boBHo_(#>@r%r5q(66jzUNt zLcR&4Regg#GAf#mkQ{`x2bkQ8{%4_qnY26sEnF8(#GRBOppE5s0Z&nfE6ot_kMd6i z;_dw`*qQ#n+WXJ#oW2F^ovEGwagf@%zBNfMGsY*R`SqZ}>1ojnm-%f;gRn0V#^iSn z=kp@+p*moG(XWWh=$xG9s=??b%?a?1g=Z-~h}abW^dGdx(e0QsKltwhOLmLjp!M?9yMpwTsDt1X&5!vO!15g z|EHvcW{5G@du-+xJ@w%3W2YPjS`Nw|Ywa1@&>N)o1bpHc3%(f0@bYY3gJ}kz0^=g3 zk%t}f;n)P|8C0J$naH~NlfP^MuD_f;~wQXtu@)bC5Ho_ zL@tx$;7~p{BISUIZK)nNO@9{-`T)mxY&D!sFy62JbET z&dU4X+h}(3pB}R7>*m$vI5}`X^#&s_3e$q6?vk4gjYyYaryuZ9TDsx1*wTw@;v+}@yL{n+MnjNC zY7F+AB*kobmquoM|AD&WM)y&C^DG?6CRafI2O2p%{r#l_zE3VSuY3OCQ<0mvGycag z+UlI!49`Cp%zS?JipCf3POTVGvBHO1OMP+0%ZB$S#nb-PyR=56U1l;E1X8L=mI8l{ zx@6bIHO&v2A55()JCTSOW{lAE1QUMd7>#XIuhh=SZ#)Zr@nmO0`~hTVA|RZ6!KuzS zJ-BfNeUW)FB~r1pG(Vi(!sCpwbO)#}Q#?w82TR3>v9KjYJG}_JCQs{5cz`E?qdXO; zh0mbpgM-(^nt{V9H8{CfZbH0u14?HdzBl&@ag(2pjgZs*DF6&qA=6_F9cavKiNQ8a z<=k^z?>-0wzRl7Q{OMx?tV386zMIam8CQb$M)cSRhFC$3XQ(ergI4^%ap>ZuG_2yO zd{j<)=Q7wq-IG(EqrhCDt)iLi)mTG|MwZ+wClQv>3o&t_HpXfUpLaiaiKHyfKCdfDC+FhI{R0u1KiU}}YN zMKJT%h8H)QA9S_Uhc{q#&7}$`c|6}rNHDUT(j{oEt>*|=#QEW+Q|qmkc>zVc-l7f& zur-uU*x>I~YqgOccP1%1Uv!WFAXrG8xQynN&~eQ;OVG@?Tz!Y zGH<68tJ@?E)s73NsGOHa_u~4WTW{HkYi$>80=-e;1PYS`z2fgbrumV0cVgmg{q02@ ztUCK4e^bxVxOYi2>d;q(Ez*oy($M@VhO@f3T!P9#X<+`C4at<*iW1WdY4(f^8wZ)Z z=b=N~3LWB2DVDi>aGGuG>t|lSvV`4UteOU%ql(|OuLyezlc3m zvTIpRdc{)jOa7(DEsbSpD;8gTcJ1oN?25OTFhDt)o!{g8ZG$Z_c0iBDzaiD>wYH>h z)y-jyu&75{@>pjFx$`jfBk$MX3lx;&+qv?zx!|A;bEYM z&WodZhXNMv>5e)aUAPQf&UwgX2II+`?o*8sSg-S9Zto!cF6gdqjIa;SOlujQqA47) zoXQb(Hl;hQktj2|-_DC+AN@PcM7+olWvfYG!kX%)v2gvQ!IBE5pm|@8Zcu6{!tlnhl{h9;q7U#tKc#@eYt(lFMjwsCKY7qQo zYt+ZuBWgf4Gx^=`3h>zq5=8U(b`|$N$$_*-kV6JEVSA9L^HxId&x=tX!jsao{z&mn z&q4-?Hmi*-gx$Lpd@#v~%#aV^uM#Euq!>UP%i}lqznd2|r(c=`9$k|QSh(lB*aqGj zPj{RbFG)K4(ls$&PqEVd=w^b=*MnJ``{hMitRcgH(yd^=+9NSCOzi58mjAxfJy`yG zr28D~Dt;CxNdfV24`hfK|C_-8awD{hN2GS~Q)$Kf0pOE!h}nXiXs~|O<_5&ApCqvo zmilQb%$F5Rdn8+?A_C&IK6C$wc=uSG{RET$>{zT&ATR``dk)8*>%nXM5p+SEL*WfFmVx`&zyVKF-F_)1LHCM%QfwOE^=aPZ zoH%F+A1e)Mm~_xE#X;IWSP@sEvDa6VoK&HxcarXl`Xktp_o@VY1-RE9=@RG2ViTjr^9k)Hf&*3psQ|)D-pp*=H=VL2LS#~A}*c=Iz0hCMA$<^C@v^3j8Faw z7ExWWo%*Hx%PkDn_3;;2dfbImDfxMIe&0=lRV7SJRv6(&Ez$Q$^7jf!B^a!eQIUCa$!6NmLhQFKms zhxmv;x0!h+e|!!$KYW_P6%ZfpyWBci9t-V#m>t?gSfbL-zZ9Swjm|y6?9RT|eI@YS zq}2$D+wa&zg$&EkgG1Tj5Qbmb zDW(OcBRVJ~8=VK(AfuZgw2vUhVrC{O_uAm6qhKk+5FqBX~@;oAbuAQx!>8%P5PAM9}VNL`p)1+B$& z=xCS1SB5WC77Yho{U5jkWI6$Htp0^qS6ak^sD&-qQgzrje(_Mx$~5&E8He_lC)$A4 z%?n@SR}k}ABbPp>)4D^}V@kKOzvNEYCYj2vU7*tL#{Wr2(vcn6=s064f=9v#V`|~( zqAk)4&<@iP_2}VwTcnbCLF9cj6lGYG3RQ^jY6g~52G4>cRUsDDlV;dL<)B8+llYaJ zGs4cL2=I)ZmUS#1_A{AIkm(X-&w6BL%chGHhthf#;irICunWpyi7HYJcX?$m(DUU&}`AvF@9D zU0l_>x41*x?dKa_v%N2|;~z*fVm7yhheshN+Aix7HnT_36XxZ^j=~cn;%sgY-xCMF zEiLRC`LM7aMMr#_A~F_sWSox6(V8y1e~?z~tq0xJpvwaMaIi`14zN)Ntj7?alJaLg zX^!!lBS*TP#X9Hp=sVA8hJN#mUGFPqOJUja@xnnl-V*L z)^jG-`JIz89Ub$jBEOR(YB28)&YbGJ0)_i+MBn%T5vqfcN>?y*NK4SjBNicVT!VdE zV}s=_^8fC!P8Tr09N3uZ@_KZ#trll8pIup`cNk~JKvIxF^U~{kbpB;Uh&$vDtLAsv zaz|p039diGJ6q{nrXVc-crRc7gY?v=`Zk5$-lOZj*Z#f4Sd63-jKJoI*Lb`WwsDBn zc$}W|W^TMT^HX+dY-d*qbolps?%7DMx(KjRZ)u)aszg`{F{78h&%re&kyX+xODCu;uf`KN~C z20L)!gdS>x_wib8yeji=?uOQDVnPo=W4!yExXjO|#RAVedWQ8w<9}TysL)}L6Y_p; zGPDw1{~>m6qqy{-F?kS1wcP)BtBP>xOP7y9mj(Wv&M)N~oP#q*xNRQrE5Yv*u=~>d z4BZUi_|5-PYHL0UImXUm)QwilYR zrNILHy;hvw$nW@L6_#tJybwRg!Kc=;0lR@jkwq+=MMkgN`0h#Pb#}MmC&El3KNJ7Ki^D+K=17|4b zv^>@)=Lw+iPhmTKRkZYvcC;tPtA>5@f6M!OqwhYs zZhPM;)IEW^3e-K<7v||j&DZ6cqi)aUXYBeRl=&}rAKtzU`;M!KZF5z8zi(hpbf40k zqK-J5;V&>-z?>q!5gfUi@Y^%n-9Ix(3IN9h(~8^hEFDoj#C+p5N=UMD9T`>*cl+7k zp5~RSg|%&QKb6;8I9MV{A76HGSv_ZeDlc&)f zidpY1y#_IrRE{xcZWi27#fenz(Yr?PR)n^ zL;JnSh!R;M?_}C__ZOX7&Gh^_X*_G!SlfV&TbS;6r=Ce4Q#(V^&RZDCIrk$>bu;+* z$`P6QwTLlUCryyOKS7Fi(>}&iG?sp_}4+v5zK>ZIM&6bdCr>38p>f)aQfEB>#by;bghJ?ee1#*Z66jj zJ_nv|YQEhXlUDjrDeV;X&ZUR+s}ab2v{qivN9FaLiuEkQdOk?&siAea7weFU8Q$;K z;PylIPZh1(=={zmwd)mWyg(6S;ol!~zNvKevzQ}iG_Iw!UW|HSsF&wH)v47g5nXF& z@fps6G2{rdrP zWc6CuL{XNjV1GzJ}rU zXwsa!>!gPPtB=SO2fw0DT5XQYtCJoArNJ8_?FR2gOTA^7t4>0~V(B@7DFNXnb<$QL z3ZpS6KIvMh&KY7#N!=Pt3F0tkkRm^ zV%~{WdvNQH?Ir8@?5go4M#l?{D{=e2fBW`5qtSjtQ8GqV#dwwSJsc+7bCDUPCSyej zII`m2Pc_UJTQ#)Ng1^I{wIGV&Y3Tb?+{!NhdS)2mC~DkQd8SgQM2xr6*h(&MaV152 zn zapp{&G&Ab83YPx0%buvWxKOhISjUQJh48A^7^=R&lfsHRX%<@67^&rZ@c!P4k;=R_ z%}U5WDyE_3yDRX^SSRH<>m*CXy=~gG11`0n^=jLrhd-Eq%<}rz=SLn!qzPvFi!1k5 z*V-2>>a)eSx_*Dy^2ZiFRgp@NugFm$>fqRXK5Jj;s1>CvT2~lafMJPt&Ae7 zjsuL8L^ZH5^jR8(--f*_AkWO0fvEV3tm3vjMQqFI*wXyi79P<5+KTX&7+AY5;Q5YV z%%S#$V}mzK5Op;OsQsygN8T?dP6$Ea1L$FuyqcUza0}LQWQY2(_e}Eu%$BUB^~jc? zHVWk@qWq-WP&;0R+6gk$X4va3!(Hh%KZ|%RB$^5(863r1mcubt+T-6#o5SZMz|sU zHE{cbViBw-ASu{+6*0!3y~KQRmkP>5M5|K2O%7QGHA`^-(QqS%Aa+(YYK{P`X9iMm zJF&E-?l;PfXK2dDzn!!;ob|6EwNA3P?8_UwRa1#|d zim8KfM<|ZhO8g#pXwRPA7WVM$wn2mD;vCWaNqs1DlvBAGr`<|ee=A@&&OGp+txSat zKVevmw1mzq=pa}~$+E6zHAggsv_xW15wu6Wq*$3+Z+Z^G0g#bAMXK86N>pKZ5GNl1B;LUnvMO|b+Ifcegu6oOPhujyXwk|zvdF~>`^~F z^3pE5g|aEu@vx#}>#m4-z29K9)2$TKw_WgYsj=*`b9@fpUKq0y_dktCBY%=lomfn~70#bl zW#zZzBa3KyIW$o6ST?#JEzf~ev%+=Bg9##UL!oS7yKXRt-?t|}Pq<|gqJ(Frl!likp>L6Q>@`9E&1 zVW~RhTdJ4rLTPhnW3;EY*^IODf!|pW=T7qIO$ja^Vwt#Nqa-f8+H%W9t(dk1Q$n^g z8uEfn+u{oIC`W5O4BvZkeP|H!sEBa8W`QkFubQe}>8#6A8&n7-PJSlDJnIv#rEJc~Z znG#{&W_341%AJ*Ab2CFaxYjp8Q)jjaLY7dyh|AVz+;Sf%&-V(-@1aemd+f&^aF*Cx zA$Xwt{053UqXakUcgA>yNFIJ2li?ruR>|tp+GAF0j)O)y)^ya30M=XCPz|?5y<-F zE|w*^hkCLyx?S;}CCHqGT&alRI;2G@sDuwZ<>mj_a9*wX)>IbjxGHXy_Lm%MRSO3^ zD&b9!4nCPiNfBeEAVN6+D*8)o!0K?g~{63?`-U{f|EPI`E`YV|+0ZcK|f3yfM55bqCi^|6g6 zL;;MFoZ~x=)D+Kw@;Jw(3}p-ShZRSC+DK&!wWslh^WpG>)=&&| ztRdBXO{4n;zct)gZA(7sb&u-J$?rf5L)juQUBzEbsp zpGvu16vIPht!^$YpVCNuM18Ahh(#Zc;GPmHd%l__?{fyl-*>C5$}yZP0aO;edyK{s z#m;n`=5Jsd#ymP90zHO$rnyB}RsFqw*Q2y<`?uMpVRpIAVGX9nF^#JI>DGW)8^A3i z&*KVmG7QW^dxTEZx4~cJK$G!=GC-)TiG@SF;eEGY`w(A9QlPX(vTmFo99ei%%<3LC z`_7o!KQ0<(i$$D3mEoayWZ+xBa6O$>_bu-Nye^(^gq=f zRTzy-?TI|tkCKJh$qm@Ho(ilD-h!|maPeaMSUy3V>F*>sTQh6d7qg+XKQgSA|@M6DS;f*y+Fhg&29{p5+_SnWC z<2f?a_QIhB(jO!F1M|zGH}EGT5Vaw$0&!*xL%g$l2O-}xY*Nf@`;sOOIZe1)crVK_ zMpgU64LbXEaf75S8tRRd`2EBO=|l3*mg;7uJRe%SMwU)d zOku8M6zGZijI)TIZ7Oui-pW-)Rmfed@KhE05XW_)bqMeli&VJ6kl7KjW$G6uZWj33 zn}7knK`sBTFL^uJEtk0EIE!V%TQc^9Y)1=PqsSzn=Q9@Jk(Q|YpI&~oKCfe=E%GsRb@86ZjJ8$ zb)+gZ<6F*O&zSO>f!+xp1_@_a^8?rsmYV2%z&iY*Pkf+fnTPV!QNGPH>wbx$Y=iET ze8nlY^3}|cuQszon zdcFtIlJ^{i7HNbl4iea0uiH7qvyDm%ZO!Z8J%E_VPAWeccI?h3VObDd>=|b+<~qFU zYmcQsd!G0Hz!zZ0-*B>29=ih{OT;^|Az}pc8mr*3>1LS=T}B7|<;O(e`y71lGlgBa zb0t{kpep$LXU;$*Pfg^kv&;}j@(1GZZs)iWYtN9RhD&L;qBskQ`lptu2@WHJF4@s_NheHtX?!Q3*!Tg=j-e-!q z5QCh&LtHwX{qb6y8oLWcLer673Aeo$?-wbH2=1jxU$m7r`!S;wN6G2?gDpLPAlzIKB7J$vc;`2t-(|pTZHQ|`8-DaYDaJyaSD{k)~oQq z!ob6fyDeX}sC>Z*7#BwLuV3}oXHv+cW*A?j>+9A5xFZ-GfMJ&L#d(%>%zYd?ps#rK zSM`JN5?i94(dBu!&vXX7e+z#Lak?hMf8*@sRO^3V))%3U6Yz0!>cKcbM$4^<2YO7ZnQd}dVT;Yf{^JeA-5FW=(xFXhFG`b`uC~biK{4X5_P&A>g8kLv zsWaVixX@@kJoiMS0=}NSpEK%q@wXhtu>6BXO3=gOq-bHEq(S7`Nx^tIP9^+Pc?c5sgScSr)bg%JdDbB5>=!fT!Cn9cL7yOF{+DPd&IXFWq zxB&b`BsQ|6*t?8mtjY|n>z5fU`GXc(Hbmn#K(^$Y#6ia&d>;4nYJng)p`=3`Cp~MM zgj}#baTat2ov=AWMkw<`qlrsE)Rddf74WiLu~4h239Eh6s(tzXp67h}?Zs_>*N3I( zb|S9xt;g-=eCP(v;kA!I@Hcxs5WA@W~WIe0%p$L7PpZ*ZjH{v; z;QV2IJ*~keFQ@&jO`VLmD6|&yD6$dq*>uFLh_b3{eior)T^ zwX0_ZhX~n(-38BY?8elQ;6m9TwV!`~nq7U%kqU{pT48)2yMtWNxidfsOk#>!O~Vq4 zD9-Z3k2U6R608>JjXz+U*=kV~LtP-#XS72CE|X zx|c1V13nP%og{JUIhX?*C3Py9_E z&GWVR62wq7Vf{kCFW&w=p-(g3l1co~#+z@xOHqbMlBDsi)@;1l@GfuH?ix`MDdTI_ zLh~aWaG-emp%6=ZgW6`P`@I_+Df3vBq69u36p8p5w_zBR;u;tN4Y1{La zAu7oyR`eMwQxgyym|sh0vgIG3@R?CJZb|IU!U*4Jj%@Q!^i6eaGIH5T(1>=3FTskU zrpPD07sMkwXqxQ9R#mth~R+*+bs4lN^LKbxO}-)? z?U~}Z0pIp3;y-#+l9rJqp|!QtHrWAcOJEsaweUG7eSQ4drXs{23I@r(M(HwEu0}RG z<66jo5en1m`f99Gl%)(s5{L~IF zjKc~QLO$$6yj_cZTykvLOj{nHqoIf9&AeNk3L~9yl$Ou*L`1VuC_-xxj!1ROy0f8g zXBlftJ?J(^)MnIxzN^9Ta!YVP z#dFeF&r9UXQ}HLniB0!}Ab8Z-o8mvE7i4<-c~Eo%Sxu@7pOdqbgffr%c4XGzMv6S6rE^j2)#>`r1|&Cp7 z9PjwbnQYbXSJisO`vdy=aSp9~0>bMN&#p$*@Te`y9bNrK{6==v675=6z`GYSy?K)* z-1TrHq{<`jwcI;X=NVpYNPw)hMKPL?z7hIj4}1ybtl7xUu0aHb5{vEADxr!w$St z8Nj$Z6=U1(DY6c{U5V$91av;F4!3eQ8(Zqq)N30;oJCN-JyC@icP#cyQVhJb3411i z+tW4x8yuRSh!xWFhMh@>yLKoBr(>``+fLY&R&8lP4k$v}wI8G{o?+Z>E(h}XR$RvAN^r>G}fHuRg-aDkF{hn38jw}||VII8);});pOQq2B zaq5qruY&FI8^J4ghvBT%AJ z_*kE-a`L}vQKaxGx(PcAVj)A~oKIUhENlF>E}7vV?$pl3#Lnsr8zSG*8>7_*z|$d_-G_j*|-Bp}8q4put_cnkFySEHz% z4c*{Gl>R(8p*R*g!gT9+n->we#usPcO%C2P2Xl&%{R?lh@aCnUxi|rD%y{#5aBOj? z4(3@zzHc7_1hm9lU+KH%L5gaAgAZ{cyuCm^z8nJ^$Ji)ydj%;^S zS5ZqRk4~GnZ*m1UQIoatX4ye4?Lif-|D2@I9t`kp4+CfR?GSXC@EXj5_GFZQW@gIT(DGBUT=F%lTCWg;gXvszW(XMr

nU^30%Xmx_3Fk>w;p$o6Gj0d_60`S);=FomNNTf z`$^;q)h5?M3m;Qb*L|1ZOkRTf#Mcp%zr(O3FJaE%z?4^D>VQY?2mON>rj6Mvqt94bCb9dkjWgMmq9HFusdxv}I8SFtazL8_NK7t+j zV|R{&US*x>nC5t8DC=9q?fPtpBzya9OyZ`etIvgKi}wIq z%yf_I@LXhS*6u*G#}9qVNP?Dd$k>BZN$-3=q^n`aIOJQPdF5hWclAS7M}X|Ye~@-I zsoV|V@VM+3@Hxiwnw==Pxat$_I`F8f$dn5dXCYaZ>_@pdWZ(_WJsZ5667?6?#JG21 z#@saW{EYD6Y54a(rdZG(t`Mw$0<=z$ghql)e;;6A&kJ*ZkQQxXnd4zQb_4erOV-2U zA_sKLobG3AIp9XU;w;FN$7|L43Z~cm71#B_4t>1_`Io%QP zAtOz;0~y02e8agX?4)VR3s6mF%5$%^Pk{B>4aE1Qn7+x@F{l;Wz1lVgwyS_z^dz7E z{+?#fTMtdOSA5g|yZ-)m|EfQ~G|=Du{rxSqtI(fb?r&xDVyb1{C?Enfyq;h^kUZ6( zhTh`5e-Uv4VXz!IM61A!c3J5JoInJa;u-gwkEBa(H#P-Vj&Jl{2hv~v?w z9dAG0j*LLZEVxPY>q%+JU0zS*k%mF1Pp%d`2gPvCup zJoB!q8d({teSeiYBm7JX>~O{*;xRnjurA}Q8egq~Zu-ytZmR(ABzBynBuiW$K|Wz} zCm=>GH0sPKz}qp{Gm!USXQPoMYwcgh>?(+bJiXX^H;?%ZBFU867aSMfGE9gD z9DZUrftc2miJ$}VPAL-s(bU?B2>J!1*Bhi_Q$4k%vK3 z&c=5w&H>R0l&@;Tk`S#xXNt}bouj>=$4?e0TXxErYv=8evyK)g%}MP(SwPX3N!!7~ zW!VJs4?Wj8{qUb`t03(=$)B%$8Qu$WHb!GE^6ZB5$Y^0?+ZDBZ?KoITuH+{pX7m_| zZePTj?xEe_O$(9pwb;9Zjk6As{W*%jXFT6g3*PL2LoKknan>hnCp%~IvY&0esO+zJ>92gCQ9acEcYBEte1HFINKZqg`ld-=J?cJvp**A@F*>A;VCMI$rU+?t5g6G085HKVC*XGq9E_$hX#@m+-(fvv=NoMHc4c zdUrU>JmniRHX@oWw*WbjOI@M&%iY5#RC`VqXxz!Pw|mk6D@M#k--z8o#w~S5%9;29 zxV{b5po@A&pp?Qi6p<_mc4GC@0Wr#0nr zC|d_>p)t^y2F5`53}+>M_G8C5j0b-7$C8fdjLJ8mhX7xu1y4@eb&WkB9`J)FW1@J! zpJI{d83+R%CSY+^_ju24)Y+6~c6W-=Qq-=$*uQL2 zw4YGK<;NsMS4MkhsB*nOZmNftm`i6~gy|WBBw3s8b36y!Rs)}T-zG$ghfFWmdu>yF zCH=j!>74xcUz=*Xk@pii-yb%;VEZF(duA9^GpJ$Et_$ordsIERv^}~B&*v`yJZ-%# z$5W*8(Cf0)V#qc?f8k84A#G$j=4phr4bv+;hv}~_%$K8hjPSFFIQ+?)_AfL^`5I^i zYWz{VSQcC9N2ezk=uA%11$OL<7}O}FyxixlW@CprhiJ)_eA1b zoZD`lfSL=?>a)S6z)|mEg%%55!~tJrh^U!kTW(zAUB+o^b=$*hU$BOOj}FthJ^BWX z$?T?VOH|t{mItv0-OY&G9^TT?#0-!Ub+Q_YQAKTe`_QVH>?u$B{)dl1ri0~tcrCIc zdN*)u5T5`%u2H*PSA(APVYQS&SD~YRc6;=@6zRW=(I>tr{W3<#8zdUzD0mCku4l=2 zjxk!d5o1)E?t*2&&*IG9BJUnvf!R&KXmV&YSe=Qz_Wq|d#%PT*``N>^x!pBz{r zpJ04Efyl{ zA*1oHGGe}KBWlC9!wa@P^oBHGyZoyRv=R|D;aFi|AI2>v7>vSg$lhR7-Kc`yxMj{{3xj3 zrAgPikKy+-`29lgw}(IUsUs6S`zq06$I3=f40p6g<)}SJuMV2-5X7qJHXB zrcJGkaIf+Ho>##3b6*8TZzWsppDL!VUE@vQhj=t;SWjN>ruS3VZZzzz!29f#6+c!O z*REXq7f+}jm0wx0(-XEU&(7igUt$e!Abf=#+BV zwzj0=X-`=FQQv2g6YTo|`&JzwAc|^|T!w0E8+7$uux-&dl)%p8LHA0>)XE07u&pMh z)D^;r%i+uaTwmlaZPRtpkK7N3BNg9Y7FPsHoJ2)0mgb;`1p9l)jC5zaG>eFaF45Ar z$2r{-1|C}*#cGE@@`Ao=2Sc*}FWTDWSif<7!a5Uf&5KxJ{q2?IYI^X_*ymZB0KVn% zE>7EZS*g8}tI`H=htXO1!^@m3|D^MvFusP`$^TYc*|%rypaw2SV;WSu@uu~ip|VCR zwrE6Qcm-FjPoHsX_&c-Xl}^NYhD}j&ZseuGMPwC@xE=D_2>ET)>`3{o>QWfmkE_th zc@k#a8u1QgN(d{`$b8)3OIrEu>C43X56EGOPa?jl4)+$xVd;GDp}eNWiDiGWzj$b5 z*^7`w-HJPvRfpJ7T z@XcNwdA@sIn$7Tkn@x8hsw`yx1a z#(T0v6!#NOFWnoz$L&zs%Tf*%405lNPu4z*uK(MeS_b*H39D-^v!gfMtt44gbnRUL zI$a5waxL97x@^J}h(N%|{Q0w5^&*l~1eM z2#XZNXOVfsapyukj)DLDmOZE1Piar&cZgs4!}@oGJZ6)?qp4i_485G+KA}+Q32B8! z7LITZu27#DB1;;E7Y&smbeL^8Xpac_3=G&qy$F7O9^`+2hg>rY`Ar7o z&UD`pFGKLE9um@>*&)9?fwT7y$frfXIKef+Il=XE%mRm1T1H}eQ4(vT&qpZ~%CfO%}UL!dDyMH3dX(72@ zk#T>|<{qUx$CgtVQ*j-BNNjZW+}|LcwHza5u7c4v{Zwnb6*pY&F^b2JMem z9Of^yYLnZ=9ErE)9tPZNZB{L~8`znE)Trvy6cH%e{CbL9rFp|Y$dC-LqMN9z*|<}Ki%_$CH`uA>Ck-O zh|w&nOn-ns8T}mT%j2AMzV%o+9o8+(h)51bWo<*@t9IVdCywzqfM(X#YIoJ!lVH>M zBw}ok%%=H&m}q#L94>9oZ? zoBf&YDZ&dyH=xgX!M}Zu;I~J)RAKH(7 z%uQvf2MUykzYVIkN8>K*KOew3(7%$^RZbogWe1})OtB*?G-?Oz>=YA6QQEK;! z{_?8tQ68l+zcBca<1ZJ6EZ5oU3>D(GE4HLC!9)GhupI~f1K1DV#H^eU353tA-m)dyoDOQ`(e;1C%O;0!J)7_rO zhIvk-yx|X_@)zXt;V7T{2UZ*VZ{>g2Ej-Rm)IujR?>5HTc(eW8kX6Ve;EMgY+XnCj z;fZR@W|i{g?v|!d5x3dx~@M0f2|yWzdZ4ULvt*1W@--* z)`%*Lu4H34(3wgeSOOMhI%Rl^8X7nS;9R?n@C2*dDq{)W@C@v*-|HUJm;o*0W}L#c zJ)&omJz607a5ChnPTM!oKl7t+h^u;@wsWKC)+3qEl_vO=2RGO)iOgqILYtx6U%m+o{E(a~!6`d`ByGHl%tH}|mA{iHj?`-kNBhXJ+IKm&7G@X!lOaw)RlxD_UD)z;v5-ztS-)&4E@;s{p$@q6s$|0({+jONJd9V=d&^6VRd9dy#-A- zM7_L6nJ#85b#S!{2p>W}!FCiit?@pk_yhK}Mgr|wG160r8g|xVJGDfF^{o0Rp5F(y556z`3|zjUCfh=`TH>;Lyk zn)R8Y1dlT78(4xW?t)etG#F`45f>EjAJ@Inu7>tGG2e__plygsM!JK&uoKPo{>Ay0 zr?MywJHd6o`Lp3*C&$R^atrw6;XKx@Mk4f;2fv2dcfND!H$3(bv;1v;vt2^ZuvP0Zs1mqR(1?kRIFq zH($8ES&qJA*G!xFgS4!Qa;5D=kH_){`U|W5NB-f2(46e(Ro^jl+70ntX))&WC1QZg zm3u)57T94QaiXr=&sFEUo`SjQ)*Z;Vu|$yN7P4fJ2TtEDjg|G+ciHZ;cZmspDg#bU z^#FLbt@u8>af-YLrpC*N&Bnp1`-=EKJ=%IMTa%%!*?2SlV2n&PQ9Da;Q^d+QMLKNj zC|1=z|J7Djw*)(o4vp&#@jeOO8h{Xbl7bzXFYQFcBU)8`8&8pfIzuu`oW_jM*l^ZT zl(l?aoZW#sBajvCA3ccUftW&6(}?U@MQvfaYU#;s@4*km3K%E&ejWA>1lI$yf#u*a zC_c_f$lacTE}CHd5#VTo`*SfWZ2{oDXdV-YkJ^dv*Og_f)S!JveJf3lCi#;u5#OCfXRbi}N10Uw{JsR;SAj8;(%t3i?N;B5q)k=NP2$weh z)O6>#mdNYg+Vc^{)X_@wp}9Ew=SSz*nf4OS@o1)Ye^7W`{9O-GC_XVY@Sgq197I3? zSHa(_>FRoLdcuzmqEN>`-xT4?)ZP%EhXzPz$h8jk9_-;jrDmH8@tI>LzL;PY-pfXo z`h{tHOTd_e2$N&YT0oc{G#GO9BJ*-Cr`)j{m|!&5E0zTs>{|_SB_VpO9yHeH;UlZV zeL8(kJ~L=Dl;6j~TRxBue1L4Uh|hCDyUT_c0>BCVd=_xRD1H=h!l*DvCN@-&WI~VN znHg*eWE1bQ&ly}m*fo~P{p5HWK22QvX2|P^qT#!m7lOxs*@j${Pun7L!jK7+ku{_F zNgH@V`8g;ZzDpeLpL21s^@*bE;;q06hY|M4Aw2-qEI%2VFsfE7`5gR z8%e~unul$9kcum6NHRn#Y&YB#ZG9^p@QJ7}Vy%vMazbogNkszMUxD^N57bEj2pLwsC+(W&xs(t7ab}e)8z6M^|HF<5@IqGdz zhk2pm<(uMQxksF5$UbiRE08mfHrI741smGG57xO|@P!lBzTh!#un7&ilRhQSU^&UvhA`J?GkABD z8)hE{ywD;UHyrmV8PN%AAr~RruK`^y>7&R7>`t6;1n2)aY#*nAzboww$xBLc-;u3K zC+^9|K(keX*U;lV_GXXKQ737)QLMMTwy=z&zPXV_ohq`S>#PG!%3vwTh5g;fbc?O` z6lrSd*0_$mz?uf4JQeU$p)8>%fk|NB>#57T%H}%ld4<9;f>L+Nek- zTocA-*`G&_tPrKEG#0~#eu3qtIJ(!kA=g4OHRHOFWlqVvzbPbLY<*9OW16f}B%kMN zkXPS%GCwz|tV7R!F^xAIM!p`xSf`sz)~^IJYIaNe94j0R9AsO(-t~@x^3ZEMm&BXB zW@vB)<5$rCF6$c~uU7lmh<^M?lBtWunV@1|$OY{7a- zJl(78a;{Q<)7&oz;Qhw-tcnukO!uF)ZyADiR@V7DZ?3Yad`(R0n+_@gcd(@L9mKC0 z_{EIZk-I%aTNi>RA>4fs`$GJ*Dit|tdV|3bUVBmItkv$rg+Gfu$O@7Kymr)o$lgdc z7VHo_7)a_LWsS977ccd`V}BR+e8b6`!1y-g0#RkP(riI(uFHmYR;kBr72Ws7uOvsr zj}t~41dNsj=pySH-XZT)4a zoK?nL`+7;Xy9}6XWhEqpHS78@*V=x}br=>Bup$HAy56%764a8lzu>JsYiC?UY#8A| z^k9XJOp=*eX0@bwu)^N0OSJW5$t6lqVnXkamHR4dI7?eCd@6e2brHffNoJH)^Qgt` zp!$~12*usF3m0@#fB%lPJZtx@)%a$!tFpz`YAN8MIntR?_3m|0{Y{AWm2M>q)kFR-pFD3i+n!?AhlS@XsY{S3^nUF~h;54%3 zTnc(;0Iv}}zYgySpOFrP&c^^Q3l9W?ban`*%||;EZ8@sSEO9@LV~+;)Ha% zn__1-=F+K&*;i47In$^}GajPPV0}*OXy$h)v3sNJqii?DU>}vY@RwVS#PtA!|Fi)S z$nltn)`cS0H zL6KUYRtrx2-H`MSG$42zn)^$@5np31q`Otx-@#sSJ9wRX{3l$oOU4ws{Z|mfV+Z7h z304ky*;NgNbu(GAZ0t`ee_GcH)21G{a!4I=}%P`*#i~<;5#7 zHNqMZ_fsWv;|8nK-V2`b2=Kuk>xSZ|?L_s$Dkvil66RCN^GzXoMmPR0E9^8{*eDaI z8pE@M12UP9Il2GfPH{hS;fm)JZ!0ntvlZVfepD#$sBBW6Qz}&HsxOp9sw1ioRUXw%RfO80o~M35U86p#{-;_1?{QsxuIDXC1I7Sz zHFO{C|F)x>ZnS%0-|&1VZmEiUVU01?%0_c00ovBx-RZ(~7u8a9JiKliAgLh8#%_S; z1MwTbzd&~jS6kT6`=WGIh2a#Uf_^EzD5bOCd3JZF33Mi@Hx9gW6n`Bt<=EK!`dhgB z0$Iq0PAbYqu^O&MkNR(+ej2lS(Cd1{+41s`^mb&E+P%t93%?SDKPo%AX=-!v%~R|8 zf9H&BGBw*1zxFZx(so`i%h>gR&+gGejKm$MQGAI}&=| z`80xo@r;h*41~jPiYqXl(JT}*gpb^K^TC5el@)G9W<#t*Eocy;H|SihBHp_q#CsD@ za^J$xJw|Z)C}f|=N`jsEtot>LWh!>!JBcK%^vx}?(I42mo6zE(2J2Dm!&{`=4&%~o z7&GK4>C;@G7q;*2P8If`&UMgyL~+dSU(3P^`|nuGRCz6jV=a{!dn%ja3Dq4X9F*&J z_EO!f{<;|#cHL2Tlw5b3u@m{sUX(_$ksj(bMfgOn`JG&IaDUB+3*?(Iuwp5KORzRFq^OEeErkLge?{S`ajvIfFt~64;>xfBk9x-J@5S=Yi$sOJI3-pYc6h4RI zs}`zr+^9C!Ko)*od?!F7dE^-?$xP0UL!pt#_EEo#_8-G zNWD8h1x8#0d=LAv0h|b$v>2AsS7&{)+#jew19ly=N<~F6MpjBi2$0eF@QXbPk9YPXbN8A9qx&RizyP zp0y2hIPv99oSkK>RoZ0yrF-wN-1AcOJgZZo`DOOT|Fw5Sgp=q025zahdv+jBS_!yf$!@fse|>1%<3Z2u{bnfvwUq%rF0=ZAAjgpA9naT^~IwkNELlt<_iE|Np((B(K%o zSgXg;R^mrb0Dhh>`WZAmGN7B0Wjl|?tmqoME;Pn1y=&z$u9e4#D3^d~ehbMWQC^ls zKGcto*LX)m7TGEC80YVq_oouHT!xmPp_YX(BU8!F;Fj|9v1fAC-<;e z?jcg{;q+#XPAxp7o_!E!lxoD8<-1nj3i_-tLs{=4N z6fn3NV;~s(4@lUSn#cYWii`d>d?sEadIj)Z1w9v?i8Y{Gw&1%RcSH-$LN{o*Rrv0_ z1uRP@)&Z=_xrDE~#w<<`v@;d2S4?(SDw{}!0m+Z z3u0bwU5XJth!LLa+acW}$Y&LqE<-!=ZqHJAlU*e$%}&4}8H3St{+bkn;@2|9SZT9m6om;qY*zM^t%0(FE0>Hvn zKFaggeu!Csvp^8@x(wBw;+|lr%ojKT3(TgA4IzvI7(ChO1P+7N>{nF9E4EkcouVDJ z2zzXe`Qg%^kjemkSKtCl%R ziAsk7q~{qx=KWsJ3}kKp|L1)_@5j$0a6R{ZKlkCfPuJmlp=TFhABY9!Qg|l|&kSR5 zrOY7@%KN}sdF4VBS9up(fWD4m<`3)wG28-hCp#B{yN#AhYb4o;#BG>_ib;QG%%JSXIXPC_=>4c8mL)V zH_5Y|VtO~;VeDDxxaV32`{~=MGGbPu+t*l`r}dg?g4cH}^_!(=Oa7MSXqj0v58=k{fG26JBM*>-xM+dRn-oxx}rBgqx3rH6?dRv7@V{n4xbv zs}Sqp#lbnSO3LfhB5uWtJ)NCg$5(S1V{*YPgI+$n&4OJ{o#T7)ME5?Y9yfo3YRGjr z|3mW4f0%oh-3+@js+9q^03+msWOYKC4wdO8XOGw(9GR*5Y8zsp>s8#z8ptPibyvfy zsTN*Z$*#@U)osvd&hTL;GpIbkvP(J@gEvTnM#Fcemrhxg(31Q^1zDm;JJDMJZw%?( zc0;Vew_%1M)9g-w%m7%W&^1}WU1Q)!unzUkmG=hK2GR6bF808B-^JlBK~PP*ZHT7kNBsJzs^66X8Uc^^}gZqR~AiI!SjLI%D|Qg;{p8?QfOgi zgP*Kc50oaAMI+00r!#eo$jk$j;t^KQk?tcA8q_pdgPJ8=7_I_;bJvDm2+I*jhfnw_ zcVYg$2zkPuh>Z!|pWOJp5bsE~@GNZq(=eY&?m)ICiI9)?VxE$H+EmPSvQ3+e^e)&^ zFQ^aOrY*&Ya{;yN`ics)9;!Tj&W2AQpN+(nb(ukoiqBzVHP28Wcl8=GK#x#84 z5NyfU0Bffyv<#A810>CANKiS_kga;@JngtO<SK~Aki`>=nre0epD(m0Qd9UOLO-a6e(*zn znXArytaEyt8P+l+zy1#}nU%-38UESHq>yJ8`3$Wyt;b!NtR21+-|Hh=hj2fA=)w2o zlUsgdY?lD5F9Y~PpZD3|hv5l^=LHjZ&tn7LWGSo_AP4YFabOk}Pm!beO>s_f49D-u z#kKyuXkSfGWw2l-kCh%K-hl_{S0j_5Je%!cbF*Rf_#J$)!Zj$DYk)jBE2J@| zNG%>g`wZ~xd$w=Ssz>}6+;whR`Kt%hs{c>wL#+9R?d3sXHjH z$8%e7FmzRg)-P4u7u|??cdY40;F-qENNg~bL}N@Q9gVh2K(iQCqU`E^%v`cNuLHiJ zC&bMIF}AKE>QO~^3-)7LugI1*fVR%Sx3D7GAbX#-X~okA|F$Ash(fGczWxF<>+r-y zqz41b20}cOZVPPn99Q4-MO!I5x@8F>m+jY^E{H9C%JD-^zdIsFuu5F!vkh@ZF2Kgb z0QW2Ys^`{}<_%XXb2bEwJUhAQ%3LnsYirFB)F#A;W0-a;J2}0wnE{d+J4IC=S1?S= zNbxBFpKAX)!=M6IN{Fh)$?5W9L%Pb#=18puxKwihX-lT!3ALDpKB>Ydn0_7x}OVMOkYK zo|jk;;&P}d6(TNRN7FPf6QVO)e9NYDUP`ZTnijCJgIvG}C(Lm4PPh16@Kh6f^ZURW zr&ir`O$q$mVvM%|qp0oEn~GQLMLm12?OU;I#ql* zx@GlQDPb!g#l)B&y;wT>iTj^;?TL#|6h8_NYQ`wE0LP6rzxMdW$45VQ|6`jag;gaS zYp}yh_q1f)6GVI3{c)AmOE8ku+ zzW9JgxqTW^uIjM~8lV`f{2BvL01XW6i#pNo~Ahq{TUR$ z?^OV|nK0Rdh;pY8_B0txB`b`=1##lFl`Fo**~lV~Y8$Zcw8xFG{OT4Fc?muKjaPx* z<>a_Ig!3Ml78;`zrV0vk`U)ofUT<1SP|QWVawhEoU&#s{p6^S&AFlbUK3`z zCOzL9o003gQ>Ba`yWh4pjO%`rFMsWkya_(u9gW$0E6?Wsuwq_5PEIk5$y^8|@ncL| z6#F7LGfs+%n|4KG{0mk_mAB85dbQcbaO9||ebSl_56 zjK3HuvXG)I7+wQ9@rLu^u7-EC7Nlc5HzTq@G)hKf6}f-EI+$`mRXwP_2%Z`0>K4Rw z$Bk5Cr+S1z`!)65u;OA;$+}^(PgB1FUpo}4JhEHTT2~)Zy_|#ivC;5Zw+gX=^Vg0w zD$>3?t(asj7*ZG;IM>ajee2sTY2X7E$Mb=Znz5Yq4XU4vIt=Nvp`NjU&$}lzvA6|I z5qx4-P>~;<|Ib$TCTnJ!@6%RIeNa3cR5(An%uHV#nY#}gfDsNKZ<@d1dM}+p^`A?%pOBnNCagX`iWybt5o=c*xchG*c=y|0;?dc2d0r%JfuXw`kafU86QF~4_ zsCEGvmfE8*pl)RY?J*QM(Vi!M-5%h0o%I?0RL>>BC;fx!3lZD$k~qCL4YGmQz`b-= z*V(CkZH4fQW)ZWI3FMUU`8ma5Ulc9yhe;=l7Dv!=H z-VYc<0`BF0+zV)&Fh)gR9IO%&-q6BQ%~PtYdd=~iFcLeC2RPR5X@gvK&QJpo97-AE zUVDlwCeYY7P52*sY~bncmkW2}r$0CuUaYnFO@Hl9VLN{QC-?_DzaQ%`b}Zp7atFKv7nkc#Z?d~h zOnV|56ByhVGA5dyw#Nik_v!pZ-y_pieNV#fDbW-Yc%W|`&P4k9X^`G#d%DH1C1xk_ zkEQ&)I_Zn#O2Wk$*1|cRez0V*#0v<~0egp{P z`g(qUNQ}iQZVPB|_ZWiR4`;n{ZG``Z$ox0Cm*&%@(>hqDZO{AWE5#&pVxj<>uIku8 zR*>p&2D2*xr<*tqv70qa#&KUZYLo4OZ@dRscJPXx<-4hYBAv_yKTgAmnE&#elv2)^ z6VVq`-<(RNr3M~cu<|!&KrS^+fP4hyv*=&8mf5NOlBFAEd!pvD7w8&sXBwIGHlHFx zcPh~YbVx%^;YYw=(-hp5KMk#X2w0fmKKmTM(Hz(t{Jix}piWljZ9JZ3PlObJSB$sM zp8zCrn;xs3h4u|Z@VOnnSKB>GGrnPPG!Z_~aC@RWLU-lI1Z>wda^0wA?*O}m*%^2C zyH>_%6KH(?5c$^1;PtIh`q|vOQtDCjlfI5f9h$G^y&V^+Mf5-|5Ph+k?y!9hV2VBt zyCd-K9^7Xy;cQ9w+GC&<<8i@Pi0-#nL9fj-2=S*!U_>86eb$RZ-!=%t@Yj9#tNEwc zw-fEtH!J2y>roU7m-|Xti0X$%j0S?i<(NHU5ZmIm!MAyFTvlSSKQhS6ZAO9!zvw z5G4x?>D-=&m=(O*mu?6D@O+nNUQ`YuQ~5{Bf3t@5IjN4t?icgM_+rL#^$MQ}y|qp< z7V7*){8lCzor?Nl!0b;di48p8Gop~%%GGPo(!X8vHw|;9IAX>oG$#ltLb7w1Bc*s4 zq=LiH<`}=OLzEkej49)rW^wPJj>CWIVS3%bo1CIr81~ zv!-6sdn0Gn#BdsIG5E>Pq$d^%zl`sDAN?OPQFO>`ufeDSEgGH#ikt@66wkr)XC) z{WVLFYnF_Nj`5Cos?R{p;`|y@n|Pu}V`31QcL);`IDz#bAVytRC*l~Ux!hmioZ1(6%GinJxZAH?oH-7dX(S-y6c zc87m)QbBRUHbfgvaBZ7mlI3m-Qbu{IXI9TBkW90yW%P|G-xfK=^Vg-=GV?h(g||Vw z>uE<#@GxgpH-0f&Fv30td=E!rLxbm<`j7>KVG;>mh2Jo`{h>BT_hJXsZlkn zol(1nRbFIL3iLIroZ4Nh97_vz+n>i-I$6-~(oS5KvL}yxfbSl_kbqr{5wbs6=8z=v zJKUx9+qJv&qm(_&bXflz^tE1b*0s+s$FPsMaR$+&m$q-r)B9!)ND=S+S&ArozR*bp zQp8j`J&+WUw~()1d|)bU-EUxX`RMK5%bfWvO5|*M+uSQWP)HcF&76$y1JTW3&i_uF z(?@3v-nR?h{}qU`rP+lyaflVelh)7%YrR{X{od#8V#l>K7n5lVEZ;C1ZQg}_`CjPc zj|eMWBZYffs7%KprY0NZXE}1QQavbpWHEs`8^$|VxHY@j>I?*_-+04Bi@G&9Rtz3BL0rt07!Lq~>uE7B+ zjqbHRg}K15%)G(3vTQG~$C#S9k}P2lJaoPjm&x{6h;UJ{+o{>bm{ye85Mi3BK|BEL z@rul3Tp$FUsw7z`b|b_D!M$yy znMRojY^mT(9y?H`;2XegWvgt0zx6OMIQY!Bq(o+9x2HG9_qmjCtX2G1&rwL?l~#oX z)FAG?$24CtHR~|4kHQA<`OY@j0>t`D3zfOigupkLup_yyqjQ;RN;5QDVQv%GN9tTs z0srpvC5{q%^bXC=a#%N)3dI*5Xrh$(ii|t?ojA4!I8552pB{Yj@$)?+Ig8>{_5%)p<`p@Z8dTl?&uD~3Ky63zOBM^Q+CsMm{eMNy-?T@YTc=OBeNI2p1+6%4v zOx_!p$$Dcl?LK8Yr_~tkLaX?vAY>%+m&^_1``jj`T;u#VJK98rJX3&uQT}ebDb@y^ z_$2ggOlGnx4m;k&!kB>a+C=Pl^c!>SM(5yx9WP$Wk$1c}?08Px#b$QLHDm(GPKWp) zR!0nCG$jj}SXVOfS7I?C+`W4~Dl>7Q-o$5LMEde*xdw66>-~ASoh8^uJEC{MpQNlD z>rScgr}L`J8NbN&o}B9zUs2$Y_LcL5!$|(=#MiGu_f7mvx&rML=nk;I+zcDx%D*uN zAJ+SuKqJ3unhP&R*8l7G(DK#1?8AQjUV8nRg6xfx@Z1M13QaB5_5puFrqM?d<2din zBeIA84)*_V%QI><_NJxKYlXD&t;-^#u-`%aNVGOFAC{O2#~$zx$s8ORZE#}8a*UBR zvd(0cYql2!mTPVBhGk6S&nq)?eU>uTGRzx&g0p1!qS{$LJi0aVta=$dr_p|O@#p$@ zP@mQyWV&TVKSe#1FK!%| zjWx|rI-hhBr`9ynti&U?i1SmsUJ=48Fs;9~!22G}PMkHWS2@YP)JF3oE*7nfg;z;C z;wmaLOFXu~e%YVzHN**`Jo_L!{{c9>ma=(G%L{ebMGdEBBht@O`!ZQmmE^xyrYdFX zz4p6hDr>pqyBl5(gIssWZ->fn@3h}8zl}v)wjX^9b3g??@3;8TCcjDBN{8Itp5@@$#!y;WYV_OIz*;aGDHVk+o(&cdFK&&=|@v1Up` z2(h(4L{6j0j6I{a`xE>=72bhu;akHZ>#u6xoFkv$X{J%y}tU5&lZlqUrDq)cuTi09*NpKQKk4nFzG0Wrb~G zDx@PC<3;haKBmUnU^mPGt^lp++1*O`fX@*YITnG-Zs;NJSP7E)F+jGq1v)+RWbS}< zLG?WQe4M5&i0D>|DBp7(bDb*xT*o|c{XFM9tk(3~8N_H}V+Y}zbMVb8ow;$@RY9e}Zb&YeBhVgAHtlWV;~~OmXU0C|jdKhxOn}FrwntGJ)uTvQ zTyR?f-6;MXjIsVXsPoqZhs6Ck80A8|qS~;wFxkOXebg4i^(428SES;{7Rh*e_u@W9 zdkD=1!sjS}Oo`57{rAy=DANzU#`1M`qBIZE}<_*mqwB*R7LVedei}dYr z`sWI$bvvd07SXz3?>^a(V;{P7DR3o$)4M7b5--aAzkF9^|3mL(Bzn zK@j?3$b$X_4<7^gu;ALiTf<%|)OU2}>i5&3{)<{2mdEX$vGbtO9s3sf+G}4-$K4IG z;J{D4d6-$ZShq;|R@Q7cZGo1K=GqKUX5(34*dpD5pNsJtOHv#)~PjUc?agMrTu`A2vgCS~DU1HN@JD+`Bn^^=?Cc1K%DEnOQ8yWdQ#P*vV8M z&ay?i$Do%Z7d^X}zBoIDfsT(&)178bvGB@@MyWb{JE0k=O_;rCU6lMg|Se$@G)9CM@3Og_)ctSA}LH?|;t zblBo24HiG?u=r8bWI3~BoCDS*iBc#NNHg&bnLuY;>>7_1W>_ViK6KTZsRt6ZtxBm?hJSls^{q^!vmx;%?J2ioE)tGpJN)IZpVv|5cV>~Nbf$Hsfjqk!;77*Q zw8NJ6U|2?FecOI#es)QIV&3f1lDmoT)S17?lLA-lImE<*UPbZmA4b5u^v@|{nxfr2JiB*#ax z9|+lNhAl9|Io3JWA;)St$H)A)tt{$df?Pe*+AgYk*+6Pj*oQOI`aAfYKkDSR|&zo9>kB`w~`xaE%`rsPRVlFl53Cu!6tAKN~fmzy43P#-4{dWJPkYu$axXvVqoj z^9J($cHN5{MaVZKlJ8^wLhFr@`V>a$Qz+X#Qx8r>szTIfdi+Q>>g-EZcJ zz+C?kdqEf_rB&R0jSVb&H*BYH68EEinW!6b0g{o@{?#u>Z7&V)U%w?!U5dGK4C&qQ zPuYXB*iW#HoQg6I;ingLS7zAP>sFiv$u{ddoC6;PUf3)02-q=l@T-hi`(DpIyB#lM z1m?r?-HzT7;ve>Jmva;%M?U;l`h6U(&r{{7MxH6iLp{m?LorSGeIXNg?fuQa8olRW zgG{}DPb4kbAQuAp<4iMQs9X`(^=+K>Py=Vqf>rPa*wJLd#;F3U7*{46JLK2^_}(p-M^~u{m8?_QH_<68Y|*oZJl>rDo+6MZ!xnM50oB&J$|9}dhg!n zTW_D02LJpkVocwka5uZ!@H6)$`sPF=Zn0;I5N#pZby?ioJIk2@lr`H=|6p@Gtyt$c z*s(tZ-||dgSw7#(jJ^rj;D@AJ&8wNbZoZRN4%U)?IvN^OjVUT{Golz}TF*)o4w@{{ zzU2+t9nQuhc^V&UYP3y;G(XAhuq6YvEk88T8Eqgh@tB>CZdG@FzN&p1r-P)AZ(qqM z+dk7DZ=BkYF4yl!1ka5@oW(nV`4a4*8>PlK+M&VM<4Q(3fD^I!iug`1dlR8l6G@P&RlG15X$$3+CHXUx&S71lC^!h?o2`G14IBCY?0kVnUY_k-Zm|G)?974Y}D zVx=YkS=qNo5NjoZEh&AY(4@m(Wh{KM7UAbbyc-e~=5^w82hKM%r!Ij`vWO>ePCSU- zKZxEhx&{=T3e0r_;lUFE0-@paWR2?PglT(WaHD-SXqDt zjvmSLF@dFjVa(4MI13Lum!Xh6S4nFPg9BDB&iCXY@(AQD7HIIWo=2pQ+nP5y);r@7 zSz)CADMBKNYs%vgmx(p8e&AZ0m~{4x+HVq`0vdACw7;ttHk0mxsaoSmhpu)5f|p%^ z&G!?C56W91uMj@)y$9Q7s;#FZMIMv>5h(%2H4}*YOPcU7dhAc&wW7dEjcWW*-*VV! zt+mDntSr@X5sj%qm61X9gr;#Mqd;_vmzozjljK^?E9`7Ue;69`7~kTiMTHHLBQ6Uy zQ=cqo=trwm_@Vc}`G`Ty8ORBNOpLX*0%+hW4Leag{v(-x{<%q8n}A5JpKhWap}W&Z zo2Ek6MWwSwwwvq7b>)Mr58(?ATb<;1AkCUEfR%^3Gv(29Am`?nib8Y-X7?B0ZTab&RwsWE)@<7A6PtUI!e8#5>%zJYzle%*Xl#J7B#CZrcmypWFa z(^0;;H^;rwkl)G2lMEJ~>A06(5l0~Q4taQ*orsQBJ=n>mhWQA4OU<-Seh|qI0^-{4 z9NFJJ$JKAO&IIOd%5g96$q$eG`89+*`Pq@`>(*}L%AC3&;L{2_d5 z!e@^#vI}7#?Q_!n*b6+-!al0&CseNhdo)ehUHH!VbJ9B%X+kY}VNXx(tnC<+966q3 zcxJ&8j(^EP`L6)i5o@=6vL584zC!HlY$i}kcu|O=#}3TK%}D*MBiherMEmHS+^+*~ zH#+G3myK)v%8a%D^DYtqDeRbz>qxVdT#jDA=SI*Z7 ze98V5;4PHtaunePG105A*u1P|=5MAcaop^uI$fXlb>v;<$odtX&hJbWy;}$=d+M*= zhTq)o82X#^If%RY>#xjoP+3&!75K*xXW2G}PwKYL+>Ji)9|05?P&@zzrKM?uT5u~zeMy$VAlMto&v-X+=OQVo?<*(@a)F(MP%M{WNEh<*>YRL!jVjq=Qb-v8Xp=jAt)H>{tbFDWoazmqI-ev8Y|vJn_@SHvHK z(_2!#I-#)WytADYfmf5m%Mp#MgGwuAv_B4h_LKG|7tqcK)E1o2sdNwawD1~! zq#{4U!?w=D6-Z?m+`wkUdH;BUOZ@}z)yv$_7tWAJr;4ljs67!FC(R+Z>*WhXLyEX? zzm0WfJHkB|U$DqMSnjtNUm7&&{nCaEC*A&&3+B0bf12aOVg|RqCn4D)Deaa^inx#4 z6BUV$MUBfFxvILndfX!(frr+QVr9rQ{#}<6Rt4d^@9l%^YiXaKL$lNg0P{2uf9?C|=&?pnI=m}$4+GI@(j1%_;M zUZ;|KweYTdIu~(WFO@PD#h3l4baakP7j_%2h)dzkSzz5+7>~&AlrpM$oXKLMwA{c= z%q-CAcUk<4yk~z@-oNtwrJU--T8020Bm*)eTi|dxXF?riuf1pFwU468#dBt0Kz#y# zKzP5LkHl1!3Xn=;TNg<+ty9VB;73X0brAme1vuX+`9bh@D}Z0zqraNro1>(5S*wj{K^a(JI`W z78hOyj#M0CO^lYcHcHHjFxPOFSl_JQDlI3<7aq}x<d`%@^+1@wf+5dGiWrek85c`K$w_s!(cFbFBGR zGv~h*cjN>!;?op`PYc{1eiY;TMw7Q@LE>tQJSX!TGMpJe!pgOhwF+;hH)G^CPS{q` zc}@w>r8z*X%4NP0w_gM1Km5yBL@A&bRorY8Bz1z1^4z-w}F}nsyg%};t?>h zQD@;n08U^m>a&#FjP`K+;=IMvM*5jl!mFn_Lg%7cm^0)%Nb`c`5f6K%j&orgM%rh{ zK1tR`BAp%QEiQG1lb3Y1O8=kQM{3SV-o1&?{;(RFDVo>9Gi6C({KU(mL5|a*^xiu# zTEFuNh?K0U3$JF8kGDolD=~)SP2myDI!hS-X~7qgUTNcOWCSi$&cA8=h<@$$`MDR?c%Il)f4#LMCfL5)9zTU!)EJo5lhQh@p? zX=*8+YZ#Mr-PM1+H3BOo5H!7u5K}taH`?AMCWJ;g(+qc&v4Rab9_|_AhYtRl5k0h1 z%Uaf7eRRK!Jn2%m&tfi#+oTjHGbk5`_ebX~Tury%6vIVPaZT;VIX{=hO?QZ6klSgC zcX5XA#cx6(aemXVh}|2>45KlYG|t&L3%D?T{bNk~KE(-NigodWWL}ekbTdGsHIsOP z&d;QCde6D{V6vMe;2B34V}U8QJ}U57kTs*_(gToiKZIu$p2zX5wH|bCk#2_k+lJ>p zJSz;4ap%=8=8R#P^cJZkPUr124+00KxcrUmgzv@LkYQ}l=WT@~ctxfYaZpo|!xyaY-fC_@G))u7~q5;Z{iJtzgBAR>LFoaaHA z4oWvHhr=aTf+B!|b7X|F36$GFximm22gMEw*=mP#tplYHlz$IU)_~#w~1C%>JnGee90m^((7J%~L0A)5Pw}Y}|fHD)5J3v`DKq&-eAt*%y z6akbwK@kQhd7#_{%FP3mTR~X_%7g(*E+~sZu?$cqfpRw}rUA+XQ0@UGX@HUi%Dte( z4N#(HZIMWO@N9nj;z8KM6ka|f0e-3ABw26rFytNf0a}5d{5FaA=YjW&@jQ%Y4W4K4 zK=WbPi|3Dcj^IIr1;ZD3F5vkQPcI(rF~%?yj~R~@&&_xoc<#Wn9M38|>+n2>XFHx( z@igLT#`8}+r}13GLpq(`SxpVUtnDNJMR8d_=q%^W4RllGpfw8XiAoK>rmX%i%A@_1 zfxdVQWwG(U&iO=tx`EQ&|3xY5rwo*}#`>HVef^7CJ=vdXproh%i?XhtGEmZbIr>5@ zblCZj|1+rtvUcZy^G#X16J-)bZOyQ!N-fbTl%XGZq*$<=)Sor{{I*gTZ1%5WCaW*FeFbmFF znr^bX(k%6u!!}og4GOanR#%tBPr9E&ga&)^Y~j3kL&(rD6(wYtE(6uBR*Ks5UVA8Z zEKZnxtgoHXos;a1MS)`Gt~OTp8A_M!P`pNA5z@cht!c9}f3pH5>tHM5O?ynx&{Qpi zeK<}-9aqH5vVBLCH(aZ`kz*5d>c#llLqP994SS+#e_clVMeVxyoa1WU$@?Kovm1_U zmA+bcJyOywAxk1(UI)pK7+n_Pb>3lyF?p1+qW( z9rgt>EgUa&w(O5RuW+_(r83v?Op6Kj`pKIvA!=Pd`gX{sbC;3=1f^;5BXY?w1)$?0xct=Wg3w5 zY%@BkZ;e36o{uv*$^SY2FzoAx<3!rf&6w%!Fq}_j$P%$HVF9&gBlYnOpyk1XWe2de zNRPJ(I*IG`cdqpj8+oiZq<`+keT3{)`eT@q?IhVruGqrK`jBIgam|8!_dhtF<=|Zg z^c!@CA^8^Y*kI9!leT|1tn!}*M<;_{h+kP5bKs7R;Zvn8Fn1$K*-1{@kEBhKS|%W1 z*Eb3;0PEv2tgwhPZXU=pX(N+5)%A_|yAYG6`toUKqU&k8Cjw!n~$>m19BgG!$&bUOwWKjmOy|MY|-zIYAYH-S!M zCyl{2H*_JzMiUTU|3mUg^fqZj?A9(|OO+O`KVRzH4~xN7g-NjA(ljT*BlEKOL(mSt z<|jhX5JJOG<3R`}m&Lgi4XOe8~>^(t6037!#rG#!0z2YpVEM*9$G@q_h|D>@^4lD0NG42hP28s?|*)9KEoV zfLd}+(v)8o7xmFQ-0E=VjRIyK-Sc(X&*J@M!WO}3-9OOEB^xO1a}6YmS+pU1t3yut zR+l<(_fv6da~-72_^x~_9Px`cKZx&z5SNyjf_gshIVX9xlE21fadMFAfIL>^loLm$ z!^o!qbBaFS|kyB_Of_NUIG7J(a#?rS5Rs;BgM;QOz=`{ z#3L1m@k{+4r_5Q@$X4xl=q&ZkIy09_t0q^)02w8gQ|A02nnIXI%)SelSq4Oy;FVM6 z0wJBEJuzcAGir!lu4HyZdRaLo7D$7d5Ml>2l^1YFiK}+Xmcg=QjihCN*Zv?%eRw0! zfM@aZ(F@N3!|pO-VmxwTGq`ax#$%N<#XYzo%!kA+#EDPIt-7azIFV|}RC}B^_&vzs zL5_vLkz=`>WBPSD9(S_UzmxCw2GsMNzDcedFEq7Jh}E5KYM(6se=BaCu;zudjnl}s ze6q}q#ovtfoOEih9qZ5i4&32k_rz?yEWSoSNrC3dDR_C7P~R7HZn{8rUluzY(A8IVVY5d7-3% z_~==giwLm=G1`PY*sEO<&-Cg2#1(iqz(GbK$8ibx7?g)*S$#Rpz*i%d5?KFbO9_h| zm|d`7%NKgZL9mlZcVxg$g6{pv#ToFj$#7U;C$afF<$b0+g>Ij4_+dJqC|`e``danX z{`M@wG$;I5%}nf~x5TQ>?r*n6XuKvLw8^nkK+BELIL%~#Ebe(Ur-nn$m4^9p6?eY- zGC55;et!V^#6tYO3O{L1?EuCQ#Uvp8dcO}$`J-X|I@yMijq&xi#Th8$c|0^%_qR`s ze3jK~#~l}A%lGSDIrNIpBlkGGhnODi<`iNs!@Q__NC;o5W27z!ECIhYgQ0%*~lpk{HoOmCtg9aW5!SX7|d7!5xzITA{ zcXq!UR50hnd40SP>;FHedxp|k>3zL{Rt2o4ayj8r+}+!nnh{Tl2^{rM{TPdmG?%1v zl;bkK)O@c4oV7LH)xT=&r*zOW0jh(NEfD*d3@@HZX>9;MCYhxg$q z^hg}FW6Pyf=4MBDHTtZb;eHU$_SQ=rbGKgwR5YYODo(bD%!$-w5iFKJLmCC+^fP0~ z4j#2R7Q-wtWzTQe@B_ho_K3q(Q6g{nHQfl&sp17E7 z5*qU~-lSpd6c$()oS)sn;{U6yU*@M2usbtN$qV+iDg_Sy>5PBSD0b&#P4DONKG0ok zjs~fhrfBbeFOQelVeIh);ip!zwvOJOjyXj(xzXqw8P|b{I~+19;1h9Q$RKD6^??t7 z8)7mhSE`-Z>no4Ki}84}(n&s!`oN(hOf&g;_MczLr*qt8si+n+_8-`r6hf@96%iul zbgKkwg8}|F=fv;3$v0p6{rR$VP|k_pcKgfd@4B+nYSl?YiQ0Hh{IXkZkkgdZm3*FD zKYbFg_~rG`Q&;j)r-oxPN_>WrtrB+-URJsKEAuSF0wH~rPv2x%!TFc0=mH8No5r5v zM$Pf(rOfgcFFA?1xnzYMb-68=*u;(cc9mTy_TPJDK^oJhR~fxKFvB#6=~$ar+5A}> zuh}87%w$+V=Oc&IU2>$ZY>`U;Mcs<+!)(*l$JK2%gQ7i^MP$p;uf+#?vBr%a=ij%Y zF>jc+t_*K9B%jxzRF;7+u(?aL^(<_vD>DadeBCN@$uwc1J6opz1D+==YLn!DZOPt} zNx}!68uo)O=JCUMlbXj1#)8zWY~gFfSr`qM4NPx;w&*2j(7k05t@nSKTTGGh#0GCF)mpl%eF?RW#~_KrtXne#uRTq5lyQzPvkS>Nvh2 zX|?`rhQJ-jQ{UCU| z@zo*VAak`$hW<--yJA0a%};%4;2N&BHjnl3+sV@+WF2ylcqQ&IW3D+!v3&XJf)NQ4 zJ2I((1#-)~A*uD3Wt{wtG7{j?y8dvwJ-sj_o(ZMTP;_}8H?LWw&iDe+jKICRz-(~u z`4okz1z4irmVMG$pnSFAz;NugkO9Y@9$v`S>jRGlQwo)B)0OE3Y&~z%2X^(c^+{N< zN`i^<`{hBj3}4tEik|RJ-v9a%W?*zw%qaH8Wl2Dmk1{l9@pf&9AJ^p@Yfu#`CLp$Z z=$*XpeSD$L9ul{N6bD^L({Lv_i2Dl3{&MhpXPZK^`8aGt@Ow1uNN&W>n0H7bUVG5| z##~8}i#X<65wrV6wkpZZq!T9RsC3qQcS@=MPPa9k_nl4I;bv3S{&CPo>`q})IsXp# z*%U678MC+D%4;pEQ}8M1QQt5GYqj;(tF3I{95*AwBJjQ>cR@g*U~i;S4|?{tFX59c zwat6m4TxBy7m6&mc~z(KVU z8M6F|k_tZZ?8NTYy=v{r9N|cws-0CSj;nDQ3W>-2x>_~up$Rm)(;Czm-M{xqt>Jec z_puZIk|&+82+y~&JJt16Zjzhx#~D<9O8HJ-dn*Tw8;v0$ponE_72cu4*_Q^F6j&7g z0${u=_`xM?wZg|_yx%-G58kZ`2C z7y6>xqqH&Y)|h)zv=WaP+)S*(8#kWy=D=$*)@)KMzes*#Xu&v>N?JVj<&*?OoTb}{ z0oq`z?x0YoR-AlyI_@5N!--P@dyBe0Nm9jy#Cs5hMD)EoeLLDc2V8%9AL$r>YSmya z4Ej>NUALb*5E5P27B+D^HJA%(pLV+%t)#TJzEi?+_#K6;$#fnm;t#rRa~)O)(ZIj^ zH*lWPu3wGxfG}Ol?@JXv6|-Lu&%2s*;gFh#Ee?# zHew+dI0%iq_R#3$LtJ;nP;8 zZNVsco##6n_N~~~zYD5p7u0*r*!O9bzA7Gtr09|LkVO28oUUp*wMr$jW7sn=jp#F46fTG^z&8mcnBw+adUlUH*dMkcYhf>zQCtw zpP-%ujd^(0-XkqAPcvDCGNP27*cfN6VMm6s{Ah&sRsXIKf5ZXg@|)lw0uDyiWY5KDD;{Pz1_-iH>v+7c}zX_q!EJ;2{U92k`ZgviZMFI@stksqBrT1@>0LZ6ONdWpCuM=DZfV*cxr=fX4XX zR-k_vw&i{I@f1_onW1P~#PV~)ZQeSChQ}+S!E1J&Q8<=K*;~RD% z?lk#iRi`R7v#^&ePm4bs>s6dGrj7KqLVBFyzb`G$+nko@Gds+7#vJeAi#m!BT4H;HeoVgXKlIpP? zzQJ~V;DDquFU+@TVjaiYAA~ZaRm=*ZHsTjSAf}Y4Gqh(_&Z@>?l_zjhOkgy|Nx)Y6 zIvB>IpgO0)pYdd*4b7;xLP+$*7RK3i0efGpQ)z^qf|Yp@wu``!W~-yZ7#vx8dz4A< zY!P4X(-rChIpCl$I!Z_^Z)TbkaA%`F>9;R<1;799F2qEF9UEbJ9eNmN+SLkSDEP== zf;R`Sw(bmNjxqwh4(L>iTEw}b`9KCDzI$6TH1N>Kj_7k8GMx&-K;C4)hy>$v?@^Ocih_x1i90GEr26Hh788_j2(Anaj zxVzE`Vt3KY&M9s}`Q;{TIjHD5IzPJIpd(+?_zAP&DG_7R1wIO1ENc=}0am#QF-^8e zChL%fI=9B6_8Nq<;x|Ai3TvRrBf|g>PP6r_cv_A*dU``k*+-oPI5RMT6C3)>f9)(# zC58c!B1q+#cv8Kp82lg2s@?-Z7BuCT^*%zx1a zq2x4cxK=yxeex^`>sP5(>8RBU19c@z1}K{bC|e|p+%6zI%I$Iwyb0G~Eb0G7h2y-< zm7_OhK+3u0l0l)^)+Oq%?ZEtp^;>p@d6eN2Vz=P$;(9^VCP0Jsttf`V+A}-SWJ6-% z4CcW@fH^n~=*^$1MpkMk-UdA(ya3LyImwV}^kqms_NM5}uCq6{9GR~6O^Vphgf)ez z(Wtc}`lG=OV;szRCLUg1L%A35?^Es+cZriYEsy9gkmHWDevi4pZL`C7dW@qb1#y*v zik6l#W(>tEqu7aLM>*2U{sH#H+YC-hHxjYOj1tlWSf;p>;agVGZTL#X&sNaiRJ`sY z{6&9-dCdc*G;Xh#ww8`r{Qy$Gf1w3;>$^_I6&Li z^39^3@A4!!IRd-5|G*~nU(h%8%T!3e~U?nP+&GzGSJhK_cU4H5aQVP;>I3>=ZOn- zZe|Q4$MpNTSLo|6JO0P{z4%h-SmPcS^~SP_U6D~?0(V!a(jF)c_kh~hg1v5O=X9RK z|Ifrn`!&GwYbn#36n-@{k+)T}l*P#JAHds|RkvKQ3eTdK{?*%3W=GV8ETPgtv!+%2 zr;Nm(iIy;<&X*B-?URujf6!UL4grcTFzkD1ltyBdrelOO5vdIk0kVXLoxcMnct)rNSg}+eYFk(NeFG)^SPouh?uSm<7WcLIXz#`I zEoEoatG=jntKiLPg`HfhxT<&Qntu5|^_2x<@|0YAZ@J36WDWH*Q+c&NL$^tJP9`MUzjxbZj20A3neP;*@wH#@&-C2Kp6 z$13C^SMqP<8ZGB4yDnFj^Mh6zhd~yrkmSomzP_GK4T6~&^NysIwJ1sb{9~fns^24G z`YV!_q4pz%;eY&Q!i%{ zBtxH+37b;P3z`#G;e*qGJK>E1h30d-BmJ!&eg!u}p1vGE^YPOPjITo6Ddf0+)vP8O zF#v5SgGTN~dF0}Jb!)Pqr6m7EieE{*PW-URu?Z`{_oAt9B*y92;a~OON5NMlJ@Zab zFZT!O7oTjsANi(HJ`-cc8{~_Eoj`cz7CXZI_`000rEI6x4_niOW`o&k9-e=uHFqRq zV76uncfjXEdFv(d_28I-ry5k|KLlw!=0)l}!%1k+T(tq~Lq*VCx@OJ1M#d6*hQ=g3 zB6EVsVX!-o=aY^r5vSI_Wvl$j4Lq=h`Sy>wexB!h?(iFk+Y#LsT4b!AQ=N8WHsJTTu!+x}Lxe1=T1JcAkF&cNjuryKS9qGVXwAcVXOD-PgPicC# zzC-*dn0Sa8rD$i0pWUBUkY1qd@;ufd-W8;{w4FW!-OHv?#Mw?n3V)}IDf--(<2E;R zh+3RGNiI#2q~>5W>gPJDaq6HM)4-BI>%ghB7}3g`-OxcP(5_wBv*>Kqk5}+}*i!W4 zb&tE;IqlvVv4W!Oy~k8Iciq}^H~a#0fgUN-JXzQ%t<6$&{l%pVbV@`W-E(`<9ffHH zxX};ig<<-{Mb4+!77$Fn!|Fy-M7S*qs`S z!aE)Bmj?N9Ev+Y|N3#S+jpUwFo!0_9BY;LWvX-w;)ktMoGc9L)kEVRncxzEz%1t<- z#Wz@Csc@lpD$olNiyXSu$NRGFQwn3{@^1(7@1%yC&@+xd`wX(IP4OV+r z;qk@};5uc&N;IcoymJ%~KtrN2INmV)Mx#J z6oQ3IEN6yQWqkfK_{-qF+1MeD?oB`o*x;#gdLL`(5HI2`n2x&L5~8z4F4F;hEAZ}& zR)OtNWp$A4qCxH7Q^_E26%dX)#Q*gCvz5;Cgb_{p00YhrbjE!KKl{(ZG)|99cIPP8 zFox6{7(>YuxJLjl@H?bW0`K;p{pn0Ry=>D#W;AIMUKDBt{v~GIdN0#%g{IaxoJQ$r z_x-C#kMpRnViuv{CYX4P$@@K;2KA^1{rt`ZOE*@{ClOs-8+ZO5qPc(|oK?+}?8*KdJox`1qa6rl0g>RUWGRd*eoF z{@{!)W2M+*&wL6cZfzQi7)YV-S?PJq7O2wuGM8Mdyy6CE5_3=i;yX<&H zT51~RSC2~a-znE9ujgRH-jz1t&VoL|PbYNa12&-uwd)h_>fv|(8)a*7x>5@2Q4TvZ zuEqPYv>12=j5V7!{Er-#XTFE1YMM1D<9 za8M-wnV?O$Eaz8S`g14#S8jbIcg(MH9~sDfY?v*M@t5Q&WvyTycxn#r(zoNe7tj1J z6q;JB7o_1>?A$6%PA|G@bZdIJN!z80Y~W?%G;+X$RcUD&PWxQWp)SLE(Kl}IT~H(;(t$rf>y=)0wVA{~UH>#xOBewp0TRJ8P~NcpE* z>Afd5e4pRs4BvC#>YDzPN2n5V>siwdV3vO=-_vb@D$gtSyz{s0jJDW1CYGz-%&j*H zG4dLCG8kTCW3a~N*7w2Zgdc|}#_l|foUweFdnSGkFFz^iTqh;2`1SS}B|nZoJ#t)S zvtbl&=%c74(u(wnZwEKXtMviQ1S;t{Xsh|yW37mn&>q7d$zwW#o*2lKUxv=(mY2C( z{*q_w2zVxq(|h?-QRAY$Y2y_BhsG(qPmbffHq5~bp8HB(E7`YMdw}=9T6wY3v{`e2 zZan|?ESS!8obb%T|6b1_iQAf6--I|)iN4p{ZETb*fvaFo*DWr_ZR=*+{|-5PQ{tyUy@_Q$ zMH>&~o%U(4DjaELZ(+vY@+H;7A=l%y8mH{xN_pWx-nZU6 zHN}hLWl6un$QY@7uAaO%<0RG(DGAG@!)L&#Fvj4Gck$mFNh1&&Qxpiqyl{nO*?b>r zfRicO_4GBBotIl!ehpet@F;e%-(SCH0i)meR@Z`u6~Y-Y(8n1eF~x6feY}w|Q51+X zkR92~tneV@Od-TF;i1oDwx$bKfq&z&Sc?$5s4?<(k97=GqZ}RPN+#Z1=-bq+aqw*zbTFPRzQXWn`847czxVpO>R)) zl+I?bUgJ2<$L11kstNtpegpfG#O%2W{lkmS36){{rH_FRlf|Xo#!jYE%0)u%Eu*mx1HaBl=qi6W2S8_U*}j` zSQX5*?Q2wx)p@wHYYSCVbRNbu#WnYQ?*GHuo5wd*tpDTZBx#avw6rXxEs!QGErn8A z_M%PGHY5#DRs}(=qSv|?L~g-_6cCH3ECmIMitEJ{TEuJRVo_R(iuWc8_X4FFR0tH6 zbb)i4rTM*|IVVv4+|TFt&$qAF={cD*XXcriXP%jP*76NCt7N_jeTlmf zbr)V+va-P^BPzdgbx!%g8u+qwJj(KN>5*q1v`raHnm5S>Qw&?Nf-8M-1#i`Iu3eye zW9>O*bIz5(i$D&%OQ{@NYwsu;Ymc{E&s6}fsTJoTKg>TzZOef#ltqsDMGIzZfmYvU z^8mz4!)a&4?B-jFZn3D^riAf`%@KqVt6A(brR^5A)+6wzDZ zXU?__9uLSGN#WX52-#9uq4@`Qc6l|*ssh~`S;XsBgE!kMoC=WM@8?6$xmJ&YemguF zzGCNw!4m*HYy9rj+tQdd+MA|S+ar#^jvTbWk-_M#m)ndG_%+Z0(7MLouSBCMVz&GDSF zE$mdY#TEpfjC5_baJXPY(>?Xvr1F&g8!XClyLnDQQW7F9)=n9rbWF+8;>1Us&S%Jf z1;?evoZ-`=o%fDfjhUr%9B3=#@=SSoGoiD^i`b=@Gwn=YJLSouH(&)e!-p8-B4p`i zg}Gek7N&|%>$sHVMHg^#=X45lG&ueDiSVtg3#Pn)2w^AmJhU3&^~wJzd_Sd;4^CPe z!XL8cl=mu!A4csAc)`LhFv?K(F?^fE8DarltO4FAw)D~64T|$EqS9Ot-tNvRZ^4rS z9A-@gxPtIknN*&r)}DCBWb~Z0uhQiqhVu`#7ZA;8is2Ip@BebG_A&UjpIxNL&ca!U zOP}DFS%li75}+Zd)|2LE9^`3MgIjp3%VO4N9o6+Wt2H+~; zFX{X5fSzVgJRWmi(!V79C*1G5Q>pE}MyXwkGkpclR{AE&XV(46@V z=c*w^LxG<|S@f>ZGlM2;2-1hxqJWnMn;rjC!3}R0&s<1><|c7nV$Zw-Y0^&#FM${S z4rtCBrd&b4*MMGHB@EgN|Ekv#-Q0-W&V;@1;FOS~P_&#&c+sS8dBYUE){Etjd+Nr0Ds%1h*^cm2 zhSWKZyHX!?=u#hZeuP={AOEASHK~iRUaU^-<+$JVd8!)HvU}nGd9nVsB|9IxZQ0*2 zl0};HuUdBXpaU;6I zo=5I`{G`J@P7HUgN6$yVOHE=~f{v^@e-;wOXNuR&m{Oib_;WW|7`+6q&PBR}lz~|h zn6+EQ;!fkzZJ_6oDcqJAT^4wjbiU(;T!anY72%fP1@MWBbh?y#;lq{NdQq4cI4|UO zYg6mY`^?4`@ErDp>$RRwMS@iED!f(i&^c9m!jSe6s7S0{y(jE7t!JG-%b>2>WYAPC zwnev1>=pA(uS+ppugmMys_I)rT~sg3O78Nr+#E4BS*h1T(^LsBY3j@BeleNqwgG$? zJjL>3F9>&dwIdsxRM&=sZlOl}5V5v~n-9Q4(_-eKsaiAGp=w(M3ugn)=lq#0Xf;OF zFHNpZW<8m%aw(BJndVCaRr(zB1>sUxflJkv z4PS~}%FjZkk7&g1{lwEHE{Y14z!wCoH_JuyvgI2kvwt8zW;91>&Yv(!^PkqU&tX52 zfH~41HWcFyNj_;GpQ+S3Z&zsVI;GJ5fOU~#N0Qve51DB>_H;bkYf?RsUj+EEx{({4 zX}~80jBxOi!8;nFOMw&$KKF_cJJks26<%&Aw^f&tGA+`~Z!6Ln^=`zkHk8kVmlHJ)gcbAIGC-_9Q6Du zm+CB9PpnUR9)#xztfv3ODw~WLu&~P4J69ajs89A@8Lm;DjIHcnw1BUi$!F`*e|P>2 z-=t>+Rj^B#?Tf>{2HJPtIKV8$#^_CaRQqlALl-9+&k6PQ6AuypG8S}>;_wn5jKkDS&a#C30lU2Su?!jZ;$aVz48gVV!#gmZzd;_X~i=Hc2l z!5uK*Ev3`@L_{h6F5nV&b#3j+h0d4@{0ym-Fh_sdqXLd$LEaSjd8@dR<2k0OmXgBo>^;0acBHYp@JQe(17$wr^ZuP5eyl#z{V{8@5K=S#r6w&vY z;B^mx?l=Fg8XSjq=pj*zv}sP|`%zWuJqhpgJEE&PgkC;M&2vUoH?Q2G4m%OKV?fRE zl|N~QoWMzP$T*j}I-&fmFwpo-P%rwYdp&+>BiG@-I&uyEYa-j+^kq_j>bvaJyqbbjZ98nv)oo+L7BEdKJL1nZ z3zq_^W*xLRn}uHj#h#4FrVdShEOh#w_2MZlx7Ru`SGNvU?i3|!9lY+X6N`4Q6K$K; ziPOvYs%F6vP`AyEDgnLJvAtij@b`dbCnAXNi!Be|p-gSTeo*P$^1xUA&33XYg8bNUSj@C5m$bt-AVIqoCn^a-{^n+3N8nm*i>S3b3ot6r`{rX*dNb|-$B`UG z_tY3`)E=$pTfcHo)Vm!*na@%a1|6v=Z~^q-tSM7Xh|~kS3VoV2X3sf+@8(m^2|3-v ztXj{0e}8-v0e`fJOPhMh*?*7Tx?Hb#KOjs1j_9CsxE%ULxkC-E{(Az#*no26DYs(m zsgVO6Y37pTAB9{o4LVgiXar9d)t6yUCTcjv`~9I~rGbuBKmqbzHPyA-tQVY&!6JGBwt4Xz`7Ae6$h&3mehlAE8 zlnld8X;{&4{GWh+8D@<@zdRnGe%Tu^SULSU;gP_AJrS&D;4OSeiunzSt#`Kvw$E?K zdhG)M|67>xA$d|8v=T|4bkRv~UiEKdP!bh-hCz83gYrplG}@Ah_7ZI%InoZf-92SV zp*`svcvp*S)q&ygVG+Y6m+z|KhLD`44g6YKW3qhp9mN|{iu5*TDc|Y3D>DE45=!ZI zhY#b2s`LYG1EHZ3!*eh3+dAL}C)1p0JukfGAEO(9d$oU(E&=zK{dD3;;B@BRhRl=` zdh|7-uExM;s=^rre>T!(M_k>Qq8Rj8j4ifkU|B3=VzKx|TFQv6jRJvZ&Ob@;CAz)iL-`@oT^n_^kwY8UPYCYCxTTT8J& zTI>r)yuuDa?ajo9E^wBDm;EWMUFJHoi$+5mC@eF+lpFdjG>PYwz97cU{8o&}tSWs7 z=e1s$al`u7Eq*emW}La?Nl;dYvDPI#>@Qiy-;C2_h6=jHzdH}q>1}!|RuE%!o0`ME z%`?LHOKpVyV_$oR5^-S_zWDsi>=#5xni26ddMLLC-nI++PdkU6>xcOh@6(y@H^*WA zd>WWpcfNFBT|jU`rWXxc>@;&gnCLZP{%vtYSyZkli^6rMVezuh-EpkX8U}DW!uO}p zSG4vLK9H^%$*aD^nTqfs3wCm#zEd^2%6(^r_k6K6TX2e5T(_Ba3?-XwNu^}1wX{M@ zJDRDOPlsNxyimlK#+9bkL=0J+KPz#E>9FVSigh+cNpk7hx*+x}r8TReU$+U-dTyym zC|P4$1MkRdFq&&Hn$ynVf9V?AfYRqo;JH~6OMVo_`RrEvjLlt2ZZmwxZ-#vrw`ntM z-xTc+E#>jVb9}Y}cP{o}i*oZ{t$&>!UjD&A)#l~a0QT4FtB${BL%aT=lO3f0rAQjl z-`Pi0MU~g2t-QZxtf(D1R#Z>nHjNb(QT(QhmCDVEP4`=Gvn0AotqUvxVUt+wN*vJ- z-)N_B>79-~qB0p@j6@kzxXsWGPcF9bo8Mib*nDY)a`Ph8`B!ngt2$hf9_v)^nJXqF z-=o)f)_d`U@0Di?;K4s2+$)+abF95xe0rjsD+0NeU(Yq!VneRk;zZolJ2lnZh)8f z7I?M{dz+9BAjM*)GcnPg(A@lWJ?1F(f^oo4+7HgaeKq!ke+Nx!#zl4row)X$P-)|! zLz;wZ5UwG}hdL)2P+KG*A(;(+XNQ4n0sa4%6)%COvHM#wc2krk$~poOJ^Vs7=6%$e z2y0}ituDMMq9ojk3wnxp24=o+f#LYGlFp(Ybr9_Tjb=_f&?acQJVFp&hwj3DkM~^> z-V7q5uorQ}t?{K%rP1cdnx7M^Yx|T;fMaddldxK(x$lOY z4ScbhVc4DKW;P?1uS>`UOzTBR#Y!jEaL^0_;m>82-DuBo{w9PUa7 zCFBk1WmL*UDP^#$5Rbc4nu&eNec1aN?ou z=zkhdKiW5QDW@Y}?GzJF2Yv_fHOW4a=naiG(O^3Nbs_I@@OH?SF&Se{ypI?5sX@hD z-rKEr;4HFBRPI@1ZHLD1k78-XOt!`vL6NU`C0&JEEVo!*cil2=G$eLUjLC%j@be|y zP!IeN6?^)GuN5n24L1+0+bTXgW=_p??7^SqNo(*KJ5lD{U2E|h5m6_Rb#YyrHijs) z+qtbS-?}V0AGO~u{!hyMtXR?eS#kB4n4#qZxD@W{XJzMve|8l zoR!k)tUcBOeT*fv+c^h2tGAs?lKDMfAp(~xkYQ7fZ-CCkD8$eEY)Mjinq{q6K4v=F zv0_XbwB6RJJIZUJks6~kwJHs7i7Urw^$!AP--32TEVNOy>Af7upjK~+%8@JG@zCd{ zx7(nbQG&N`n!=s@o@i)Pco6?pWsb9OBY$jQdW%o9=+ z2%Jkve}VK9LUJI|X`nTt3~8j(Ky#OL8Q5L|e78K?s7pfrz)GV{W!`R5Al}Y)Q<(E& zt&*L1gTiZdQ;?!X3Vn3jHKROPj<_ppzJn_;%Msydez?4`P&DtPLVY-&nS5 z!U-7B472f;&cNGEy`98I9An9{_D7#yf|hKqbA)X)G-lFZOAa5T$UokdVf(Fiy9qJG zH{r66n2}l>k6gT-EX~qv57#D^Avd^7VdGL6FK|K$Y24fOLv5eB35K7sr%wSE&V%kU zzTxmTb3)0?xQzDGsKH0UVeywNxV(MeWG*3>!i4b zIiM-D*DCFy$3y&k;uR8~@bniqc!Sj6bgmnWa~-!iY7Y;M?{)#Y7}(F3;|v$Ir*D<= z{kSTA#~|4EwhM!SCtT`-&N!TgcB*eX(R&9;G1Pk^$Mn^o5uOS5#V&jZp6tO=$no9+ zB{Vhn-NWr@7ZmKvn{bMo=Io0z!y~K?vomp5bXy{?YK!LL@!dV}IG&Ih^$OWz{Ja#@ zW694eo7Jf&d+qFBz0))VUVKu^n}u$&afF;kg}ZJ)J(YJyRjUw{x(e|@GDgHYm2Gpm z{yWYH(}Gde6tP|7iX4I{kwbd9R70Y04vla{0fvjf;ncdQ?S6KaL)?rZQ8>9Z3pZm& z8jU`YPKm9E9>KRT)T61*q$@Oc(iRm^V<|j)cB7Y&d^kAD4PgKKK6g9 z>3t#}*F;1Y*1YEzrgm!~4?OUbrg~Mn_cS2U?fofA_u)@U-TOa9=-!3z2QCI0E{J+q z?8%LIU=VC6l_N}=Dp*=TUbk&EI5#ExeI5^|-(Vdh#>G~e`0w~E(OpTuW*)f8t>V9b zID&Hxtf?54T5lf;S@O{RzN@0~+SR3-3XScHRu{`p_pdH)t<-AUHL2jsw9Zde4pVH# z+8TwE+`g#G5sD)PRRzi|UtbPW+*VM9T6*bj`)Q(CnWBD=lxuZo*qfVKzR?M48Wvqoay##nxTMHk0n(DQp=`gQ9-k}*uy|7ly z$NK_Z^ml9FPcI1&S~BBZ30U_&yAyPEDRgH+4~}$bQ0`omJ5QGwm4uevqFW39a=9pT zT4oShsB7UNZ>=~3sl~X@!ZjP$99-6YYsHzn`KmVIRwlhnmWDiYTls zx?`;L1-jza1k+kX(!u?1oM?5_mJ*bBS0<0AyHVC+T=(L-FVl`1|H`dJydkca8gG|n zrXgh|Qs&#&ihsdZ%QIDNPjDNp16)efa(gCfK@J=Hav>KN$DtMTGb^q1-5vOD5xyzH zx3}TDI~g^(DKHQ3LKbTifg8}wK*XwKQ214y<32)boRk{TrdCjTtUoj|XN1&%G9%7` zcy$?M^&3>?w?-<1dUX}qx>5g)Lv7=6O~_1kJ&5tonILL9b|}6 z1n+IgOBmiJ{2iKgG$U7a{_{h1_0MKRDXY5ZR_r)sR%U4H;fa59C_lapYZG3BEMQgV zrynY+^9$ZL@s9V+zq^$gH#_t6WXm@J?Mc+DcK%O$zBz*=3`)*|MW0^6put&$k-DsT zhNYN0QZI)r_y%D_Qxve|!)3sgokhLOqnC+BF7ipeu3^1C4_xAj<_PRFYGr%+!7gg^ z_vhiOO-oj!pjEglwfrz`doV%AXcti~KI--Jr1Jtha;;*R$4#`bzH`NgE6<11I=Ydo zF9z-}#>EAL9C80P+M3~SGtB(rw7C7;uoo?Zz%TXr{lfQw=PhT!pN2*zG@FBhGN6I( zPNk(?@OM31M3xk9iJh7K?HU*9l9Nxabwz_p*5S!+d&ZJf3ID3KnkwjWFi&UXYlUov z?6&gaq;g&#@6pB-!*3B+^|5#@GrG;d^Uy7Sct%2ff_a6lT^Qdzx$+=(1NKozE-SQW z%>Bu7ZB!O?Iwm+4L64)@L7E%$EA9b2A9oQn?*JN{L$aWEVApIZI#)`v*%A)^oeL{c zvESbBz1Mbc(V(*U%1A`drHH?aS=2-WM=4zU=!!d-%t#9DSnG?(m5p4#b=@eVQhu9ZU4^$9c>6<_QLbUdDXIK4 z>k_<6!#f8~c5|GG@b_TorvCxx-u=ZP)pWO<9Jzn$N< zL8janba)5!Cy0+k`WGP`i^K3SM>6V_*!#ZsFO`YQR0KFwlZretL@RE zGR%#Sfg_*6htwl8Hh@dhVo!W8W(&BFOJlbTs004QW}3CGPsD3F&16_*JEasZ<#&Ce zYlkW3w7N~tAJ=EXN)I|^ZO6GF^flF<3jyA+PW&x1!ZpTxT#r1Q+Os^6i4|3kxBtNk z+I!C&>sy#-?LslI&FFdE-g{5@y8_}M(XX9|hd2sa44h}1J+j*1S(R@9_1=GV;+>Zr zF|TIh%o^P`3fjOLPrXl*jL1noA_)h6RpWy?}-hcRQy#3H(*0uwOJ4OY-EQ! z;patEW=e$xde4*1Kf}`!VR~Fe|8svAJ9RrvG0x)?Xs<#VPMl}J^?dEXHP|{;#GI=# z(YHybHEr)HeumCCm->c-QZ#MH@%t)%?{rWr@f&TvJ3x25^^EI!R{U+#^KMO>9{J88 z-#YdkL2(4Xj2^%JDd-CP6?8CM#ydJE9|C^GgRdEiA5FNqsQ@+*u&Fr|l=LJB*WU+z zQoEPUAR5RGhX*q3ci~wx^HcaQg1jSqhZzw#(jRubB&Kl1txXXTh+zpms4vRu$Upxq zXuuYG7ApGG+dvm7QsXZ|yhxE6>8&DtvXkh`1PAO671;k&Wto!=%{U*;g5N2@Kc6Uz zZsoybXv>Ff`BAXI^PHtdX--LrY!f+kl}i}n<;`I`^*VKRS`FvZWX>;e2_0QZ7oM{t zVK;2Ci~&V|p3yFI5o-hNf7LFjjx2ab`vp;00ej|RoGRfL98lek2zpb%;gDedSvUx3 zxMno4O}(mf)m|ENZ9z(k4z%q&XveLNEUVh{Ax3<*GXqg&HP9K4a%5OYFI8s<2&vxG znsiG#(;@syXuGbpG7M7mtiVJU*5=5A(0EzZdFrD*7Y??mWAqNaA=0PJ{02J{UBM*t zZTS(1vB|~sgC@)dpB|^o$o5zZhZ&;A0v3r9f;o5M4c>O}*?()(YgToB{n6?Rgf9~@ zgKW@fBwQIRJ_~xj{K7(ceWdXvy7cREiJwBYE<}S!mQK2jkh_+~d4dW=pP2kzE%D6% z_&drLZB4pA0{(=IhMlI!l1L}`UggcT@UH7Ym`I8eg;<4M%E+>^sanV#qi}Ii3S%dD zG#^6-t36;qiLkRS(c?Y>w%CcVf+@Q89=O7T!Mlo}6gzqOW>00w*PoKEKOsuG{5GK| z9{Qks4(IAu6kpa4>3r6AwfBqwzscFBsCOwprgsVHgj~QZ`Bj+Y3kn;9Xb~jKydtqo z3;sXxnn<1uJtt$)Ouz@86UBJC2YqxAJj6V}ABd9phs0AX!?X5))≧K*L%BUCvXm zv^hk4?L+YO4-Y7?#~y-y-VR=eswn3NPHlff*n?iQv5z7{HdTvB*y+o{8C5!~0pv%X*5zYARV72yInvrB_i_7&md&mAI{ z1&QLz<3*)sf}&6Q z)1$Po0OQifI}v&UnrMXSnXVMfiMVtF?E%XMxtIjpx>B`e;ls3vY zw2WkFjF*S`vJLZm4%#vv{cW(79T-r#zBXE|HTON4QZ%=8Yfax$e##@s{Yplazha+T zGPiE$dOf@b#;M|>c2?|MzopjXF)DUeOjF04>|@)xewI4sM1-sNG^OTsl%sU^hTck0 z$P4N!?X|I<(J^h#vO_!9$EN7Gx-3iAMq zzUCEC6Z?%&=nr?%n0_M^_*Jg>q9n~`K&^Jf!b3-OZ9L%ZboO_}*uJVoT-|g9yn3q~ z9(NSvy{Ec=bw}C~ADI6Dj~KFp6{}6ZI1(O6ynDc0ms`oaM-grijs#@*J)lRh*PD7q z=+}Mcv@o-wd=2=UzY5X8p=FC?=r+Q4HX!4I!inxqx5|90jkIx8W4>9@tWlkuXMvVc zEOg7dX@+{7vu(Gn*lv!f`Ax6}XU>>eoK>1r`h6moes4>5X;$ey**PT<@Hf=aevJNm zmA*tn{2hV*6c zKOQ}HS|LfEesN9&RpX2GvyWV!0_Sc+SwEKny07t=QSmI@Q05Y@V!d5!`uV$9Ip=S_P(7z5n?1;O z2LbQfrKhWB847^vOJKy4L5aQdC+=66PR?y^r;3wmpnun-+=9|jH4#rRGGvn?D zGRp^hSA#PB)BCHi+@D$gHCwyFgT1hJX-24=(M4D>Q+k&SEW7)GNE`9j22^gT-3)0^ zqMcTUjILAI|CulsxjvlnVaQNu-C}DT@MppS#gH)bW?yF~H?n_ow2Ub$yF-{#ALw*z z(cABv)DH5HK_!ND@l)L3YIEpC<_8UJjYavxZSeg=>6BiU!g~Vb!-WIUj>Uh?=qedUi9^; zi?=)Xiu9CS2=M=t$1drb(qf-^CA|X()wH4Gyt4_?f>! z&ZW{FL%#cZlu8_X(t)6INr&YqvjtYd8)ctvPu;PUv}w?p4Tc%`J%+O1ur?E18Wgx9-Xs=H{9Q(272|>y zSmWFp%&Z|FEq_I1d9uwh*7Yswi_>6VHZ$dCjOf>b9d@$PxIf{iabJmX|Fj#lu{^0J zn&o)d-wVGCH4$>Yd;QY76N^5766cxF917`~(Ad(r()iNYQoBUx`O#dCm>y|Uo6}2T za4vdG47Xf?&xB0#BtW`5c#k2yghL(?<AxiY zQcL@P)!g;A!~3?I_LwKYr`)rapM-JU+_`m-CPg{d6%l7>9n%Y3$6EaiOYyj#!TVU} zGt-p@SfGe}jxNP3%n5|G!RX37SZ}0Vd7j$ymqSk>Uz!tIB6yzx*kNyqnrk_I1W;NHCaTBFe|^*X74xkg+)|Sxy~G4mXh+LumU!)6KnK|x|HOs zFi$#UR))VuKq9R6WcziHFh7^5O8~#C8yvuyx7rk#H@C1I!PBmJs9`W*_hMd`Lf-YW zFIo>jlNPnd>o3Otc>m$r>9(lU%KB(sLcuhgoKAH81kZ59hkBb%n1*coLf2H362(ec z5Gb^q5nSE*XfLPlHk^UKIGZaE?-QKH>5vGSBlJHC(Y~9d$lSV{5Sf!atEQKJ0qvOw z@joszef>A9-H;cJc1^%{YF6$jK=+gId|)V(1WIWJr1^zDVv=h#@~K$90iZW(*GT-< zu;0C5d2~Op=KF4~YdBKFSgIOdo);Rs*cet2pN3?2biN{9&$b~-E%AEZgr9c8S(3w% z%r1ntJ;vK~vh(Z5-;)C7qkmS1;-5qVw73jvE5xTlQh9?2R8G-Z&%MpR6nt$csTQ`rZuoGh&Hb`$F%IXzG&h)_S-qn zNASOlC|?~{?3-VAUgCHr)!g`j?Nz)#WPh{mhsRzu89V-F2QPDq9v)Um+lcHzjv+py z!W?N{ZQfu$23v|XZ+?G?GpJ#|eoVM5u4ccQ;Ey%SoP(5~#8q-ix}0)ad`eEy%P9_V zrJOQAPH7U$<&@aqZ1X~t^SSsqOQBkcG8_{Qh>yv6{M}MrABbggN{5{Cruc}Q(kiFy z6d#mR&dDj8!S7HVR+#_M7R-$_Kj@fAx|FTQ)lKlpN9{f)*v0#bOKlSh1{M4pEo~AS zSbCFixSRUnKj^zA_*$mkj5@=&afNB%ok33BS-h9}jLK*dJ^(!?zV{5d_P4q@{ahRR z2U-HTozq!PDF^4--8BQU^;b>N=Ipa?UY%*65qaBAbu~eslhd1RO|Zk{^wj56L$Sx6 z-y}T2ppp7!7Wqz(qA^c#XS30*cT>BXgi^Up{n!}N*GHqP=kWi;JLun@9p6138M<;`ck@bd!Nz&Jo&>-xtF7t53xP*Ztkp` z9J~J#U6cEWZd&8Fg@4ZtuHm)}v3{8wJ&*oQ=8k^ofsq9tzfr$4@Wbp;KYW<`@Xlp> z+xP9yUDD6ceRRn`avLsh-?3xISGl_$=PIZCGT~{tp88-grhwx-tAfGi+=-9DmH-!i z=LUoAxxrORBgcuk)MuP7#(GRRCc zK$-PaF4@+9(GhX$-`a!Y<1;9)G^d_3+s*p3T*lnyn~EpoXE0+`QY#nJ?nsf#T_czK1-M*4IJi;KEqyY=9Zgr)-KPXMlhM#l!D9p zH#d!UXgn|upf;Y|vIDvqpf&{`o7U~4-Wkv`aQX)(WlIxcys4p$sCZB5`B3CM@P(e5 zIJo^hbURuuDfpI4Duc>X)YS^F-LOybN*^k{|ObkJ7kJl$YM9JXu{G z?i+cA`@eDfQZ8ZqudD(bc{m4R+=veT@8gz?aWnp5+!C&j+xLEH+Lh}_Q~%4J=~j)2BW-~7k%NR;!zj~v65{~+Jj$d}wqeg1{H0pqX%d?0aSaS!Y{ z;O>*rhmANixF;yR8lgYNJGDOSvNGbI?x7yeq_OGq6Y6(>LU3AmPX``+>HgEW)&D3y zbQpb&?)D(WRW7!>}3h?7`t@IDHIeiWqp*GY)yyo9UZ0Ptcmy z=?YKk`(}H0w$-!h*2IFTom_wVnr0KAUK6@=+{}C$pRxn}*z8exbOG9treXI$b0k}g zWxvV}QCgOn^OQmtCEBd=L90xe( z(7tsOwAy1JTTMDhy{OC|>llY!T9aT6jKyAfdtr<@r|^3p&Iv z2S4&QPh-As3WU7erYZEk?126cbRw~3uuLZsd=i~dc;HKf(TRbe6LAjh{u{G=EW8}Z zlmN6tq81rJ`mQG}QF?|1TYJ!k0bZy3kMH{g;nlZ3L@&w?^!)=&16tx_nEvSv!BpH0 zC<=-Cke{tQ?u#~_=Qb0bDm`yshd_ep754i^`QwVj12oE2CK~f-b94(gntBy;jT>zp z-P|OUgA$KIKW_Jmhej5GL)nsM#a?dIm}c?N{O#(PMp6Oj2 zv|(uVf6`0k;iTrV=QRnlSRU9MS(}81z0IH=7L?x?<^KicbNVI=EpuSRhM)`DgR6+#phbky7C=5rf{Q%QK$izI3zR-5%^?fYb zs&6l;3cp3K^P9OXD$isemG$iWgIr)31V{pi`)p)*uEnrDi%Z$;gvP-|Yen8y)}BN=Asy~h38>ZBT#r^QQHKo}B9 z7{}Hk=_&qy>5;U$=<7Xl3Y=a}kD5^OcWC`5UTVD)ZN4(e+il8NXPlKe>SV0-*~4Z3 zv)xml+cy}y!}ajx%fpTXanX0HSoEK0HXjJPRPe#9tD{yj{C$>oXev)N_G6v!V>OAb zi%r7cpcVD2qn~xBh=@CE1QqMi?)zw7XsfnD*PFw+pQ!X)pJF6nYfp7^_HmtfqI}Sg~;qf!CfJv&2BL z_)4@G69wk2s*tZT9~^wWFR7I@ZcRe2zpO?<=b9=#8!cOx2RIjb@Wwpm4T=n|suz1Z zrE6wQj0N+*i(1y|CVZsv_%~Ycdl$9w3Z5=?(a1F8>6b1VapJ2!DUC@J&3oWu@Xu|0 z3KHx8*2ZSBXB+*0pjd_?Y9q}exs4cs|K7^uzCX6|l=y$O@+)y>O)s>vNt9X{)uWY9 zTyN#_>#bZOx6=OK+gQ9|-#~_YeSmx0(9RFuP&3@?NsI3jB^t-(!$t}BZWq^J=8a@C zPa3UK@*?NhYD2uI*sU`-J+GtQwQQY)zu{A_{8hGI`9m9RP%Jl6Bg72IuHCwLEa&-zGAhg3rQ1Ny9NGXp#3M|!1r## zKBdRc>_kf(R5qnFf$PMjZgNmPO3!cL%09>NSLt!%d98zLxXVIyz^f9gLy`WcS`d+? z6yFAr|4E0onoEDhu^oP|X}xbmT5jjv?9@&*Ho<;@QWor;R)jekOOfn)_72;rq>Y6{ zg?f%k{SGCZz#M&1B>epsuy#Fry4Nj1ycO@a%Miba=PisHC_OI*KdsBAI!bs0n`f-| z`7Nj+BLk9J>MM2Ox9)VCM6W@ugWt;q?rXhmFrX{rAv{4-2AKPk+@=RSm@i^@$ET`K`&UHq?wNjKf^*L z8m(O%l(-=Ic<*$ovUxg z%5l-TuL)}<)*9MlDLgNOetm3*jRM+E^j7ImdMEK z9Qi$A>&kt=i2FiR_=B1zA=1m~#hQ2J(rxnxWjBe;OYQrnx`T>TQ;QN&=8+P%s*kFERbLB;5VcU1UC z_iUDOR0s@3zP(=j4=)-DZ|T+(ij< z*LCO1dA^nNJk^~iryP}2mUZ7OryP`19t7ts7i~D;r*;v??WnLJNWFO!`Wf6XDxb8P zGBNXxg3m^|r22OHv)GB)#&|SGVe^0E-2=fJrB$+Y>HF2}`Ka(T;|v(U!84ytX6HES zXZq$S--4LXdCrh^6<$@V~Fnu+{GOH zF_-2v%}0(anIhHg3RJRwqIr2#I30La?lnEyoP!icV6B|eUruQXNPOg@(EFD1d>)Ya z$QXM$87&9SmP;DNzq9AX@|%4)F^e1Tx;`SDz67QI z&By8Q#C={s!Z5=2qr!|p2)kbPNtj$1$d!BLc{ycDV2YgbjGU4km@KEPlv73oB);QO z;W0TSB|!Z_@F{S9$YS|vBqWIA0;A;;7RdR-1Eb`W*>VaOkap!qg{g9ifOF6&v>~rY z5A|pK^rNt?kT{e_;U9+jNg9cf?D?pW%I*@D9u)?&9+J)v|F7{X+@mG18ZBrjHP*tQp@ zo&B_J#hv!{`ztEs-a3f2VHf(OtNRpNVWhlI%5U%RKf#`E^!z+FGo{{nMe<#^k;bH3 z*v;^Z)2#*$te;3J6X!N;4(=V!uxNR^H}6OqVG02B~MPd;+rq0jF(d`_!eN52M&0# zhO&|ro|nX1Y^%Z9+F<57-edBNqk_&0t_qzwSb+yFmqoR%OlK?VdL z!k8zY`DiR8$T+Ww(aeQ1rS*2*c;}Gmo`(Z-G+?8K#)#+j=R@l`|k7Q(;(*LW?J&-mPbpto7sS8}N@rPj@4?Uz;{ zosVQ_M}-F%Yb0+yCqFB6>sXF6hlv z*x-d*TNU93P#wgs|H9IGdd2E}=L-9n2bu}bW6V>b$;d?%wQ>=lOjc{_nUy~k-gHWN zeMhB;n&v2OeRE}mM}b_UR<~1B0eUU*Tha74Q^@X9d`GZu|ma0xGyWSQ3wR# zD;^`c&z*p_Za72x%uQ}8y@tW4R`iO9V|ib5OZRH|{<3_pV)85r4_=qoi}36F8hPC~ zEaOMLJpV%X-0xDdS3P-Jaag|7`m#zM?>zG~T3>b-(u^8;wqV-s!ci^x_&cnR1&3D`Zk3%)oYkEL~B9DZkY$@HIn z(Jid@Dm*6aLPtY}5Myo>%7UMQdrY~rn`xd%>rH=rMeoxYC2bULXFE*kT{dbOY-<$e zV8`gG=oS`uInN~2IDnOi^$qil%F6+_xer#TB(^#dMQ#)(v2UdBZo+p1@m(aK{86Md zX`K(zN$eL_nKJ$j8aB?D2R_=j;2jbVQQA9_ywy_-ZsC{c!KwEZN*WB*JH@Te<|$~7FjwU+I99v4x^{ZPOS>bp+I31R&|~5Yu-reYCcS`0=l~oQ zR6aW>EiW!-bxO3egyE~yL+^AiVQ*-*OZ`1dq*DRS7oyUQ!ZvpPp;49U$P=Y?Tqc!!))DyQ6#|2IPZPi0eWgdr3edX@wG>>lGx zQiVpuy{7(`pwh9mg4UNtVG1N8)c%RxobjlyWgTx!30Jz1h~u845^;q*3VKJ;inuR)xt0)ITRKaql0!tksq=$@Amx z0oP|pqwq;k>uwbG2RTIJlXm+g2Wb?pvAvT-{r@RaFE$Fl%KNDlYol->AZuBGN=Q!x zoAhKi=i^Ks!p}eRce_`o-#fLhKxZ59eJ|uLpR!`yl}W8PIo|qw>HQP_a&y~*-!A8h4S)OO7t)v=4uoMu(^H|K4qj>0-r&$8+(RU z0Hfz!78g9+QiY|3LnjGZdTD==s3TjWn1a zwuEwXZNbb??vXQhw+A!tv+Xe5+x&G$yw=ibPgo3{tQpOX9r3DyPJ5s5ME*6kYfh^| zz1R_UIbVAV$4_ccYPhUbo{X7Q^Eq^6m9Sjr(tkVC5u=2?>2mIO_uoy)u=Pj!SZ*Z$ z@_Y5r-Pv7W{`#_7J-1aIS?-utwAG|NOZf{_TTKK{ajRK)kqsOPY;eX!1r4O~P67JsH zvrp%`^)_zU!bGiCDK2#rmz;}CN`!{hzFo#8?g1A5HE1CjXbhxYo#R$kzjf8#r=V3C z&Oyp;ZB@?7G$*^2JEKtJch_r-cMnci6ZFO(jBAa`>aqEo+?pa~bzEYfybZu_!ZQbO z?l)gBsPG5z7sLI8XQHM?peZPT-SP5&8p}$_RecnD{1xO^zY!iG(-^}K7W7mp7!9x zBOUR|Jq3uuce&4eqJC(*BI7LWF|ruvxRK!@=UGx=#QeQ2U}w~es8l0taU_aNYYVsorN2PC4swS+WMKCQW^+R+Zvxl8Se}%VtJ@U3C>#r z3*@g}lfRlCxK&PhNlqyU5Iv=pp%Fg$-nsgv;po->412SEW&W)3gYvlyg6P&3PCwHo zwP$2NT0v3~do_m9aiixYyF>#Y0wfAh*hJPcsozR^^u=v*FA+DJ(@g=T94-57rZT1S z{r*e_A=N9Tbg)wfw4srI()GP|qu_=|k!Tr$Eq2N)K{4Dn(M{_MhiD{`tSma|H6j)r zy(g%pa^q!akFatm&y%h{)7^sEH~$#d_GRu5%5Pq}$J~^=ph~}Wi1oYNDn@V5=e~Bd z+!4O>NbcV97Y8;jIi9QXz6?FG(=uP{BZ`at9ThNru3+1wOsboJ?bm>uD?LFOMSRRhBw6@$@aH@?mwFA zr1wL$KwFDuJG4;dJGitvnmPSs%vhCwQcjsl$9xGa4}B%|T73`P()4IC&!CWSHU>C&k~pDjq&eIM-3997Z&(_107_n)8DH>y z?)db!-W}ZwZt8V@Sl=hUY3_jsGmrFGe{GxhL0{IquvNi>N*JVdSZ&U5EViX#9o|`} zKReh_VyiA3boQ?fZge^NOts~ngNu;Dc{bY@;(jmu*xQRaPuH6HwpUDpoZRT-W@=Aw zl0z5so?f4FsV$C(He*r5ReR!Xt?CGsb2@fU?ES`R7Ac>?^Z937ifS``84$MkFVxXm zt#X)b!#zgRPE#NFqB-2IUCWLB=?sTBu>U?Cc0@j>g zBF2(x%l&S^nyxgGHzlxdg-P7Hlbu*;deL>|^Y3ta*(=b!AP9IAu3C6h1N{zQq%*!Rh85Ma^8VD&P~ezf#zo zpz^=H6ai}XF?P;0hjTz5==Vo#|Ig`O0EVvheS0YiysjuF0c{j!gFmLmZ}t0k#pZdq zS^QNl#RflP-(J$buie~&|Df-npM-ynLQW4#QgOW&Y1XV@wMaES#-1fQkkaFu`$Vc4 z`)ovCi2-zKdA*Bad1$^hB92<|pJpiMohDNttGuHYx{Bl!qnz@4*Hk%Wf}C=`t58nK zkWdzUCFKZB$DHn zNjl9ORD^NP>YB~g$c2nfHo%h?!AZT?Agm0&Ciiw)59pT!Tf~XG-?zh?_J~Y5ai2A<)=YQ(|2G~exx6>2#Lj&U2OK(lAuNvUD zm0*ziW+G}+9j0Da?cnsbK}2Pu>R+(EXrmboj3&KZ;`JI3(F1zFs={=PSc8xpr2cIb zj$@>0j0h41Mz?`s39TCqLKMqGWlPxpiAXtfSj|~@@9%!xW;gFJt*14k!&bq!<$}7n zl*)XgCvLUGua=;6;{;6mz8tydTG**psxgV3`?af&gUc{-4(YQNciLkU@=^;9cSOv( zqX_4pY?D{n{l(SQcOAwlM%UU)sT_l|Of1D^;zp@9|D)b&Qf=no8-t+U%TCr=3`*+L zce_=UeX(2GZ8QouiPBRDiyH;_GezG^H9aZU z6l&G7Zt7E-RSm*JtUM{-U%I7vp~Hw0$0km^vHCU&kzyi)t3jB}_ymoDLX@~}4T6oO zGzeY6zH%NTOUZ)o6gJa?N2fEc+Su5k>$mw(BMAlzzYcC*DAVa4`^?FO9-s z8P{~cHv0O-Ak6^K0G3DUD@Q<@0moSyr>nL$2uA~oT?%tl0qk=IA8wyeVF0db`3B*U zpy3y8RPfq8AJBeo;4d^QCE9dXu-`AVeg_55!3`vDnzjq8>>)ef_S78Z)hY4Ht25^i zmNwf7c3MRmgeq1eVL+pBsEcM5X_p-Mi0YE$Kn=pUpk&F?AY{VU{ro|0)E8%z)r#%J z)eZ_R2dS;_bgC!koBsBD-l8IToS^v27w11 zkSM9#&)}jFEudcuKuOyecFkbBg$7}~+-Db9DyN%`J{x(x-y4K8-O{SiAe>}5BrH#Y zhxlkly``S-OLnB_4Tp%2ZK5Fe@F$J@oo zkLF6Ru`Y!8OCkOf!~JhI8M`4@=Qsy0SFUPj0K8Nh*&`Qj?4^RjvCp`AI={ap+k0(h z^2`n9O`wGp_ASs17} z`@ROmU*+^mfi?dI7eS4D4D@9PwVg(5{h48;xt$-@#ucnG!6E~GPgTZaq81)bqcT^@ z=Rza1+Zwa@?!>!3cH9KL4R(L5OqucAfH!m29Q*3w%sYR{C0+R^PAiOLtev3q9q}Kh1o$Co|g1$jW!me10ma`oK ze#iTy7RC4^{T?bu`tmcs^hSX%NM=m7KtzANUaIjLt8q*Q)mYvl=~qbKz1pKj%KsCS zOQUxA`!imt+<$u~u#vb?V})GfSNMWzRPZ;s8xR+Gj68paIV63F2H`Wdi@t#+`@F+s zZ2A!1iGvepL=Im#C8~6%(EExu&IDSWKNaHw>vg2mUQil#UXb>aSOdJ$6G74-JpZS% zS9>M8(;%$6UiOv?)Prth%8)*E}&PG~P6x(z#bGo-fO*i24(D zrk|Z>egzIfOt(7F@)eF%Cpv>wpg zY}BY^JtFOXPcynDttD5n^QV35+pHe44X!^W)zS%?qQ{rpA^&u+6VQ#_!izq7ZV;Yh zU-^X}{JiH?aiDC8vmacxe)#gM9((K8m>yCC;&@B-JuH9ug}+;PUB;%xEKS-UWiR_+ z%HStHSVi-OWL`wian%Qdl1!kd42;gNv{NAdOmS=SBG_nE6t_k#YAB?UA+8|j*$A%e zqb)Ig%N?*toIo7aE=_)?J-+0G6CMq@DE@N3a#ieX?p||0*za?_A4=F|0-tz!ajQw8 zIGdDoZ^H8h{6sZ!6}QgfuQ=^y-7tKY7w$4RPQ>sxQ>u!+H7N!;-Zw!`qH1eVK`ISP z*J9OWUK{Rs*Ss)^e3%oTJ}yaHFx`BP@%P%BVQUudac?zUI6ct(A9rHD%8{R(=YZvm zGNHf>$@D|YWW+R8wynY*h>K6CH-p!#ysQC7n>aYm7=nH_x5F)QrSy(j2V>0NNA%5| z9mb`59r2y^-UFQrxl;-rRyf|1u*HErj!vcbsya0V&lwH*%iI!me}h@MGzh;!0x7Pc zD+-=EKX>bf@YttakaIP&HMK!FK;s3U*jRg4(Rzy7(b^SvKErfMx0tKV51zr=1bYh3 z)5`X160Sb#U3Q&nGzg{MrSiP55hdKX(_1E|yd$UF;tlQNUXxR%dqexVt#V3%w^aV> z1vw=LG>Bv8OisTT_?QhIA7=>d#u|ila0Q88ER^Svfz1(VEx(_&QJOD{*)x2gV8?X3 zEC-VME5e)Cqa{jjXg!=JL*VU_v_cw$JUOMUD@TTMvYc|UE3`U}mQ#N0k~pgkLaHd8 z`TpHC4rh3d-%xX7M~f*-;8Uy^?HBe@H7j1-0+#hIIqxnsb8lir+| zSo!%S@18>qH6I^(_4kyUKb*bGUi|cyn>Y3SX25RVd-GpseF6F2ExFSezxi#N%eXwb zS=ry?ehHTw*LS&uM^8*YG3Xhe>fT@aH(Y)@?8B=ApBmbF{_$Shc9@q>yPW^dEAUA_ zey%vwsCp@Ct7cQLU8+~2wkt6M6o^RnPSVJP$juQ|{ZIUD``7}0Y;;?tmb<(zj2j;A zy11Z0_(tT%zhkyR;@>dbjSAQvo z1aY70|6}jp!<(wIK5%@WoZOqzlosp_NN-S@76RoeXhWJFfr5bG4R8#I8q`r7^|hmp zO$y$1ERUVH7e*IIk+wb#P4#;yvl&UdTu7P2{#=QtbrIPlPinm&}Yzro>+{oJG* z3kk!&1kg?)Uuz8MjhhNj2TVTm4t3`hPyBdc zW>_6FO?W~cJ8gfn49%$kl`&Rdln|#DyUQgD6zpk2`WC_kXJk3{?h78|rs`b7F=W8nzHM7}$3p#sRp&|^FFEim2Pe1Hp@6ZHWkt7e;4=F>sw_QXb(^;q0itxv zvF;%%J3dv&&b!7#+=q1A56M3Sr4M@eTGK{kHJBn4MxQog#MkgKl`IWy4O{JSba1K* z0hVnSou#H)^UmeNZ;oUQUR0{-EJeiMn@|pU@kaOh`Hg(-aOYhq`yA05W}R0125q!D zQ?Wve_KkPWa%SuT$Dd|R)^;9M8`l5Dr>)g?ejfGcE~@1e8;MBe`f}|CnpwP0AJXe@ z#^~`CP10li>W!TkLpCPul&;qB`kSDm8=O~ZuU8)5Pp+)$n!@G^uWOKbJ2{IQXTs2|;pPnxdA`U%9 z`F_Ib{GW#;27im;p)!W&;w<{ppdcO2)@g)UL29X_ov&48vK$)od`Y*PWsD9QYi+`E z$5cUE@ntw=(?ux;l=m=nL(ow1JKMoPUWwrQIGiuA;J=jaI zpjW&RoNr#oCsBNPm0;|Q;-k;iK1H^6u63j^R=6Fu!vWn*vAe4ao21^~==f^zcv05S zAOkM01P;h_)-%WFm`^Zraf<^okuP%LOUc0wHw)(8~lpDV^r;jkhMia2ze(_iYw)^~18&&e!@nbys&$jO&+EdTjsX?1p`!@CB4hQ-M z*)rcBHkuG$>RMTMYLaRrcVd4n zNONkE?(I`75Cox8dazttfp4*F&d6S`D*dCC)=*;thK(_-nRJqKV7c7^@m}9z5bhJN1;Du=f52`$HvBb^Jhi; zqiDV<>rinXG+OMwqOULTwS#WV5Lw~7IG@bY2iGQ^Zjx@odAKQo!VbOWt`sZ$Q{MD) zIZS-dt5^YfNP)m5CCYqcZPoBL_FqS|@R$dUU6tNvWLu?zk$=buu$yz=6Jho4&Z@S}OAL?LRD-jP=$O|Y{) z5E;`=kvlg={P&xr*CKZcBmVnMI0HaDrb(I}@!xNfp6OLQ`N@)`jLw*giWf?g^mwFn zX2g@fNqR7HC*`8zg#y})+=;uW?2I%?OCxuT7ZooQ(5CER&?IqkU&)Hng!BJoacPny zSeh6l7SJ@XNe4-@Y_-BLybL925!YRk2FB!cva2CMlptAsLJY3FHKhYGk zT!+!?x(EqmjFxw42xrN^B7eZH(E?v~qMgz+fFZwu;w8ycY%vqSO! zS7^NhJB`HUD*F_={pW>&Tm(dS5x?Gi#Shp!{gH*PQ=dQ9UH|sF$(x>kIzFGfyQ{0& zS&*N_-|}hN?|+{^`S02_Ju5ckKXIAp_-Ou#CmJ4ImECv!*}sV6V-5_?cbi{Hl1AF{ zhpcYB{K=_X^UK#fc=m^prTLd<>`VS&^Y;9^WV-(*f7JRm$Qos@gCPH*mq%p5%4?XY zLK+EbpMx@@u@;!xK@0Y)WHh-hlFN?fG zd?Kb#!334=1HBTK5rr6Ik#q5ZAh(fK8z7CeuvXEmWa)RbQ^`B!^P9H)JUmChAsq$q zm9QPY8h1y$;k$4~6Q00-ca3b3rg}N>(s=mqnw#!L2At23Z$K}9JK|A%dF|psFXbP| z^dfKEtkm!Kz)zICd3WQ}-sSZYZLqYR5shYV@4(Dd_|~@GSLK2p)@A1_)bC(uvs`w{XIDm+)2?*=&%5aA>;|AFHo;TZP*X(pU&kBt8X!qPFR>xx!=O!}!`O&&MT zDLXi9%sqi)SpUa#EhP`l7YLJBbs0Z}Z=@`LnhX!Vf9b{gsW-Jh``K6i>)$`MZDZo! z;`5)m`7-3z;`|<(?y;LA`49-=C{KnDjEVcp9e}MaQIP`zwP}WlSBDO64-o2ah3FbWB(C zZ+g>z?Q-ZclZx!J4#d(XfOcQS-u8?DVTUkvOj;(teN4KupW^Z!la}<~FR!DNr;xE} zBk`6BeiIpJcXt2M;AiJb{)eB$((*LNB7Jn7SB#Es4D;J6v^;g$1>(dlhubuSV)FdYD`m! z;t}(HHhOJeSC6VMK2CdzSqGg`y9!*95wU*QK=~JI60Y9kCe$Qd{lywM-ff`>->U0?XE>8mE+#K-2Zf^BfCPn^EUTpw_W5kpSf(pTGt&eCT{N2 zPe2Yv;zqBUGv9HXJjpUl*lW#mDfjN|xEY%43!cLvbqwor!RB9)VhT+$&Fh%My**FY z>E*s~Z$?y8Q!BIn@!K=_uJbQ_S7$7Hka6<(Iz6pn9g3Y%M3ep`pEOdj!C@2C0~%}UHbRhaKQ$}M(3@1EJAQf+d5 z?^^77+4Z4oUdIlevsBv497~#2h|-#aXo_~Ga+pGDQ?DQW*E@ypg&%+eT|oGrWqZ1A z^`4S3V)x#DrTwm!6k$y~{KHnn~f z*5gupw#{dvwr@r7>C|~*zUir8nsdJUhX`Ij2VSdOHv_NddavR&)mh}W2?f|`D8iE; zfAi$9`z{(8!#joQuRrQE@G(}_z1Fj!=%(3;?l`xmlQSYpRi`0}iOan3pj>PW#Tc`D zO76=RV~jRo0Zw6Hd@t^S^u>vcYV2irR~NFbK4>uUN1F;yBO3KW=NI_T#M$1#?&-6* z@yQLJcj}{-IFBMDEj>vPbvzT}y-gv#s_C3(VVP5(cg*=&ca#yC1&s?J*~pr~#Mdtt zq>#OWi4(oZG^)DE30$eDg~N`8&c7nNJJm+}h7=oOi2qA%4%YnY(HJURg*rvZ7C5ZgJ7OO4-$L-8@o zP96>|0yV$tnb$D{)cK%H&9Ai=8P(R?PR2uL+3Dd!OH}ijuG7O-yT1z`@UF&8deO63 zrtGy2)$tm4r9%pwbU)$#-n9kvc-r+IL8Sv$xJ>80fa;EA!>-WHO4qje`U%*fxiGVR zv3qkn*`5+b9@$>?>XM$FyK-CcjbE{H3$m1&LMl^!&%L|S+Y_BL-7U45Xl?t*D>oVo%^n zcRFGUKIyWvN}P78-$i~rhj#IfFNBhw6}#+=kIbMu+7F-GR+88ZZUP)VF1Mv2-;{;F zz~+IGwmD(x9TQw<<}77)+CxqhR0TuT%SPL#^FZ?%Dc*Gw_dE%6vqp%I8yv^z)ykz&OaWx_4uv;pA+AF_wYq>*=WBb1#!Jv z)x|G^vu$^f&5Gky$WC`I011G##f%PaBrgaZS|Q1uApF7pMu?l32~IUw^yI^nnLim& zPv>(IgkPIa1mguibd4VX7oWXqf7VGmBwURy&aWvp6~E=k2yoXjWXv#!xjSRS+`P9O z$pQ2W?G3bL5_logJ=~ot>~avqYBjZ>4ydo?vl9^MTWn_8%>lFUV=yb3U}Fu>JH-9w zlP@Q1azr10CSl=lM_sCrEui+f+%y&bFHH#tM3julc1ECa2Hpsnb@>L?sT*pZq_k+x zD+rsH-t9I|C#;1DeKF802CsR~nj47Erj8m@2;pt32ISBs2D}-CZ z>L;oHh4>6N?*POZBCl3YP(ebZJ5!x3yTPC21UyANu5w6Df`%7Zc6VTJkQc<@a(w?e zumd;~_pi|vU=&&Q_5LsS^2i*#d^pRQ;*S^b?viSqgptcW`Q_fi4ozlE4*nMoIr*mC z7d~XxYSEu0VF-snRdrat&okB@Q|gc$$f+3a+jth3wXv7+~KdluZ5TT(GcRb&)M`eV&~ zK)w&zZxUATDH9NdZZxF5r(ZhSuMb6OF$&X%j)4@>VDCa#)ND>2Bpa<~a=1I-gf+t zIC_5}-dBsS_MHm8)~|ZfMg5zJSV|l} zyucY&KhQ7jylfE`2UCHA^OrURF`_2Gu3BH%e}2{OTZLQyV?3V)%#WY^_t9LVK+LDP z2?C}4k2_5&W2crUeE_Z77RwL~wEkIG?dq2vygWrn4sLO0WUqGp;BInR{R}jr1_ZN% z^RdUcNgyl^ab9Rg7Bt~8;a0%;26(;NCbm0-2LZPo+=TAFCf{vqr@B51n{7V;m+`g) zzZq1Pz^@9Xtz`IAEnBuy9ZFEmSe6vrtdul=PbJMUN=cOyC5<5q|5-S}vV3L2gwMh$ zmIc9S!rEXe-B;nhd6{zGJO=Ggk@XB%KcHa^1kcBk@vv#X`0h1Drs2LlBitFM=Jlu^N#7YytE5RI z1yz~0Y$vdfTntZJfg#m9Y1Qftx(!^#&hXGyPAu#%NIBf_Qu;Jke4VO>GC&QZb%tHF zXVndKm*6`GzD_U=LOZp4Qg?uIt%H#NGaWfjR8KzyJG{BQj>2KZreudRS+TxvwSpB>SC(KqCke;M&n1efXcW8h$;IruJGxTqKRDhnp5h+XM z@VltPpDvg%ig99p%)E}g^l(5~$HzjlY5f>qE1m+sdPwM4Q5DnR9~V|xk)beVXhROZ zy^Q_M!96AO_66|#O6d#ug&aNas)av~W?h-y?|zIG*RoexDmQ`~#wBx!+%?<~E{==k zVz_87iZei@>o^U^a~#*tF0np#fl2Hf>t-SLEBl#sva>A6+Sm{5d-ff|2>na*pEmuMGDl$&Il>OHgLw8n zdzbBFb!<1=$+ok1*k9ONYzy1WUXQ%zV>Q32q3So^Ut<*r^EiK|`N;ow{r|>+UWgT# zHNGJU`h`lI-an^^ffpqRX7K3v$2EEruGXgz!w}bgT!;Ut(R=V&iL2)cwQvxSY7MaHZhV z<2r-)zrb|>*Ct$LxSq$g0@r+86L48@nQ^Ic^`OnuxW2&kCN2-IRk&`$<;0bN>nFf> z8doi@mvI&2dH~lVTr+V^z-7T@!qtj?`EhN+^)jwixK`krgKIi23obfO$-_EK5-kq; zfVEzc9~Rh?%;4^bRm6xtFj#>Qt-u5cqDpB<>os-76~LZkn$uy*!8KdV z2CIqVOjFx>uoCQ#8PUMm;=mQ;|1k;pMf^bAuN8XhVv9z&)vZ4!B?Jy3*XT9=p;)s_ zOI%W%30(`>ORXeR^pK7gP56pr2|}{`m=yFA$5r@lM853LR=Dg0nX^ZvizSdk(q+k8 z;OZkgG@2o@bV-MFxhrK@aSBP7+};2;{gnhwE48K$bNT6Y*Vet`P+|RgF0cx%sD<|6 z@>S=8w*4%7wx8CRSmE-y0Y2M$Qtgg*?{JL5iVFnh%{LFvKA7;wv_E>1Y-sc5;e4^NxZIHxXsO#*_dtrt z`BDles9U!nHzHt0tY|m2NR&9hE9=H+rtBXzh1{LdskL%ucnEgeNkLw*#{$W?-qqCT^v7BE5V^D^{zlV*9 zZ?FcXp-B9V+PHheA65nr$hVmlge*?H(bzE1rA^=Mnao);XTO2s6YnB3l^nwOG)qcWZ}Q5ahR|Pd5kja zG}YyZ#BvN#S*o3+6&v9Po|eQ?r#LT52Gp=Hz;YJ&rzH}#X}8lU6=wY*z*VE(sTGc_ zhHPPWVeD}oa!gh(Mbx3jx`Z`_TK_njPoPj$tPOtg!MuL!Zyan*k zJ8@x?g}k(C!_2(a@nB%NfV??T+E$FU4=px+U#Je~g~f%4kut6)z)gI{@w;Y?Z=3U@ zPQ7MpkgH;u@C^s#>zte6(-RHck?sAHPBmXpIHjQgGdxSsl#|^{+o?Ac3R}qA>`MQT zha&3-^zZwB>0k08_{~izEChUP@bQ8>s-W3aI}#eKLSkSxcJDL<-3ZV`i6a$XN5m&+RD{ z20@N7@fVM=xVla!aO1d46=Bc1xUSq0-@r08*kiZ`v~NPWu0VQm`oZh!<`2Xrv?$R} zus_Vk757W4df!Z@Re6`6%lX;=hI4-5`i90%qlU{Ik)t~~8YkJ)K~JAYVt=H9zHIn? z_hn6$7pD%!Ic=bu+kllN;85^dwyDZ&PQDCOQ&x@j5c%q*s)`E#=OkZ= z=cbe}XHykdWBhrHzX9WqvA-iFtYXg~6I`sYq!4k6#`grs()&W;9nFNObD6a&vL_X$A#0wOWW;OP&P_yzpX$|M6V-c3@QG*wu*@ zx-w0bp)Ro|%B7Q^ZuF1`zzBJl48DWqkEA4)KU&Ok&iHLP!)aCN1z+1>EPpd(c9@MNK^Gl1a^EsWm^9G$Q z|CeCmx<3ZFG~K!{gUEUBxec`4a{)PqH_^9WFEFg)U+h}|y0>Ev#9X9#!$bkF^FmbF zULixYs0y>0_)iZ@CEtyk{huez6!hgsr4W2H%rW~L{O~L=>)9B6!!3x0V~8RA$F*!i z%(zeZg=Yt+AC+#ppcbZpmmih>_liGyBltO$`~bT;tQ$7HDzZWD@Zc=xGy3YG*u@L2 zAs>-H&(c?NosCBF=EV5R{t~w%ZU*`4DA>yr-VBXX>0uAMZnXk!f{@=cX*ZWj`L_Amy)>dfnqCmVv9<1bL?VaDVM5WyA5}D6f2a( zy4t+99Bm-6nj4?Ej^>grrxzL?;X40(cvoUI%5f@qaDN$I;aOBXXr1z2Z1bRM6?UAK zW53_aC9YF<&fv=AxoDe;5~jnTk1wCd*e$QvS zW;qDflAcd?r37yi5^FC@kU*f-3BBnFiRBqfDHh^~fUl&de^-)_2c60&EJ#UQy9hQ1 z8#JPx_Jk6wL25qfH0mpzis$wHs}sZ+&WO{cs`S6iWY`0yJX1$;{+}pu3M}__@iS1q z5xkz2X{+FyE8GS>eAA_0 zacgc9xKv*3zXVMY^=vCm1_d`_R}*nA%3^#~PGfaSRZUWq^P!%SKa@L;h9((3UEg|+ zCymHH)@d}dZVvuqlp9YKX6dGKW97}x&zzqX?r&HKUm}fjJMe6U6jiq%C${nDq^3@T zVNg|F-Bk2-P&F^!e_3hw!P48nXOnQ}L!4YENbbg+q$>Qrn6#coN8fT2-l03MUshm$ zcXdp)qi!7T#^5~x@fzs8S*0vj-!cxnM1;*3B6qJZC8?utnJUbd@Bb;%?s&PC@hExz zvR1~(=u$0A1OY_)``kr&Fg}KCZtVJEHM|H`Ybz<{I`sNV>_s$!TbI@y2%UH+x>-4&jOZ~Kr$UmXqPGe`Ld4=waC)87BwQrCdJkv z?59w~qZ#J1Sj=s6A@yu+Fs6!VrlVgIiv_BUemD=I|Z5MA@tw8V`Ah=(KfZ85f zb`9DdT6i<~ae=TGe3&FqW^-aKRx^+pyS-c%??kRo?|eFiDa);S9kUFjz|L#r&1W=1 zqt%b@Y9UE-x`Cut3HudZUHWy0+Zg!Kd)TjyT6g%&{&UqOtos^oMl6@}UHB8Py*qm~ z&7(qrjf#hDP8Z^I^Ey_jdH*-?+-#H*FLODXkX|F6mdB+^-}zVF=Fp;tWj>fr*-RUe z-%5T~%~z#?XC_B4oSm#GhZp7<&l~4FgAw1U>qP0iB9h_#pB+EhiS zqvO{OS=VwlzVNg5Ni!3x45ahsZwbv%C+1W(Sn|pdQR?(|?B0%L*`YuYbcCYfEJ%Xy zOLJx;hvYg{`QWzf|Kq*JEAJ()O`D?^473YOb!!rHmAdWXn$q}4-JC74EGbgwk7smM zN!z)#tQ?&8oguT6x2r^3zZt$kYDm^kcW86%;;mi|UUG@@`6u+)pj+23{rM32{{4VB ziwf;-dWwAg@V((KIX6+b|5ki1k-v*2PJFh4&ff_w`Xkn2$a#qwB)Vl^ePxDCig@{} zFj`OJEIgi9?VL^iS;^5fRy6m%JUf`Pcm3V7wJ5Ht3M=ooan@0he);WhV)SG=i1Y8N z7e2@SV81l|&|t{3&cI&qt=idX*f#_g%jg-EA^vo8FZeh<7vPiT>s)+BVZP47C(YZ! z-hL_Z5RGo5RMOul{VC!*PQOQEH}D04W+yD_)lVG!5b<+X98}^cr+2mo=L`BQMrZK4bzai`RM7sIWjUnv zisFLy{GPXVd=g^VH;Cb7>BikNn@&~Yqz~r85t%n-#OC*`+c6?%!s&R?924JgAL0|? zj92-f7Q*|Ixj*RmZQ|5dYiqWV$KawSLqcriNzWU~5{8l4QE^5w&e)YdP(8S%Pu6>Xmj(=Kd_zK zG(Vgv-u@@Gz6#e|Tr+TWKBD}l`?0fF8oyQr8o&8aO7*ZB)jGbsUz&FamY}sNM7^1P zNa5cV6F05z@Bb=a`TQ<_V%zSCG$;D|UmutYCB)l3${ffaR-IDGcjXnN^>_v&w(3o) zG9GQDAJW$h&FeqEX*-S0D@FS1EuF_m0|o~E9>GBK!M)g>^FgB<;G8Px`^fm+ezWi) zcroV23v~Lb)WcUlU33iIkg(;5TRbN4dnT?1zvmq>qzQ3Yt;pvr`=u$euQE|!qx7+? zX&Y5;$ECIEJOY% zocBD^Li+m?fq9Us@OO=Ss3UISLmm8lnJa@QqX#c+M{M*(57P)4fxXm2g++xJFQST} zka8w&2Ph7H_dMASDBBakRMPXr?m$pgmD0h*yySl($c;-}`*a%{_2Zd-#I_^JuHeBA z-(clrOrvy*yjl+IdL(GX%KcPbc2S&tA2f%d&B@U;JBafz!~v`V*Dl(fSyb(q;!gz+ zinH^8oH!9dyC{fqc|Qdcw+^3`vP}h@LW7mbH9LpZq*N7%{RIU*t&B&{`lZYdV$o~D zlec+aXlY6Q`Ki0tLf7vfPtgWd)p2%Jc|p5n8sUP&9kf$Et(_b9VW6yyH4vRC`B>*q z1rG)vZf#I#@z)YJ=#TusRS}<%erfT5Pe_boPU)T#umW;ru*twuIYEGoSYqnbFxuH9 zwWQw&+e#oecZuJct8RF#cz;TsXlB#>RWj!@H9RCTI&offsP94;YuCPnLsJA(tL?h& zj>MLyQ#5{iVS2O0Z|Gz5xlxh2wf|E*6uWpo1%`^eR_o_r9ldqr#QSKbbN_ z*5*drtElA(66_yXPGPmR9VQjc1B)UP!=6n1Kj(ps zN5!>fTGjqIc$9JDnKc}MO-J*mx}2KaYA!F^sk45JHOgbI+;utStoxWpKWR{9mUB>9 zI`&VQc+A7n*M~VzlJE+`kHnN4%GIzM0ap`@>&bq!6@Cg>S9X20`nwQRHB){=kN+R3o`Q(pf^R4B)}8YE|6ncQjK(>l+4Lno4YhA*S!mH}L+uavJn{@Z zOA+ljG4ejX+Z$Qt;V`q44=yjVBN zHN*)6H6ZgGYPi2Orq*1(!V$BcYEq*njGyPGV05La%8Cr&OMC4Hr|g;(%&keU8@P8< zuc>xW<(3!X09gX;^ZmA2vh8P%kQt=6F)HjpC_9G3IhU=l`53H~@G$4P?)N}zdx=)k zJl4_5lXE9$VBKk4>lKoM2H)m6yR}K{G0qlyD1bGhz0nlX@#*lwg?F^tyq?bcD!rpq zG|Sg4>d;^g|89*feGanQzY;F9y%JvQAxx^$F;k4FX_FDw7|khqD@XLmSf;n^;zyrcTe{w-3(vUjr{tD!7Vy5JaBIVxu(Rhh##hjcRN=fVH!-Th zP!lJr_`&7$TZP|BEo;!uoJPA?RvP1L!8>2T22L@a?A_0m9)gt1t;(tXF1%@TPD}D@ zHhAusGd~kd8#fElwc6J0IM+;N;MK&gY2n73$LX?j*XFF#xe8rkiv{a18kaJx=}LO0 z?H(viHBQ+YJUvGU2p#1*u z$BDkB$$k5B*Fb6Xt!B!$;Avy+MB!!1&6;-tJYxV_i<)&$1S|&M&l(oWD9x#P)5+y2 z&nLScbrDaAq35-C>1KTsS&YoV6QQ-34 zyaFdU+@?oehL(Xjv`2nt$*vZR&Y;?;${62P$Bu@KgcXT{)+@34L6_+{PS~j*N-!=rTDch`;ibcHFm9EO;p3B-`;NUy@we}?Bo0v9>XJljA^xS}<2+bewtY%W&4FFT?XUMO6@l z;6`c#FA$xC?O>mPtG&sSIbh+srj)Uy_^4Kz!7Ru$hB%9k5WzS8c}f z`0_Eke{D0=61Lvb=AXN9x569DF?R90Qsp~w_LKN-Z#;ZK;p=VJ$o3uF$(MPlHSOgy z1hqag#?PEF`>4jwVG*u~zSV1%taNExN>I(KoxebhWaISt(mS?s|r>#AkwQ z`Gk3yqDNC$#4-#Oh?TtlKaFwmmLTtV%z^to+j z-&Htd7yt{GKBJ8wBs*n(&ks8oI5B6cmU$=e;~But3SrFdJJHhq#`oLcha~>wQCXuy z-|-2Ez~F97ge5Ensp?b0j5#_qf3O<#t8T(6tr$77GG)2=C7}0xd3JdEPszD$t$KS$ z;VQ&iP@UD=#?SBIOe2J(Rb)Yg!so6G*%aeKNzwySO zOZAg7Yhr7+IQUZr-%q-dbB#N5Y7%O>ydk~;o-i@Oo300MiuFAJU+ofU=T72E8|K=( zU-Ozr5l@;xQ9d@QTlJHOyV$#5^j_sc&;GcHb+y>B!nZ>Aehw?ulAiH96b=*&5~pj7 zaODzd%ueFFIW;BV%Y*;_;>#-W7P$p($G`LC!T%>;jsYG-#97rh7;`-06t8W<%-xWx zbM?NTl5aW_Tg&C-)Y`j`d$|d~A`cmqlMCLOv;Ge**4^yYPZ|R0>GE(BCb|-Ql}=p_ zc)llR{bP9g4W15+Oao%G#QMm#chGbHaBc!Onabv@r_z&MkD&BFp;NYmS2S`H5`7;! zM{SpDYRp;x?2lQjL<;RtxUx!YlUGG$+leZt>}oqRaQ`Ik=l4wB*)NqI8o2kBT=t1b z*@i1+o8X=@Op zmt-0!={j?+z5Atqp(GF2)p8rWNr;k`%aBHIAE2ax9xH1`ZaZ-i1w;MPw}&1Y&c>EV z^LLxa?wXt4Qa}>l7@^xe>Q-~Ud2B>_PB7=u_!8DFYNFfQ<<_inYk%KHC397gXCYsWfceLEZuaEP>lLFzO{z#daF?`EyI8lHLD}UzA9H*!_R; zi-%-*lC}+ua)OWA8{*^gXtpW(lhS4n=Gty(=N-EIbJ@G(xr)O91GAB4Scx=m*VxFK z0r|}2nty&r8O@aT0Sru%?|=W!z_<;+@?^C9_qdk@@nv;p$3>$IWCbIJ zgB;b#DO!NVa;&HkdHKM=*ig>+lAgFoZ{9m&^ks<_BR7$WZ+Sj|ZlDer5dlfxz-1cc zH4b=h`kWrmQw)0e%*Mv9S}*QE2eDAp(WnEVd!X6Wcn^dGe7=LI2Zb@l1|#BR-JPPc zWWFX%k}wWvXe(RFIn zOiV#b7Fi-UNZo+iE^54^Yv50I(w4e7W%RnlRrKpZ^QmNlJGPvOKYJ8e-UWCFF1I(c zHhw*E+8qwoJs$L;v||@{dNH>i$pH_$S1+&E#J!%uzNm5oVufYxQRs{vjIOk&UX=cN z!Q!$kBTb+IHP{;M>0iLx|FZN@!vId}Ve>2LS-CZ{R-x-l?b;0E`a6TaYTgH95ED$}1trhej?hw)W*KtBY$~i(L6q?GCJ~wD5sANP6)lWHo3rAhVt_z83$Q892>p zd=00CZapyAN1T&1(Wr9boW=@Rq=6Yb)<#%W*vR5R^EkzIS^BD;%2KI*sp^Bwn$szX zr;N3=j-jXG%j1LTf+|QYP~FB_^uH{=OzCyTfoa7y=$Sh`nZ6w7>GrK5mHzhOY;@+@ z50C>OH{F_U82w7P7W%2rcK2ypx^3Jm;f=5-yl&3g9_t&mEw;8giOWq~7w@!pzYm>+ zWul!&;ww53)6Odx*I$-Cs2>>lqu^an_dEa`C?htsJ-!wiO3sOf4?`+7myzS7cZteA zZ@;E$XeI4HTFO$_qGwUAcB7Av%n`1F!HWLdIWp&h(Wet0Z#ULnDYO2kV5ZMl%W~r@ z?rPb8h&W8%iTGM-p|*W=%@gg>p>3+`=YD?8Gkx6rrp`@_b$a;CodujB3zk6a^d+t0 zNKYRB(`g1Ti0IIE^{0E+JKz_ZviM|l$j6f4uL+-t&D3PEVl~W z$XH=6_X_prhwQp6nd_edr#!1Oo#4__gsJkn4xE55=_%M9UrsfQ1(tTmb!E3l`%LLp z`MeB`L1qof{f&GEY@QPye8tuso z-MeS+i1W|oVak}S6~(&y-kdBo}> zTNBBq4KuS4B~0`;$+qJ6JaiT?%V%{drMYw~A_7}opTm1Eaa#gpj)__1+$o$mr2o#2 z#G8#}cJU=o!t05?hk8oyy3XlyAj)d#h&)Z#V8@bV19l>^k#!J}l32a;k4xN0?z#iQ z=1}0dg*C7 z4q=1zad@hrD`Ut#LOp*?UZamL)omO)hIOTtE}L}|MHxX1De~-TKpY~HHFHY2>vbF0 z$Uz&(W0t#4TfssjOIfDALMKN{yQWm@i{3EN$wq1`OdB$MhTPm{O)esLT$fRivGEgl zpS~SZ@y(FqyfqE^cH_kN`HiYZzFIBJE-3o6JC0H06|;~a+=TPzaeM)C1AZC4%`;!1 zoJ%v1C6HERp5XMElY&hth_acP0j_=b3X0;ziBd0S(o}Awp)9k)vI5zc%Az(TVrA3V zb=;%dIA{#({+q{28CYpQ7ki#+E)zD`#x4&$Ak^u%BRW<+d|4Z$sbLMiO@e=sI=x=1 zl=sewMlc3_hH4FLTn7q%!d9vs!7tXj#EScm3tLY=Ye^l~~!Ju674Ax5VPm|wDIA8X? z!grE?jAhvCrTM>UWv|@I(bW_UO&Q($FV`byD#8Evi*&bMnj*s=8T&p!Kj>(oA(kl3XS8?LJUfsr#zDH6pU(#q5WOXr$ z+O^tH3ESizWxhnoQ7(CJ#zt<8z58^jX(N1wC)Z<6ys%nICLgE9uIJY1eMN$PqeU3* z)Njyk<^BqE4KqZLid43vwm z=EUMYkC0KtAyWoyrlaVYUEE#DS+q60Gfo_Vy^qbFCY)(hXG3zY(N}4!n?fmkqBF^< zUpvgHT}S?!nigY~UWVZHK4X~{u&U+yIq@~rK8RN5;(fB0m%aOKc*9W}&wHYL#@9h# zd$g@n0Sm1%Iq|IvI(UfAz|Q{Zi#A(SSi`u9?-c%Wn#z?5#@C2)cQkzNi~`-l@`in4 z>i3Gi8G^Bl6YEK%?KZ5&sOA`|G_ADL{Zc7LH3y@bt&A!+K4}&8ofGdy+^+ndnBBQ` z?>czDG6$Dj7$-lw^@1wMflqX_=_>1`GC6Wty|h@i;e5GMw~_eBCvCcodf(1ueZ^xA zHqulPy`in`_xPr-&~Es9o9T7EFKS~vw_0G8*3NOmQEH7K11bPr@q1n%QfwhWR(@B7;y$R<^p!d zfj0{{ASdd9Ic}nI7XA8*F`p_GMv$J{H2!<#o`GiukeYNR7QtuUVC($vTc%ZK9G9!IPIex;I5E?Ysh-x(e> z#!zNi0nd${EH}Srw`NpA?2J2(}D|Lu$vzd6uFFMUPte2V*O>Z2Yr6CUT=Ft4dsh3P#j9BEK2-j37 zJR`j{lRT7UKWSC^$XWGLFhX&f3k0LW+vi>)zBpTso~Q8h^I_XW!^W$*LCoCGdnc~a zVs6wU4-vt#y_BQ?&Ml)(C6^BMpk5j#KYgQAi4E-a?g3TKFMC5cO8oL(@*_-a{RRG8 z#J|Zm3w%AFu@uB{LrgczR@8O?r^2m(=UZrlcJay5&*96rSc#>Vwi*3hihjQ?M}}7T z@uFVJfm1Jaz;6ZplRZq7C*@&%$fm!u_j$R-DD1r`GH9n9+mU5`?7wE?B0;xdY8z2Z zCMa@x3rduEg`e6v+&LE{oaReU?XZgm`05a{V4~QDY@1P5^ABEjr)0bZ(*!dl%MK z8qmknL0zSx3ioWfvZz)6(?+uMg)>CAN%F`j^z{UMUTj52q!0TQ+Epk$8+Q)Mnek`_ z)FVDBQNR&oh|q;tf$}EVcW%a6FQyleXWUq2lBI(K`2FAvjhU+59yz$ zY}7+%;8DcQ6IIAgVCJT@Gwi%(m7Nq~Az2h2|A(-`;}HuAJpK;YG^S!6C3_8_aYk*; zL}4}d2zm7EdLahuZG~PlK(Fz*QtW&n3AT`uo~|8B=#&KHfi0VMH^Tn#nHEs~BGCQd z?fudXhjbgk&7nCT^K7}oLBK!YIXD>eCKS$%rCu{}jJNhig0}xJ4g6JeLgD!X2I@{EFKQ}FRwIEOZogV!8s zIi&fTE9#*elYgATL#%zoL$YMQCK{`+3D>Gh`2Bwp`BRF6Xxk>dcoD+g~U zEYEI}=XlSqT`|zqOQfvbEbTg(m)A?9!leRuHG2tg9Fk)!Dl~|ES%?aG1n0SQfQh?~ zxbHQPpVK`BZNOuVcH`8v@v9V?F;w+Szo4~v@XD-NN2FO1m|pNWbXUnddc9M>y z`w(YFAD#~5j?#^>oI@Ep(-oiY!gpXK+ zKRWuPQ`qDEq7paI9O!#S>MKrBTRbavVcU=W%+Llr`x9ut9E4cntHwn zS-6QO3x(nCKiel1AkJ11MJFkjpY?qGb+Tp}#dA{U6*yB|>N<5E&PVVy=Ao_dNMFX% z3zh*#h*|Z4_;!{d0x=2GnDJf zdZo>mnOjwMQJNM;)H$1~s=AnSf_s<2Lw*MzQfc6+<>m9(DCLYbH`$hb!N2Fm{Yx3n zGwjMcBKPB9dGPK;Nz6kyGWhaBE$9F^kRx#iLSPwc3pp z6QV@Y_X2$PbZz$BkwkX>OP*tHRW=i!_2QhqxX8=l|HEEgrKXCBM|C ze1FTRS5YB#)NDaL>b2lq#a3W%gD2Pekl&SpXHi{CXB90No-jK9{4Kj@6q~QTeJP^I z;9U0MP(sY$W|gfBeNa(`mQIIiD56>Mu(K*p5j{=??|1g|Ng3n*n;hy&vr}C*9_RaM z9Q&kwWKn>Zv303h=vtbC7;qSKj}4lX!@E2su6T%Gv(g&kg1>v|*I09G5vITgj~Td8 zzqa4tL_QG{GMM*%2(QRW^!~I*Q^}?FOZQw>u)~e3LcUvM%l0Tecgj8AVu^DpbO2wC zs4c~tQeFwF*ISEeCxkP!v~!vFU}fLrRsjz$dU*VQ$wNLHM?K_ysHusECdRweHCaN` zm3mmzx4{J1O*F~KG63q)VdXi=4|yz(;JA@mfaPP4=!Ccr+2y?ZNQeP=im zyP(-Sa zzot5F-{-tD z!(esy-~adjeEz*N=Y5{%?E87ndCz%H*r0|x3oaXa!`fi98NOn3SL8Y|U04;lj@`u` z5FS+D&Bla9quC9a2Kw?!V-Y+G{pm zu=DjEZP>8SwqV{{cKFs1Rl}AZX^^_$@&@trppzHnjXfQ5EZU3`NqN|KVt1j@u)C~V z7b2w1#yaxHJ5;M#a{hL+QN?|+>|Jim-HCe*P;NIze_I7Tbd)F2Nl8y6I%t>o^$--bthROx-X_fFwxO$UK#K)4@XHI}l-{hilZ< z5HYjoARDs=U%E(VQh~YPL7avkpP*VjYP;z7PmPtSjoa~l;4QRpthT0qqNnhO>nV5M zI4Fz>lBSz|p$iYH(uQK4?|~hA4u;LFOJSiw6j{^-0ozThrQaGu4?`}p>J^G)Wj4yHZ7p>b9NHW(DLr;`>Vw8=Kr9One^SF;r)S4AmLUj}N?{IWjy?IHEQ@k!$2% zGKS}U``PU0cY~9BE_jU?}36bSh3ZK*PjthbVpnb zq}ynb538^)I%%&E$6}h;Gr7vhnF(%qkt~d%^W+5Fb$dBdzume&pL|xW;W9Z&ZM}l>0@-b!x*jXay8-LhAcOHgJEb9)|9X`lnwjoYa z@AxuP9Xd*U@iiufj|uN?FB8`>l`bQ^+d-Hh0@DNYFcqZDXg|$m>Rl4PbFndp4$hAv z88eXm(l8wR=d|1RXr)~bLOrBYn^my$zze~zjS3BqCFwunx=|sz^buOXU@`pxz=w3I z^gUW}*Fv4JgM1Xy)#h;chO(Zy5IzVL3gm@BUIIp;gMC75zC~pThfF8pkp|m#_J*&z zaczk)6kmy=v_=T}AvIjFTma$;g zHK_l)+?nXp%TH&928W7g20bmFVc|RS*^v?Y=+n2HD#Ew85e4_+2F~yzw5)5t+`R!Z zGvHfR)#2eqW4C{V`4D@k94mvw53sJG1tV9m(BLyF7Jd5G)7R(EIy^`p0*Qp;AoTXv z7B-X}zG&7BF9e?nne|9+$dOUA$_|g5{nhUEz2cfKqozmHJiQwdR6Od{EG1;`e1!63 zkEk2!1cwhX&0OrdRZikr?(eW#Y8+W^ngZqg8$SV^_yura#7j@(e0?wN{OJhYqsZ z(LTxs*~$)Aj|_oio!>U#%ZBFnxnTu&L+XA}19(dIdvD7iDGi^W<6rXdZ8dl=Bwb)^ z5i(3hwB&@-JH#W`i_>gcjO?SjqX(&vTo)R%eQS?|**xn?#B2k0PY>z|A+A1w#?%^P zEPC~x&T4bW^T9nT&F`M7(-&g*Sr60 zyuaXrJ@l>jg%^hAPliu11@whillv#Hy-N(=?>>@OHpYM?qUh5y(7>9(Z+K}T`)W$WN&)H z-gO&#GQd&Mc`jiLi=jRRcbdfJo>upeO?3C|y)TQ9KuYcS1`%<+JPi3mvP`jls1Avr zZvGQwXN~ymj@*u(LE6l9kh&WccUpUv^<03P9%4>wPX?W4KNREM$oO?^T;2)&@R^5$ zR3ufY_su(UC$EEqU)<&hSH)}Le$@8oAu}Ci78P__`$I=h0vmgpom~NcShsjud&1b= zJ_qMgB;yJF1;)dnYW-o+>laK+eW`54ZRVcaMEh^`yR6SJHqKEdY--X~!e@+PtYZ0x}jt*9l`)V>k6iLI!-e{`1## zxaV=rv2=Z=InpMdj6FB#p^hW@;gM$F2qip;TkOvX4+&!>xQO7cSn`+KA3v5+6nuoK zr<>uTXA%o=0a_B&;Ho$1*@ME}A&@m5A+5*Q(EalDYlmRxgBJ11k!inUYJu<+Wc128 zw#hbH|9a<$cE}@;++Y|f94Q_BcgzlTdxMS)xpXkrb;e^w3U>^w?SAu*M~2LsUhu;~ z$4eL3RA`gJ)Y749^tHm|XCPVYCQay0fzOX0@y?H*8F_(sZXKC_Q?96RI@52;J+s>Z z*gHXqJ)C>G)7#4SVwNuqhIHas zCLXy?Eu9u{&!^C{Jok(3g16<7{-+0-^fl5=^DK6A_P6RYg`+wHdTHZ9JbYL9%pWc?8qTpiUOJ}dve+==Th!gtDr zL6bfligT2w@O_%aPu)J=Hmg8b_2$X7XP&-AcqsP7s_NWskLu~=oAIqueI%IKEeV!* z^V8;W1&=}|#Dap;xQiOM1xn8}#5a68sxUud)HCLIGh{*Q$G(WMWUaeFH~FQ5Wc%R3 z*9yMIY3kD_?>Vgo-}E8QQIEIvoqVnD>03g_(EL3YLSkuGy`1{=a*`$uDZ*Z9(NY0$ zy|N=C{AKV+J*Q5(aEofg^CU-@qzH@C#!iTY9A^#WI78;F`7*5LNF-x%49Qc@Gl%UV zDa0GhLF?3(JPXMoCW*n{fX_I6a@#3x6FV&SBY#s&c@;(Fm8O)EqWMNs3JZMvW(9Lf z^D2wVN`J|`(pYRPF;-SA80h}4u|c}uK|KUD9v+84ZH9V=0ucmyGju4BJIdHcP$?y4 z`Nrb&0)akbMZTwCruShgJWM7-*bX>Pe^(P!j?m zP$sCEfV<2}}hi`s>B;c}xXYf)ZS%#c64_ zxujY4HkaF0vxsqRmg;}fa#>+fzLaNguCvv1w5Zu_b=FyGtQ3dA8<}pw+e{Y*)xLr0 z_CwV`l|Ze8dIahjsP$0yydmnyO|UAKin1#`SVSV!q!Tk#U_$I3IrzK|*lQqr#&sD0qZ0UUvbD6YkZu2+LK_PYq5BP7lrqo)|nS zcyjRM3zo;Vx9INGEmw7PaOcS2c6|&-GdK8PjlJ3Bwluq444B(#ZSA>*%{6YDy;-t5C2On0X?3}XB6~IVCP$;S)f*529X$cG7Y!8$ zJ{S5Qul@!63Hq6bECh-F*!-sf{=cjfKVdPdnX`U8i=W`OHaYAd+Qzd+dyS=$)!D3# zwXDUl*wWZyr5xvZ&*~fP)iA9xmd<4}a#)ka*39aV$2L?xi`(vGO;)!Bs=;2%W-QFR zg2lO}#nn!e;#|z)ra;^%15orI7v~x$#ajsFp^QJzO1}w(Ut@7wo1vHk)!goEk}OV} zy8%JjY9xDepi?Sf3ss6GJS6V-fZ%-=5bzTCL6NgMos^1ZNkJMc&9#j-)Te+*H`=jB zfXAt(p{03|6yJoJCZUm1I>xhVTQjncxvi~kmWQfosaYi17bC8X_9d*w(%fu!OQ?n| zO;)Md-kjuWaXGBbwbokHN2k5TZEHp@53p5hMR@&&0WoQ#vXLw`PP@y68096Qz#64$ zdrNaIMd2ql>zwu`31PTwh_EHV&t|*SgqC5cxAtd1RaJcrbbX~L#mBkEvvF}X<5*3D z#Tg%0JDwrmnynTm>GTfNOq zoq)B*ZLRftWp&k999GF?y}HHPj9$}c-K)=`U;23t0RO`FEDtoFKWmZbzl2wD_?lD2H>C3bBSbtgMS-8m?>UepCag+hfx zT?n;dqo^AR7z`D?Nz`qBQ`F6QN7U_syU(Gbp??Wf5>z_W6sQ?cPk$ilo`T8)UI0}D zRSZ=IRRJ|0$^z8@)nsk5JKH2wJ#-knujOrLnp6#qMZDOnF*Z>~^5RFWiRUFoZHB6m z|7k8|t@BxYb4z0*Dwn^6><;ehxVSjfKKLh%YizMpIa*u|bxKx@V+$2Tie<4^(8#M& z3HP&scE#ktnf3y%kk)Q z8?B2Gb7lO(h~l&n!-g1~7dUmqwq|c%*l4#q7`nm5HkS>yC7ya^WTIh>$38IXES|J& z=(t-kY!c3^v=?`|tqw0*Z*5jaM86TnE-&uoU(l`27)K1sI9v0${?rCU!P1CMrnU`T z9r{dkJ>X!d6Qz82wKcmft;%r4T-L@qZ#TjHOHNJ>@X$M~v>?yMag+X`Kw$v-OBmg0 z6BP^}B{1X@e}#_BR|7ES)?)wz57r;umS$f$Nv^i0YI`HH6WwjIy`{bZ;|TQ;N<;VY zalXEMk+qFCYPffgV{R%eC1a_7Xhz?7o>r-)lzZg!$KQPnK&q;UT=uTg-`xzj66!vv zSD_w6Uuf7O>Q+NhA4z(TLH!x(1*mYSNT@MT@lYvHlc1(S>7fdsilHi?=0jZxRSRW< zYKB?@RaM2S2dk=Twl49Z^);Z0VE|~v5KvWRy&5k|Z7tremTJ74TEJIT)!G&l4)&?4 z$^p)ys;Z^A3GYTXy~w%33lV~@m)Bj+qE*}NjaJNQoOYgXtkG8A;Pw?9#vQ6j%mGuo z!qqX<2WPFtZ9!8b{!9XsOpFo6Bd{IB;m|n6*{)jfUruL>gNDyh#Vr;#;_ksABSX9_ zk8cF0Vz)4GJe<>RvbmZp?wSS^DYG?mj>}CgjKw9VO{_;FwL7Su)mz=(=z29=J`Hcr zj?AhDi{|H~-~bI>(W_(Q&;rN7ADi2Tj)QZ0Qd5h|Emaev;~l9LOUlsm3x?Eif9jC2 zKGYNSR#8_7I0$ek)P+#dP!pggL+PPPps3z00DS%`L1zYBP$%f@fLDP24eHu((2GGQ zf&K*k71;#c^`O52eH-9%(02l+Sq0rrm`?(|7xemiLH9errUpUxFkmpu9|QcbR?z(! z@L9kY0e=JdI^e~C>j4MD{x-lp)q?Kh?V@fSLC_BXeg^>?6&(k#(!c}vLG{QHLjuz9E|{$9le<_FxE)32fAw89agm=u3d#~K^K zqA{fu{l20npgv6r)vt>t0v1)NI^O;b>?tA+|EQ94UXQb}ik)#7%{Zeu?q>t%9gzc! zD0(8aJB!Wf0<Y!zHpi6c; zENEhckOsAGpiP#m>huOpTb z?VvvgC~{nv5Jnv;S~?QLoR%fvZ{ZgZ>UIF&kO1OB!vs-n3YuhJutIz7C=Vq)HSFMQcKXpsLC%jKyV!d@v902J{i`jC5wRv&NcQMjaq^ za#Yap*Mx<{Ay*T)f{yP-OuMngq_CxzGC-jh2Noci%@FFp=-?n$OS z#f&8YH-D_yNdq3bS;40R|28#9Cm9rbWS5?^?5K=0LB820t^O}?SgI`;QmE|E*tPm&Gpeq0rU~d-Sa|pi_@OkK8hB0S3powVsI}h+`*t-(&A=tA4wgV0U ztO0BWoC)XxOaL4KcqiQXQi*zFb)pf{FiaEnHnzk`6E&q?P!Hkf0+_?b8d^{(E!CJ{ z*VyrLp}$AFY)mqwu!Zqq4NJCb)%J9qMN- zRCBGp$qQUo3_b9=fw`_mJA?lX$_j<#ZT#r(o2~VjhAg(SCAM0O7`~p~VRvD4fVSJ& zhUP{s-BMG7SudZ4WBQ8LiHR%fDPr$*HQ4Ih=ngTDtHyxFsuADnR(iS7#u-|c(}E_` zNTV#)A{rI@nBz6l${Q9DxHj90JZ-;P&~*atbqc!OfHu&30Y|w6-G0Cx=pO*w2>2~v z6W|FzBh1eNj)HwP>U|va2La9i{T}pBp)UE#%A0zO-pU}3^)IyYI9CWdAzFZ-*jlTB zO=BU!;Qg4X5xqi4FlSO~KSQM{(oTY!_h(yPmHR<|1^58q?Wj{pfKR}l0Qe2`PXYSsRzXoQg!A*c7KRAxB6I_o9$<&? zhj4eRpo;-)x>3+w0(kpx(T@SnTP5hi#|7zxn*?1d=t(f20(b@V(-6*J&{?1#xgIp& zrO?j>oO1*EH?jx)T#ENC=-)sO2JMSa{|bzQR=AwaQaqMhyi0gkB)}Tn&sYH;ihcu? z?+TdH`Ws3Qq?dQ;uNDf|F@Ob1N|45+Vnl`!mY%?AVnCDPmGvBAZyGK2SQ#BbY68~DeX+(G7+*kF<|zS-a9)G{s^!(71w1}gLo=<#G+wGl-`ebF z?U=7@C}*kO(n`B8FrS&v?|)ESzFvfu578aORa5EuigMvN$x??JKn8Wh{!3n;{UHrV zmV^bQT6X2w2?;sL@eAXUyjhas>)uk%<1KyBr3o`eJ6ijsFua{SU*`0(tUjB8MoLBE z%i35JZbOTqbyG%pg&_;$NIVQtvzM71Oql6n9v3p&uUndh+Qi06>!8_##1 z?>*moj(WcEeCg@(?Drh-9Q1tU`C9)&#}E1w9VhfBA^G{ojvw_s9X@VyO>~Z!w`#XDq{gvIy?qJuko7jWw_t?SrJ6zKDG26j9*dAA%dXUaM`Qf`o21-;?VKZ0;OJh^mr1?Uj z&?+g3Q<`*d?wJ&00y@rCp;nYa~sVW{qa8YL%*6wOy5}3RgK)<*K!6h$L2T zSEs7O)ed#JdPgN+PzTGx*c0P}bhe{{?m57{9+mDDz?UDy91n0uyGpke@WY1%-A90r zE>r1t0p9+qO1BTNIsUwYLc zz#pI((vW9&w4wjTS5e+Mpc$cuYhooBQqj-xDF$&mqehQQnml!OX-%WE_2%2}e)##9 z-r2l!_x`Vn!M8cV-3A7jmE{{`{+BTI*nkK7EC2N;cAxjbl@0Q0nqK|e&zjTZGMsrv@Qo?+S0{1^TH1Yf8N55vRimmdx#H?^If0Dj~`y6~w{>4XHd*a-_iv@D| z98Dp8kMu>~KXGY3(YG#4%fpoAlf5VDPn!?^xl8?zauw>Ibj!-Xr|DmC$zG7x`D?B( zs=hGSxjhaC{;2^50q8Dy8O@>3dw6X9nJm|xXRMHal5r2zPajRd*M`FT=l^U0rS|Pp zv9)X0dRge!AvIF1TRr~t%KlPoln`Ikgx5@GbZYZ6U*h1#Fn_x-x|(Y!vHfm0OX1;?-t6%Ba+E3mY67qSJaSo8yd<^*?c@Xoz+hXLWw|ar_{+|9o2g)-`4FnJ$N) z^dgR~GjbWN4gHfx6qWYPs37{n*KK`^rMS#r;nl!#F5pNLl;J=RWx0 zxs~l@VIj0C_3QIr+Zaw5yKVmpB{BM=O=wCMp~GBDe0cG;aYvX>RX&G%z#w^OdHw~@ePY})%4x3nwC_Gnq3YX z_Kqm)pNRa|mjvk!Lv5|ZurNo>6QRi|mM2elQ;88PzeOE0X;7+1<@{ z3-_xdwcPK>yh2uLmrS(9!bP9qO!<7H7xrwa)q;wtRRUYGWJxkDza+U^lkHA$BD9cV zX~9+)Co6+~<$MYGhAcw9d9_(L()%d()KQuBKs^myK)XE#{8=xq2EGyaP(W&pn}H7o zq*n3;I1rBYb$nmEIV+J-vmW|f6g=S%UG4fZB%P$|R*BdgQu98WRe zbK7#eqs4)mS25RUVsniZChVAGgG%??9VnT!j1F|wY2CtaWcuk0!AnSD5I-RUf4F?7U zd;VlOTqmkv4R%;;jwHvXjlV=58W%T84h_lC$rr`NjgUvj#YM_O+F-RjGA?eUtQkKZ z9!{Q&I4r&pFI_~e9DzrcVZE#gvgO&BeLY2 zv122FjU{qyjvP5LQ77xNgH>{TWo0qNFH;^n1Gy>bXMknYA!B2ZOLCSjGc+@cOyMk2 zUh4H_sSG`x9G^HbLKdUPN^+DWW#JVC7pak{Sz{w3$I7AQpvO*394m{wcn~ubk%)|( z5QV^_Cg@~=>Zw#zi>1J_=EgRqx-bhSm^G}HVFwVa#|+Vi$>t)~$eJ+iw4=Ma8WT}0 z*s&H&Nta*_*@j8!qnN7y5x3a?nLWq4*nai}`;vXdzGes5LCh(?VTaif_ANWgzGL5` z$LK-taGafBKd>J$=RCzuvoq{0JIDI4Ay$CU<{&{U1PgwoW%Xaxuc%*D zzovd&{f7E)>NnMYSFcldsMo7EsNYs^RKKHsSG`HSS-nM_DyE6)Vum_io(RaLSZsgW?o@hDpWcY^wOXgbZLvt>NYf5oK2?^rXPQzB zsZ6T0*Vi{%)62_DOv<2ln4<6XQj*HCzRg#UX~DYLUBcI~?Jh~_VPWd?$%N%jt8^S(yMQ|G3S*@qEj^>S zLQ`H|0<-e@^YJb&pE!w0`KFR|{)QGVUNV&$XX<=efh==zuaxb+u3S65CrXlp?8jS@ zs0>=OQ(LoAm$ojg%TBEWQnyqGj)j{m32bbu@P3?8CCr#G1KF+=U`0!OBgWfky#KD~{#^yzCxHMyWy7GCfC z2F{kgv-CHuG(0&??wUnyA!QhJoXAv^lDFt234D(`nU8f9R{9u=1W6`rZs3SysJ)7| zF@TtBZ^V`x(uHXOKE1f=tUOwI4c3}P82(xst+`;<%4z823<}2(P|YHa&86)j3$gT# zuX@%i7=5UoW@5q{U^cK_FgCTDo*DHc;`BlnSv%%niZyNPMJ*J^0Rdn0QBH zSA*Rh%u_6-A(fPL2?eVl8IbX)Se7JzZPw&kt&TJdqgF>ce`iSZEY9XM{!T~zfdTTL zKJr&$tp~}sIkC`OL5n;{fUUqLRoJUhr}G+YPKQ)!skNZiIbjt|t|_l^ky5I;_*S5B z3JX!nSNz}qr3#a&h%GENT)_-Tlw?4HBm)v7879&TTXLid z2O2;@3%+Vsl9fubVsfAYf|YQynPi8!Y5sD}t+RliZE-qT9++NMZeQYLhMJoB^jbi# z%UEG;J(K2=4+eVGRvMY~b8+T+hBQ=LLpr@O=rxgEjqW6dR{}%S5)i8dBqkj%c$dKP zT`(Y@6DU?mc)5}&R!J1A1d33?FNaox3PJ^n&JS@!P)uqvutjcHQ;MrD#kHuZp~=zE z#3Xz`)#ovN0XR-rXqd+&h|hL9nvgO*bg;L)>>6sj3#^T0&iV>#t&o+i^>$W;SQM8e zX`ZRD&{p3d=9idQX^GLGl;zKrLV*GO9VNykQnry5DksV~Z^u~Lf>{JAEVgubE51nW zJuN+z)cmxGscdR03o5ZTw=g4pS~SuJ@N(K~QQp|%!u+PW#YOSmTG6<*!nxI0yVcmT zwX$|=Wy@AW<5q(c{ZU!7m3#Uwx|Mg)ue^(ns>=K9muv0BR;wA4|>f#XmNc8g%1f*uLkhc8}@Wezt! z)$2;ESY<^8C~Cs@2@DAu6Lz6AyQ%rQ*jzh4E-|H_&{Xo_NHNwL&=FvR_$-S9ThklQniXV zl4oFaIsB@d)YH9<3JZj?)BHu6hSQ>O&+P!{B8 zrcVv}$IVA)!mbLOAE@;fMToyhq&!PwO-m!z&1?OGs{tb#wGcE8$^qm*b(nz4*YUPW zY=mgEU1Q~)AN2EZfCOK_+|(^vu-#rvO-@QmO-_}dQnkhS42JHKdQd#nhvK1*77ul` zc)%;rGg$%DIlx7}wGsOlnW@~wcIm;P|N8uz1Hb0LuQ~8*4*Z$}zvjSz4@v)*vSXip zFke_!Va?jU&l`yq{-s~sZbp1NYvZ-QY%8hxNmMpo$ zUsk`ICRy(E`8a}m;ZKs|tk=u`4D9o5FDUnT%Dq7Z?}J}TjC*@e9y4?8TfJ$z?gW4Q zHei^gB!FA=Ng1lB?qQ%GTmyxo#5gQ0EJSH;ySUZ&-WMQa`VMbb8c+&8ANy?ujJZC;uapA! zrRnCwJ_9fGIX+K&hF9OycfgBb7t{abIoEsQSaT_@1AON?-WLqcvvHc6 zP>$?fvgDP1kGx*|Y?{{j_U8P7{F4+r;%cvx|1W{PH-Gcf==@xoN_||}25$efuT}n+ zUBzw6Ir{(E`w_(M=+CihKTXpII-ed56!e@e_v&c>tFB@NMv?#J^MDe&pT2$Z_nTDl zVFTLX{mf9G!)r~b^4t6Ok#qm+=iiUQuP%PgfnRgr*BtmY2mb$=1Ez8#6R;1K#Ltls zz@Xs4LoXZ^6R)o@+Z-*e*DU?bvi71JNG+g}!R@BUTLg)A&F zmd?Qji{|<(rbz`jW=!IhXx|3kB#Ui}*d~E3w)D}hRVsx{C|1DFB=Q4|Mq_zJSqUpB z!3JEMkKx-QnW5BBTsBiGDlMOby_BNrT9p_s*`;u4Scq!0YHYlel_kZG1sXC;GS4rV zZ%&Ku`XY-YgYuekL5fkTJ z7$LR91*_T(hTNql99hDFS|wyb*;Ry1M|AocAOCo?1{~1YNjp(o$}Ua5VH4sE@%fSE zm6cXjlohkA|5IP|!aT$>uMPY6t7+IVxLLUpukL@tH5M_#!q)tNjgZ9Y*k##5;Yql12nwEm9lI& zPaj`Wd^0x19zQu?W%VA13{{3qJbkjQ29&zbo3RMfOjcXvsC9Uyuv-h6+4X$4yFT7HnV^U z*knqlbmufLYPK)&N=#)l=TZP~vlT+IDqOuweV=$)P?Y9#&1!9xE;@K`@IxW<2MrJ1 z7JBpGoFP99c_!@2@S#K34|NP1J$&M_w~x=*Y)MP93#* z)V!!KqZ%(he({pgr$)C%pNMXj4oC}Q-jA6P`*du?n5AR(kI5VR$FVH#vbY!Gw3l3V z$e|P)`@w)Lj04U_4KQxm5oPKLdV#Pq~8{!0fw3A)o^BQLQqu{3c`;^m3fM0;Xe;*E)SCaz9= zHu25GZHZlp#}lnZ4^ze+?88>Ha$dEI#Cbms{ zW#Wm6>609jo||-ZQo>~0P7J$cL&%aq?w`E<%fnWoH@nOic0rsiO~+1jaxrbbVj zGws%C>!ux>Hg@`)={HV)Y5Et_!?LDj)n?t6^YJC zX7s_|7vX;`!U@az0%6{Wu*Xh6hIrhH_(V@Tgt)aLjzLqmAik!|i!wh&{4G<)O!*q= zu}w~xd=%+(OiG`00_km=m^D#G`fo-)glBw&JgH8fkbVq#bOZ8gWZD7b+j8Wel-h&5 z{2lT%C*{JFqsZem$m@B?^Wn+Ik^g^1IV?kY%tpCHC25n6qnx&(yq-n5-HGyRLpfSe zo^w#Hg(%-_l=Bpn_rUU>h&nL^bz?f}NH*$<;k^2ji#nBsx-}7XY#i#^MW}PC#2-=r z_MjfVg8H};_0o*`IUyl5;VA0slc=`~QGbIbe2lv6MxEA;{{Z#7GCm@HJL-GxxRa>+ zmtCU0Zr#@4jp;Ti2aeq$R{q+USz#+{RN{ga7An$K63#I%{vXHuX#L^I6GxAyA8$LhzGqO+obEq-|NVD4->o|O#kW(wz5U47hjR`;^v$V5 z3l6<;F#6z42fqLMvajF$YRXqneR=Vh_k1zs_| z``HbjMSu3@r&oN+K7IU?(oat9d3?{@J;8hazPn|2>h5np{`1F8AE$lX`_cN3Zu@A# zN8>*_^Wg^{KK9|V59fb4>BHe4p4j!#uGe?1*|lQV)w?d=RkUl$u5r5}cZKZg>pb51 zO=nldfm*@02iJpyY#* z9~{{B{I;drjN686`{@1OzhC?Qg!jAOd-=V#_h!5&y!ZCjo3|Ei4c)qJ%c?DxZW+Gi z!_D_?Ua)!8=DnL%Z>ruDx9OXApMCf0cPGDl=AHHLtazvVoyd3gZ+vFs;*ExlLpFZ) z_A_r^`*!i$qu=h?@Xm&ZH@G*HY#6sewV~^+zrXeSw>)pvzE$*A%3Bw`CA@WX{U_@; zuYZ00v+EySf8Y9*>u*_q!}{gxJy16QUkSZOVfH%ge6s%NdI4@y;I07mB+m=wI_vWo{ZxxXKHsnM1dlQf+zkmOu_lF>lmLjhXY#WJuYe)WdeGrDc zyb5``e*59=!;!~kd?^P@WkBmZZi9Iiuoyo_@BYUin)gHcZDC@&Mr&5rWB8Rhs8 z%JUhN>#Hc=w@}WTQQiZ~|2@=+&8Qn2QAgfFU0HWt{rNlU)Z3_A@1c(EL0$U>b*`^7 z1odwm>R}P;raMaiNsJD-y{+{`8JnHgosMEb4rJ;WR`QvXtPDOqH z`|e=W{m1v5+Ee<;9SbJ};tmW70InHS$8 z{vtw3)#dPf;pc1VbGJH-fAsd9tCe&q+?=1Sg-_)=l4F6#d%hMoK5*K1#x^`8n)^@b zi-3K-u8f=WGrJU%L1A=!m<@(|y7D1>P&B89d1*4I3?Oq{(!tG%CUc@w2j%$P4}m_> zK69d_K`Gq)BG?DXX)=!rpeY(L0W>A}k^q_tFd=}Z0!$5{sQ@Ph&{P1^yfn}Oj|nSO zb|-}24Hol^rIp4C$y8aCH`|nADlW>$IbY^ke%_#|H6wez5Lf#UVZKLH~#kK z-`91le`~|r8{c_%)8;K(-+O=C2ite-?A-O?M<4Ir^U0^5?frb;FPNY7ny)T278gk- zW96K3W`N+b`erHD2BD!2ob{vgUHQ$7pUZ;0PMrT^?9Z`5y4SIWc&|&P+xWboOHWQq zo(%Db5GY26sd0Lx4TAb1RI!=WTH06xICsc$tAWrtx0|-^bBL|`Ht(qp=Hkb#xkx}p zV&@^x%V}wXY)39a(OFkc0)!!{mE<&98;c;v5u#Gvbl9&MXP_YIil8fx%Ryb7#ulfu z#TgL&h`2)nmU7Bpk&;@AsRJDzA)${gZYxJ|vc#o`V`M3&vN@&srW9*)3NtM*RT@iD z`0XdjODv1|5w=?8sCI1(WPahy4uq*9F*S?oahC#QY}uL}Ep7&BZXDFr(Hg45(UgZ1 zE66vXg-GboO7MzV^UhzXqtTW@>7=B zuEAn&awDWk`%|D8v1B*o*A|u)=d;qXQX_M?)$=tA*rMtb7fYEuk;UUIr5%U$;}_W= zFc?C43$I~<_mpHxZb^B+fBwskpyjJh{ign_j{3Fu%}Go|@{@7oH5mupW~3#|NMmWO zjIX!ze1Vu=siFW!#ZZ;JxL+U!6Zi>DOP!SqqGEJ{5Cy^y5+ZM`iF9x)5dy%i27ynkjjNFYa2NzShEbqnn3ALPS_R=CF|PKf{}A6bQS33CXg2JS>RT3ZygQ0s7qemEgPG>YnG@{7;oWDMaPC|ry++V$ zBvT*x?mKp&Mi|ZnGS$*cedfebrWH2-VoewWyu6iFn(}xr?oSd|~-H?inGm1?~I3w*#yhIv`F1}9r6BwZF zY^h~9fJs7G`t7OE|r*+(?F#pTuoIkB+7) zEC~poGh(bjdh28*$r!=GS#Qha@&Z8nD!h;Owsjv_V1XY+6gbDq&})#u_@d@IJJ>%3 zf(G*f;Q^%M#h^z66iFn7rh;;J=y$wKosUGlCQvY2up+3%6 zzp{`O8w)BKr2FTg`^P(-%{3IyF*5L06?sNhVJt5;0D_4!RpeC_6jhiitN7LfpBC!0 z4@HIcp{UC~6xG;=;t;&oBOHbIVR?Qm-;enN#1VO)y_tTj(1$_T3M4yF#EK23N@ko} zSw-6|s&XrghS{7fH_SAiPZpPz&g6!CvKU~h(EY~qiz)+5%Zulj0?3l0(g8F#=J}(< zgB$nL+!(p(jU_kbBqVYdSIsLdf^37C6~+Zs`NjeR&a0yUFneYBWtEl2d{$6Kg<-5P zKx{y9UVha){w`!FoCQ^-W%Cpy*N``RW(6_Dj3fdSq6n#8Q zS(B1i(zlzy;i6Qt2)RoH0$MO9OmIl#RXQtR ziBY9<06tKp(p?KUXRBIw6X1T>`yJrRm-frJ6>=4!1K8cOgbn863;5<8oT_J#aRNar zB#~jR4Py4Z$%Nbq+<8OOe)O#DS=?K(qXA(8(!_&b99T@(-?>n$iz@R9rAi~JHJ{nx zAV2!5Ek0&a={C@lmV;5oO$V3)kmP#|gHDJonA$4E50v0H9+iirqZysnYorRxV%y^J z%s;Ck8Rh645iedqxF~?n_;EuE@r5RmaZ}lZ?MZZU{U309mf&3$m|0wwYbciHLZl(aEJtfU z3rMN9LC_c5oCI0MkYT(7@Z5*E&jHYadUXi!H}?y=Gk}jot8^mnBH43H&AMBamy_5sh})&~AV*H$#rlPF}U^^?JEo6{>1)hnTo_a+^&qG}(qrW3Fru z9x=Y)68MrX2s;wmy|KZa)mT5h3##6&(mnM`e;e~QDHMnDK%n1Z zmd&uSN_jlEG$Zim(`Ts=>(|QArj&=72mTb@-srPALmV2j#yrGvHm5h5bQy~@N16ND z``Wn+MtYI0QA>w3YwB;R*=9LwZZ(r0xw^?hziqCwIjuZK9&LxVOXJXF;;StAK=zhJ zF3YTQ)S2td2ORI@+!RfE6z&~YliNF7Q8|&^tp>6?Z)$(1{eY4{9&YRCvpL&b1H)*A zoWX6Do36fT>b8r|hV^3K4#hb&v~_gr=+sc6=;>1$VF z-0x$54k)=0l^GdH_K2cfiOS53>JIDD4s?5yg-p2~E*bItCebqvXjipr$YBE5m7$+#YgqU{#C1rkk5 zcIf9|U93a!s2N1a677p0h3PAG()Xp|CSjX!78S>DuTImf$r_S*w!OFBZ%=zu*i9F2 zn|jvKYHp1@o4JjbB&Ap>O^UZK?tVPFFNe#?Rq7#6U!S%wj6~)_pUczj3xkeg&w)Cg zP5P7%qg%6=I)-#V=k((i3Nv{j_+)QOoEs-F?AU)4{ z;r6GELRa#DyHzR%-jv^zGRkuVf?o&HN_KwYAJuJ3M@?6~FJH{dSQfewq_a1=H^+?l z0_Azy72V~l2MSHTX}bp0gD$i;uRXHE>ql2kS2U03R8KSu>(7TSp-athr9nl4_>DZCdqu`-B!b~0lvzSelTT16PIe=#G637kozYh5qH(k1vqh#sS> z9_cfLclH|{6+Ie1{!+HT^GjA-%A$6G6H>Dvh|F2bSA~6yUpQGP_x z!$cl^9yV~TM~NRaRq*kwx=#!FzG5H3B-=VM6nLK&Ho1#X%@FN%L0^c=#3+SEY-7b( z*!hgx?-06#RN*YSpv|FjwmMroOdKX2(|*Ctd(~&Pm%#pa+V?n3Ir)Y5w01Pp@bo;4 z@Nr);{Ck+2XQ`KIbH!XupZYBK4{`8t5DffOMRISl~vBM(? z{Xe2rqDB*{zF+7@^Fa9^^y@TlX{yonMe*=MQ5wVW8_hyNcWZmKx8eGno7iovSKEzL z_3_lkiicQ1hv zqaWF&_)=LYzEb>|njvK>TbOf;30@>9%18L=gy+&?mp0@cMlJgolk1LEtA zALWQ*ew}z-kOuXkH;CL<>b=HcAtv%GOZn)9(P{Pia!|ki3}Chxqc?@E8xl zn9(hG(5rO|%aHdxzH0O+0^{+~pmtH&P#F%<;=XFwiDcc#`AA?IrqW)geG9cCT^ubA z;pIy{P#!6zt%9v6v^Gi~Lry3q?#n}>B9Rj`LWaU$B0yo%N^(oQ#Iit=}4-6T2fKG6nd>@mAF>y(saOFkG4o{BNy?c z`ehF44qFwnDx^EaJS5dyKO`0oR;yg)z((!gW7}{pgKPhhRn= zl(gck&w$oSu?~k{;mAXZKjmbg|GxP9($gK*9TqNx3v1EGbRd2m$jP;!!v!+I2@>v4 zDvzN=@mF;tb@W@SmC!1~VS*k}iyT2=Av}!9j4~7X*NyN~QL-HLYpw~`t_s>NIz-AXdd#RptHW?zlefPlJtgl6 zqle5^gU_M%Zbqv&vszVyxBXMwX%K2viaw^Xv=Rd;l~^_T!29)$m8KY&?@JtgZcwCN zO2t^{Z6Q&J-cweP>x*@9$v_vBF?#-pwIGi0*DC$91L%A7FAtzs>E9ecuh4HCKzsD> z51^TT*8sX)zh?m5owIKMovJ@PfHv#DA3*E%KMbG?^=AgqINFvNn4az&-2j^D!w1ma zIb#CpjtYHpAk9qrse!cKq|XneJtlowAkF6K7X;G!dHR|_+A~kz6i9c>(=Q36*?j%- zKw3Xv|Jy*?GhcsiAl)%vzdDfiRO_D}Kv(Kt4y2i0|8^klG3Yx3X|q|sKageyeNP~* zH|rVJko@(XQR$wm?54kk&8Imju%6QvJd}T7Rkjsz92h>RSfT zml&=Kq`U0;6@j#Vj(%kz&6xh)0d%Q3BKazFN(%>lj!@G&Sl2=N!d7op|>{~O?XsAAwx!2TBC z6~J$QThw&|r^UMuw}`rZz-I&hJM4T5ybSnpz#pN?foq^240S2+5r9!pmjh1(Oo6%r zcqZUHG*&W;Vf8UcfEL`PEuZVrQ;-1`-&X206-W_@UwJ%=w$2U74-XI_U{LAXG zc@rg3h&WLDuKQ2nxF~_%WI9Z9cl^j&GhjRd|c-fsm&X zUi;y)U9(=f=66?JJ+eF`W7@C@=RW;x>$)?)KhpNl{NGN0W8^cBH{QJTtKyB9$0n+? z%%O&;zZ_k8?%Vg@-#g*iL2owPUi8R)%l_K@;gu&!hi9iJUpm?`WVQVF@AvLI`@yJn z)1F(fx^?A>JD*y<<@qCzhVDpOU)p2e?+JgDy_Ncs@lp9g8qh58V9feN_jSoxJ$ntdBb{IX3xD&Dsm+)h%9pLBYhi#e14I4>^_c z&87#wx#iZ^o_Q*NzO_)(IFHX2?TJpKDqm6q@-hcYd-#&Zjkuqz_O8CDdGfM3rS2>5PJSVK$B^#PMa?xS`Br?GqS~p-w_E z+!L#V8Ul3@R5a8$sAQ-~P+3rUP_v*eg_;jl1=Rp`HB=kaa;RIN?u7cyM%-%)xEksS zs4j%@EZ|?E)k zK}Ay=odE`vLNP?GMCE=_V2A-k9UaQC>|}phrdfEhj(PWFrN>G*>XFhCj#gSKU|3q2 zmY6rxf&IVV+IyJ6FzY$zIsfzg&sp%UZ_nQAzSmxRuk~FP;12`=eSlD41P~6y0FMAu z`AX_E=ssZ<%X#w?X|s2%Ut&M&bP=0bn}We_C?J`cJnS*e60m9u)8lvySPA0K111$g zR`UZvqp%yCLTVF9LU1G#B276oz-Tnhnlmp8n(u+Lz&YS2-~wi{+RL6akR9H*{x&Qb&4$2I039T5%X{Oea*86h>+lbf*1C&{r5QeQ|sU2qd=uJ z7VVi$p1#G?(h>Ja!O%Iw{ns*OjB@zH-XF@83a*0JKm~84DsazEIp5+rukyfqTxPnz zBTJ-*RiJ;>Yb&FAoD@g}){~4Fc{jt;at{ZR9&@I8y%je_PgT0T$Aj>|Jeo5Vo+wYA zXGB$SaeF+GXgztDEiio}d3N$J*=2gU1iTn+c$5qks!fm1Gfab6Hh-RdP&t3eO1Q47!R4X@b~o}|+2OR?dRb&rIyT(nYw^e7sXNa1;-q~Ofy z8zmL0AfXt)(L#uZ|2ul6R;I@qW2s)+E7c=66GM&6-YESBL(78^7fEd zPhJCgjpW()!)x9LPulB^V0*l=dP|G$wG?>2Ln}T535-o;i--Es;d!^`lXmQCCH$W0_@wfWqUOoDx zoYZY|!v!8hI)%W}_tcX6sb`aCe+IcVdLp-abb5jATbrH8nkIs>FKSd3fmG zdVMqQhF(G{yRGohN#JS8L-R9q5_mL9&`o3Y+D6pP+KlH7-mjjwCaPNlZ>Ha@8wHUl zFq*1WFQG(v@;oEnD;lXpcCrM3-o!-mh?gY{$2YT}vogCd8l7K27j1l!yuIX|(!#rl zo6^|ii6D|n`Nl?MBw!_v?iH$tc2J@FNvPoM92VVz7&^8UeHBj=_v+D=ai?2(&Z|5y zk9NB>rARKjHBlC?cf7D6s*qj~47r85=_4Tzk&GR`!((H)>~@Zs?_vmH2U2JuB)Gt%elyV{y^pF;?rafWXdHYoE-h`6EVKW9AJO=FIn0 z4YS5rhk3+h>w~Z{8@O}UcGd+}I)?;i53^dsM+f33xZz-K3ph6wMpnSX$M0|{G(X&` zw^{>dry?70!xwlV>ViPMm1m9^-X1s_INfUPYKrb1H*L;f!DZ82J{!z~Gk;CEZwxp_^GUoaXhcT0(J zKKR|C`NsL9tXA;5Q6TWU1BVBeSW3JsC5UDjZn1>u0s?d)FqBu~6&Nr!(NZX?^;V;( zvn1&(fx0AJpe}!SzRs94JjdvjIKcvbcVS|zFu|$vF_rIXG>tjLFv8I9a14-js_^H3)d- zA^$Y!q2N<27ow%GcO#~n`a3pxOc)yv(JTnx39&Lag9-;01*A-|Gf;~-kIau3NGLP| zIydQzgs_kz_!N*fqyySIqmWI7_|-I)P%@Im106la#Z8WKs4-0-`Twc39TYejiX;(a zc(92T$-zOguSIeu!DNDvP9Em9PAfdY3KN7j9-PW0+@>j_11$<4>;V7dBz=oQG`vIP zpuHR%lVonZNSS++LJlO5O`0J?E)9_}B$bZf+NKz8$&nZfoM|9GFzF?|3I9a&l1UH8 zFXN=*5YKBL7_yCze__daik)c35n>3 z-~efolkM10xFBqUN|YFPl0s30-+hGi$w|hj zh)H8;@MBm{co*}R2i_Gl!S4wgc@hCJ69G>b7fW&3Cf3ZtQ=ooD(Vq3~e9voxL!!4% z8J51gaO{%3s~>;+i@)c5dZuQ<*=vnY`e=lghIH%s*5rO;b{36J`=re9e9i9ozy5S0 z?VxnM_y@P(=R$qlR^8P*^X=j=W5uM0w(cu`^nX5kJ@4H2H!KIP9A7x7y|}D%fNK5h z0U0|IbWsN@BDNg=^Mn^J+|2l~=~&?>>WJqjc1eCcUsP}OAKYixu-Jco^!4ib!@M>~9P&C9!zXc_1A@uIJS z&aAxLxAcu=BmeT=yT*sAr%ulPx+KZ#Y>$G0H%CAJrF#GCSGt_uxKw;{*L#EC{OIx6 zhrgOLJ?m6pR>w>FxdS?V|IF3E%9oGc_r_ng4S(vLm!fAKnwv1T?y;2q=XCjHfsfsK(WO^+ce4b4iS@)SQl2J*I3WE}+-Yf8qTij8zhY>4kW9BG1_ArvYg zOQdL741^>cw$&N~$!*9J#$@KvgcqXee3K!FI2vOVYin4yMqgYGn`?Tkr-?XD185EI zVdb|Czo+9k1@OV~a^NufyIHxu9luL)ya*s2R7}%z28j72Rwyc(gS6X`V}Ve9^T;xt zg(Tzc!3TJ8)M$sOKMJgD^B12G$siqRrcaJJA~ZI{LX&8ol?@RtdD~jN+8pWP`yzH? zcr=FmsDuPG7cC#Mr%=vCK==0rjXTyBCeU_R4Ey7Oxo*leLvMw4CN4-tt6?`ZadvtN zHoheWMRX2{Ubg79;hjnv0kjZWl&?rgLC!EHB0fBU_P`B<9O6Ha&zNn3=0WJ2D%uNN zd(%-c#`*myUTjn(k5o-No^|w4-YDXfu~FkiBWdte*d^u*p7D4g z7q?1_3G7ttj`|Aw8#{{KPCH|-(l{YckVV3{28H}eQ??z$dda<5H$~Ydfu;gxU?K1# zPzFFc4w|7tjI57?-FjI^N0HFlXnlyaYBMHAO$|6u!ACHshd%=WVb>=X7WJIJb7HTx$!#16C1*yrpEwBb?qCHsmUW5*fH0I*tC z$4;`Z*&o|g_S&!Zm7NIPLWtY))i1sWAT~>Mh%`fhFFS=jJd^tV!?Y=K9v+Q+?1$^} zE##E7koPpD7JCf$DiNqCantPEC1~jJpdAY${IE6w`bx@vV%g}b|CDvu$ogS= zf#btNmgj|Nb72;q8IzcU4-mdOXJ*k;wB1LF)b9&R`YS5Y{YfV}h*TWt8rPN%qHXc` zuh2n5`wtr2e{fh3iNw>X(9n@X2aOCJ5=0*~JPh`8Ls!X#5GJ}3b{2(PV~evR{IF+9D& zn9ZG%&Pd-#--1v4NBU{&URol+YNntTJiw@JFL()^z-{g<_z7Kv0HK=@CkXTAw$R#W(qkNN%DmPp-?Cm<_PnI`NA?`nd(K=ORD9nmsKlND^;(kR;gZ9y{0Nt ztycY6^}1?}>J8OjRBKglsn)61t2U@Msy3;7)V`2txl8S*_E&dN-wg@iuIg^;?vRM- z0l5UNT2u!^9^xK#h`N`$x4MtIulio~ed_zw{nY){1Jnc60=V=l*xz?od#F9t8g)B$ zdvyoM*>r*xi=^P>;FRFh;I!cM;EdqR;H=>6;F-a*f^&j%gY$w-*fhJRbdMAw^^$r^ zeWbq9z0!Ts{Zc=vzcfG^D1}Ocq`~;K43maR!=wkK;nE0cB&OW5D7-Qaq3z_|m{7_L zjAQ}88N*NTitxIHxK%!XGni#nVv^L)OA|5g;qNJol(Nh|?Zyh3svLTiD0|#zLxva6 zobpQSC+3;*`a|VE7iwjx*f)|-s_`=&Z=q~Fv{221s1_cJ!t8YO05Jx86ep7ee{p&a zl7W2zQvqLFAAq-JK3O6Yp?GO3%FJSECVU8xX;Beb&Q8yvM1xU!sMhhRA?ASn$3}{L z8aNhnL400B;UU6WIkhs3oR z4>H*LC}$dmp1e$G5i0e~O@;!3GSzDt@}O1WoB-+!G~C_Rb$Pz_{o)K4S5jV+)OP5l z_4TE~MkaTg>oQsg^ziCHUrVi>NAtQcL`g4Y+GB=leQhJzBOj?hT7GwS}1GY>gp3;?pcZiM5rL3 z6iG|>e0ic`^}N=lMbT$(soUA=>A|_o?0HMJR+Jw+SW{DT@L+kx*5~JCw=Szv=ghfV zYj(KAb~Ht1W>!{KHjvq7G)L^`s%sXt)YuXC_tB?6sk5})2KM{n$f1hgui4s;-W!U$ zQ{3W~5vO?liHfPT(%s^IEAG?l4xFexv7X0%dgqCXL}zh%`~y4JJ>8OYOG3p@uiJUx zMAg>Z`#h&soY+~s;y?}LuUaxx4m#wnF0W}d6lP=;e^67tI=4eRcm8?rKDDB@dj4&= zq#o5(tw*!j=fmS(fmVKk9kaTPR<;BWsq{Eh-1CO zfCknP96ExukedoY$_L$`b@qUdrY)oCk&`AS#Elab6Fe~2h1LoHn}Ztd2mElX^vZTg zpri|zpO1O!W9}M@)?M?%B+N}`x@(3f0v+5nd&1l`h1u>J8?GNHaM$#Wk!8W0ivtg* z)3~33c~dqZ6+;&lb0^rIkBosnpi`KDVx$);t0ws7;Wi*B``_X4Nh*ix)T1|@2hneI{9|hs(E9Ufv>P$d3-zcEyY_4y}x|(fuo0$ zZaw|Gf9Ie2?A?joMxQ@*yI0d4QWBneDy-x5i@w^X{5ynf`?BEf;bl3j{yM*_x@?kJw5#>7EO_SpLb_53|r;nn$VGJvg>UGPd-F zl{!W~-uYd44)0yR-gx=i^=D}sfxk7luw%`dZA%$5fZ_L0{#8jHQx4&RZRw3TKJZS! zj|)G4EgcfTK$EoXJRRfC8~DlH1vk;LkJTWa&rCW!P=3i6a7f~9j8Q`O^CQ`F?*#WX zPO4yQT6#gf3Wr7f64uc#D6c5W^L2ibj!1q^aXwA<8#iv;lrGFriHLrPvAGCv0#|*$ z!-1a?j7<0cD-KEh9%q%mj;x@&r5C)t-)<|CY4WL4lT8w9*xL;r3{Nvp6UH7=AHCMl z0RDc%HS8IxiW7X!v=v=qKTFcjz7q5HDy8_pNbJf4_Zdu@JsT-t4C9fGqXEz!ZMm!I zK|$$Pks%yIf$8XKKH_s@);xam+wMNw*lqT!f_`#aPRWYLpDu`v(sxXlp`84e390vt zWD(;UyU91S7^E+71TX*sX2Im#K+1>9;3wcAbM`Y#LDkjOF-()#u3fv>rcImJs#UAl z;>C*@Hr1j}CpKx)BnBm52KEW-*|R5u8C@j_dOws=GH_`CUr=L*TXg<0x{Kz*qSRR} zi>PD?P?l3w^koI`U6i+$vLvi1@rvAD%OFfx`5KeUTHTNqO?D=z+&$ZM^6Bi?B_J@U zql3#QCd7e*7#U{X$0tV@x76|AYtJB>u;5l0ogR2Xew-KG>^ zn~%Iqdf&*)U=c85M+^8^7!V>d9b-7LimDU!;LYh3pb$1Y){#qw*ATWKeiWb zD{QaY{%m{Gw$8T6_E+1xw!hgvwEf+-*S630k!`>26Wc*swe67YGus!oqqeVX$89yX zI@{OkQ|fQj->Ofmpsf3N;QeOCRW`keZ_`X}|z>I>?I$_C@b%8SNdDt|Fvs=Q>p zTzT1erSgjLYUNeqwaRP8#2i}_b69gib7Aw6=CbB3&E?Hi&9%+vo9)eBQXp1% zbW*I8DCI~NX|c3adPQ0zZIHG}??Y1JfOJ?oCe=$nNDWdW`j}T9%S!f z543l;ce8i32iWhncd`51{p@$yJKKHjK6Y=NcX=mWr}B=vj^$oDuksGM4(082?aSNg z+Ldc`nsU!X&p^*wk1~%$=p@&=m$@gp2fEj)%hZWjA*;p8T8=7K)lcQ6I`3BHw#99U zTaH_-TR-UepBJixEy5D4&ZS`m&xkd?5Uc~Lh0E+Tp3_RKlCK4K#sFH~no@@RRC`C|t!OKDU!WYR!=c8ZU^C9dw0ClkE z;k!@;S!tDK#AxuWz^C#D9!pYbp6rEdBUPGd_$`31by0_Fuc|b%K_N48g3Z_TfjzDF z&((P*`VHy5?nzz6!G^huJ@b{{%XD$OlHD`6)ae8I8xw8@pVhy1^~ujWm@g>5uj`Xj zVPFU@*$iuaaQK-;6hfvfBiBU32aJqm5@0+FuVo0RBPb7JeggU_tz5lc{#n1fST|?r zg%LlFQfLK)jG7|`e243t?rs&0u~L`c2G#rDDCwY04DbxhVI)( zB8<-P__0w4r#HkdFd%HWA;%{I;Uf%7-i$;XqhU)}6yil04t^YsxMK|G9)+$-aExK$ z^*5Pud>*sk>(4%$(udWBU12FTdzfz3%Pf3pBujmyne95cne9yeh>gq(VV{qSU@;!` ztlf_TSm2AFv2#6|*}d-svL8mTXIF+k#f-ZKu(Go@w!L>g3tupUeYtD|o49ZUE4w^` zJvYO~`d+VKjoJsn4!pqHKmHuc)#kE83x=_F2m8P%&rbH|3_a`r;|%s; zpCWeV+7of%9s?Rgfen#|_eqglh|SxhWH#D-mdm3_Oh z2b-R}jA^=m#}=(hXKVasu;&d~tn`?~`k2Qt5063Y)5-qqlMQAz@0%nxYsnto*Xeyj z{a%@kqJ6IO`_$i9NcXMumFPy26HR)gs^mfXy|8=32vCFAYcAe>thDD--wp$1JuYPr zB?@hSdX-=AlX&?-PXw&oBJhYaU<3(va$v-REWtsg#N`@9jd(oH zh%G3}FHBDp&2zw^&6TG&F$3d7ZuZnA4%W!QU!oL~)6y{8qroD)AXB8bs*@LnO`E_6 zQrP7!X-tGQvvhE-a$uMvZ4TC|VYW9FnIZ`=tkUGN=E-KrQ2x}c>>Ol~$BYmuC;mG= z5FELJ9ri>Ks>I_WERqHZR>w9M)0 z)SR?Xk_M}nSS#VZ_t)j6cE?SQC@{?e&nG_{y7S|R7wghM_z;CTCAmk+CFIWpI6!8S zATwp4W@hR@Vj)+(k3o+p%+3JI7dKz#w4&c7r*R8>uI+6WU8_iSiapr<9_M3^bj5yOWDy43+l)j1BTAA!a1!X5)rZ zMlH8qOqoNyp4UYQ;H>j(Sdq=-H;0B1F!pHdK)cFg2zs<^*PFT(G5Z|XTiT3raw&+* zGY5lUMP_ONN7)<$5}plQpgb}Pxh03xWD4jQsQB}mLOQr~f8}yGA39|ybDnpk>Kx|4 zyHg6C3Y(yqP@xRm#29ZDjL&3cNohAsiHfsLMOb#C0Ue_O0z2ckZbmeLqxx)|(!u$o zNn#0bE_J7#m?kQHkzTI<#4P)uN|sZiuz4Abk!^E&Prv{w3u_|`g)4vd*vfZ5FVhWK zzv1XTS7SzuT7TKta^ zL&Am*dtms8@Q6s57NoSD=aN%WVa$`x_00o|6f5D*7rlH0IRZy<+4$t~6!Z@{AK%V* z`T2LbJD{r)ty}lN9zojMr*Wt2w~zTByyEyS4l&4?J|22Po^^)IW4sf2xoAI zJEwAL`)Vbp>DARl#TjedB0zsA9{T{%HGY$gA`MG+l=OJp-#FpIH(#Fa_OS8AqvJdd zHIy2!K6GloTmK!#?W>Q^i7ffi=t$@8Jog+y}(bP)-o5MQies}()JL~XoO#i=0{kH}F+XA<5fx{TDHM5~_JpayUy{zp_Gt8Zd z1f2pSC?Qrs0w@8@aE>%kLXLt$Py%@S95ztG5(Uda31te_f)chU*bYi4S5OH`s8VnQ zlu)bSG$`S`g3F);y8^Wb6A4}l{6GoVDuE*el+aH>7$`xfzz9l+RgeHmNK}vpO2|=A z2uiRhuz?bmC|C|kC{wT&l(0p?c2GjOf=WR0hExaAPtm|qo5F!U{PQLB`i^}9F$O|U@a(Ni-PT- zgmMLypoA&~M?eX+3QmI(&MUYKO0X-y*MLayQs4(l2viUPO6aE`43wZ#U<4(^Do6k& zBq~S)CFCe51SMD$*gy$O6f6fNlqpyXO4y=cJ1C)CK_w`mO2H9OLal<+poH@ZE`t*6 c3e@dTf51zDA1EPEK?o?Jp903n7MmpfFL>IUXaE2J literal 0 HcmV?d00001 diff --git a/Multiprotocol/opentx.bin b/Multiprotocol/opentx.bin new file mode 100644 index 0000000000000000000000000000000000000000..8e886c42a6124e07e42f51ab36b361274825ac8c GIT binary patch literal 228420 zcmdSBdwf&JwLdzu_twLbjAhFZTjsGP8IUa#Yz&D5Nf46R7z<)vX?dkccG5_Y6ai@~ zNK*tRsR_v`2{Z@n(2|h$q)F4nqVB1i5<7vmNt3n`k5dClqcmwv?4*^kjkX_H_d8oQ zb<@wezx%oOuWNty*6cN}HEY(aS+i!%5WFBQ@Sf_ES`)sxQ0M@@mr znv4r#-0Ud`9ML2%6nKzI%=2FB)CZb0x#w?U-&V7?CP7wDtfu9S8+n|Hu-g@X>y<=&ozp6@R!&2=!|H;a+V+mA@uIsk4g`vc!0bRB%pWz@x=u#8XO~ zorGK=yNDYr8U-%nK!@y(V|3Circ++j2vgF^}{QsprkGlWgmFKFd zSyNU@$ZXHv*UbJjHxX;2H{Wkb?AvDP3zy}4i+n3)JMwm+Ng~lqD|BxMDslP)s0^6wcwImPouxl z+lW$#EB$+XRiihjdcBw75Z-P^efsMCbm+nakMkt;RTS^$z>{V4i?SHG6&oNhK z?=<^==QMkROVag*cY>D-`v@ucZ=&-M%NQMxqBYjUzU@|pRw|`+2xEj@ypfmT%z22_ z9Lx){@;J1E2UV>JnR9iulRTCZFzQi4Z5UWCHPTbNIcN@YQNhkdgG*Rm70L)M364t} zp0LDaY~h~WpmlZ$Uh1X`7Ip2-adq*P)U(l>9-m|7dQonMhW9M$3L8($`^Z?^#^U{m z9}6!-m`4v<6Q9*)yS45kqd2BvA=kgdc+QwkrSuc$IpQY?!;L!9`4az>K7A1m!(h6w)Q!<>)efA^VarWJu$lT z?*AfPZ$}@E(bYLFypb+(2_Ey7jAo;o#;sk1k1Pyvp7mRqlv~fZ zK^gCt{dq1!8xg5EhAVhN!D9mAwJjx{BQ8~pid0G^OH)*=irW$Ig%~NUWKn_eDN!tl-=sjC3S@A^DdxmY z3M8yRdPc%xM%)O9K33Bg4zl_?M_7nhPF>MDQ_1)n+Eb8=gmV%B51ad$4#4LBTs(Pr zCgTw~=d4c?i?aNnowd=)b!k-JbCt%{6Ta}UQ|fTI_vtr{q88d?hl^z1aI}e~I(= zJI{DkgWT0KeyjT}FD*AZejPh?C9$XGT51RHB{qJWdt3ds)7yee_P&OeDE+5*vtB&y zd(+3>rvvm5d)VB?2lD^fSAlROxWqjU;#45CKDcBN9$oWTXc0z*JFw2lerZC(zoRAH zdq@+>vK)0bI*l#D=E5#YX)WEH?WVQHQ`(k^V>DjDXnfxYqb{&pLGbmJHzpuf!+OBU zVyjsXI5Xn9(L6+fE(DY~$NHrr-7lroNh$!nojCOk#+GFbT!YR1L<85iXqCRwG zHuo|-PvChEkICH>;luR@Y<;AzKqxTO*XtkW_Zm;tA4s&=`W~*cC9?Q5oU`%!4)`BE zz&T!tR74+dAjL)1xozAGI^(dvkmE1l-A9DO-m~&PC!XLc|A%rzJCn=58oGM*Om9Q( z8uxE|x$Qq2y4v@y+>o?_hLlaIO|xlhRtzS^;7t-`+^^d}h3fy=D9^TLRbk9FA?<1>OiDdOyi3}@Xv6{7l7Ui~) z1L4P69-_SK5vywk)^QuSbPv*GWKi1yXH&%7ytm=$hzZ!UUuzf7*CUqS|Iab}O#jg~(v+jROdQR8sPEfw4 z@0smicGvXn+WwzISCjPCHuMB>&)j#S-qsM<&-je;wy>??C2-Lmj5iMbs&f|@7zf+J z#rt1Yc-gi`^;+VT)0IVzKSs%-s}1E$w$+D$$#%xippg5m@ObW}3YSoYOIW{;a&=$$ z3*0saCkmY0;KH2dMW6|d)5Hj+7$;-t#&f?iD)zG!z%?<#>)i~4`u*wgGaiHSn0;|v z@eM`ITf5xutzE0pW*R@;JAog?xRuc-th6M2qa|!))gKU|7=v!c;aptdZg)Loa&te~ zIyUM^oiYmQ#zq0+Hr$O?eIB2%EM3eFX1) zoE&&MVoB_FySj)o&*?U=b*){5lz@X;fQgCS&UA_75Iv;Nq6f(#(u5p~OwF_@x15X9 zrVK-#GG7+>$3{G>jg9#|pi6y2`0*x;bFEVyrHQ!D)RnzxOwSohL)x5)HZSLK_L0&K zFKF4u)^Klyj4gafcXCp7W$3J*@A10NLSN^sZ}kZDoro|Ot%NMK zCVC?Oo~K+I!A@&YMb>rMg4Zksnjp>Ut}MZhvJ$6rS~F$Iro*;N)2fF|}n^ zm!Ck#ujyN1tLeLfvU1TYt7Mi_6YKV?tk3#ukvpB2h!v+!`-un(270v-Jdpmfj((+A z1hmPGan1BdU+?24_WPFK_yqH>r>PVGCw0&exm8t*dRUZMW9;W~qF=(-wn!x1W}UmF#;fzE8{Am8WIH zN~1-@3dxyb?~N&IfY^XrnaQ`>_ms~PIOnSk9dc!z6}s!Wrvq3A_=)`|SasDT4mypn z%Nczs@u2s!PGb9Kx>XPU@9FetS$K!u_c3@xh^ahI;J41LuVb}82s&3l#_*I9KG5Vp z-MfhA9I7afhdTHuFJk7v!{Olr#+GOOdje;A7ZIJGv#Z;9(c7!zw&Kxw*MrYoeON8R z>QLIUJfsiNSr`Ev>8=-4F%=}-3xPUNNEN5k+1I@f*7Z(v+5A(4%=1tB@9Wj^zYo3B za9{5sx3Bjo`XRj94ei1Px)bqYKXD;+JD6w+B%3FXpsx%>a6+@(snd|+$uALkmp z7m?f2#c?dR+;Ue)CuM}_&8q`g)zHPUCj&+P66DSiOs!w-eZNv4f5!iVe7f+zhpt^? z-~WTO+P1Iue&wMO-E0*25U_Y-AzE}xEaq>D2DFiC;8y_?U>U`$_ zQO8#AG(p=TD`}k7X&SAwp12>(2j|GAk}Xfkw7oj;s~(zlM{Hlf=ARKD&-6!r)2mtH zYOU>6s~+e*qj^#$E1s0OU{?G;{1MmVpnzJ%;_mWM>zz_O#~)F%R;AwOcs%`nvMCeiV0`e|ms??;nw0 z_iCgk{nf41dS9ip227Bl!X-BHX&h<%;4~9U8C;T1_YT927~1v*Tn}=$nG{)d z_v#~Uj4RXW_&{Tz19FELFyn%kJP&dhJu3ovPBu=C1TG`Q)+J2OA&1&+Ps)5LwPHN* zz?}!~rFnp1r=ijPpjn}yI!3O(w_>f&3^~PYuS`FQ%6Vm2b4%|wqdxyx&BP0Pcg=5x zM9S7-23drWN0gDL5}ABo@8uH9uiFCaVew>NSo`kUfSgVK%NorEI@fTL7}px88Tj2MIMtlp1}hB!69$ zjIg2@VMY1#ul`Bdj97i3z<-p>J`aofLPJ}rD1xHy2Mhd-T*fG@rq8(otDO~)&WMB5 zM2JZXgG6U#g6fa*`q;66vDo3~Vf!dW4c0cX*bpr(&WhjjV5C31$>GO*f&R*iW97X` znLFxo5O!`d#2Pu(1!Ak)md=@v{t_VDiJOb-z}tT;cX&%7>lj5-$umRLMy&hL`h9Y) z#fJ9V(f*vX)KV|^8=WG-Z=ZNV9u({4By7#YmTYevz zm{aZ z&Xn!fyBX*60bX3Mj372$^`1(8e@NR(#G=129(Z9$EfIS%+TPplB=(vpgZ#*x?^D;0OM9i649g5wGD$oiHUm$RcqVKMY#Q7@ zlpnZfi_m?5n?9)Te>(6vecJzdB-1_7c||k%0-O0Wde(0dC2JQXR9%OhSGrC*=G~3m z+6@ZEFS{~gtv4_hMls%ay-34fV5zmhxl5f68xh_z8g?T5;%FMyt|ImF3;!ukE90RR zQ!6)^an%-Bw}oi}>+Aj`&n^3tTxvOM{*zo-*66BeGf8|8Z(!xubUkZm3N%IP78hMa zx|K**cFbivYdVRvmU{}m=d!m=lvGH~QobDdlWflxrS;P9WuZNl{Kf#j%N&)z#hcYK z1);esS-Bq|zA13FlZC^;FQbQM)O4-aX?p~%{nmA$aRhzxv7fW9_mP|PE}hu5p!xh4 zB(^Ppnnq>&98jz&fIh}-L0s#7R4iA`g6w-z&MG|&nI=jsRK)0tRJH(QuCLMmv45TK z#IDoLf6`34a9EyLMjbh^V@St4Cd5!%+1QRC`{kiSo3XldCDfc5<!11|apZ3Qg3501%YkW?ulhdrQ?U`a zusW^^b1z_Cn!er-K2m17B5>x>0h?6(zs_QGCY!(RhaTSOyC0gk-ueM%H8W;gQG))O zWA>(!MZ=(GUwGAe-z=q_@IF{lA)OSaTwt6Z9{d<-KLBQ126;PXYugE|PRWiF;S8G) zr}%Q(PK4Ro?aAq^9J1;IFBRAOl3d1x{50Lt{nZ!FVU%kD+?1|ov(k@!M1gN385c4Y z_=Yq*5mx$lyG9R6-{aq+5iY2d_$DQuiuZU`uVJ6yyNr%TtXHng6C{Q^Z)39?lcn00 zg9wFXQ<-36^F2$$dXdRSEpmJ^?{a`|9{*i{vi}*&FkxR~r8AzQD1D+*IxEfC(i9M+ zBTLSsEK%CvCl;0iDJWJ_7GsNE5+o=3{>kC6#c9P1XiFu(GtA1!DLaq+$3txVGh9tA z0i-2~y9SQQu%*H}LLG*v`Wy!y6{P@TS_UV?)1e0jGDbs(1_gv@A`Hp@_AqvBUNd5z zLODfCVh17nILEEAs9a%*DkDDo;+vtfW?Iw^hyb`fTVL6ZF)K>v5r&OE@wPlI9+huj z*)r67jUSryrLVLeb7h>1%1%fF)!8|~;=koHveRdXvld_WJDM@-EPOEqjz^ZDeTj?m zVR;fpm@$@7Z42c1*Tc%W4-hTN{bb&TfUOyQf*d5q+8u;mlKWHEe}c5`b%rtTC-m+~1td*yV^P5%M(>=R)N(+q;68sP)@P3wZ6 zwC-r}galAM!$Gc2+VkNRQ{uOTqq+1F$)#T-I=oxSlVnSSSx4uqi^)|1X>t-8VkR?@ zF8v>sKbx1?qoxJ^aOlXA?glD3v7%?Q19i-Uh3yqtU0SAa3rp3snWf@v?jQwK6RN`a z<%kNk|0(?86+Xdh^jW5xScx0_Imq)F`f-Btd)cp3ehUI><#$7XOUDOTsmDlK&b+y zH>RW}G;=lrnaiZdlh-sPI!z9Y-vGNd89oKRQ#% zRlq&nc01Z#+7fLhw)Z2n{MUICWxA2fl4Es~HxN@;ALMPGAg$nRMw!l@-@I}1@78=0 z;mV2iazuA`UnjF(!&7EiUMPnXORO{FX2-+P0*603`7d^)xfoV= z*zo&!csky%hO_@N8^42l);k`G79)>tZ|z4;{8+YWk>4Mr|*pp*5hv)3fDL&F>4wJ(F`Dk_Mvc_=!>z+buf&X%V8=~_ZJLl|F zl^?>4Ws+$8>&rE^9o42VadbxMf~Lr)8@E)))+9T>#=ORg%;EPt=I(sZlbfKzls0Nv zcXzI|@$Q#DB8A64y02PmGllQ3X1QV;zk*!Ek&K<`+@!#3N8xKn;lJo4Gw;5O*j~Sz z-fEaV5L@Z7qxJO18~mHmJB$L(#9zZ&TW=6PF$>HS=4>+?wr}g*X4Y}G^6jK4!oIin zZa3?ecp}@Ug##ZsJ=HY@{_4B5=;hm_IX6mqD}0-OzK7nXn_v#=4C{kBU1M;L|6(wE zLjJaF!@6zRx=Y)RZo9>!1*N2qK9u{yM_>VZQzDMCSn;yM0|v;*;!8z0dWT_lB-|4^ z8OjhAb@9F(JFo7{cbD(9OZc)lJo(=8UB!2~yEy9{Xs_)f#NK|@yoa+jpj77ZSngl# ze%@d1ZFJG7_hIcvH+iNlWBRQ*Jj0*m`B3&Be+GRq30Cb($nl}PG5mAv6rYui?RH7K zv;(%brbv7VvCp_qB0Tr=q|3p{HdzBhgnRwz4mV8W}ZrNUoc z-4p@EjU&mmsSWXYca?*(=MT>HoBbEjmYDQ+ZFNX1 z@z{Ik6Dh&etg;kZGvisFeDt`v0rrsV#ICtK!819mirXQFM5dEpPZfG299u(thxO?% z&_}GF#`<}z@0fgIeH?6=;1MMA! zOD1ysCu~RK>v;(E`~vCkUhP`V^09KDeWJ|;Xcr&NJ|{SI7qP0UUiom=oK$i;qv<79 z24!|C4o`LO8W;6tlM{|P-=Tq^n3VPY4+Lrmj_ z-(4GODWwZIhwb7`p8SUW%_sa3|4~>u^wL>##4A|At>Uda?C2|FHOn)Sob(1pd|Wfy zo>M4Kh4OA2EwQeRVVmx|QM$NUA242E{4z@0Wj0Vp6=NKr86h?sW=5S_eSvvYGp&~S zzuXC`kT#ZAwCTg7D!Ak@`q9|32fZLA z14zX}Eag{~lov-(26lJ!A+=;mcvS|eI4aJnj#Y<7in(a2I43$azP#bd);~7T*%M-B zwc&y|YCV~@v^}B?ip{0ce8~~7ZpcB%B5C5kZy>V5t`Bd@`BQu~46%BIJt#MCC z=a?APJMyqMRuIeBIgH8^`#4OdX9j;1_&ats^sQw2P4SPh!!#J>o?w2GjjsOaZv(f=6Uo|UCMoMu z#Qs_IW9(!fb6q(byqnHTVBd7d-SVm5efz+-c{?jn6{~tg_Xxa8toU;0Nx>x*E%lpK z(ovT|%8FWH?JJ?w<^&z?9U%6+HqdHrF1%!k_>)@fokB|{*h%5H0bX8T%lP%fRQUD7 za`BwQvV)ary~&dk!HNe~*n7pp@_nVOoqX+Kxwh2oJ}lRj;>()lu_kuA8eNmHLJO0_ z@*WYc1YMl>u>5V&h*Y~pe2L80rQOVYbd9HYJRF|8UrMErp^Go7S_B>oXD@!CSGTZv7M*n-|5m$1m_S(P*KNmw2CqJ<~fH~D+) z&#_ z^{yy#-cfp3zEfm$H)*VUehY}R{jj_cB^zuL@O2mBYuXD0cbB2=u)M4tzx-i&Is3I8 zmKTH%%k$eec4_S|Maht6K---&`Mt`z#V5|a*Uj@MhkAO6<5<*rt$!P2^u?NM{lR+I z6W9soM65_fRkxOM zn<7L!8U8pN_p0N1QHUEvF3zX%V6%BWX)A?%;RD=l+=8R7JKFY!+?%0^mtqcILW^X` z)=X*BMLuxUwec(u>0N|X?tI9$yJNI_rTWbP?fw#^c4)-d%;bZ7>Z8CnC;z5btDaGb z*{=J`mS^M=%v*kFOMj33wpXjUz4EYJLb^3l7ZI1Wkqma4Kt9FFnTT@MAl;?dgGAMr z`g&b{N#!BA1U)f}z=sPv(=62mtjQN4)o)|3Ak_#`9g=60L-NgHN%@8lQDX!+ODdgR zJZM=`n&%c1L8p9*BDdVK&kvuQk_pnMVH)EA;r-^oVb{RfHLd0lv&)$`TU*WhpK&G5 z=53xB&y{`n)b;+^YXyJDTGE^P%uDPSq7Fal zo@7)fvebOHWGX4Q`?mNP-mLau%dZ;*iOzdDqHh(j^5hkXG!bbh$KLeQa^6S$`K|o^ zW3GRkHO1>gbb+aBqG>`bmAoC}i%QuS-IKH76~%hu&u2dZO{b?spUwZ*aJsHK)D*;6 z52Cgp>~hH(J*-2s9SstVZglW5Z4cGLpDxb(FZ)k;+5A7vv8p3&i`$+ewmRRRKHBJ5 z8a*#hK1gi$Oy169wPBilNyjw%6K!O=Fr7N4N(ZHlu~z5?Hy3+j#9Abq#ODHyu97xU zyjg6(+E8D7Ep{TXI3cP&*q$!CGPSmqNnLP9hHc++N%UI+pcwR_<@_)ht zTgU7%CB!T~A@C#-3lr<}-dZ2C`MeXBr1B8Mf41Y5nA|zr-V)ttKN)T55AP<4Z|#ap9mp}+8nHr2-s&&ZhvZTo2aWmjEn$HSh*-q@|7Oxw(aQ$rVSa^p0it|meB zk9i8P&)<_*73$r{xSH*d^gUGndQWCnN31-wPVMZu8cy%C{XL9)iWTkCuqFQWRt|gi7wMv|)qL|t z^i8F{7#cs{A3M5uVc()xpAVedWrFm`i1low#H+51+lPmy+(b3i0yIW$ZZoumH2wx7kGEqWwq*p&7TKPm3xPed#87*Ai;_4 zxj;s@#1+Ytu+jha8d|P*48kIHn`|Ch+f}iM>yaqSVS=aLxy9Vsh-+f(q4+O*^jSiT!D|wF z-JEy?t1yk8oav-@d>*;AQ!VmJOAp8Pck)bvf0wNtQZrQ2TuHDM1xV56s2w{{ zuMQD=Ft!EQk>V}Ui@W|>%uWT~9knDxjdu3RXjajJ*h=&nmuM5Z8ou&yF*x^m*W%dv zha)am%pA(Ju+t25{yzfMjCUsx%gm~5oLJ$z4dkFq!zS54oLyS+4Ym^-9VxbV%#?G; zV-lUC@aea_i>JkCS!U74v4YSB^~?(+#W!^j8`6|o;t#Y^iIdLL%C1%1#*MVhTB$GM z5-F}f_KYhp$~e!lkF6(Cg?4aX?R9S}FFnoFFIvm3VA9QdA~czPtCoYS+zp8896DV85(qu9??SYqd^z^ORJh`i8@AK z3?S{cAr3Pnv~N+s&QN+@OtiexpY;fR>L%FDJJ?4%G_)Ep40+; z*J?*WBBj^G^sOT7@IFXm{V=s>V1Ahu_4>}s3*`^R{1^PTP#g3&)-lR@F*_ude(;J{hzoXYo2n3&^+Hi%R4-L_w}|bP{z;F}gA*h^NPnD(zQ1Qs z1&iQL^uFoPq?dCKWj4))6)Ee`2lDM<=9RH7n)xDI$zo5+z9PnQ+&rQ|j;dH@Q_fK) zApp?OPjhMyq_N^U~zQu1V)Q%~t7`E?CtI;GbQYEpzSkD8;+4 z^Rjz#C2g8*HQ)WiPUMZFHSz4}wCU@uKXdUhz@as2qGuV; zp748p<=}`{3c5Q__#FuS8vH{X??EFPKBR9_ubQv``df9q@npl;Fv2jYLQmT zlNS_AYeS3+pBXeNTo^p{Lmw2}a$-2Nbv0hBb$Gt4&^U7ePq?C7Hj>~HP4$7u964Lu>*Axd zEL?OgriUL(n6NV*Ov7)7%*1}DO;f#*z*l`+8D{3P<_1`UX?b6#wK5{dIVKBPx*XVJ z)E-SWR&jK-Ea(roTzJC<(!f=jU{45R-pYfmM?gBx!&epfc`s^ddwLX(F}qAB2~`%@ zLY82cj+M*OzlZqoakq_&`|B6t9OL4;zYsTNT%7!cxU6w;e2|EG54SFm{hE3wVY$}Vw@20^pSk|iPC?0)Jz55+ z!RkQyJ6fnXWf_%*llKnP^tG=h)5#%z2D4@b;ISi=J}IlbPs(a|-)dG2C*K+rCA~#w z9Zudhq=VOl!7`kjI|O`ouyk01&453|A>>1PHS)1MFAkPTz{WY8tQ!c6WvFSv0NV*f zJ5fKlrUmtShm%J}-0&6>N_i_r&xrN%RaYu-@C8G-M*fyMe zc~IjKoAYrNrl@&+kdK=~Tr2EkkVk7nI0*-wE3k&8Ro9d2enr~edxMCY7L`X;g|j{u zRkg}ll{RS(YJd@6GX+Tpo`i0WY4WyDMQ;OYv&yD*>&|YneO2Kx{;P#*MqxYE%cB22- z`Q%c9cy$$r)=U_*H^Y+?7A}Kge^Aa1A`NIx_F<0*UcL#QUmA1Hx1G~tyn6g@+#OKw zeb;~5s}Jx#Pr&Uv5UBUP8#wLLZ{}+~o87esHrLm_yZLmjehXjc+2XD{u%*84-7Tl< zoTbh(=lsiOOXukStt?}yvCKHX_pD)#>fB0MSO5)efiQpItT0C#J*%1A290|G!9&mK z8~Csn_BHf>vFY3aO>@);41XFu-6Qa4&6mfeec@c0%qz9i(Ut1E_NuX(B=}zt8)Vsn2_6O;cr~+n zQ{wJ&2GJ`J`PHH1`RiQbO9M2aOEKCper1mVe8=|B+s_b@3{w%jD5jDlivMs)v+Jrc zIFh{MI=x-)WR}zE*lEBWAZ6w-EVN;B1GwAybcCJ1GULm2l~VTQ#1~2Y9AiJc04m;WT%;Bg9+7yvttJ-Uh(Xa|WbV!*6( z-*tPoGhrlb^)3MBOn4Dqe_hOQCW7SDl?rDnxtfhePXSiWLowEe^FbS9wFx(#7~xNz z<+?92}M0B9aYt)U~mb;i{UpWgIT#d zTJr9y=@Z@DbW*5{u2CtcVv-JHl#S1FxfC9MSr`c~$;DEsl!?#}WxeNK^uw!*F4g8g z3Q4ypzy4_bqN_%lzwg;P^S#vi>|S$tR35VNq*cb#XsdpT{*4c_6YM-fddQA6E;W5| zNNQS04&_yGHYTZ=gk};`gI~cpl>9tpV)D$**N?`nFfJdJ%?h^Y?=KBuzcVcjhLRUj z8Kd_d39+x$vw8pg$j$Ymc#X~#%6NyJU)xg3Zc>8R_Io2YkKK}llg7^g(mFC5m_9a~ zi}%TqLcGJnpW^+<@E*K(4Y%U`&Ee zIEweC;U2s<4ll%e-LQ=JmxlZCUJbvxR1#AR-phxl;axr4hxZZ%UO9XX;YGve@V;~S zRlFA{lw_EF^^FDSQ?_TJZMg}w*2AOxaB3pBUzhHMh zeAfui+nm1ermSiM>@Y;k4rHja137`UIE6|{hKBuW$x4kmP@up#vP#8ZMpB^siUcFn z2pWLLP0#_srQlY~+BV+GX6=9^+PI(ORDp}dN?CiyQ1Xe93UKxW%&SAm$3|RNC-4Eu zpnUBfsl56GzA}`r&zamd4#X3zkmcAkzN->V=UV)u~ z`!Pc9SL9siA6w-L?Ai?{J7v41wg}cC_)1}K)T*%zC6A4?kIvzvwV}qe{1{4_M%2v4 zvWKjJj1)L$*sLZ@COWTvI#*Rygc9Ez$ZLgs$4+(yEU(z-X=7>sHO;F7SpEK6nqZ3> zS^z1{#O@orZw0>p)4v>_rOfL;kV~p?7Xaq%zNo$Gc?*Gl_lj%>tR1kfsI961M*RHTGgkK;pEf-3m`uQq$6rpO4=po1M)*a{urHvk|;`Qkn;d*O0jk9nJ6up zbTLawyHC!J(-J<0K82ioL^dK-19C>9nyTUCRhizdmZ|=Q2r21~@k)*_gPw}sh&EHg zlf6Vk!g%)K;qdLm!`jK(SStNE@_ZzftWOy+wz<@`&LFJfX&M-$iJ-x~j0S~w#6_j- zDe^SbUxoVnq6MQgaL5IK-3eG1T4MnXekk7r$UHzkisn>(1R6Xmn*b>Rq$5fSKaL!8 z>7r%#=+T1j$_B(tOVPQ+el_+^rw(6vDdyjEI?CEJr1-Y}Z|(VKJBlRcVfviXj_;4K zb{JbSmHekutcJgjz}nEPRd61H50@6OPXHtK?$LT)$8NPUCdSc??d)Dw%6w>Kpp)&N z!eS?!>2V65M4oqPuwI-fk+Yvg9%!zRnj=p4EIrd9D_U}J z3Ot2*%NDTVPAHqthEt+M`L!ivUipR>iM#99s_9BxxZLK$y%sDz;4D6!4x<8PzScvw zvi+niNr;p@%c&&4q65_<3PIk8sjq&1Vos*T2Aa-^ZC?S>jm(F}8 zq!vHu%tPq?m`3dA6mI!Bb_2}O+~uj{_fif8Ux&}3;H&&Xzi{|oUw2|?fH- zg_hN&ZyaE2Y9`YfUc(90=@{ML;AYONqD&I4rO@!TkYX9ZCuJRU0{x1iE3V#|Zs$x>kiF-f1?iol!q1|YaljVAQ$WoPQQ9+6=9G+G+K?%(tR#_)k zWr2t1A>F9)%#FK+37tbW`E3z5&Z5p0{b@@>8?&}6f zwV`C+uny~op=22QGy@p@LrM4b_6SZWl4IDt(57V~(~Te#*&RGoVk?fJWchWrE*VPR ztK{PVnTdRub&)28KF7L_7+ciK=Gbgrobmwo_N7vGE^5PROF3pd<;1+KZ4sa+g;x$G z-yBNc!}OOnRu9gr^>GieQr=F{+Xs;vy`*Ly-kFl-!Z&dm57sE`mEF=IBz6l0qh&ld z#Li!*uycTui14PYIK?!n|4P{>z=Jo16QxerkJvBDeKvIk^66;GSt3NMN(^n^5vfSx z-$TrIQ_D&y_TrAEbcLy8V~WR_B6@o+{HKyJMdkxPQ%f%VTP|y~=Na}nXnP&%Za^EK zNoC>d;UUbNppB&TDej-RG2?1RHAYP-^uIwH&Zbh{7G$$#9BYg*8sFs6S%a8+CP-%Q zWVGSSXq6hCK#X$m5Qi^J@YINXAXXwV8r_l-gY0)s%B%d|oI0-j7N>-{0(SOZ&OhPm zLcY1cZ%&FL@9m(yqVE^l?@1*mr5yS2>zJELW~Y9p?7p+o^q^o0-dj50lExx8g?q$! z6@01FG=|(|G{$-K1SrF1MAoOt7UrpVAS^+jn=0ibxGWmY3x(rsXV~S@6`B9)Tdu>%>P2YuW4lmA^0(KLyzc4~yt+<=c6-s2BQiAT{ zu;5oy`jTTx%;C44{1hkR!;8RoBZ=l~ofe7dy?-5{*wLhgT;UUKi)Ma0)8Y5DI&eB; z1xhE|SebG&DV!3oP|jff0efHnh0JRFGri2q7 zFhZfBFv~L;nrh?7z0Ktz9(To*2Q%PXhg*db6`U)fW$i@U|29$@YL76V0CxUZ>1&J= z)(@3<@>+RM9^$bN52-@hSbRlGzDETgvs|eF`rT5F78_zK(WZw-I$D`cf#Kgh5{CYF zCXyRpg_y661aHLrd4%a9s($kI{ur?=L+mESk9*ZfDp@%qPG&wMP8Z{6R=>8z-&%)R zjD*@Xy7O8oTQZ}?Z;ammradLV$A|g)FuZ~-b`Nk0fj5EIT^vrqOOs-2VOvTiXN}}x zz86N){4sfi7M8_FQ1@T2v)!HFjAA=8Zc3=L_~@UMJ~xf5Q}Skwyp6nnyUt_;*45W_ z@nPhATgmz38?E^qoNyj#{usNC*jD9K>6PoatM2+(o7kMr+O)eRS7KU^6CTj2A|p=6 z!@E7I!pR|L;zwa>TOAbQsiawB3HkQlMXbY&9%*ZQu*7k z>A|g!knN+gX3Ib-dGPvcJt+Z{EZiAis&LCI*V8rrFzm;fXq-?0_w0xri=(%8n8NOO z-Es$b1ovMhQgo>K_e!2ake|-P6Jh8?*VDNOa*;%RxO6(b18c796B8*F<2qfb(OQtr zZilgXOQeOU6YIF^?Cj_Rv2@OlQIBb(|Mh z#&JTc^q8y_o3g3nn4D3H-L`U^g0Vgwd786&f7pr9YD6o@enQJ=_tQBT#YUVZ;jy}+ zT=yR9FC>s;3&lk@tCYH4KyE z?c(=m;|9aq4mfSzxl*JPrP2+6zsbMVyN{#g+z?-G^9s@rI|aq|IVNivpX9(!iPIPy z7p3#hM$E8W{Oh;Dlex4Ypu_%})7I$Hd-XBhQhn%h#M;a!hIlu_Kh7rxcs*(gaO6AfWK2U{g>K^^zczL_jAwUpUN zAzQD}7ZrOev<79xg8AcZSh|(<7NK^zWrCz)_l?1y)p^zJHpSsZ8)#DHoY%w4n?a}h zXG(WKK2QtOXoDl#=ILHOz5pKKz&D;gd%*Ax!4`x)LXQf*e$1Ab!g^C1F9jbD*Z}Wej-7!4HDK#SysnbXWCrP($j@BG(Oh6Kap@GS zJ-C=%GA+%Eb4n;@sVVL%(R6$?)h;dNfbsTJvST1K?!4-9KkLfq@Nu+<`0Ubi{pv+5 z7M{J=>0Bn?UWni(UCe2v58-SF=vca)?J-ch0q5YD9OGmAG1LDl#ia1v;O1PVMb3zk z=@dn5x0PYHpmSi)#8w=uS!96LJ?+V~@i9+isQqkn3cnu_F)u<7*CnAG>vH(QD0v9j$Dq z6n@9CQfVC^)r0E(@HeEz@ffQ$O)XX{_ko7_I(wH$f9RyPa_>u>oU)_*A!x;RRY}{o zSl{i|z`#kg|4y&%3cWJENH1tL%$i6Ne}9A74B35ld1rGH#wUvLFo;32I6t zlu#B;&;R*uA-+nptc~5nx6Vlw-Vpzji0ACami&%|MFjrS9^?5!VTdOgo@{uR=2dci zK?@(v(7)LOGfzCj@McdI?$An~h&v6>VOBr0;C$z`W3tnmeXLRHopRX-zpF!6G?yd% zQ-`EAZNKhyYRF9PPz`MRn+6-Mu8iO`J85vWUwt%uuH8hXgDWsN#Q_%tmeIVe;^y$C-#x8zDgmg z#aRce7%7FXAohaV1S>oH^raNek{dP+J~8lKC!MRS&i2!?Y%lYu`gW)O=0pdX{r4!} z^scM>Jh7e!q_ZR0sZo4OSbyBwqFuIl>U6I-pB}>gUm=G(T+Ef^unOmMmttR~6f%pY z3w?vpUat8-wujXiJx!9fFMc1_lbTOv@;#~BaPohEILf1DoTIv_*(i~j#qrvc(~8v> z-LTEz?t)alC(kd&r$(n1n_}?p+Dc=_xf$^m+(k@dhPeVlWOr_xcCKdb!jcK^UxY;= zBR-{A51ZCP!fq#|rQtkiQ!_o%Z#qjQwMSLW^5%JsUZIVa=6TaR&T!oaK7q}vkYI29 zhuB{+p3=0CLn*ZA`=dKW?DTPe8;?_sbU^<`mvJciNfQH)sq=j@EK>SK=g7Zw%0Pl|ul_Cnq& z7b)Q{Su4@wACSW5@|;C)w}A(^yCDy7HY!Wo_L7b37ErtKM(x@t{Lhuzt48j}xw*@b z-mL!5l=|U4=+-}bOtuHrusIxsyd;MgNDaXCR4SOi0QR?PKxhTCKiD)I+vqLa9op^; z%53cmSj=tE>rV2h6js1!>+qof9TAzpWbdIy`BQEUwKzk1^QQBN> zf-W?Ts&CU2!RydMEqh!Tr$lHo2AS9OD)b!}T1C!AGMZiBeRqh1w}LxZAKKDf+gj() zL}xFZ?O9}A=f*oB()=K?Ar|pkaGs`v!WTUY+TN_F;8+qXj&E|9qg;p4F+Cbw;&Z5@ zwT^iRW#L4k&o(zcxq7l^uX(+Dvd5M1a^_$`HNmN}P1e0Zd)yroA>&P+cC*Q|*6mH~ zCKKa!tU8RgytpegyO_VY!C0@<4v*Rpoo{w!#k5GRMQUflNi@o>$nMZW2Y*p(OQ#Gj zv7>!2zx2{eteu5;N?UjdyILD2OIWjQSls+*-cKO);m;qmNi=SQ|687f@dq25!9xno zAv&E=#f)92#PDw-+NyajvC^Q>k;h7|HuWIMDfv8dH5SB}{nk+;vifu$*VU};mueT> zI6u(17v5~)#{JA{jyvJ@@NAa}yG5A2MOaF(S0q%M9%nWbcH5+BZz>6=H+cRNr`)0e ze==L^_2dEA7gxMqx66I+R98-t`I4LA|Mekf zXuF(6ZLZ=;GFO5*!^U7s@kMWZ-Blco5yu~(CCJPt$~|S-)S6Nov4o{5RUiBQ%XdAw zB4v@x*wtN@%7aDYIEYFpT$ zyUS2jCcW%qc7S64Qn^qRTX*cj{g87tC7(l6hV-ac=1KTWhe5lNmx!3a?{Pc=WKAA+ zwwWejlo+Ryw#kh|tb-m0jS0F3u^fC2c7av@7klpl-(-3B4`0`P-#Iq4X;ZK*1@0sT zOADB`fG8ko(gsR^QVz<=k+h%*2OAE$)~OAkuHa!n(IMz$qMP$bi*;6I0m`N#ZV89U z$r;71nC^L&(n3N{`G2oFEuwRKw{&--~l@7m9m`#PV`*YEfHf-7no2`|LWz@KAy zSFq8SW8jJ!R6;OMEAifuucuu?9y3wA7vbK=&=YyT`<*6+R`LeckZK*2eyx7d0l|EW_e15N}SHyQe5h$-pKaf za8Pl-(kT?XPZo!#Q9py->WZR>dR^6H zbUoH&LfbwDYTr!M{!Kl~KK|>BY3!!w1KjL#xbrc(xZI?`AUmXUyAqlPmXP4U5{7cG-I`f7!dP0J&j1xW|2aVPX_JEx5^r zj0MD@ygwe_1l(20XDX&aW-fRU$D^D%E?tq)!OqC@kS6oX(tTNagJ+z%8IE7z2COsk zX!IrN`->=c&M?0b?E$M$cO?001k z6?-H1clJi|yTH%XRsJ^Q58#x3;VS4AVr2Nswo$g5Y>)N5{6C4EHpwC3y&K4gp&0wO zA?~qVCfkqEHb3iTHE9LE5#Hr`RHJY*4F6^W8z&oV)9SrA*JQ9gx}!I8p&K;ioo{}z z>^-gcBZS=0ohIIo?}Od4}bC>73*4_$q$O-W~1mfL3(W;(d6 z{4X%(VZW%iCvro#xydojQNsF>VDr{v|Bz+)LMz^hRL6J!qD_zWibC!{`i8Y%@Sxwk z2paro&v2U;Qio_z7-b2((pKLRU%858%_tt=Cy=o=%l`9BUd%UeT|)i_vk@!& zFT3d2zqQE2pYz4J%0R`?=PdL%9hV;5Q+&f2db2!Ol&cO5sHc;)!J2wHCDt$jwb73?@qg_dHGQ;Qo|WMk#a0*m#?>o9`6x5w8i?XZl={7{LH3Lp8Lpfr!?pHG z!07)x`oNygqu#9~w-9yrXfJqW%^w;C$RRxn-4bgmW({zZc1#9eF1ynohDlmDB$9_I z5d#<_Yz+|6fBy^m9;gA;*cU;uam41fJE5Nh#pVw-*4SK^1vhp+U}I!G%xoNF!)`A8 z;T^XZXOX@B>l~j{t@V>&X9={ zB-2A(MqBZ;;=bAL!A^G9$@q{{eex_t*8a=ko7lN0+sE{zlpa@%N(xNGh#y?v8>#JL zBU%(Ep!PDmoMYsEw3uI!wE@x^)qO3+#@L5Z6UKlphdWL4GaT$ZNTc#mQ##7tP~msh z8=xub<+FuAPoyW-6S4O8wx~zdbXeZ#jZ6WjS53#{H&|b0G3~_&-w+#m4H3cDUiy>4 z*g*tbv?J(Du%2)*o8A^tOhcZIclJb{MDL!^lsGfjRe>De)HTX6+@=nyvR-Q$Zrj(w z4S%CWndSb=5YT7N#CZRCi;(qvOMHInpYK@PEk(Vju{OcmIg^njkWSee*m)Y0W+lzM zZ}8h%g!>M}e%U$I#MW?vKg#g} zQ*wn;^;b6$R~v}fq{mtX^*QcA3h`~m_jRbhLG?f-z)lav!V|gld;JejAe(=~#!U}D z^5~CiH*b0D@h6`A$<}S#>vlZ#^iOv_^ZM?`pL^r^J^B~+zWCBFe);mRUU~Jk*WY+^ zUwy;=w;JF6^*c@PzW4rt-}nw5I^2BZx4-+~!;g-BeC(6o|G^(Pe&Xb*KYn`p%-M72 zKl{_?|G+)c=l(opazzrgDXD|fGKan<5|SZqr$faNqA2Rc-*G0r z7c<2nqCwP&sp5Igpm)++#kp{Mh*r@(EEI(dV< zN%oO?(m?i;w@4#-oBW!*Lz>9D&SX?FS(EWkW`Usa(`cmUqTt*{5RA8Zt9fsR7Mq4MHA=% znnaVSjt-5X(G&84I1O}Hp6pyTMxAncw*Z=+^F{}f>(IgQ%s zOj=6I=v+FV-a!}A#q>_PlsahzT~6<&Zn~1Lrj>LJT}SVwKcx552k1i(<6X};@ca3< z_(uM1{@46Fd=vjJ{~rH7e}MlD@8b{hhxlgx2>)CDcl-zZhx|wUQQjov3Hd?+9+Jih zDijIDf=!qzOcP3k=@2(QLzpSd5=wGC(XZ97)34XxtG`eGLw%LLT7SR(NBRf!59%M% z*XRplmY6kG6f2I|VpC(&VkNQZF?(!AY-Vg$tTZ+|Ru-ERn;V-Kn;*M9c1LVMY+(%4 zkED=Th?NwPVqzmx$uv?zrV~4vL1vO!q?F7iWn>PS3&M^0I(ht8w7(*<-9T|$3A9e`R{M(?67x`M8v z_fQXAOV`u;Xf^#21!+6o#&75A_#OOH{L}nT`JMbT{4Rbs|1AF;|1e1elPzb z{}TTT{+ImA{IB>|c&(5uK;E&CDhw0`2{#C7Lb{M43>GqlA;M5$m>>!up@E33EMd4X zLby@L7Dfs=Las1M7%hwuZW5@#3A`W(GC?jV1f`%7)Ix%w5fX(Y!J&8R%k>rdW%}j% zyYzSK!49Zjp!jPJJWxY&M@^i(_)cP5J9lNZIM2D(d5?RYXsN7RzpB!?Z28)_12J9u z%d?P~bFHGa@}9fgcT3umd)6;sdzZ6fIk}0Dg$szd80t=_rBF_&3aI5!(O8T(6Pbf3 zyhH_VoP%UQkR%bBEK;4B4s_5Pyfl3e9ej}DR(u%Y^de_8bHg3njb3i#9xnGFH#*4O zMEE?BFEI1t9Q@5*{+2!b#Do0gAU}l&g`!|J3&jp$s#hr4BiIiLGlN1Yk(G(Exn|jX zhwKioY~dc+;)Aj~gR-SW?iA$}X8Cf5{BEz@y+^+CpnP>uUP%;dM8!I@;$Da1hh9bX z9>tFiDjp0fYKU@!sN7^$KH^aR*sI*k==1*b_ixp}yuvw!vr6WQ_ydi}-~SaC&z@5{ zQxq*FvqW+m-8+Bs{K!)?n)>{^c^NI^+qE(exAhg7a8$Kcu^L4oy`TNc#f!j;w%(F>7MT7*0ynN*B zIxqjx{(rCr=D$L`95)O(kFPc2wbf>hbD6smEu1&TWcruP)rQkAzUQ$I8n}Y_Yc#BM7o0jW?mA{@^gk{u*SXCRSKeh$rO2 zDYS+~Rbw`rV>O(HtEmx`+8P%2HWosDTVa|02Q{knk+u?EEGsFt#*k)=Lo8yfu&^d3V22s$xYCnvuVv$*~%3b`h!*)${;1M^z6nR~B}{11P;x znVOpR0JBq0LoA{&rN}H!GMmK*GLgT`NoLVJsVEyUXlBozJ*jBfyctDWrIxiq4Qrx# z*)gTkkf~H=8kEYL`X~CioaPb?ZTal)783E)BHVlZ=kGr?@Shs^PYwL1 z2EJ7Tn0UqH*NF1L?@`y!u}t6Zhw1gt5oI-0zuo`#`>RX;a~vaE<9yU9vxcFR)d^q>#gV(WWr5ni@+(g+gh_D%%l~ zfs$lvh{H|!yb#gM4{@5B(6S{pq2)_R_)BkTXx_Y&t@G!<<6CXfd^W1c3mlCNA)enD zB4iUNy!y@KN7wpH2a?02v@}HX@Q$51BLvy|ezV2dS_m33X3rPQ2BqiHQTwah-|XhECZfZ(3m+p?qf|bk026_t(lG2hQd~%tS}^_rUOeuGc@MHLc{}%_F*iSUkA2@ z2_ykg8xiX}H?%8#V!__F1b%;;$Z5`M@|B-)ZK;~WZ5obtYQp+Xu1yn!4R_jixJ}dm z1FKE!)O4Ts6^1l)tNE*p7km_{jkKB$RE7j$*rd#}nz4!Jg|<|12Z@~6DTEQG9Wu{| zzEfx~4)MstR?+)Z}Q-@b4_igC#CgZws@~jrto@qYTq9gs^ zw71O9+FS6Y+q4L`EyO1c1w{#HQ&94GOJo5vDJjfm7-og01F4t2!XzKP>`gWS|CSUN zhkFYPJ3JIMPD}?_{25X_ER9S^8|7@XLv*a%Hz&l8V=)(Y5WNX+Pg|w>BYKAXgg&xN zXv+uQ5rJeULTBR*?EBocNN<|Y%;<&aZSZ43D}G5!LwQh~XP7Sq_@H&+n$itnN112p zcBGK%W9E1oj`b|RdXz#$SmcUR`Xm>mst$f*M$awgPQ`m`f6kVMwk?^`asG``yjU#_ zo!3ArUw;3WYdz1QRe93McZ;2@E%;t@2;!8`%Be+%{z7~n;4sBBGdhB+GDFGphWIi= zy7@aonxva(!qNp%aXD7eod zR>*$TVFrNvd+QuzF)@qn<$X!d&E_9ZI(` z*K~|OO%fMCYme6jSXfyAV`O}$bvT6s#x#5b8q z&0244O~=?bS^L#=41bfg?x+@KlC#zvH>IQJ4Q6L(`KDjgbo}-Wn1q^+0dJxw$Z9%T z-$-e}D$J!^CMg4tC!eb9s9LwbwR}#>nbOc9V3QK7H8guJ=A}|2=9e_gfI!V-eQGMw zH^~BUF)JCpl)2xY_@0Sjcb3{9O|=tf~naSFJ$%q?8|T)m0pVoYF$`G;^W(9p7S0dTuRdRm{|-z(@v( zNsXE1m*pKZKh*<|In7sMVKGhdztBdxLd=?4NStfN42qev4G+0i?o^4z(P}39E|VnP z3DBq2$WNHj5A!I85WP8N$Lld;nOhIf#%vL$kWvR8lib8c)($)?BU>entMq=BQ^C)C zDt$^&{cR1=q)g0oo~c-EN(HQq*`Q8lHJ{Q()=u)_`5Ad(rLcy3&8!YQQxRYJAcRJY z71UtxwFa8h+7Y()xv( zMSaCrtEC~T;d~F<*sjDHe%q?_?QQeU1!n>Oe&^$tl(+6}Jv>)?4m*kNiXwtvtXdq~ z^I+AwWNqb0yf%UJ3VY^@xz7&GU@KX_d+5A}C#XhF=J0RH#CE1D-0_IYg722!THQmuc5bI^|M*54)&O}VP8U$(VOVR zt5^#(^d~KvzS5@oSb5cc6MUul^6+~)fRdAV>MY+ku>DJ^(zXqHsM1vQBTW(wSh%DB z3(E)Ws3oOMc`cmzT5pN#%u>JjzIt~1UufkyR@2~^37N&4QP0514J9XALs}iH=)be2X(!$@aIFC1v^cww9s(mcX=4GHrwDS(pNnDFD-XGMKV9%*+f1 zdUB>*nf>NtmTyLzXDVwI)*?0e-`^THxBRzdqC+=Iu5$`kC%3CZ{Odl(P#rds*jsrkj%=!#6EL_WG0Yi$>cnJU(S*ddjZ-` zNJ{dv_(An$|NcDId6VJm8KBb(i{s^a<$KCf9bl#0`#q&`2fk|2gCgzyHZDo@PdOWp z2Wd_$4GkQAed&MQs=0{|4Kjc?!%`Mt{#Y$-#CaL}nsTMD&SDOH+48OM#oq~EityNt zy<*AxZg|+%S;X&#U;dr&l?acNUa=&9H@ty`CkUVZZpyprVEVg;cNM|pcXQqqpwD@i zLT`BY+0MtqpP~IfLq8aT{xG2)D{A;)TN-9o(q`x+m#DbSveV}+WOQ^48zZAC(?)X= z18VT0f{-ad!Z|(4Yx*TuiIL$!fQNx`Ttc@&AYz_^h#T=uwGW&QiF*!(!5S4toro$& zTObJ^NV}t%bg9Y^Z>VHBj^>SZ~6)R<|FDkt%6*?fCIX5SS3y+{nr(TgGvs$NzP`w*7J@fE^{A#=yN zCeu!Gt%}6JHbKr(cs|w%gtTyyf+q$?%kPYpaa^04|I-HKQqI zIuKnviePH>yYXpY8?sAwUPFruAMeAro^9JI?=TgvXpO>dUxUJ5%_|;nFYP2^2 zTRp?WRTost{nWT_jmdVKgGqWH7_74-oY-Z#F)-MUUQnFDevR>dFeJeIeAUY+`EQIp zig+fvPDjC=R-ID4&7ux0*qj8+8s>2b_wH`aaeCLLr;RYr~k3@<0#x-9$jpY^Pd!72V7aT@sh4afbs&oA@vfl6@ zcpBQkug@7P*6gW{*E7o(8y{MXEnPGrlaFdf2_nsRwDVMzV~uJjLHc$k!;<(LII8NR zPiZ$rcZkeYK7A8RMBg0Us*R5~0d2+FD9qw(%)HiTxaww?dab281uRJ_tR06O!-5%Z zb-m8k)spVCJHdgRGYFhUm;9RQjOrIG{Fy_J1m{Ah2EKCYwbgqtwsf`>cU1DNc5?M) zP9Qt30m=~go#Xtdk6^5^vatHq*y;V8n{TDbR(DEMLes|%O;Fb~*Ll>T2xd4j!kj{o zbI)~RMsV`Zn2}%Wnac8QY9u4G{g8s@8e&UnI^;}qWCnG%^KRAPV!ORt!dZXbqz1&klnHEK;5vs zSylj>wjCGqjF^2wwTC_5uer$(IzTx;0bgZ5r(7q+%IpoW!%8`FSqP6n<3`rUYc zraiNYj{T}3Q|j}>Y?`JajvIqU+nugCgVRsl=}sFlu3p|nQb#$LJB`jIXgQd4na+uh z3TGNP$%vMBFLbGkERKb)Eg6d(;8ArCsL!?isU?lglUl1Y&1nHIYS;|)llQ|1b|Rmw z%pc;bZA`JJfj@-oHNH3BcpZL?3#;zTEXnQ$dJ65 zyNF?z(=+uL;$*UBFrUT#>H_u-Zu{AM(A3LXb*~fYxt;|U0mZz)0cVEEAk216IKcV^ z5b3iXHm87VBGWP?V6^5sAPKLpcU^Qj>bVCtxyqYzTp4CaW&l^r$1#O{G5oecg2;Pa z0x%XcEbRf}`nm;ip%1gXu=;0xw?Cc%=mV-z+SBEkOyc04E_F%FKwFRSXFW7JRwVj` zo?V`Wkglse5Ce)lXlMGyx(W5b)`uwMF)}Hb3j#MGPLgvwB6tFB^`I=c zW@VMV$ym)rO{TrouX^@Yw|b~?rRP?(2hc#PjP`8s6?5Z_z(m|-$vjiAhWS`mT_ADV zjga`dKI_s33oteY_|r=jt^5r?l2$Rf#69=ho(U4~(WV|YyQWCv9(ydz$1A~mx5^<8 zW~_+Mc$u&>ltX43_|YIg3~C_M^<$BhiLHNZPGWNgTPO5(FGf0B)5L4_Hnen@T>%8l zJyqGP7Z)sd#efhwuxYvH1&<;4Wz|NkQ)8-gtM_AVex-V-?Mu(-6=d|400|DQj-fAN zh1Ozxb~#*RIJctQ!Bs1O0<^LE1&@4ft^(cJUzzQzB{ABgU}O=9um%s z@?)4pidf{gy(+{(a=*l`RTnivI;9+Q2}7+TVbwdt$L0|>2F60Md8Pbq&(yV0d)hLI zw_R0>JrjXkR2K){`*iFCL6IWjnGzWdC zR{Fc~b&bvUY>s8~1M3q^ell{AA#FFe$m$$xkNX)a&FYlkfm=LjGg<$s}BS^`FU4X6Zwodsqn>_urPEti-Dn zSp#X8;moT_yJ~uRl~}K;XFGDL=Yq5eJhwm_)H3PRKD4}f4eH7Rg*pnahK%akqu-TL zO~bxEK7W^qS2FiyUvo-Rh*REV-?%TsCGmATFnc5h>l3z@mYt50{F zb&&0JJA8I{!O6zZJ-H5&Pq&j@G#@UzGMdP)hRb^@+X91Kx(-snIIL+M-ObSV((LJw z4Gh_`Q&WKfyUVc)u@FoAyJyZWM+zhgvOIX#W+1(U>6>ZSsYE+u8Lvrq)IoYLaCPyu zhB~nB-+|rp&OJ^hIez*#I zkt+56LDP$>j=T6ahxNGia64x>+$KQIhtNselCp|$-}rFVM-2wE+L}U-H}IF8)=g2Y zeUJ~nPzC7$Jd=hb4=z+uL%&JPnrOBv)qwb?T?a!@=h*FZ<`j)3B>y_%o0dgt{IA+{|4rF0A2%9Nw>l%CM&eGwg$c*eSS@JG@B?U8%l7_EbBQ zl(fI=QhW0BL+!Q6b6j@RHJFL==MZL_P{KnN_<-rn?Y!>f65e&eY;`>DI?}!|EA>tz zB-lRe*z7vgZpoXoZ!`U*#Hkj+p0QF@ueH*k0rUfD75#n$`=aaY7hGqb zvFbYi%dYc(o&AFA>@!we=U+P0vOFOE>+Ba?v$v{fu3|b3=v;h|%LUq6<=jfhy(7j> z-0I?up+7xk<3LEiNr22H?`#UmSf9q&%>gqp>4bhClZ~Tbu4d-?evIiiXVh}FM(g9XTu0#?qxBf{n$1S*45-JUjzQ_H zyBm1#rpJsOq=HFl*t98O3%?Qj?b`JE-3`{TndgH>{4zJ*3#m<;y^!6sVFO+><32jb zT=>9mzmH9|yBpN?>1Y!sv1bFq@SDHs!QeV*)b*8)Xj$oIvT|rsgV)MTn5~7C85kzl z$}HL5%>0u6GMnOMhHO-@VwuSjh#GHvWS?MrwAKZg19_#uqwVE(jtEbYj~DiJMIz%h z!#aQ5%|_uby!u-3>W3*EX;%p<%`S@`*w}N)J|GV4ZqPsq4xc-$^YQMTKEe26R6J-1 zeqGBX2tQ+y1(*bxedzbQ8|1-s<6LVzjJ3mSZEjEC)J;q(BP43Cy~7HWg0(;Gx)h-| z`x+n-)q3N@dp8+t-J4mxQb5TYYhS4~c5JAKOE_0sAtM8=Vf5x~es!~?+aQCyKZbX( z=TS=fTZBq25|^pLTBN@nyz5vyc-Qr}L%%(d?8!Czl=?!H8z@@gUP?D!7rsIYFZBWz zFLNVXm|Ve)TgYSE8}RC8wSuPFTv_umM8j`TamKLYxE>36(;IP`pAGH&gZqdZfMFbU}W>&vZC5oWR9oMMem zfO$yV9A@sbVa||3r%$&=m%)@KnbKf-0Hzxx(;%33z{Ex!j~B|xbF9(VVAeV~b2gM2 zY5|l7supSw6q6;dT?Th3Gt>eo4-^<|#9C&TM8rM#5;9qQ2Vc&m!;GpkA9JZ)sn+T4 zRO=R~qfqJSdmPI$YW%N&+6jQo5Om2cw=(^Sd-Q;lz|{`Ni3g6 zRrc8izK!zS8TEvN4Ura5P-t2E@{o47321srplh(kF<*=u_tClmkOVwOt~-gdR{mLs z3MTpt2iyTLmTsfZfEsEF^^=@S{?owH@oJfTO13kA%mOn9zXl-Ao@F_Pc|v2-jHAYi z^0`p#H1~%Xkay5`%=})*3$9$3&brs}s>|p!x>vYBZ(%h$u_upFk=kRxq{ZnAaS$m_ ziT0zgnG3~I*n<@M^M%*OzI=hlzb{`g!@+j5c2RkMz6{gZYMxM~v6WUmS+(6IHl?6E z!vjY>#vs!X=%#Q$2DSdVYN*u)-t3u?6+AaE(dCE1QV@?&G+fc&kt5h(^jO zTd&hlzLJ<1(rtkC6;nX^6lB@Q{#<1a$;?1PD=rQxhM!>j9jQ#s9^S(w4?&uc-P1VO zrLi@)%Ph_9@)3NvM#gt|`N0~sXO`y)&&QqxOk?&Qv|qI(z!vu&l26cPU5lmXJ*>D|thYtzo713XK+T3qrDlH1QLKWHhCSER zsIv~R@f%f}U#;D^Il=0Nw4?;9p<~}119o1!8+6u98#Zlu1#1F)uhUr{*|%wD==EDm9PzlKb|!+5>4!;yF%;|5tEWfWms!7=E%-7k;;g^+Ep+ zdB#5}uE+V4-2)u-<6PZMMFP5GhQrd2r4)<&5lA}+|0$Ldz$aD`p$j*SW1usef1wh)MkvB=s!zu$+Y z6pO6x^Zk#olo^ zb#A}#t+1DU35~0n{Lnx?AO+*0hTp{oyX~C5iWs&v(HL%yb zjUGC(6st|MXQNjWP-4Cmj8+e@de$|2Io#28f$K5KLy+-??wZI%H zFRtR8%?=I}VI=D{3vCnST${itkJHQAyXj?>-_zw;oQj|tTd9ha9yrl+=`DsRiFZPypS2_8dGYRnwhWhGTi$*Qrsn%;?%)8Ab@aEm+4tf#+{-!J zlemTDyUGt5%G;A<&h}x&=&5U)qe2-oSHg_<^|I!urcA46H}H1p{T3IxZem2<@^sF* z&TUS;`-HQ+s?L&hTxi|IZO2W%7P8-8!@Wjnc&l0KAfnb86Sq44+Cq%q_?xr(AN#{@ z8K<2D=LPf!NI|umk-vr3gbJ32)fl_%&K{Jrgm>?T{N+NP%as9>T;|7(ub&rjzJUS` zHfmSf_^fM#`$&5sQMOO52(1U_1PdK)oK>Z^sjBFh zxo+GD(c-`p?vbuh2o2dBO?S1QFG>hL?Rq|)PWg4$l`G8rNBC9x?rQ(R`ccj!RRgOa zg*`x8ACbN8PIa%sd(lbQDEtNW^hQOe?6Tm#YvnlW@(Rf|Ah=(2eI=X6==jSD!``yg zs=}~PNPt1~qFe6>RMC;+0|D3Wh7{~Fm-U!}vsORl%5#l%=Qb@zekjKK`66{Nw}?*M z-*vg2nVQ>G{GC?jI@Z~Ywv<8II%34^DT#kN5J)frs5j*9bRx`f|hX+7(kRP37%!*{b#Sx#!W%~sxiMBeAaL3SCOhpT9gETBeSHgZq7)$SEeYgj(;+)=dAnTEmj>`TI7dS8 zR*X71H`9q!#c?)@{(D3Qm)YM6?n!80O%}Mj;?)0%<8TZG#cezhv&LJAi zH0VqA)f`68Y(yoaNydZW!*m0hsKl5(8tH$^XN&Ddve zigt*5qn+ZWXhho_?Iu9YO2%B1O!F_cfL6y450QMF=*{pm!?-s($G9mvQ@1Hvs%wtU z$8P{KA{UTeXfh)oJ#GnDJ8DDzhQ4X6-m0;u-C2}MW9khfXzpILa+p>`6(7SJWI5cf(U!vAug;>MIHRrj*^( z0cEEfSWe=|FIihW+6}3b*%AN2_JbgZE|p$--|oE;@*026=$F+DHQDMa7rMHQ!k#TBFzlsxR z)3qE6eL0@gJ5s@)V!oBgGZ;xEy%zeFeR?zWFZcOjyy3&Gnxu2A$dw9hgURQ-GL}Wa4uZ14u28y=bxB7yI(;3q(CjSk7f2{&5QB zsew{YImcScr9@7t*e1Ujxy~NG%WVj2xn0g-D-_`*Ue?7If6#8VVkdI>&U;h*^4y{5 zdBUY*WlEeSgI8a5f6%VJVPes%&J@t*3wYCGZ&1wcj`~~C*S`iu%qLe{T@#C19k05F z6}{=a;G*I#*|=qAG#xzLZK+F)4G4|f_NUE5hDU~ZKkU*L}EH#pK()BFvN zjuxYv-pKCu?#4cDm-BAy@ITtxIFk6c@?0-@i?Ut$swFx=Gi=3mSat=n#O|b13 zhMZzO-_dmeem_Ib>|H!?h6rBg*-3b>S7j7}6ehEAub1ufpBT>KA#*-+P;rqn!l_QB z$LlTLULD>PR&$N8*TvIWA+=)%k?hwH)u{oJ{o=TN*ekW~T15hC`cBtMg>XtHx$lEN$9sXFlwq{fI*v7*4Wj4h3^`4`wyC)v#3t^qh`zovg7$k z``6JUQ8Vb@Sc%U8EeWGe&jas5L@h9y$q%DDqJuEPv;oz0qdUdLsF5CqjS}&GHEyxn zSdTVA2ohlBX7?ix;QoN^7#6b(pr5ccejRsOtS8)Vyw zSEk;`7g+gXk&Ey*(sm^J)gwou7w5rgA2H12q&ftwE>xrJpNACs|&IIIA1AC%3z@{BG zEZ^VQ{Grc==plv=7zGHOmjIuC0{RP+cN_Ol^s;Zcz9qR1kX*M$kBv+4Y>j?0&W_(d z4Bs04{W#$A813Gz(Ev<-$@CaZCtx}*nRYjP>^+D+K{2Y5^VojRt7mKd`-qqAyxze# zzUMmkE+Ok0?Ntn$O$ABKgEoAAQ5XJzaFBa=78j}a5H)_A$P;8`ZHAiOD$gO81o%k_ zD@X>p5&q);{^(!F4QP|o!7gvr&Z(`n)MmyhkIncrcN}h5UI*q^p40=FuiYz{FHkvp zC~7w>%L<-rkRkO?y`NtM`i~+ZNp}N_aj`1}Vg8D?NtC|lTx#h%*e#d7i``t@-OXa% zgE*<}08%2kB;4o?)iPPz_1<`2L=HsJ<_f-AOMoHug11%r{tWe&lJ`axpDPd7$k}ee z8%=dGs^hz)HZa5z`{bju8DUHCS5>xIbYz}~T-qRov`ygmjFWuv)60AlY=X3DbNx)Mv+zvM5Ls# z0p6X07F+BRa*|Geevu0^IkE|a8stIFAOv{>7ZeO6D8s2ouG4{@oXvWJFxNoZcJIJz zscKHMm&1y=KA&cvN>adG`kBnK6ijk z6G*7WuJ1G(b!?=y)`GGTVb@A~=7`fohJkD1NtM9<}9`}v${ zf$6oontmWp_A{K1+dBuaJi;vlZnwgX01aZHTq(IaJFm|vOKEa%4)b5ejYf-&mizU= zMRL95H?MOD-k!WkI4{rv)3tuQ`|z}jr`w`K^Ad1BPJ&F{w`h}>u)4m|BM-uruZ!MS z@HbGamm%+-0}r6grbd4~F`jRr1;0%j7^O?d=xCrKb1~6*6Fj`p?x7PnBd|1Xy0v~u z=FxdyHE;#QaIQf;zoW%;fZZz@aQ925fiDYn2y8{P^#(noY8=?f);QvO9BE)~sp4&^ zVTWMwi=%9T=~djVs+=37_SGr}Nq-5lEmcG9vS6BRNQpc+y*AUHqRw!bf*B=gIOAfU z-ID`1AUgJNStEketJFE^{)C)NzdUCcYB5D^z^VIat+r%*PPT8nK^4?X<^d%tm{kTE z)Ix8*6pE=;SB^vKfY|oO)s~cs58ga=}$L zBeVF__5l)gF1dVQ?yiS)1u0=lRDr|oMO=E0a5}9v{*H!P$JtzscjV^kv)Jc)t7O?+ zu(`d6qyc%5i0p=Hqaq=&%&-;o23(hpOlZRVM65&m-rwQQ{IC`2Q7yQmlH`}p4FX^J zZRuHx=b!HC=oY#%T?e!`z(scH+(5>0{#xtl2cGKcz^!K5yblJOFRj*+E=98P`IlQy zuK#fGy@QXn3iL(ofTAOGfT{|=6yO>?VPHhHz?^N3P z%X^#|_itAz{bxbB$@^0a9JCC+3o_4~W7w9C4v}6Kq3l`tbXp04@Z|wLbh< z>_RmieOG%ie_;)OMz~ErW~Yx1zfirr{l~fsYglWueEzGrwLKAM_xIt}_C)4)Gu+yq z$WQUc>i7#R!RQE94+MdWu5^ik|&=(nQ zZ4VF$`C-UxfxV1fzr+^JiP^Vu?ZTkJVwLOsqUB>HhYYPYg&;%#Ztc4p(L1DFR zpUgIP+6}hXaf_IU7W;iq9%}jHo;=_d0gJ7}T#!&F7&Udgk?v6LQ0V?bTv zj-(wA*5jO7kp(myMIHaNu%jn3u6IBy5Hst{Mxjoz1G1A}9RgRrPIyZ3R8M3?FSBQ1 z_@@iE{I$GuC$ zqYpjy5T6Zd7^5sO?LqZ}puI9M+8Bl!lq6yNvYkqXV<^_rLqJWH2MTci%P@Y=N_zr^ z@yoEgDBhRKK)vxMc&J|Q#mtBNyoi2?_k4x~yOyDGK2JXj*NPvKdn63i zp2!28z%T6W$534xEWv#-!%txts_Xg?O;-Wiy)v*$LQqZcP6;}$Lr`t)Lr|TC_FIfP z6MN$*sB;izu0M{RI;i*i(NiZPHN0W=vfIkZeQAwHxMhLy!Ko-i0(fQO`5D&hdJlUN zDav=22^6=Uy#M;hX&sljid zrqZm-Kt}y%$f>{lUm>S%{=XSDwSSzy@T9~OV$GiU<9!=!a(%W$OVq(PJ*$d*P=!kWT z913Z@Wc&#dZ4YR`wT&F!T=TBi3x-y-QjJGzFM zg8im-3qVimbuwCE$*-~B{0Epb?54(y+RBdmmv78C+&+sdOHcD|Zm?c?+W3qm)lN@S zgFcv6RXFrmL(-@rrz<3sD_ZXwepl`r?vBz}aN$hW*fMWZyA{A&zmJzWoJN2{u*~;^3?BPnVhZ8ZI zEfb%{F3WuB`MFasndTgsz+q1t$2?mGd*WmJUO8@Jo6YAG@{^2{>l-R*wm+M_75KJ@ z8#^<-Xb`YZab1lWjq6xlYwU%WZke-d2^UTR_4)vR;idM%g-Z(C`DB`>4A2~Tpe{O% z5Zn@AFUC@XV(AgR3A>!4CZeB>uek~BIwQ;VqHE7o?SWLx$;w8?eRB>cM5Sa_*o!aC zpTp}j91Fo~GyTddhMoA%xN^)Qy~RsdNizEoAmU-|0yZA_F1$Ebcv<;KDlxNs{y6`i zVdlyDG4s&(MjNGYBGw4>Ia4F}T7h>LG7=$9>*z9nHvrymJp-b zqqdE^sxvFa9bMsYW%wb17VNRS;}dN)*)RKQL}jjj-hYFWz+@JtaV098nVxO>@2A0Q zine3?BRJE6XGz!84cdy?P0-bMNA~ub>y1_R`uHu)yWjvZdfHkzU=g-sXAC}lv_0D~ z?`qg$;ZAHPTY-p63)tA07Zql_)i!@ho4>t<5MmrKy)-;O@0r;`!T!sgOCvbPtNzYL ze!Wd)1Q?I|Zbe(H0IzX2XpN@HN(7@S1EZ&nq472|48cCyEoEbOL>49bdvkAt#woy^Sdg!mBa=Xx`B;epOF#ekh zSA{lkFC2JvHLr~KuUO>k7+0bXgBRVTJn(DS>##b;B9~&a>2so4T7CG(QK5vx45T&d z!;6up_0xD|GyJh}P}-4NF4)BIg&5vEFFn4Nn5P2P+XX!1eZYQw)F*b- zc$iEO%#M!E$d#DEmJ1(m^-i?qBh-^uyCUm5kJ=PA9{YejKP(Na)nvqPEH{DvYov{9 zweh%W0ZA8mUf+vnvr%zcNe=e-%T49;l6?Gp^z`EBrN?OgMM}ZVy~3) zpg6&7i9v7gj8sW3bo?hRtSpMp-a##Xh+0(_ybPTYdFZq<9SxSU7tN>=^*c>`CWDMj z`s`?%TJvo24&RO<4zk7=|3O9Z%h72Em8X&O^=QK^GxG6s>;MqDV~7qF=cDI|q0VyE&A|G+wwg){%!89_f8Jns;AT zaBo$rVPWRBu1iBW$07dENYUHo))n;>H};B^SU1-m6R=AJy860D(O zxT1GURPNmpm3dfscBAExK1wt0U6v2<7Gi#52}pZFqq;Ax`=qokN@}?KQs}yG{V_?#bmgih^@Aib~r1Z>S_;zj(WZpm^C!ej<>}d^cxID z`1niLB*Rk}A#h2;D47qQ$Uc`dU8C!>ZRvfc<6Rz5B?*ZA2Hdd-XI&CH^xoJqi{k%K z_9pO6mFfQYd(O$;EnR>%T}YF*q)ma)qOvJznuaz3S>16c6t$ubVbMuJhZJxGm$^Vu zvBeR^ac~)j263nk(<;umjB{@yI=2-0OhRd z(cAST=YBB8PnQSOrNXDMm%#M{p!+jGbtp|s)EazkV9Pe$S!VLR@)yO{N;zs`YpI1& zdRF?C|B&?bn%Fh1itvwFu|rxV)>!03d|9;rtLUBRk4X&39z9-=n`9zTR%M z=6`-a-V#1gj8kxFP}a3xYSCw-|7?sW;>=DhIzM!=B`MSrjepYElkTBgTYoIo{`*mQ zhGM)k$DVWzxj`xWD=v-rCTYZ98vVaUJUjaR5r1uHz0~uMj(&H#fU08$*v6F#^R&CY?PJ$eQb;u zj?x%6V2p_$2~{9I?C+&tjUv`finMMvNqu_Nr9LIS@O2Y0hI}BZ)F7@sH%*C=w2Y0E zW9VMJEVx1H!<^C0(s$-)d`;1M!szo{U}9TF5M2Dl8DJjz339om)ZFNO()Y;7M(KMH zF@dRu@wqTzsNrJT-VqPdfZkz7{Ox<=(;$sc*N8Mef_83pDl=!FBa5#1ip+-`mR6)| z=;^Pu9N8Wvq86fEwBkM=RE1v~>$4LhS^sh@J{-J98jI&g{&6gRc65G9o_}W}F=sr2a5zn_^ut~}{dF1g{8X4dOjj-VDZMR}2G1vflaXPtT zFyFC%Y!xRU!YHjOnr(X=h;H7sP8zk?@I5wF$f7zD)&kMflu4sge(nVD)D*xMdOR8q z7mtnJ-GfhmUBTG2bcvqQ>Xr}2>BqTYN)L)UjVLO$_#&@VDK^L3^{$9>+@5oFy)Oi~Dhj@=|?&7H`wz9iRqFm-e6%G?g|T(IP8#RB;rpch4do38(FwPcd<*^% zQ#q_vB`EUv8rme@jWra1znbB@q;^ydPX}t%HU4?j8Zi?&g=psOx&ETI$*pk;K65y} z60KuveTn$vi=`9|-y@Y`82+EJ)Vaf$v(qDiyjE_ST6(KXRH9sTU(BfdvBOZ6`hiUwY=>J9Ii^cEK z_|eGQu{e!yj((TM?}OeyzN?QS4*kEP@rVr`i_>^d^dITUzoPNA(MvS`=IHln{L(ka zX@w$>IHNd)cSQej=4AW%sfsh>vt~4MV@wuQ1>&@QTJ&CNyi200F}htCjZ^#lC|5Yo z@B}Cg;^{KbncKO*1fusQqT-p-+(A6^*iZCAkk)}Z8mIU2Xq?`2;07#?@x5U*k{fFn zOL=}MPVJ@r|BdmvG0xllZRnrPi8yaJ3cR@==Iur!y`z_SyHQ}P(L8{*4r^`GmrM>7#-9Fq3A+z;G`^3FMt(o42>)_yAK5=d+?ZL~ zOHye^_h5g%U~#CTq^+ZUXEgG{XnZgE=}>ap#9$F9hqRNcpNI~MYOF_9xNfYpdxoxT z<$`RQaQ3LgvE4SbzO}%|l_s=%7*UK37AtlLiF>PrJ;NK)uN{|qEzT`D|7owqxuwy_ zt)u^JB`p~pUrAGjzPpkt(Sw(2x=*4_6aGa_#CwlIzw-U@86UZ9X?)_G_-G{KJEh0p z2=Jon1saiJ=D9Osok zFXPMg=I6o*{NkRE3%&~QuC;{H0htcTS7#m1g6>P_$#P`6Ze5qT?m?hG-ncGj<&En& z3t>y#xMq1yTJ>4q&K23_nXr1xMv&NVx;5^C)?}bmB)fFpStqx&Cb(`|mjF%EpL8w0 zW7w?}XXMo?#1}sl<6JrJStnA<&a=b^MVIi6-Np!tW9AG`4aqLhVYyq~uYu0wEfqnpjLVs}C@=TBdl6ihVh0%?$yYm9qvw$NMB zgBhaY!$+&+e#OjRP5%8ZHtj+{jeGJB4^|BXemlrpuJqklxhHxd^tesd70<<8A$EsO zzV~-t6*>M+gBtUclVwF#6sDw>K80%Nbg|`6rm^1E;M#6{GY> zidpbZzg>t$UW_@~jt?eSIx=OSn75>dw1~NYHzpk+GrBt4j7}EzT2t%U0B<35iqu+2 ziPoGFz4|<-HNR=MF(i|aIGP&McM&20VLhaKi-METTVv_Zdu^x0oq9g(webUX+ds>b z=&b1Lt318(RR7z8qMZDL;YD>uN!qmy(a4_>Ih|zCaeM<#!atDY=g^68rs4o04U&zq zt~LYm>wm9C%@5Y77^`tV)!0rr3smo=x=evfHK3+tm)>o&^ltJW=nwS|)+8INY1P=f zjn@I(tdhj`M1#z5pzfwR-A+jcFXOD6$WGQ&6>wHt^P>^_FjpwR57B%3f@;z|$t~;& zXrACtq_C1EDjMmHR#eY`OmOP3)ur1-y^|(OOVoL*FC4OUt%2On)?7E2GzIV`)9thv z4(@n*d-D$6!-kM7o^pFLe8X+HYHrlQH@c)!=bh$SjPZxA0os9VT~(f6~UMqM1?~&qlNVWgGv!)+wd2zgcSCG^6Crtit#)`iEcqW#h=upUEy0 z_}%zyPIM|E!Tk5;jWix8i^}9oG%B`$VeE~65@i?_Z_(t--xuSdz_=)vL?ijpEa`pg zqM6@$--^Cn(8^pI6N};L9S8sAXh&%*EZ9hDhr2a$SdEa9CWLL^}@(08f#yvT2 z!B^_vC&zbdP7t zkrxZ!9c!{VLY2qbaDqYX^ zNi|woi;SLmsq}WKe9XnTr`d;uUun&>c0fzTSdvNh=`${d$Pk$;uly`|)+E>(l)?%Zjzm?s=JnT_+fW5@tWbd%k>~r=F8wS9{CIntNsNLHyDp6${0@r$ucd!`;E)Hr(Cj>Zqi=RK|Gz zZ@rYi$J>DC-*o@P`4g8jd9(M5|9xz8|r8J#hszJsS!5>RC@TlQGaSv!L z?EPT9^Ulk1c2th%Jt^gV!`sun8o5@v*m-89Hk|6`(y9HwmY%=ly%|rvXqPH@1C@?c z@GE3Ue7uB5r4n{~ovv@X7dRJOYDF5g!OOM=n5n^!($BLc z^5A?boyHA!P_E_f;2h_i%ksoq?q#*e^&|h^yUUz2E0ku;qP0MOf zT1s$=v*@z4RJ)eVL&`Z+J7y_7&DcyJh)fOUAzw!&JMXoY26ax|rCepmb)LEN1MC>J z*z1-D)2R;JnfUUR4G9l>8eE}X*<>i)kQW}M61ch0c%m~x>`TJqbEze zL>YLGq?%no@guaTtlGW!_Ezkz1>d((S);Dst>8XJtc$>SE?D`~-mM1>#J619Q$gXE z!D4IKjdfXT$M;ocjU3Nj%nI=AUcP7+`Kvrm798+DHJ}hcoaosv; z*=HCIdYgCT?j%Z=^qpN(gFvix8}A+GD3nWvB7clcaQ#|Lw(?D6zk;4xp0*HHEf)N$gH?+KK4ZqX zJxet50lZm@!FA+~l#JQ3L?fmVrK=Vk!vfWY&RW8usDtJ_k9sJI2u7m#`W~8)}*8(RDc66m^KjD2b`rpi~up_TG zAPxEY8IVU;8_y}V5zmWV?&I)eMvdgxr>iY;PFWN{+M=3x{d>h(>c!{tHv=1YPp=;+X9llJ*VRs`^BK7RO;_MpaaI>heWRJLg4L5B<0MBOQEz0-; zuejajuU%f7D81#GTKIH_QsMKMF!o07le`&aLRZU-hizQ}g=E$4K6&w-U=u)kE_ye5 z*U<3-SY9cCUPG2wL%_)=%PUR(P~WNW}i!04>^M1Zm@XtC4jhq$OK~v>Gd78L{w2ZMxbNeis*Mz%-bF1pO zygC-y6O*|l9{N16NE^v#L7MMK!&OHkpFuB4>E$l1LAOKhy!>P&jW5wcU^yYKgKNjv z0*gg@#>)eeS-dOPogKaPty5W zw$NCg-Nr#4HWKkf_4V45Cg@&O$77LjjCWaqCfFZRNjQJv@mpLI9DF^_#^;4-hB3>| zisfD0z>yi;K*t8elj~mL0tVr^XL09Qx-;`aH+p9cPRQgRkUG!svK!iB>Gxf3L#~o6 zxcX1^o)S*$x_rg%RE4u$S^m<7mp54ZeD|@^DQ7K?VMJVjA3!=YWddvEx0?>ya=Km! z-z}W=-L>I`zPsHBCadSXnAS4Eq zl(ru&P#~roT2xt5^J?$upKi*_vVvDEP7cS)nm{LnE^hW}L_pzY9O?~hSgXgqVHVAq zw?0&-#8wqi_I~=4+4jZf-}?!!hLzEr@>hCK-@h*!=~qV6r%ZIMw$pp=Kr#IEv=i2`hF$}47d{l8|vVErgKF3eHy-PW^ z4ga^#7gPdcUiWA$M*efa;egHNEXlG4QuM`p2ATWuqv|L3407&0gR(=KCljYMMkrrN=te0)%DNq&lJIzFhf*c^P*N`1DuQX_{1H5(lfuar36+~CHWQ4q`oZtX^K6i z8Pcv^rE*fOrFKJYd86I|todiS`3XOrk?Meay6vQs?lA$rLybspG9 zik!vhAv}z_hP88vi!%Z}oc8!Ha93d&io6knMS?yWDU!G{nqyh!-LPrc?U>-0?5KgS zkl>t{4Eq;RxF5&^35kK`sys*X=~Y9I^flWweqrB8WMfolHf;XS&w!HdABo%*E!un{ zT$Yk>238;%S+7&rA#&dL`W2??kXN-sn0>YU`E4BjE1!4f z`Mo}MVz#Dsd;Yz3_p0ErX573_TxL0|zTR)VpEEBH$dABoBzE|I8G0bgVtjx@k7Qcv z9(YWgWT^-uZEd#3(Z5q+v9oZdB9nArL=9@|?layGj~ifM9KJVrZ~lEqssBiA27*tq zROYOh;ipdzPN)VZMFvtA!`M3yF^=m4O@@&R36Ab z^9Tt!lnNg{Xg^?I#7$+rUOCBf1^j2UUu#@${M+{Y9f$9m6r|^uKP}w8dV7^o^Mm(q zFdFYQK0uzM-QL4LrSC7i;jGjF=aKN0v}$bWb1r*nZd+uMTqupmj-2={WvHTMdeTZ4w_+CVw% zmzL>!eYXCcd}f)>o_SF+d+J`ZM!0WI&^TQdK#u!%+{=n)22-c21FfPOUanL9t%C`* z*H=Oxc)=7*`-RHU?@M(I`9>pmjXWi)^a=<3-cpQP75*4xq?I-!@ICYF>A`)<)K6l- z-LGAJXmxOPLh$gNYk>5lvwv}CaP{HU>GnMP>nhT68n?#Gs=)2FFVy~3w0QArVz-!dc&B?7^$~iL2@xEpLQS)>laVJetM&ThQ`44iinzG)=8{t35?Ng7!7pnZ> zOuN^2bYS&*?jy_gq~M`})wP!Gy$y!?r_>DgRmBdjjQRvNR*0STL#>idM(xx;1jI!zlR{9CkkqYF39&-eSb3(z3R^Zo|`{Wr%)&Z-wOxH=QiE0r7^= ztcM~Chd7jCgs;g^rawPdqm z4|!#rzr@kotp%SRwq?`@12>q;B<=c@;J2w3p>NuZwfME92yK{n zSS&TpaLrhly^=Qz@TL|5S|fDb@Z`;e9d)Tox*srl>fq@Mj0`*{pD4XxbQjeWI1@6n zw?68qb33FMF>K&hOAIdg143_AGBd8qN-B!^6j9~7Pl_puC&lESdD%6C=~`>g0j;%P z%{WkVccnE|JHR%;0=RF~(nuD-eX$vkpXT3~)50oy@{I~plRMz%!#vOV1;@wTtg!Z0 z?uuCC?pX5FL0F2DrO(gW=^aftGwATYdT)H5kli?EqM5P*ytsG6tm>i2arnyuZ!;zs zuB=vK^jk$Q<|{ABF$8?dEtYBqc?Iozv=a_Rt`|#PQ)_g)IP@Bwo8oeE=Y=3-vNad1 zV{-CDgKj74*x2mF8O(NAwCiV}?{BVK0`48M+TA#XWk6mI52ohEB=mi?KFg`C*Mn!! z)=sM4iGTXuQyZvFm1G#HwHD<3VHqjO+of}%mrhzh7P%L0FI4{1S#z~Z z?x5Kr!ycE|t~W4v$a@X5ucf&luM-A-wfxNez#3rW>7bs$g;EeGisJEX%F5bG_vsGs z6=L+8IM`z`RxrhJDYx!{DK3M(d@xO$WJE-SD8FW(nDVoIVzOd!&n{JU&z{Wcezl70 ztyT$9mAJU4J~MNGd8C=7pq?E-!`J|lk! z(39C3c-Y6r)6x6_wZOS*7Ch0ehwUd>Z~z|^^X&5Z#SGisZ@YQ7&CPGXIf}WDXDr-5 zc$1auwQ~#E8O4`A`Nxf(x7y^M3eRJ)P4>) za|<^(H@Y@eL7z(JL zsiDz*)0Vf~H*H;*w{lZf8&O4p=aEK|JEH8Xj;AleeBXqq8`7!&A5Q$%!N|5z6C`nh zVKDN}s0y0tt~Is`e_f+{uokNc61SZz>ke+$c?l^M=W9C4qg;hc>1+~juyllF?DR@2 z6DlCxW}Jo2*;Mxd1FeTp#ngq1&)>Qc7WnzOp@!HQP{%CTLC>?u@wwH~fzK@#oJPub zLO#6}SJv_hd|qw&9G^e3bmDWBB^94HSP0c;zJ;u)ueWG`Dz_Q()1BgSVC^(mSfM;z zpvVv>T6myMJd`dEb1E6GFf&7>lcguztlECLKzC)mRr0mQ2gMpol|wdFzBmZH_*nTv z;%v)9;vDon%~`4cjF}FZQ)l;yf}Ste+B3~w-v#)tNMi^;P*~`%$qgk-zV9S!%d)Gt zzTcV*$>OKJowgKz##TgL^sm6D8dx|Q*otc;Tk-gB@~4?+=EIqMcR+iR_UQ0U(9P%l zqpddZ=g^9Pr_q-3sq$>9XBl{Sfv*7dsRPzP2K;Ugt^YP~$s3=1@i`MP*6QMV*_lP{2Wns_?NZS=cEO>nflVN5xI1-v(s0GJtq(T66yMf zb*$t>`!bsk>G^Xm?3zN5D_4UTWBN(XNv@3gtoqeDO>qX$YPn7oY*uI|PjU)jt9-dA zyX$2eq7vOTh-jZ0+|z#NUiPkZuc6-R)6}{#w{S+&KmT*!TtEiXb7!2F`npxx+l}gi ziOyn*&1T>So>-Pq#`jhz(!|sy8_^d^MOBZY@FP_f>@Fsk{Mwh{zh3(@ctMzanRb*5 zzT_iib^BDGEF7Cz-F{0}Mkpo=`Ti2nJKR7Ia7%qp*aX*GPW4u%3BB6|!Px>-jq$ns zC3q;z<;sVSa<9-#&M@SL(nn=QqmdQEGvJ@KSKP{UKpL{J6bJBY0@bZkYnEQmic4$W zzggDx)_`~EZXdLUj=$Z^l@;4HC7&%5!o2WJpwN};xuW$+ajUnWdOc(%kPig8Yfc9S zy1Q@IUt8G57ccJlZ)G7U)i#wO=w#LK{gKvpNj6YRSVtmcEwYjc@Eu`m`j)-hubfok zSW}e@4@O@7l*sLAtCFAjh~F0-9xf7v4wPN?zugg7qGXsEXg3hPxeo$ko{-Xf|Mf7h z>VSR7TKHsHu!iSAw&ezG`Wa5G$&Tg6CN5g%FxB5#FT8!E9+v*Ki3Z_FZs_MDsV?3C zf2bo_^|_&2Vk*P4IZ5z|$_-r?!_2Lr-;asumfXphxB7XOaWvU z);{h(MSf5u&s4(-L_I4Tv(3HWD#V9VC6Eu*`52_>?45o>Z~h@{Mn9hEp%R1o7JZ?ai3Z(e6Ya8e>y>` z%LLt_;L5aX#X=xt>LnRp&9}U274p}b_%oDO5wx1PGuByra60ZxK%|AF;8c^wKg}fb zmzp3U)SL9O;1oR{EQDQXk=}}T5RWSyDLDBPp0m1Z)(x@9>oLo9+{{RK-%35a8FL+X z<+1#}%tvfX-2+`Fhj_BM)s^=)o^gRJhuE!xESni0u?byouhg{>eg(#60f+w?t(BSS zA~!F+jhp>GVm?qxAQ0pW7Lq>3^-+Xi#tM|KBt47DaQ}Z}rdC?*14Q{O@b`9TF$Q#= z(jK2&AitRIY)sphfmJi`5v8E#vP-xpOVUx&2k_OC&KKdug3O$LT+_MKG&?XEtLbv2 zkMiK5uuD*zOV1n%-v}M53EwLPCGdJOoVPG&KZVQ+pqogDA-PDqQm34CoF~c-0(C`t1E8)*wLcQGwCXX&vqmtx(bw2paZVxnOl_)djY|dOE^gLEv=%Af z`gZC$N+UC=&naB;?>%4D&X3`d#M5w}LRO4%buUPVPdztlvPsrS+>I7iA?}mUhVzAD z^KECImHGfZP`o-&_PrjsDfq1P#>&pp@4Rsl?q3JwVh3{X7bct2ItyKQ&v+lPtWK;w z&~S4DL$56BVfxvAo#$cO75+)(hi!d<>BzMfsWqKveLANA>2JC{^CISo5l>%3)U6zp z*^W`kJoE1CRmGFW`tf5}yQ|qPZJ^QP2sY@G_}gIh{5~4lOLn{HO-|~~_+EHD`igK| z;$!`;u*%Gx!I@yJPssacV{A$5^U{bZ#%g+Ih#iPV)(uNz@=a)g44yJiIi42v-lxTa zL-}pwmzW+{SNOsXGhu&-^$Dv{14=O>&puMvhC~c8fd?A zL*GO-hBqLu5yBP@5}U&^QKhw%%X(FuD$L7W?r(kf_-eDThd*@aR(-1#-lY8Kq3b^C zUS&Ld-G6m6mVP`Pew?|XKSa|m^W)47#fDQ{^86-ou7&Nr8NRn?eOyz5E0a9RW{`(x zqCxE<9&bAE+HuYkx%u=~m*^JFIoiJ)YXsG{<4Ld@MI3cID2X=ms-mO8BG}qSmXUiW)g;wV>A2H{)yi0O;O${T7^l5O@6+Sm@)k zs`bIlSLlpwxY=!luc8r1^qCGqs!qZFC?}iQ(Dor_JZ3{gWv1vFURlsOt(5ow9mqT9 zyG050E(vLBqepD7wR4bW)MaL7YbNip$i)V!!E#+Tqh(9^J;pxFiS}LUiPmp6HhtIl=*B%p&K=z0yf7_TFDj$@! z2vp7{0VPjB$;M5TXUf?9FQoe!RHJl18~61Nq~9!{G~;HPKWX!M;5ITbVZDm>KbX8n z7Oz;yJNAPsCGYyhA%_5cLM5FD^B!m#oUnv&^1XK~KHqW26?WAX`l+UNeIak6=*M~O z3vi}&ZGe5^j7#}mTu#rLAc-e$1!y1puc=nGUsJ<+9ZVRQUdioYkMCadUO86!)2vsK z_)3-eBkt*U!%TC9sP)2IGnz8AYw&|A;nTLNBkd;~EZ7P3+a$F*nz-bSNU{@Q1yEkT3F&aF+kjHVV z!fpXkFTK@X2dy!?Y~aNepFOa)prT*St*+!t4i9W`a|07Mq_`3S6@90G1h5_P6yEOl zrb$-Ji$@~AZ|6$r*#kfDOz}G@6=eQIuju?qat$y3uSWFvrrknFB_JM4Yx=|SU#Hu0 z99KE_?yd$#SL(wxO5?}r(!OGk%~*JNcMI+sA3mU*{P8qs9|Ou8KG8k=k#f$*+LIsO zRU+93JntKf&ZoLdhqAPr489=JoMdVA+X> z8;uW-|2A$%jFQnTSIZjIhDc)GP4TC3`%mL`=`M8XhZ|3J>mE*#bkUMbg#@+^R}qp)V!9Wd=_+b$yD1WAu3yLX+15P zj2vQqpQ7&|J_Yg^cpW~DQi|(75l!VX>_trf1tJv3>u^JQm5fx6#Z-kd*d5Jqa92Z4 z8e7ZA8|F*j`G6bz5WM*vgp9K%mM%Tubupb z|8Q-*HLMQyq=kpYg5`(BqUC5S{`KV)K|U6_H5UKAY3%zt>HEZ@SY!!wkg>>bW9F>P zt(5XmjHEfTQMR|M;xlaE3O40PT3@`w=C$XRK|RT@TB7d z3qpFOKG@Qb9@?6cY5$IS1w z)6-dF?Tvd(-4ttbrHisX>M+M=g*deiK4X`1f-dc0g)ciM!Ooc|&pJO^K33*a4PGbV zgmcBp03j4WvUJ~~suS&bj{gn{#qz+Ss@Fi#*zK(7zkQ5#_g|4Y%_HZ>{;L z!ECRtQI+pwww@=_W(=m+Qj6~6ZT)JVG$<48iUI5GuMe>G3Sc&jZ2E=my>?(Y+-D71 zFK~*hgA}D#(ZxMxy|qW7 z?T~!bsz(unK}%06M}Oqtu24-)^B;2zd=+1dM1M*4NBq$=(4OgWe zW&a?7$6Jm`;4gd2i}H8<#kZUU%fVc{W$yRh^8c^=ozCW7(0$2%4f_+>fJ;6Jart}V zLR^#WkR+prES_ZZ<8pc6o6QDyZO93&gN>XPoZ_ydME8@1GJ)|b|8>@|#GIVanV+S~cVqZI095 zFz!O6a+oV%g?ekTbx98=IQ$mq7^9K%!`B3PXnM8wq`=!gef4KPhG_5=LZ?*=4aZER zg7555X;7G+7SOpq_r=S~9cD((ptWX6W$FE^b1aS;oN^jtlY+A8nE@?o-YLH8Q}$N# z@f@=6)UK3jpM$br8RW2wLDngK5=O(9;0sJ-|AaN0h!~VP^@*-Wk7n0@p(`^dol(oU zURJBMb1%js4?})1egcU`ZW~RM&O)U7tcC1|{U%=vzahjr_c;OIhC#EXFg?J&ic*iI{}fu-~(e@BF{V{H#lQN+}xI za@dt`#)h^Tw&jiN9{fG{y}!rUes+-kiuu@U>~;44*jMaZHo!($GWR+6ckUQBfwORn zxO(n>?f~~YjyKK>@&y!|du_F~?-v^~jBNiQLo_mFgyhw1KiBl5YU_myspg;-ahO=* zV_&PZH-R6WxO#~p=QHVEGVWPdAk|Fnd^fN;iXQvAnk}h*(U*Ydtl+V)Gua|s!P*lV zJ!br`pjHq2WXJ~=AkPQfA%lpr>B*fzZ9YBGunIhRVfCNE-QpzKbTzKltxgGY(1ASm zbt0RM>(5s!gZ#x7U4c6{Z?G8j#%nKY({!nw6h-%4)W8Q*p*u~JYT}wq(z9Pt&2%5N zb4^B+Vwh1v_oR22jO!OxE9iOQV_%zCHm*O~u=srS#%EABT4wwU>0{Bt33&1WH_y;C zcAY9+d!(!6YOaZ%zGv7;xupJ3z6V0!`rt{5~uz0ZwE`2m;IO@2VvNxv`EryE{^^cz=G4IY#gjie4Q ztfng}-D60-_?8aj+_E&oXhO*`*ho+-X=L*@P-#FLFStf3X^Fvv7SX%>JxXJ1m~rXO z7g6Ydk*{1T%W5bv-imxe;dESINHrOjjP=5QMdQ6tJa+#O+VzJhwW?6MbA>cw28_kx z^Pg=vgc@g~9KI-5YJuKhC!eP$s0}Z{yNTZ3YB)Gn_OsCpDV5c*&=^m1Kq@&|N~bp* zF{TGKn7Nv2n!7Y-s9kCxlry6o_Y%kM!4h#(G_oa{jMF&LqR{a|m(Ej2D8%{#SF^3a zDFg~2>rZf}yVE@Rt~7AgI(O)#22^SCwR+bRgV(rkdDv@MRY~!n=h~l`vZ^wBVUE-2 zN!=Aon^?_Xr7E9omwV3ocKeL(RBvvZ(p~7DfOAoLXud2p@K*o39OusP*0ntW?bjnV z)#ydD> ziVGeIC#pC-%eOf$L{x)npc`RtxImCkOH{U0>a9Udm`7aU;YbCd%D!}2Z2{3CPLXK( zoZw60B;kOAl~xAMe8Z}AkmnUU{)}Hj(*@WRutKh2Y>$)+Ei(f7&VAx_`lY^<8D{_W zDC12?3zhzynv^ni{YSn(^>W-^TVAIU^`jm9g~&ni9LkbeldP0dfQMFgJ?gfgE~CL} zwl3=tSjuJZ`SW2_kXo-ppZruL1fwL!R}$hp$-&58a3SUa^)2mdV|}qe0h?!dSwZu@ zF;)h=tR$QrQ*m_{T~#Jk^7;&1tsT1(^pkLP>)4e{ufx^#F7UR09{QKLgsKiLI4ALV8m0jIXsfXL2GCqy8%1-=Xy9I;(L%t$v}X)Eigi z!#eM}J&T8S_ob92`X@To;S}{pB0IDaPYH|a?Ou)MgR0~+49K)X`mQRc#m(Q+)SZV8I~#KVTJq%*_S*d_1D;`7vPL+y3OzH32uC@H@NY% zZv}8pEWqOOhdBnhiGFEtx%paura8IuePDf;xVSmQ#|+?HYz+$GBx#l z#Bp74g*oBO2g-%*8O{vnb#t}Iall4898RAY)H=(hGK5}Rda^SOaXuM%Gm?zMX7y9D zUL}t+POm-rIo2V)Grg+?yp%CrP?h1lb0y9@-|Qv1256A8IRDn1xJBB5J6kYhhk!TS!W~F;-okMvVBm4^ z05I`>Ay{263+}2%w2d3#JyIQ)t<&0L!?BnZd+sdsBhfmt6C<1Ml{hnyZJW}Rd`5%+ z1XHp<*(5uo#eWhsa$}Jnp|Kg)lPU3A8@?xn>uN;wXoX4mbb|%9n@k8^A$?ncs=$y> z!arXCeoFP@g=~tf_q~jJoXXyJg}-E;#tfRzr>xnC@fdgf6aZpKqO)l~_YhdS4&pSuFBqtlqmP$jw>jeJq$(QWW^5 zXSGKTyS0W^dd~7mZ?SIli0!BT!=4=^_j9wUp1^JH`+^s1L5iD3AGF{+gP16TtkT@*X*gZ^ZV2G+&2 z&MJFs0&M1WX2h-I4(WpN)HkV7)}bXheawk9R;kaS2DZbOer$=I;e9N)mvhbx`3EPM z-OPBG+vrJv&5O~^U8SEc3(I8N&d>gh3bq|5!s?W5=coUMC`}EdQV*id$GgoE?zq`~ zuA8;@V9i~CzKYhK>Uc8Znd{t1;4Am6VfopinWM0~GOBB^uC-jRmjkk?ewSNsULV@V z-gEZ_xH5Ig{{+atgw}Ap47p3_?SOT_TiR5h7+nC?B|WESY490h`ND<2+j1RT--@;J zUb{>WZJbh}@pIGUfu_M*Z1>Gzk%+^ExcV`&6iund_6ZqU;G)QlJRxF z1ZOaPs{pO#a#7Eq%7sdvl(G-EJWBy+W@1)=F6! z(5Cv<&atfsNwV1&V1GZH9k*{eGKcBUjbRbaB$-ev-i`QbqoCr}#r2F2L6;UfUg=>T zIrMR9ZxY%sXG#rFoYz0CywO)@>F8_qvfx_d-a(G-9c21jd|sWGUt6vY(iPq1=6ZGS z8N9H9=A6V5afD8*c_ zpt!@|Y}2(LgN~kGxVC`4xy0o;3jYl`zp=^v*VrdQch3jG&*D9-zT139Z0d85X8!#8 zj6rT;Rrbv6=lT87f%A}n6x`~2(00waM>3lRx!OmrH|hFyEj;{c`n5r-dtl&^>oxW? z7?h9>4-<%J(4p`Uo=VZNh z7CMQ(>hs|`@tgo;;?PO0BLoY95Nu_@f$Bpi4;Hj^;}>*Rp~cHx4+7_#X1&UR7}T;@ zPT|zTgk{T#&Z60K7C{i~B9QNRxYx(A;yo0vXu4atuP~^rTr6VcW%|989 zUQiCOJMbNOVZeL)uLit#NK(r?TB~Hx#kkJ4Rn>fIx`BiB@ijvwSvwr)ALO4kR1A-n z?G7ub(TAg4OM7-PP&{PP^*f_%`lhzjBLAubVq zSmDH|FkzZ~b0s{Y&fi~oxOaz2)mx$3V^>8JKrbp~iBYb?Y`+oMA(}U+w-JlwS2!W` z?eWQiIS!(lKkLRW=NsoaY2T+kuiS;+U7-9<&kl_27v+154NAPBIxJVS=?d7g?;e!a z;HQE|9{eq2%d)fAN^>fkzXq1a>TqmM9;`f=s>)G`)Vt2Fs4D1s5%x#Gko1>lr4Opn z7rsF@;H~xgsNY!ao4y@3qOxX(-0`>0B)WIo|A;R$AV$4T$mS_U;jw)dDUNqp!3_+nz z&d?#qfm?f$NuN7=zH}ez{gSRtALGq1e`-DR%n#B#-3)ngl1de2vs43b)gz*&JkjxDgTm3+>H^<^ z+T1`BpG^p%LXbY+ue92zoVhU>zrMlTpad1H>|uIqzlM09zJW4pU(cqu5f!`HwhI`E z%(tuk#>%0{i{j)V@8A&+xPqfBG#}2E)}FKMpXYiMxft}fLy;M0# zi*g;3a&3VA_`%_nq22ulK^N*AoP&WUKLWjR#(;Nvi%$teOz(7wh7|B!@3gXD*1|b7 zmrB*2I&E^`Bz_2=HVyw4eA*BjFj(S9^R1}-EG5CdRwwj6Ur95w4m#~RM_d~{q|i89 zVDUJS+2Lu|;?oXzSMh$#1#yQj6SljAr7NvVbiA&E_=(J8dK2GSk(cgL1ZzzCGt0sA zrh?~nNqn;E+JQO7i7L!@l{FSgenSP{S8pw5 zI3jS7{Ug~v(wTwI3poz0v-xHo)-C%oROT;zk-*AA6R1^tjJrbCtJklc`VQ<-Rjy{w zbGl`|xRvHIA6N3n_Ji=&L>X8&Bo{~nA5Ciqv^iFnH(A17I(mihPhJs^Yl*9F7v+xEF7ntX#5oOug9lfyDp?U= zQ(^RO{AELK+vg1oND|7%2WlR0sy&L{iiv#h&$u+Ph;2Ql4JlF*K~cHHyZdd7$Gusw z(wff_Ovqih$W5s_0BFfg)dUuKu5RNCZyQS&Y^Zi)A2%We&I}bik9L3J{h}eEjWha# zE<_z43j8sMyo@)=0>K7tYqf`&LIEmq{a6{y;B>zcRF}Z^W-4J&{i@sBBZnvN;qDV* zS&AmG#I@9!jTTp?^Atx4{+G8S5o@nZV|J zRKm_gR2S;4Smdvx@sUl0ze^JQSst`42tH_=iGNqH&hw-w^HS~u>6M7}{ztR&jKy_J z1EQ#(pZOc)wQ;Q;ga4=LOpZ~X-rYN9zno(JP`Xpp&8D7czsL5p?PKXW@8b0<()GmdW?MWZ zD?thaXZYf)_*zNxHQQnrzIc^0&afjEI;--sZnAM3KeHc!E$o~InjLAd>V3qWDM`g( z5BH5&*$7L{3`y5wb>v~6T0fe$NY?9^sC1B3TZ(^zSY$D^b^#w(rmujHr7Uku{!tPb1c+z$$uJ z{vV4~XP))!=9c#C<8#^<_v|K)doT<9r26b7u2S7aBcSNwf`1iX+hf?07P6*rLBp1h z)bp_dsGS8)F2Bqk*Z{v|eYeNZS`9fQ;x0xT9TNr<5(guNBMkNh>VCvnM6_#TaVDfR zgAx5mqg}scQjN7=&TOEzr+iy{Tvtb>Hn^#+*0UcHH+qAGcmvjVeC9j-YMD^Vb-HG; zU`)@o>{?+I)Ap#Yg!X@%Je(olcK){C2xD@__acjL^O0ZhOo*Pf$@ zFh3IAS ztPd$wt?=AL4ARbx&P_FGpby*m$5ygnuEXuL*)w+QCi5i;oj=ANuvKpxQjJ-e^MU6F zylc~gcRCfY(Ng5Mf*UW;>3zhrJiN=fYbT%Tt1IqoUu#J75&!$V&)`eLXvoj{@cAC` zHEW5Zyx$HB9lz4d1=iZ0_uW7{jaKV;Uo8M#R0d!6=Y4+_>z^$VCs^-zlQX&%)~I)BY&rg;qElP)%gTmCAopY6|KIW!RgRjqE#5cU;*j2E$n0w6Pg!hPm9%N~-Q-4aG z=l`qtX^{3Yc-{r|<+MWr7eIfiH(6L-$rUdSmEqjg*IyRMu|MxK`qJ^Xmb0*Ni=S)O z(wlHss;9vsRkiJWm;OK$aS%&|42IY4^M^W?zt-{SZTa>%{0q_!R4QQ)ZoyI=z> zbGVtZ(okT1Te9mgq#CpW`QlFk2Ysi31989I4?WX=cE{J{xSWypc#@To%|7kb!FS^} z{Ddt@JO$AdOKp5FC;o!uX+oa%xc+QveE(-TffV#vwLVR${RHuStVzxctQuAO`p_W% zr8=YCoB1|k8o`rcb#-M&8bts)tLFX0M-#t3&Ld=E-U<%aEJO)Eb93Hgpkm6L>GpJ- zj$@H`!T&Zrpv;>yYiGcxAE{b8BaqlVrb$!7<`B{0zP|y3iWn{X;i44=2P9 zZl8Rgtc4Yxm3bE`nuNz`9m@k;v##v{oU;BPG;er5tX4dM_zs&I5<)`4@}30qY=4HR zo_7wpONWHMkCdgK!1{|{+E&jd4+omGyobwI2A&vH9n!%H z5^~ZIr@{Qi=WWmhrAl;bHa%yfk(S~2+RB4OX;|pxM(zshR9SeE%!f8D&!JeuTvMK( zZy^uj^qxe4Z<^$XhN0|7jT>Klpw8+tjsKjF>r;g8y zaGH+~3kf$>vHk^(&*2yKydiK?)r2mKcm+-?Dsa)1YcKZLXFZ>JvYcFRBZsgMc*^(w zfqzcq_cVDkoMlpKYe?NlcU_Jq?{Y8oUV5Mo{ExBWmeymQQ~edNgje{fMN0q6ZIiLP zObpW1w)5Bi2ECGy5-vzI z`|k4-cy4z&MZrDSF*%J|t@ax|b6X*Qvlv_B)_Z$IC5_6UI;xCNiX?x3gRh~5tL)i_ zb6XNld-_&}J?-^DWiOk8+-;ZV-hkZ4JeXIdG$Ne2q-HYWJ{JZmM1!09ciZ`gUOgw~ zkpB_na`VmeFKm0&P%{ah8A9q_aiMmvZQJ?#Ue(n=hthkB+qHq4+uIEe&oV!4Yh_Cs zO0nGj6YF~cOXB%kN#K(KttCM{+;#uHpxfD5k4eW!9Lo&6}@$y&n zz2z%v$^7%bd-d#BG#8FQ??O5lnjb_1mB%ac1Vg<;7g`A~gq7sACRxc}bv(hr<$*g0 zui&|oHD_?vE+E;OGjCE!Ijg=lT_rYi%PxqOtR5vkU zC9oMfU{eG*=rc_~SNS@|SxSOaAW>Gey9}lNLh09H!xVpk^lOE|;3s)APJV`5f4=nV zMnk55vh-`EA>E%R{n}|r_UGW2GO%BNEI%71zZug3IY5i3c)%PByk?jLS-AG(BwT5s zL7O<{B?Jxl2&|1Dl}vHHJ2M9<$mi*Q;cdy<8z5Ug`3I(IhD>@UerxN24>UtioxcO} zXV^R!PZLyEB5uz68cvl78uKmgUk!X<@_|wvPnFum8M6E-(l4_i!=FsQ0+8J2C!&Sx zVu`MDOD0bC2~rB!pZV4J#RpayFdlT`Z>M^wzLz2M{u|mt^(fJf|C%bOt~#DZzRQCQ z=eO*0u}EZ4<~Y$>58GVCs2xtE8ET{%Y6C4JTuBbx57%OB{U!Q?pSKnqMX93@m|Qd` zwqRY*yx@Tof&W_Chl!UTz7u=^<_1|Z@UGuOli*%J_65OK^7GPpWUfllz+|p=>B%MA z1A4AKu65NJbQ@EE(^l7(QnL&7Cf9HUiLlWEsvu@TLJgvl2NP-%cd2SVgtp+UFWs$n zV!vf7sYLC`TJRxM-#yj5DhKc0_%g4exTx+A;%y+Ag)VgM&=ixZGv6Vr)`fZoNfyQf zp{KoFdvZE-fE%7fyk}hh7Jg{O2Y8iS>SMwRd$nDL-y9-;{%^Z`K^yw?liNAfw=rJj zhA$qXX2G5T8X$1gO(KT~Wch6dobTLLU8t~)B*XOkd?X#^2H;ntiuX7?g3;q)(!z7a zus69W#+= zRa`dnd2GHZ<&4Uuc48+lO>ECVGz=yDg>z~t_PN3dWNpk~;rI_4poy7$q6<0wLES4=^JhW?o9m^mO zq0MZntnZc0UwBf^TBq`X$>!9+BE+GW-z)EX<=(GB!{AT5#jBnf(6xd~@naVa=9%Yr za^+vRuMAEaFCkp5P(V*t-oSM=9h(%4mozC*N+tb78D1!VTvT+_HzbCH#3en6uo-~I zg@0B9R*pZd^=0V#sMHLUTD~D6nCuWERj~anhRp@p>5CEj=x&jD$!-y6W$9CkaiVi` zydO1)RDNPj7Cfbufu|Z)HqbcP!PPB7%-TuiO}21=`j7PW%dEti$k z*<^3Iu~rW+(s5my_V_+A-^yC=Ze=qeH!9d^(*y{&JS!x^Dgbg3>`(EYp&lAb-L|4_ zJhgHx^=Gk;luPLtQ+#J#@a4OeC><+;VmwMT2fX~^^B*tE3TWCpH(RfE`wEuv4`V;3<1i-+KKLv9CByo$EAv=g>$D( zC7*VLKj!&@z0vdMKZcG*#t5ZPe%@WAg)Z;Pgewze_KfyFhC_-!hEo(5e6n7wnyM7k z%K_u6PO0=$ERGV4=dsv=kXK;AC}bkv()kJ)0My>oChhS|AOTM7bZI}P70hVFsTTgc zJ3pgcouE#XyE59}3WvD2!YN#)oh0o4A7^g@-&C2ljh`)Rw{(N{e?HUlkNi#Q-UgW^JiIG{pMP*KPE5(b>g@=ivbDbqSm zLMi7YX_N1IP6|5nz03do|N2YMcAsZ|o^wCRd@9$xXCVQe|R=cWeO_!;niI=Ktfs}gPx5NeM#$@k|{xeKMAR~T> zHAPa#L(9OJWzTh*N$lDH`vbz4Cj*N~eJcGr^~ho?=TQq(@tJ^`rhQZ~5ASf!z`zo% zI!aH9x<2cnD-&RMPLE4&BKorR;0WWA0^L;kKe5C5%<}Dd%5YA;*VBEYNA_ojyqRBT($PC+*5(y7vDba~AH@!xLEoFX$(|PjrCeeu)BR$ggp2pR7^vnl<*RX=0#}Q1 z#p2l{?i-iVcVDs2!xum5G5XCcl}}R1^ty|+U!Iy$HLJ}A#Cy|~R`;|i z=UwA%X}~Ms47z+`$*DEY_8kRIgT^}=*QNH7Db)6d$(!Rx7;EsvyiV<<+sD}XDe?Kx zo~2OR)y7Goi_|3f-O!ZqmXi^0Tbe zcGj5bTclK7P#K7YW4ev&dxA4q6Mf&Olq{!|Je-m$pI8$sfMW97i0mz&zq^NWllF76 ztXh%4s$Uym)UW-MQCH@$>aqC#ybHeRu1Z$@Id~VTg2gwL6Lk2hhD39S3YZwGun6{j z=Ui!SSjig6w-mA}$YZ18MA>I*5AYAy3+R<)3Bp}D3!rz!s8+MkRuZWtRbugI_hc&- z7e+#QFevhf3`+Y(N^~jV`muwTsY`upj*Kc+eTj8=50T($z!m1S=zV#fyy8^v+vq3S ztDB(ly^YqTz3~$`oKfr2-0BIc3AdN&E?*R8A{ta~ah%%<8%)xAbmdDK@{V6kPiho? z*E3UqZ@7)TpVO4q#JOp3kuiM`X`2@CDRK7HqY3Co@M+glmqJ^o9~37_tWed}aGhUC zwaw;fy#ZxIY(LpXo_tS$0gd*Kia(d{sg6?ZQMAjWz$qX|Scq{5Ss$@GUB<`Z&40QX zSRB$oY$abI(t>{jPcI!EDa6}|x5JHS9ArwlE%byLA+GK-?T_CMz;gC7Gt-+<%NoswVVUu{-tXoq1F{ zYx^3jTHkOTo}ENu+A3yJ?HtA-b1iNOi&CY@Pw$yXa9<9C-$)l=>lsMrW&o=viP024 z>sDhVycAGy&$=g#H;w0odhDy!Y*Z|Zyk}|XO;7KI4E*p$*{+~EeO3{{M}xm%4DF+a zU4VF;m(-(5l+QQxHYyZeqmW?3I$a$V?{$;)TumYtg!(D>4gN>-{mPo zsIk7^CMe1@fodk+-IPPVNatLTWvqfP;1GFx6!uzO!*9Hfx0Q&~5_|tQ(OBx_o_6@& z^D;%ee1&??K^Ew%}rLcE}Yu5`O4>tcl}?!tROtf8lD z2mem(gbe_t7ho&Ez!Pkz8G8?#92u`Ux?BgDNjlLVzyO0ts5Y;{{LkPmHLxA=C&0%) zqlvfXqaT#u-~OJHYapYyA^Lb1%!Mwf@a4N(sW~4V_8A}?Uamm}io+N~juT|-73hi=?dCMu#k+75GW5^(GvJWD8J^?xD2N)MIe*DF-!p;lB zJ7?4G88J@p2=)UvZLkS1^2b6YT2Q&Sk2M&1yVZt zsU|AEVR)p+=3Gw0UHM#r5-7~sx6mt$p5F!4O(Tp-Sk~N&`1DjW@nobY z-f(>ss8aLrWFoxz7tyAi*qJxFZ}{x@(Wbm9`eGqAl6!{e3IA|u%2WYH#RcNI&xn;U zcq}51CVV1k%e)3IUs*cN!Iv`;!2rq4nx* zuR?}+9M<398r74#h~;+;yaMsP3(joOv1NW)aHux12r@q)Tj8&*?u zyV&cenu+Fv^>BOQjw@irrZQ$&SJ~q_GMYZ^1EL;qW(dNpvQ5!WjZyBYsim%UIO~PP zgIYtT|CiEUY1*lALVUm!2mjLWJy<16WL(ZGQq|U|$cMEZ%1$E1-ey_ujq51zn^;YI zuu7KWP-^^G)}+GyVLh>pc2yU2l5(xijJN)l@C&J4dKxdR$mKeL z3miP8D!OnLYuHqIj2JJF)mnvdFfWqpOXyrE%om>S;yTB{V)CottE#jMeV{dgb`jca zzOW*X(B2+V`(imq#WzEYPqTyaEfkb{KJDYUnp)PY>8MlIf!9!WYW5Osg0g){&m%{; z4*JL|s-z2W*tn2`6c;Ep7pjnZJW?DHX~oDUXUUN&d; z3kR@@Ld4E^NGuC7kXvQWs`KxYef`hC-+qdrum#?~px{hd7^@vF?qXq!USLf+8|RyR zys#z7#+vj3iT`|8IKhXMcuxl98WNQxHJNe-(u<0FqvUFl0d)jN@Vj?N-7bJ1AUpwS zvFA`e$I%=C^OH4|q`7(UEXEqb`KP!Nkowwavr>ItVJ`x2@gqc)i`DA)$I1LBX{8Db zw2`ng!*_z%tAj6oK3B-c`-E4!HwwKP2fL6ig`L};(J~IBodXv`xZ`Q>-b~}(sWNt6 z4JT|qoS}@xm&SZ>s?Xo8pf8k9<9w;t&ERA6r)5o}#wJ~SP@y=Vjyv&g1+U~OpPJ{h zVtpAE*9F&ECJWPmK9k}9Qw001`C3T0Es+}XWBlD48V&7EAC02CRjofqsFD^c;Op+1h#&4e8ap`C*Mo)Kh>iS0@| z+evCy=ikc8JF*)1%bXzXL-;PT&YtAScWe+C4b*l9sgV&A6`zp5|2NxAC%4%nAqJW= zPUhx{1uJ&xvG%f^AZdYiFC@O1H`Y9SoSv2zh)E4ZlNayNSH`g}WBKEw>|n zcqel5IKk<`IIJPQO^Jx`m?mT$r`oG+M#14r2{b})M77@r&f&+{k#ZNADn076i^ONk5E^9ihbpngHA7ev*mVC~-F66~h?PPA+1i~3_4kr4@RU>8> zY&9efoL;v?Vf8uZB6nVw*gXX{a_8JaG9nbiU+VqGic3>2GY4OSH?k7_Bo48i)D9*P z$11hJ+2<5cCLzuzm4AHidBdvlZqaUiUpw! zc5oYgPpH)c$LFg98njnflqB_}Dl*m-u^zM_X3SODlalniLBK3$vBHIYJ{vFsUkvDJ z<{%kG=LeZRRRUcxPWTDt2jP`xMA**d_Qm7Lj6LT%<(pev3VOTx0lT`d?$+o&B^~QJ z7GRS|>U8(VuxKLoWNGfRhEFiABk*4%Wm#aSc93+)$lvcHqb^pu*~klCF;a(b;S^PI zM)zDBQZ4y=3<0%nH>Yt)LjdE&r!>L(>KlL<2A`?rmyJsW(yI%^7V{Xor ztds4fTsIe3i`=H$%6&&lN8{=z?9|~Jelax8zI__OJL4+3;eC2oybF2G@hs;WE|fOZ zVr-GMj7Q#oja0SNUgsa9cCaSWl1k$=-+QI1?m`r2v&h--%TZ}E0wZAaQI z&5ds`+A~(Oi1_Q15%GcHd3hh^5gCvFfw@T5(oLA3WDO+q^Z|}lKf9b&-v|AXcr+dJ zGYR?wGFDS;WQ|FXaxhlOIu;QhLoD~7xYGRUBn33M@XI$)ZHIHSFmm&Oi-h$*r1VkS zO}OUdUYj%&!xATBnXCbX$4$NNd?X!fXFO)a+_eil#_Nt{%oxGH6<&r5_wNf7$IXYm zIkhV){xk%9b?VQOc^hzcs>%!%sCQ-LOWYIu&iH1s>sd=zQM-t30&JXR>hCE>$tdiE zno!bJ>dFV727Y+BckO&!$8xA0erJlDwlYHPDt?^2L7qe2^e<1vA!^ryx1P=hSIekt z@ICyq^wK^%I8O>Ys$BVv{06#84~~eG_wo?R8b_WMudM?AumI_5|E;8-4v{AhK24rI z7_MsRU8@2|ax=~TAZZ1{$&mEk8j{m`oV-E4xZnKC)0gF^58iruAt;ZAUy;5h{Z86{ z^Wi+=ZRA@W#}vS3(>qR{b+KCR3X*q-g!~&xv4=ziVE15u0IPFW z(i(RoPIy(zDC{+kg@fV(@MEYU;(bB36*RT%2hSW4?;X^HM{Y17l|pNqYk~aqAv}$x zdR&Sek@xVYr|M)(aI448a$LL$Yk9+a)=dLpJTR~t9Bj0m;Q@$^gzj{>h^MVTHNdw*PBmcd~8}e@Tp;>U80wGLmwbw3jKnGXzn5Q^HOftF_j5q)aW}**kp4ijq)31dOHj*W)6%Jsl#R zkh%_uizR9oi&P7-{t+B=va%5A#uuyGSHDdI$4Ti5vL>NFK^a3S&UPggo$gbr6p*sy zS<}9x#=hkS8Z*B?pi~!T5o_9p>!-jKbOjXw14U#IF?qu)!IuM!<`Mr=wgGbGI^oyA zog0M}!)TaiBy%q!Qjt1gfA06!(ol0w9WabL1O-OhPonpiA9UY8S`px>dil=M=1Yb3P2*uF!dwyRx%s z=ufKz7Ml2o_$a;*ufeLNNceHilI#d#i}4fRcD+6D#3QNzt)e}ph&d4Bq)h1jCl4po z5&8UKVAV4R34Tj!kl9UF&hLssGQf5a9R+JJXVa5Yk@g!y-}WeAwLrPYmD2duh&6G~ zLtg1nLZaM(F-vWqDr^CrIpWBi3Q3R+cj&4JFz1b`g>G%=V zv494?=4i^`6o5L>_Fzu@^PR#Ksd8%)G<7tj2?wH_@xeSiYo9Ny&WVUML+}P#b)fH? zRm*Fb(H-F%kk;MkPqns(gFzA@JkuZ5^tsfs=C7l+ka)wDe&JqZt+jsAr%=2aU^uE& zb>%Oag`~bH=PQHsw1FPEHoqdJSu_hhsVU#W85QMQ+{)3SOEFg2_mQ>|DeBaa-Kc@k zpvB1FO1D=FjlymNC*<+4zaAv_Fh?|vSo658d9YC5jlE7y6xOTo+-%`l`?k|OnZ)v?Z z)mIEF6C&|Vby$1__RKBGUG(Hk=O`b2`$$Le7G?3IFO^fWoFjd_eMMeYYliT&CA(gI zF={e>@x|!P7w_i=76n{^m*4o#?_k#bi622LKTBz8n=-bS)y92I9Nw+X0J``r?Q*RAR5{HOb*=nMt%26v0rNZX*&(drA!O2Y~ zmVS#og#xE1Z5ltsl(XJWa0QvLWvoM-0v31ap_ZK3+2CN*5HHI&Rfem1X9GDjnSK8Z zQ>AAEqg1Mkb;8*IPqUCCMG%Kd?IYKD!`Baj>N{v(OJF;X{fV9}>op(>2UrSEx ze9ItJdd-wgPDN%VcQMz}#GUPIT39LJ6Y?}KJUj#dx^X@d` zBYrKLVV$D?zPx0o)*6{MCJJo>S-nUL22l=rVpROi5LdqLI`?LrJU*rY8|BIHT*fsE$hsYkAtnwp; zXaO~P6lQTMR>SA6Hc?4c8IZvdJiO6z8^jMb&TfmG?h{^qCLT4zlcLDfHqgU zWHj-7C87kRU^n!3bZYBPsh-+H^=52qJtb3rPn&D)Ykg~&7TQxt1zvEIHX%F-!O0-9 zcY+IgC-6uq)5Z*)M3L@>pzk|x(34~^z>>04O;~O5$u`lMc zkoR zyapf^_=dzegYat6%T^r*ok7tyg*V$GVjd(JkO@T}Di$oB6sS|YEZc?rW{}f32OldOzu7 zH8;d#;l()&_^7R`>M#bmp)@50{) zH(dL@^aKWao(EMs;8nB{yw**djK8DZQf#c6VDXZ^KL-0heWCg&?J*XzUaoFPJQF5X zUBokT4&+7!F0$7Y8`6Z0!ra#Q-Kz0Vs?sE8PeboljQTuK^3*C%RvjWCAO@auSZ}Wh zvmz5#%>XV>-v{ho3-6)wXVzw294T@8h_00NJOWQC*~VZr{H5R*pt`{I#ZfCVVeQgB z1Uxt(K~Ged`@MAKS3M0tTE0B|mHl47quJYrJQKQVYpE->f;IDeDX~SeT!t-@f~mlc zQrjlcTepQnp)BipBOBIg$rrGp_iha}ChW4;mYvIh#-8od#*?S2-!FqbEq^hsZj*&S zM=Xm{7o~Y}B<^sWKPfJ*kIjz9xiWA*Zey+X+)n8{oH~*ysxLKllXTuh`|#96Poyg^ z_t29pR@pZMGJ7&-h`rR(Lb6)yowfIlbdREYabcGCd9<@GJi>Q>A?tA$rg$l%(g!RM zqq>;srpFgM)V>mj(pMrQZ%{ssu>?pQ6%GnEzTloQ>z;#kE5X7w^Uv4_uQ&uPqEWbw zPtmtxG%u2F<5Tq;Fn>%Kdq0wPqNTW zOMkIx_e;l>)NT9-eJfI=Rt<@dMQ`Kt^p6c+J&dc-`c=bM58$d??-;&n!qr6m!}8TZ z>^g1(ueRJ~y-qzkB+iXm`F#D4A!i#BXX3n6|A1}HFwOnLG-jEmS*DpH(=4{N4Aa~< zOj9n?ERtyoWts)@xdG>u`nzqjhw1McrXL~G&y#6%GJT_bu9fNM*s6S_l(Xe~luUbv zEo(T9nZs#ZkC3w4WSZ}AUaGIN<;d^NknepH5p0A4HC>fF{H|sA-7n;K%`%-Qay#fs z^`s3xjbzJ|q;)d%Q*1-x`!Z#fO!=;y%S8G7Xk-H3s+8Y)GlDOZZ>N#$MTk~$cP-=D zgkFvJ5$h}QV{m*cT-NgdYsrc)G8=J7uZSamM2KN?{>^ay^> z;`a)Er}4W3GNpU*TY=wK1+c${o%M<`R^4u9)i2_A48L>uU75hDd+}334rRnT;(=Us zBkW)|!*06+zt{154s!ht{9eU_~(*$&ybYEdfE~3q4 z_$;ks;VG~{w^7c017bqKjvEnD)u2{`+Uz$|DtiVjCu>@7FJZq_8)KCCo?_iS^y;gx zl6n%~aOtQhDx%7KpiLB{)=jrSr@_J!5$$p+>r6nU1m6+;2}Mu4;rfT`JFh6FN9h8U zP?34br2#ciE{3Tyti;-A324=&gi^vDZYA;}`BDB+R06nI4nE{&D#N4{)r=IM*_PnGf9KgmDqJ)eKG3{tU!gSzMhu-~9U>t)YHLze3s9P>8?z>iT1dGzss))U2OJ;5B~8 z`ShB0Np}kRB);Q1NBP3Ff(!Wkw->WSC zLoTri-U*+nof3Um<6oz-_iBnhtB5`ji4#w@ek9YW{p-~Az3M`8=k38Jya3pzjM8+SnW|4r+bLc{H*n=aV)Sn7@x|-_L#fRkD))3LBqsRmv=p=0zE>`e5+xvanT z%*k6^>x4(XYCO?Tb+mp8PvDX37r@63X@jl?^m@VDbH^I0obqee|5@7iK7E_=^?3MC zC;cJm!=2bIJ&7NpgqWge;h-~8!gwRbsjK>ZFR!WXqNm6A)uxvqmL}!z!?S=#dysoY z@#=thN0{5A-mU7~2u=`Dk=fII6g#)Bre<#45#Z#oz->|NX~(k<};&T6QHtC zy3e}~tf{vZA#QU5>^50rEHY=z6SYml6muRLGF94uXm7ry21tEKdQ?SQGS~4`FeGsfV^pVhPT7o<60bMbaF@`e7(9#Amt)l zJt>{cJ3L{rBJvTUtrUOB z8b6*+q*q2c!i{2rV&KHQ)CvDs{i-J2!xU=~Gh%ZE{2Aa?(;Zd&qKJ-;Xsy7h3$5cW zMa7SBg*No@2FPFOOdznR;W3qsz3CZvC(_-Np7Wh7Q+lWIO*QZ%7Y4)&5yy!WkjBz_ z-k^d!l<6K2M@5hdG(TFQ0u=9oB4&HY3Wz`myL*L)nYss-D%)W#&zNqAo8KXJ5n>IO zmqenc2;9ZTV4ZnG{CQ|8JOWItZfbTir0-V{ITFY$+YvopkJ!{&!wCPkk-b-SG->}l zShG|5_0S#-Af9vn@s)fLQn)9?`FPh#NU(_R)O?F#W#kz3n5hUJLilRe+z^F#GRC%a z)5dqrRkkeiwd1MRpBTH;dr5Wg1-dlL>nx|ekMN9dL;0Ovhn#MCh#EWJqj#{v|k5XF}i$m_Xo-BF{D=oub?)qJXWIZc0irRh)eV>%hOYe<|AEL_OB^eQ$p_qzJr> z5{*NN_P}c~T3O;FHBTmWZrzSqfq0AI^jbwK)^@oCYb*)1WtUwQZ;u?Re{oCAfuR&m~+pr-~gdti;XW?kj2`LjU! z-^?GY^uL)uvA)n9O%_r-oq268rkL)gP4Pah0s4{aOgL>ka3S&-Xvz0vrIrLPGbUm~ zdqYe2gLF4-}v`cWk4JQ`n!`Db~0$&Hgt>L$6cI_Ng?~=-ooHz0q1>ZI@I^Njw(O^eI_-B0F%rku9IU%I{Uf z(3GA)uHgk%mh~tXNaM~B&G8IUrmb>}TEe#xyDr^P=u4wKd`sJ-JshjEyHgue%p1rVScFUsBR|sH+}Vu#uQ!{;eQ|uo7iaewf>r~7Bc$9 z{Vem2GThb?UCs>W5uRn4mk@y>~>Rfy+ed5_eK#NNZcZN{!bCs2uAbFbtn zKG&8jJO%4gzG+Zwj=<+KAO6%1SV)FB=jg8A!V{h~Vz1+?5NbmlB!S!o#27Txz=wo| zkF1HQhcy&kIVfHk)Rcbh-P9Fl$NT(}u6F{4B#jqntLQa0q!Jl^t@(9G!LJ~WGFp6d z9b^p}l!^FVOW;pcLhekAN$I1&?MzP>@d{H4%4@GVK5kVGNQ)n=8R6d)qOfvtH+Gvx z`2QBF60VE2gS2q?IM=rsqwVqx=ulQFNVrmTU;C>qhb#!s=_wYDIkNHRy4QL(~W)>2){a>j9TNGCP!?A@^tv~Bt%e~b_trhlryV5XvXhfcR^JmXnh^{;8O7ND~mG}ty1-U=daq~XyEvg&k zE3!Wij~enn*K2~ks|F}}6TPGDqa69Tr}UPz(iJ5RqdjX2G?Y%*PQrG$0Df#)byRr< zI8)M}gJRvWY*2F^@;}i_#w=~jw50;WIm4di$Utf-NC7Aa4hbj-&s!A8tEe@mYdLw6 z$YF@j3c-aUzV$!JWn??DtH2(3l4sQO3K+E$Hf47~7em^B_~1`P9O_CFt6l>7YRK_c zV=R|L=P`DOQIi;L3XIX8MHA~Wp4jPKX~eQFnI4du=xeX7Q20j1uJJ{hIqn{e?-9Z4 z;<6~2ucW=}hv$B-O?@=izSWZ5s`KX50hK~vBsx1AsLZF?IBRChDT&tI-IBd#PE+bi z^@$O-t&nb|4@WzN2KUCdh^};6`ZjM4{`>P%*RU(Kz9dk^d$n~WjSMTL*I*O}}ckPpVOD(~2t zOaUuLD|Fr&U&;AOXVUWZy2@hsH79zD>ls6wz(RjzXn9|v`6Vs)G#Q@CTL0pj&XtZ6 zM$l-y=<60k(>*OqnzEkSv&OLgz)GW!AYQOuGV|gLS-u>ZE^hP(n5+9T^}cgctT_k|!-v3Vf``V`hB<&zP95YWI6&ze(zN(^rXLe2_X4{S~P{sXM9n z%{t%q5d1pPx1Z?|L&Ba}pS=YLsl8NSu=q+P}$3~4Rn}3;LU31>DIx>l++ZUVFJv-s3Ax zv53HuxFJjxPVpGG&=p3fB%@hR@JgZ+cMC4%+7j>`fqh3zy8ZwsDic#a{ zN}T;^OAY=9y(z6(jx^XPo6~@Pou2f0(wQBQMm>QasU^{0UVS&gmIy8(QI6*xJC{z3 zHcmyJ!|jf__2UjkZc|cE(&mIGcos3Xt(Z?g#BC5EmlWy-#kla&(%ME$0)_i;Yug%3yVeYO2StS68)(SgW`7~YP(UW zf_CwpmO=3n?CXuf5_0w9LGe6rg{%0iEjmc{sqKT}?-6NY$*t=Y&7gQ1x*WYQehamI z2|ozmGQF^sFSOx)=z_G&G=7U-$bx_I2gDY;aZr3MYOpi>5ulVz(;tAehzBC=Ip&x< z2l}Kzcw#8{9KF#n2pf<%$U=!eUO8bHgnEs50fn)=cU~UlXN&(30*?i;jXlFz8H6a!RZMj^|zQ z0>j#NDHMyUH5+9i{q8uLE@%wAy@>b-S8@Y8?@R+$aW&W6N_<(zdG1A|dJQm2Uw0Ka zjBt+pu%9W&t-0SZ%10IU%ie*07w2uvO9gh>C2tzOfUQztmJYHi#U&!KA}F{a_(7`c znp=4}g;V{Qc{NR#kx_9wN`sXEKT?+Xh>ROtL&NT8EqD;Bkn*2(Qhp!HLy~$LXQLF# z>Hl!4${Kp-sg&LK!X84^w^6mo{^vzNF?21opCvqx;T`h=tc}{5EXO_e$wE8qhw8u~ zluCEiGh?>_Jx=Z31}r&iKf?iOgj?!jA!GTV{}e+RnsPMWjlEw#`cfZ$I)cV?(9P$| zvAaXub*lIqSB9I*U+Mx@0xZkF$vD%;axb}fmoD&&B<;o2z}lpS8yg+Jcf(G#;H;Yy z&K+0yRvy;?&%Ei?mi@#>2xH$PW7-~GId=NDS1ykvA8LHiOE!_cF!wz(0%GzpQ_h`oyilC;$5 z>?6le9_3|}XjKNzFzTUuUz@LYeS&Z${>4wZp6jAvMLCKOifus?`I6T}#Gk**CTmJfP;?%r3(|xx_g*bHn^$+J+4WYR&yKH^c#@{dy1N^o$l>^%o`1^t|OY_km&hX}9PnZ8%ix zyjBT%I*!n5C=JF}337bJ))u66R8jqvF@B!07LW9*{65AENo*#pZdIPMeF~&~-ra7E z3uxnLA4y@^5mJu2cMsKGy^`arEiU=Dcg|pLYKsrLwT2J+;^cRtQ%U(F>u;7nxc)%x zHy0&X8+t=GXZ#sJ8!d#_$^Op>*eQ*w1w4ezclcUNAm8 zp!l>780KJxN1YqS{#ly2-VCit6)Zb|S2l(&Ju6X;w96+fX;)~T*PCr&F+Swzy4_~3 zAL-C;i7Qrj&(2Xhr`O$9541Ll_Ss95F5AkIu1o@YVzOgm{r5Bz>n04-G=Sy~(3HzG zWj~-PuPYsKW>-!;2 z*bgzn2xixIl%O3Y_^F)wPk&H?N9!IPF2P%+$(N6S<}Lp4jHa%KWXk0-r9v*p^126Q z%8yGkFMm`v@=D80Zou;x4-H9Xw56*_roT_7*U0pX>+Y558DB!>YnEQ`z4iCmlAGW| zhH**x4><2EW;_e(X=5DrQRrb)yRh3w%cEe2JPICNKi5mfKur+wc*qzqC0-s`mUyMs zCe)|?px^Cv*5MkIpqArMgXwZvrv0FnHFZ;mX(~#!m*?hb`V!Qpq#oKfN32ehJ@*yw^n!wE?|B#V zX^&83Yu0aDHRn<9%59G1m2*~5V?O=sf!gQ|rzZjh0 zsB+%)Q6RkOIDBgee_Bjo{Nw!K6yRWk2aBYzYEnlMtA)gDnTdLlm@U%Ll9^Gl4PFwI zsmyRs4QC_~M5e&TWdpdtZ%{w8A)_Tj&mivKq(K8DZB+484>e|#gGZbh$f1U@uqNaN zfo(ShzJ9dhkFLqN9Tp})Gtip&nRvydU19KuLF&|>v*Uqk2@KwNa@+;K_xJDoYflCC z`jCK?kVrHH*ZEc?ntZxqAtKQLrSV!U5{-0%l%4p|kb2(4$0Fa=U4<%mBgelMlO8=I zY`V!J&ye&9`Qd=Jq_hjp3+>yES?;ZZjoj(?u`Vi2?xHSDXBAtM!FwTo_N;g3}$a~`ioPq~yNrS<-!y9#q*T~B#wdOv{9J5s!3J5Y(>`y-jd{iiGV!j{h01$Zmd6Jan9t#nu|vsvubC z3`&GtC*ye$dgxrpxTdCG!D5Gy6z5rh$RAhS8Me~{9jneQEHgZe95H&sz+Q*sayyW$ zNjW*wkuKd2%9$jWllbE_uUYkj+G^z5jtO(VMme1`;qRb7HDQlSDB9&{`Lmt4iBW0b8uwWcZ z-Zp9BLqu{a!Fa1j-_qDw|0!5-B=#on-7q!@JHX{#naY{&OEtj2sz|Y=)DgT)c~zbf z66;RhoPlaPNuAX55&tNLM;qPR6Pfeh$UYeDD1mn&5@!X*pBXY66+VHA@sCpx9hx{dwW*w@9SBC6`+l7 zD@3H~LX>!K5U2&0EtWsIl6*HQ$aAKhP?!vBK=VxSV;AMSOE8o%o(+g7Kgm}~N~r_t zrkByf;x4}&`-JG!g|$b4ltJmgab-FRd=<*L3nPygK^__p^c*&jg}5t~MVa0ASVs7G zaQH?$g?9_F!hSrM2#N#12g)pBy4e8FD0~M3i{+~WxcZapuG+OOjVH^lkvIqOVZiFn zGuS!zhDaTitk#=cUnpo>ArIUlivK6bbufq>rSQeuxDH+G6oCy>&bn(U82=~m{f30b zuIR{tekrr*rad(ImJ%PuZ+{j09+2+>(P5Ak0c)od_D>G1wN1ocqyzm>5ONx|?dn|` zc$pI{rW))i3BFTu3{#_l8ngLuhftHVRZ!APY*qL|QM;bOdv`^f>`k-KdVI#jcPxrN zCD$pudRM%=1|Ct%`Ma@(jF6gJUu-3-%Ga%yUe>bm#&^>;0~twpB=*cJl8=ND}Fr|_Bj^VrY-TlvWU#533fG*P`Jr-dxgEu{fUcd zugA=6Vip_gFvnL*r(K!K-FVyTW^+;7;zRRluW(ZrVoeFb@AL`FZ63~aa2~_o^bU=G zhonk0U-){oO_fvmku(if*p%Z`zsiW;j3&ncM~_1fSu0gQVNBA7+l=&%I$(N5MYG&a zOx5=-H8tyxSy`Ow{ONv`q1l1|H7`28b}+vC9WOin>WKAp31oj{Zj${w>GR(Xe`ozi zwfwfjLBxR_XMYINRkJb|s3Lc_7zFkMb;S`&njm@^NDH#zH}@A8Q)KoOf?p~G#_7Ig zS!>!f8J>GuN8u~PGBeO~_9-s{)ALfR91B7@K}zK(O6F;Q%-Z8p_|lNtU%?pxFH6XF zK>~x=t6#57acPQ2TuHYvqsIr+_$+H1ywciSsfcGlq)SBlAxoE5%F>S|DcF1Nj*#dC z$55(>xGWgkRm&(b(8KY^Z^jyUdqgbOKo#Vg{o>MaiCqinWJNG-Hi>;y1c_~qa z$Gq|5moy@JM!b^nZ?M5M*7R$k9c8Z#R3aLc<4nJnd&08G4Y?d;rVb!J6jkJOC0r!W zp0K6N^HsZnowlZ8Q4NI{9?7#CS0ieHp2WtzgppKlXel%>U?+3f^AKGE8NY4d6LX0?7T77<4)=?Xg<|cJjxjo8 zmd{06Cnz2cmPu(8k?&pilD-eZz8KNU@yrL*`TfD$8su87oQ`-GZBp`xQ&}5bZIVt& z6Rgl)hW`{TMIv!!yVhbqAx9e1J6(wMdyRn)IT@j(rHG}A+*0xg&9KNVzY48BVxy!R zt@o?w5Bg!jTB)t!OE*f%qfdH?9-b*r_3o1DOxeIvLL9BK0dK#U5n}iuaVYwO5nUq! zQ#zfX&a~bTPYyNo)@p$FFH!kL#^xHG&F8XNy&2~g+F?nql68z0#7%pvFLhL#3l`h1 zq|laYhRkP=Mm1VOpYXj!^=Ov|&>?t*#cY<~M zUWM%K-dgsOHlWr12(ejHfTs&DAU~b>8>!B@NfLa7I+~Q@P7KhA&*I$}#ZEjq8PFoO z!P`=u&xLqEZ&;EpYWoEBvEUSEQs|e12a)n+q^u5T)n{r`uFwyN&1+{I#lpkp*{LS6;`t+aF_M1 zw9yqCa7JiYMAGoUvjh?SRAoyt_=oF5;?t2&d_S>a-G`4aIH}0;`V2lKu8S;%oqe)U zb7MDOw_)bBmf2gLm?WiAYG=0#(YLxO9%Z05NCJfjxFvLep&9V#J>CPpg}2f&L^Alh zki*@P`ABQL#5^+ZX_KqSRh<>H8XjMid8K|PiJik%kC#&7&H4MW|8crDWfx|>?Q*&% zxfHHl;p^fKpcf;yYxaIg(X?Lz!Y*?BllNg?O}*9j2!cRT#;Q9~Brbj@q72lA*c(be zt7OXSyqog4^4q$h=~N>|igScO6+8()BH-$7RraY8=?MYrTf!T{rrNZN$0cFkG>Lf^ zzP|gCLeC(+-qRsZtpc=^vs7Z9eMJ%ulU}{r!%T!95#lGS9V14O^ppWcnR*d;T8Las zouc~`iD#@0y$|L5Qld}M6R;cLcbf}(DMeD96QyG+lxQoZ+*ZF0q^Mr>-Vhgt)wUO< z$rOzlHZuYQ2Vbn`2E|XpGOk5KNIVt8MtBNx2KX&4h22dMayKP>Lr%iqqa3=yU*K6C zbU+7j)B}^56F5&iPzooSI3VB05j~tk3q7IE91`~*tH+w7wuQu&A)wrg-Y^eNiD)N< zlMms2l0NZCc^3XAWdC(nT}YfYw504ucZ~9|-HXe{c<0p_efO8~;5_x-M%axI>zAdl zWw{@}W%xaSUkiReHV=tk4cVc`%5e??TMV|D#tLUlwk(Rfh8SNh(!N_7#al5>YKN?L zt1Y|5I`dqXnRgmTL5?#o$hTD6Mqy;83?=YpP>mlNza`D+f&|6PA2ud{rUo=qpt}r- z)R2jv3>to@O7?g%^W$*$KL)YOUOb_$UmP7QXki4CzEIc#-fIlrGs$#}iO_v2)0KfP z}6Y-AJn?>{a3+W1LdQNN(fuX)I=Np&8##D}n9xtnFqvcy~ zlt)ZML5F?oH_#92jwab}<1@D;V*Es5&lE8;K&Z8Xhk^|UuZ6Z^D$l}qVFNrOE@6F7 zV!;y|Psy=8orw2diuIeMLv)flU}>ssw4=t!j7yR9W~OgFGq-i)3X<9eCj%P|-3daQ zt|7DpIsR`^%GkWpxKj2rsZJC$GpFl!!=3^jz2bLx_JkBMDeSk?Pe@Tmxr0dY$?lk> z(Sor{8>vF(qS>;*66()x6(zs50x;IYH9{USABZgR{p-?*`Ax8H%ZzSa_@xY6_0sS)Zz~BNI z3gar}A@(!ADWgSss8LE7ySV9$l*r%HlKs>^oTczzZ&1ETjouX;NpXmt%2h?hLs57o z`hX`LEp$wMMrl}%NUet;i|%tM4-rq+zprk8oSxX+Ps2~aNj3Fv!0~;yx&I9P_Z2QF z+r*TYtZ3*>H7;L){Um#6g(?6H5TJDZ-n&>l+b1A3$%{bQL=)`eT$|X&6|HmmO;5+;T-g-&0nUrrJ zH)u~rYBXVW{Z46&X{S`gZ-%YXPN~pD%4pcnx*jU`JB5y)}9tZu6A^M8cKWbiPUeUdB}a7Y2>8Mk{M^?O`D}^94m0N;8=-c4UQ8`AD2LPZhT6bgA&d) zvHn5!DI9_C7$MhA7llZMu!w@?)&}-e|7IO|`jpfNS>9Z!>h@y+bJEY3Hnu1OS;}{p zuDkw=H}?rZafi>U^3_D}0;DKJNQo0q_1Ef*{@dA%nkS`1<=fJ0N}!$~DiQFG@m8{& zs_tJ>O;&aU50Q6AV`l)HE)tW`(z_l#xf!V@O+-4QcS^61KJEIT-^t3hs@0M{21edok93JNUu%73MI$ z4fh;Ge6LBk5uH0n;^MXu3zxW{m%H(;85SHXzY`A(qQ;1=MX7g5-zM#pzP(L(WONQ{E_}(IIxf^h}G)Aoyu2=tjjX#ffpLJ z6-pWZoDCFGjS~0sjTQ_32ff*?MH5mTpqSehOu@XlJ_x$TjGvjWtw`N#`44Zxz^jd^ z68*HokuOQ<;65(?ua zc?&o2%Ir*MTWf}?(~&UnW+O?(FQ?Mg7*|0V1aP-ZH9hd#IiLR`RkA*$@cR|Z`c>(l zKbk7lEKHTEAEG2Hj+TY=L<)DFTf3}Zsd(-&NtU36&R2IT##LXN-1yZ(4O-+{ZOp0|Pv$DeH!n(Q0b@jD3Ry57-d=&Q=#pFP`qiQ=vtLs@Sv7u92t6QIF zJ=I#>%jpr_v^r~5N0aWvLfAAB+{qOC#dRq_wbXjD*4@1hHmv&2b=AF0b%L$BeIv0Z{knPb)y5LpvGwcRB)%xY? zWW1T-8Bsrfwbq)sx~&Bz;5$~Edug+|ee z&pKN}FPp*iscAZp!M@O{e!TwiOK1t@XrY&d{Wh^oy5a<8Lurl6a-1tk@gOpz#N~{U z)TLu2Whq;t@lL`yJ)Yc|ggZ7XxnI2I9_u+*b8+!X^R*Mshgz1^Ka1G2?>o~5h@|p_ zbLo`gmCCNlY`SD3WSgv)L?RjQG5Oe%6r`s_O6qCgyaVfslwY3is{u;;=@hz>q)Zu+ z)3h8PSE9pP2}znODBZM*5QAhT4o0PmMA_MrhtM?p3x;5 z&O=xQ4qc0^?(=Ic`$XE7Sj6=SQNxsFLH@&V5`OZhaWyARvM`LAO zpwe8JM!XRNY&f|(lSD+qd$U6H9^E9m0^XACglAiKU3n|k?NW>jB1eiw*HKfTJC2tz zmkeE5tv0kJi9m*UWX17b2IuKK=OZN|_eTup{Ew548CLMpcVM4L=@tK%vp0{Asyy3( z&oXtsfXi5_Q37@*+d0W3Gv9U31hnt>`~LZU`JKtx&vTyhtoME0 z*JVr#t~gQL&U*;iXYSxEJoc1@bKSbY2Z&VO2eg1;%?kRz>Cxis)cDya z)v*~T_$WI`E83295hj3eolO7s|g8e=R$g~VkzH38p<)(sKi2eO2Spnb6TM7 zHx;q4NRzJ+vy3c<0!n{z&*r|9gw!RbLW^}+TG&B2-6Fp^HY+y+OPv5M*i~5>-kIey zW5|m5o}3Co7Uj~OmGM17Y>z;Dth7hfl^NSJwLCL+U1no~+1NF?^46>g-i(ULq$a1g zoSb~^+2CsI)c;^>Lu?BwFy(xJ_AC4;_+pgCC*HE0^uVt0AQsYu>j3Y>Rg8xVb5O!~ z?8C9A5_!#KEHqzz7=E>F^~6aRtZH*Ud<mSZx*N zq?oUj=Xte`IR%??!>A$czrZy-SUuc^S%Ux2#M$|UDJ_Jo0 z6{V}7#!0D#9#R_hmo8#saR)E0($Cdyd(<}N0=!7D-Y`%T zPr+O?!MCcsD(FZ~4s(d3d1<8{I?hT)V_^b_T`7IkmT*C&@yp!ua(2j*&GeSAK)!6& zYyqQ6Y`^W={?=hN1HA1$it|g$EwB^D?R0|q9U9eP3_BQE1YCcrA+9X1!{{~LWvH7X za)aIt>tebYgo!D19t;##7I{v~%&`fu&7{^nVkiXf4lxg|&C!s^yrr+v~kHk0Xl z$h$GyX$QIyxaA$_8=(Kymf^@LXPf#Y1}!XOy4U})tUrb_Q=rRN$I?Ms*A_&RuN(bw zAQ3HhU1J8kdw0us1k&PX=qHt1=YG;QC~cN+4uECfQ3Tu@EPaCE6tD>Y6SvWv`!lP_ zsAFS#iPRQRUrud>JqLX{+KVNy*<@h3+HTa%h20Kq`9-DqEYcZMauCaJb(9Wx@9mRb z9cE6LfS4JSx<@htrNliGC=CjVNrAf>TUrg3gy%?eCu5&gkr4O{WxM-ZPUNf!*41F- z;J|)D?f+-kN5?pOf*mzVWCM722J=R6WGXbOPy$BgRj<=opU8~$6a0^lxhRKLL(7WN z_%+_;&>duVm%;lkN%Q3gE5V=U+3VP4+qGi%jf;G{E2HMrxwB@<+rY_x|BUFV=Wg> zo{+IpQRFrE`}dZTdie$aGG~@s6>vBSO_YTz#gSu<-?T0*w>$UBw+V@0R9plLTDj$d zia)!{>iXR$`paZ*wz9tzInG$E{RBu z1g(lfv`CW~c7ZVaUw&pzaZJB?J``f}8#5d4urp#O%0DYKT495;W&8fO?RU0}70G_6 zZFxT)+_4;L#EI{e@t?g_D#|MF1o+OPztjbA^wc|Lif*v_CSw07B_ey7#8d;V?`ym2 zV>si_hm}p<6~|tiQMUgLd!-Nk9+mN@p)E}1|Cg})k#CDahw8%0y^KKh z$Oqh9G0vlU@&_k+ie*`K$DMzuBL14++wwX;>{TeCo0K~!{X_1TIJwy43&pk1horxc znH=+6h<`-90TV21c&U=+Z)d8N=K5|G+DI@2!;{13>jvN3qzfrj$H05X?v2flS?i^4 zC_C$zmI};(`vwc=%4yd3;gN!$bZawsZh!%6d#rPCQfIih=<5yaozz(Dk2foh$m`REBrIZj~yL80IX#T#=c@Bjn;vb@aK;odp34# z?X_dz>+qY$k3BKGw7jr!rbp2TPiDWp|F6mSmMXlNt&5!LjjSczdz~|@F|qWziWk~i zff&j1Cim`3UQjuGI}Prc&Y8;%jS5^lK>==DL>MyQb1U*PIXTXY)mvM0@Q!TZ>9%1+ z?i*0o8RPs|S`Em};$fQWUGk5D51$nmyJ3Zfh8Wd{$56&;+(>nT%DDyg#ESC27xl!0 zvR{m``FBrX4vV@%^@aEn-^Q4d;&fUOCCf z7pVM+8EW)~9(!Wa)_L}nlKpTQM>BzIwFZoYa4b)g^JtTF$&2(Cmc!nuutSV=k zoLF!ql*k%e_u43eZOD(@0M^pI?3eIs%k2fR2r?j8D5^V@reJ0qlGF4bx4q;hy_YYd zEM}uie5&pC?G<&HyMfn70Lyd`dI!N-ykFdI2Nq~D*kM8_2kNeSg7@>V?r(o-iyexd zx`1i?96hfHWRI`2i0+;MmK~tsj2pHb+48R~;?|Uac6O3qhxXKMakgIErZaBnFXJz6 z<^#n2IRM=mv`tnH{*+hWqI{409&~8Q^>{nIVjbR2eWplGF4$?~&(J$RV&i=JqVIYp zqBiMIJ_bB8D>BCSs@Wo4Dc5T>YR#wHB!62d%CEJpEg|0l@44Na=eK)SnnnLEk9V=c zJUu>&)23u(GKhD>%xp4dW@&*0tn;Wv6qT&Ox)QM*>Pnx?>nFHWMjo7{h)6QBh({&+ z!y_m!YcYl(?B(2wm|CKqavS*^%kk{(N8B6wmrcmtVgk|$dUdfpFZHSJx8J|#zw&%< zq^ggFg)5%#3LcsULy=nI(b0_OJR=@K?o-|;2VNXxwx*c*F51@fDr|f2OPLkl{{Qn0 zPDJ8pi?H-f%%(!$faU@Z9^2>8Hz)r#a^bXA12%m`vNvUeC1?>)CYMpujFn0A_S?WauKe83n2Y?= zp(n)T0~yscAZ0}r)3}!G3&ixR@tpu~ljtu211D(+tc-HNXF>BRq932ZCV^&vVjPp3 zz$>p$o4W{4Q4(^vs$cr!yShqU1r${))3D%sx?)G3xH^BOGIks0gtJkf2@_6ni$9E6 zTx!|@Z&tE{>1+2g!T<1Dj9`y>voKS6&3h=6in_pe>rJe0kqOaj7)PvePV@dYkZDSC zB>1ZkSC(eB1`l{wI2kZOv%P%TRB=ndU`p_p<5((=J>p$NA?|hUY)S zzZB=_%^tsY=29p7so{QOD{Iu{8n!+i9vr;RsWToY^qR2FP7LyQ+a{H2#nQlHQyO#) zGChmT)qd;HJf$+s4$XF!^=Wc58#w`dUw8gYB+e*SoE=b^QvB}$4aNpjlzgu;S1GpB zkzh~-?A(0x_hMFHlF96wVk+>Zn`ZeYn`Zl3xx-9s!)h;62x$ib@73jp$D$qL2NwEcN_?q&LGO zL&_HD9xj+x3e9w48G9O957({&Z$KnI$3R+2s-0>?0T35$nWwZdvlX=rS_-$Egl+>O z!YMw{#DNFx6ymMfnuK=sOnSUh|+(eacjd}tx-fWK!2}K ziG4c%);%KjaL|anZW|l0VYDBSc1N~uW6axpqE6)xwEb~dp^rba@Lk2Ab!$r-Yrd;H ze$Suy;`dSd=Q-E!Va#{H1k8kYMXs`)_z%1| z^(#~ds622Mpz$yRTGqiZ7Wm{1jz=+L`mkEL{J~49x%1>nR<>w2eDeE<;n86^=>u1& z+@2!x@JTPrnhHevUvF3Dy};}b4-F^=J@@|J`d!vX{eMy+Ka!31cT1Nz6o~4-x2)g=efbkw?|(jTIX z@te&@vRD?9>`{7F7uV@hM>US>IR=uARSDjY@sH<*PoHe!B$m_vCT^z z;BP?PQ(-<3v~#6rst@&g8GHYO{H&t%(o=0zN2$Hu+Mct#7G+|gj}dss!tAp~S$b;p z&TR}Z8PkATlBM^CjKX#|hNF~mQSAK(i)@rYjFFk2m#>SaWrx)86Z9c+7JDwCrYp=y?$WQ?g4>>rlc zsM4qmr7?WAEWJ4Ps&m~oLJ{BN(*nb*3{7It-ekWBtjYXv{E8%K$R1v<1cILf;_zRQ zlD?3d}<`=c`xd|t3oDnkW0|Ki$Vsc4MSL)xY# zeS7Q~GH+!HilL$Y@3!d$^SZu}=e1Q`Dm5hZ>iA4>Pnu)tc(C%vq6O&~k@`k<#YU2f zBH|X%7qx6(FY5v=TFd}^ETPB8nImH;#r>r4a^zR^eAq7V{O2$aj&mP=9o>q4>i*UQ zXhb)Gi~R1&_2LNP?~RToL7UAWkB^2QMig^X&K2p@n7cJ0k7{OZ9JB1rSERp1R1QzadX%6(yTAIq{`XM=)qb#AXesXm$C}Dz;{L!b<7dB# zv)6W1#m+uc{Xzfx)SvsP-$sk$R|`QYEmAlBn4?(fVHv+>RqBd?*P zR1NH2ElXd4xgZ)-Gf&1H-U7B}L;Q z48<^>I+MuIyoln^;A{JAFBnFC!>i9*4QuVI48SV~QL6>_GU6kS_jSs> ze4a8#*{lM-SS3zvJPu6W@ma@*6>e>p74s3_s26%XLFuofY6ml`(zmRv{4+&JrB#Ks z2erM5grgy40t4heSQ>#|{-ca~2g@~+`1m)>#0tletb?faq`@@|oSF$-gO82g>QL;> zcX-9OfN{_BFFY=iYAP!bBUi=*=#O_)!-P7gn1u%>WQ10u1oQkf$hSAw(rsK zNl+5!U~9d>H=~j`eyQdc`@TOX``TXUmo!Jr>7A8OWKi`!sB+iw2f5;P$m?H)!OS)5 z2qIw>P#o5)A4d%umL7_xhZrUuQ6+Ju2ugc`kD{CsLf7-R$hnB1N&tRamVOb@2IAZ6 zV)eQ^N-2G(%jx)^9x7`qp)o<_?BBrCB{7%yH2>1i-Lrj>pe zp+bgYUinYo1}c0J+BBnMC)y32YT~Db&U=CiwrTk1mfP*B!8t#Nt-5xC;mF_{TW_^L z8J0qu4HmNa8m)o5+wQX$&VSXWIFGcKtgpVHUFsKCfFW@B7y74%e;&BiKE=QeZr}X$ zu*b!RlOx;gTkXk%bAI(C)TB29?{a$U`@ITyRQUcJ1AZeL?XTLN1A88|;X%g9qe@K@eaW7TCRe+EnHH+FIIzQs=n7;MMk$+DEe2 zBRWHD;rNi(PAvpK$P~TTU$W%A{szr^{XFS4xS$LtkXNfm z6yY;yk=Uh9Xg#oVKEQfX*Kg}?uqKWuq~~1E)!kr!&c)_EZM~yz#wC^Nb{E}20|t^W z>Z*b%I@+`yKb`EoqHyPcCYD7Dt8v4|A7X0126*D%?xTI6h*f3+$4febZY@r@_ z{4(WR#J2Z@roBqwF$#P>3VUcDKOrhT6P-(I*!P=gYRu-n&SmXm3!7cgz2VMpNUk*0 zCReV*a^A&-ysHg0jPU~*+|h%Fi}XcR1I|K&OHN%vtg^b0bUxf%IP-llBZ&(#jHlE=^2Tf_50^|DSexxQfgG=^x`cW1vT27>(-p9 z&QzqUxQjEIfU zG9J%y(K`UF^|Z><@=Zktv)-3)O3Q4-vuqbPEEdHFs|Hk{xkp;;FUX~cl=g0Yap#c+ z@e!=8x^{=1;v-^E5&M4P&LewT+U(dm(hy%`v8Hk6de^xq^|QrWk@^CW+A}DxTPfeX zn7dP&fkw8}zPh*QPKF!tS7K3^8y4A<43G>Xt{%4Nc z|7NL8N`}eJ4XAR(KznsrKR=0^4==_nzFUF$gd!LB&#iQ>2kStEGtr+>S5c|$m{6DD zO0CPRV{^_JHkyk&HM!vFF&bQ4K#B7;xoi#_U~>x`OPx!hiAC|>X}6{0tfRKMKFk5l z6JpO!Qs^K-uVX@z3+m+|sU)Jt@9Xd;homn@S^WNK?E0H={;Y{OUkQ)3TCLV4F$2=2 z@T5S$bP!{3*pA0Cu-+sW2BMM>orgW_m}=Ji*cEdWTCFxYA9e|{untI*-;S^KNzqON zM!dW^+n<4Q;=E58R?K%$bk|13;7d2@=Vfo32;@Il@mbP_hBpBa4nmruU&2zs2WU!F?E)pc>F zxsFPQ*%g&0Mw5_2#1{LhB;T8Q-j(2N&bs8vud|{2=esf+FV=ovW@6=nVXcQYa#ngK zga7nQJvi4`;mDq=Px$YrMWrtzGo3~U`1{Qh{WIt}6Ry^;+{!0ixs_bs?77{pjJgtx z<1<`sazRmT?VP~DY1~Y8bKaFej8FksQficyeoyWzt=(xModl z(|GA_YS5p&zay4z)QNa%;w{+K8o=^=;QRL?+zgfXSU%#NuD(}syRcliky=C>+O*d; z5Z8qWYu~lHGa@#Yu$&Q842}zCDG*u!3 zMMLN_bSSAAV^r2(1+y_>SJ^xdtn(;4RjOCO($Xxeiz4nrR`*Wk_YHhT?dqZn(vT{mFM z*2l86W#tUss5B4JA>NhPH#aKH#yaCF?PJknm_|$cHej}PXeF@hqZ9DW8QVIvzGv#t zI@g|YrN#cIxst#;5HAT;!Fy}`us$2GG-Ej*YoDtI&aPe;?>m;n+goab-=cO{!7_>1 z=Ys8%i_JyDPzQr;q#k9sG7Yst&!@RkoZTpiOii~dsp3)eeev)0sF#idvF}RQ!-FZS z1w0AEz+WMiB@=cL0?WOOoBXnfJilTWT+{Pc-sQjH3p~L!PycF>qd(p+FNL3yJ=ZTiF}#0xDPpBmzEo%%W_GBA|44Hq z=*xr@0?aqb$?-jC_0l#+>6rv}wFk zQMnFdm&QW$LzJ#1oK<9hQpP*a*BR<b?> zJQiZ^k>RCC0aA@-_Oi0J?U8c6tlOk9tH5*-W>+t#2cg1Q&Dp)z2+KoEWNS+)I!&sxb?`YsPrHm zk8K~m^~9~swt!DQi4vw^yjV_Q0Vo*d4T}PcN)yWu@%^>RibrfppQ7maAYlc`8UQvw zL#)|o2q8s_|UOp$7SftvN>EH%Cg6VGK$%_7bVn%l8O>~wUj=FS$zr4^^IjY zVP|V{4n?=VCMR1M@ikd*c}-5F5lHQ8a;k-U1#9-#%V+8?OFN@E*z-s1`O-JN{M)w6(za+e_PmZgUC@-H zJC#N=u;)eW`MYm2?!@9wtE1`I*AgYgkw5v^g2~+}v2#~MCj?liGXpJ(E0;y}II9s? zw)xcMm!%t{>=KpCCcMzb6!iM}*cI8x&sg2ZJF^VW>;zSx7t3xe9JZ}k=soEjEsj^( z4#Nh&E2@VDgNvfhoK&|ru&3rGg;Wd&wbo0~lQJSGj@>3J!VDv|Pj+ygsZNe!*tj#E z6vvaESQJ|$sr9sg5#Tu>LOyR(IOaRXT8}jLwjSQr!mi4Ce)E%Ar;0vl%P36>shK@( zEbe?V`mC(BsAYEXk!{zTmEG{KZa&l)l{%w`yezmPKkun+yf5>cHommhOI)3?xHyze zs&#u2ky^X`!(NT*O+3-mInCk8fMqgUAG~+0cKiI&=Q4*7&HUpnx1Yc{oVa~oTQklw zIJRX7h;ycV&fBgmU0|TI^0s^gbg=@e+mxzbM}ZN5?>$4MI)`ZZRC>D&h^hN?&pOqI z=cw1K-IBNER8NeLyTRSA!zkdkd$lW!(4D5|&x0Z`lRXL!Sz=W(V&q4?=MmULsBPPe zHcf6%xDlM>6OG_m)UJqMl`*z0%i{Q?ZB#N`yN=jkA0D@(&~@NOHWGh_CiWa=Z1Jpw zuKFxhIb9VEgA1rU(HOTo{IrwGeEgd9A6)bG=nt>?Dt1l!_%*AqT|-!Yr87M{&_-Bg z(%t$rx};#xPwg~upic(LtScv$A%mVgp|ek>73Qos(u znEJq}ro)zo6mU!*_~PaL73h-wf0g&|%Q<}unmbcD|MeJ^bA5YKEX@zZp78mY!r^Y! zjHmh0F%6z`7W)`e@Az}>!*eJPsNK0*uQcGhzYx3U#0+m5|`a79l887D-aQ)R7)}2`m3}3F9 z%k=JK6u9?h9HTnCuszwi8!Dh+>R^%_++21qn6Mc;w%7xj<#w#IqTV6Gw)Qz%GRj}_ zf5o|>uEwfTA4RNCtc9KX(6LicsF|`NDxHp|V-BUMCB~CRQB9Zop9%F;5APQp^)#kzz+S{1owdqJ#g-QJdbi%9Z8dLK<$!AMb184@D<}n~>}yq-*)ZJf`?u;sU0+q$sE7DHt06P>Ydy zB3`eG+jk*%k9OD_TRN8A*e>(J-nPTu7v)i5ZEGp9xI>3JDp|%ZZhsN6{&w{GV&LL- zv`;{t@qTvk#Vv;#a{@;mV9Yo94mH*tr&cw)D}Dx-pXx7i7T#!R#C;id(IGG0OE-Qm zw&>!Pc*_xfm(M@cXz=s6TU-SJdJgYW%N&*ZM_nD+&g1yz8Te1gSpm;K)X3rLZ+i}T zKj}HL?fC~j2;IP)ZhHi+t@ce!L^yfF%G`?6rp>$GdjTgB#;l-Ml4e!s5Kkp~+ z(io9unaNZ zA{>eKad0=I-faAzcsw)Z`OfXW7e z1B!Bb5u8Wv_I-$APJ#~B1fZN34HHs|6zfK%)x&iT?v)#G-nLPt!-en7y+Zm|A4ey} z?)x7fxDbVOcXr@VV|r^;T05$89O%$H4}+a(mmEP%cvJxTgEiv2>Fm3(C3vn!jlDO* z3Tj+Kby-Fq5|yrxT7;iq2F__yR!NoueTBB1da_r+;i-vP=9P1a_2$uZ zL}Qu{+Dh>|jIn6(N$Llv{L1az11N>{i&`H|=W7^|zmIGRz)y5OxF^NK%(D9a3Dp63 z%$VX%W(My_uKou+_E^t*7it1a%@cjP))eyu-^;dK|HG|nv${K@^ok+7=EVlVVGml_ zw7|=@L7xGBgh^1z3i>CMX4m-B?>4;HAl_HmS_?%#M2}4nkn;F*%Q^+1#N{4%r7ahT zv%>LV&j;Hr=2cK@*FyFJ##9#xrmA9+vHJZ zYU3gAVR>}rXNcQV0$by_q|DtXM_oJR$jZE6ipp_mQtnPUy3&Z&<#|uQbI{!#!|`Y1 zOR)BCH_p|c_h_{gH+|l{QoOiD@UVdow_Gp8(|YivMf_lk7hfm7J>#Sm+wt|9lSx!7 z+(%HefOcw}7Hc)BpOVMuj_XxPR38?4uJy*+car;zoa!s@-P||=3 z$MKUGHRskGX+XONo>q$AR>Vs0#qHmh-r|#2%Pz_UYNNtoa8Gp{d7u_7ftemB>I-ZV z=;zdQWo#=Nxd>HBU=)GVq&jr<`h}<``qs(l@6Jaj-DvilS5G`^_Oz&{pG%GTP$oE2 z%A4fHdW>1p*tz7#2V0gg39O5U!Hmc*HoGwb+DiMOSc9>w5=WkjGKl4ix7k$wNbiQm zKV+lQwD(F+MviqPIL~i4wvrA7sWN*{YLL?PD9eUAtks<{5K9z)CVup_PED*F|4=u_ z9n*@4f(yQ@fCFkXEWI05F9(aAyx4`hD(sdQuOtu66H%;g(_j@znC_*epjeJOO)d9R9d9DK-ny4<}>0Y`75$=Tizyol|nuzfUq@6&NrsFOD2vivPvGrII z$j-B29ofrlM+TYNb-PeD_B^Q$pKIQ8puw=`w0iU$ybd^O*cG=~V6H!IU!l1k#pxs> z=PyJ}6Rbf!gZdCvV4oEjHu5(LT5HgaUYI;}pPqc_-kL z*agc~1D*i8y$Ut0c_(9Bw}FQZWZkBnw$U>z#%=~Lj%Sh0MBylCwe{)oF5hBqCim!1 zYT8vO*^D{te_a4?KG3!rE048rF&-j2kfuEXpGZ{djq+6ATy(rw3cQ1e!NAt`s)4{7 z1{Q6mDZQK%>m8T}la0s%`w;#saOU4Ic1AAP`Ca43R_bpYw=sucd8?V_^zLUi`7aeI*ldB|WP-wNJW)1HPe*(=pYQe*!gh)jt6 ze=yQ3EgcO?AC5+(<0G&kBK@yKBhszm@1&>3zLTCG+wf)t?Mbin?r2E51azy$8j&7) zcRJ%@^4`k>JegxO?S-*XL`1qgW*JWr@1KLZKh+%Wo`W2UL?+_*=4cLn<;b`A9gH;K zw=a?h8{`tkg*aH`TjVhIeG@U^_p68%zyFG?#P1i8J^1}JatgoQ5e0t#5%J;oOeBO~ zs8{3nZxI>4{}UO+@1G-N$@xd z6e>Dhu)9-!ksXWL7)|>WeDeg%H6Fvbz~JG6QHIG!e{5vYPSdsHR!l108;;27CVuce zdvTEgUc!58;vOa~JWK{y+b6)=q;@tplAV;}n!V)vqUTZBiG3>d(16jQgho0i4oSZrruBuf^~PbPV00A6 z)^|c7M;}YkeX#UVnndI$vzG-{L;+tp7*wyNXk+IlXm4xUwa#hqIW56kbVk0D!lNpu z3YJ_IEP*s9_)ao{dr5PW^7(39S;JA%4w|-nzkCxgLGQydJ4jlE zG2r?Kq?)j`g9#L$?3IKtZ{mCr>8E2~_Y}v{Lf>BJgf|gLQ~L5xM5srjdQWBcz}O2R z7vdEuH=@#$Klp}RtSrM9g6~1^1O>wqCdV6NZk~?Vwns7V%ywi#J)PMvNtdHb5TRwG z7QS{!N=7c}vnRpUOj~L>j=7c7ybd*2RNc}*`kxl#Wex=Na}2EoTfxsd3ONPYMsah>d5>6sDU z6hy!B%-9voe`~<4MfTPdpcncHy`WWqGhqm8t5wN9@&LAw2N1EwiT+Hj&aZ^mVhMb- z>s1O^uM`ziFs}X(eE{`oLEH;b=tzSGIkd{MUZp!5h7NPBN!1l=L&wjju>s}VDV)EV zM|qB&eO{~a$I)R5zheB%198kT&V2=3gZ;n`rlGwKNnN8kt!d?H6*NnI2o|toj z6uStvH*I+wR?jU$Yi>_jKoBXSY5H!S_HOk*M%`KZf*xi+dX@<|VK$Mh#DEw2Ly zdIi{aN*j%V=$#g}&xB&1=;<<7Ai^O-%qyQ!v0Gk>vC0xK1^sm8ZrQaGxZbF-BHuB+ zoYEjiBGO+Y-IxI@!QXVh1=y-0Tv2pCwyZ@NPBuqC1Rcg6VfywaW(n%S~4)uNUSc#{OOO`%&rmShDkQR*`J9+&L{1W795-TGofzdDj*qRg&J>7^u3 za6LRnROTBHEr`hQ*wrtMXmB<1bxTB=6gf6{+m6q>=njney#K47?`>sn*jJtk2Qlt{ zKibtAky;}uuxUVB5Ecq3u5ku;lJmPZL;zZ=TNBE&>o{Xd@XBa<2U-wVKeC{O{v9km z^ya$gm*e*({gaRJPS4@HFq^<$kFkckeHuz^neCbCCb`10VVWYpxs#vw?=~(cQ(bU2 zB+VM*gaK*y=p-k&Mun-4)WKiw5I&WJao{gpg1sJfh>$5SIv+fi*%-~? zo0!}~jw35V(l?`rs|KX0VZP=0$~R@^)F0)gX}c~ZChDP!bkMPmDH-8LbU|MCHX=BZ zx~(JphyihC8sIT`oo6mzDX?E~@y@j$nYF}X(_ zC&1~b0Gs9gmb9QHCDZpXzNdX8q5r&k(%A={385-xJrFx5*CZE#{ntVfB+tuS%aL9| z@4Xb*dZah7l{GW{|L~IH%88IN2EFk&xUI_^!+HiFR zIDx{tM*d)>H52bR)%P4Ctrekaj(VrNNBQP2J_nlcK0!&9`Mx3Kdx1@HOe`2v;*l%L6?1+aH9-fHkTR0WqndG-6;S>dC&5wYZg zy5j5&PDQ9Hf$s&lVDRL+wT|ZDk2=!0_o0aYo~r8 z2fP>B2m?Ahdv4{RR67Q33d`~`@E0Fi3y(@dSHBdBaxHK73e&5Cv)OdV+0GrtUm114 z9(?tG_P=L5Wptw7cq2^r;6sScnx`!Ioxi2$Khn|&mBuXpCHO3OQ#$&u#F5G4rSb1y zQ>oD68&9=gX*2fFeB~{CxgFB_H^l5@r0Soe_w^{Lk9cAwI4=uff1!3_HP-(KZVGDO ziZGs_@_Qb5!8?}3`+_BCLq>59@lo%p=dR-xAGBTHxzqE(CZO0XsC&z%x3ez?rF%x7 z9aam^4y!Dw3frX*jL!}$Ezb^X7~3U#>a*aLXDzl%Yq)2JwU(8Ov9H#C$+}WG?w8nM zn%rIAkx=<)TcJEb*lFW^>|F26AwLxJLSFQ`?qyLhZ}LuWF{0WSjMec}FLdeTcD_E* zp`A;}c6&X>+4I+Bq{?i8kU!a{%-3{&Wz<4_eRf{5o1J?&RHDk5t?AOvns)!ZPR$Jc zjD@zWP608FIvh=y74Ty|yQO)@XFDkU$_-O@?%Vu=o4}Ef2sB zB3|?|xk>Kd)qmH@*C)WsG$nAco-vR3xW|BvLR{^j@6YuM@1wkYdkFVacAR`Q2#ryo%}tXRDe#~P0K|$ZWPOb?>e{H?7AW~ zVc!)073t0}`$qB2gnX63+@}JocsBm4Ew7rV`hjCP{;g0I^p;$a?nnPI)RXP_R=6VF zhijoA50R?JI!k7JJHuS(>@e4vTUX-l46y8XhUHcU2-0HA=dVb&1B>||-{l^29oY-F zgC*mNbQAVn@hgzF+;IHq!+5F!t)vxsq{vAG%S)E~ij*JT*jfbNScES^Peku%3>I^? zpoZQP@BZ_!#dC^s7o*?cNy7k z4inATk=D#n@~r=jIuZM_pmt1Z%e?4r5hTn z?q&R4?)HN=^0ua8M$(6x;_1kDxIL=SJeIDqqGnTn9G#Ec&Y6!`BnBfoj9F$9z97kQ zNB6G!gSP6^JP>d*eY|-QB0g^Rv%RZSC7amZThKQAZ&crk>n-xhnoYkzWRXUdSBkie z-XCRy!O<1_lBVzcf9}_)mz3_8=P|u%$0acDbTZmg{RxbGlI}AJ_jwg5Iq$!lQ4U1! ztIa5Y9`rnLUe1q2@yE|PH-V6*jOow**Kk$@XEn(S88GDv^NQAc7!~-ntp%lES{Lvf zOS)YMx~(!sUo!k+yX#;9El75J>m^(S@~E!4e!p$_^i3TU@5}m|HyJw&d!DuhPaoJc zDKOFTThCJVT^qF|iD#lvDYwJso$g~zfo^kMOFgg>r-w4X>ml6LWfx;Q=R+Osovfc% zga|zq-|I*-)!bD>Uy7d2&Ln>k<>q9^=2(9IES8^(ke?OE&!13!swp3SgnY=u8{Xkp zqxXYWppx=!MrnVW%J&<2oA(V8@!& z`cc1nvMPXF6c8<#NA~{7u=me%6$Gy4cqp>=#MS(!Be)`OmptE<89Re=I}q`8{2;G| zR23I=+a@FaP>mV#JYX{C3x$abl7TN3cF7A}lpgfY4IJ#&!G<_OWp2kubx*hMswY1= zo0lAjN`8#kmv)zBaTq;OxjBOTEIxAsP~U9ce8-V`cK)+A#Tj-s+eJCZ!2?NNi8mvb z){?BR@C~wk?Y3Tju!r{FgY-nD715VFe$*k>f8|=2mF!~|i#4^|$U{}TS&b-jsv%Kn z3G(NPkHs7VU&Qntn5F2;xMQU}C-zmcPamm&)}}lif8MVUDFolLfVyCs=qt(61G_mB zS}jp&O0*8oT9>6nZ}8&*DSz0O-27@Z>L|Gh@h8y|M&w<16L`xnOB15%X{Y)YHJk)b z$qdARF~J25htTWJ8D)U_FKn3S5tnWe#KyTD`U*?RJ0!4*0oKm07qL*`Zm_S zb{ny^-6(T<1u*7(NY7vPGkLecwm1tOE&AHGM_sMJ-U^BZ`q`{6)WhWRNa43$O>2@c z<;(rD75TQ*LL-^ugUpTr#()nLOI4G$JU}X*e~B|iMI`uLhL9hX+jSYXso^tnoc^U4k7U|Bn;P{W+ znF{+QbuH{V?!~zC&2DUo`(?X#zie~==#s{C)TatFqcCDj`AO*s+Y4tdWF7}I24nuM z&pI@?`B9syyJ~3g=f`c2b@F*!9+iBqND0=!Ii>vUBQ?1jYBuz2NcA)M595g&g#B`@ zo~m3h%@dHpX(3H4A>hQ4d9se~or^TrIPtM$Q=v zW2IJ)^B3U!h1W{$yjZE7A1k%_&Su*b-^@xzNNdbP#3wP6T=cqXt`8&#ivx+mb%7LN zA?o1#0522;bi!PWK;{JY%Le0qIkS-7k?KKuA=QJ7LaGN-aL0e(nbS~vrW+~Wx!V15 z7Szu7%TuW~iDJ!u*@&a!wWC7pXm;%AMb{q@Urp^1(>d`J<_H)^Q2kiFx~8NObMY-( zN@_3z*sFNiDl4WkPfkQVd0>p6Htj-c`AS*Ta}I4QMk#LgfPk?u>rMi%O2ZcLvoYRQ zwjjw5tG1DS8QR}Kg}@?l;4wbs+Cpa*1Zp<%h*(oOR>RxIhFBeIhdlk)&E`{Tg2Bebr~J}p66`eon9H(>0uY8UYeZh z^aIg`u{7`yUDVgeyKLx9h_g@LCDiRgD?aZGGv}P|%Q~o_!B5VZ79+>L_1Uv7`vmO! zSs0Oormy`%-F1$6KnF5gE=zZgo<(lYbP(Teul$K@VZ^#-&u?srr-3!tOjoVJ*!!=3 zv5sA6xC_XX+V6S{cl|SSdhJ&(p^n-tpDfgfbzghu74g00X|?G8DLv}gFU0~%RW!Fk z{nIEN{O(eyB+jgdXDybN9sZxy6EmLM_mw%cy~YO|52sag=Th?5``JKBe!2ggoE3`+ z{E=@Ruwi_#Q_Y)=2y`|V}r{vr>}qQ#(94K~uHN#Y&$svx7wcN%2g z5=t-kASwc1mbj}DF&@kwj?8Ir%<5V!Pho(u9&RX`;b#}}#4rVZ^=v=GyvZ5> zw@rYrTVH?FMJz?r&1GHjJL{o*epij<%WCryA986gBUWb>(mXnGx@l3@bj-Mz97PUm zo(9~W!`~r;VVi%|m@PEk#1`e;_DLmp;iV@fNs%ukC(+P*8$U~`|V}9EYa%t21zG~AcAJ{N= z%m>G71lZrk<2y`6UG7SxZ0Y^SciBe#Ch$}!kRlE#V*RZ>(;V7fJNR^pWNwx~sG1v? z*|L99V0QknFDtMPs(Xy^4memRb}9s=@W()X{a?0UP^r(E>(V{Ib&kF4I?I ztad=}W9sagtdG567$Y<$p(?1+-9cwF>#|6LUcd}%HXSUsAg|Ij!AUao*aIt5HDXAMR>b{6{N0e<&Z#6s9 zOZBohu{6jjFlYCfDkdPO%(0xhE^xHo;Q1MbSz3QwJ0IL_~0_i5nYv zNY_5E)}F<-nw_KRB&J7&nf_}ON9)si4uwj9kk2r4UCW@Pq6r)d)x@^>E}?i?kX3uz zj@I*X0z-DgeLa-!JA}a=dZ*v|_g{;HUJ9F18+01V@!!(^+F;59>|XX2<;yfWEDI|f z-*j+C6PlDSCm&@GCN^Q#g1*7sp*xt-p=?n%ud7K4(09|GQ$B0LcdHw%t5F0LCQYXj z(eH?aK0vtSF2{rhhi4%n~G5uqLxI_#T}qF z+%t-DAJ7U(cw+p?^lnKG<@i(oF`{tn{XcJK!rNIpbS>uAS*^;KXF_|o3HW=}_plwh2+dG5$*B%ZWyS3Kzp(h--+zm zdybJh;9AQ*hq~z*D2A2`QybHsX>ls|s-9Fpm2{>1qwH{SHu@j!m!;VEmAA~y z2O7*9p&N52wmQB!@pXd1XxO_BC>bm+%8O***;dgrX14a{?PTXrt^xa5JqFE1 zE|<+^1J$j!IZh%s&ETVHX}ee*MQyzmyoyX9*TG=q8_lb5o&oNFF_t?Q21=bwo}tc; zdzZq8^8I&+U#alf`@NHgV7JP1ERJ2(7Fa|Y?6AHu{jYgVq+hOQX7cAr!Ot3e&P&>l z=r_Ou^lZQq!xLQ>m>tvYWAeGrfOl{|87NdGp51-zi^rd&^Q~7gA+J{zpm$_~?=%#2 zyx>S3-)e7&zwwawzu%a&snGu>PKL!z*KsGl2$MI>d#7W{m*AxutqzdZ80qEtieMAP zf70RZ0DnkKcNxCMdTTr;``nLN4Qcu4nFNOXx*OqdFUGecjlEOw<+adzGK{Inzojkb zIF;469j^l0^T^0VS$F7dcr`M723Q2GLBDrmU~f#-{Zhvkp!AvGmtH!*7vI1{jyX)f@=FZeQi@t3?z9*?hsSVr)MRDyYd35pGfjPx@FYkZ;yap|*? zuzn-f$IQCVewY(Xe{us@p9+?O=~A7tteY{WIh+R@^z&d!sYGZf&bNU;A05 zb6;C#BePF!WcO*Zi;V-Y94cGVfD0Rtj>)CYsa`6F+StehePQB+9x4yhebvX~CE)e{ zQv#^W|FE==nUg+C3wl!~`n0IY&)U8?Pl#zIaGQex1EDr>L5sOi~N=E0x6Qwp$c zrH-kg+^YsR61$ISBJ1(D(fB-r+WeC@zPsG)aRBqo184CP_-it^J#lQO>2Y}>qiw42 z|FLRFnl)7f<9@nN;Tl~~fw-xHj}aRG(@p5Scm{AOYiJinO} z3|k~=&iFloz*d+&tT7LxQv3&_8Q~QUSCh?8k+1Q6{|4(G(7@{hre`B;9ifFReB04S z;FsPcPzj#u8j$WEezvk9ePqD90nv;b)@aoGbWN`~ zG*8_zvL}@AWYwil5_CD*19yx(I&`1YQVL&{C9&ylSb|t+d~5|6Z~EHzj~QtjVE#Qq^=>x^Gx{P}RZ# zwJh)&$11cmog;|{noW`6|bjER{%i`kR~%|8URnXZWvce(cia?XUJ; z-mVJkM$|1_?b;eL48!FhA(7JjO)xy;nr?8pqfsfqhUsqRvposGI1i^0bKyW#7% z=P<(ky0|{?%@`l8!-Bp`_u!?kprQKJmRsz)gX(6s_s6O?!+k@OgHaXli^n>Vwdx(T zG#~e>6BVER9vd+?j zj)9ifd8g)JhC3zJUNfEae$)mWt$Om<|^%P+>;kh1C-1*mI;x=BOSjg<``ztAJ z{n8_2G~&6*$BEh7n5Lg&q(f@+Z`j`5juZO*-{_AwPvelU7J6v zq%8Hq$KadS1QmsQ!+pVx#h0O*e4QtRar|XzhOCq|49#qNdTJ_*J*1G$v`JDsFv~2E6yml`P%aZU!zKyV6;^mM>!5Am!m6nmr5_7y(OP@#{(T!4ZMx|{ zJ@l>|-nIPy<6UP8%kZx0V{{*0n2Q`LhrMz@nmKH9&dpATwxAuQ<8Pz%-c0ZzFDFtR z$Jwzuy#TB+92d`nM4*v;;X?R-nf%RAHD^JwNjU*Er0~qr$DuKk0H$^QQSCN+DKAgV zTI^9bp)CUK?Lk`_a%Qc4Z&*gIsP-wFdZj&4^}&#&0s^%;s%%Mk<>Q-F&1_LmkGQQE z{#G^k#K1Tqg6BQVhbV7mj44A2e3^XTLU;w*asRbQayi2W)EE_ zyo9{lK1z9P+{Qz1ffE^#xa>$(ZV>$)9pTNSFi+*>ng1#;??GKok`{)=ZP0eZ*Q9c^ z(=-A4q*|ZXw9vn=yifWmq9g}t$JgF_?tqMfiik4IcmYOn0L{B` zbA%ZcQ!8&3ij|kjL9)Os2fUk>GH5Dx4rX<{brh^~q#GRVoI0J(`!ZeLW2whMD-$Yb z7ccVGWpEdUP8RpBv%lFhkt!X z+|>D^L~ri|Mc17rV|(rnDceOb1IA`41ICuz%{>_~6c;y2agoaMHcD}k?3OZc0t(nQ z<#uhP2rnwy7x`|rIu2@^bJ#Jt!zXSOSyV{5*Ndo4@2 zWXv%@e+3iI~TeDx0fH&{6L<$`)wi0|J zQqgDF^66+Z{N{tv^(_x9$LYvoV6Ef|a{+Gg=7aPVdTyZpsC+qg+TgYy?$=B+;g54ZE`rmi$3Jy*3p*1B~x@!ZdIfaxT57^;Bo5}zi3NBURlBY5^27RdXWH+y+6_~5I=ppv z>Q?9y#^}AUR?@B5I^<`u*k?D;7rF!!dVrb1iq(4hGT=|tX#vd#$Y)P>ulcv%KrZV> zyiZIBvv|ebZ9zNt|1K6(yI=!KwgL~rf9!MQf@R1FOZ)lXcsB=SkA-9wuOT1HZr?yH z)=*n*VM*1qY9Xio2=_;QWrv%#Bq}d%#uu0EWr^X9<%z2sE1Eu>z$LQQ zm&>+FyL&6*NNjJ~1X^%)jdVK|%!ZyJ2^pl@kxO$RPJ$N$fU@8@3uT>P;2+nPmCoLe zyCV54MUfAF`(67$7nMOrnEa&_kMPO7R`}hfmk^H>Uf+cXg;6<|YSV4Z*bF`WU9q}t zg|*N^_#0&>uSRA-UI`O=GG#UuO7z~t)?`=_Rn$C0asb_0=<|^^4>2hz&(dORatZxA z)b^lt6J~8>(;abqV4n59*=P|NRGB`_7Hf-ZN-ddV4Z$pGX`@6Sxh8{aUp&jV*0aW z=Khm?aOg(OK-_8?%M`@v%|I5GftUxZm1#403u8$HvP&CnK~6e2#s}K_TKn~k@wota zM64{$_Z{(Y`wrw&>E46xg+bbK8SwQZ@MbB0VY>79nF)PbDekH*I$m}E@L%H2{qT5j zPupRa_aJQaCJz-CH5p$Et%PGQz((ub3#?NgD=XK_nfUSQG z=xPWv=lOvH)i2Jz>YHEAMva9%K`ZP$Swa}JaOpTpz6xxyq=O>#iWNR%iL^tX#b`{g z_)b5#xNajXdHb^#aZNj)fL!Fa_Y`kLo%aIBX5k?1MhUXvM0f^r&sqh@ddqxNlNqy} zMb>e!XlNBD1Smdbf_XG*RR>mCM#G-TD?Wstr2QZ2Y37__XfM3tAm3x5{>J~RzfC>; zJre3~v6ZaQ^Q8U?>lRQg(?%VlnZm*!8l{9udIe;MKeo@O+gJl_;u)F+Ze*jGcEEW= zJIHT7uT~?UdhU&6-koI@tijGZ(clZ^#Nj*oh41d zFV~gbn>SF0Z@sKth!Q+A<;O}_mLlsVyRR8^vnN+z?!vOcrNP<{mno9NFAjrlHWkr3 z;mv`0Ni{1y4&HzfzuoCH>tKn`8i-R_)c8Jl1fz2Z;xU3(5fsMZ7l#Ai-h+;dJY~E! z2I6j8zKA+FJq9wZeE0nV#@C0qLxra+HN1X+t{?F5L;ZQgXQimxx5fB&imFZbn(7|% zw6IPe9YC*(#dt82XfZ>p`FI0a9)^Bkwi)2$igN5068>vc*mZ7$+8?A_XXin z={{JrO4+sy8OWU&E+9I)f$ilTsj!erKx#)X~Wjg^pFGnxC~?@Ma1$2d!d0BBp8^PL!@LMLtuWYy?JQHJCI*Ua_@f zwS^!eSgK0t%Wha0H1pvCs~Cl^lhONqAt=taoqWz%xB5ByPN$y-Daky2%lfc7<8y;+ z=HXP&(I@L2sM9LW=zKsrFUB`g{NDM}+22|>53BfYR;+WbWlmnd5|Rb;EzY%jr}xF0 z(i-ZdH9V&$8vTAl7xo%tMvkJPYT)$vwu{rX(%N@1%&0)p@>Eb|19b_g^}ha3@JMPE zKkLGZ3&eHC)zksMWmleY(NFc2wXWvpxwLn)o^mE{tWamTU$L)rt=yQr5pf&2xy@X{ zvc};1hn)k*?QmU~u5{{YWvdf`DF%!stOjd?oH2^zVHe}NvAPGRy`r^)Vz%+d{)jq8 zm`h^CeeA7O%^>c-n{TqL|Dd?XwlL^~z+hpS|Ub?6?NrMnn_RJiw>Ls(@d}jgAr4c<|nlCOznnVb)=}@wQg@ zMX+H8>vwGEcJ;UsIe#V!U(fW#ajb$tUN!`C13UdaUf9n{(TFQxBctNMp~v8@JdJp6 z=uQ=_h+VMX|JJB1sg(H8fBPe?N#>Xp6hDAN9>lT^<)}}c3hO{!yzMsfxyVT(v8fO~ zO|<7}9*M_062YrzjC*2(v|l$b=YEGqB~iHswWPO^>xbkHwRVadI_4wFYn-K3e7r+D zf(`$%RyArwW1%X3$Tekt^T$fnR}67>=j$e#qb*qfKnbi+p3uEEMCtZHR?#XR2*^kE zx%iPsE`#==mhDMJBwhpd)2a@g&VvXct>U%-H%>ho9>JGm2k9sL*HTW&%QE2OIXNHX1hDSa)?kB3gyl&o)mVp&s`*V$39&CtBKT zF^`zzlD6^It3Fm11M7)NdPH#xC_H^xl6eBMh*<$iZU-{tcqTKmS$;VMI4^72BpYpw zduX(EkRE<8rX(}vpR*TJ^wqhwUc``7kC|d_aHi^pC86wO2UE z=1>!|g>cpn^1^|T7p`%?z;A?i$7}7IebbnPx0_hKh#0#xUoOx(F@v^V^SI56Jih?$dQ1|7a5#vf0ZN+>lA1D4_dcEn|BcKsvHNb`OSX|AG|%>qYg_) zZeUfi>~ajO{yLLjeS~ZP@H4ogI%t6{q|*74bcPdOzz-K-W5kAQkU8-g2bRcPFWCT}Ij&_BZW8ddI^j;;Jg$P@XF)9R4VH*>4I;5Kl7g8^ zEu14*F7v1bQLOXlH7zi&1D5>IzO2LmxpwgOqMFkYA(ia}zR*@}yW(14&PKl*+Lr@gar;Z-M_+Q@!AUbiH~(F6eW$DF zV|+Ui-##XN+xLI{c6n#P(>3^Z48ENMZf~TCNiE4d{rJ1kbsu%T?SrojRv=h@NBl$J zb)THQ;-YUW{W6^eZ7+m0_paElQ&;q&%dp;}t5RR^$OHyS8|M&!PxLMHIrwgXb%5or zc(lW?zQH471;_zkggc641$0kIeme$rl=2;bdm>^m>~f11>siuP6;e*ago zpgIm6s~0lw@5T!%KYn6OstqNTKGh!bRm*PHB){vK9hv8qlg!0i395=gvczfr?qTW$ z<_GeW4&owOMJFWgLA^X#LJ5r*aJ!O^iq$;ZV$l)*xez>9czrS~`&fkqr}T$yZ`AM! z>qVLHsy@P*`kxuAQ=F-hdto4W~J}t_Wm(Fy*Sp^NjTcJ{uh*K1Bmc&K%K8@MKLbhoWH@O-WTO=h-%OptRG9`&LKcQQ z`h@RIi~6K?MbOeD)}}tmIp`$ogOe-~*csu8=dg17Wcxbc&;OK8oiHA-f7N~nvg8!i z5S(cz&EP2Z93Z};`aO>#5^LBBS)TXf`swDiBUPRWayIf%Rt#d+$eoZbw@Rnk2w?;_ zIo#L>kxirAacmZQnC)VJW*@Vw>_?W#E#MwSCfki%@T`hA@%uT4(sK{)!HpJ~ClY&g zS=UodM4fB^K0V=ot+cR*+75namQJk6K9<7Vi*RBUmL4f(6-A*F%N9DZ&VrkdXOvsh z;yYSuuPrG0<-Dpcn%V^0cHLv>VX`0JnW$yvpr~bL$Sm)Q_P{9Vi%0N9vj1A?(b5Vo ztJwh^TpP4>R0H2Bc+}wbQ{60Y1b@Hvu4oQWU;lYhxr&Y!DLpgUO;8+O@rm|M7mbhh zOThP93Dqx$r&1E~LO1Z~_~NTh8rzTdBPEbyJElOcT;^7Bw39F*XgEk>eFwhzM|*Nk zlH_`ui^en#tvY=KA(J3WLaaSC&aLqs7hFei2Ee8ewlcGE$Ke}Y_cwRM>1{_#3UH=# zIMW%<^lIBloM-Vk&s4hZ*-6KVcD!A;_IIwOV@}nt)zK(o(ceLgBFWrOP2Z(7(hRnO z78~uNGmL2IHIQps8Ti1^c}8--^{`p$KGWzt^M%f`ziWbLS@$^>-r3bf`-aZ5U67&N zV@U`8=VA31H}ZxfCCrf?lIF)V0du2P-$DE-jK!;rI%>tI$K*ViK|4Bpd-*9Kf`heP5Nd}Da-mp6|Fbj2~Qn9!TT zUT+oz3W~#AL^)AwM|-`o2C9pLUb=lERUVaUS-h`%D z>v)s)uRR75N15~W+)Q}j*CKNEtEf|+XhM{Q5pCLozqfu`%eS28V{@X0^egS>zE_^% zzE*w+mR4L6b0ehO=nS`5zOZBmWD^yL@8T&())MH>c9wA1bAvKa_tX{rtAv;YVI( z*iBt6f6=lF(mJN^Q_-iY&%rBfhgEy%EY1@3xSct3!4Yol(S`9iH9!N6$cKIa@>6i- z3TW(@nz?FVLCL~+*ID|h)_BtSr%Apd&Z%Vy%9f9n@i|Ip*3Y$T57Oz#3>k*|rYk)% znevd@`FO}a>TQx6^g;bTlH35+-hx25+X}0H(x*)>4X;N$OFhM#WEK7KW~s#^F6es2 zC#%-D?`5~dGXdnA-%|zetV6LDuUf<0?Ls`HbDZ&?zA4p__$}6HHIGBhxoGvzfyJQw z-^L6rz|C_euv{NeG0XChVU2qUr*f$GhC5y~Yrt!1)J|7emC|T(QszIZjlC4W9Qf-z zlsBcdmg%8s@v;g!nW!yuJ6bi7jr;}Azl8{7-FZj|cOV0=dp)-Xv2<`28&rGM73e8U ze) z(TxK%m)ZagW@kdc8Y(3i8{3vAtk3thwy4hKC?JR#kM zh#{zI9l~^%!7uc;2W6w(G)@Zc$#qjX6`cvc%+R!sAeQ{eI>$`o{bii})Xj*GoRy{8 zqpo<@b2gIZ%IdaCsK;qY{J^GH?)3vE#Ef&OBRzamtqc+$1Sj{1;6nJb`II*dBa3#Neiv8%I7%8ve5ZDgY`4q z5swBYmp0TA{WiIXG8W$w_3dF*n-E{%FLqhtq|ylI8uv2-4_f`GjUtVc|IKyVq@p$M zAwslEnTYum!kqMeQqe~JYc{-3E3{p+8Hx&ve(ws_qwfoC2V9zi*;WqnyG7>kDmt%- zkG>D~Jxc)t-LkNO#*PI)5Y^z_#wHgP*j{jH4!!I7C~}+?G@je61_o%UCio-=)mBxh z58V+n17TGKu$6q=Nfc%k1Kk+4v@v)hKIHU@uXaTqRMp-RZ*>tC@t2#$IA4LC;!QMm z%t8-CtZySrU+;El6cJT-#OOe^eTqv1UPPs3j%b|!=-bg36cr*PI3B|M2?5<&BjjF9 znBlOVndK_l@a|5#t7r&l|0`jfYAI;`fsjRf3)v~%j|qQc(%nG&0rwtiC;Uh4|7ou- z>Qlv~D~){|8*iK6>Mz|YF?oY>!)@I5u%vtM4t#57oXn1#1hC6Z$cX%|ZytI2AjXvR zHbQ!;m4Bx}`=A=7oIdy79rPAu_0i-hB|S{v?{J~x?dRXqebueYBs~Y|GKZuD zb(yrk>CSq?^75JcRuH$YT@iLtxX^D0*^J&Cz7;Dq zk_{<&v~F4A=9x0*Cm0)tC@^6zB{UBE+J@V{buEQf>6)EJ{T%Y)!Um=D8`pYk(lA-O zeC#dJ>yzEtKVJ^5%`r&XGDffwC#TC00Umc%o6@;5wEy0gEE90k8Pc;M_l9PCXKSk% z7ND;mY1X^ltyQ z10gvJXVCXLG9{W%16j=vz873<^oGWV&=;Lvt>Q{QadgFv-8gEIM$S3%df{kIn{Mqg zvTu^IRR66-0bHJMDn!)rWa-rNi2V?~Bd&p3n%yXCnW;JC-)kYgLcUsvAhjmn+m)i3p?>M#q}XzyS9O>!-z7WHitDT3{4xDV^|2o zM`Hid{&=*__4EMO=lEX#eDM22()Z!`KH+)hi20B2XSM0pardaeW6n7pw472#ZoJ*{ z$8LM6O`t)SK+e}Kqa=L&4Du|xfAXFNt*L=Lt01`lhz~!4y+`I@p{_}R&F?`C_Cw5eyIIP z9O_$d%^J!)1{tJ}>SNOd*mG5xp_5X7UQ73*!dd)l>_Zkej|j`e5yz$n->;V5p9S7d z#@)uHfJ4y4H}Wa)$8#~q*v1&tD754^|1QcS{u8!OEYjS_84^HyKN6bpc-$FW#SYNk z4!;4k^tPz6u4N@zs5ciJ_Q#!6XH+9IEG^+2bBQX3Jdy3st6k&Xz(0?bE%D<{u?=?R zqK4Jd2dBCRaS5na-%wAml*i0bO``JYX1XIjB=rSJf{nXJNO{G{jgybwczfMx(v9Z3 zQ`y8kj1P16WLuSgfo?XWoSL*5z_XN@9`X6kZ8bqD=K@K}IVuFz8n>EH1Vm%}n|%uy z-N)E_a=;F2q7fD&W-hD^S=V*LW*213JUZbXf3$A0Kgwh>eI7e8VJ?K9+*pq|yHhr* ze}0SejT%5~DmQAK=_@$h20{$DqO+2aV$b^|X* z!ajoJs^js{`CkYgfM_O?r4pVV!u>$F_&R=OfVUb<`T&lGL{}1^$S{2Yd49zhi z-|SD~V}8=K>9#`I5K>#%`YBG7S30F zpOmrWx9jzwy9&%iMX!X$gW4t9&79*wyL65zTIbzkGA~6m(w*%;i6*J9uh7>Ejc5g@ zFmwNxy#!vo59NJyEKL!|J3+Nmk|L%&Wd7Wh9q8fF9q=>F!VC_(#s!A;B?O z(Q8<1=48m4{0lIiPZ6P`!$%`RxE%N>ykkdQsh^wnKf0#RPBQOD&X+|xi64=4c0q~Z z7?V&bb4;^Lv%>zQoxTADCVv#P*jD^Lvu2{S2F9A3VordA$3u&l+^IUmr74qD6&r8I zosN$BYUIZMAk?x8l*qsW%_b)nb-e8rBumVZYka&;>sR@?u%t0l?up&<10Ys;w zSq*CzD5{e;$WLQ8CeywggZL%zJ9G$@vDOmQ8H5N%6WbeV8R9=tO#?Excxu zz!|7HC`e;s;9x+3;;g1I4Yb5y=KrgWEcxf19uUI#dvDJ=4UGZx_UAH$Hl_G3FvHM{ z>{Z#vefJhmyFq;rgp2F0*Y<{Mku>iEJKhIOtv6^qG?pJj%*+OeJgaqSb$kxp&yqP+1P0qfV~)J zLw{h)lu6QFr3r{xeE4QF5-Q zq2zQ=$r+SnqvXw=lDANjgAzo53AJ+^CDTz-*;Dc+O3WyEv8UuUl*~X$c~8mj zQId<2(w>qkl;okr)>Co-B^H!C-cwSE5-Um`?kU-el9?#Ezo%q3N@k&CW>3jZl*~p+ zc2CJxl;opiQcuYyl*~a%YEQ{Vl-!4s#GaB3D4C0r_@0syl*~iPfS!_dD4CCvh@O%n zl-!RJSx?DRD0u)S?a0*-T#HpGc@QP7JtdE$WC2QU_LLN&WFbmiJtYMwS%i{*^^`0@ z$zqiJS5L`8lq^BXUwcaKN6AAddB3M*E=nFo$=RNg*(iAgB`11Htogfr1(dfmyL|~8 z7UdQqqoH-~)JM6)BX|3r1g<`XXAK^kuKSG%Z`Puu7|+vq)`i|wsqqDHa<^{-@cel^ zFW}iINxvc?{mKTln}fH{qD~2(QatP7IVh`4wi>0IOpTkYv^~js)I4~*#*qjf;U6+d z1~v8@++}&L4@NNEr+EH_=UY4;Je_#LMnX1$XE>fTJon<6iDx06$M6*6vE$i|=MbJh z;CUO*U-0}Fo=bRsz;g!=51nNso;W;7c<#ZIjb{!X+Ji)Y_QBcKeGW#RI25{J$qH=V z^t)HC`U)H;JaWZB>7LM3;g*Hga30Zb!{bv}>q+}nU&f{r9vLryUWEP&^iy~nBGR!0 z=$ehlCj3Z%@|Y^tfYCN{3s#8&FoouE5>OJ~oj=?mnOL zkUc>#v%Ol_ZMA|5ToIzxgHSz$9xeyut^)M74ORqzu!H<%6vY(h@X!lU>7OG$R=K4D zUaOz0<<3JT$MB`y-~n$)TEokmai+58tZZ0$B5c<(hT4WXTM=jPS?G+P?PZ;~F87&U z7KTNVh2h%VqFxq;Pe>MqPvt!!akfudp0dU^>2Wuo-267|=CUJM>zkXe{t)ZVVI#OC z{J)&NF8lxY|9W--cU`2YX?w;9$~Fej814p~hl2?*b9 zgCD%JBpoVl;(b%CG`mw_8Syk^nYrM(c;Q3X*i6iGi`QZANN>km+~R8idV2|0JgJ*$ zmeWyoAi&(o@2Aa9v%)sfm1cpZJ+LhnYf0F&BS32qOKSjolMHwN&A~Y7=_TDaa4U2i z3FhITnB9<|)7L`J*PWZ#Fj})8sh33gCABriHaPc|Sl8vg4r?DoA0CWoqW8Nf7c$ut zIAL2r`-Jod-Li&m8%vTokX>a`c~EvpbiyA%ThzezAQL=XIP|1Hzz!t^_uU7em-C@R z*hjvn2YD%v#V*8*r92iyW0PKjpstso9wP>Z)!i2tS&*jxw z`WDn#xP-p8bMOT?XQ_j%d(U;uB)IW0&>3@%2K77Ef&@K0o__8O&i}_z+c4A5U)PyW z=jAq?wx00tn$vmY&7`Uygor0@#KoKg3$dTOK=C0T7p)NOX1Dm~PMX7|n}R1mhIh#( zWs62e`70$)knn^J&t<>iL!|{-ZQnT@UQGsW0Oug&`F@-Y%(4&aoBpz>UyCF})79R=;mc z2cM@vyuAU}ulf?p@w}!pm!s7`wG$Mu`mSA*)s=#Uc7kYQN2g+)p+8~#p zB+lWgFZzgET+$_t6Ij9b=)h_BOt)N8yFvRBXF=oH)-#^+a;m{4$29WE>5Zf{DJ?&Y z`hZ0%PhVWiRgAW1jK}IV27VY18;>!JRjz?Qq&$7AE3E{asUV*;7uF-^un*Y?-T?S8 z;#?LV8nJv*By17mV6E9G@in_J?itq*S5=EFf;bf`&>Tmx zsw?k$CPpgp@4b-NQ$#8rx+exdKk)jhtG?|OmY1x-^>|y7mqErcow+xbfm@)c z!EKs0vb~Pc6K|B!tYJ7|8185r<$BLFhndvwk2)WRweZ+T#pM&8RLLHkARL5yX z$_YJSxq+9PqhE)Q+KusLM?E_=K04k>a3-Bd!6%9lXJpVg5n3R=O8El z6LdlSFa99f0;r=C%!r~%`TW04N?H59x=WC2GWXYZf{(!;pU&KFt;hcQbPI6W9%bu3N&ZUTWpJZLHS(h#Y9uMb z`}P6gZj(c2+YoCe;{NJkneKp(ZK_XQMfqh6Ar6nZ-#}E1vyrNcWKDFIbQbAe+j2vC z5$}52cH1_#=;jCsneVcK zvP1{|wm?7rcl`Y%?kw6H#0Sd316Sf5-Fu`1ARQR-y$S;xh91xhFY)lE(B4;7!ET`I zj6ENiOuj+D&xY`m%1<>d7WJkdlq?+7pXy*uj{0s+(%Z14K1KS}aAixL8u7eY9r9ll z0_O=^-QsT8ImbzsNCRvI($zz5He zG*x}91wNYlLDvldUiH1WFSIh@Soe6-QO{D!%JsG0$TgN5c_)1>_wBZl{3}s80CuX~ z60rCFQvx=O&d*WcB8X=wlcceFv)$SbYV;lGi>l4*^Ix!%)C1lc$=Nyi&7a6F)ds0= z_1I}<*w2FkH$so5-$r`0QOv{a++Vp*xNBTEzk@%;kK$+Ym-%ZvFN_hE3NH&4!YSb& zLX>QrY=UfuY>}*3c3M^|`$opgljI-E^5pNx&&gf#+wus7UNJ}UsG>sguHv5x9b`{# z}?CXo2j?3yUnYzn`)t{uB(nz)V)+g3Z z#`(?#*qHV33Z-51%oURGaE@H8C`n}TwbrKp1m5RoI(Pe$*ki6&;o(Jced>*a>{JU% zWNjN8voO@c{Z}UT$Yt@ZmQ`>SVW__c^%I%dgYIU7vqupNfy8id3w_1Mm~Yytn34CC z@Sow_Zx9*`3R6WbeLt|BAbE02@XWWjo(V!C`K|l{$yz{i^aGuFL0<@q z%_o@$Vw`Iv8r8Uk13r>vRuI<)LMJg1mIKip(|YcVL0iHnZ1p|Fm^=D|bP0}PTY~xB zxX){4hy`#9$DPSPPBNE5be+NeVdP+pw$J>MKV5+wU8s`cMC=e)9jNe!Nt_ z6!o7*{V(5-lIoZKs=ns`QeP|8Ux@mpsQ>o+tX>P;@7@Q*V^xBW8VR4yb-1&(V2`W< zk45*>gW$!cLT-BxeiA=*R_b{%dY<9smA{PsADzE7dPHxP#{UQKtg%>=#S+h&(WEmU z%{wytmbkrxX2%GL#x3zKB;ZSQhw=CM7QP>G5^k}=f5@7E^ZpPxxLe{ql6~?0n>ho% z#Lcy@XT7+JXzY%u@M~Ox@#Va~2ej`kabX8@PkVox1o66G&DGPt32hM8a?BO^HgEN< zLt8`Ne-`-j0`MmdJ`>NFG_bfQnE5+n)&^nB@E1ui7D+IE8{&;g7lrR74rX=eJYM4- z30;&|yxG3h_Y8AiFF?yH(6XFb)@clA+5fDKZ+(54(5}=|FToxn{R^cY7Dzpum3sJm z6DMhrQG@s=S+^E$jXR&8gFgO@KAvSCUY~(J=Ae%+0{i_Xy`XOkLEq%dlG@Id+TJ3y z{d%zNaMYl-wUc|`AHt`h?Hy>lgzW+MIVI0}V~jMv^G&oT%c6d3Po`VOTD@Xy*M7)H zNtftq(o1y~{%TE5bo>?u1=nP_v?l(}t-gh9{`G#naPWLD9Nh7nEp+2xe|Ruo#2G+1 z_*ZCH7MsRg59Uf)kGmiZdSk-xr@;qx^FPnx_Z;vyq(WXk8NZC1~wKv^JIf^;*?zIty|BvHb~l zcLpdswy(hl6GM)~K!c{nWLWepSOR)p*(3pr-Fjdwu_L)b}?w z0m2=C@MH+Wc@l)TkdJzcghx-}4!tPJ8_J|{&%?M&dX2jckgf!z^Oy}|F3mH3zlK)R ze=qPSsDYC8I?dNw)&g@nI=1@mWect??*%7~>IsZ0LmJfx3CaTR^r(F|76Zb^0pTK? zClBbPy^3txv?8~}Rb7iED2oB*775A}3CafmWqvOxX+8%4$_LnxYqW#rqrEh=S0J@_ z-m^T^UY2xwgqP!umTr(~XyY%Q<=wWu6@RZ?j+Q+B2G4S~)mOmoHl?GrOtcn;);6Fu zx{0E34;iJMccV-WT-g9 z@J;=B56{nK=OH&{u1J0G{MfI%1$otwo^h+&6fP#6$_dz2x5Uq+c{ovq_Gk>lDGyS( zHPd@OGzys^FKZ2=k--1oPdk{b{b~QqH@(~x+&>Jm0opT{AP;as{x$`BL<5^4Uns`M zSiGY>^FH)@%fKs*f`0o>v7m~^ozfro5b4Tv=DNJ$-_>Dsbr{_SjBc(p*IC}pp}F2A zNz5K71B}D)7CRsYR`fwiH`BYB3x|9x3{Xx2lykAiw+dR<8zGFDi@iV?^LhxY`*Z}q z`4~H3uF2R`6+BUZgBQGZoMEt<_!U+0iscpHVO=12dTfol`rS)XjWs=3+kNYk4+zN# zypY0f^{rtYu3Z?@E{v&PTl$Lqxw%&-CG@oAX+ZG^ps=xbUCRJP z5uo^Q%+CF|2O<%VGI)~(cgB^D)e?rRlJ0>r2|8qwmu|89G1uX2e$Oq?hrb^fxfRsJ z{cJbn&kv*BqyGIPxe+Gl96szsWM=T56EM!Zu(~_pm!~K_3Z)x#=QE8N7%w7_1H&_V zM$AA!2cd> zKyNtzDQTLSvHum$a0qzC9D{lw3)-d#oEQ1u@D5nT!OCf_sh^Ab9wueciYal{ZqHIT z>SuBZv9<)8UwjrZa||{QyyMBH=Nw`PZoGZr*r1^O9&n%NEidRR+A~Y=*fRtbJYiJl zalbqbxmq-1x|P@`Y!&S2L4$SY+cIEJO~w0-(5cg1MfcHAJkMZnk#D2qrw937ZYrWf zgy_}}8r8>|#reL0))+(*C!IPop1lH!TSq%5YUcVn(C8*^IB0wAkaVts?c*V%Oyyg} z{h)vzX0P5Ls-MmUe5V~UiB1Q;G7;8xTk-x8wi~)*ZT7&t(a*IkR zvk`sZpapch?|?N7oWD-dzZd6!R^t2zmsI2$Y#P`HK=p=uBLTiJ%pgPTfsveCzsuT& zTu||26qjGL4k`&#@L%qPR${Pk2P9{Q5IrN-wy_s%eMj)R^Iq1s%*}C2y|R9re0@i> ziuFF?`CfpY@l%BZGAQ*ujXCg=_nq_TB6ZHvnYuBCl4!^b5LX=XZ<3~sgopRjmY>C| z(%tYwIawkW0i((jV{I93SNR|bH|Dh=7L@PewTEX#z~WFfU)CDFys$K(^n#c5qc}{N z@aV|)Y7pI5XuV@<@M>5_YjaUn&GszW*B4r{Q!gNQv)r{fOXk|1C44OayBD*n+L?KS zYg7F(+JD5R8D&=(e9kG)mC}`#F8hW-?nZwx*J%AZ!1y!t()*xyS0NT1Mb@MIjj-~& zy}o$Hbd^Kt?B;yl?y+&CSOvGl$2wQMDmzJB_OJ6ri($}Trjgs_rqb(`WyU;$KF+I#VMCxVnbcGYq5G34%1*PO& zi7(W!pd6m>=G0+`O{p-dBoCzwc9{Lla=9(s8IJLQ%@hNTTq~U5{ z@4vpdRjlhMggv#c$N)TQ@bcu*Sya(PwCJ8P>ctNI%Zp_hpzhi_-jw1qY-$Snk^X;y z8~AcxZ@Aa#DgpOf{sb3c*K2pyuZ7H@jbLZ)`DIJtr`iqub_;J%y~?1~(r{!aOe5eN zNA9dIT9wr*F6v-+*4w&$QhP>VOKp0sq!7NY_wsY$yY&VC|892w6UqwRYCyRNP*wm+ zUV`$G5R_cm5%fT|h!8=`RfW;&ET>T3<5abQ}bf0-y97VmLhzu|2H-g_K$?VVK21$<)oTKx0^e0hY z*`YOEide+S@DOkYGTSLs*ih}w7}@Fd|IEEm#S+e{}nuVL3mK$aJS^UlygrH1<0CjNRCo+8q ziZvJ?c}l(%s4iOLx>jwr7lot8k!3QHyC`F4a zEDB1qRk*S1-wMhX>GtkACAbPpS9)bpKivr0;S)>~-tmd~9X@emrw=x zrb`O`t2WW?Z>V#NPj>a08B?QQ5rH+C@IgebPyDof_zL-*wsnRTuV%F(?#^{_T%bFr za!MZf{TD{_eni?*>?Z%+= z2=W!aOM1OvOT}%+>f~nKiiDMZvDsfzSGaO;$#+K9IJk}*_f8h)3`eF9WD`N3iLhpB zM(zVuy;8T@rO>T(aZ_hCHf`6L^9K9HeC(tGXZ6bO#n0Omq4v)EVe5iiVarxV>TcG4 z>5FqkjBH$+JG3PGf#RrQ$1`6%6K_U_hz*6)uln{h#MDniwAq2aaA*|`iM%h|RGG8O z$JvnwOG#fL!x88%Rehm3V$5}C;dH){z7MO*bZ2mVZOF+%IXa}-`J&@u9XIuTXK+*- z5$AqST>;ixhgB?Y3)2^@JOVf$ZF_BH;mXg~^X?cvwm4Wn(X1c}vy9aTb5OWvymhA! z;_eSH%MlBVxnH(J5>h~M{(1LM-Va}RJIbGT_Kx-MN4!$aVQn27rK(rx2DsxQ74CRt zR%33BERlE05vBfv&KYi%Qghf;^Q7zg`Y3nb$Q90F<+3lQDJOj86YDw~yh=n{s4l)< ze8m^NM+j$q3{QW*cEq!fJ^SXf-#=UMG&H0v!3>NHaE3RZ`Tm&^>mFOT!zVK-%ndcU zh=BC9&s6OfE3hI{o$>?Rw7(VH2V80Q<<^XIQN-};>n|!se_5mCzWPRK{8IkA$;#Y% z*nlh3SD!9oBU_e^T6U|*R6;$(1rnDY-FR(dFz1ebV^sFCji(DJ<4#L~cl+t3DFr9( z@&lRp@}WS6S%s_t3YSWUD91YHQtIr;3K4<%!;EgTy~FML+jhzaaxhC(pNjePBR8}R zc@iiGieEhClbNgQbov!5so!e<>XqMt3NlKo+Je}=>dzBkz3Ugh3s4S(ZyRNpU0%vl zM|oA;nO!60<|$^GA!#K`dZaONgS`MQ%YnX8EXs?(@OL}H5W z9PN6$?t5{ne_K{RXN)VD9|b&5K!MzRg84AAfUE{>oxBv;K%_h=Ki{C4Gj7Jrjz~9q zZkWu3rG%q4WQLGEFGH?wpLjp=KKSZJP*gt5)K*`Ni$hij8L~p?5E1(cL|W#Y!_2M9C4Z{Z!C1xZ+eb?u4BJt2D@narg5y?iF_q{7knSU#eyC>`I6 z{!Va}K5mNL-1oTZm|y&3CmTlI_!FI~V=K|y*{<#Hz3Nk&iq9&3mySI25r_w7GArF* zbv4w=5`X+!Ho=tBKTqi%3A@hkpc7R=Q>_&QcbAeGuQ>Z2n+O=3hzg8&Uhe)~6Y4l{ zGLy_r;=oQ>c0~4PH@NYpF)hwdZm5p=Als5zFWh9)mxT821=vPS01pSem=T0~*-V0a z>Fj0sOb@zGrNl^>;cwtYKEBBeAK_`nEztKkMzl+Artz3NtARZk?$_3!PWOz9&%PUi&dE41l0dS zC*aZK()e2P5Os<}j%4OeUm;{eJ|RUmRwKUx>BPb?D|xWmZx){q)!l)<{>ORk2GQ?v zXqn9?&? zKXW04P>1@tzjFcnLa6sC2@^qAB_O%_gcGVy{ z-ddJ$Bsb2cbbr*5Y5sk#(ml8HcX_YkXJY3>co-kTZ(W@W%?I!^zVnq_;W*A=L_LHq zdL(njl~h{y%^I}*pt*8(-?}9G%eg97`gR5K04trevtG;TcSr^J5K2y*3p#^qu+|Qw{&P+R9-EW$8>B!oQ@d1(p}o|0%)SJW0{b^rrG`C zhz?do_+u<;ztNqvpMLmSgGed|vcA16n_!5EF(U?v zgJ2>UzQOK_26dz5dE}j9$)7vZ08N@5k;m+Hh>*yVXFJE&P-d~YfMFc^6E0o##g#Eb z4CaF1P2VmzR>Hmt)*Oap$d)qAka3{>Jj^e5h*haCal|`%VpKO95xG$NO)X1mamtc4 z7i08@eyvN-yMP$8s+>jHndspK+!Vn%yNcfkm!9nS=Z%Gks_n?y{CR3_40w4#mXbSv zEHb5JgyFO^(!GInq(H3UQb?X1(<5EKzTP$1iJJ@Ku}!N)f2fZZf; z_Zi^vT0E4)W5Q0@YM`9#GKr^s0>2;1(wU>a9*Pxx8}Mut2b|WK2jj1|@K^oa$kQ>o znG$S^0|RpVxdz}(we*I^cTxE3pj4~D zrtQIOxuEQH_e)YTR<8q0-Ea}i1aFKr>YW2woEdTMz?lum9gwF%w8tr(+V}cf`h&ji zkH|YQ1;}1fFv!(^CZejrFXyYaXyn{+_$TY4th|nE=Ti+U{^ILnD#XA2Ooko*D5son zS~!hevYDfh^>R5|qy2xxgPmxMQCeo{mhAF1_?Or`wpWvn(mun>EteXB2--=A=2c1cu~k zTto2N^uQ3S?AYKHBU2Z@ zt~nfLD9lzLRv&aN8I)5{vkzJ6qiy?U>ZLfd_s0#lJ7zg%=J@n;98yHSaOZC6i(S3G z*gfk->5Il1_2I3SO8+~2MxAzhSfc!5PF%Eo+pJA^tDDnr`wO{jSXi>mrnvZg?tFMe zm(6@0KF|6L&EYj}4J*iA7I$xQ)a9_$oS1JPc%r6Ql2NUd{Ge4A$qV|Kydp{VL>XCb z-XOVoYyler$=K`A|<> z3fOccz*i1dA@DB*=lNKB*a7w7u;KD{Hk~DKy0Ak{VszU-Z}#DyD#4uhd!ZPMI3y4fe zQ8QxE|2{v2qS-%-54O|YC^!!zqCh#aF{%#ZjTSk@1kzY#ATr7{Yqv)`eDwl}HkOj% zj@~o^V?K=gBog}Iv*y*dq2@l5Fc-Dc%Zv;EyrMO)?`&VJ#fppt{T|U%)DDhAr7H?@!3R z73nI^lTRkU5uslW^r1n|5&C98n#}N%*d^f!b5DTv_k?RDmXh3vgQ}`BM1)#v)?a(9 zj=n@MI;#7#_>m8hR@M1;S8d2>^2YN<&Bb7UPlWobh8I7l4#)f;&yobmFLjsrGww#N z1a61xn>3i&;QNO|H8-JVr25v4D7^V~pF7c~puTn^EJbLf%({J2a-DJyuT~}Gns0&^ z0M9P&2RT$C!cHU*N{3I?41ZVYh**T9s622g1(=pq9QetgdoWR*QcX#-+aRSqC zn~|ZRU(X3#-{D%iBDXXD-{e+wggDo9>MxJ|O{ zbrXaB7azbba}Lh=Kj8d7iZY7NLi^&k?uDtV5fc*r8@=y`-uEKec#=-)Ab$Q6@h%EO zE3wl;_({y24?_RFXfR{bf|KQr(vrj7P zORc38wK=@9p7skKsa4)ZZNF}&^%b0SzL71kstW$cj;E|-JD5Q@tBpiYk%*4x5tG~G zDJ$$5?&FfL?wha#raG@drb_lm#?pCpOY=0irF0kPAj91wxdoE00(({}l}n{dau-RZ zobdXd#L|BhXDV!Z*-)cI&s^Bbo~C&=;jznmcH@RQaEypj7lDkar}AvXFYr zX)2zyDX-&$X*(C4`Fuq!UZ!>MxB9d4_P4k$tBu4AN8K5ya?t4<7p)Z|^x3 zewZ7p92H)<@%F+~_eqo;tzha6!h5QBR!#Mm!`qvM>m;AqZXA{H73cAC=rxHZ9gZ`b z&iX$=FFFMH{8m{|-$M9W1N>$0z*n#-S^Y+{e1Xndb6EN;FroWy+YrAAh!*d3K}h; zGvPSmo-WkN8Y%ZG;(vlh=>!amw2SL9TkmFnu|z<0r?Vcu&%ZrPnAg$=cAey-xfm@@ zoabD^xg&vVGAFf~AE!V@U%@CeJ{(_^Rg?*uJwa}SU#T{_z7s9OpH!P&BX}YpkB;Pc zSc!w~k^1BD)g#(4$_sYieM_jV+&It{NGzrKnoEd896QuW(lp8eBekS(5&ZCymEh$Q zsD6RA57nRd#gf5lwe!Bb%+@LM{vkpC>d@6$s{swcy%cb_VpNvg3*PhagGPG>iVVBl zM883A1}|&U8ON|B=#1I0WN3|Ll^Irwl)zy<^E#&?T1`~VRQMh)u}uY*58kdqt}&HC zi7Z>HLl4DGv<@v{h5;QK%Vkp8Gg?-AZSq*Dq%`orwVGCt&^SF~-Cl|vH=1u%Ueht44Dcp|mON86Pd|8=n zv+O;&TKPwnAXmt*DuTbClV6ic!wr3AQzXMNrqw!%bk`5G8DHrUk9PJA@;@eR?!xS} z71=RabJng{R8YI(Pyy%moTK}IbPZw9chVkk)iB*sP_M){bo=nH!QIi#^CX&U^Kf4K zGzm4iH^p)v-MFjaOK+%o%c3#-C|>E}T_s&DYf-K z`s;s#dbwpeV0boEgM$Uu7!&8#o?FsW@3&!JU|E2Ai$nE35+HL6!IKw)XRc&NM>ANC zukrxT^r(xj+3>H6E+cFF1HL?1aMNhNlwxn_v7?wlFX{Hkt}w^CI)Q2zw&6>%yo%b6 zpFul*#TD91WE)|CZ3K8D!}FNCNtPcGeV<}woY@xqF2j3r8(|3bQV#v}>)TA$)R}`o z5zAVO`jf0zrB52Ga2o=rvP9%oxh1xC1*5Lqq^Je%UG=fjJmg~j5FIjP!_|8Y<1O)+ zhkwETi9Bb`QE$4=!7q;Zd7^u|dH%On1?imM;{D&i_sOCC@+|m@=U{g;8}>N;V1pBe zpOf%z5_k^UQxD@VnUTtLEqM3u1mvv4{q-E|-wsGn<^jrVc<**w%l3wIuVpXb+yppj zE_opekxE|5yWh3*KUQrgY}shmkA=P@Tedtz5K-1Anm6bDD1OtqY4#H}yyWv)4qYz! z_>|!+;~m4{o&ARnlP$eO@XSKu>siUluLaL+{5CInbNx}zTKp#MX;2JnU_<@y4_Al! z&h3T44bq-l8Jf=vz{gzl{>g`{5Xh;Xu;bxzhF*`Ge5*ZM}9L4k=A2v zE#mO@nbtVn;O!ZAKjqTxH<8bp@aOYRnv+}NOFlMYygA2u)_1R=n00&8amMVgBOu9F z;f7YW5msLDjXk3`MmU$(s1dR3y)2cJ)7NH?27bKBt*iQKUk{NwHVKlj-0df#k+MRRXqyI zoez^vV78dND$h`KDfsOMs0FeKUtp$8J-0+Gg?|Y=|kor5qZ}ceYgE zEJ2*c>|)P4$AzyazT9-tX^3~sU-<|f=x&a z_@nq#;2GrJ6-@Fmlg;Oy@4+^X?CI>Sv$oJWC=b#)tkAF0fo61PevoK>0<$%s194E@ zt5u4W0Tc%gv2&u_CXQfSM3|scBqtG+a$>PIPvi+mFIlb2_6kuXLqQZ@NKk%6%w}r8db7cbtb_1Qgby{{;0*Ujr9_E>KXHrM z?c}$vj7qn4TRbA0;^y>{LFM^Fho4A2>Lh{K?a$ zJgvbU1q%#epM~oGDEcr`{LS;pS|`mFa>}QTYLq&k`k4v5$`5SMax2V#oKF$7L+G+NiHU%l!4DaPlXe}eUh8va8_|^5`t+F0|SEk~gUAuU7N07VW(!L=N&#bY-h zYKp6*fKU%sprFvIU!)#Ybe9xxt%$|d-PK)pe+j~VIb;bG4YcYelrqz#P5$p^(z5J# z_YbdWWVjI|gldm@!pGsh>PS-Sf`fWbOC^P<6@LF>T64>CpZS4oZIxnh|VKS{rfK2w{Q7 zJT*e0g?hR#4AMQ-hzY2f4GyIz0X3l+qA*Tzr`yP9F>?uh(IJ=Q4#MMRIgR4%*%aEb%4MyqTe)4$mKM;Vzl6rPUmVkG z826D~>De>Ti>#6H=8iM_AKXN~sx`;rdfr)>T(qlKsg3J-cagsH^15A2<`Z{cer_PW z5>)D)Si9RWe?|wRUoFM?LBuiouG6~Z^goE>2fk^F^V}^u*dV-v*wu*Dh6^v>HaBC5 z(@$IxF7{)1{etafT`Z*BEO=CJIUl-JSF`_h=Ng+Z27Z($L-VKSox2`HJ-oeXlZn25 z0AGO*d$D3ch0oT)`Vtl}r!YeM`Td4VMbZ7_O8?{f*O2xHkpYEOt}QZHx|Q6$Wz-U` z=jC;b@!wk$P5TurC(7{!Gbd5H`1V4*QBNuVZ_9pwPjQ+DC+Y@wkYjaJAJ#Y&cFg(U zM40`pb(|jcldTH|?cRUsPvZ>OMec@m!E9##r2&)>sT`>^=CSgQLwG1kHWv0CG>#V7 z6_$gBQ1U6z$}flh{s@`MmFJfH6>{P$G=3lz**uk-)?WhM;UtPn=^i@Jr<`$^XQ++F zK6YRgosaGX##m3Tkb>Tw&|7erH2O*Zn;D}8U7mo@F}=xSGQGryqVEc=mHAj_w8nPe zys#N-i`I>KWYm7_YplOVaW$VdFE5JUN}#=e+PDt9R?0EsOUIv!cJZWLMk{{*sIJz1iZr$1INukSL~HrqC! z6O@|LW#1JPvqg@vLFa_d{z}g?wmac@qLlH8C1K!HLwBA9P6wR_RiKOWgj&p2D?+(j zp?eVeI707`c0*>xB*kACM7&mCkoRP?hvS!9md^sx2jpbj=!a~)6l<>cei#@9#E)OS zkq#avtD*Iwc{{p3R#l`;#;FtUp;2FQtIvPo5r9*rX^!rk17lvi%6(C)d86AwI~Q@s z{+-GtD$68wqt7;C4~q5BF8CG@aPok58f{q@>Him)-2vzm17#Hn%$* zB3qG_IO1I*_J3~#XMuQzM*czAasMEGBWW7dO>B{-SPj%jb;C0^UjNM~?4Ce*bT5NX z@MWIS)*jIrHrR5t_tvt48F~IUw7~n5$OT8CkD6jw-< z|Db2s)9j8UfwQykCbZlHS{~^={tEhyX$`{;4rxeenl3C`lhklQnhu^nleFBO(8B6& ziVL6#vdELr(l1Vh4jYqe^CUE-?n`%ch@r>?A!!GdH3Mm8$!W$Sjk|3yMQ6l0JKn=K zCA28tjcbVCeN%iq$nNDGk3q+31QX|-ASASi@SjHIUUVyfN;yg3az=p*^84ka)f)1h z%ie7n_RaU1dZE>#ac5+)(^%-sa$a^Hi@!H~=gYFo*{1RO%q0hWN`Zrp8{CSHAuZOJLbNRExg2Lu_uQJH+@9=B<#%-I)FVz+Hk{2ld+Crl8;7o3dpe@ zh-d{(h0^Z}X>593X1&@5{f_$M(1bXdskD)vgwlWZ7}HL=B7?j@(hDiPCRH_J<^CC` zHHDBQ?0`p&C!sZKa%pQO;BCK)kba-^(xuuwgmi#6}3zWSy|h*~vAOISF6U0KC40WRdc`S;*|B1c6?J*EH@%I^`EIRMsP^99xg?kAic{&_`y|e! z>5AhTE%ohx>Ebo}B$k;9B+)YD7#XTL)?B+x6?eLM&E72YZ1qWXmszU_jApBDFze8Q zKA`N3DfAv#(`w0bH`gLYL*Ktxl*%&DCju__&qGVwnrjVyGvB<{P%}$d>L`-K{lR1x zi`ry(-(K-XO^NVXw}$uF-?cb?~&*EmK);x zp+SurMw@_K_eqKnjodzr+*bo5HxzAe?ETlsoeTf_$ej!ij@-UmBll%EI&#f57c9B3 zdOGeJ9I@Kyi0zks-F7a@Ck(U&RsD9cD@I4Qg z^Q^ZLa)3=v!fS+ftuGcSP|J_Xk}rH*&J=ncWY_X)56hFFRPhy6!euaAZNI63WP zTT-BTz&Aw1vk|V5$&WkF?p3@?v*u)v!Z{&|#vmAc&#f2u}?+#!X8h7R#l;x z2;ZBLBbFaMd_^pLuWyei4%v_YfN#x-c=SHLBO>naFNF>iew(2G^#FJRA>1b(A?aP? zA;WtMB}FOx)a-yymYwXb34d%raazrA$y;L9j*2j;+y|kHZvNU z9gYjx+-PR(8vzp^10UG2pf}XRhhncb&Aj1b{TI2p`9^{FWH`$G3I#ifN~pz}iK?|LpN;0+ER{y0ctrjP6%q$rp|L z0yey#TBL7`!izq(N!>!_W;i%+vR37#lt;n=AN&P*HQFJ5MH1Vna1R^7zMNW9Zd7>7 zf%T%`Q)}1;g@?)iq!lv@q z;eQEly0P z*h50IT5;;5*`UwkwBMW&*cs}U3`vz75q}2nTcYQq*?ZCMJ2C6;3KI=~)2G2&NI9?G z8~ZMI5Z+k(m$q?`?U66Xn7wMWlG2*PXM~f`QI420iQ1^*583C~k1B)&crED*tAyNv zuio@NlVCr7sa7X{^CtCqYwgE7VBe!SdjQ^-xFk*c2yjT7YYtQ=v@tnLz1o_sjwiT> zU2N%^k*?6qz~Ru%>pLyVZ`N7T%+1w5X0BM1=GCpKYr6@nDtzgLF>V%k+`1KN&%bsE zt}hqwT(N@5JMGqZ4K+<`U|o2!xn{)*`jUK*b<~o2mUfv&bTWbVDD^_*?gw8WURgReyA6H3?t(n64!`@;=XZyAG_` zGx!x$(N{3eZNPV*cIh6m1N!j4xwT72!?9N(<`Kla;dyICboWpOOMDYpei$+!1>1C?afBT;Gi1Q;fb6B)|RER~(2fsVonoDbX#4Qn( zU_O@fP}hcBfqJQHT}O@a$>!&>QXhV@j*9J^l`Gx~#`gr{{vpWZ1{Sh?K_|IfmFi?xCU9`jfI zCxHCLJg5{Df(lk?2?6*T)w5VtSA*U*xCu38c+TLf_b?>tS@m6+(6_#j?9CA z;C$^{{W#yZ%YhTe6wGj&yb}-e1*5;^-qV)@tPNHkNgl36TcH;e{*4h$+X=%6FV`}n zg3~MfPe$x*pBaXF`GQ!aQTUVk_Xob@)8XsTTCyGZcd=e};>W&cjI8G=oQ7lYh7r&m z;7z2zJX+tC2|c=1sAICSlAY{X%#421$BsS#tDyvIZ1GK5 zott(v$*nk}%N^zE6yy7{y$|FjyW4ZqJ%&nyl`*6_`D&$C3k&KEE_T`|Yo;>-bhsEV z5Ol53#IHFu;zbL0jx_RteLtF=INWxL84aF=q6lZD3CV^ou~||VT=%3}75=BgD#Ow; zvnHwXMBpKY(RD#?&uD)Then`vU8ByAxuCM`YR#(u1{Tso7>%w(-zB~rBrRyBon-%y zfX@eSsd5|IQE!Ei?n$ahM#q!2D?=0B^9exxv?PCgI80L{y558}M5BRm? zb991M4-1!NK5=VsF{}${-faiEH4hy1k=9Yx$vA6i^?ZvDKH>kB)*ifow6RG0By6wt zyB1>}Z3<%sG`99QH>P?Pw+wlg=IQR;a@Z&E+X3^m!X;ihOpd^pe?4al+UPDuT{Nn zo8};Ue{SOTLyDf`ixUFcSkh5So45cH?nKPV!+qb^wh1aft9;ha^4lf7X{f8&p)so6 zTH&(Tf^%pTH=ZQvT4?ncOqa#i5Nh_H-P{56fO60bjQ^X>VZ$H0%T*cUNF!<@r1hj1 zlVj?ZX)MmDIXe%f^8S9FxIN?(fP>}?l?iM*Qz7CM#%QjnM$Op&2unf9xu$5X?!)^@ zBY;W>%eBfwtrp&@E7da}A!KtAecN`)D7On%qH?>Y--?OWp}>>?Tj;27(}gmMV?Hc- zw_nvN6!0Hh+qVz%7+mL~O@>r=OUIX^XW&;x1~ zQwfcoGpN4`q~zeT5LcwKhsO3MdyZ^dgO)1u7H6cdVt;aOb9fNwltPddE&SoZd}_4G*rP zaeHT-Z{66(9z^O-E_dK;eebE{DwB|0(Fs2<#9h+YpO>+kGr*Ja-xKA@90I<<;8~vd zF)@&b9Rq*T0X{$RYKRX**xF75)v8nU$t4{CmuL{#`4NP7iGPw2gBmyCJ=#s+>YM$$ zH*vD>&O-y7*HPf=M+`rS>-+cHpS@ge(A6^y?}E=o+IZ|PvRZ;}e81ND61*DN z19sHLKsKtzs+hB>qc%~Fe-N=9YiC?G3D2XKY~hYtE6|rFz;_?5noeL!(tF0EB}~qx zTC#xu)j*9u>n>-9!V>={F}|NhX%t3jHb&{mTQwT8DLz+^w>}`hV}zH=Zi3^`Uq6)ID&kq<_|7E;By|g18oD%_9eCaUIAse{!1D6%Vq4ot&BTt-};C%?R1)iQsjF1zvL>H zbJgCKYl7`FAB{tb(IjMe#v|W`{%2i+ff;*5iUIGxp2--TKYH>b{u6xjzA42p)PAJU z{*TvyJk|YABM;?Z8WL`si_si~at=yOx%6$2U0{}f9GZA(HY6im;OOD&u}KpfG^iG*yjnu{sYK`j|1Pg+{9}>$M0{Ullm2Wc9ZXJ&lim5e!{4S z9GOOLl00(Bp5_e`2Jp=W=Q<%pJzM!Kc7UJ67bBxERzJg7Z9*&h`wsla_#Tw8GQCcf z;f)PU!v?u8*oN9$W7Qtozs~I)?7=M0V<_ir-#`!c#>qYS=>O@#w?c19amw>S4R8sIXPcPZBvXFvYa99T7$_jqU@Zn6uPs_jtRou zkl!n3c8R{;vE@&@REAf2X*?DU)Ojv!O-4aVPBUzE$gyt2hDEK6G3gwQNpwU4LFCX{ zZ70hJLp&W+>z|5L-b@z{yaGP(1vfb7b)mbxTAJ-LIzR26(`{B=5!UI*h+zZmq~mUj zC(WZt1M!J+ydrJnzr~xGaRc$;Fy)`cC;nUf31;j-{7-WH=kR$x?B7y2f!!Xh!38 zz`LK1L};E7COhdX{14)Mn4>R2KAVR5=)j&%^Ok6-KMZgSjq^jI80i$1z4_J~;@gnV z10lgs44;QTNzCXmw$*xQT;Ad)hT$nBeSn*&a*wJ6En2O`Jj<*u^k%m`-_k8U-J5=x z$x#HD>gV6hEzc`g_BbC0R%$Q#V(<27>0CC8ysX~<#@>-0rs}VrVu!&6Oid|<%CQqC zsl7J=^|K$>*ka)yLIa!8m`YHk)$m%?J{r15p$DNmJ&n;4Z8d0vcM$TlLCpHXYu&T% zpPM8odOm(!1-ffy=sxJ3Dg19q;|;KRk)E2M==s#H@V^F&VufFl?y9=GBDY-O-y_k< zk=2L9UqqtR<3j5~>mF~YMr~A_nP-iN>w2rK+r4?fFVo-*6Bf7jDRDAln>6raJR9*V zd-=i+-zjPR1fg=bs_c6i{esE)%eJ zUhSI>3rP5+f|TcP;Uep_iX^%GyFi(ixTc_I3ay#;h*;Fi7aaDnjq6+{;3S=F?G~r@ zPkL|YQYsf%xj_^JY zodKjB8iNaZkb|^8an)wmK6{86Lz0A@LZiUH%oJ{PGXawZ*0m#Ol$ydnUrTbF^`1@h z$)bLUp2wJc64JQTIS+aHrXj{4cFkW^D1dkH6zqSyJ*t3)sjbl9`7u0qdHyaXA37F@ zBz=D-E})5DDNrf=L16ly2#b4Rk)k+3<^QjTZ(23`lxITy;rg#yw@8aqzmS#|sk-7A zx1>095LVnlOKYh6`l7PKJ;AC351Y3|s@B6J^NszFRo&1&cCrYNPk zJ#vkT!iQXMJZu*3DG!SskVgR_;hCTbp@!d1HfEf6>bzXXMez^4KL<7vkn4a~V2X2FDYpzGzUNzAjj7@bzH=y}G@``_4*z)vtFoOIPK7m*F|(b{ z?hH6$Q>V5_&UIJBB>5zUQ;MM;eYf&Ml1eCg{#Z@r*UBv&jh22pQ2tq;ESYMJp67k| z?$Db4pl9~ePGOf&+QRDh2_fKS(oSpk?{dCrwOpFflwdSppIoPUzqCasB+7f>Dd61D z9-D|gwzMS-yn4Ryd!NB!!N}?ARypS3cSPMODb{{U;;P>XBr5qr{_Lp2`gSeQ;1oGj z5=lkE;%|F5%OxGeN}!Tn2p@wN?Grv=E(H?#V;1ImuQL&rgRev8G2?Y^#-|qZb-%Nu zFwV`Ni7!lW=N2lwj}$80zbfS1W~{->&IfAVt~u~r%t7A!R{i(&`sXwU>BRGQ=aSjX z^>3W>@z?DZ{>^k}?Og|K)EeMI#w4llPJ^3D;ik5Eh8vXh#6iLI{cd{$FJ8t@_RI`2QwNB-ht z-Sjr&P#$(idtTD&vJbFV*0BKY6Pk>pP=4TQ)?3eGf3_<_FpENbuX$9(5O& zI8x$IJmOD^PsDFRPx&+dD7TmI@0np|9OfV!_zHaZw)8Jyos`6Ui8dazob_n1D;)E& zGnjER&Qm=q<$9czobp)NW=F^BXg_&8@BDsUvNFW2>sjXOgh(P^_*__zu4Qz{5Q}#Kyi4udCdCfxJ%S2>c&3#SNAM+3#wR zkXv0L08NGA{RjK)BVsGe<-C7&UkUaFvtDb6h>mcst3*&%n6Gn|e~4|pYTCax=VQ+z ze1V6d6GZFft;%hO(j3^?N547$&8kH%Ry)N0X->E337Q<;@bNg^ZWNSWeJ=0b1U?Hm z8-{7{B01cY=~9A{X7gFMu8{Mvr4%+@kG2Jdv+(k@zehY3-f5dyPg=%I{uk{;dp%H? za%Od*6Sk-ZoIIbd11GX@vRhyHGxr;p-U^gM{${@ZL|xORO@&L`+?l$)NpzcGNvn`BcTO-cs{{R#ic)le_R#g=$)?lhIGJFT7Ohc){h6PqGiUttWcI)C`@5 zl|aZ}Z{v!J!ONnZc*CYr$1xY|$=riFJ#ptAwoRW%7UJ3E(+#`vmE}XJ~yp7hS5Z#9OtyEeiMU)}K{Qbf!5gF4du4bLy_a2X@&dYFjDnOqRQsR^Broo->kn z3K_sQrIs%|e^=#QRz+aCk_84=GN>3$KT$tA(%REbHw-P`6Mg5BQU|y<&{)b9CZOki z64Ulws|7mSrP?N;$o{@%q?@$fa`8p^x?LG4}@z>xOmSVgwc{dealv-e!`kIp& z1I=su42g@6HT|}*G&yXTHBAo7s*f|?dnQrF<4mns=q3D1;uoz1ADH+>M7I%N z_zPS_+l>S7_EXS(g`fck?eJT01|fURLYznL#<_SU=)Da{lX6>K-?qMU>wWq&Z^`d_ zvm(=bdwbrnzJ6OhUzO|mnswi;e5y0A$ockF?3Qh5_g3!1>0zdqW*b*jBIz;iC2q3) zqiWkgra#$&%$CIyvzPyqFyIq z0k5I`JLZv!Qb(c#cD0)Mur>sx7H?=f0^5;PLo#ZY4DCE-*AVSW>^Oe~`rI|>=ao7x z;En?qSX~Fsorg5tGF6&WZ(Gd%)6R|BS@5^;kJf9VvTwTK!|1&K`OVhHfMK(+k}EF4 zd4+*K@q$XcJw6?Nq*QwHf;9^=FM2~KaICEr-PtS|S4$%#-gtlHt-kV=~3|P!G ze+d_733#Em&*Q&-9<>dl`A>6y%~bdue4NuLpu;u~^k*^?#|#B6N^6AH2Vum}no(m7 zjjqhW{LGP2ItTCN+7yjO_-I=^=B2^r#9#9BTpm96y$)J>#2HCG_ckOxm(yPczxr+L zIR`8=Mg4CL=%tO~$lt<({${3+$)9;6{kLy}k}u`B3zyP=ZBbn~V2RvJl+(4}jQ#E3 zTh+d|EvGzjm<=N_lNg+{e+Parovq0q+~B#I>P&Y1wOIT4(8;5=;u|%~nfvQQ3c)pR zp*!Y`A$O5`Mef6HZSF5TA6T!#!|X%e&AH3*z1WnS=w9vpG*<4c}%m*Hu(Qk$+DQ51`{`e3l? zhI!o{?Ba1cW>=E72;9WYIC(LnJH@|5{Nkd>HTa#X)M|AP!V;g^4f$K}nph-hat{fX z3*ZH`#OOKynK0FkdmUIH`?MZKixOdf3p2W8y{bj|Kb-%)NRdI+umiTot6`yBl9=?D z#A``RV%JucqUkP48=r`k$aHOE7D>t3yk6r~LA!+YtGZOfl1!>V25_(q0z2^VrU z2Am)Nb^A_jv6lDJ-FWQ~t=iAC{DiLDNqG?)i*%6W052Jt}gNQkD9gP zbrZ1zt_d=uWA(A113CXa;kc&QM&MVgl*XH_N3iGe2K$VW<%+H^__A{7tt%U(AD-c$ z2b3^rxPPYl$JU#z@i_6nJEBxjVCM)xntg4ALSG8}kFKD_s|XY`=2k}cz4&sN_JiGHO`O=|8cW$ygt;?-CUGuO@ZscfMR7_pfT3V-~++$M#v{FlZ=jtQR$9v3&K{5wBIxBga}u^Zlsm-KaaUY z_u07L68@+7dM{(h1nxNy+4Y{VF>E9qI;gUQ4xbl&SceznB>ow(^(3FM!|qszrUL74Nz>!CiW!98If5RL-rRT0m8 zu%AiKH~DDX+-~uY(r)O4qufZh_(g9J@45nemm|_t^A>y=NE4OAs@(QT@^Kokd9SmO zu@)fT?%-}96P%CX+<9`(?S{V$a59*HXv7KrJ|^CDqV>8s0UFJ$p28_U6KMR|;Va@p zq22H_66d-ieiMn7qI3@@`VRFdh_K#>=#sWdJyQK~A4m6YL5Ua!BYHHK*h762QKpYmLx&wE50mk$bs{2;V73ve}qh!p47%Rpx z@=uZPr4ju{pUTE+H%q1FAH@1z_#;E^i1^*7O#3LJt&raYUTy|-o7s0&I8oma9|PVf zlRMYLAB=BMwWJ?p_a!vk5Wfgf=qyis)AidN1_Sc*sW$CnS@TU)wF-E!TE8 zP9xD8vNOEm+VIWR3zEk9Jv8-#;>{qnXR{}MZ?fU@b!?MU8n&N*!YK{kG3N;#%3cvx z?_~}A+J12<%2MyW2cz=6v=pO~BA%r&ua5B`n-yymhZsFVs+n%k=`*Cod3tZ;m8xK4~l;bF}c?~!&~$fPw2UW z{oh%uwL5*?89`P zUo>#OUI+S(kg`P8QOIvDjbJtH*%K7*jbGf2W{d##F?jU#80a@>s8- zg3*5mK7K|^tlTqGL(FKMaDebYHsfnch$>nk#bDB%(qD!Dkk_OnU^#G}h&Uq>=XC;mKB+PZ zJ(grkt{h=chRi1!Po#y*w9{GhN7#ojKZ2jf1eJuJGZkmaB+%Bsh7H2YI8XlN|In+0 z*o5|@ci46v$^x?Obn9C04RMsj7sQ+pP%-R8&c8Zzr8QQ6By_!-2X;CaN-HxJZu;Ak-m37%TRHFjhE?l7^`**vR*ycT`Thmy6#DMcd>~yalE-X;T|do-qv%8IzH`*t z`a_pQMQ^f;Y`s>s?IbFpdZ#U`hHO{Y)oF+#oP+gre7kjfC0mnPljn*Zy{hca%zc&< z{*`rGZCrJB&6c)^XpPjkHbH-E2ao~ps!OllY}*XfmdzN=%^1zOm+-e{vn`|Mc?me2j`v3> zc0N(jFV5;!^|+rbhW7X)r@KkNiOb3#?inH};vKHM4QpHzB~8IZNj06>F;U{;*&SEw z`JLR3H5K<-Grctx_gMQyZEuw~Gk+NJXr?p98}1vA3+nEF@Ds(%+fFZT~d0Btg|bSx}abDe^LUpt(5_-QW4N9 z>Y)K?w&hzh@4usho7gX&kWve7dJ@6CzaNPC$@pCcNs_FsKPd%IixHZJ-v#&%%b^p8 z;Hd(k!|*#h?2Lw%49C+9gl6D(S{Pqod>12AGVxT5&}{sUheop;I(Y=12s0nr)eLb| z*;u5Vc3B)5-hWJwxXf^!Fv0sh=(?{#0Uo#{MzJ8tNfKZEXp-0vhVq6NLM z>k1-YE%v0>aFL$vDGmZxS)rJd(6!3-^+7+8`Dnpy@Gd8-T&L3 zS#tEccxUf*u|kUA3wjCV`o$k3-+?v=h%ZS6wroeH@T%+60);2vmS2(O_zP@~8AD!0 zrZ&!*3$(yEJDnfX?B9ti`)D0^in~BBnOu5Mnlnx3fn9$^YzPL#AEi-1lPGb4LKb)S zk01-In!R%}N!N2;R{dtzRq(8h*wt8r(XPe$=6@sAu3=cQd*=+Z9S4oC^yWJ_7sXwr zGY7t4D?y`YI`V;Lk!dF?9T?1?lpH5aC&GZuMxPQtkMz7~ub{CaY*#w_SP)0}euRgx z|9<(*U$*^_3cb1ulJ%eA>>x>e%W`}jhfA=GtXm*|AI;cJQ$kTW`d!w$tZ#VlnmZoS zq^Bm}EY$PqS|%qTT7X43BxZ|Lf9F_XMB8p@+k{1~d7z)Sv82)Vtdn-tzTg%-1Mz$6 z{lVwpM+DnGc2}QgPg_~V`s^~iy-oVhU3HsOm$FUTG$AR+k-_Mgo{#NUK)HU|#W42= zozld)>Mjj4se-~e|2}D=6}kdzWA(k_T4vGy@Xd+1P28Kytsq zmj+#9ik;K11dYrzHCtjlY)b;9{Q)rynkW?xs(&J9=Tl zQ$AS_1p31yTPNB1pp1g#?XTu!h@Z7hM~J4K)${IYxQp>{`l&!wohqLgr^>w1`@AKHA?<(wd_`Vug{37> zZHVHTh&7bvEk-QoroSm3;-5{h7F7(#*Q>Ud$(@PyFdo_*c|ar{S2-T(Cws@)er(-q zfsc$GxSaX(bF0#jiq(@9RG#h8)=WE6gTJDjlq>VVrc{$QxKp2F`^ZOir~*B%!z@%s zWXm-Mv8E~23))7~sm=5n+6Nye1MRbYB;ReOIZk|N;^htUpoxb)$hRY&9?gBCABe|C zSjhd@4~R~hllCti6XIJFkBsEbfQ-=Iv!`pSZ_S);J|k#w=I5epE!+Gq@(MNPE7y&SLo;4-g0csW-4?q%{d1nmo;BUkxn z#y&I>c7A-mMcn`^0LZEKYyzjH`f$kaXY?;rOpsEO>n-d_wn*~T)6;^ZJuS1k8=c|$qB>(5=lPAG4{TN1VRUM>-Mo$5W}oA*J7g3f$&${oK+)x?$_28HkR z=WS9o^5ZxlIxj2#eSqQkPL79VDzAdo6uiT%^eFaGO?O)UbT-Y)k5hXTji~Qqjh6PaRsQ(6WZ)I6JYk>9eh?m zvY?8i9$Y}SG<>>HA)kP$zHGxqa0J4zf)RD<#`VC_`emNDS;|igDk4X^V6NSI^EZ(oNSE zDTLoXT>U#)Xs2XACj1y?!e{-_-r9JB`E8Y7l5s`-aj0dC6%ufql-5x#FN!~guz-c^}-gZ4DsdK zgp*sOIi@Vs&}vHa4mrVSzlCnyQs~+#?a=M)R-@d-D0hiAGd>F~yGsinm8O{}bFL`@ z4aqIiJjBjNXcd0%#I+FDB3u=Rwnz*1vklkb6`dca+OesXZJOjs#hV;jE*@VN?U!=t z_h_p+(=A)1d+B#2PNQ0COEpSdVPbK&5@oHz^#HC1O-{V=NoI?*TFWG=5WC)#hmZ{j zS?b&({T#WTFew60F)vkQczL|#J`>)86gD~MGA1>ZK`WM;>MJPU&ya69@>C-4y~uYz zc9V>Nywyvpma9ig-zeZV!9l^?XQ z?t{WlK7QN`&n!LJnN2}^GWCka|Fkt*G%`AavWsACrjO2`QAIQ(wM9z|>#%mBy*y}L zHWDMM<6vcm%Ydu6h9T6b z!V!BFe!-a@qq!bQ*UEbr?Obg98{d&W25g))+!())_QLiXwI6KwE{49NFEQ;YnEN@n zmEmp7iWk0k9p>-P(`F=I@N}Sei z@leUfLR~JX z^yj4eZ1+`;w5LH1u9Q6kEVC|yq{+Zg2y;EF?k-u@bazGSrNQ#3tdvXh2c(-!cYK{P zq^aH^>2}cmn&9ac=gaTT6%I z;*~J{{SQ!IyoGcF<4BaY^+}4WCa_B3PPP@=G7`L%vDUiOM)?dkEy%GEo9un)pSce?D!TPuy z3yphShJ7$@tsM8b^%rv7ze;>qew)3bMt<8bEA5!`M=Kj|~Q`z%RkRRKNwwH_zdNYSy>y0F;%idD4z`%e zL~BgX`IBR&R(;jYWW3PUBM3}!#i|tqnlcZXS6xJ zmwqRpo^SPTlYZRsqE8*rBi(~Yw^hzZwWz?8+27}U8nW-H*xzPhP7TWXmx9*U9G*uNm;quInM;bQg)K=3m@>V8?$ zF;$&^ij57##6qvb0t- zJQovEo0gV$fUC@VabFwCy|jM`m2w+kbE@)2-%%vk&`+Cy*r+qD!f6q> zO{mpMtcwy8GW*!Wu-b4|HUM?CzC;MCmhF2ai32TFgTXB<%P z)zDLpcaO8`WSzKv@uy&}%V;&qI&tU0a~jmb7z4?0cBsUAETBrtbL$OpA>Q;C&=}hC zslvTwu?T09MnIS2g^(WS#klK3tPIu!JfKEWz4%VY9h3cRfBKtWe^00}_ahzBcC*Fr z1oY~SH~##aP2bae0ma~FVFN&O4jp|ILKuMdi)+z^MghQ++IjI7foR zBj4GxZ{20xx`UULf!OrQG)Ei|1{m+K$}~H?B01QildY@s!8h^@sZ6P1C!|yppXi$S zm%bn26FDNj6hVs|7C*~n+BM+G6F-mSyU^P)Ujc9E57=)B8`e|}-cbyreUSPKbtj%4 z@%i3IyymC|lIfKZwcHZuCZ2(H$8q8{9|wLLP&Z%$Jk7*tmxI<;RHi*|fK_CcA}c;^ zQ$)OkIK0iQIr=U9w`puKx#{+}Gis|ER^~V(hH~2=*X^Tndd0MlG{>)Ee251gz*>2}HwJm|T{__>>09tDBp-dRNIt7M zsz!dBO9hJN{$6?q>Q}+hDft-n1-*yT(z{BIve4SPBHk116Zv4FjTyas)sJF!FhRev zEWhG~^fR?5)G4P&Z1@8Zj0@H3(_^d;u(?aY(X*)B^$S^V{oV9<8AGIjGd?~_|Zf8*9OxdIc~t20g^2E zD_@4N2ZJnpKON~$utszjf!C7mibYEmy*GVD_+`*C;tJNcGv%y#P&QAp0~tpPd<|-2 z${2)EB+7|l^uh_wNyg!_h4!MnMJ*{?cTLEQK;(;ojRW`&h8+m9C7lt7Z(0Dp_{Z3(#|VcO))&6`i?5HsNy ziT6+8h8UkI)WG71F-``ir~z74G|Nq19o9pt(Li*aeWds4LSWt)Mth$rRLg0vxihUl ziOWNb0eXmX%HeX#A(f{Wr+QQ65Sb>lKkL^jlMu=QhxD031vILtd=_t-_E3(UWLq-7=oLn5#u|SB{hNt?HrVV(GwPpfO;Blsp{I3~i)(hfhSspte~~?` zy3p~Ob8+?Jw#Mi5ekYfzNR4l-YkY23tHp2T8tdk&l1>k?H9mKzD(O_LH)Srbegoz3 zo)qYgM8sJUZN0NK**`uh;ISWXd@fn1N3LiYF_m|2j+Uc9Ih#~nr#V|=eLB)hKBk;8 zYq6#$Vr|o&MB_)}NP9Q#i#}f-XQ$ujn4X|JV06IF4CARjI!Yd|3*w31LoSjQs)0=O zj|eAZSoN;gBz5uy5f*)38q*8n%e@M3T4k1cCu*&7Cj$|psWlDtz2O<|O|pH}n&p6& zmYauuu-_LC`RkeR5572C=0i&#VvB&0%x$t3&xiVw1*T>6fMKm|$If8wf>VF0M z5$wa}TohYE_s>-d2FGUbEPoXLCz4}dK2W=tVEu)fF%jrU-|#7fyKSTqqnPlQ+Vg6~ z=_OXCt33Id_(yq#`r*Un-rBuFtm`M}buE~`psJ{*wC0;k#`wU6;+mqG)y1XNvB0QTa=goJ^KOI>fHX;Cs$S zZNwmJp*c@uGPu_et{;6@6c0sph5l~(7cZ7%5hOcOU>t{mM@)K$@Q5Yc;ZPn+n>%Fw z%7;vjQNc~vnY0r2+kTVdTk!?#JTZ|(e7Ds33Qs~MzLvU_>Jj#p55?JtXO>aFt92*P z)-s)}_B?P7&w%!`Vhu7w7_$=Zp>Gy_-!8it?UbY3Xr-_-bmIn7F#LSNz)aZ?9-Jxd z{Wp9X^!7oE%1ww2RN~!XcDfIoY6iVXxLefL=TYWZ_$p-KquZ<-1FJslmBF%+OD#)h z8K48^T$^s!TfY_mU(hmgfkkIqFe}||)@38)Z^3LU#eXY)6@>ijMsO{#mLgR*R+ukB zjya?)&1%+h-n4-*wHnxdaVd9fJB=y)qt|xF0rPc#QGqoU5ymGBI#}H z^dDfG2|lNm5I(4mjD|B;P+wrZ&&JvZ(ipU12{S9v#$!*5mO3)X<}5JO0KAY)J>}s!_T!+x?Mq$WTjDfS*9JeI=}2e-hbXcAIjqYM&n#mF&c`zKHP; zXXp*JeJt!j{wU*lQ2m!ew^x01@Ete8P8aoVqg-d|UFAUUp6yi+)Z=n^U?&2;Vm!WL zOvDOn-@79~Ma0vS@N*Io{~j^74f?61l{s*a5&afeDMJRv^sk`rt8Q$-xPKJJ-ss43 zCCDk-dlT_waK#R!`(1DJyOWGQp8=X=P@XZU_d#Pz<4WU8V@vIlpm#@WId)#0O(hts zli;T~6pXR@p?he8M?0JgBC8F?YIsw&ODLDt3DJM%XOs--nb3ONYTGtH%Q4Zhb>5ZC zE3HKPD;96DojA1D(jrU&hS?_T_u_Hsrne3fqIgeTWgT{+I$2MTd{1OnJLQn?y-vg@ zdz|xl1FR_|wp6PN!nRHsfRT?dN^d5Ld=}$pK5-yjo(EbRh>wHbj?PrtwjP=tjQ{yy z4JbOGy$9D?*9chKIB_ukkDb4?J|yf9z}2VtzkMrhtDu_zRGsRT6{{-2sj0@fXI%@< zpl^A9j*<&K20@wxsk@4-d-4VT_nP9vmZ7lj$#Q6gG`miBS$rG_R3$EbrdF3-1XO&S zsSQuYLaNL7{~FZlIN|wBZ93!s-(GO_7A&-JST}dd6v2A$0=!`q>K=qXcMW7%S$zq5 zoiNwR_;-h3?dks@c%s#6i_fiZPtc~9SiLhw5vUeVd?EjnEqik(2XL@DudDY~%P zdQtR;W}v-{K5V!st`E)fl1wk%Q#ub)9wAnL8N1=s0gtC8K=mg?9;58>^kLcKsSzGe zuZfHMbG${!r;^L<>94^|7$RjsS~nQhg|I&HTPekxk1&Ot?hNa%}Po#E+BpL{e4{WKaY2DJ3b!AQWsW5u zVe)o{uHWE7L(){|8DrvkMRi#NQER`VaR_TxlPe*GkL7jU@;e))X+k=(Q9 zPL^*{r@57mc*k3o(H?dh0}2&(a`&f5Y}H$^sc5i(XU_L{utR@hpA#?eLQc)d8lCVP zOS+&4z=|QD;1wRlG(JBaE6aa|$v@*s7OwhovnV~zKoZeCwiHNP^Ok2z9zRkh<(CiCrrdKNkgT2=!*r>KB~OmNF}b)*N?!gzP4dJtDSr84 zNwd5R*J4S5U&Zpnz-N3a8@B85S?njU280}}+;BEg7$K|{?vfNwDW>xUv+*mPc^@?% z?dKH==v?ufp{g0maK?C@YY*ClF z7msA}XSn~`%0v3TawJnw;vOO(@3Ka<=-~_U&;GS_cBe8YsQ`ax4?X*)+!j~^s#IuC zrZBX6N%fxU)78mEtrp1x{4fPOg)iW{)M*K4N5Vf8^`syvmIcq~N9j>VMNt|M2zW(- z>#Nr6a>D9uwuIz5;;q6TeMvUc5$NXDa9(%jFwa335F$%2r!RoE34CWWY_6uA4`?~G zuhg4vc0|Ljd9=mu%xi8FT3XI9+RbYFQI#;t!`Czi*dl!=&!_pFGm&$|P*1wB2y^t! z06QtCQ=u4w@E$ksFuKaJvmNP>f-nU^cvVqIgb!ze?`mf!%WV--{d`iDCk20tJo6;Q zyc8fl-U%GcI5)kau`CtkDB9;DghGdTn0EZy{uPJ!6~%cd{=h(5N{44#r`sUJqcv&% zNK#d2u|e`g*H8-VJymYB(}-9jldoyF&q)D_V!L~S#2LYXNgCE(fV&sL?@qn3vFfk~ z@wZa<;tBqvVU>`KUON#0?+ou_0*d&m&adNt>1Vj?c6~7ZdRiIDLgseH7vP%P+!YVQ zC7w&|{5n-ZEhtr(Zn&vtquNy6P52jq7s6x6x*m8h4*S^y5|^pGsE4( zFz-q;mN{T2O57eJjg}saZO>;9@puYp-b|gPKY7oGfPJ1x24zWYn_=i7nh9W9kGrEOQz?7>#*yQ?D+B* zvROglZN_;LbJyrqhrM*9I%AbRp$ndOX* zR$c>E9`y~6z5!j6WSP6^&?!g-*&T_Xk;e!VVW-V5i|Iug%tfn74!~DET^@3e<=69aUCgM9Ij)+?zwBNy@}kdd zIqy4?{kQ{jKK6i5i#A#uX{9xSAEHb2ORqZZsK0-jWi!kM-+1tgfxN04zH~- zeG(BLX}2pF?PAcHOL5(YE01BASX{9EVGiPASeE`WU(l#+kH;g3u5b(KxzUTHt#i!!R z6Ss#7ND*X_RSOCNQcw{Wr0fMs@Be!yOIxTxX3Elk+|)7eS#ENvqT(-riTdZ#mPv3H>ef7HHvLOfwLAEOak{DUc-TFJjwjYmQq8pkzfe>kZCH{ zFwM2le_PEoXQ6AM4baa+zX`n-dJpto@GwytUoevj0&9x(6;TN#`GoZZaqgheOzm^G z(w92>ZpgPXK)=e?Rg&txRH1$Z!M6|8oWJ%cK2D+W7nBG)v zK_lsl4HZU)_On?GRvXJTR2o@fdUkqFdSSs-CghuJQohMrZYwucS(#91DX)~WN-B&} zUR6as>!GhO)KEhcPgvMC@P&a7)HhC{`F@o`Gci=5ISc*V^;r8#3QbOVozWt>ixmnC zRb@t&Z7Q=e%9QDimU2UdWHwoB$nPV-|1tEyub5`?A*RVLuQEy;wq6<*7#|o24JrO< z>=A~mPDrJ-;eBoQX%BJ*bPRGQH`}ZXFuAhLsIDreIvOgX8^vcgyooO%B#wxN>hokA~G_PeOhR&Fjg9EmU_>7j&`F&lEEhB80uJhoy}NP zVl0uUrf9_iW3jQk291$xie$MaDW%+2X)s$QQ1?QR5I{`W#a}p%zt7sE#Ss za3`qMnq$f=mD;Bpt_)GD7AcP@gZh-P2fOoTByjY2p9~h%ljbZ*kHNspVA**SvQkl~ zesWe}YG%5gWtc3L1{)J58)~FUriy9|o!cTJ!&!>ag3(k}g3higE4Q*dv$3jhid1PR zuaXSawpk_%s#j^on{BEZTPGEpBHX?hZB~XNvQi3?sah-}hp`v%9vs0~c+n0Xo%0*#w@GIk&L*8{IFod~;e67$hI2_L z8%`!QH#8@mZaAHEs^JuSmHmtTlPzN(un*Z=?BDFK>>+j!o6r8ip22u}jO}4xuuoYd zJID^PeQZDbm~CR~*m|~|?ZhO%_2str+7`Aw(RQq@rEPQD-nL(9b#0k# zQ`%mZ-;)>0PsqpQ7J0M0R~{zE%NjXYo+a1Gner5Q>BXjt(#4{SOD{EDk}efpTH4ao zBDEB?EWOZlLAp?MA^)=Za^U6Y%eyW&UtWB9#pV1~b8BF0bnC9x=GMinD_Wg>oI%cO zoPC`=oq-Sl(aSl|8RFDBL!JGc!Oj8B{texdx;1o9>fWG9(lq!c`8N0``8Nb41vL02 z`8D)N>cJ+l0ycx)!ZKJ2%VjsR8fIa0*&J5NX0j@FJI(~%>0~^b9 zY&?r&F>DOGeu|JO)CseMU|b%Ci~5AU!e*gGI3_$HEEL`oUKXYR5nab-v0%(K@jyoG zWt&+GJI0=13)y@45*7JKK21JLeTqa$Y!a7>MQRCx#+Ry#RFbMmwN$l2u~^Zp*rmV? zh6=MHU$H{D7|Y0A%4lVv(yYv<37IRogKG0>^J#bbGk?S&ll&I5R%NTwW6E;8!mcV2 z+X6O-+tdq{vg{{@svl4`F*6HMKBQJCoyr61xuQkF2L*RW|cDNm$x63r!HjmoFr_eUjix!VK(+FUw9}XMj`faZ!lt=kdXu zP2lsgVOKj{@WBf!1G!b%rdEgwu?=NX3XSLodz%_Dc?v(3zxp2Bh&)#eak&BQAaM}l z9N_UAgeDCv-;VsHm^-#qBS-p+B36vx1i|SCUCn)|Bls{9P ziTsxE@C4;tb&8mxYE!oI{A4*;8O%c{HsE7Re3t|)^wzfsD6J<1KP>hX96m{C|51E} zs8abUpAec^5z2!=Z+4IBBh^fn$U=Dee&~%}_=Pe*xSQ22>Id-p&Swv>7Iiaf)y8W( zNUTvEP%gySY~>|Ui&4H5PIhv&ViDXPe-Qj+nY-B_{sVUo&~l#iDdI-;2A*EREK5I% zOYl-(xN;@13izo`3SN@iCbR)w4h@IcACp0| z;8Z)+&B9!?J>|!gO&Bwb!=u9JqQ0R%^jE7?D#QWm4=o=In~Eva_ozR@=!g|VMStGE zlmoSqtG5-16@s^o>c`L$t{(TaA-RIl5-R-skS|(O)A>g+01CoIJ{p*Esd|ODSj4P> zdBoM8k|I!yRy8Rb(Ebe|H;7gRisU0H+TD_Z;BvWFs1}PW#3oe(!jteW(z}rYIB9$p z`7{SC?zXsFbGIV@X!rP#u#$>qP3i`uXUO@S`keReL!APcCJ?`K0q5NCGzdk2!Sg=5 zMhmq#)rFuAL|%btLxP`LvSa=p_&xP$4rmSt6as}6m}43MUjtfl1>AuU2-O@Q%dUK) zIfN3yuV_Z?=(j>G;jIir2xdezS_GYi@`PqrW1{_6?|!YNmn@ zt^jVP^k~N-v@F#q5H)BPoBfzC^L6^U!&QOm#Xh@4vq-H)st9A~*#LYl-18;*x!Rs= zq$up!0D4a-HvLKzv)u1Ly*smn5{1hj?fr)+SGj+P33!~vFdAyf(0L6l*|-5=cC3B6 z|KAE__!dL`UgLKaN`Nb2Kz12pEmQ?=v{Ip08111vazlq{|2Gtg{8+;OY;;vn6Fh|$ z80uCS0c|j}+<-;aVFGE=InXIOs?skTJPMD@leOohv{&@ z&UCG0U?ycc7X%!PE)2?sfa=m9e}=gN&?D0p%Cwa-Z6gEKQah<`4KnK1B%@l*Iv6cl z7_9*?+SD*)rB3IR1)ZZo1}rBX1dtA($yzc30I947%(4Ml*wd~SBgXx+A zD2lcT2I{73z*ut`P7FP?xU5D8kYJ7fI40NWFeY7D{bFed;8Enmh%A3cExCzCHW{r8 zP+E%`r8QyD3)F924x$bLfRBUg2E3V^7}YwA0T^xQ4V{c!);eHdkigKAf#zozBrs@} zpiW~=+7`TTjyAk+Fs^#vE>qo_c{BaTx=|FFBBQA~jS|X~XU_}bqoRc%YLx*SMiZ0B zh^7{fmjzi!aIjV(5rbdA5N)}ejCEuj*1|Z6PHDNUMig0z$n-~IWZ)o!`U+J=;=;Idnk|0ll@Yja&kq5WbMMW5! zmQr3-G97Dn7s!H;RRt`9O)8vaG1+VtMjg|Z>eKb1g*h?W(!!kB(8A0DSTct&A;n+= zTC85mHr2Yf?KZ+;q^IW>ImX}qzF%>Kg z;Mt7Gwal~c&!{k1XGw(UumFc5r5S6=fm{+&j7GC3ijY=rHCGtwrPNu*;@K7Dz%~gv zJ36gXOrJAF=;$+ycV&!#8kaI!C%LlJQ(o^kwl zI_|Vgx){++$V3+h3-Tlt=Q62Ar*)?hb`G|4I_@2(JFVk!kQ;xxp{3-q%!_lG=Zdc_ z26#L(6jBT;l?7ESpFR!I=sKCehSG5pMF9w8kG4A}pDRZGqX8Is@+Uz@?)IllnQ?OG+ezRAsD1VsF-k? z%D`dM;XBn!hj1|BmR#(`{%@yS+KPy+CUQj6IWKEIq z5;?J%pvAn#`y^~ER=f)Kx1FZe1+e$TlitbuVef$_y_Zqt9}4@kZhJKBi(&UchGSuW1$F`UFxWqY z-52@X(7~VJcpLr%OAz!{*n8tibH;nH_d{AFVQVNYp4UKs1bcrx2S9Ivot_<4GEh*d zAi7KkGHL?wMp-~d-Ndq44iHm$ET7#BRF$3;vWY-iO=eTrRG_WGFex9Fzm<>3Ut{mH zj(r5w+y)@&HUdqz83?*h*jBa;$hsXs*X;r#?=ztCb_1#RIWSTC*q1=)9RO@b zzCsWM6*eE;1V6zaJE&elkkA*Ht^PuY5DKisAYrgD6gaLCLbwnKoJp)ON*Ik>Z*CCA z3pycLNEOnB3Brv+wvY>KPk~S;mYbIRwHFDPGBE>pgw z#Pv*wifubFzoTK6$gt$#G&GK5Lh)_ z93hSr!^H?OQj8J>?7%@OAo_?ZQ7vjjU$L9m9k?TZF+eN|Glb0yD-J6OGlrFhm4(d; zD-XLpY<5^hSY=pMm?L*?s$(;P03kVnela)cZyN6FE0j2w&UXq0@t zJX#(DjOSQ+9KM_?j`5bpCrWx30voSN)|B)D=KAp9C99Pxjg_nj_<(p|1$H=gI6`1E z!v_P45C!pV);22-B;-OceEfsePbl{ad*NtNwkU&n{HEZBe$D|HXu%Cy*AKx1oC6yA zH3d`Np16D2UR+Hatmb(K7bK@;JWk9Q zR#-rvPJ9B>s+i}ajn`oVTPS2J0+qX!kBhhXgs8q!J*&P=qxC)L`&73n-Fy4(@LSMB z=YQ7!wSXCcJ$tU}Y3>!;drNO?(11Sc`WXAFuX*X3^x(t6bNcn{zpVe*0b2%44*5Ey zV&Lh4wV@Y6>$GRIRnk#uTG;lm@q=C+6m+fq+QZkT4t{`Q>%t?$M}^0SCxq+5Q^Hfj)56pFFAetO@TBlW zgxnB5HhfI@XvB*Pj}4FEzgXC>hwlxDks6*Eo*O2P&KNJL!3O%Wv#b0eON_;|hBS%F}j=VE+Y2?PpSUA@ogaO7^xM%#qx;9?#mtLY6>}PM{{b!JrT z_2%o}xc>O{BS)8yerfc#qpuxf81u}S{bR0)*T*l4|0LdLtZr=G*cD@sjn$5uIPS0G z){Z+hZtx8gZ@Bk{cWyXxLqNi~gpz~@65dYOm(Z3VjZYarbG&o>lJP6Ye>(pA@$&fI zi9-{|BxWS)6K_i_PrM_sHqoBwNOVHmVZQ@@w;?P8afT-LPLz@6Q>0yjJZ2&< zeH;0gpqzk&BPjD;ls)){Q-I^IfJZy-7+|Xdj6P#O0lfP7YvT6c0T(5E%D4+GJ+zh}ctTqj_kn{xL_or0A1q%g4~B zx~RTU$I-@1(bkjE=Dj0Nqy7Jlewd5?xC#9d5}}SbjegpJ{#uTHdl>y!kA5_wKPRGJ zGts|^=;tx$@6P={3S(jn#>Nd8BZ(L*$ybb@6pX0^jIB`^W7lDF2tSAMw-4iR zCC1|-jLRa7&k-a2Mjpp_eHr6+8pf~Bh%YdfZ5Y#<;X5(D3x@>_+lBF-a@~21{ac2r zhrWe(fem?naO&X0ct3)!eRa_ILEFQog&mcuq%+z&?S;_V(9;7e27VnfIb_R#u>+R% z@7aG&zr(@l!7p8-zQ)*hU7rDctU+6PhxRu2TGz8@&l!QQ1)TNQ`7h|P!>_mB6bSb` z=&SX;P4le!D^-Z<7N5t(-8jw2RxA`Y;QddK>)PJA+}s-8T7GHS#cwVQx?pH|?)>3% z*Pb(;efiAs)3K-PPpv!I{p7^vf1Wt;v+n1`$B+Cp=BEdL{PqXk4^Mr6;n>t;tG?5I zH~;8~Z*Tc_(>G(jdFAVYU;q6`k0bXTRv%v2;%{OQ2F1KI;? z_D|o>_AmP~_sa|WmhGFg&v)O4d#m?G@BQhE*T1OzBIb*h&)0qaz~@sxAO88JJv;Zj zxM%L3DSNKp(|gaE-JkFNVE5A93wPhK`_|oAyT|OlZg=qRZoAtWPd9$w*wnbM@w3Kl zjhh=cG_Gs>uyIY}>c&<4w;J}fjSY<-A>`x6O^sU`KS8|hjXN55^4|{Fx5D>h#8}h# zUgKMhuQk5V_*CP=jSCv@Y&10*8ug8-jj@eVV~@rQpMCS$_Rrq^Y{_T$d{*|^jh}^o z*5k9|pKkl~l~3>ewCK}upZ5Orhh6J-J+|xiUE_BJ>}uM%Vy9zg&d&ZjkM4MLhkZx- z4*wmWZ+~Wc$@UT3o438Yt$y41ZNjzSqWzFc>Foq#k^NLzwDo;oJ80Y?qsIs9=jU|R?nFKrwRc$aVbe$x=Z|Lo?2n+Kpik8jztr8nxg_>&!<_@TZF zwrBl_VU^vApCmv271@L3P^Q!M&RkA5?u{}!MhpF)4WhJJky{reI6c?uNXfcVoYto*xH6Mwhv?NdyKiZ#%>sY*I^uHVLaY}ak&)Z z^Yh(jcK613oq}=uBF68fJ;O1UAHbMy`8)>W`}Hq=`XUcjUP?s4SrM+ScV%GYDQ+4RjV-=6q( z{!#6BtG=6h?8339zSsTm?GF$BIOeA#KP^74`}xGr|2#3Vx%A`0j8ddw!#xCbi;`Y!1Ep`U_&4f+G<4bXZU5));C zl_lpUBaxJqn?JFTl6n;1G-+NMgHbiU5l1{84E57DQa`HId}?=a0#vpvHMr4%H|jEFtirc6;V7&HQzwL9oAM| z9f!z?LzpI&Srw0om2#kXbA#u`mzqn9N{fz~H|pkV$&bo?=nhKzkTpaX%+t~#(|pH9 z$5B@WdAW6=t-2l7&SliGR<^@1|Bm@%cMNRhC^mvQ+OICOE;QPYawpZ~Xm-3OED;{U zZwZdVn;lJnr_JGlxIM@A7I3vfNPKWG#UmHBN=STsNOM4wx^vq31`6eV!hG+KYT(Jw zRn9|qEO9)cqj=5^{X}kp(US)~$&Ga}Uv0x}1`=6I`MJ_ID4Wz~|M-xQc)e}+ z`_W<@2S@@f-YE|K%&Z9%gibo#^C!0lJ}T4G>*U{FiycBM297sgsj5nq;2+=WXesl? zQ_l~WKXAv`R&!lZU2tps4&IYgV^?ny+#cAyc5R!E?<8EKkk=2#PLTe|>&$l?Z8&sl zbHy`bj3**Kj~7~(XgB*e;SkK#4vF^Ay1A^)RWAo~IF$`T8xBfUbt*fc#VFlqI9gOw zlvos6gf>kmnv225e@&$gKoC+roQ4KNQxT~qbA!&Qb!r=QO=j*v2H&N$`!y9c7@P*4 zj^fpH$PY)ePV{Yyqt)>cMuKaf6bzoGW@UU?aH;!O)1qt9^7KN3(8N0r{Q_9f?J^a3 z)Nz#eDY@H60zq3xZ4FF7I2~Hjj2K6EjL%Wh+6UKQF^*OzX^h6ot=e(la z_PSB&t~TIlT>}FqwKvs_+8l-8*MPcGoU8Jqv2AE5ZYuM%OVM1MB!SDN2;-{bLJ87Lr4l$IC2&lsdAWrJdD%=Gq7B858^HJR%6drIvZ}0vpH40X zT9{|xXF}*@1R3&MWg#!!e#w# zwe%vT43s*lz~7S1(hIIKU!lUiN~ipfX_J<&P_V`Blvq9V;40#0q}RDdQ`gC*6=yCV z8Yoc8H|Pw&qogBkzml@(OxxN3H7`?^&$pbXKT$gWddj48@@+tTO7|`5s49O$O7@n# zmZMBPV7i~Y%(XVB*^ED-HM>x|<++5Myh8Dm-bR*7uLyQIUy$c^<*%X_#;r1+n9^kj zMYkP-*tiud-07ti4Nf3k8yY-7HZ(La#i6#OuJT_XmoxT&EU)K*(s^0V1W`E}TjCy# zvityJv*ZO`rTs*{9`D->S#CYueDW;%GMr)!I3c&4J9+ZVWm%qq#<*Voq^q>A%X}&5 z6S`>ai4$v0J%H9FrSLPoap=TaM<^dpdiiyicW1Lse!R0sSFXq8x~{yHCoW4}`FHe_ zE}!UnINvCL=ZzQbG#4dFf#An3GCMsj&DeMHE#4@dEjjIpPqYsPSw7*3c2ve0*)OP( z@+GG$NTJqr>)sKjoLlf%$HnE{|kvllYG{l`pOvQv$CV>x_V=(^5jcRX0Ow2 zF*jY3^VC=RUhP)+>8uH_^Bqc!3fhH1o@i#143=^e z=+5zN&Bs|-l}*AS*zLw*qH8x;aK0;Lnt;4!=>=n_NW;=C#yL`fp{BfMI4jH~pTb$D zN`qC(thOQxqh&br91^F33VtSzVnG~_b68yPl{c}FxlVXfOeR~l$xwnaJsbo=j+E_E zgb&LppKX*SWgGK~N2%zaCGz>-%SoN|px&fyz!XTqP@fK-`z;>zgR+Cw1prcS2{*115_`TDBl(3r3pvd*{PP`THT z;k`g)BH-Aak_ALZ2gtf$zhGUQpI@A;jz`sFh7Y-xiX;kIO`seWrh`oYRJ1CR$sz|2 z4oZ-9g9iu0Hkh1)b#m~iaE+`<^i{~i3JbFdzIb`?c(kUJG#;xG4H`BKtt2OC;{DFA2iaX4d$ke{D}qi$lJ;R|31 zJV}NMi_uV04_*?y0CWx}>1{?c!>!Zer@xfT}2(eewW>R_|v!a{S$vW9QeDE zc_Rz=+%u}jjFUaJm#_Mkc;oyhi{PX3v+oiQnfuB4UB~ML7Bn;X=!q^B3;J zu{dTFwiE&HE?v4}G4@he_S|Sb2ZlvbI}tE%@x?s;naYRb#LtK1ok9_8T3@wi?fV>@ zT%AxzSS4{4!_(hR_9)lKF$vZg+?O&M$!#vf#~=`A-3XrMjuPb^<5ukt&Ie| zObIyQti#!W(CZ>bkG(0kxWZDm;K9EwdGno(TRz)+_#1tCu09Wk$>7Z@OqV#L7Sj`h zq!k}ggViV{XJ@+@)QDrSgotg3-pi`Pr@tT%vuZj^t+s%5PhXBtFh1{Y1n`}pbD0ah zyF7GtdeCOr43!8qg}=HTdHKa~dkthu(grex;mtcip2Wgntb z4jGgz%gKX6QtF8Vv&<=4ARX2PM;oSs~o)t5VU2bgr+j?_5U~ zk|6u!K@R8;awa4=A4ux75WpztdwC`feR%FjAE?XD!imo{E@ z1P)6>bE28-piHT=Qz)g4x1;tNO;Av6PG=;257!*+YWq^-znl;N=uu9PHM@4m%Sj9 zrHrfB4qk!QQ2BMgdb6h5zO}YfV($3I!B^T#kaoFMyO+x*t=_iq>a_PA+}a*d5kRja zRJ)hU)^pXtC$3Jr@ZhSB5wXbZI_>r@%Do~j|1?}(Zs69{byt`B#6j(@1WT_*FSzJL4vd%ZRGr2TEr`CAU!z1=`a{okx=-rK+2w*wmI z*AmuvXPlaszFaenzTaN;pVH1>w)x8gU%tds&tLiFnp@k!<>@!CTsGgEwKt=h`O8*r z{&L&$$`R^mYrb4r^VsJ7%ST?3lCkcUPp{tJX(}u&t$Ba{>ZdEa`}%O)n$NT~2e#ie z+zV+Zi)#C}&a+wV>TRlyF?=*v73mG$c4gXC+q_}FX4!UN<+5duJvN`K$CfQydEmgW zCGm!LOQ^i->E&zItl74D&6?#;-&L8=@y+%|`~QWd#5l9MtPD%iaH+&p49NjiM3unt zTyJ8{`6cuw@cO^GpW$;)5g`obT1LI#v$``{y8b;Cc2Ud!4<3 zW75Om(EXZy!@gxl*>~WN|DOH8eq=x4>c^ki2~dci1U2|+c7~m0=fFRIfn8*mK!$J` zhtM+QlPCorK`rVv3k5ritld zhB!gY6tlz|#hb)zF-Oc5^TeCQ0#Pp(iW9|2;$(4(I90qwoF?8X&Jb@C&0%+hS;DMg zwy^53ny}iiy0H4NIbnB(*~9J%n;Yf`OO{jQR5?vfmowxEkid{7-zeWCXUjQquAC?5 z%QwpfvR*EfC(4uL$&k-5RlWtQ6d~Vev4Tv7P(EqKQbRSyOtFjHUjj}N_)mxdF*2eD zCP5WgVS-n{GpdNyg>ObWFfRZt%2@SA$e)3(hrSc~E@%hz-Oz<~<5&UoWP_y&FNPNz z%Q3tXvLEJ_(}8s^xMw&P6MaCL&H&G~K-}mH;UU3o2ndQtOK=fJ602{UDO)+^A#*WH2L)FCkwmsa#rZN6swg zt52de8UvjSJpnogdMdO5x(eEbH0C0Ch%E?kS7STp5+EWKrt1sQw!}*0u2F%h5e!zWJ0^a@m1V+#hoTk!Xk^OnzNj{RHkU+#SSmgmY&AHM?C%uy~ zZRMPo`aK@M;L!QD@1Fi*^`;G(-%go7>!rFRjUiYu?ArKkTaNF0==(P=WZqZ)WVcsF zzJK*>em{<~_=j5E2t6JsN94mJBfD}Q+6;Gx!?1J;gv zW9qYYixxio%H5y5`QvkbpGK_9J!v}Z41A7#6#ca%<_}5AFqaj*|CcBJcIo*q-yXj{ zq|x#9jMHx_7WX09#-}c?y^8+^}e9<`c)aZv*EBa0@t*PmgF=|rwzRE5B7oxu3 z{N(rd{q_CVUP+r`%v9A~H>)A|u;!ll=ZD?3_168mA44x)xPR|ct6uxZs_GjHZy9rY z-#I6{?dt#bh)2dnUJf{3aWH55t84CGe(dQj4-U1fD@txn&;Dn^U&5P0*7<2qB+Aow z+7CVT#s_QnEoyo8nyS%rC+6B_{4MgW#83U3L+M`oa>ycziB@PT2P!nx&^J#}Xzs%E zuHg#J78}CHDzLe~Qy~UQCMi(r)lCtq7(7f$NRWmNhP7KSsc1^Zl%nVfw@rwSx7+OT z(RFpB{E|#}n357l*N#rSz5h5x=){Slzjj8IrD}$Gj>BOI8a1(RkW@XySAorSiXGz+ zt8r&j5$LRfgNf?KMR_A9I+7iUKq)wqW?HA_0U_jYj1CUz<#1eAmVVdRL`T-0u|oY_ zYUOB0mSeOkuUr=jTtDdA9KMdZ4)Q|=wWA%5L#69FBgbjG=kc>th9nLjdb=kwd4|73s7NU7*fU zT#F3U0dxuX8xk?D6q-LJQc_9FBN<;jKUmID8d;GYaM=0yAN+OS=nb zfoOBuUE>`NpalRB&;lXxA$9gTKYJaL+2if@!3n{^34`r+_=N;#-fFi2E#OF#66{3@ z_K<|4gpdStyg4DQBEBNc@78=f&;qtwvpM&c%~;1zZ19=48d(pOn{Gv#oSB|0rRC+O zV{(khOqEiT3)0w4w-bKqCffQ}5rs@7F?K}Q>LN`ROle>Y^9Ut!%PE3*CO*S^ya~fE zk@Tfbl9=2?lP=mB7j+NAY=qgZFd4*@Bpa!^!T{7~Mh3nQ%7}=FtlUYWFe)`u7!4ht zni&%f9SaS=82I_zTwQLoaePIt31@*|1Z5JXmqw14#*J4ZR%#~V$E9YD>Otby=op17 zeFQPKNiOV~_h^hEOrJ7Q53y6IB)(W_wCG~0T%!4r3Qc8Y6~@^7JUy=6ATz+_@5&J- ziT=X+X%=|w=qu=AaWh%ncsGQ4a?)1-iD>DbUS~$eRW^w60w1WwAZ4IXu;Wo-T;*U& zuLhk5RI1599YJg6fj=3L{XH$>kM3$cRaX@pUlnBqNcG1Q>k9XgAms z>tH0*CFepmAMmu2G=$~M)Tw4e; z>+L#80xgv-67KR!{sHG8gIP)97HOIb$vR=ubT@sOguXZ0ILBqFk%PtAZe3qs;v?ob zXTI3wHjI(t+1xhCP*H81Mu(z65Km{*va1c#c_Hn7DP=j;R;(2y$!(MDc77VooORKV)S-z>( z!jg-Nr;ss~j9XY{Ng0zSQ4YyuloX~jsVkVdUvdnFZE`Fbab%1lqrw(J8={d6pp67n zBT<=H7|3oUOS2+?avn)gMZmB|5L6Ka)kp$pZ>oYTP6d|TTHePN{da|o8yXu9EWXyL|8LLRmMp3ArsNvibV{SDT z^BAxem>8_s8~WrJtEwTzuiVDcX)l^j(lC5W33iK=|c?z4B z8Z&)bYAkfz^sPv<6=}92%~quOM4!w)(WgMCLZ?BeLuWuwfX>9q*k+?9N2k!x?WAeg z(x|0D>z>pKGp&#gP?%}+Ax_3|#Jf1o&oiB(S=(Pj*s&_F#u}c_K4>b4{;S9{+bqU9 zO%7xq(rl1bY35QKRr>M@d~ znfZb-n~tk+U%IKnH8H2+^vHy90-kNjTwP%`T0H_3S+5-0n_Hr8#Pos)q_{}RjvfG< z$Kjts*Zk-9Nu^W!PCnFrbcDpEo6^^3%8l5f;G2_LpwGyem|e&N(qcxlw0I_E7sSMh z^j)GD&{M>W?5X<9i79%7W@hPcniM;Q{A1J7C*@5Y6EkMg*fC@DQ*);1vkO`36ny_D z#Kxse#R*_m&J+zeWH~L1&wn1a#J^Eh0{(Y*vvl(|kA$sSG1eS5V~O{pmW(e6jaCd) zMy*5QDESlnSum{E7lJ~lqI`~#PdW$yrH!?^(rlyYh{TDC(UB1m(UD*QjEs&}LwW>g znjr>|vY`2z6iskYG{r&T8%=7o>p?FiQecyZZ5oso9ObtF8}c}Nm+c02qbGQ(bAe-^ zkOVdjSdu3okZ}*N9=(9G$P=oBP3~h&8kH_e9hVdUqftUbpx1w+0^74IrhiZWUfRHZ zeR}uoqg9LAYx)e-_8BM)RBHRcuI)0nP@hn3p8@_oyJ>s+Yy0%n`Uw6#`)NgOPi;?4 z&j77BKpPmSRcN(BC^FajDExbdYJK`6XJBHqf!csTl9z((z0|?#e%JJ*b%wc)rGh%d zyYU4P6qcOjRpjHM`9hC%q=CX7x5UVga!V{EI@BtaRa>fAvZbsV+jmGT#fv4GN+sJY zqcoHH2+IX?xy9g;X^I0c*QvlCZU#7s7-2=g@6R~k6w)kO1cQW@{Z_?~D3+cD(FXMt z&Xf#PzVsV%(4O>`!D-E-*OQ`lOq)h-oU?KPA>LRWEEKsnW4-a9sJ}a{JI((aX=6Kp*~v;k z{z|z=PBu3;bk$M6mNwN>(kZRS=6(KJ+B2?k21+}Z@D*=DSbimK5(yK6f@~J|>1Bt+ zzmgU)`4PvDu2OhH-XGkcvVT#XmSvK=!MnYSNdGCV+f`SQ5ZZ+|UQ1JZ zI@r)=4|VczJ7$1r;R^p+&^~tZnkUQGcJgpLXt-SAuMFr6F}vg@AiE+S10AY-=_=1o z9_Qslo!lK9DwN#Z!F`3b`D(yA#?Vq~9K>F&Buc5h+P{O3f?n;5%}r7VKb8b~vJ+SK zR>uflyE=Jm?3Z zABBDz`bFsF(CRE;q}1Mu=KPn zw}hl^Sykq0B3LI`<1Dqp2ofG_(;?E#RB6R=Aff6k#aI$yQzq3KXIApHJeb!!G-AZf zY-DaZW+paoNH)<{UdVOGl z(-outAqpbJgBQYb@XnpwgBv6lybFaLL95f_KinOC5#Ra2SHeE!e^Dlq-`K7MUlY%* zy-pM+gu}BvQinP*(Y2!PSf|?BhrE6D%XN~$@Znbdc#+;JnITvAe^7^f-Pz_logR`* z-$TgIRi~Dg^QVea8-auH2HdBkf-_$a(jahqE5B7_Cw_9RXh}i z*MnQy-gNs1dwJZWX;c2cC>Is<3+-9Fz{{xjKuiH|aIX?K(8FlsmFIxJt0&DAD&)e= zqj~xXm8yFNo?gX6VR${-& zE(j389YbEvx5k>CSJkPucFxZBoL%Xzu2YAp0#O3LX;1Or+V15=J>8!CY3^~a2VxH- z(ZqY^ap2jZPI3!>DU=Q#+@YV)RWI=&&2#r8ZZFDf^G+2k9}+YEXLXS`vclxa$iz`D zfymm`Pfk)RPM+tmd4YDtcEy0b?Kuy?jCHEh-u5ba8^lvmhvy9i*D=TqFWC99Qk=6ZqNId>LknGMSE)1p-zu?Vyp8+XwS}L3+Itj5oxl`U9)f;a5Z>K9l`;h4v>37>(8j?H( zf&sO`J(d1ao!n7TO6M5gxH{ZZrv*P;0f(oEE4;_M{he(`-8KmP_(Rm?mNTcooO!0D zeIjk4a~HzvwJYx9HsE_jjEg*kS_I#xmF*e1(|1{?wH`4RIDnB`Bv%~qS$C5EFFg(} z;OtzTLF%ebxt>+odLH+p=dJu7r-}zaMfXRlrvcsZu9j<8*J-E5<3}F~Qmy%JpI>0Q zb;bHsb0IBb{y_EQFO}$l-y43L2U8!|z8GpVyQ2xWdE@{eBSsOz~$6{MiD3 zw!oh)@PB6u;O=0y1Lt?2LYEz2n(~88qX!AtIMzc<Zm|0I(tGJ2jad|hL;Yn70-E=r)I#fk4NH7NN zUol#qYFq{PPD`g^ap@f+( ziw4D$#Z+B3iF3y!G=wp0{b9u>b6kBQ%lKZrkyKZ(c1pT!em^M>ZMlN(N^o!W3J?evDz zX=gT^NjtmYY}&aE=hDt^IG@(?Ld!QTgD;d^cmYzN2VX3?_`=0+E)Kp_a_NOj-&`8p zTGIOW)^}QWx1MPYx;*M~;bq(9zh8dm^6txLE(f)ZYAbBBwLQ?br0w;#)ot6_4z&H$ z*4pMLhu{v51aPz6Dp$yM+&jD&HxDnBUzS(k7UBlnKfDV!5I5m2;%2!8dm;N>_Ii7@ z{SJGjz1(gDjrw%^RQp8x&GsC7mOb5`Y)`Z&*vEl4W3+vgJ=Pv=kF>c(3 z`#YNl%0e@EF^kv~+#Qq2k|4)58nRU-NaUp}ctCVj0vg^e6F{qOWm}1s-pcwxb7g18QM#tNQ-$g{I7G(fO zxOna$k~C2~oZmx)oboj!ZnXU_BBlx8ZqI#0f!(w`f2v;);wNeHcsRe`h#=`6(4Ern zr1nEef!(#-z1!`kaB2VwS0FxxlbgcH9o=2$P45qXa(lwbEp?CL;rkFDPVT1guR6F1 zjITSmslvxPxTyn=cW@JO<5UMXb>R69Zt8$mw;R?@%Egh1W`%Dswty6P3=WsXGsqnz zUXE(BdocI#uwL0rkoHG}+XAuj;8rXbGYk{lvVA~jZBz{*5qcKTgF|KyxHCxR4|@mi z%}VInYC$s=?^9|fn1(7qhRwQ7%Sq3j2o{p6vgzZb4BXU3at2+cIPbpaFZ1r5zhL2g zf4%>K2OnCr_~A$X_V-60d;Ezfmp}Eu)Bk#QY1luXf8oVtFTMQAtFOJj{9kXZc=N5d z-+A}nE8lzngH@~7e7Lq@-AC&;e7tef<}IIW-L`$l&Rw5=*0_7m=U?pI_vQWr2fsS> z3*qP8;m^9{7Uh@Qif0k6EwP(pekjG|V-m4`8EiVprl}%W0ty!wTNr4} z-SZ92KoQbN#$J~g>n}Ybgi1p}JRK%&R76Wf!dR&Q1K}Y?}EO1 zCGKH=pMAhqvDIu1`;e_=zwaKcFRr*r>k#{W-0bJC;%9dYicT@&`))+PyOtsDj(5+) zGx@M%QTn`zxoP?+V^tK>Pt_Nu=R`q!%M8~>}aI%f_8j)m+4rfE6<4Ry3RWhVl z>R?Ae$HWNgm>8jyD7M69;g9ekC0GBuu_#V_re{C4EzZ%W<>{}Fj7GOfxyd={cp0UP zfPIy^}ePT6GE6U zkO`qo(6U~~6hE<`)6F4d3}n3mdob0Hm(H-hy_;K^aQSjD8U4uU&y+tx@OxjC(3=Sq zswP8u>CADa7S8;{MER#nOdZ&pX<9F^K*g~TGLYl35EU7IFb0xsAlX8cWFsS_H`#i# z2onTeM1W4t2EI5pv);(Ct~ONAv}Ub!J&neh2FSahR}|A5!-{Ao@ydZ|fo@P_hM3#H zPfHK5?lVKI%N6T##kpK@F4riRYZP}`aI+|Pa|@-l)>?Ro%?N=7vrUXYO|uzzO3SOr zO;5PNBMDh@vyJs=Xqdc}AxH#lS=d652!$ArCDvn!W9SetD^)UMmFo$&6+D+Q6hM|( zkA+7ipHbvvHraR-JY6xs^Xf_i3;EPhndHMQUY|H-!<%M_j&?m`+|O9|GcKCVs%Dwh zRb`On3oa;g1-SfhHR>z|?pS>-7-q>jo4&m@hS``$5NxqkmsMkfRaL=qjbOYbF}YTT zb!`^0@))p#D#b0B*g_Q>$}wG8!Chsl0OML2&o|8oa!Y)(is!J@IYwBxm^9irNnp~8 zAtM$BI9J__zHoRhyd*2XzK(HyTL`oRVUBQgzj6bYP{7!y28E@lvZ#A@Z1tVRS?p9;Km)_&{l6unD65(KjgM8j9PjCiEE2S(doZIrMF;juqGb=YE zk4-kZ1P%illf^m?jc3JLA7VR5mco;QOOhVkzqa6C$GsL>C=+kGbe*EsDee>CUe~IZPJ=`l;`BH6U>AQsq z>08&NyuR<5{6!}&mHu#fuWgH%@}R!2;aRgJzS1Z5x>cjIcYJ(k#_=y&XDvMZTc`!21rys9c*WC==o`sP7HUKS&6a)zBlnLh$vu8sO{HwV@9*s1r&jh_w*0ff z>(`zf-Lx(^)3@=4TSk04qayG8U2`kCz4(`Rg6BW{c;weFol0nU_tTW&TjTS)?Hf>P zIx*LleR=x*?(-CGaoDH*r*!|$QB`&JR(p=$#(TdA{r2%Q z!<^4OJns3o-%7i2`?N{rhw6&_z8`3bx|I0f=i;Vk&-VT1mBrHCtKN?N=f}5X-}FWO zj9G_6X7xC&n-l5(-GXx=8y?*=;<@Kn#NYGg-!f+JoKu*2aO%v69}~>}7qpActByXs zJLu!r-W;^_{YRqzvgyv;+xJYlHS6o~w}+n$tqZ^a;9n#%hLQ5Ryq1L|D6NBXov4!O z_JlA=D4`4GijcyUq6M8@5@=Cm61;y^ZLW2t`_+hl rU<7OfxblzN{@SQsl}CU2%7^hy literal 0 HcmV?d00001 diff --git a/Multiprotocol/telemetry.h b/Multiprotocol/telemetry.h index b305cd7..126549f 100644 --- a/Multiprotocol/telemetry.h +++ b/Multiprotocol/telemetry.h @@ -1,24 +1,26 @@ -/* - This project is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. +//************************************* +// FrSky Telemetry serial code * +// By Midelic on RCG * +//************************************* - Multiprotocol is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. +#if defined TELEMETRY - You should have received a copy of the GNU General Public License - along with Multiprotocol. If not, see . - */ +#define USER_MAX_BYTES 6 +#define MAX_PKTX 10 +uint8_t frame[18]; +uint8_t pass = 0; +uint8_t index; +uint8_t prev_index; +uint8_t pktx[MAX_PKTX]; - -static void frskySendStuffed(uint8_t frame[]) +void frskySendStuffed() { Serial_write(0x7E); - for (uint8_t i = 0; i < 9; i++) { - if ((frame[i] == 0x7e) || (frame[i] == 0x7d)) { + for (uint8_t i = 0; i < 9; i++) + { + + if ((frame[i] == 0x7e) || (frame[i] == 0x7d)) + { Serial_write(0x7D); frame[i] ^= 0x20; } @@ -27,37 +29,121 @@ static void frskySendStuffed(uint8_t frame[]) Serial_write(0x7E); } -static void frskySendFrame() -{ - uint8_t frame[9]; +void compute_RSSIdbm(){ + RSSI_dBm = (((uint16_t)(pktt[len-2])*18)>>5); + if(pktt[len-2] >=128) + RSSI_dBm -= 82; + else + RSSI_dBm += 65; +} - frame[0] = 0xfe; - if ((cur_protocol[0]&0x1F)==MODE_FRSKY) - { - compute_RSSIdbm(); - frame[1] = pktt[3]; - frame[2] = pktt[4]; - frame[3] = (uint8_t)RSSI_dBm; - frame[4] = pktt[5]*2;//txrssi - frame[5] = frame[6] = frame[7] = frame[8] = 0; - } - else - if ((cur_protocol[0]&0x1F)==MODE_HUBSAN) - { - frame[1] = v_lipo*2; - frame[2] = 0; - frame[3] = 0x5A;//dummy value - frame[4] = 2 * 0x5A;//dummy value +void frsky_link_frame() +{ + frame[0] = 0xfe; + #if defined(FRSKY_CC2500_INO) + if ((cur_protocol[0]&0x1F)==MODE_FRSKY) { + compute_RSSIdbm(); + frame[1] = pktt[3]; + frame[2] = pktt[4]; + frame[3] = (uint8_t)RSSI_dBm; + frame[4] = pktt[5]*2;//txrssi + frame[5] = frame[6] = frame[7] = frame[8] = 0; + } + #endif + #if defined(HUBSAN_A7105_INO) + if ((cur_protocol[0]&0x1F)==MODE_HUBSAN) { + frame[1] = v_lipo*2; //v_lipo; common 0x2A=42/10=4.2V + frame[2] = frame[1]; + frame[3] =0X6e; + frame[4] =2*0x6e; frame[5] = frame[6] = frame[7] = frame[8] = 0; } - frskySendStuffed(frame); + frskySendStuffed(); } +#if defined HUB_TELEMETRY +void frsky_user_frame() +{ + uint8_t indexx = 0, c=0, j=8, n=0, i; + + if(pktt[6]>0 && pktt[6]<=MAX_PKTX) + {//only valid hub frames + frame[0] = 0xFD; + frame[1] = 0; + frame[2] = pktt[7]; + + switch(pass) + { + case 0: + indexx=pktt[6]; + for(i=0;i4Uvd2V9>2><{90RR915C8xGU94T%E=NXuks?iziKWb+s#l_~i3Ite5(VyD5`h(>z66S#Ks+iaNA``~OoLXh>_8YT$&s((yJ&r%!Bn-1l zydSJ|%5j}MB?TNYMtZ*Q^_BCU5XaP_12;@(?Yz&nBFWvhvecFpamNcG**&ITd7+eY z(my&|7BM$A8@~N6mJV&2Szyl^inouc4NNz6eK&B^I3tg?P>&sWw55!d#@nBFNr3Fz z{hr)wDCP?V=4Po;IPvxQ8{x*D=ohhZ^r^z~Y{a&Ecr& zJOzvIWdr~rF5y=EU^UJF literal 0 HcmV?d00001 From c5d819be81f15f79c51d689332d0247fd13e8da0 Mon Sep 17 00:00:00 2001 From: tipouic Date: Wed, 27 Jan 2016 22:05:04 +0100 Subject: [PATCH 2/9] =?UTF-8?q?Correction=20mineur=20+=20=C3=A9dit=20du=20?= =?UTF-8?q?README?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Multiprotocol/Multiprotocol.ino | 107 ++++--- Multiprotocol/telemetry.h | 12 +- README.md | 534 +------------------------------- sync.ffs_db | Bin 656 -> 1274 bytes telemetryFRSKY.fzz | Bin 0 -> 5198 bytes telemetryFRSKY.jpg | Bin 0 -> 72125 bytes 6 files changed, 75 insertions(+), 578 deletions(-) create mode 100644 telemetryFRSKY.fzz create mode 100644 telemetryFRSKY.jpg diff --git a/Multiprotocol/Multiprotocol.ino b/Multiprotocol/Multiprotocol.ino index d075ec1..469fbdd 100644 --- a/Multiprotocol/Multiprotocol.ino +++ b/Multiprotocol/Multiprotocol.ino @@ -72,7 +72,7 @@ uint8_t RX_num; // Mode_select variables uint8_t mode_select; -uint8_t ppm_select; +uint8_t ppm_select=0, flag_decal=0; uint8_t protocol_flags=0,protocol_flags2=0; // Serial variables @@ -161,14 +161,16 @@ void setup() //Protocol and interrupts initialization #if !defined(POTAR_SELECT) - if(mode_select == MODE_SERIAL) - { // Serial - cur_protocol[0]=0; - cur_protocol[1]=0; - prev_protocol=0; - Mprotocol_serial_init(); // Configure serial and enable RX interrupt - } - else + if(mode_select == MODE_SERIAL) + { // Serial + cur_protocol[0]=0; + cur_protocol[1]=0; + prev_protocol=0; + Mprotocol_serial_init(); // Configure serial and enable RX interrupt + } + else + #else + if(mode_select==MODE_SERIAL) { flag_decal=1; } else { flag_decal=0;} #endif { // PPM prev_protocol=0; @@ -188,22 +190,19 @@ void setup() void loop() { #if !defined(POTAR_SELECT) - if(mode_select==MODE_SERIAL && IS_RX_FLAG_on) // Serial mode and something has been received - { - update_serial_data(); // Update protocol and data - update_aux_flags(); - } - #endif - if(mode_select!=MODE_SERIAL && IS_PPM_FLAG_on) // PPM mode and a full frame has been received - { - for(uint8_t i=0;iPPM_SWITCH) - #else - if(Servo_data[AUX1+i]>PPM_SWITCH) - #endif + if(Servo_data[AUX1+i+flag_decal]>PPM_SWITCH) Servo_AUX|=1<PPM_SWITCH) { CHANGE_PROTOCOL_FLAG_on; } + if(Servo_data[AUX1]>PPM_SWITCH) { CHANGE_PROTOCOL_FLAG_on; } #endif if(IS_CHANGE_PROTOCOL_FLAG_on) { + ppm_select = 10; + + if(mode_select == 0) { + while(ppm_select) { + while(!IS_PPM_FLAG_on) {} // wait + update_PPM_servo(); + if(Servo_data[AUX1] < PPM_MAX_100) { ppm_select--; } + } // attente de la déactivation du rebind + } prev_protocol = ppm_select; - ppm_select = 0; // protocol selection - // THROTTLE up - if(Servo_data[POTAR_SELECT_M] > PPM_MAX_COMMAND) { ppm_select += 18; } - // THROTTLE down - else if(Servo_data[POTAR_SELECT_M] < PPM_MIN_COMMAND) { ppm_select += 9; } - // THROTTLE middle - else { ppm_select += 0; } + ppm_select = 0; + if(Servo_data[POTAR_SELECT_M] > PPM_MAX_COMMAND) { ppm_select += 18; } // THROTTLE up + else if(Servo_data[POTAR_SELECT_M] < PPM_MIN_COMMAND) { ppm_select += 9; } // THROTTLE down + else { ppm_select += 0; } // THROTTLE middle - // Elevator up - if(Servo_data[POTAR_SELECT_V] > PPM_MAX_COMMAND) { ppm_select += 7; } - // Elevator down - else if(Servo_data[POTAR_SELECT_V] < PPM_MIN_COMMAND) { ppm_select += 1; } - // Elevator middle - else { ppm_select += 4; } + if(Servo_data[POTAR_SELECT_V] > PPM_MAX_COMMAND) { ppm_select += 7; } // Elevator up + else if(Servo_data[POTAR_SELECT_V] < PPM_MIN_COMMAND) { ppm_select += 1; } // Elevator down + else { ppm_select += 4; } // Elevator middle - // Aileron right - if(Servo_data[POTAR_SELECT_H] > PPM_MAX_COMMAND) { ppm_select += 2; } - // Aileron left - else if(Servo_data[POTAR_SELECT_H] < PPM_MIN_COMMAND) { ppm_select += 0; } - // Aileron middle - else { ppm_select += 1; } + if(Servo_data[POTAR_SELECT_H] > PPM_MAX_COMMAND) { ppm_select += 2; } // Aileron right + else if(Servo_data[POTAR_SELECT_H] < PPM_MIN_COMMAND) { ppm_select += 0; } // Aileron left + else { ppm_select += 1; } // Aileron middle -// if(ppm_select == 5) { ppm_select = eeprom_read_byte(30); } else { eeprom_update_byte(30, ppm_select); } - if(ppm_select > 5) { ppm_select--; } +// if(ppm_select == 5) { ppm_select = eeprom_read_byte(30); } else { eeprom_update_byte(30, ppm_select); } - if(mode_select > MODE_SERIAL) { + if(ppm_select != 5) { + if(ppm_select > 5) { ppm_select--; } ppm_select--; cur_protocol[0] = PPM_prot[ppm_select].protocol; sub_protocol = PPM_prot[ppm_select].sub_proto; @@ -488,6 +491,8 @@ static void update_ppm_data() { if(PPM_prot[ppm_select].autobind) AUTOBIND_FLAG_on; ppm_select++; } + + while(Servo_data[THROTTLE] > PPM_MIN_100) { delay(100); update_PPM_servo(); } // attente de la remise des gaz à zéro (poussé à fond avec le script lua) } } static void update_serial_data() diff --git a/Multiprotocol/telemetry.h b/Multiprotocol/telemetry.h index 126549f..f6fe07d 100644 --- a/Multiprotocol/telemetry.h +++ b/Multiprotocol/telemetry.h @@ -40,18 +40,18 @@ void compute_RSSIdbm(){ void frsky_link_frame() { frame[0] = 0xfe; - #if defined(FRSKY_CC2500_INO) - if ((cur_protocol[0]&0x1F)==MODE_FRSKY) { + if ((cur_protocol[0]&0x1F)==MODE_FRSKY) + { compute_RSSIdbm(); frame[1] = pktt[3]; frame[2] = pktt[4]; frame[3] = (uint8_t)RSSI_dBm; - frame[4] = pktt[5]*2;//txrssi + frame[4] = pktt[5]*2; frame[5] = frame[6] = frame[7] = frame[8] = 0; } - #endif - #if defined(HUBSAN_A7105_INO) - if ((cur_protocol[0]&0x1F)==MODE_HUBSAN) { + else + if ((cur_protocol[0]&0x1F)==MODE_HUBSAN) + { frame[1] = v_lipo*2; //v_lipo; common 0x2A=42/10=4.2V frame[2] = frame[1]; frame[3] =0X6e; diff --git a/README.md b/README.md index 79a074b..578a7a8 100644 --- a/README.md +++ b/README.md @@ -1,537 +1,29 @@ # DIY-Multiprotocol-TX-Module -Fork for adding PPM select of project https://github.com/pascallanger/DIY-Multiprotocol-TX-Module - -Multiprotocol is a 2.4GHz transmitter which enables any TX to control lot of different models available on the market. - -The source code is partly based on the Deviation TX project, thanks to all the developpers for their great job on protocols. - -[Forum link on RCGROUPS](http://www.rcgroups.com/forums/showthread.php?t=2165676) for additional information or requesting a new protocol integration. - ![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t7952733-114-thumb-P4100002.JPG?d=1433910155) ![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t7952734-189-thumb-P4100003.JPG?d=1433910159) -**To download the latest compiled version (hex file), click on [Release](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/releases) on the top menu.** +Fork du projet https://github.com/pascallanger/DIY-Multiprotocol-TX-Module -##Contents +Afin d'ajouter : +- Une sélection du protocole via les manches de la radio +- Un rebind hardware en PPM +- La radio TARANIS (TAERB, B = rebind ;-) ) et redéclaration des radios +- Un script "LUA" afin de faciliter la position des manches +- Le protocole H7 -[Compatible TX](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module#compatible-tx) -[Protocols](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module#protocols) -[Hardware](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module#hardware) +Programme des évolutions : +- Ajout du de la télémetrie TARANIS à l'aide du projet https://github.com/shadow974/TxAdapter -[Compilation and programmation](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module#compilation) + (Attention, il faut rajouter un transistor afin d'inverser et amplifier le signal) -[Troubleshooting](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module#troubleshooting) -##Compatible TX - -###Using standard PPM output (trainer port) -The multiprotocol TX module can be used on any TX with a trainer port. - -Channels order is AETR by default but can be changed in the _Config.h. - -The protocol selection is done via a dip switch, rotary dip switch, scsi ID selector or PPM position. - -![Screenshot](http://media.digikey.com/photos/CTS%20Photos/206-4,%20206-4ST_sml.jpg) -![Screenshot](http://media.digikey.com/photos/Grayhill%20Photos/94HBB16T_sml.jpg) -![Screenshot](http://static.rcgroups.net/forums/attachments/1/1/5/4/3/7/t8637216-7-thumb-SCSI%20ID%20selector.jpg?d=1453737244) - -You can access to up to 15 different protocols and associated settings. - -Settings per selection are located in _Config.h: - - Protocol and type: many main protocols have variants - - RX Num: number your different RXs and make sure only one model will react to the commands - - Power: High or low, enables to lower the power setting of your TX (indoor for example). - - Option: -127..+127 allowing to set specific protocol options. Like for Hubsan to set the video frequency. - - Autobind: Yes or No. At the model selection (or power applied to the TX) a bind sequence will be initiated - -###Using a serial output -The multiprotocol TX module takes full advantage of being used on a Turnigy 9X, 9XR, 9XR Pro, Taranis, 9Xtreme, AR9X, ... running [er9x or ersky9X](https://github.com/MikeBland/mbtx/tree/next). (A version for OpenTX is being looked at) - -This enables full integration using the radio GUI to setup models with all the available protocols options. - -![Screenshot](http://static.rcgroups.net/forums/attachments/1/1/5/4/3/7/t8520065-194-thumb-IMG_20151217_002215%20%28Medium%29.jpg?d=1450308588) - -Options are: - - Protocol and type: many main protocols have variants - - RX Num: number your different RXs and make sure only one model will react to the commands - - Power: High or low, enables to lower the power setting of your TX (indoor for example). - - Option: -127..+127 allowing to set specific protocol options. Like for Hubsan to set the video frequency. - - Bind: bind a RX/model - - Autobind: Yes or No. At the model selection (or power applied to the TX) a bind sequence will be initiated - - Range: test range by setting the transmission power to the lowest value - -Notes: - - Using this solution does not need any modification of the TX since it uses the TX module slot PPM pin for serial transfer. - - There are 2 versions of serial protocol either 8 or 16 channels. 16 channels is the latest and only available version going forward. Make sure to use the right version based on your version of er9x/ersky9x. - - Channels order is AETR by default but can be changed in _Config.h. - -###Telemetry - -There are only 2 protocols so far supporting telemetry: Hubsan and Frsky. - -Hubsan displays the battery voltage. - -FRSky displays full telemetry (A0, A1, RSSI, TSSI and Hub). - -### If used in PPM mode - -Telemetry is available as a serial 9600 8 n 1 output on the TX pin of the Atmega328p using the FRSky hub format. - -You can connect it to your TX if it is telemetry enabled or use a bluetooth adapter along with an app on your phone to display telemetry information and setup alerts. - -### If used in Serial mode - Telemetry is built in for er9x and ersky9x TXs. - -To enable telemetry on a Turnigy 9X or 9XR you need to modify your TX following one of the Frsky mod like this [one](http://blog.oscarliang.net/turnigy-9x-advance-mod/). - -Enabling telemetry on a 9XR PRO and may be other TXs does not require any hardware modifications. The additional required serial pin is already available on the TX back module pins. - -Once the TX is telemetry enabled, it just needs to be configured on the model (see er9x/ersky9x documentation). - -##Protocols - -###TX ID -The multiprotocol TX module is using a 32bits ID generated randomly at first power up. This global ID is used by all protocols. -There are little chances to get a duplicated ID. - -It's possible to generate a new ID using bind button on the Hubsan protocol during power up. - -###Bind -To bind a model in PPM Mode press the physical bind button, apply power and then release. - -In Serial Mode you have 2 options: -- use the GUI, access the model protocol page and long press on Bind. This operation can be done at anytime. -- press the physical bind button, apply power and then release. It will request a bind of the first loaded model protocol. - -Notes: -- the physical bind button is only effective at power up. Pressing the button later has no effects. -- a bind in progress is indicated by the LED fast blinking. Make sure to bind during this period. - -###Protocol selection - -####Using the dial for PPM input -PPM is only allowing access to a subset of existing protocols. -The default association dial position / protocol is listed below. - -Dial|Protocol|Sub_protocol|RX Num|Power|Auto Bind|Option|RF Module -----|--------|------------|------|-----|---------|------|--------- -0|Select PPM|||||| -1|FLYSKY|Flysky|0|High|No|0|A7105 -2|HUBSAN|-|0|High|No|0|A7105 -3|FRSKY|-|0|High|No|-41|CC2500 -4|HISKY|Hisky|0|High|No|0|NRF24L01 -5|V2X2|-|0|High|No|0|NRF24L01 -6|DSM2|DSM2|0|High|No|0|CYRF6936 -7|DEVO|-|0|High|No|0|CYRF6936 -8|YD717|YD717|0|High|No|0|NRF24L01 -9|KN|WLTOYS|0|High|No|0|NRF24L01 -10|SYMAX|SYMAX|0|High|No|0|NRF24L01 -11|SLT|-|0|High|No|0|NRF24L01 -12|CX10|CX10_BLUE|0|High|No|0|NRF24L01 -13|CG023|CG023|0|High|No|0|NRF24L01 -14|BAYANG|-|0|High|No|0|NRF24L01 -15|SYMAX|SYMAX5C|0|High|No|0|NRF24L01 - -Notes: -- The dial selection must be done before the power is applied. -- The protocols, subprotocols and all other settings can be personalized by modifying the _Config.h file. - -#####Select PPM -Calculating the desired protocol with the position of the sleeves during startup or reset. This allows for a choice of 26 protocols. A path is lost in order to have a hardware reset if using "PPM selection". -To simplify the memorization, I provided a lua script for OPENTX. - -####Using serial input with er9x/ersky9x -Serial is allowing access to all existing protocols & sub_protocols listed below. - -Protocol|Sub_protocol|RF Module ---------|------------|--------- -Flysky||A7105 - |Flysky - |V9x9 - |V6x6 - |V912 -Hubsan||A7105 -Frsky||CC2500 -Hisky||NRF24L01 - |Hisky - |HK310 -V2x2||NRF24L01 -DSM2||CYRF6936 - |DSM2 - |DSMX -Devo||CYRF6936 -YD717||NRF24L01 - |YD717 - |SKYWLKR - |SYMAX4 - |XINXUN - |NIHUI -KN||NRF24L01 - |WLTOYS - |FEILUN -SymaX||NRF24L01 - |SYMAX - |SYMAX5C -SLT||NRF24L01 -CX10||NRF24L01 - |CX10_GREEN - |CX10_BLUE - |DM007 - |Q282 - |JC3015_1 - |JC3015_2 - |MK33041 - |Q242 -CG023||NRF24L01 - |CG023 - |YD829 - |H8_3D -Bayang||NRF24L01 -FrskyX||CC2500 -ESky||NRF24L01 - -Note: -- The dial should be set to 0 for serial. Which means all protocol selection pins should be left unconnected. - -###Protocol details -Extended limits supported: -125%..+125% can be used and will be transmitted. Otherwise the default is -100%..+100% only. - -Autobind protocol: you do not need to press the bind button at power up to bind, this is done automatically. - -####BAYANG -Models: EAchine H8(C) mini, BayangToys X6/X7/X9, JJRC JJ850, Floureon H101 ... - -Autobind protocol - -CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10 ----|---|---|---|---|---|---|---|---|---- -A|E|T|R|FLIP|RTH|PICTURE|VIDEO|HEADLESS|INVERTED - -####CG023 -Models: EAchine CG023/CG031/3D X4 - -Autobind protocol - -CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9 ----|---|---|---|---|---|---|---|--- -A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS - -#####Sub_protocol YD829 -Models: Attop YD-822/YD-829/YD-829C ... - -CH5|CH6|CH7|CH8|CH9 ----|---|---|---|--- -FLIP||PICTURE|VIDEO|HEADLESS - -#####Sub_protocol H8_3D -Models: EAchine H8 mini 3D, JJRC H20/H22 - -CH5|CH6|CH7|CH8|CH9 ----|---|---|---|--- -FLIP|LIGTH|OPT1|OPT2|CAL - -JJRC H20: OPT1=Headless, OPT2=RTH - -JJRC H22: OPT1=RTH, OPT2=180/360° flip mode - -H8 3D: OPT1=RTH + headless, OPT2=180/360° flip mode - -CAL: calibrate accelerometers - -####CX10 -Extended limits supported - -Autobind protocol - -CH1|CH2|CH3|CH4|CH5|CH6 ----|---|---|---|---|--- -A|E|T|R|FLIP|RATE - -Rate: -100%=rate 1, 0%=rate 2, +100%=rate 3 - -#####Sub_protocol CX10_GREEN -Models: Cheerson CX-10 green pcb - -Same channels assignement as above. - -#####Sub_protocol CX10_BLUE -Models: Cheerson CX-10 blue pcb & some newer red pcb, CX-10A, CX-10C, CX11, CX12, Floureon FX10, JJRC DHD D1 - -CH5|CH6|CH7|CH8 ----|---|---|--- -FLIP|RATE|PICTURE|VIDEO - -Rate: -100%=rate 1, 0%=rate 2, +100%=rate 3 or headless for CX-10A - -#####Sub_protocol CX10_DM007 - -CH5|CH6|CH7|CH8|CH9 ----|---|---|---|--- -FLIP|MODE|PICTURE|VIDEO|HEADLESS - -#####Sub_protocol CX10_Q282 and CX10_Q242 - -CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12 ----|---|---|---|---|---|---|--- -FLIP|LED|PICTURE|VIDEO|HEADLESS|RTH|XCAL|YCAL - -#####Sub_protocol CX10_JC3015_1 - -CH5|CH6|CH7|CH8 ----|---|---|--- -FLIP|MODE|PICTURE|VIDEO - -#####Sub_protocol CX10_JC3015_2 - -CH5|CH6|CH7|CH8 ----|---|---|--- -FLIP|MODE|LED|DFLIP - -#####Sub_protocol CX10_MK33041 - -CH5|CH6|CH7|CH8|CH9|CH10 ----|---|---|---|---|--- -FLIP|MODE|PICTURE|VIDEO|HEADLESS|RTH - -####DEVO -Extended limits supported - -CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8 ----|---|---|---|---|---|---|--- -CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8 - -####DSM2 -Extended limits supported - -CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8 ----|---|---|---|---|---|---|--- -A|E|T|R|CH5|CH6|CH7|CH8 - -####ESKY - -CH1|CH2|CH3|CH4|CH5|CH6 ----|---|---|---|---|--- -A|E|T|R|GYRO|PITCH - -####FLYSKY -Extended limits supported - -CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8 ----|---|---|---|---|---|---|--- -A|E|T|R|CH5|CH6|CH7|CH8 - -#####Sub_protocol V9X9 -CH5|CH6|CH7|CH8 ----|---|---|--- -UNK|LIGHT|PICTURE|VIDEO - -#####Sub_protocol V6X6 -CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12 ----|---|---|---|---|---|---|--- -FLIP|LIGHT|PICTURE|VIDEO|HEADLESS|RTH|XCAL|YCAL - -#####Sub_protocol V912 -CH5|CH6 ----|--- -BTMBTN|TOPBTN - -####FRSKY -Extended limits supported - -Telemetry enabled for A0, A1, RSSI, TSSI and Hub - -Option=fine frequency tuning, usually 0 or -41 based on the manufacturer boards - -CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8 ----|---|---|---|---|---|---|--- -CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8 - -####HISKY -CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8 ----|---|---|---|---|---|---|--- -A|E|T|R|GEAR|PITCH|GYRO|CH8 - -GYRO: -100%=6G, +100%=3G - -####HK310 -Models: RX HK-3000, HK3100 and XY3000 (TX are HK-300, HK-310 and TL-3C) - -CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8 ----|---|---|---|---|---|---|--- -|||T|R|AUX|T_FSAFE|R_FSAFE|AUX_FSAFE - -####HUBSAN -Models: Hubsan H102D, H107/L/C/D and Hubsan H107P/C+/D+ - -Autobind protocol - -Telemetry enabled for battery voltage only - -Option=vTX frequency (H107D) 5645 - 5900 MHz - -CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9 ----|---|---|---|---|---|---|---|--- -A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS - -####KN -CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11 ----|---|---|---|---|---|---|---|---|----|---- -A|E|T|R|DR|THOLD|IDLEUP|GYRO|Ttrim|Atrim|Etrim - -Dual Rate: +100%=full range, Throttle Hold: +100%=hold, Idle Up: +100%=3D, GYRO: -100%=6G, +100%=3G - -#####Sub_protocol WLTOYS -#####Sub_protocol FEILUN -Same channels assignement as above. - -####SLT -Autobind protocol - -CH1|CH2|CH3|CH4|CH5|CH6 ----|---|---|---|---|--- -A|E|T|R|GEAR|PITCH - -####Symax -Autobind protocol - -CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9 ----|---|---|---|---|---|---|---|--- -A|E|T|R|FLIP||PICTURE|VIDEO|HEADLESS - -#####Sub_protocol SYMAX -Models: Syma X5C-1/X11/X11C/X12 - -#####Sub_protocol SYMAX5C -Model: Syma X5C (original) and X2 - -####V2X2 -Models: WLToys V202/252/272, JXD 385/388, JJRC H6C, Yizhan Tarantula X6 ... - -CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11 ----|---|---|---|---|---|---|---|---|----|---- -A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS|MAG_CAL_X|MAG_CAL_Y - -PICTURE: also automatic Missile Launcher and Hoist in one direction - -VIDEO: also Sprayer, Bubbler, Missile Launcher(1), and Hoist in the other dir - -####YD717 -Autobind protocol - -CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9 ----|---|---|---|---|---|---|---|--- -A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS - -#####Sub_protocol YD717 -#####Sub_protocol SKYWLKR -#####Sub_protocol SYMAX4 -#####Sub_protocol XINXUN -#####Sub_protocol NIHUI -Same channels assignement as above. - -##Hardware - -###RF modules -Up to 4 RF modules can be installed: -- [A7105](http://www.banggood.com/XL7105-D03-A7105-Modification-Module-Support-Deviation-Galee-Flysky-p-922603.html) for Flysky, Hubsan -- [CC2500](http://www.banggood.com/CC2500-PA-LNA-Romote-Wireless-Module-CC2500-SI4432-NRF24L01-p-922595.html) for Frsky -- [CYRF6936](http://www.ehirobo.com/walkera-wk-devo-s-mod-devo-8-or-12-to-devo-8s-or-12s-upgrade-module.html) for DSM2, DSMX, DEVO, Walkera -- [NRF24L01](http://www.banggood.com/2_4G-NRF24L01-PA-LNA-Wireless-Module-1632mm-Without-Antenna-p-922601.html) for Hisky, V2x2, CX-10, SYMAX and plenty other protocols - -RF modules can be installed for protocols need only. Example: if you only need the Hubsan protocol then install only a A7105 on your board. - -You also need some [antennas](http://www.banggood.com/2_4GHz-3dBi-RP-SMA-Connector-Booster-Wireless-Antenna-Modem-Router-p-979407.html) and [cables](http://www.banggood.com/10cm-PCI-UFL-IPX-to-RPSMA-Female-Jack-Pigtail-Cable-p-924933.html). - -###Microcontroller -The main program is running on an ATMEGA328 running @16MHz and 3.3V. -An [Arduino pro mini](http://www.banggood.com/Wholesale-New-Ver-Pro-Mini-ATMEGA328-328p-5V-16MHz-Arduino-Compatible-Nano-Size-p-68534.html) can be used to build your own Multimodule. - -Using stripboard: - -![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t8214655-87-thumb-uploadfromtaptalk1405598143749.jpg?d=1441459923) -![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t8214656-102-thumb-uploadfromtaptalk1405598152484.jpg?d=1441459924) - -Using a [home made PCB](http://www.rcgroups.com/forums/showpost.php?p=32645328&postcount=1621): - -![Screenshot](http://static.rcgroups.net/forums/attachments/1/1/5/4/3/7/t8226720-197-thumb-IMG_20150715_230603155.jpg?d=1441816457) -![Screenshot](http://static.rcgroups.net/forums/attachments/1/1/5/4/3/7/t8226719-72-thumb-IMG_20150715_230024065.jpg?d=1441816456) - -or build your own board using [SMD components](http://www.rcgroups.com/forums/showpost.php?p=31064232&postcount=1020) and an [associated PCB](https://oshpark.com/shared_projects/MaGYDg0y): - -![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t7566755-3-thumb-i.png?d=1423810885) -![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t7952726-108-thumb-image-62c29cf2.jpg?d=1433909893) -![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t7952733-114-thumb-P4100002.JPG?d=1433910155) ![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t7952734-189-thumb-P4100003.JPG?d=1433910159) - -If you build this PCB v2.3c and want to enable serial mode for er9x/ersky9x, you should do [this mod](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/a8180322-194-multi.jpg): -![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t8180322-35-thumb-multi.jpg?d=1440422869) - - -###Schematic +#Schematic ![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/a8443844-119-multiprotocol_diagram_rotary_serial_2.jpg) Notes: - Attention: All modules are 3.3V only, never power them with 5V. - For serial, the dial switch is not needed and the bind button optionnal - -###Radio integration -You can 3D print your box (details [here](http://www.rcgroups.com/forums/showpost.php?p=33294140&postcount=2034)): - -![Screenshot](http://static.rcgroups.net/forums/attachments/1/1/5/4/3/7/t8462144-54-thumb-Multi_case_9XR.jpg?d=1448575289) -![Screenshot](http://static.rcgroups.net/forums/attachments/1/1/5/4/3/7/t8462145-106-thumb-Multi_case_v1.jpg?d=1448575293) - -##Compilation and programmation - -###Toolchain -Arduino 1.6.5 - -Compilation of the code posted here works. So if it doesn't for you this is a problem with your setup, please double check everything before asking. - -_Config.h file can be modified to compile with/without some protocols, change protocols/sub_protocols/settings associated with dial for PPM input, different channel orders, different channels timing, Telemetry or not, ... - -###Upload the code using ISP (In System Programming) -It is recommended to use an external programmer like [USBASP](http://www.banggood.com/USBASP-USBISP-3_3-5V-AVR-Downloader-Programmer-With-ATMEGA8-ATMEGA128-p-934425.html) to upload the code in the Atmega328. The programmer should be set to 3.3V or nothing to not supply any over voltage to the multimodule and avoid any damages. - -The dial must be set to 0 before flashing! - -From the Arduino environment, you can use this shortcut to compile and upload to the module: Skecth->Upload Using Programmer (Ctrl+Maj+U) - -To flash the latest provided hex file under [Release](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/releases), you can use a tool like [AVR Burn-O-Mat](http://avr8-burn-o-mat.aaabbb.de/), set the microcontroller to m328p and flash it. - -###Set fuses -Use a tool like [AVR Burn-O-Mat](http://avr8-burn-o-mat.aaabbb.de/) to set the fuses of the Atmega328 to: -- Low Fuse 0xFF -- High Fuse 0xD2 -- Extended Fuse 0x05 - -This will make sure your ATMEGA328 is well configured and the global TX ID is not erased at each updates. - -##Troubleshooting - -###LED status -- off: program not running or a protocol selected with the associated module not installed. -- flash: invalid protocol selected (excluded from compilation or invalid protocol number) -- slow blink: serial has been selected but no valid signal has been seen on the RX pin. -- fast blink: bind in progress. -- on: normal operation. - -###Bind -Make sure to follow this procedure: press the bind button, apply power and then release it after 1sec. The LED should be blinking fast indicating a bind status and then fixed on when the bind period is over. It's normal that the LED turns off when you press the bind button, this behavior is not controlled by the Atmega328. -For serial, the preffered method is to bind via the GUI protocol page. - -It migth happen that your module is always binding at power up. If this is the case, there is a big chance that you are using an Arduino Pro Mini with an external status LED. To work around this issue connect a 10K resistor between D13 and 3.3V. - -###Protocol selection -For serial, leave all 4 selection pins unconnected. -For PPM, connect 1 to 4 of the selection protocol pins to GND. -The protocol/mode selection must be done before the power is applied. - -###Report issues -You can report your problem using the [GitHub issue](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/issues) system or go to the [Main thread on RCGROUPS](http://www.rcgroups.com/forums/showthread.php?t=2165676) to ask your question. -Please provide the following information: -- Multiprotocol code version -- TX type -- Using PPM or Serial, if using er9x or ersky9x the version in use -- Different led status (multimodule and model) -- Explanation of the behavior and reproduction steps +- Ajout d'un switch + transistor sur le TX +![Alt text](telemetryFRSKY.jpg) diff --git a/sync.ffs_db b/sync.ffs_db index b3d9648ab4d2a4b3328fcc4b591b2225552303fc..59c8138eb586a0496dd45c9b30047a55b7b6421d 100644 GIT binary patch delta 625 zcmV-%0*?KV1^NjRMsj6kMrmwiQ+aM<00{s900OZRegc0G0001j5L(1h`bs{9rqVaF z;z-z10ssI4000002>}2A00000Ur*H%K=2PA3ZG%qAV~kyLUg0bFqrP8ZgjGR4|j=U zzQNe_e1Q*ex!fd(84(oi5fx8iu%Obxg12|2Bw?&p+7b8vm_^v7Eq5Lc(lVtOnLkBCJB&z zx7Rhgieg?UFgM4Hqj9iLxl{Zb)XrbOsnSt60RR9Cke*GE;q6s-O>LvuK4I=Ky2@6Xisc`=GP_o3m5?%%Uu@rMjAj?F+({{SrB#u&XB zRs11X+z7+J=fL8P7~Ct#R!5iHKn^!_hu`hN-* L-^&O9#*W&=y2K#f delta 27 icmeyxIe}Hkttd6sEi)%IxH2!9fs=uOfpMcy9TNb1KnIrq diff --git a/telemetryFRSKY.fzz b/telemetryFRSKY.fzz new file mode 100644 index 0000000000000000000000000000000000000000..7f3aed111bf21b0f44ae874241b38578ad07b63f GIT binary patch literal 5198 zcmZ{obx;%zu*dIc=|1V>gaedDx$9G6quI7k5iC?o&@WdE{W)=t*W)?Oa| zirPA=hTJv*Mz+B~%Iw!k(Bt%Fw8!{^`*!^7*B!PlCRXSFh>@7w4fOBuS{9y4RK$sIej5LMrH zZN=+yVarQOJ@u0EUwC*xN1Oh7IM08)G+UNn*+3XBBF)tF&3acJGjoAJTt7Tg3|ORH zd|!Mtula-|{ZGq&CD|}V3C2G_d8htkjy8nXFDm^*SiW$N)%T}7m*wlZi7g9B8%;|K zJDb&!S$^&mNqUhtR@8rQAD1-utC?DIr@aK@R(vj*@@*ntDc!eE9W0`T_GW*$QTvKd z-Duytvk+5+$}Nqad$rwOG|~ZSv1CO8c73FJrv?zy3*4AMD(Usg5F7K*k#6C9#OZks z@+@IA=nuF`$`}>t9&o*af-jA_@!ne2D(7u)Tn%s(!f4Q;(7ahq!<5~_K<97uOK4yRK7dh`zmv0AUceG_i8 zxvy_M&vL~h5xNlWwpdqC|uhbo9!*`1()eT$*3Z?4q+6bHdL3H7w%G1;w$X33h0R6aj$iuTy@$lxJw_ z*d)B;Hh3d!B)Yh{4nJArmaG@^S$>AP?WN)|WfW<0@u#1Ps2st2PNf7vFPb)|U<>MoZJ3oN3Oq z-W=hi<}WkD0>$$a*#pI-f)+qOg!XJBak@y!0PQn}eOL8=a#81g zd<;uVabq0J{$ibXESyOo-$M<+V2@WLP4~-Tx$B3fhm|ahq`Ri6zD;|v{m`rH>-XPj zFI-c9MB?o|l880xTz4|XqpmL|nTVsU2z!|2i`G`9XqThY`JTGRb11?rsnB;vVpeU< zn$#qs0e@Gd9}(vXEz6;Ya>wu=emS4<15 zcF!lxMM-I9O%)7Z>ct@pOkS*qZO!6uHB3fRAT)P)uC9jsGCC-WE>+RBY#npD_tqJ# zP~L|wRnfQ87f7|$8KET>6#w!UQMdp}Bl&fweG3cK#geRucoe3Wh$;V@k z3ev;@GWfNo`zRtWgE)|mJHUbqx?mZD7%URlH(_2C>s8$NOUDN(*)ti)$-N9}1y8$^ z-2d7|PH3*D7fq%ihuRsGf>1|Ry>0nG5Rtx`O1^iv_N(x-H~-B(XZ@64eL7U^91;D# z%`Kt&n5gkShnS7@Cc4?1drbK0UJIi93^!U*ox5u)eC>zV*wh7vgvlV|ppQqBcmZsoEyWl>{n$Q@=u=WeMmLOlYl{( zR2t+;8zej}(SNWcx{L83@xi3iB!$#5TO%bjlT6f;@iuDOG!bp+7YG6el-MQ>*Vt(q zcnpMcEIDfX_P1lT$>c_fKHR;irtGs-qGD!2t=vfK3qk2zYY|=9fQfr6w^b+#q9MHF7eWcNdQ{em@ z8mm*4wgaD4O%%_YrNFBoDyc}!-D?D+1E&bw|BRh52rx|u=2>AfVnRu8w?~c*vJNVxa=NkjFnVcZC`k-N1nM;;(W3Qd9jYvkBgYrz{ z)TEf>tXIGdBXgOTXJ=+3GA%X_22oltVASH63_YE!sm#oyo4SnDe6gGi)CYUh+(c&k zr$+_*hD}OVf{FZ-p47KWpA1_i5=_WH;tMNG4b@fHaygigG52D+Yrq z+cyowog8Cla2G3|J5?J(^nr9yVYcK*o|-C#ss_q4%wt`u3e$uv!huZy1_?=-RY)W<*PHYVbJ^C$*m z1Y+%ZdQmP5X__n8V=mm1!e%DC{>j&9**e1hUz-K6{Ac5ySdCpMO%h|_^#68L#)D`I z6EAJIr4}Rb8KpQcZyoDymRfyT$G{GtUjXU!KRv^*_3h^JDlKqri`o% zFPpcJuWW!PsJW(z;8$R4F}x#P*f%`D5)=<0{w<33DaZz>TsXNGORwL$r8sXxI)>Oe zPmVnrC0`{d-Hn)-hAPBVxQ=NFwGfXv=OQY{L^2XOHl4i+ceO#q^hkFb7BVxR52{Ln z%C9m*f3|bY*PWYCiHNlge2M938l9eD6B<%9yWlRd_G?QQ-IRPMPWRRB?VeQ+n(Z4b9noo=kA=mM8w(*rZ>uA7 zRKsS~+F!+uuz_Gh={r~~s==@(9;o&ybI6KzWK|T}7nmIeIM5tOxlhMgQX};8`P$p= z=5t88UQs+HwpM}9Qmr^SSC=Oiai@3txjyf<6;9Im_xhYC*H!8Zlv*c?$5lP&iH?K~ zCx*THq^ePF4tGfv-{A#%+R{1Gk`E`D(QEYup|ELAKNDWhZDJgFxUWx$+Fqd}C_|?+ zsKJKbL`5+q2#f4z9G*qTfYTCQOO98G1=4w+q)88uZ?0W~@l>`|HOxP=^V=dTe>IR; zmeRZ!v?v3JgducSLm0ll%bv(1`uy(L9!dKMIY$+NFa?NMu)clN_TP}g%)@GH3*%7% z-I8^Je>Z?#$v)RFPO*w0DO>(LkBe}Qh&6i}w3IyQAe{y1tyAK96#vPXBwUJOG($p9 zmC?#u+@S@;ffPal&zpe7_;513o-nKsgvDKRjpS<^_-uMYhX^fl%f+rn^P?vr|94zy zo{Ufel&d_!v81)2W^jy3q^1YV6%ospJR+wO=uk4h=g@3&zJ;IpIaiAOYIkD-nz8%L zCrS!Z$Oe}0dcx0KFM^{~;3W0gnKhqr_onDww!7EEFQD&&HnLl<{<*`8cT3b%JfVVy z>Vvc{)>-W21~xA5@XvGgE}8SH#0X5QJ71|#`T2Xaxv2N7ZXpa*vF6A>_&ul@-sK_##ca_v(BQ)voxub6x;87zJ(t5&ekBIj1n1;C%|n ztIV?qI}h`orCQWx6Oo%R5)h%>E$F{08X&%Uu-jjIasFUO`0?eWo-=}aebB&XG~{Jj z6I*O|8&kp}Lv2~ZM^|M_i6P-)z9PdRFYJ}%uO)m2QRg6N@kdvm5XSrZ@#|NKsf03CN*(R#AdUdq|2m2i{~`+B>savva981msYDSVeDJb ziv9tur$O|4lUd+2u5rF^zjbcE>#Fx2MAf{tPGfF2j@odZ*|xzAv-*gBV91bFG>-Bp zBkmE-%TjRek@;mU-ILXh43AWyIm#lUMHb5scIC({cx>@*9N+0`@;Tko=P#_ytKbB@#A?>-oW3o54t$yR zwx(^421_>|h^=yu>T;3ps~rGUAR1*GT$YagbT`JQzs=m? zlk>IjM<`gdf>XY#B&l&MB-U9rL17O(}3##05e z)Pqk@?)?|g&hWyQ)j3+h#WelrklcpBh1q6Jk z4$KD2BCUR+>9|DVi=(rPZB7k4qxgei^U!S#Q+CYMHVS53pk;sCG#=GkX_H#G#p@69 zP*s~CaUR>0&HJO|Asn+HPp+l{l!_TwdDuGKQILSm)+O4w5#1eVf=po9(E~sANEBpr z)&4T zN7ZTFmlaG{UFYaTQY^Ho(i zG{l%i^Zb-s584|2wzl?lz%6t6FKM>AX>;ug!4;o!8;?OqApEyoctQzPk-ZE*23CF{ zHB9FqkMST^00ofZW1uFSc5>{KIyY>(j-yl*lwOBCu+Y#J1N8q!A z%z9~hosfSwviM%nCu7B}(g8LR`|w7yK-YA~IYR$t9h@eZaDf!KsB*`N9jiP~B@_Tm zk39cGKf4v-mG%;ol*OZ=4MnOT)Bohmq1q96>=+q8W6Y5Gn=G&r5}OqS@1@|mF=b2t z3}^m$?EOq+xj2G3ReyP+oLl~Ft};#3O^!6OQ2}zS@f8MED zluyeot*}$ox^qe(7yiHZOo6r3@og$rt3JTv2El9Q0!b2oy>tG#HbyLJ{JYb#=itvp zXHWYiPp?$NUWzd`I1c3)+ia!%Q?2`XiV@bM^;ovFk-~psE1&LY5Uu@se$i3i?cV}0 z(#&tA81s0&nMjm*io*g6?60_7!+={ydMQ3R<(%XL;@_(1MG6wtAJ)vrEQ?~4-sNc# zLyE~If#fX7e}}cmV-V6Th6`$^fwzM?%C-|IP+cC8hD7kMiwU7JKa4rfuh$VXo?QbC zo=P3nkw0#b8>djJ#T2>n#WzhEKZ<{`F2M$GI;c_w6eUn0`xAW1Xt)DSrM;D4^httg zvSPaxt^1eMMoL9?0sS0i3~;n)ww2)*+jtG^<`vx`C-okKb($iZcs=Icsa_l4Kk+ml z=pFA}C-VOd@3634pZ$xgr3%CV0RDgU_mBPofd9$=+W!H8TB_JM|5bqhT>4+U`9}=_ Gfd2vYjuMCf literal 0 HcmV?d00001 diff --git a/telemetryFRSKY.jpg b/telemetryFRSKY.jpg new file mode 100644 index 0000000000000000000000000000000000000000..2ce22d2436447bc647475f85b0237f6c5a9e4e06 GIT binary patch literal 72125 zcmdqIdpK0>-#0ueDMBbjOpzqJtLzGytE~_di4c<{#>6CKWXxRI?_Jqm5fieDF@>== zll`w$_9i37jCOWeQ;e0_cvkoG9{2kk?{WX}9{2Iw$8+4z9M+m;)>`K}zvp?b@8aU}EC`^BUOy^AX#!b({Ehi5)v7rJxI_yJ1_zwr<_BZL7HWwr$YW zQP6qVHaT(mgU3#9S8()}&x(wFSDdf9xL$K}_qpYJ+s_{z5E2@8KO7hFASO00J|QtFIWsFe zCpYh($N43t&&tXxDyyE?)i+QZo0?l%ySjUN`}+U&`pwAb*!TqF!z7c3<&Ht~bUw#%P( zl<*E#&^Z2Z$DT8fieGl_)HHGe_TIcVEU9?Nn61VAE!w|H_Ww_?=>L>t|1Q}7D;E>C zYpWPEd0XXR2$)E8q$C;kzizsKl1OGh*X1!AHOb&XFNvFuuO%!vp>z??D;|%<9^N!P;%A z7auTUje{$6RRf7$2~O$K20zw=3bBWR7AnF}6 z)Ym6yzX8AYkp|g4 zf)g#{ffUP#XZ{(_@v5yI+{48uxp$aTx7YqM6TqRhkTXuO5)IM;BzCW8fK^XUfF6ZL zf=51)_Gy6LKnzEzcZw*9KL+}ii{3TmH)iqA;C^z<`cP7!W*;Lz@1dnQ8Qs`uwZ9q2 z=w1|tb96CGm3j9IIlBp16@0t^0CS7x)GF$I00&QqPcOzWLo=r zOJn0lu9-l-pZ5wJt{`^0;_bNWb1Sc^SCUYGlkB7}o47R3*4JhC$5;lJ;>|%hv+gwb zoI#x5jZ9pOzz-dl?c=`r_xyK(z*6tBZ->Juj8gDbCINFw^n?iP*0UmEtXCPhdE{2g#BATis& ztOJmE=>V%|AATo?xR>y5Ms2)Z7Z{jR>fVH@;7^Px^{T5*)ZmRc(yra+o3L0DgzSPl zBB`O$xGn3se{10r*FS`(HeuWN!gLe*hp+66UR`7&Tt1Lsh`%Q+-Guogljv0BvJ_Y9 zA}|UXcDeWWvXZNduPvDS{bdQaB6Flxq;XPRUP?ekoaI4wnuQaC8fD8FJsapHTCnJF z!dP6EZU0{t=>KiUN2%oHLf~;t?Q-n|^Gl>|Jhe#oAvOYYFnM9bN1-|S3-hv1k;IhV z@hzDeFM8c5pXfZ9i8T_ag%v1;@LC`(6M~z%I_Ao|10CjgE|MBqOHtLB@Fp`;cVeHK zJvGgPllNEPN>E{mr?qp6EjK;x7>(XOVX#C~#_LBoQUtfjCnVO2-aaq;C+@2F&HG;)S2fi!p&j@36oqpNMU)rg^y`y&;&eK=Yjkn;Vuq)L$1~up>*q_9|iDS)Tmt3C`UZd){tz(-o3<}hNXXqhr(WAZ8hQC`D;=frL zw~iX4k_iW1GPyRp0!wfSHei@c>8_!{(nXZ~s%Mb)&TkYQ zvOAoj?sv~(yH;dCgP%Q0@*n>t(%>GtOe>v(%k|_r{Fr3oVtSeJO*Pl%ZzLM0=uSl$ zjB8Ts<4s^2C3aIsf|hHv+NjAJJd4LQOP`vP48C*fe-Ie@)V34(xMjjHmY0{LcH<}e zr|qw*)^VaC9JnXZy^>6?=ZkvjfE#LZL*L^Hm;^0(7T6X*+KborjSN#Gr9y9N3bQtg zP1!%cez*9^>8&gq*%)d;it06Aq!iwovG&e(@ikCe#3K!Df6RBr%Zw9!Q;<_uvZ^1> z^DR6DvMA;OkT)CKKm}blVLRNos~ev`9sLdBlG%YkM?R~FmXx$bRTf_^mP9) zb=_;`W2c{=-?k>#@bD|v*g#C+wm`jgC55-I_v}6^Z=5-xTNB(@^Zm`!M}lTzXNyP% zEaW?ZQ@lB7aWU{AO%tmb3L+MLPmn+fQ0Ux9``qn;JInJ0PgZ{fiQV^yUS&#IyfV=@ z=zlfAxOZl-i5)f3;-g{B;jgy}H-rtu+bC(#B)yKfEWy_Wo1EH*jgjdrNr4BzU0d9F z*p4n6;671s^qZAt+`(MU`*;M!x*TIzap|4kbL*QMVS+1@p4ZPFkQlu+Ai= zwdtw*)RecoUU0galO0{NbKCCI2gW1YrgXO@+by(85kr*RE@C91C0~m||KB8>b+LK&c5Ps(;>~)EIun%VWxu`SCjXXBkzn`}%pk z3A5uK-4SXXpB&pxHT-bDJ~e&l%F&Cw_1*8E-^|%p!}#G7MP7shHbn45ADX)C>ewXA zK+HDftCRLpdDW4@1}U@jDeYHe%ri7kS^$3>prk8&`aDB*0 z|FCuA{qx4~M)%Y$i^w)Ajf&Pz3cB-Mqvc^4waCunpV*v z9M9-Sfrd)U{7C4H;X$h?OyCL`%!d>MSKdRgTdQeloo_Oq?=*l&G_cYaI8bS$%Yw7T zlT&((D+}skz*}_-AZ0;q>!r_pV_fo= zFF!e^S?mImn&3urGcD`#Ik1Imbh(*J$uKV1_qNWXF^?UEawYCWXHAy1yXWM_$h-{R zITofmUk(!*7xCUtc$_e(T@EZCGf)}n+V@=}-ea+>sc4y8GxuoxdywMD#FzQvSj*^{ znTX^>_M_Z)L~}ZDkGRC(di0}S(*HsP5-0ne#zR?5JJHTZT%U`=S}Qow&nDd1Jujx+ z#DHYjYhl-MbYF2JJ;8d|m~7ae$N3t09SraEIshyM0AS|AKDrme2f^gCNy~+NI9@^c z5-(SIZJw|dqyqg&?)Q?s{Ir&sP8D)tJCC&6QolAJXxP0!9QfJ$z%{Ymkm6ad_1yED zYgP@(Z|WdyUjW>Ni*@m$u`i34{ zVyde{!P1W!^J;g0tAo33!=#TR_6cmjw2J6FkzzdtwJ7tKE3qJ?u z1m6rVw4te{$s6mCulF0SdR))wky6!1z9N{8hUwa2gcg^9j3hnmlHrZyh4;KSD;GMV z7e>A_!*D_RwKp;^`bFQul_kxb-1{i;0K7k3Ab*8}NF>g-5djytBC*p0Pn@;)fkLnF zB_klRlemTG%Ss?<`Wx!sLHHy0gD1l>l3RatPprF_*^cPl%)fzJQZ#kc`B9Q6JHL_byHD%LYun>CeU1T+nE~^Cj`vct+{>Shx|dIs zq?VrOyPWL@UGe64YUvSb*pW8|j@jEUj^gjOG-tlo{lt*(y4V9(#a|HnN(Z8=3Oh zv%@J_CzGf`0$f*A7m2_*S@0;U3kB*W{3TEzRUx?H}&*hqe>)=Z^ zNrFZJs!=wS+l?c7VH5>-9HJ|a*K}JasF&15NsRlVWc5cja@|^>>c-at`CW)QdJi2u zf?QTit0at*0B1y!O5U>B+`F4UraA4SG{r@g^p{n5%^|&;kH4Cl8<71di*&ir6g!&< zrmPHZs@q(*TN(J=5bQ_noMi4-VF~0C=60If2DIkpa3g0G%Sy!S_<^6}pR(i{rVS#e zPr95u9R2MZvxw}Y2Z(3!tu{8cV>Kdj=me42d@CUhFr00C^lZ|7zSSiMC}6)YC`V8H zVU6+iuJ`~VE>P?0>Ko&nR3kk+{7a)}c0BTlKQdx`^(xH3f4cv1$f1HX#&M^>^UbWs zIwxMAZ+`aiR#u>Kp7Hf3&Ly8Rvy!u~XWwF`KEb{%)!ujHb?@(MUiaBr)uU1n0Lt(K z+*wH5gv}Px6)eqwg%N--OcFC#Mxf!76)wZOUf}ZK$#AJ zVIh+K-1A|9Sfvz0fg$<&u_*cJQekvt@)>LsvNVPX(h+#w>T_EdwHDmC3y$l(c91aR4=(Ujf|`BoFG^L={XNFOmm6_ z2RlY7+q8SHbZf8Yq27cGRGQfO+Ff*6$Vd5mzDTWpND~R_tn_uLI(P&gKZUST99l(4 z8^*6LI=$#Yog10pJF1*-_pMnbFd}$Y&st8=t5s|rGo4biOIG|8pA{B3yf?6!?6a9{ zJJGN-YIEWDsnR2DOvh|rrQ4k4BQ58lL(hWx)U5i{?2xrU?MsXXGV<)iDqkOUVIq|O zPTO^as_TypT}ECS3w%~jA6;4cE^imvraNU**4WxuWEPLp%G7auG>QCGF9-u$_|C*m z9i(87f=GH2)MBHQaYbKwli)lcf`i)hl$-7PvhkvAgbDLDFq{LAzcscJlwNi`U_-06 z5U5^eMm>8#cs!RvOqnrg$(*om%A6A()&1oRc^1ha(vA*|dI2<_3Cz_Zb!tZ;O_ngC zxKUeuI6v=1N_P_wjuXpHNGCHa=>0ZZKiWd zbKfah7WRWR?*gE`bdY}#zeSiSQmZ-s4K7ZDqrFr*CNvs7ths(E-*+(wGung0w{RiD zlqSGdfibrfl{NM+S zwUEOIUKmd=hU<7qz0X8L#I1`Z;|-Hqk0wscrHjTtJ^C1T?wp&QQT^`c&v)MZ6PD%f ze5KmJ`P(otZS z`{%ocYf9*yuJZsQk+zk4mDDu|!G%G1H|}8ayY*<3K=UYVuTh%v`I7F4NbG+5$XzrA z5Y3hja%uRxxzTlOF8X3&+Pi96w~}HI^G&^JfxRy{V9dk_i^|^_PpsT-ih93`OU?YU zY??oC?429{e$n?8DJE6^_aYv&SLiq(*T=)NKkJ;D`QeS~YwY0Y2NP!(;Novv%VwL2 z33*=fk;O()kS2<&0X#$ieziV~-V?YJ1G=w6$F`Ca;0(7ageJp)|pJ@TGR< zU{f<4=%K&KrtPIQL7JqHrZyNs+`sNl>}r_6daREWBzaF*+Rgr&bNf7Xh@v$GshS4c z#6h_u+$4vE>mEARe2HAAw4Wcfe)%3@1^&84X`A8KZ*0Q8ZNe_3p}=I(M9$InBE{gX z3Dh!Mist%SMnlDwoNv?&-C;~g6VK=T-p?#~%e@?widBkC0!QfD<-){U9muyMtGbM@ zw*3o#+BE+qi1f&nKFS#}R6uXYJgXZd&MrS-pPQnc(I; zky`79&+*q482CP#+El=OqeCI?Gu@bwh{~x$fGtJ!AHzWX?;26Xb2yQU>H@vFw}msx;OYa6fW^ZjO8LN`dFBM z!zWtD3u;6~iY%HCwX zc#VZ;nZ=iNj*_OR=}p+NHx*_a%AV8j zgQOCU$3OjQwoO>RAQQB6VeK-~wYF9ybZZ^UP|T>dQ)s`}U(R~H|Iteu%}{F2qv5f5 zR~In|ns~Nlhei#`UD){M$H20Z3kgGQrt+_*viv$4`R9;IOues?Gv~)F1OpL`O?gL4 zmo4rRT!*Y=aEo0c<5mWB6Q%|h^cJZO3B)@bU1Sr9jM9*qi23G_Y|Xqw-}$wxPgUb|ywZ#-&moR2Qg zw>KWatX>MiY)wNqOh_q@+Lz~da+uHw^fTy+5p;PLDh3YRiLZ!^V56q~xo+PafM}R$ z;#jO*ERMsPOrz{ap|u<4krREQhmm(?N6f&1n@|5pJ&o5RMtZOgR_8s;bD6#GW-E@#Ke;C}$W-&s-BHmoN?^dL*6=Cb}+COJ0 zH|YT7bBIWCD=}P2upa^84jj3GhIxd5uuh=HQ8N=sLG!n*1*@=lcY(P| zgoSy^dW>BjyvK}hnWb+Nc#MUmUHtgbI#B;jz`FV4V;}9XSR?b-!6pqCPH*{%OVhE| z?0j=P`&Rwi+L6?h^_9LkHL<|LL_TwPu{ zKwTH?HoP<(NZW_k6BdRUGO;~6WG@!sO&t>#|MQi~{fwIOyb?EeCTl*A_Qx2fek8OY z?dJQgpN@?xJvXn*GG%8C(}{jW@E}F7N2y2s6ez_(`~}}hI{~>t4uqYeVNyM$+#W`i z`EOJt({_mly^ag(h_`g36xhPS?hFYQE~a}%h9U5+!G-q{jIq&03LW$jflk<*vH-D1 z4x?mFPCWo0GVDT5>WX%(Kw#XZF%$Yj_*VK2*|Z0yS;mUYS_+WWjoL~(gwFTvee;Gl z6aXcy?Qf5~$Hd0pj@Etb6XBxcZsM&fR|RzQ3?YyCq9AaXij@;63kx@4-pG_9^&z}< zC5X7rASmMuXZtf60+o81mWrxw~D_yxvYI-5(l);qKXswBw{1051#Sz1$vKDHx zMWqTddJ}dV8JEH(i6pB429GYxr+cp?vtF=X$;PAV2K(S~Bz3$e7d3mkkgta!Hf+LD z2?xRISLTo}Brz%2hh1W+V0dsTiTL)joHhy^?C)ZpyT9(rBdFK6H2=6WCJKSZa;NAp zE|RCvKE7s{_I5FXNf5c0oK>lnmVzx)0cEOh!nVterWYd zB5{{7TwI_$E;%__yz(lqd4!Xmo2VYCQV*V_299a_a1+o61QI9tkNYS3uuzN`8nZdhYR z>Dln`&$jx3UR=NCW6kkqM_&<+L-Ouz-#e$KE0PT6uFPros+mS<&nYcGf?kO)pe`SS zcOLm(XV9RJ;r%Tn)6sBM(6G~0?!-_1&rq`YJ}RClWi_B{nfrP+_F?iiIqMB91PJZ+9 z&J|J_-PNQN(sl#OlfjkX*$do9qk(IMh+Zqrm&5I+ix=yzUH_MuFHIThxOf&jzJS}Z ziUPG-@yZkJmuDn~MFzBLzL9pfnrmNm`A3ZYtkA5VT$v%s!j*+a+I3uQM+80}s5U6T z1mgq6YvkY1O5sZnAzA+_U|%Atu|aA6)&amO@W3J$@0$U=`6%|K*4-@_BXU1i`lgj! z)B(>@_d=Vn7(ZT)zvYUFZN?iCgmd&GCyjVH(0bnnb?Z{Q9p6--jCyE~ttfJTkjNvjafn~GyM~BeE_&+ncM?tS!T(5#k%tUKn?1nXum`FL; z@P~Vp0^bpD3WP5^LZeC)#v^=?>FWE2E$#S61$%`FB7G5a1Kvr-I@Gm*e%!NjGY`3E z+3TIM5}k919Z0M}8mCP*c1E7-Mdr|Vfka1Y)Zsy=@vrU84ehb2cg0qbUD#+ia1O~d zpX&WX^j0JRi4cenpRm*~oe9WqfNy2+9)P4O+ymwMZ7S(y5)Xq++Q>)6J8+uOKjsf4 zRb+~%pZQ_kLMe6=y&XYTzxLCIG*GAh_>z0tbDK~GqF!ZkdeBd?!e_sHLW{6KG`P*r zl{%%xSo(D!%jK_kfQ;QY+7>!nd)bhG=o(>4WFgGLYw>sCt%dnS|Azo}PHjCwWB_LI z?twNyH^dWAvf71LRJa_*OPSHG<5T6Y;zf$6cu{DWFEH%3rMb%^ zOh~EM{3Gj>l!PBp$|IknL;f;C`C^@xkG_ffB>+sc;~==4v`&i1L-i%K&@l3_lR& z>;clNO;|#a7C6lAz+P?~7wiS3x)k$!ztDk_ozvtsw^iLj*=~Xs=?n;4*eC|RCQusY z4+7fBcRm5y(P@L-`W|)wtJBLI3+gK^&->}+=0XttIU=*a=fzapnf&jCA>4S2Qx`AX zFGzHn;$5OOU1{EveKzb6;hxQlbItKq$Xy|N+v=?jy}8?m3MI#1-_Z@Pqb-vdY2_s#pQ0V|5SV-T?H$PT=+n{ zcIElPXtplLU+XA%$GrFao7#PhGTSiM)ex^>ZluU2FO9e)9wr!}Zy~bRh)oRP0SXVo zQeF*0^cCR_lMD_5)Kgk!%%P+gMf=9+v&owj{r^^#)-@zjd-AY7Oo7M^;n5#uJ?Kwa!*kb+EFC|1a+=eQ5t7w zL#(}r_4rcgB40J-UwWnEkNo1j!zvb3d{=uteew9x>Id?@7}i8vL){uj@RDl zp5x!^uoq~4-Vo5Y`qicIVn}rt`Dl)gbIO;Bll?P9ZMMPj6D(Pf5Ritq1Xj5?mDOW% zu>n_lW?xcYtZ~Y0%K}W$KdVQ{7s&1=Pk+rjKRLy7{UKMq348OtNNE#Rrxm;jt48%) z6-F|CrV;s4q7hdF;F+etqi4K&2LX+TyVITLF_1Ol5)M)VXw`XM!WZOYklB+#l#x)HSiYz9;^~ z;{&))rzQR=aXWbJ%Rh(eEYZIRSN|EV;^fKQ$k97@tL~1;2}X|bi?yR{MVWGqCx^?w zzH?B1W0)UWHCicr=08S0di5%z@5gm!9BLm(F?0@g%x4SKj@HW)jk%)dazEJf-S#}pu49?Lv~jBHBHz>S^oYJj>zGN${dI>C z<0)0)nGNO};!wT$Q1|DSw1}z`jsx8B+r>&Jn@2l2&&D*U*@a|fvhU%{w)@1YuY1{X zZ;Y2)yyp$li=ML4sJc*H|sG;NoIN@&O>PMo{)^Sg1^ z?B~2R4A-v)@2S{1+&lcl&$i>*^n3a20Hhu**ct#W8-Lor2f1tS9oRM|zuk&72yR zZBvh4%|;K#^t~O)b?bIRHgt2i$9sYe+y-{3?R5{Xh`rKxGvJ+h_DGtgrPh%ygR9kJ z)Lo~{$3IJ&Af8DcCC4$Q?%Y|qAA!O&G`0R%$NmrvOWM^F##r@)=_#fAM%0jp0d)J= zIj7xK5;*7Bqo*gUyY8lPmX^lnPP7^4cR(Nj{YJ%!@d}3;xbe}hy$5wo-bwx)chUCU zVT$D6_t7Si5L5sKkdEH}4S-|`&Wb=`j(08vHAJ7yB{d!63Ucf5rqJA;5gZlfE3p%S z)1;%tOp5ST<5GZNtS6+|y zMbB#sT?{8vP5ZW=s08>6Rv$bTA!{iCkl0OvJw`kd!0M*QiFN_>ZaNGMqwN#*J{a{^ zmjYZ8eApBze{v0mRQJA^9PqBp|AB8>(%4!gf7(g#Du^o8R?u?$F&_c?t}s1Bnf82# zO&Gga2t~OY3YA;Gn?r=x-|oF87|C_zsR(oEH&^xwBDlL``9}CCFox@bO7T(!5WMYe z5W6RysA7rb##{lv0xB!#WBRYWev0$pG<73WAF#UNasg=0soOd}qoKkFKf9SZ)kt=( za3^$^m#~aJe~8tvB2s~WKyAW`%`^Vv?$~v)UM`d3=vZVDqH(z*{c08z9#li*L+=Fk zC3S`5_k-O$k`zHxa29-s&#NXZYqW&O{zI2fhqpG)`i5CMo- zRwJtC)Rj&Z`cfhP22PuYwwE0As^?b36Es9`Rm_%^*hF<&g~2}?rj_YdNAMb4zt}a@ zuCnq{H9F5P+0Z!3UEk&0xN*echWge73DLet9^_X&%OZ@@L4SzrAc|c;u=D6>?1qim zvIQh*0uM5=-yELG##kL8cJ8+%aus+7gw=H4LGX@81mO?S3`wz;pdQ>qF;PZ0X z*B)eIUhdToINeN6`4Vgy(^~Rb^Zk9q2-!(3--X_NPCSwxamS9={-25 z^OpPJEk)t4SL1!7#qoWYYbxKTLXJ|vP}TN1_cGls$Jo5%*clge5W$tBX!GRuH33N} z*LS>L5{EzR9Z%VR>XK!EQ{jUT0SzBZy~wIvjul$(_SueHC+iRD0j`}wsZP_ER#g#U zbB3y5g{O$gUGLHNm1m*2@vZslrP%#-`UQvF%@P`_@3w}=wQH7}`xosSW=HqE(b496 zu6_NM8vN|yqjO379ZUN62Ung;+bw?X+~vKF&f-@uZ}|%bljN!*;>?R_b$M4NdM0v5 z8{R)M-hSnu!+-tq4vjqBk?D8dui%z%`{s=0$FdwuFQVU=V3&ae8^ zM;AmhHFw93UT`WX)@c$qPsw>7*c4?@O9j3jczZm*MPzjB4ZS|#i^;ujo#WSBlPJ3m ztJL@%&Fr=pFCgD^Xbp1UeZP*dHP3f4i(jUFSQp>De+-EPXCS=-5AGxVwp4WZa ze>`6KfJ$yM|JQ}%4#$(TZ{=s-$}T-L4t4Rcr``ZWu0aFbbW9+YgUiTU~T+bbDg?%(CwFK}YIVJEPY+=foSW={J=g z<($3vxuLS8Bu^k{NmW9g0~y`GKJx#Y&Fpf92R!`&ls`%fKp zJ~C>5CP(FNnZwSe!=*be9812J6*S;771;Q}@%-N6O4rXBf<2=mNi-Yr!LEw{2ecnr zLU^=P0k0Q)$MaO3m3Sqs!f;}k=vzZOZQy&_98$%9Mhy#Iq_brqwsp$=4ECUm|1y>{ znBt|^l-KDcncJrd-vh?+3PoCJ^L|k1F9EJnwzpNCv@I-;OG(A?J#kRoFWCUu- z{cLJ_OD*0OMur{$(cPnO;0oBtL`!?VKVh11kTi!}Ugx%aVpv|O31}^Ata^r*8>M=l zf|!`#nRac1cmTXlRP25F5B?Yh3LfL(65!cx#YX6vG?~*rz*mQfu$3ePmDkwFGX8tSdFs=1{KReXUQA1}xLx9ZG%wwy!sW-n){*lC}~P7<2Rb3{$<14-3SA z(N`*#`CpR-uC+EtC((^|dZvv-rvow4?@OyODvhNfex zYaI?RVb0Es02QwAk z-XVes0Rk}WV}XW)ebex{yuJ>jK9o3pHU}Zz?i(2l_{{zcP%@W=rVfo#`etU9f9h)z z{&eNHyrP7rueU4j^W^8|9&K?Yh zz&pe?+D?qwj0Fv9HN{R;Yzc|7waa{a0vjpm{{Rthsn1S>Ujo+SAxpY^eBk_$<*BFs zjhE4_rU}L0n0FMJ_p?gp&BLhF_{ZhfJUk|^xp{PAFxxJl-;XJ^`JLbzwLknj(*^wn zLdT|128@R`9)(W*TZ#+Ha{W$vq06CDMZ{Qv0$Wz>8xxg)-^cDy?N*UVD0lPEKb%%_ z?R3R_t3gt^`_#4h*29ndf|9mBE=5nc+;41Dxte(z${}I*xJ+<0j;NjABVFIzne8Cg*4A)Pxz}_p=v`CW0}t~(N4%^0(pA#*PAQ{ub0i@ZVitZs?nIYP zQ}zA8j_XCay4;_Orc~w81Z?lF#JLCIJT)$q5qQ}52McmFuIwMu!H>>$y*R&zj z$7o+@ijNE20KeX%1HxuRknC<^*B9vbSp03iOFaj^d(q52sHI%6b2RLoN$6{V(rn8r z6rab2ixgx*YdmQun9)N}h-Y;X21g}HF#sqA(rbpT~o^o04AN|g}zo<^5Qurw)iD_9gd z{KVhC-^lT8O7c3Fj{c6t*1FvZEi|;J(#OLBojg2EyZSI~1Gln%EdWj3@N@*=Ma;NQ zQnIo{)3m{pkaeMe`{wM1fvnk{2MzhI5Xgvz6lv!5dDo5gq?J{>>0w)WyJ>h|(H|q& zvQd%xyiz`;lk{+-uXxTA$yw=(vRJhfNgbQT%79HguV$(!?DV9PsZPK0De%fg z(_GVBVDiIA>B)d!9ROix=B3M+V!t>#oj7*$=!RIFk<4HL{20p7Ma}icF8d}J~GtR>h$FK*k=JM!$8M2>$1@5{p*?urSwbX&SU%nfGQ5o%X?Y(&{%xG_Fg?pNwm6B{ir@4HU`C3F& zM)!>Rkfr8Rf5IN1JfRfy>6%dXtU#Mv zWmR~1T!S)%anz2SxSV#y#uw+eIrgZ zPY^XH#8{8r*x~nL+?XO6z+gr#X`I8oZEU)G*7D}LP($U9sVx$}ZVGcu$Q~T5Kw)5( zw2a}#h-5T{#e{8mUoPd9v@C~|x`g-OTJ!dg6ZQ)bT*N0RH^HnmB+T z;HL0eK_kGduNB#yp$s_zJys_tEcHaDG2QU(#M^YH1ut>@j^$w!bm)<=mEE0yEW{Eo zW(QjFuQj!euD0MWZa9ty-NBC9dldWJ_x_0mamZKn4Q*5tT%>Cuk~D%s+?QTvP~MXm zN573_mhy^(rR~8Ln2r8uni#RuunZjLENeqq>9DWKCdgfQLokO+>SOXq>^6Ip^RRIN z`N2=SVFU7NN)*y5keS6()u4N5pPWn$+|f-0`57g67rzzyMD5H`_$5xYd= zMOr{YG(k*o9pnR}Y!CcF?$>lHjc*eaaS&lnn)u$F9(=6#S2bW;T^$8 zVO5LfC!n>^#gf96_N&7H$oV^aJD>c8R0Ym;zsbMaV>GCzewq(q1)a{uo3IaJ?H&}o zjWCfOIGBXkVYv_fm(n#*2t;VUNa*+? zn8uccA-M`(kfC!Vb~@Col1~b}5sAigvxAezsH9!rtfYrS_3thAn!nZLwejV@nUfnS zm8VNP;)J3yeMTJqLSAcF>@jpmK>J|V3aCekA!v%;!WAHJgY3aOBy6GW5kZlT4E?qm zkw+e(9Tr>y@|J{t&+yKGOj0?TxlD@zCS)ZE!$taIP!gY`wq?T;d*&tgYDMho$vehS zE@N4CH=3avh`lGaM*NSZDHW+J0EVI@#&Z8AEcrbo3j`Xi>bYw1^$09=17W45D_f{S z{2;~q42u1(&<4*S_xVGaQJN*_$BP=Fsb2qJoIb+Dl$*;7N4 zjjVfNBfd7BBt`#(5`(5Lf+mKm=u}q#8FR9ec2JY2`1-g3&M8Kh(2Up0h30=H&OLAG zR~asv!AY+IJosn(%vs&Yv`yGK)g@hSa6QfyzfD?1yiRl{fICrk^MsvwZ~* z*@Sg>5yUrP!{)-~O&HgW1vrvKamffa8?gnNxI)55B3QEm9vR$(o$0*~-$B1ajE5`I zj)^7^TV!%LtOS%C-G?LxS|dSHxxl&!_@3cg4Qg_fVwC!=wt)S!9Y`ClK^wYCpwD&5 z!%{vlF)D4}-1{Ea;_P}hkcq}>8ei?z3H?h%{uR)OHww`Zpmk`+ro@U4;I6QndOYX~ zcEB&up?Q@HF%%rVOGPP(ij{!|Q_gr=(}p4VlUF3eU2?a>kvioU70|6S6>R&nHWP*o z_Id%kJO5NB>=HH-B)~;C$aRXeZv^|R5?Bjxke_DXe792V>kVW{|SHv=_u{kar1{$Nrjs4r%G%BeuYWGo{${ z1e*3DwirXHoM$`;M()O4=_SBhQjlEiL%c_Y+cz%S$`FVr>r+2HxZhG?9T5>QALd6a z#pIiaC~WMWd6o6pu;s|pV}d3&y(eRLFGmSH%Z)Hzw%{}tR$O1mKipI{Wmkc-o70YM z_!UU5wG5l}h%6|0ZMP z3xJm#+^nVJ`Z<3zc)RN6YLvt&ZF{mHBxG2Yy`2(%3~cfNYNpap&~k&Hc;7wowkTdf z{4wW+vkv2RS#nJkd-_O~GeuZ&w#X?YP_$q=<*C0R{dBQWU30W#Y;_`g%J%+4%L_Wr z**4C{Kj(dozgFg1`%3R2>Q40`^e>2XAr7gZ=zJWKCl8Pk1UqMu5J1xPMfj3n6qR=Y z6a%(ippH@B**QWx8-YbBZnQ7oEWtx0ZwQ`+aB+?4QZS@D-@*e*95Pb$KLf7OWiR9V z`v^vWQZ9i>1g?-I2;FcAf$l6Rfw`Zk0%-$yn*4`v^!oKz_S>b;_9$%>Rgj}%y4|fI z*Zvs}J(wsPtJIUcVVKZUj%pwJk2IE=0Bj2C|#w9A?D%i^s*}E)?`be_G`9(WQ2LYnpyxtE6Zo+P+L#E-` z0E+aP^&=P;BkGC3it-eG2&zR6^gWxf$&=Z{`JM;8|EFD1vCnXI<7sPmP>ow)J)&o5 zV(;MsI&u~4M^@iiF);%|YeyOo{}L)t@<9h>BEurWL-bsD6GIn%B8`*w_`iQs@v9Pq z?9w&^s09*)z3`9B=aTAWyH+Nzh$Jm$v44?v(GGxib3vtmY8PP}*vrmfdUP^xsq~Qo zxj&feU5Xp5j8G^Jbm{M=E8umxXYIJg;Sa2;hOxg#?q`9Y&r)>Z>X6r{&5*Lk@h)A~V*NH)A@gnYeWVYL!HXTNx6DpLUikgAz=U2W>9FjT+crULUlN<-K<>;N~TO?+Um-dMJq!r{Mtuc z*E_u+W7)0O{p&&I;+63RNQ|j(>s|+&RUO=OSMCtonMc@h-A|fKvM0$mo5JGd6 zi=l6Vl1`FYqS|Ak+?I0J(cli^0oYFB zNYD|fO^zGDS!8G z<0oI3T(6{7hEuOqZKc)HVs*=%n!N*G11Z?+jG$P-IR3F9Z=E1AM?3IV=IK#??d%62Q1m?vh)g_?Eb0GL2qSZ{SlkA~ zS!v~!i=(qnI$`@YRu9Py38oB-72U9bD8*XD~d`OoT_8Vdrm z)qz8gn!SA8JIN8k35eWINx;-9#x1au8HnOYu;CaQa4xVJQnqi|D1O@Z3DzL)!FP7t zqAL%a`&-v4%2j!6Dlc6#V`rVE8*4{$3o-%Ia41c368uRg!0Abb_joii=SQd)WEJ$) z(gU*mMF8aQB(pHcDWDioWX{JmVOqJFoPPrJfiu$ysa>x*C1tpJ+IlHnswdKv@W_e$ z!N}8r5VPHSw8kd6w%y5cS*Z(EK9Zp!qx!qA<*v74~Z$)zqj?qGL z&qGUds*t@{0!(g-g)aFoecHaq#72{mcqgBsiaGy}K*&AK3Hs;vkH>B*w=w$AOw4`E zT1GH#?KEl)Y{8pBtilI+iyAZOJFtfiH7+-lM^yrIB}}S?nKnGre)mJQK-u1NsNO%g zjkt4geo=Sqt)1JOkhW@XAEg*n--kYg!7%9(deoqeu@PlO*ghmzp1jRaCWRu?dx4M)!P^D40c6#HXEYgg$amxn=SFcnh@(hR;7^6KCPYBAn>fdouw3Pm0+K`F_MSRdO+3jTq9%uL8(2W7 zO>!tni`|F3gHlcG?1!$E_SYZL-r10&n=EXuc~hwPa2@E69`AL~O}HdLL+?qoZ0SLS zbbqeYIL276oh8?>lW6b<+=XzrC~VobH?I=4(K)X7AbDTm z4)C*suZSz3ESX7Au^GHAo!s}*sJ`0?U}T8j55JQlq5i= zN@HF~4@2x$*L1W#Z694xq}WDXPeAw1OO>8Xk8kd`&>ea`go`>%s$`EcXHJn>$GhFYgF&gHXH=vW5RO!6>Yh2WG+eC`^ETV%An|igFseO|A$TA5r zP?})paI32d5r~!4ZA`%FaZgsd7__lX#@pCEgI=L5*jPP7zfAi7SG zSV>PpX6=kPLqCyLDvk;^xFP>}Tm?Ru8L-c~t!Zjdda@#9*(}*2-#)+nHfQ#3MP5St zw_432;<>39_Fd8)(tMHJe8mq+CgU?9U(WnNnnEX)15|`lgF{RcReEexnywZJ(5Xa& zq0fV;jg$JD-#8(*T!712L%*Lyw<&7{NH#vRQRjmd!>l^?Q(;|aM!oKlj1@NMD#pD< z6SEF2ib@?N33W(J;@Al)8(9>sP_d5ZALIMs6yavG1xC{NZ}kHPeV>OHb$!tr-jQC; za6ab@56KabVgmnl14G2fG^?Oq>@_jnYhJ1AC_-lvPV(5R@x__2FYgFqO?L&{*@4>I zM++B4cT`^>Z@~*yriL!FU8BqDNGoBaecrN6Y5;Y$p2Ki~&6#QL((t)Yn6Po9U$kzV zK0db{Wi-Snu!`MGa5<8)&!c)jOBTHUpUL+?jT%*?^Zu{Hyi!kP^Zc7lU$XPUpR>Q9 zb|9ntm+{Me;y*l$`$M0Nkg{%%zlgC$3?tgX#J=&^QKNY5^XQ-~!VZ8e4#f@t3 zLL{M{QTx&~4qF|6WMFf?AoN_(sr<;vOE0Ee5yzD~vUk7OwM2S@56uNx!3{LxtoVDI zW7X=wU`v;R^*72g@~PIFuh|+JUGURG+{#o}c5&IXyLF%Q^e83^33&p!8RW@GW~?V} z9w9Mzq7H+gfD|EJMT4^8_6&PLVg^6s)Q>iOrK}SVO>|f+E&4$?ROHUe+0ORmMpUv4 zlPWBHC%G=+X#a-B+JU-HzKeya%ffGDLB3p@Bu9Wlu2?3^MMDk}Kn_~i0y5hT3_w(U z3Sbbqyo&)Q>M|VQNq%H%$$_9|!o(-E`+cq{kME(h=K zu{`H6cDlTlRm6ffpkguw);LvJ(VrJzjp&H7&qMDsHT?!YSqF4GTI_uKSAqAgoCj&w zFmMpKyS7?#@{$;2kxawcd4Tyw09w;e1*tx`L-rDhDT$XQ1~}&A;b))~{T5|N>f4MC zGm~14Zv!vls59l_5cu64iJhEHSuMAoMk-6O5K$tSU}4r0jy1#nBF(?2#w{Ve&Qx=( zvnOT){IK_F<3n5fGtpTq>xLTKyLCEk#G2}-#W(JDzK+0D4<$%k09JPq-t&YwDmRB* z+gv$WPSD8&Y6n$EdZhnSA3;xm+*~niVj<27#6HD`wQsp#kwGs-<@4EyDX%7)o>}}a`Ya18mSz7(WKGN(;vncl zU=kU%h&ILw>Dqp|y1WNd*Ey#y(rwk5Xu}~0D`kHYRuscC0_9v5a${ISArcss;^~rh zpwox}TfK$8I;|~NOw_F%qG5zFn`f*S=1L|#n@T>t{dhKJ0uxUGE=TBKAYg*rs0#R% zEMz^d6WBm@N;gHYkTt?-(powS_9to^vM6NCZv;D$*7+EBUiVTw(aaa7v@rB^TZp#3 zL87Wk=!Zn{sL16WC%ZId?_zo7o^P5xE5Y*})fF$mu9AQmiiR9HNna0lL3ToNOEX!i zv;#3ZAx?vKpf}3RU|kncd-k^?9$D>UDCg=M0b?By`=Lzh`zufD~^CM2e#!e^p*o2t! zi=`P#)+YV~sPZCPyoY<{VgxT;n&6#fBfCQhReHQoeq_fSg%~hN;04OJDpCaW*_CIWa}5Re;AN$2+y+!NSUSu7i?TzHfKE zpYiXh*K_G|`=$HjAy*SneFS$z(#eEeadkkDz%>r7B*lo(d~yd_4K}kMLhT`F_tCdb zQj}=eTaAhrpnzxt-3ezR%T@51%h`d-%OeLQYqQ+s`K{#ze7&{@mldSb&idc zS^&0Jr+D?RzZKIhrp9A75R8R5cu(-$etziYN=jxVJGRginrC4~Bbc0j4oCZASO=s8 zkqI|bdW>J`GcI%)VzXlQWYDOkw4pqo&kaNX{=~&gmCN9~Df1E3J`!^~Sh47Yn&}PU zm9%35ZUUyhot#PBfsbH)?`kly^KXQ5Gi>$#Gv|lboFwqHz zK!33w!7)XyoJ z!#f7duH=MXQBv!i0F@g90PP3mBlOKZgl)jJR}Z4J7wER;^@DEzIczm|WM*7tIH>Mn ztI!i7r9kkbv$%;Ki^{``N(W4EXCR{v1#}J?)XW>D-lB3oD6jiLHpfCB zrqOCdbtwYeMWMVKQ-><$k(GR$Dn1c>p`_U$9(T0aNmf?JSUc6DAUA%~*O4aB9e&lX z+%@CFX34yc_R7a9?ey~HJ>VGdWQ34nDe7q6Bd+c&T?b#>%GIGVu2b$4jbTNJ0X~|k zLoX2M&Sz3IP$+!B5)-4$gJZ(OBN)G+ev;>KI4xMt0z(0`}_SbL`kr=`tz=@ zDL#d+>Tv3hbA!0+Rk+0rC*OfZe;>ipIa=YAG`F1uonpW{e=206w4}RW69IRmlMhsc zwY>9O6;qTdewTO*V~xJ|6)vls0^m);uH*+Z)gKM;RKLE+Ij8fIGfOL~Ot$Y!K6_xF z;wYsyiS^c(kC^=d>GBV~EpMmJP?Y2w2&VAuN^H*&hmDQpc*B-uWMaKufVQ5;xQXMB zGkM=Fqdc$td2siR`?HJh@GD!0Dj<1vT@7r8W1ft_UM=X2gq?iG3fQ1^`C@h?z!>aW zbu4m|q!v%6X3VqBG+3k3N=HM*v7sf8j^Q>xv?o;0geW{s-TlAfV`Ynczx+L^W`0hC zR5Z<~)0!QF5W=c5e*TeeH0y3|2Re>{KpA4-yR5T$y7>~ljXyfZ^?;vn{*jrq=sWW! z6+0RezlLnfxpF&2n}C(;kwMu6P?~4aL>3oL;jSS4d!PC`3kyUosJp0R@cg-e_I@fbcC&ej&&wbj1 zL$!BqOFpz>>xP`)KYTW-2=mXs;;_Y`!K&9&w#lo=rNG*p@0ekAuEfP?(^Nm;>Xxo8 zKcy0Hu(@Nu&+d*rJ8Ntm&zGGoamiSJezLb@ZGXwBN85n>@up|`p8nF!$5m4M_NNDK zsyhwnY_&(J1*9+pXG|O}OCxF{(kbl^OTc31ixPZFZ?~{G_3w*IpqI|{) zl4l2%`e3G;=+xUmC1FjeBcZpnZttJU^DHat-g1{%5FMe|>+vIa&O?GEb|V{>TED<1 z5>LWbh|xhwbi-#kiZVc*cQ(oizc8;6lCzvqm@CjTIN!6VXXx9z811W!@#;S*&Mot1 zAIdEc%kyV-l}=mc^eYfS65DnHxUo}~!4rrFwFdn7r@}uwcZ0JcnZZjtaSx3Huix3R zqCiXFlb)67Ozy}9yp)%Ah!G@z z{Mf4CPLj@_SGIhw6q%PJ&bGu_ZB12>T7_G@qL2bGkh~s|1dP3Bt$6U zsjQ`;<>zq%oDx3wO#KiIEl^fJSAWMOO4-1>4;OBscW9a8u(i4NO(NdE_`!vR?0@iv zOrjc$XWCEp7E)^ zz1J4ztUqX6sH`+8O0-ye&&&1b|1E4Ik_JYT5l)78-v)rWowxyh2c?N8L4;Q&XaW=S zYlw7GHKPR?%U#0=c1^-;2FMCt$kWTYe^Y==VbtBK7S7#1^=D|I1%0?e-4)s=i7Cu4 zjd`vczW&Zaw9LItP7Kbwc;MO=(Z7Yeto(K!?k~0ek>SvBuoC4M+L3LYwN(1;`IElr zx&pSD)ra5ziCf`*uv>J4c`@{SvCH%A&x}5(6x@+myWK2ytal|6r^E6c#vVWWMhdI* z;+4)ef}}OG`7Nvr@kycV#HMcy(YMay@_*n00rI}J$MYhH3OL*S*S}qJVeo^7qhbzv z^#=~kUaTFou-*8T{l2F@?XBJE>Sjj&>>Mt5d8Hgc*^sL|`KLlBMY@Xs7FxFjfh|1| zupX3kVqFj^0~!A&!=UO))7K~UIs-_u^;*|Yg@TD0e*)n39VfoW)LPC3^9#^SZrwzS zSv*ExYEc~E{9^L1S35}o#&(GCB)8X@R@bAD8@s8Y!;JyRf$JAjk3{FoG^2H!(}E=C z{WhyQh%1H|yjP^Pm-?s^{d867&D5_-p?+xfeNUxF(fGE>6OrZ!Fk`gDpp=r-9t_}SIxB3Z=8En#s_#yf0=bexhvvaz0dha z*ui4Q5}%uAA8om`W4hy3T>oy7U2LsXbVKZ%Z$q^0PoFTdvbl1j?&XJU$Aug9H#H{D zy0s0ldMg7SX&gR&wsfaa&kLcVBu;{sgWFb{J6pn&kQG3nSc%dgtcAko{v8B-FR2j( z8ZzpaD#AK;Hp+*GwT`{2$@LqQe|RuP3Jd!lz?J3gu9WwFZr_3(KL)Y*-HmN;?S&?c z`!r+4_DT%X+LaaVB{<`w`B&kg0U|QQXS`D2uf_DD@9@1@?uQR_6m5K4iM>lqGwBZ% z=RL1{fwB9|&!27ZQvpp8ZBm>Cx93FKF9CNeFpCE-E~5pz5hGgi6snXICbT(Ec)q52?liT zS3-e56(}+Vl6{@m4^TF#9woLg7EUv;ptRpg+(7yPpcwh~d$Rka$p^$?upp00H~&-s ziRw{g@0^D8%NU6Xs;p|w=7|e<93MG%<HM=WlG`TG&4PxlP8+RohHUU%@lcx792Q z$Om-2IcUZgr^YVQ9oPx%saNnZA$R>TK^aO-8j%NK9?CHEB={i0c{&8}SyY8pnJ z>Nd7IgOkV0OMO+h?Amp{c-Bzg$7G<)HE%tJidL5fy#zk`-2z*)qiJm>Ys!ngxxOF6 z-aR`OSQ=)XuIc5I&lWrV`)xW&YH=W{kG2O0@pW8B|Mwp=y*Q@yY8amKllHDIvPp*c@PLdIzX1* z0ZSy91s+Mim)ZX|N`SmRxtc#A+ce@T-SrRS-|-j#P_NdKm4m07OuFpKu@wJRQ&T-; z;|q=P$BTecox!@Bo&BveNC2!|#*N?90W}m^(LeOA|F?qjFwa6GxL9DeF2rld$9b`; z)FffCx28~gaOW9Uc$e2)P?da)^vf%TW7yGjs({Z(4KRc{iumM=!cBdZ*Ue{;>j}TZ zK>`yXuk0}St^f2}`oN;HW-D8OjF;N&B7>4Wr#Kq>)b)8vl-`L0n2+-7QVd)Vc$lkg zWG~Pc$q71&anevQzvTxncy6`XoUdrYRrEYtxv)rx+eFv`4f16LHV3h53ZlzG8w1p8 z;Wq+ZgeLxja+qLu)lO(4aqilz*~H^7uf)Koa$XvUlWy{ruTPO|{6uAGct8iw^yJrC`7>;N{X8up3wZ;@6eU{5l1wnHb0wNFa$?y*9>`lSqA( zWoRR^PTVNaJ9vJO#CMm!eLc8Q=LI2xpoa#x`3w%GgQ8rNxx6}N3A4Vafp({`eJ^OQ*Q0}g5p8=0TdIm%UrrLY)WF^nwD;sqVmJLje_c4n zd5CtWim)A}1G&y6mB2|pjNvF{-L^*HR`6D&*lMkrf=DtiP_B#F#gSP=4p0NUXMZX< zp|2r0y2oW%=pY=&K>S#w>s?^R!!X&&Xmw&2!OwS^lN&ER_+mN_nbg{8TUYZDPxg&- z>A5z?f76)v^@m&R_@1W^J)-2-B1xcRX#y`IuHo6K# zm&^*6+%5zt#HfPMkR_|3MN6XOEX)SErSwYA0?4OH{WLp~8Q*eFiHB33x|^9)iZ>7% zwwfiQwnJvA=EzxRU$5bMJ$-CixPhYxA&wcM-r1po{X@COSSbYUXe>gC&%Ggwy}|OV z2Ygp_P}d(rsFkvp($x?b=q(_uQ=^CPNs&eO+s0Xm#CxpeyZKGm3Jg5KY|g__;~dwEHT>nv?-(tU#rj!x zKTdPnn*N|DVEXO>_=fA{#OZGn?Rnkf2}M)O{xvqsnZQD>--l1f;4Po)`CcG`VEe_0AnN$Q{t8G{TAN3CwgfX!505;oZpXg zd;=;w-b7<#N@J?5Obz?L&0Vd3^Ke|%{CcuSQ#de};zPbp{S^yK;Qc42siA9A>h*kC z7oa(}=t|PPgVF;{ovpa^>Z!tQ^08x2wVT}4LtF$_?{;;oW4=22Mz1UZuuQaugoa9|5uUC2?+m}#d=Yqp=xY_ z-(HbQeEGS=gX>aQjsYJYWjh`S+o%@*MW*NWKb8u`>=*yPH{aru+Rh?hnaR}506zdQ z1(0z_Daa7OgMNa(h*{o&0evvJ3VIFtU(liX|I%fcVK$+8Q|M8$L(krCL?vQ3Mo&r- zBh@+xxw(8JH*7QepRYpQZZ* zujj|gFRXnsR2NO!1P6NS>ksd!?xjY(RhY`FD&fy7Pg~~tZ2W7*qU|qb&j0L(#&^V= zs;En7c3-}SpaPpf#(XXd$kZokBjS`oYi7D?Pu_i}2Em}i{9T>b4^uh_?RLGV(BFQA#TJsf4dK%D#bO#qYM_JxZdNm>6 ziRfg=;{nF^tM~8-)F|q*B(!KZ5#WCdTYD5gMtZR*P!@^lNSaKMvncQ*G^m)DRlvFU z|I2Hr_!QU)T73mtXPO5sFmdSWAbNhV&bw$-w!~3-W58l}T9W|SA2fK-?vz8;TPDw(+L6muKucS`kK4*u(!YesNdHP z!6a`Vo<`jE?h`9mFLCROG{?*4po+L zrwg@2x$*VXjqrR6XDNlIBmk2MvpivAaf)bHV-<<%L*kKdar%$XUqa0NRIq(>Ul2JO zBe4p70CFp(-!|*6-f`gXeW&_LZ=et6+${9U6Yd+?YrCOCV?SZM5q4=%Bv zzDD+dZq?WdBt_^t%_pyPkIbv!hg+9G^awWrI`|8;As>0|^FJ#VAJGPJ^9y(C-{O1+ z>ye*yjDpvmPfIv`{FxrG2#V*;exqu4+yquZcwi`0>+qt$I_fgt^Dm=T&#%9}Y3J2E z@cDdPtwT9;^x0sZGf-$DMvHm5plyQX&$pPx(tqo-*$EJgq$D0R5x;P}CT!Tv$KHJS zcJ6XjZMp5&%F3C%52aDj6*HW#<#&GRmbzu)QqoO}!GRj{WyRDv3)d9+R`_N#Z+^9L z2*-B(jjWVEcav}|qI7ImX(=bv6J^#{MKgF(nz%?&xe&I}t8YP~=iU|)9w|HP?>F}B zZd6Cv+#)ly@VCUS_IaVdeH(qJNWXl|u_pec_?Z{Xw!Ke{kW&> z+j`x@Ns*g;87d!V@(SM4b2l6s?p4Y-I(})<1}R&?M?+ak0GjPY59~uOth^6ucQ@iYJ)8^mz;D5=jeb`Jwv)4!vsddr)ZCsdM`AxxdHsZgBrj4z>youcJ)@f(f!qQ&< zd+`RpefSHP10CR@qb@6|4wTtyyTMpYC$vrZ8pOH zeKwyq*{SZTS2MjUQ7|5) zyrufpmkUv=wj8MW<8P+Fw)e3uRY}kildhl9?*hqlsHP`s-(9-W_qU~{LVRQ9W_Tpy zvz=C6_3^7e^erxN-29@x&ob1Li__Y8H}L76`s$^2su-oDN}mktjKi(jj&)%lRI|Lo zOu{}@cAMhRs*k?lX#q&Rw5}VQE3Ru6I9|9GV7NM=?ee~b>3X9-ihbz%byFR`dxfcG zR*vQ7`Hf;md<ZnpJACf2!{i@D&d1WXDHU*WV(4zb#W&k2BD8_@wbH?na!a*IG z-3kC7Ss|s{nLibNXj9f?mH0Z=j)msM(B3s)>G2*rX>|QuM#E{Lm;c}YRK^~tIR9DA z_+JUwYrRr`Kz5476K=@T7`#fw({Bd|22g6huygjYHr1ZwPyfxcm<#LU#Ov zumeY{rb_T&;u!48dvWn%h31b=(*#Rby+O*to`7`{XF%TjjdYD1OE>w&C<=8=5|hBd z3;3&$rA6EW`G2bxxFT3D{qUCUd4?I%!@GxQ+bZDbwp%8pa6T&!^@Qa-w0CIPI5e{R zg#VOfquBC@dx^`#nR%svv8Yk}V0aM?=2)I;XuF;d`1TB)cl=Wi(!%Q?*|W9tTXuK;J12WW+b>Wy z7Jr4mfQr$qt`FzSPnrV<|LU!>0tT*Yv;H2njv4V05%Io&3i#uL(A;0Watc?Y|2*r=sx0=-wuUU;j2MtY}fVp}<=Y*`JN#aJJ*p(lFyX5P!60a~uqhedPp?6I) zSUi`2CG)E^U+hqp{U(5KG-l?E33BJCg6PerNslj8PTd7gS30oi)DM7kUioBOC3dK~ z+AJ?AZ;>m=ySQNe1~ns7^MYGklN!()XHgc?a5zD7ir`Y$zlc)}dj;nU&DtFnBxF6f zjhbAa5hy`QLKg}SSrO1rNI`htll3)?)jj66rXTjNRv_Ae@(X7ZWj2eU5&_5udAvPh z-#l1>4kV=$_rmU?jt-`e#Q-DNj5EgUCmb4@7}}Yn_Q?nK5^l_faDIK^ew5m2HMVWl z)f`{n`7$&w9ndf>knv!u5@l4&8BPh>SRy(i&|;m0Wg>gG!C67R_Zv7xVvoJc0CTsP z<=rJ7!uipDaWZ7fXd}g; z)fXhnW}W&pBK*ZpVCtUXh(?~X9e;)_a zO9sNekH44F8f)IpR{BbmKrZ^^P&No0Gp_Q3_F~Nx5Prgq!4?>zNUzq1RM1P~z<1af z%GEBB{{6FadNX2qMGHVrH4&f>{bA!0KleU$(JJZ=?eKGx&*$#6^XnRu{&{ri>7$wx zJ7Z7pM22L{erdS+IyfiLct88jNsY~Z&1NlZRU1u3#kfM#r{$?RTFQ1CMH-j?@^Bn) z&E9z~^ze?)`F?$2AI|;GUY#9u=bFglz-;r1du5p~%Y}xqO#Z8f?Vjm=fnF-m!fvD5 z)JG2=^<(qGy+2$(xyj8x3ICtYi~mZ~zXI+D7bk_p_bW+EpkWAk>*U?D5aa6xWmW^8 z9BLC|V4=%c!rg#fLT{1l;m=L@L5qU}YV4;oTKbwIbPB-&Rr>s0c(mz#fnLO^hqwCc zu@WqKcpia|J_=>tFM{1$^YqDlvJyVfz8@T-RAqehnVQ~61R_Mo??WuazqgUho2`N|1Y zUdYE_YP4pyD8lcTf1JND51lSm2Q!a9O|+244xm>9Wv*pxlxy<%`kwk#!;B#9>))b4 zXq=>*Li%OYG3OF{QmAr$X_ZClQo+^LqX;g=dyt3^mTm zB*sqscMCriGznlK#k%8lgdId}csL@OA9Jde<<|gDh`?Nl!u_)6be*vSf>o$YdSAbo(_5133L_c{y2|CZ^q_uD%7u-m> zfSU#aznJ)|%3iH0D<&%X;)6Zm!$3xN44!)d*jF{wPF(U3r{iJXtvvcVxD+Ulk}-8I z36SZ;@x=btWqB+BdD@W4*5bxco>_txyJ%-+?i5aHqa?6kg4S7y@(~dF>=H*`Zt~9t@#uLahq3CbOvP@HHT395)lK zDH1X^5ROA%<6d}keBmLbwCvt*^|shE)HgXuXc(4P0df za;uqT`$VF)6q6 zCigt9dOF3PVJM(OD2afN*V#Jbnod#@ioWA@&oYK)BmbpuBN)NCP;Ogpd6B;Z_T~#F z50@g>0Mx+5?3h=6lTGpC$W-O4A5K?A{;>Id5A{pyFb~mo2dJXZBRao2{))6fKDZ!& zsKot2vjmfIEqRnQn%)cV8PJ?V2jkL6b*>%UWDKH?p${AR?#f~gl^0H1o56cLXxk42P9boqTIQI|1oz?gSZ92&FM%@sX7i!v_!8W z+QPam%cUT{h_}YYdIg9Y(}_F5e&u80i8@j%(Y3t!2C(5nwYjhu$xtO?D`TL?Ey`r0^nReBaWMHV3RrJyMt z7mw!U6ScG2Q0lT;x;3$v1i4|-Fp6@$8KREpR4hXUwC{0%)nX5Z&dnp>zNJ%X%-`X_ z&hOI6U455{V;b{na>{e73OwQV8ed`jAUTD@`~xUfI%N*YwR^d z(~xYF-jq>nkkG_&@X1%P1+b4-3P|@+JEzAHvLvDwH9>0m6dx$TGJPWRI@{A?5bbwM zC`s3Bj+EmwmqE01>Ou5TMkwNCf3(;^1`K5|V>qEpZV7w@INb0h!BYJO5xxFNsL$m| z?ne0*VlSwo10gcddfewBl*hsXOhpRy{)$Ywc7NR`bqt{XWGr@-D}kgmKB>(o{qn># zH=YZ*&5tSx(JTg;qDI>$Qg8FQnhPu@eqU+_3)C!uxSe1Cv!GG|qZOyb!Ml2h22fi? zu1so5z)GmG{e15tV_nEydObhf-W5uam8NY6GAvi+?w4VQv~q5cEPx}svWVJ_hFqvB z`100eQYS`fgviD~H<5EICFi9c6kcQOH5+G9*BMxePvT?=O>!zlmV7U;m^1u7qEXx%W%850!#e%Jx1B^lA7A6Irv=PD%i05QbyVGn{)P2_k-? zY^i6%yIk9;_lOpQbSvqOJ{p3bhE!tm=F{|dLyC!Y27EIx6e6;Z;2_duwOJPK2E!M| z=i9~&d+X-HE22If>NvtcBq+#i>p*Z4keK_wMLDbWkvITWwC|x|im-R*S={9D?XZbx zg2h;eGGZjwJ*WWwhOoWJ*9Q&?`niOv~}$3Jgb7q&p2{6c32cG$ZdT*CbkCaK9F!Y99mvJ z0Y^!^z=kat*2F@aNPR-D5*?L-6-=B&{6% zzigarZiZHK$39}4PG-z~_pARFcj<*4{>=KVmsc!%0soZs6p6CD7iiuhDe;tbL^G^T zXBy477~j~2*zk0jZr4LE-g~Av_#jG^Lq4j9TkkUY>Tu z_1*l4QY*4nu>+S(ft=YZr4F(tFyYgBV$NP-NNPPIK(70x3fBT>B0~|_H_o>pQc!?& zOT`;^7OoZzHS*0yqFdbY(fsiQ{+|RlUV-uXA^QH4{Q1qt>ByR1sU3BuDf180XlhcS zRWA)G0q{4o16@r`nU#7xmG_}c;979x`^t*I827%V7WqLZt}bB{7&47^04yPb9h6y< zrv&2ydTCC(s2j6O?E)(tUb>buBZBk`zg&KJ7BPZYPh$EpE>d)-mrarq=wNt z6Ce)QC?b|U#Xnyjw$B|Vg}QQd=A8y;ff6$!n|KH+V9W^x$WfNSvUC1^z;7Z-Ea8%X zv4$IpQW#tygBZn7iBjG$$w4O345{#pZx3z5&Ot&bUlukU6Yw3d%5OE%@|2~jgv+GB zAlWkzV-t~U(N{ncb;0Z&Av9XDj`-obbZ0^MsiY`qUdU$Q62Wg-YDKEnIBhyO;)?yDO?OM@R^XI7o?P}-M!LzUga{F*)8oK_qtyhfzON5YT~Pj~1^E&* zALcyxl(F05)9^Zp2j1QBH6*5p@>_IB$%|%6{(t}Y1Y33-^3no}_&zVXIb~~obUAeu ze*TmQ8UGEZT;Is~+B^RF*!uSdnBRXfL$?EV;w*q28&!rs4@-5yDIWu_oDSOwrYf#4 zRH_R)+i{#)q5XaH{INUXSF2&1C{X+yW(mm(jyXS!Xr4{ngs6gpZ4Fy<5y6$rtq}~R zsPi~_klS!YC6_Q3M=3waC25+9oRhqTM9{6-@0O*7VUdTu2N)HU1 zP4u9QrMqc;G_;5U2=)DuXQRrfd!^cg z8oHno?$x5U^-w& z?{*P7!RAtt{nJtWdf|zD`vHr`*QEZUH9r;nk;*nJh00nIL-!sK$2Q>OI*%dSHE)c< zXfIJ=k^sFDCbv@xZs_f8@Oa?~YVrL8yD#ZuTuLtV#((iz`(p6M*S|FGeysP~cKn-P zZPYfGimdYtBWNhm&3eS|)FE2vSF3A>)_D6HWfvbWa2RT_NBErmT40gV_WMvIKe0J? z?E+^z;q3_B4LXOabP2GwjGh% zN^ijP<%G-O`iJFPKLMXKE!I4OV4j9~lY@O+$6hmnXY&y$Qumw1ldqiCWaz)Coc0{1 z8|Jj))Ebj$+w*Gh?k5+>aKcZ8|DX*v{|9X_<`-@7uhqmR;#ZPg;SP~Y3jc`4fJN8j zUfx5GMAf}L$A6qY{l4S+&e*-%3qG)ocK>^Jf6nRRyUX?&1mh}i6L|qO^!JwTFV)zY z^Lq|FwRxZxG%}|NWkR%9xf{xi=XNnDrx`pBdSr|>)F@;!K(G#d_I6-S-u}CM7f3d{ zBp2r1y?eNJfg0O%e*A{}_SFwPk6&?c_-#$1a0U%<8>TiXSkKt5uP%+OivQODh^QmS zjzsH)8DO!2mv9;d&s4i^2k-nSG2x|aU%zt4b^ZLo@{i8YVS0Ec{`ywDA0_dI_j89u zeAf&TDw%2gK-Q+B~eJJMgtE0$?mOdH%;UE_V-fC+=r zWYrbudI=OK&?ue#A)Iq(F?7dRxBChE22nfwP?bDY!OYoQAOECu6Z3MjxzjXsg~Pf& z3tOi%sXxy4R#GV!YWt&n(>5=R)k=cf5X%M!7}C>IKoGY@IXUIYSIVIdoe$@(n zj{;$+z_(1kU#bg7iRQ&dvKrE5ZW0&VrPN67>R*&zeNqTxMd)2K7A95SRJ6qz*r=_= z$Idtonmq@l0UJ5?=QAKKBQ6gXR)77svfO7R;Vp?f{Zqk)okoJ}*|16J++zWIB`}9}R8WUDosm?eiNigCzoY>@)r^p;oRtweZWM z1L^NQj613nl{35(j3W7Nr{aaF=@*|*_tU;;Xv}iogqwn4MtR2FL{(`J>?B%hvDRuw z$0F5e$|4+}k@7@xDo#jFA{v5@3qQkI!F}(o<&LD=(ZS+!&zl;HS?_amv{uYfFUATi zQ(}zX8Vs-B{q)}d_y_d^;D=)%PYS$?(LzmW>SS_L0eDAh0SC<~sC(8rIGu1LLNKzZ z%F{b_r@bi@(3chqG?kr>!cli0W@~BEtp?54&3OoOrmZeN(7T5|vAY7Z5ue4P@9#0k zXyWYydI|1)oLcBD>xm?S6Tkahr(chSOv}9?^M~`0xqtAP!Woyr$hW8ZLaHjFlyo1@ zna-7DM&EgsGDud3I)#{4Oa>Zyg=obk2LLe|vXzm7+6LQ-)JW^58l;u8*V)^3o|AkxqzkfVvTT&QVH4ME09flb- z6gtndsOkDvkYYU0%eukFZA)B5q8i~C+*LlQv($zFiqmmbXJ1eqDchh0I5qDn4h^+d zWc0k=^pSZQw!qfJ%q;vHwGO`C1PXL^BA|efuDeQ)QaC@rNwFC7?xX_261@3es8gOy zo_hzdE_F!&=||x+bmK5<&1zp>(p<;;mPB{SD&law%Bi(mrTWZOH;(aAB{``I(jr+t z-CW+qsJYFufGr_cF-i6o7>%^D+Ub@eOoCMVjzonxs?$K`ofj>oMxnLC;5vts=tGUg48XIu$6W-7wkjyHNyMFioU=u8 zkt|ptAE8RWJpSMG$$xHWjuh@@*`sMx~evvn$9Q zTP!l4PH~DefqtHl+g7aC{{yALEPWip`AiYa4ARD?tZj5hBkguq`i6N_p~HE7v{9ut zEubs37W*I6W#dSwGJ0qYpt?yJ(p4Kg{G5s z9-=+pPlT&`EIU_;;tujdl*ds^K>j-gE7`w}SCYi{$F`3&*YE_<>&)Juu~sadu` zr%`n1$`0kYOjaZ^O}+)1pgovktpKQSEc0D8iG6{SKWi=V4B=eHfQ$~tP%J)0$LBmX z^2v<>fA090Pse@6;NdIJWJ(X4cEXO7HsPPU3QISf*VIgo-J)&cak@Y|WZ&Z#rN)Y0 zcOC0X`_2!2eI9M66>UcUy|2{$WYC>IqVB9eb>rlxqk9=v#N8F^oFBg!Jk|8>>_9HX zG}M;Xhe!jGusxNuDXtD_SBPFEJmOmS{24Hjaq%TApwy&#Z)p+w*p`IwJD>LyEOuix zrk(CfkPYoSVkOKH_D;%z{6Kd0V%T5N8z5AH!NCn>MzmbqQ^2(rypKdFnvQZBO<}XRM>WT zzGFU%47yTLFuylr?lmplPE~~H)B}Icyz3_fzBg z=G1|iS+8hctaihEt^s@0!YE@vpH}zskcX`JVC~Oc>Kj`2>{IT!V%8tv4f(ncTjA66 ztR`A3CuTTL!qBFJUt_Zz%}SW>G@V7Mt))KfO9io|Dc9aanBDhQEV^CF{DeNma85SB zXAyyDBrO1xAYDkkFfkJe#a$)trV)C(3l_fLnXSjF0!dZN@WOb2sBNox%(z9*^f!Ln z*1(j%mDb%?E4VKA!|;-+^^0>`g-A}YI3HZKuq=;m^Q=M^l~m~tQ)pPPLM^>$`iizA24V_et&K_C1<)%5K%LTNQFB9?y9BcH)^ zAuEmh40nSGvd@Q~{yebo9jJ`?3}RfIf57PStUzJR$_Y||n-UP?Aw9AR!0*>jU3q!Een38v!{2+hv; zs9N8&EQ~RWS3_>Z_mGoWkQ>0zOuKQ)3|E0FiiePDdUTSO$;w#xb(XHto=Kfc^v?OQ zEkafj>zu0o0g-1)P@Li2${AqRc9yFx-!Y{=G~r3w{30cp)ibbc}vazyfUtyoEJaD5473QZ0(OQH1NpX@)ORXMeGl z70n=S7lMNotEKsjScNh$rG(|;oxlwRd`<`Nw+z$!T>lrPQ+n)d`FcbORl6a%KO&-J z*z$38!(F4+EKl*Di0SO>J6b=~90-rLTyzOqvFE#s)eJ*@>piy~_SV4{7ikfCWA}IO z{;*~LRh6UF>;Bkp<`#f}kX^=I9Q^f#aK!ovLSIK*z{YD>MgJL_y!;9{NwPY|f6s*Q zY4)X773BnJ2RG}7bm>%e^?wqWF%rOZXp zRlK`-=xZ>3JwV3eD8ZuhRDr9m$MYepnAREw^t{p6Rl^=Vvd~HMk)Hgum#tVUOJdE^stL65Dx(-&|Ho9=M;qWkC>QzcKVo-brNE>GKiXXm? zjgNu~gl#)=bqZdXZ;Lnj6Hx?K&n=*6Hy7oLV?c!p%r+-{-x_JOkedP~VA1@h<0bt06fsME0h^9SG`2!T3$4AZTL8BAQ~XNIN~tv*0q&$oS-I4JM^!oPnh+iS z0FHKm10{CvrwWL1my3qPrI+81bunYbr3vwm1Kyl%X0|jn7kE>D>=tj9T?gUv?a0+M z<}%`XQCxNd=9(VF4Cb!$fsHRVx&Pe=!0D)oSzIahJbj zjCjG+r?9YxdSS#OB9h?|AFkL;E0L~{6`7!4BuUzOEdsy@j9uET5o)#ifKSpmNft}6E>5(HrDbv@J~Vl z!yuLl!(V9cX?w(|nF0Q(F+-5>I@&#ZfMa4|@v-LFbC-}U@xdYeE((a+5LzK=A88a< zi<<4NBt##Om4H1LH9EsHY!bi)LU5!#xEoXiS}%;bsoo_i)LeeEoY324V?Qo0QhX~h z?eA_g^YpT*r8k+6-%l^0X+fbCQ$CIPad>js^yLVt`uOQ- zy~Kq_Ih=|26TU9muS>`4Yulq%+La2ZhGRy*#>|1Fmk zHgJEAhw^3D8jzpja8})S8&O+dlxDZ@K&=%uUDB~&7#xkt-mUZOdtvf9CF6B1-O*dg zxwtJoKR;Wi)vo@$@8W$C_V<_1P7n$%Rvz8iD=bN=us*)K?9=wce*Jzg0v5-u#>pMy z5Lqe(NDR52CHMAXb4H|EE@C6-4XpwYB*9#=yo0SqNOEL04_YN^dWy^+`J@(-&)JTR z`+TTUjZ!LH)6ck=UVh7I2V<93vB?=qd+h6IU)lYJ)}S^+g<&f!0*F1u6^{uC070i9 z!gMbmrwje@&Mk$;o`9dhuZVKpZdOxfLpfs$#Vr5WR$$ z^>Q{YLe921e47uNB^z|o{iy;{#)HY67ht-#=jOSHvMHa#x68&jqf?yocgwxIRf|%o zfx&C`Gy8MI&^mEIE9!7MIy@CF-}fq-vpy1iddDqO-cGpq0$L|#$H6jnzLxg* z`Gv#YcZK_)=Qel3o>gAWQ#=suqV9ck z_tLwj+@l|!a9U_8fTf&IY6HTDOURWh=t&wF0fWi~VIc#(|Ku!MmCQc{08Ra;BjPgI zGo~TwZw@}$3YU&SutL~|zJxbld>fwOM(4#*aJR(4Z%S!@((xt+wL6csO1f3hBsB?+ zG6dcn77HJ1=tD+yR(6kbamS>i2zdo;;!U_3>n?l>+60(Za#iIcQPMR~TxTEc`qD^G zVz_vxtRx1Tk_9au7a3;otAn~Y*4Yavg#&z+hIdHrOpw>`W=Q;?V&XI$d{~4@|JW#h z0ljI64qkFwnp(g}?OMc2KtKKrwgT(wBt{xZf#c(5!NE8MLZHo5eoThPFS9@?K<80_ zBc%Mb{I?;ZC+ABhD;%pa0mt#sX}ngO?>*LNtNMN^GFmvVK^Qi%TnEf$NE=|Uj^7Vd z6DYlLgFuQX$VkauRkg2r)0 z1tM6}|8jOgVuZhBIcV(P6ZHV=`eaS+R45lXxp35GT!*SLf z=D+(A20DbD1JfLKX3V&b>V7k8pR5)Qt>shXe?6l}=-d2zq&&NmHzL*rbcUr&=EphmaaVA4!98S-^5QYrhiS%y4o&PF5yDP< zgpSLDN%6$iXNh}0&$wM*^`PJj*6Yuul!DijhXlsZ7cSwCF2y>V$`7y!9PsEzdP z>vK^NK~~kW+g-eMn14A04F41N8AfK1)=rb|cmUAy*lBB41EoD2F{*|i%MtnyDb3C+ z{mM62^)Sxx>RhS|$3bO)-r|eMT<&YA4H!^kX&z{m%@WD-St^GW2GHhsx-Pkewh}G` zg@mQ-9#b0@f@UtUdJ=KJloAL|eDk}V<$2cL5I zN1v;n>HMoTvGlVTWEH-BgA{DPT_z z&6}SYV0Z+VPsw*d1#tT0h}W(VYtoj12&)y>eea=4fN53^Fs}cFuGU+(V-VqsO1;$D z4_viC_;o}@XdLHwE}so9^a^Z-A);W+pLJao<=NN-1Yn*~WbO1WnJD008+bRN=<;)Cjt;KWV@1hU#0V;G2 zk>(cS2H!9+#OW0sf%QzTw&r$KJ^}z-4=d0NU)A7ZYL7j}Xm}Shet397f_-Nexv8a= zS=*9gVU9BUIyZ5|qB`<^&c3;?8*lOpbe*?cI_$X-srfHwck;j4TnC7bpa#k$^&wTH zyCs3}U>EcEkzj~CyV1@zLgEaU?1$pg7v_{Y0EtE?shn`1u-oa~kD2w=j6fjcGlvqp#{gnYr#8k}@bayjelyES$D!2`ywhyq>bWS+L#)m_LCtx-Yvx<<=v(%+SUpo%=9$UWb{9>1vPUJ{qfou0Y zYt61@;4uCNRsH+8jRO`vRK0Mo2_&2;**}F@3%KSgi6vnm6h;r=$(Ax(KM^JQf}O_(#KSR|)7NQ} zTx?ncHOO9uIAv);4_KCx!Yh4UN-x$^BQa=RN<95+P1z(UC1lXZzE<&(%pr!J}%!4SWa z)a7&h>cesQs~pk`jt0zbhi1UJc*G?nc{Jv>2~Ud}q~`qbgWnyCBM96u@?;6lh8QTL z0Hpw%quV9d714WHqnYAFcvOg5kv`HcH-+mU;KkjA)gYYN8yO&8XK8@%W*QDHm|Jj6 zzl2ZDRecSlXG}hX(=S7NbIRM@ z?1kZBH-*7J57m9BZS>vH_xsCpKBcRxE_u0w$&f7N)Ts`Q$M^Q_D1G5+9#Zs@tG6ftmaocNAqFJ zn1(vYUiRi{uth1a5Rc&YqD#Z0@f8z^iHI%=yrX-V{uqwr@<%#?hwBq}I}Kaeo^KHy ze57Nzv3YpT@@~*A;z3hm&Nk?4RTaaM9PIvbMJBF6-BFw2c3_2D=Zc+=PIPLRMLBAP zY3zNN_1mMUp6lxB3a3tJ?^jUnqrZ)*^iMb`GSlg{st!NaACq`=p8Y&9s+@57i*L)o zMx8lR--8j6c8*p1^40|vkQ)Hw?fS-UH%->R|PSK)kIQ+(^E zpVw};7_MEg?&_B>T=HD_CUB6adiDCKk@Y8ILmwZG?g?y~bUs;*33tiQv-|q{ZR5Eu z?iNMPrR)0g!hb%NwGtgA0n<3eAHIk&6@G80fhj*Ct;+?W&8{LIdfq>eIU~cK=$ERB zlnz7OtC$O!IDL4`y8*W*jJuZM#={_q`mH1N5g5LV)x%9;sx>x?o>D~F5*{{5zKPh* z!(7Ec9@y2y-EbE4g%2FpaUgVqMzn)RP)RI)ECBAZq&c9 z+f$hvwMRd_w0l$@z5%VsN0;1nJ^48|d)u!3VUwUOt|uxN(ofM+@^Gh4b_M=9#LsxJ z{ivq=4~8SOTdv#*aG~FbHn6XN4R54LHI%xMYnY&j>;RusIhQ|@&Qz1XZsuM^>ykU# zhBu0IDP+Ds!O2}#X+gyBfYAZtKt#k-xJ9mBggFKdF84G&$zzx_mY@|)EAa(00-w*Y zOli&`8lWUW;K>l^ByqOvHv=uqMFNI*6^8zzuA+5T_>(LUoH_YM9b8%pL+yU}Q!*d1 zyi?y7JWTdum~sQ~n+c>g=32=6sb8YExYW zF|neEd=+f~ke6WKdB2fR!p{eP0Cr*V-HA3L-Pu71=L;Ew;I-3wU51-Q^HNjVs_6jb zCV+QdBlGu&6dM{_1oQCW7};*QhU=LLRjjupV%F^qD-oolJ03l8@y5e)om&q-f!F30 zTemlvIMxr`I>QMC)T86~{P=q-j;fuwcak@7Z$ruUiuMMha;2?%t=Dhe+x`57v95GT zY6=*P7l|e!Kh`p)p8O5>S-w=0E=2TrQ)dEx4O|F95wf5-zI8S+7{c)~L}@+j z>;TLjo3tdrxsUEP<*Ba3BZ;o>VqEw7!`QY#h63jo&N~6~*}H2*{8kL#wYm8q?b=DIm2L(QO8&kv8(`E*4{qoNZtyDJmbLuI+?Ho2 z;VW9Ymx7~j)Ya{LVMJXodnnfcM!;#lOXx#bvjA9)K^oARV=iXwkG7_s`)6+u{ z#6xzvl>r>!B?ENAWOYJuJ78t3oxC{#lLH!a9a;;%?;ojK>z_p^t zUx82!dRK%g?@QJrm?csXt}NkIFparHQ&}@lokG2WH-Od>FmR!Lk9e1( zUE|sOoMFi$cn;Vw0hXU)mFzFHQg7jW8t@vTj(!(l=jfsx>Y3GgLLt6)-#i(}H`oV< zg7kC7x&qcgrK}!udh?DKji(>xyp(K7q}^RCpZh7<`JOaNt-;ONN>Bmm8Z$!ccJ_MM zqtlvhreUrNYLc8Vs+!#qzrWO_JB4$$ouo}EeHNqjT@h1Ro!{c*szdn9e-ywz7EH}X z0?IkZ$))f({8JJw#X<|&G=r`J+d5zYANY;vHHNrT1K{MwfTtucaogwDgwZd0AO7y|!b5OY_VHL5QdH>PZ$Y9JZ9S*Qv7w2Q zI`DVday{8C)_Lp|OdU4aE+1NKqa~viVE>@FH33+09c(CZ!=QRKY(U6uR@el%Z@ zFFj<4IqOzxEZvz&^uocYWevZPx5#ymk=IaW|Bjijk0+n8b`s}(lUo#_UP+G6hGEWp z-&u*6N)uPZ%lI@-o%lQ~kysJh4lxbjDJZiSjQ3+zn$CRBzBRE68ZLS09o{&zmE*}n+!WF81*C3gfLneeUXUt^Q0w zz_ibn?`GsQZ4o>hU@eOmu0ajgXot%HAkuL-MbZ8E(X4eZS3fy9^kBt6*iN48P<81d_F-qO%|w)McqwX11GtT3Qcg5255 ziS{;NU8pYSb5k~^F7?=N{%lLp!19L~IpT>4Uf4sVc39j@?AFo`H%BcGTO+P6^Sv~5 zh}EA$`U5O#AAnR3#sWuERYLGT3hwi3M!v|m5TY`w+nd;R!bp>H8%qej^W^r_$@w@$D;yM$YIdIqHgRsgjdR-f+#_X2 zWVD$0JrB5-l%Sve-`z|8{k8lu0D)N?88-!lmEpQPk*j0pvlp8IGa-)mT1IbYtMu}n zL41T^2wGW6Itx9eAhTm5R5}oe71Z&A%+14=<7RXzalDH$0*q*#vSTT*iSb-8aIo(* zQ~)lVEk~CUC@1<~TBs^3nEkh0>0icpzmnuTx3EABrloXpUnM6lX zzL&^|6AfcML8THU#P zu&XvMy`1T+3!f9VpcDzF0^Q_Ckn1C8#^wkl8-6I?m;KXf>LI}9T&?EDj@}zLdmDuV z^0N2J_%Wv=Akm(i!qNpOtR@~5`Ilwj1t^V%ms7g}IFqZEj!|oIb*xmmJ&3r(q}8K1!Gg4_%$?Gp z`lbM;E_{PC!(V(^O>Z|15>*lf^BX=)?V7s0qWMxj*|K;mQ}6adY0smZ zqoo6*ZOi8B|I4h8d=Dkn#mRN&rFMX&Aw|)a@-ciD5N|~82n8(|PP!d6dj|l*{^SmA z&|gtyJs3XNb2?1^QP9FkQC!%U`yTgg0SB5h=l}}7oDY5>iwyO!pudq&35NftkE~Lz zN0;j$rMD^Y!5=6XG?V;a4IBytX{Sju!0%PD_~7l5C2|wmPhBz}NA4Pw>zI?0$n9?@ z4BuLi&)}|tRE4)c5-3`etOiUP(Y}O`m$>VtKiT=M9Tv(Lh)V_jh-1TNuQuqbBD-uT z$wU+K)6hKnPVcZ0koK`KB-PcNY`&1k?MGc<8p29^ujC)pWk3&uNs{Zsx*$qijJzgQ zt{T%YRynoorz`>I#F}Q~be@COCp4#h4`3-|aw;_v^L|N9c&g{enMHxxabS^At+Chq`(Xs68jIpfp7VgR8H zCv*>A;wWXzR-u9$8boSo5dzkjZl|FMy?+5HS=|RWicqNxds_Fo=oOdWq&=E8jSj?r z@<{{pL)e6tE+uck&;k2aO}ZM!$trp?lp?t2ft z%hmYjHk|V_de-#DeWWh)-q{)9V~MoRnFQOJ zT)VY%0ov6bwbE&Ovs?6y;w`&7-A|Qhr+0ok15NZ5u1=4v4{09y`S|21U1LSQFH&WS zqzg^lNZe&P z_+T(+!q&+5T!vGfbS;2k^e__TY0Mivc*jzYM0|$H82O=MTkRx{dKdZB3Yg$}VCi{Z z7kQ2gAJ|ck3GDXf#AauEc8BfVk9m@w0JWM7kgvD<166mj#Q+-Q)lS_Q{*Xqbk!N7t@pz9o1U`+UwHGE|B_Ej`$75RlP zC~RvEgGYDixwNZotZ#mwSmMnBqztvq9_#my!e16O|0w*?>hO<(^EMi2mo|en*Ex=o zud^Gpll*7oAKB9r3Eo$C`gNLVq}ZPB-DMf6-C|JnXM!Q%o8sYZBeU#Ki7E_o zH%GLo*&{#~R+bCI)_r^{fZFN`4~U_Vu6*^pDCiLE5GVju>NQz8>IY&JA&!T>B$=(O5c-21b8fjkJNeOb z=u+`W!DW9!eg}FP*lfP^E**--c>@RP)sEu6F?|oKkH`>Ws4R!6MvMW;DO}O=ZlCkC z2k;j$7S5w;GFQQMZJavT!v|_z=uN{jkOJH)m#A~gd&$t3-T*CDZs){a$h8aeUcPbA zy#8bH-p_+(#`IyhT(V1Q4!;1;#fu>6e#{?#QiPkW6JQPDKK`D&hBcOk8ug;IF64>; zqU}374;mbEc(_^KbRYITIXo-f6n{x5S05{iJNeG+?L^-SF%QZ9BGupu00;ZmUwptVPb52RDFzRoxX`3~N-aG$3sm)Le))#s9ws{69z!@Ta zhan?T-0U<}QR*)UpQ&~@{_ZPKBNxogy}9?0k7~g5%>%nmmpcYft5RB!TxOE{B5Uq`> z*?`L^HiCdM%7GT52lOaE#y7BoL1-$Xhc=qY2e6esiH!tC`r*}MV4Ua=Kl?{v9aA07 z@4WnqV_5MBzP{KF9-F%9G5$vhXKqb1RYl}v>8U57hC84S{D@eBXZOdPeHZ??N%Ta* z+ZJalL93P}N)m4zvNNb8WCA-0Aq_+-VY8+70#(w?iJ^}o-5zSXUT-%_Gu+3b^;2j3 z!|BT?N^HIeb&YnR;{)vFF<75ajmBY)UpuM*FS-oO#bDsQ#+@AVjC-RY;GuPBDyC(3 zv|YaSwh^qX(bB~wIx5;EG}3tI!QuYU9AA6@j$paE#k*LNBeOjH=v~@0U<7zPS~FlZO9G|1#DjW7N9CfAR%0(% z6+L*^2!xzbvL?_#`vwvZ`z7ZHNCBl2Gdgonc4s3@fx^Wl0Jcl$MO(ox4`v1kB@$B* zKZ!>AP5Sg^E~o}~9WNLG{cp>2U$1v_bF{CUC4TC!&_%M_tRUnlU2F!&RS|c|ib(n# zc=vvhSNZ~0k1&7o9WbYZxnPlMFe08lv7iev8RWHgQBUBso?<)Eo+poMK7=*^!lvsRQb)FNX^DQin_3RTpZ7znt z>4M5=!;6Rg!$UQD-`(@BHE-K_1DA2h`f_kD3*KYu`p*1QJ!|k2To;rOYICb#`0Jp2 z^#fsuMZ{-^moC5PFeab;kJy_|7vkYf^RxC5(RhA;l*9=uvGpPJU<^m)-PX8zZjV0o zee+1yUvM(aRM(xApfY?r=J*6VAE%5!INq{Wx{q?wag4w7T=Q$@ZCME!q=PGCLfP3M zaVLbVCp|2?4|22Eqh+7x-C@i*fJ=dOaE-WyUyb*y9j?b|5Uw)zg_eC7!_63)LXEA7 zJhq14_zR=U)MQ4h`u*$=Z-N!1>);`1xqy~Q<~_hbp0u&$V!r{kN=cBsjfw=LURoAz zCBruI+kOy;B{vMmJ;QX!OvS0P{Mh)w>^SOC_zN`S>}#-Ek&&;1(IDFL?2o<_ViV%O zrWJ()*xf#D4g@xXJ)w^aY`@B@!Y&V|h)TpZvfIQso~y$#-L-_Ak%LUxHTI=wDuPEV|971`aK>5vik@eBVh#6n*) zp0EXpm*!8rHP`-8R(K*$KRi6#D0Sd>HQP2%avcGj{gd#~zl~FrX77;yh%m5N39xq9 zfzlQyqw>P1g274&HdxP43oiKTysqQz`bT%)_*b&Q(o3&}m%u_IOEm|u8EJ0l9r)2W zezCr%b=G4{O8yZQo>CF5t@#i6Z-#mVmruu3)syQDeUZD;g~9K5azw0q=SPPq>kwd4?iUhfhl$Fuk>jOSGVCVDSR$k5S&F0pEr0P zZtZg~tJxVJQ)IgTt<>yT?NO00fyDW6Bq;TFRw)a@^$wl^=g@sBcXFUxX>J*!7xNy} z;%C>-78r@DaP@2{sLxY6+vgyDExn|h3SCETP@&A$$sT~NfGRcmjJ)Mcxc~#mcSWD8 zH4i&C176ACQEgf}CXhwJtVeH@9)Z=3lZdC{9srpF=%8335mEB(ARQZ3F=|oZ+gT&E zg($n}^xlqiAk z;pYrx_D~zRbH<`HF@>BQr+ca2`vZu_w6hZFcH87%lWwVMXlHB^TYBlG}s)|iAY_-cd)Oq)`7cb83ElVU|q-H|1Ib23d32nZKSi{n4!%GQ4?t1 zv2A)IX^gE;;4)jsVH(4>B#bjrSrN*y@1D)mq0jo~) ztt}1BC>1SCDZm6kT5+HF0Ypv#0t}xK@0PbjeNi;uxMy6$Uehc8a5JSBw?Z2KQ0fGk zcfWqM^Y0P8vxeK=TKS?)oCc_h&pHoq`Pdc#ur;s2ZI`s%aL9XP3))x|=FEtSr$y@N)=!r5R-Ou8q>;VY$opVGpl1xAD~Tx#r0&m(Z^%_!_-p5!iN)_ zzF+ATzpzJeIXFoIrM7u^E5O2YU1Zt7d0>8&Ear*IlYYDhEjjnf61|(1)yUOictiAF z!wqm@gk&dhvSh7|p`?h(N`R#eD%9Cq}RssWU^+~2V zw5>Xv&(6T8N~8FyK3rdj+J#Cj-T?@t$xv?=(e|-#ZuxZiF=ncZX|1XBJ7Ep zCIvpz1{{``HQCUL{eI=5*ao7_@oAwr6{)=_xQDy$hk;AC^)MPSXi3%iAl;cH$jgN~ zPY;kbzOb);T2c9dXo=MVEz6nA^$V5nEoJ9lj@JKVI)goBbr?wx3>e(K5GQ~fvr(M^W8a#M(jB8)5i9g>Kj%4p>C;L?KeFdvbG zUPb%^9t4w7%<6iw7OB5j88Y(d=D)@Yv8mD^D7c5ZrU8}iV;iOiCYFE|%Ulk5rQ2b) zH6;c8<9FbnF%l%iACtZ^S#A; zMX5Eh0+c@S5QyY92yl+Y>%d=n0yZ)kLkn|}@&iooGc|*A^)ka=*TD;I=&b)LXr;YE z!lpQBK_m;XqG@aXQJD7U7s$}GS18!jy+)R6w|~EpMIAry%(6{hzb1`qEKX-9Meq11 zYPvG*NK6C%-Y<~FV3R@0Ka~-UGg#jah)}XjuDtkBq5(J;hU)NLNWzb-6!Z}q)>+P{ z?OC!ftrC0YehB^MKYe*mg}s>a*ss^Jz-8LA`78&SeukdHqQ?Mk?DGQC5Tole6H)}P z1@T*GbJ@+(#5{vti(QvLw*qIvr5GE}yARu|1FU933u03kIS1C5{Q2GA&v|Wz#ez!9 zSUWyKOxcV<%kB~b`4~f@B8(GIRuHJ2^53E1Qoira<#CJa}Fa6-} zef+JTlaXds^lk^ciw@hJ)o&$KCyZjG*Dtaqx?r-oV0ib(sID|)7g?h72WCO%FSh_k z&{$oCRV4OPHpf|_@4qHXSC@2J9|NxP<&kbcS46AAp^s*K>OBVn`bwv4C^r_Wb=Yq2 zg6gjOHknm@F8E|#l5;8j&<)`|_<+Ql^b%B3hBZ&%1Rin@CBaDXBR|ZoVyp2E@BvXi zpWRg*@Qc*`&?MrK8e+*s!;dA_N^+M_da>#mpS6B*Og{r`>KeB$FH^?~LXKCX=^z#cyi6qsgqTgW_vebt*N4$ypZ16I}BnOC$c{9sJ=uD;_9 zMMeZaD}Bqmh4d3euv)l25?-9NtDeCRs8{3~h{fTqiM)D2^# zUQFEISI@e^3SwOatZfo{M!tF=CIa7yTLJb99jPhAY$zwNfVX*e2`$8ioNUFq zzVv$d0p^qj2q4O z2CaBFpAI%u7x5mEQYRSod1XN(yv1xQc4{1Q9n%v2(v4ALB+y{caiMKR!K(dwlZQ+NADy{{^pZ=TZ{sFClfUD5 z)&&Xh=@Wxk7^d5vggt#>!xqb0` zuyg5oaKM#2E`Q6?Vx3Pk6}QL=B3L{sc!td(!~yV0aGzSw#Y(n;x@#@#eBb;sLf=V< zohdz#2vlR-8d-U217@u&SY?7CRu@hiE=FEm^a;+ecmUtLKkXb$qa|BKtRC}Jki^MX zpOYLR^)ojD6Ne~yJCJN={QwzPz*d7t#c85-CvQp<2c`SU2sY$wKagnSu2G@Gu5kinH|9E*{*S_( zgGeIwkyT*M(>M;m(T57Ldq}(c(fgzZLx5^&|CXd7wSw|0pmH%0c7}SpeY!uyQ8kGU zJe1<3OVw9wJP#q|V?LP`& zrZRm8Tu)s8-2e0c{KqeAcM~ex(1xNL;(VJ|UgyL2KDuVy&`j8^m2JeCX?Q#LXSeq$ z-!Ff3U)kSUt^Fda?TzIw+@d^fyt9wr8_QuDL2*`epc`~vpICB9h`{q9fGMH?}B%DoH99jBGUTyzS8YhMuQ`j*uOFSBLsbU{4@*R ziIJXXD1(*2mFyV*@WCII!ZZrq_Sx%hmE9)EAyPjEL9~thdaG1O9=`o+2M>+$A$7!{NnfLZJef)Wr zZ+JF`wWFoB=JUCGCY|0ETZOxBWSaKXMBbXTJB(1#vntZdRx3rvy5n;q@9oPuDt+?x zB^wO4DeR+{;YA+L(@_uK?AMLBGTl zWM^y<;^kYpzqJ1B0m^^(CX#FrR{Q_|_p<7U6Ih!AK?lC8St)<0`O#J zEaU4Z%&Sl7Oqh%8!9Gm1iau9C$n||o)J3JoVpmRTa8FNidT&(6sA9U}8jB5|4;f>D zRm@hMG!dc=;OIE8zqeC0m^%r5!g7inDd)04%G&C1>N;Zh$5EKt!=a_hRivm|YM1*| zGm%yXhw1k{FKr$qT0f}2Y@J$d$UQQkVQacwL7r3j%|YxUqsXm@n_y7HDtbU^S(dHJ zBR-&>kD!jZ2r2FFtB42AJw8xDST2maYNvmnp#0tUdD_Rf4f?H4jx2z%Fn}O@@XV1< z&wrlvQGh$;tEMERFbpW#f)TK>^=y)4uM|TOUm20>lX_WoJuFG2G;GK&5tYU?l)v(c zODE}vE(YjADdHMLs?;}LWGzk-)s6X00PIgW=BK6G!;r@BGsSy=-2cqZ4ypAlMPej1 z0S}2@B34Fcg`?o@+o%F;c7Pg$n9CQ9iI2-}muZQmq!A(i}|^7=DRWL+&7_VrnRJI|bkt zK_Y{pO46_#31`tlsSTP0(&v}tbds_jxf8LPOK|BR*S}_`+381%blZI9DA#+h+C?N* z!a@fT_Py~tsp;iqphj8omM)^q=1R!&58z?#BEcFGgaYf?eu%{{Z=-T@#V67PsOzy* z1Gt4py@p18Ae48=_rdz8ETUullklaHYxTegATSn{ddcRKw4gYNKZS~jw1|z5EPWTg z_>`r_;^iTgF?i}4`CD=Wu&Tw6%>ZBj2p+m^XFmKddxYD<~Twjz>giQJoOh`$NyNoOcX%Te*LB#pO9D)ab7qJ zI>ri6a|9){;DCp60PDOh^;&>|%N@%;)EG+~NEhLHsP8koa{6|Rjp5*L6RPNWq3-PK z=*Q!(iltAfBJ2Ib44XmoaUo%X>zaHNb8$z*r=qfw(Ae^6oyL)2-QmGeAb&leJyiOs z^qs5X>*}HUY3PHm-@*Ac&@qZujjhw>+MO#))^+RzQQZgC-I6!o3R>5_y=UhQcefkv z&PF-TMmPUVHtDdO>iPZGPprLuW7Dcq5bAy14a9Yqtn2=_pOEeaTkR*72GanrGp~>X z@c^z?8zCJ zKIN<~y!iA+$@dodnjBzq&IcXt?7LaaLL|Jol`U7B1IwOBdWoxzYsXw6uLJXXTB?u- ziqRe%2kBc6=R!0533?UagQlg&wqVl=hGga05zIAX{-E<B; zx6Djh?M0oZ&aLKCp|kl?Dq=1Hyk&VHu)B(D*LFlsxjAYF41XP7nlNoKEllY1z8Vr4 zaXwoxaca%UdXIzb4Oe#6=G@qSZsWIA_f`JA2-9*q^|_^yO*{nn z671B=7Bs%U$|(```qM}C{Z&>teL}etgiAHI*p|BfqeBIp8!%8Wvc45DJHVe`SY2&7 z=F->qCj$5I`Zs+Fg{ovuvYlepY4>)a5RRfnFZfi26hFw+vFc($xBR5W19o14JaE(- z%%3NZ^_DmaT91x7ruRh~42=&=G!!)eufS5P`${x7$9Sc7Duug}9FnNtE#C-l1=fIM zjToE)@t9}?P)Ebi>su09$Oxh<9A4R&Cd4aEZ#(iJWWgSBLj7xuR~@US`PtBqmclt> zw`a`f3JXi7e}io@9$*bSr2x+C#ZrnfZ%Mi!qD8f_FiwatfQ!BP{g&&jitxvviJVBz zuu5fKuKUPBk?E1zYZDWpU-9#E5rV8ow;eAJ*c{0)imY|oTv<}G(&_NB+x@q0pF6j) z^0xyk)*i7`07mz%E`I%%p=O(ht+Gsy=AUA?Vq7Th@6654zM}z-jaSeg`5uQx@^i?F z4bO9ei~pm$FAsl{Qy8*N_K@t`h+!02CNq{XF>`;pAEAo^ze+obx=- zInSAYTw`YL`@TN+=l*=&%WDbe9RVpJl?8(el9JZ=a>M_l4|@JBi-P|V#}fP z+tUfH*&Khu(Z2--uaJjl1bGK8dIi0N#)y=z)+&r&&KaFWvd8XI^F5X%W7Q@=8+*|r zo)*8$T(QM#un2B=>NmH;s24d@dHRpfHM2h*?e3n`&=C1TnPKW!?j5}7h{ zE4g#Upe}=B^!4Y+NCR&abjy5e&Cr{ncn@v?%chZ|33cnxfh0uNzGf+c5f|8Min47I zUY4ZgthKY-m`A>= ztWr|mE87lM13+{-KJ%D&Pr^xAGmGV0%-mswe*AuSXO-t_9uFL?e6Phx zj*5F;qebr0n1%E7R$Az*L2y~HQ&R>&M`sYuTIiM{_I|~Kszu{4D2PtmO%mT4V166& zL7vLQ=PSqsn;6upFK|UV^(WspyA8-<4EU_Z;>~gsOc&%#3SHZ@l9tnMJv$$h<>K)r z?Q_8L)g!@o&vwifk(=nEza!&XViA|rbfpIxMwaJ4_Q*94=$p^l$t4F)x!U>@IBi`6 z`5EU2fP0)(sE1*8ia5czTZ?UwY~5r016;?pn8r6C#s;;L23PlwTiZ+dWrR*IDfm27 zjX33E$-!LTe0OH1{adpb@&xCnAzmSqZG^p|9W8o$?9rYSpB&o*{wh??eR2W|C}I^abq>%d=Ww23-;zr{4mb+d!w5tln}AAOu` zTWop&a|lWex-y-q@g9zkBc|b$+hVH1CVJ z*Aw&aF&8Xe*Hnlei2g?6=^cei!$90i0H{R~2nc06ZN3-R-g9h_p z6D&IAyt*)*F!B1SM3u6Ig!l5`Nio| zw@Zt{JDC^xH%c>4FE3xr)ElhJ)V*B179ycM+#CvbH}xyB7el=ZA;#AN&$7Jl(J@-U zvh1Xo2^CnDjXp6K`>P`*a3a25$6V?}^{L>>#PT{RC$KzYB^(p}SO#E%)5E?9Lr-#f zN?kASR3Yy;H~ICK$2NwIE*bhuqVsMC!e{zAKL?XGWk0i?sXB!cKa+*P{Z+yH<=>R{ zj9dZ++l@3vYinQ2I37zhTpKC9uLg}4y0z?0|%1jz<7 zmNxX0K)ZqKG*9Gt*DGyl=7pjJql@DvZ9Lp^bqg;+J(u79%FWU6wD&JEqn$ZRdS9e# zm%}tnF}Jv#Ow9cL!h>-`X-gy-RIBE>>E*u)`=G%D86$M-DUQUfZ9SaUs0qfWKhs-o zcx3Qt;iU{>F?_6AiN7O&%-c^RvgaXxZQCYc0h`1T)EfqEl| zMupd!A5@Qo9n+U9PSPw@>9Vzc1-x^EwYnjWKLfB)73ufNo}7^Q zP8uctT4_FP^ERb_NW_a%&b<|OtzbnO!TY7DP)2Bahue7jZM?1 z{0F+%`6R_!jC zrMbx+g)ViBNrBc-5KpX$^L!8}5ptD=7b)z{7RB#IM;1`K7Y*R-@ILPTHCf~|wy|hz zDUy0XbxqhyF;xF4H)V2ZpG8IGflRgh${T3AAvE#@H5Rl00NH|dsT(9qx7>%p@LmMQ zFg)>~DGi>O#modFD5>c#ymYWT0%({UPY*Z8*Ti%`CQdPxIQ`tI*9&?+pS?cq<68S~ zwNk4oA#q4xpG7AqK|)s3WUe|$w@{)Pp*FkmC;CdLlZC`Gqxb^NL=AC}4rxSEWMQrK z!adBbs@m0vZ07w*%#w&B?X2yn2BhFDeiQ0dt0ND9{bTZZDFC6IEy8k@h=~K)u~cy& zUjy4mZI<dZ)vtc|a%!>^)N_PwmZHa%QMHY4XI^G!XCtRsahWY{QR6>yB4Gu0v z_)Kf~P|Zd$F>EhT-QAD$5!tgQ40_ApRDE#PBdE7tjGdU>)%qMgtwBp`l-t3|i=!8I zswPuv-Sb6)(d$b*2@G^%a~fQu4zx=a4aMdHiJ~{J_|GBzdEHIzY@bbC!q-%7qF|s8 zv3XcID#M&5*y>D-$U0UUbUIY+^t?_l$#kpnX>hYU;g!YMDAGnc43D(CP%rUT7=p+WYW7S7;{_N{8Ynp>kT&H;D zU8Dx-A0C@wp7XZ8PLF#q# z83x5>u2n1-qmwT_#K>Sp$E>g2Gym4cK$aeYmk;wKfXSP}rb9cFJ()DB1I);Ylj-p7 zlw)5Ol-Sx&QnSl7m>#Nr6}D=&oo$dN*K4w<^Nke)tyXuYt>^pP_q7-~8E0YMBS zs#e}^_yDv74-F_iJTRHHa`60of75Wm*`y(r{v7*&oBoA_iMPsMF8^4mJIwUj-}HP= z4pWzicePl({UQB>H{7YY4}3kk$-fZgK;C7iWEx$bR%0`E`JwVk-O=u#_k2B|2LB^_ z^*|q$<$(s-dC^CLK0Ut<$ZXg*H9omqMf!G7)B6Sb-Ql7TTN)9!yI0oraqM|W@zlvEokWeu@qB&c*UIrJ>&|w;~i<*dg z0lISw4(ZGWE}TmT7Gg<1otb0rXm?)iVCmsRp>0w6vD$50&;7hlRf*<_t+#xP z0LmX&_Q+&J#I)7=W-|xWA>c=f-%0NQQaj;3HK;8TTfLb@>sSzJ$X>q&w?`J{XL{M}}30ZK0TE#E!~ZzV$U^Lzt7h>U)~erci}pg2L$ z7LX;JU_;a#8gw3LRlvB1l$dL5uaA0W(a5PEkS3o*Xqgs4Is?$DFz4lf(WxJDTl$Q; zUUS3SATj=t6-W}v6rSNWHf>sN%GgwZuW6j8zg~b2r9oox8cLf=&QJ=lQH$IFk3S5U zs`vxnftoJ(1-4Bi{62gqL5iCSHi==W%8>0G>Le_BLXMSR7W``5+li3;=If7jy~JdH z?dN{PJak%_qk)(!nsccv!6bMNU~}eQTAVn<-OlZu^|aczp=2)PfziP}fW#q-!;`WpTNUnpard1#7>%|Ce*4;{#yDel9`{zKA=?) zh>g@}Eqw4&f&-+efBmi$C-PJ36$qb@?||(`G*Y&C zAJj)UH3%K%-Q|-IH`km+LS`Mgzu5h4pnuU!hIhSLpk1z%cB>4_`MSW#5)Zp{zPhge zCzEH0Rmg;Lu;1xldGR2r0;ys6Ron`P&rJp=S!0u%EHS#pM*9f;guSdbrn$Rc$y~jx z%|1d){ZV!sh+5+45&>iF8hME}`z-Tuos-z6{+BqXA(hVdrM0oK4_7TuubE*dERG5M z_i&Q`Ebqw)L|<~!ga-cwVGAys0l)9FTE)Ax?Zg~y--32=XujiuGzH3hJy)HWckRho z`@4l;{HVN7SviF+p8X2q+ z4YaYSsS8Ef%09O$M@3)%=4Sp-7oE3EI7w^(OEb%bPP@ba0IQ_**+xSdMkH zmUU(T?9EM^`yASA+!{>uYkPs)e31Q>EJI3~b$DpO_^tBP@+dXM#)&rTvN##%b2;R> zQ;K>(r%nSk7dcdOsQ9iI|ft&=&I zVan=$VBo&8)U7Vo_t##;X=ONTfjBn#>-=LGnNUOHjY00=zXjxzre^tZG!zso zF(0`2Jy7Y2TIc-03zBWVps-$YaxF>sLjHGUqtfKTx-p+RXDT(>uE6fbh>oE;Jke=J*~WxJY+RL<}*J=?AGBOGzYWzDgQNbvIHeS5a1o>zu;k6&L2TB z)Q%l(2OtN+^aR2oc6anDW*n?$4I!lHBb43}17X$@Lv3**ePW_T_0h!KM%WvQqbyeL z>N{jBk>$J2+pF<=T?{vadb4HgH3+@LeaIV22XR0pJ;&}TmnZv^72E<`CiLW7N{*{&PKcbrW?|u%{ zGk_we{?ZyJLQQS}Xg^TXgxCl}Jp~kNK+e0#CUh@MqJ8gT2uB9W z>?Q3=IX+lyYaw1>OVUeD8Myk(6Z_fV#+T9(IIBO--(Xh8Oygr;LvN0%iSOOaTlVUa zyAitr<}MZ4Q$p5q3wm=*Q!FS7pI-@fs)PY-Rn%-NVF&kO;RG(ZIm9h94}W@7HnK7r zf2M>>Sg~Tub`7QZdoV1$`qpH^PF>8R^$q>};;bQxPVb6nIWi`5rGJT1q-H!^FO38I zdGX#gjEy8WyuW#)HHVSl@8sju(du*ZfDb~bfAQP~zETJ6b*F-Tbm9zJ_njpvW6@mX zJ@9)ck0!TNn>~bf@C*mb(diCHdVI7tQ#`L;tuK$=-n@k+=6Mm+(pxQ3ZkO&PnZJym zz|7&WG7moELXWmh`iZ}HFt~9kjiLD={p6)Qw*(i2?%6zDHOAmjdx5Fn6Wa$*HhzkI z)^sEb-=6VGWxScb!y}ldUSr{E4F)YvKQz20t9+@*+I#q6N`JNW$%j)42O5E-(?z%5 z)x-baPS|8R>k1q;cXU#On&395FcjeGajt*r$@x-CkI-T?TWgybKIdTCo%7O~k}k{- z=IJWBYDfpn@-(yy^d=PZ3Wy_ZQ{DV?kdXq+nJ6FytsQT_Hk$gI9NikBVI>j#CRO zxrI~g0F3*>r2>n*;{%wUA_?1s5CqyjPo+BW(6>>J*<$5Xm{KEZ3+T_&{<0Fk;wIC- zW?6CL#wj{|ta<$uQ|Y?J*hR_Hjc+c)4yOjC2Zuqm@sm=#$EYYcNAV_c!!%`qvid?N zywUTk;p0io(;*J$C1J{)tPvN){x`O-&ZbJfK=+d*LQRh^*?-Mb?y%~(gI)Llo~Q2y zYE92?I7jA$cP{giR2r|odxkq6pgH2bU++Sm#fyD+AKHzN-Fcd)+hO}+RvGl&LcMw- z|2@O-|69kF_@xgvc_02GD%NI9a0=dp+DT|YR&ZWzisSklCk(5HdHyBn+2-_1xXmX2 zA3>6mdIt3>EPx3XM+?86x5lPfRzz8;xa!=nx|oxFuHTZd7355bK#YXCVWSj_Wc?uY zX7i%|gwqBIF279#zYS0{Huv*%{}w2aj74>O@lMY|d%!j1F5^H5w9YZ$P$akKNz@hC&aqcLwiHQx5r?@Zr8-n(|h z!~NSHvGK$EufBIo61l-ul{j$igu_D(1!>LOwgpJEV5gLBqfRN-vCXSs*&sO0!{2vr zcj;mc%)nkpB0PY_4e=Gtblh~h^F6*m?{-}>VUEkOMi$I}G;rc=g$3-oD` zUCE5nX=o=XdkDgu&sEfes}7%@hYs|p9jYkrD_7HJcrjrTsTpXDk3_XGR$MROgo(_4 z8dm*uV{6~ZKe!V;#D5$mw^nD1yxlchOy9a3?`v>J4@8vResQevR6Lr3Yu8$&Rfp8L zte3_iZvV1(j4l?mrtIFaC&kGpf66vX?uFM5#y9c-B`Gu_U~#;Jh`D@)Z3zYx40Hr2 zj?Won0pd>6t4&klvMkX7{+`s>4HEQiL{EA+fUlt836=12Y#V$l_vDxfH;G-iU>&AD z-ImU9b8}Hxee`)L_-+8xC{%4H#_73qTg(+pX{hw^e09n<3@t>k|MGu@5d4=W^}nD7 z|1OIP?`a z!nT@S+!n>#m%HGmKFl1p>su`rFw1u`_R4QBR?jO$nTXWdS5ip>7X*Lb9M~$jIrorr zsO*Q?TyLT`3UUX~)#wdk!$=ptW82{0zyBL#=xi74@p z^1HJ~*BKRpRc+DjALnlit!^7$RbmwZ8)JetPZJoZrAhNJ&mf_pK+cF5}+&oIh7ctK~RbDb(81T_;8wZ|%D%0DPmUJL`9Wib|{0 zbFa!iTR(iYpQk^ypfGUD%lX-CUjXw+5Q|@1P30u!D8(Xfq#}};$a4C-*=Cds?=t_H z(SB|><6xy!*0H+sq4Ld4H>N>NaY*-B_MW2GbLoSh4m(*EjR_0;2i^Ucd3IixaxkSv ze9Ky<#4j{J7t~(6Pf{X;z`Tn;{B}zLBf(`oInz!kk=n)(!|Nmgm z4sL6~#sjZxrO7&DhG27X2oi?#uu2~qa&E$e68#LBtMyhX2`N#T*ub#hAb-WPCfoKL zja97raMR~%7LNLiO4|o)>|ycQ6}{ZjVI3!W!x&YXcP!(AbmHTngTK}7s%;_`4II&m zv3_vcgzlc~66Nv}lC>+2IrdV!V5==`@+A2lgyafd;QFy8J2*>C>%(`Q9^9F$B$K=W zpNMp>&k;C;&~gi8KOdfndCPJcv)r~~jHr$Ic4b9{jR8@G#(hwgmO+m8n^v>Mv;O!1 z5Qa&OHbG%TPh{+lwCN)Fc9#Y9>IY7qbuqPZHhby9Le{As_iab4MA{QRzl8UsEv{^u z6FyUA5kAgV5vBbS`#uFIilm#7DoY<#iFnS zWHp3vf?kI#(yC9@J?bZ?v2kX`TurgctF-cR*6D~G$b{J7PW@K@8{%1tbO)&c>EWBL z9F=J#Gi6hsw{1{$6&~Ye7!Kb%F=m2K-*cZdFQ+i5_SW~PqYoKztUNUIO~41=*SMKd zSJP1R(#yaPWl^EGm&sm$?3KXP1wQ5ZmF%E~i4zqyEO^vD2jJhlKID{`q7-d?pJZ0F zAXGFmFPXYtG1F<84ocqP4kSvduFv&MS96{k{}FLA3sU9hKA=lNdfw1+*3v!7D}|Zl z<1R1R-AN^0aK-l$GZaigaddP;Q+`pXSD@e9!b0?8g^ZGXY6Vpo>4}Y?@2m&R%t=yI zd6?;XgORpXAl@zgX90p!#Ms9$JR&Q28PmCW{k>$%YJ6y@N?_m1{%MM+aC|@_d*;KV ztt&YUjW!Lgf<`M`u5B6#2c0KUY<_iR;(D_m&Vz9`!m}tW`?~geIzKI%ZsqFk5qHe4 z1fh0(hR-}4H*}lR%YR0AKY=4n4Fjw5Y*uO=6gx$Zgd|wS6$RL^{ILf;0rXu?BaIuO zXnQ9YvEbAjpT^qq9nlq~?YHG7XdM%d@^RV_=$uTx$}a5&q8Jg)AQI48imH@5mfGD4 z{3X`ZEHuRCE7D(8WSpn=7c;N*f2-(QojZEZB>0$L!1|r4%ZgWxefhtD#{^0QZ_R%S z#G$sf+N%|Cy;`!jLhw21uJmri+fv$BoX%hRlhu_0SraotPxLb|F)s{sM9mI;`MMW2 zn*r@Q%ATE~GGXk>CW02%wGib!0q=wM|EQO&uBP^3SJ6buBL2#>t37U-GT~zKhsr?1qD~??ERB`96AKiQDv3)s5d~{Q;wz7RFf_0@*{-W6n3;_ zU4-Ftw);|j(j{OHIW2PJ=G6~n{Q>39^5s3Z9$vKEUG}z1zpgp_uXBLf%M${Dd^!JF zt!@z*f?|#4u#j1c4}EJN$}|0&H#~j}>!fyVUsMj=kv7$JoP)9ZVB%HjdKU3~OPq)N zt@)2|Z(x&4X94W{gDXHiM7;K_f#J)pg0UYJHnLH#3f<=Q>b^={xq#+qOM6lV2UhAR zDdSC532Kw!6OO)$u~L4&lpwjJ%|n1QL}z644&y-+?Gt59u#G;tGS$sgn0#X(#6CWJ zInAue!A)gUt zfy|P|NHhn>4J!o7YryiMUekHhDZ(cg4d^JWB8;5k(6>0VvYv8hFP77<^)y9owCA;o zA<4(x#4uIu)a8zsa9a>oHrN0H`DRT~=oNNbjA|<5=9ErQmLOZtX)JcXM&@nS+)Brz z{GfAlyCW}4(*8uO?;%gag@3q-4j6S(vN5PF3uj#=LiY_GOhK2o`i-b4^S6OMxp!LjZs`nI`s!a^2i@)tQ>f3(8$;Q6@*T!`Cs~A7tQKgmw={;1 z6GLq`V?kl+q0dv%wFt?F>0-`^MG=wDK`Nxy`x;kqzDF|c8B&RM_7`C7*>XG|5LsWu zyK*Do3HYGb-9$!c(Fo`;#+XGJDc*GQEs{U~*qF$WMgIAuk#4`m7O6LD+vkf_to$pA zW%}%SObi>N1$$p<&Lu}rN@hj&aZ0CmDhMYEx*xY;cZQ5~K3n}ke|0T5qvd&Rc{qLsdQ`thj3CTYkq6DVMlwsc8xQ^}=dENr2`s}Rvn$Ap zD*(!2qz~AzwKorCPyNgYEm=s!GEB9}|0qf0h@x%3M#v1R{#d#y>vX z>70R+ugo-ij*(}dJV*ax^AY?KKwylFa13NLa<{7Oy3>HxFD$~edcXtZ=Ex>a5RFJ% zGxVJ?ZSPmbdiLkx+`~CPoynzYDG6P(j}HKPJDKcbh=rj+FHEqkr__w7ZK?d^MOE_ac!9owlW1j5&EHZrd#FTwd9%~F%b}45Ny(j zqrwO$akky9bP!sZ(C5`Gb608a$2#vrlvYwKh)XT8Arp!XJo`aKN7z4h*>H+FEH`g zVCJZuIlwTmOqm2oBL;Z@udbd4by8Wr5#;vkF3*hUxfmakNx=Ijb_$XkUwhBZZ+W~M zbJ$%x)UXW_-pWR{08wY9Msn1K94RpW2T?Q-CN(doYH98!ICzV9C`-y!=UnxZlVt7Z zYV?@A`sy-|Z{7Z+5raa=;@+0k*%+`@if5Q8SJnf{#s=ozH(i*9$pvclOukveW`x^2&=-O9> z{BPNm|Le@ae=COJ|MWP}E#%GaUltS3!ML<>ZvQRNZ_`MFk{8%T)3C)$?8;Uk&VqvB zZ}(~yt79XdaA&8?5)nwT_7e17%iJ@QvdG4YjgrSkv53VG=1@+kM&x(tfOJAe(A6s! z%XO~Yh3x20wrr}PzS!_2|Jdl5}@; zXqJvQ%7I7SvDwSPYNV)u9m=8^8`|WV8pZ}!XOiC5O{4X5UUE+{h_P;mxa1)61b#Q$ zK%G58Gby5D?)(U<4jibgc>Gq`lQ>nhFEm%g`6BBxB%5(2-YT%F%0vK)sfW9bcpGhH zxpLBi&|xH3AYr~T>gHf0GMLg;o^JIj4&xjjgj2lVzeD%P-GsF5=KD+P>w$hm_+20( zCfEehagPQkrDkVWGs{8sK=@valTl=m{JVK4SkzjA$&yy5OsC_$)DFw%a!ZcR%4e-G zl0^q~M9GEWGLN#L->^-)P#UH$Zvu@StybXpO9$!Z3Dq6H|lG zu6*p)g3+pEm5ymi23cxF!TQKiS^KM5Hci zZRKFE(4zVFAfGo~=-r%k%}$ZNPTw9ET-##graEDqz6UzZ)d%6IXzj(~A5@rDDrj>* zAlVEOl$GKZDP3x-ot-xWaJ7c+#Tf1NeTZ+VPn^4gCEn_xqnShNf6UW%dJ6DwaQoTW zABkHGwiE$>tH?qTq-npnF&Yg^Q!FBTugE8Oy!>$&D}Q6%j(Rh@BME=oxk0vtzsji& z%Nrj+eu>a&11iJa%pKy`Uc6FHmf(iT@B^Slq#l}GOK1PACdUT)38GfRfYWd8Y4~XM zo@YDaH-f=H$n#SOT2SwM-iZN%cvyr>M8kCRT^jiTnNnjYlF(YdVL7&tddfT5X)Z|p zF?xB_O`+whl%^TS<3^g0-`&H!fga>l_!!u1AGtW=oJ|G|5I%v&y92Q=@mE=261IPy z4@aak)bv{_db^Id{-OFr<@BH8dvnCMY-YZ0+dK_5A%%FzsRZNZ5UD1*uo>{Xh^j

RU$_%SPBuGT)KX9Kw-N%wz;|Ui5E9>|&+-Ad-QeI4-)f`sR!A;3Y17 zKmex+QLx>w{d81&FTK^;9ahvUS?7&Sx;~PIb35}MfrUGs#j8@8^M~liGGKs7csUHZv^EE;!=T>v z7+wv^dZXyk62*?@Ox%u0Luu%i02pL1829Vu332V_9K(BZ?Mb6Z=@-0V$-O@MatXJx zfkO9K`pC<}v9vH9)MzoV<`92kF~SAC4o!ro036Egl|3i0rlV|>#Ah6YEUycf?s+Oi zVP8sVeVV6sOg2o&i&2&23apiAI=R_B88oyPU1hrO^$d!N&kp6^63L00K}74oytWz@e&k<44}#wgGalnWf9E_X(Myp|e9 zbq93}S_pDv*x;{bJt%ean+Vm9C_6#S(#j(nXIpiuV{wX=jbOPdq0E{+WhNza5z~CLjb2d)I`1p&2EixVt@bsinVtcQD7@L))u*h2&vrjA5 z5Ye7Has!Cn;dOXO&?D=b|H5D=1X{WaY-iK80bG5nzDbvhF&>|CW&JdW4CpBVZ#Y?Q zX#$eusJOnb-ZNI(KPjMABpo9DXiDrBZaaId_UGL~j#z3@8j{-*T6N<34|SuZVf*#7g}X` z7T(4sUD5%AE?hL>egL<`kCZc|W#n`vip$}`#4okw!(8~H; zc*%L!6-Z9)a(vkkB2kQlrmv)8swyiBIhhjZ&^R*8lUokm5B>%kcf91KX&w64j&T|T zE^xq|?8gh{4(xF~_y%-fk5ShJni{>W8Xm1UO5Wz?hk^GTqr;ll%PKN9`f}Q|hG8bq z05E%Vh_r|gdAb@q8`Up+dUT8;@}5{bBW|$@=SY#mpB`fSkCU+d2xH83$7iKn z9_NeaQXD7KY%;O-FlDiQq@LQ?^%8`SSpFMfzko5-;dBJWZqcLVj3Ey-i0o%FEi_p7 zBH+?s#Xge-Cxa6yrcm?xnv9fuXQz7QDF>Iy7)zOMHTIImzD>#d)(+PlEv@$PbJd5> zzsN4#6qj6C_|`(vmq1nsd}d>YvPNWOkOR1)g738<;-+ir3YCaTP@cCORMax&N${ni zqwu^?S1-PfEw3!1Yc2d^CCkUr6S8KmZEv2hpM1pxR=b9YRZXT=TtCsLAd{3re)yo+ zs@5B>9;3g&`Z(Kizf9Vt zIQwGMNuH;%ZapA0P6gmr_B-BYUqA0%{(>g?48Wz3z~PG=4dn`14L>=^Wu;7n-;u-4<^JwZhcy zuhrv)l}34z;*1ROfZ3N(YVd7&z(vNIB98&O*aY(p@T4rk+a~McESA(z(&V)AHU*IJ{|z=Jn*L9I$>hrVaT9(K*fb# zD$a2Jc8$5Mjo^NKGlW4!F;@hGWzmtV`;Xu~3f*R0jSfkI(@LQQjrAYa9TABm+8#^$ zvsxIEG+?db?fLlHd^k)3kv`vth}Rk+|%FYRZ2{sH!bg&DyR!6 zBND(X%A`q9HmAq_GnjF@SR)*TqABto2P?M@=+LV$2cnMWp3MWd*(I0mxe>o6T(h*h z%%jgcn-EQrFC?TC%*xYluVDxCt?xEM$`yChTM+CoRcUJ?n@CXdn5| zLyq|dvu4tT)9%uqe3TY^3X+_G0hx~n;2?`UT%1XoIw$)}jIwl-xT}=+8YqGhXL~8} zDr9yzN~uz4DSqFFG=K{Ey!x+v6~j74tyd!z#7=buCB{$e45zq6qKS(Sa1tk=FwExw&3v{J8xIjXVY&wAwC1s)6<>Y8V z6?Xu&3v2!$mCaiHbIY6gyvD9hEVqaZaF8qHBwZnK&&8!UjU@W@yxbTH=)Z#PKu)~Q ztK@9m2B>M;IpRHwXj=djEnmyeMjGn0K-%dnRaM2LZu<6ijVvF?Ku+=-zN1(%>W^CR zC&_pGa;9Re1fxCvCwZk-&n3QJGrotMa~xwVc;qVYHR|@z!B}k(a1M9MS_#fj#2P?f zcaxGmJAkg#7~WQj^ulS;MCo;zhssM@#XO=Vyv)&|tV(&fMaKyL83*+g^{PNW(+7s+ z598GQvfKvT-vZEgRwwViX;Fw;q4LW=0HNPTzAm;AQm?Ln7kSI>jB#Ojpe`Z#Z1M%` zg`yZb0)L-@kZ6aoYzu<+A+O;?j9Ae+?s)7fZuxs*Yq5c4A7r%ZZPndKd1jmgr;O}( z?TC!2m46+pbij0{nuA>RDG>bVJT?9sBo#k%^}}UzV;64=iH;4wNa%m$dRDd2%vk3s zZ6vngjB7^@sA=ZPkrPn+4(g=h1o!nx21r-uHrzs~S}-S@iP;%Ng{v6W_&lAAI5i7q znv#sAXXs=&KR|H67XXpFrp%&bB~Xf(R8w z^keI=wcSfKv%LIi3!9Vp2l}e9T#ofUmD6-5mq3-58=Ck5MQ$tGQeu3|>;n~@JRf(T zMmboi0;A3LP74>p{Ki?1@N&RtKQ2I#Pla%ACP>^vZ=Y>WJBKto;N(E8A2Mou1c@%% zvxr&nw!ljrT3j3_wfxfB5FfkdFJ4U&nbsNtolB0+T1L+mM7~hjyOB>I;0;|V z?eIwm)&bn{Kg!wVaipO(TAm2q@`6-8$7aI(e@m~}LP$r5>ASwBk)d6J_@8%`6(*(l zFKdmVs|zc$aCesc>vYe9aj?q3mMoiz&DrX`ao}rfUpmP|i}nwuxJO;c1;m-9RPR$r zH(R0!?xur7p3~Fg8j~DUmUC>r-r6yqE-K3l0uUzBbHw?r^RXOH6*?{x|0C44;j?(? z94CqXxHM!FHNcw_Nn{`>{D$ceR}eqa>PQlDq{$);o)IgxC`N4u8WcWt9AA zF*4LUDIR>;5e;8Cr;kip7n6RU>^U<-$g-#z=oe-aOxsf9-5FVS`L0}F^zuB#OU;Y3hw7!a(68+ApjM_f1J=CihJ@(zG-b3#M~o zXQ=3nXKN`(RJNP~hj%}`P@2{FN5&Kt=x|u+OTDPB!`dyCF`#n@fY0b-^^DqRPbzdi zz-6s|l&uR<&#V>%yGo3V7l04G@m_n9Eqg5;STB&>kmntbm}WWI6FWdMJhiW@dz?m1 zByJm)Z;B54^-%}BQjEGo&%#Y)Y?{LGHj;Uszrf49G9F2i>~K_~w*)m!Ug7sQ)I=XTnW^5JFZBa6&)hso!RUeyzz_6b3S&?x>hh!qksUpCdax zwGG5BbZhTl1`#9{=V|&k$E}I&@mGfXrmjMUmc%I23UjOV_6`~O0i?bkQA-#_eWhK`1MHfjg}1U?SZbv z$tkVB>|zzonP%{+ZC?o!D`?r6GwzHC_-^~IQn}FfgwL3^eIxftXvx@E+8(>%i>To2 zj?E63!W3oq<;G$&+fA!jJch&FzcdFpCC@Om*rC2Aj?=dVR)C~}R`%jROg@wWs`wub zxDBE7>Uvs^R`60uM|4A=3jm`&%@@S(?mUv{%$YW+oO@@ecp)9?29d!Q(g}=gCKo)S z^z9=N970EVI}E&fq(u%`fn#W!zOZH7P2aqMob?dRHD0=lm%_V>GDaxXrn=qB;M1g$nzq4K+UNrnmTCsf!h<9h4V9jSs^OSFy{9{IL>k zXodaUKc?=e|K|c~5W+=N0aJ)S4A3DgO-DG4NYA3#l)3^f>fzEWU_Q^B8{1;E2y3K@ zBJP<5Dw)BquMl59pLk(iEwlBq$Z><^U&n-`76&lnG%J1 z(b&5R{4(@DF{4-}$eLZ5Z+L>KCVe2yM&Lwgu2x$katjQOo-*T=QAt$@QgQGRTLbCY zdII~RV9RqYltGNc4JW6-Aplp74zCaNhljL(V^NeSwNJloKcsO3-cc4Swx6`JlznsVKFvh zuT&l;xmQL;+SIbgm6a*M3hH)OrrfHl%beM+TZ-DJcr9OXNp<~aQ>iGM)ap0lI5`<& z>dSgo2!vMNT!OwdMod_!zBzm}=;(Avt~2(rFzW4rM2cdPUJ(YsK&vYQ!m(jFA@?dA zb2_Yfy{-o`2uwvZpZuKT<{_!8=X77_0#NJ>pDTzRd=D&KYA&*a>>J=CX~i#3oVF~S zPLW}2EdhHFFnXy-^;_CQ17To)>>ypDEGz49B8Y|fABE1)gscW)ho(UAwnz>CTcT|3 z&pD4al1_WPB{Mv6UrxihK;t2E3gD6@<(7?PUV_EVAI%pA)PF`E@2v3!Txb(DwDj&f zoNx{e?wZLXdbcorjeFt3g6vC)9ehncG49cD-Kb^P?g(Kz?B;AGIwTpaPTut42jZ_i zk~mRx7OolmvVKAQ{KH_2%J!;Y^NvW1FzckAHk#J{GQ}**M|ARH1h%Y*CR*Q63 z1MVoxPAjn2*`qeF2%c4ST$cLB0M79&uP|P43I@IC;UCv?go!YXnuW@ukRh*T{t-Wy zg{*u!$>?nAx-wW5fisaJFcQL8I^Ju?2_kR@p1EAH_s5_V55X71`vtU`uZF+l*5QCC zHt51U3$KCM~dB&X==`EG-Thzd}cHy9~R9?X-%8rm?BKy7?LoMwj0<5umzL;ws-eex^S$E=ag&%ddjSm99?PExwx{T^e2B~?n2$CWGW2k_A3E@Gz&OumWsA%6k;=pEuyLYNaO!Lugu?hn< z&xG)jg_=CRp!kxvJHgI+bH6%rM`zjHQ&HR-T8+!9t%RZ#OKcsT6$2x``W!3Tp@8X(*vY^3m{E0b=@tj4&XEXa-ik#K4J3Jq0&Md)4>u(~2?_8xU&Im#xeJxbHLvGHWbO zQk!{{teazM9F4Fonp&rC6wcN5=axbU9I7SPoy%`YgZpHQ2AzL{HqPk^X*O|@XoG5N zZbNyxKJYqMpYzhmdnki*m@k7UBy7~0F+n5o*2&rUBYu(AC=Z47yrh3&o+Ck7TV|Xl zHXsmno^Ble^ZGlIF`JmhRdPh#!30OL%nZ|eONfFu+I^VdMyvW-uOYU!Z+w4m_!!n1 zE+;rh;g>&yh7U|25|x`ymZZ3&qL`WGqV}d00pj$k!kO5qBJA%MC&u+y?*nJgE2^(3 zC5Cvih&w6+s~rO?)p8H1O6G7&0FXxnrQty-iu{S0P|YcTRyY-`!^{nhZGGP2U8VJ& zM_c<=#5?qiB>e+ZU#HW*Z{sK-Tu8*WCpB$+ExcF4Bul^5#8oKs0kO@o8Y6acTYo^{ zoz=2$Y+dTLa(j;6ugv{b625pOyDCr)V`WvfIpwtolqg1g?nlBg*-~?RxjJ zUa0}}J(<%XUf}T`ihoOq%eDnySfUqkmr)Y7Mn%zRjuuDfGJ#|f02A-@SWSp(s&<0O z^pyXVtkLUKbmJgvgDSbj6oc%0`h+rl(^u@DQGG-=-HtwN`wY zdm#?hO47BFCdoT}bR&65nv!PlwC!0_I^|DMyXuw!N8$n(oyw~+M~v!{xt)7>WQx<# zY=BAE)29#EK4MF4{9N4;BY_SlpVEPo2rIN<-fLR)xbovN8~k-3(_;;uIP9BYQLMk9 zm#S>G7G-fGfMgGin4<&X<(tDhieJ%?x5l6+(70S(*gH>ilgCD;e&{J}FHGFKsLvJ# z=d`0{70%u^I(_wlSR^HCs=S_%kyO$=;;1Sh0K+@7!e#; z+E+UZidcHl20L4d+deXGv{{! z)DK|vaxmf0Ke}9edcq_0l=_LE*$VQ0NOg7E!Cw4gO$L*11_OfX@_HEyu2yuxRfV53 z5Kg$J(F<)(VnlD>sIg`aT$()q4jPV()@n%b#Ad^Jr8f!HM&*vF@j2dizt#xt9l}}i zNYGo1-o=bFs5*C2B-|yCqnXoJB;_tqhL|qB>^|R0*v*T>760FgZ;oYgz5n|2$7I=j zYMJY!?=Sq(MY7dSLL4TODy6DIi5Mm=>iQDZ&*uANf4?qs)h^hj0D=U zJs`0JYm6TO?ujH}VScZB2wj_M#yAD&>`tt>zQ7cMPU1)6(@E>5hcfX5GI>3m(9l3< z+d@h5r2zb+#It^EIl9XCz-lfJIBqU!;>C3KZl}hi)P*FWhYi&~hJbA zV`>X}UD^OR1Z6Xm70qyW7IHd-Gh+Tz56)Ciee$TOJwm|g=1zNF@)JsplJ}v>8F?kP zZhuog)oQ$PG3+XtXu-?u6}8u!&`dX1G^$JI7-UEbS^kQ(1jGjH_;vK5DOX(~|DWHP z^!BY;efhdAB{gMs)Mu>}`b7m4^m+bJixay)%I%){1o*xw)4mJ!VPL=SO~Z{y=eYz; z*m6l2J$_-ZN75eX#Epx{{f4C%IxN6?F|YMqgHH^_B8o=WMCq&@CR|A^@5&Baosf zhh|U7qj#e;%RSZ`y|I=HkD{)TV&)Tzd%ABHRx|j1_sn;5w+K^fhX7eO* zzLSf{cw-3Je`^T$zfDunpjEn7EGNiFX^o?=n7duU zC!Czn|NMC5W7SebyJZ!zPb4+;j(dEFlrFOPvw zCx(5j!q_l!i3WnFDWWMl+CmzbS2w_3X387{IXfyHt>0^3tvuy2n*HWx_0?+bg)=fGij6 znc4vSHreH@vf0;fa3R35S9Pp%I)pS}-?raUltD2X*Cq`kXH?hi7PFpvI$}mu;!vxm zp!4VE7STe6>0b$!FeE+xsLe1GJpY0=>oIH&uRLFQlqm~tFA{fShSAR-ERL4nX?HGv z$GwtkH0eE*!L@4D!&T3mJ`tEGTa94Ds#~ctpb39nf@k(Kj`E4yh0T1r>skEP6Fyga zhp6+6gP?vv-)FQ4)I&f_$7~klF^25H)7qTI7K8fS;9yFO7y>Ol`Me>E53`Q}4 zI14ZKHc~OynYj-N^vwCeSqZohB&u0C+IyeBZ=%pK2kI(e*jgH!C(Ou6`i_|8u~gIr zzg{d&^&>=WI#w9F?y|0H#j2gGgN?rBYx@sJhy4$laJ#z6U&~WQ?C1e4JgksP+u)fd zC^GNuGvGG~G0jLE0E5DqiYD>EoHHBp0}5SlN>!PXJoxnmJ2jk&{}E%xU%`KQ1Mm)V z#F;uVL+}NeB2|OyM1`?GWQ!B=+S8RRU zIG1Z}CD=bjXj$FvA0I;Ozj7x^m`==*(F%y|tI#T6C;Q44ldMEGc1{&D`=2=Uq<2I?~f&}MzbWeH})%f5IqsUu1T|uATmNLQoX10V*+4E?4 z5cbjU3=Qr(|M*P=i#S%v!BjaA)a)!=Dlt}HUQ;IMV9yVecmSJn%f~Pl5(hP!q9Nm> zerLBpQ7Y?6BVvv%8{Y|Wt7Fe5hsnK$1`f-2ylPVn#!5=)R64ts)(MsxK-}bTh{*C! zj~|^9QN}^+7%XSNdg0+~5ur9enLr;;vzAL)?<|8WyzEK-ULlM^|zp|GOuOciZ z&SjMfx9bY9-E_{YjQ2UaY|0AjBj+;tH2*VPC#O985U>;2RB=a3HV9*3Yr-WsmN(K2 z#%sd#Rl1vnYCRzOvEQlFPQN`wSDTs4p68a%;OUQ@#z}4xqoYTHF$FtbL~n()6x5Fz zRpYg1(Qg2bRsSH$TPS9h)W7a>1QFQOqmYC=4Y=Love5ywK&=Dj#yKJx`7R!mq6CBe zBk9B<7h&|S_WIlY0WWdd4ntoLGnmxZsG#D3c;&*9tWB z(IkXEz1<&&B|}tiv^)gOy4pY>$PjjWVJF(}>Nt-AZu<07Up+En4qlFaXB(93N^qrB)4WCvH6Cv7bhU04WB%LMU?~~KaV(sYyE=K zH+tId>g;YZ7?r-b2?&nuU*_|yQ#^k?DL>$In>8s!BpxgiPPn)AhPDfeBNrO5X;SWE zv$=P1-VxChgx3sKd<2jw6*3N<5*=eL^AqhXxkzbN{;;+^yr{*y@#N}>@`;3R^(J*u z_-r!(I!lKYMO7W3Q2*ydrZQ5segG|s!kzGuEBwgiq*Gq$r1zs z-qH4N#J`5lqXo1pMGl~{)!tMQL7AaK@X(YFy$eYeDTd;|5tSP9ZE?(G^O5WpwV*vq zT8{A!R}8?a4Q_(X_2tSLc3>;77miY`*$}+g8BpV^$u)|}M!QFPlzB)Z`#YWKac+LW ze+VoLClPHL*oi1)5+#+C@JmEd{b$Y^jLMK7^%By3-2Tm_QA#qzC4jkJOY<^D>h(>E z3!?00JmEe=Ykm<>PGJ(Iv)vC5PDWr1_?O|tnHV>Wutl^tA*(U*U41DDaS!oecXCqJ z0&Hgrla!S)JhszJzo1~uD&YNgoV6t}+qYww`>k@G)2!(3fFAA@^#(sxOEF(byuo`o zcrff*LP@|I^8utb&;#|>Z(Z!(eGC2L5tYJrNs(gRF(Szp^qDSd-{q-^)lOzOIqT4vRA-u>_QDHdf%( zdDAE~K38K|>{Cfz^61CWb>wKbncV*x%89-i1I;2^M1tK!WKSTe_oi!8o4v(+cR<;Jh4*E=H+2}uyh(dly zM}y3~2%zn(zv4$~X3*5|v;?h;@m#~_-LGNMxj^SEPrSx%MyF3xS-h-g%@Pc`h!x(N zX*KS4Xnu$$X`T*vX@W#8R6b|*c}5DlA06p)C_1dxOi%?CnZt5``bJm{fp) z!P<_CiBBsfelVf77Eh$8*+IaR06MPSkxy(Rg||oB`Sr(t(9VGvsoYmw_|)qdw4 z0su8Y%D;XA97)Alc^o)lZ9`P@s}Ll3UoCrqh*Z?8Z$@Wb&xpKHWb4DOm}ZQM`61X1 zACV(vTMAueJBo+D;E&E6|6#cr* zx|nZ_IygO|h&U;=yWoQcr6;C4e!kM{!kXRh7IB99LmK^_6P)}r>q`bzA~Ip(mSx1l zyYvSkRS}bviBE*O(5}JsY>`!)2%&63t-+8x3PKTiv%vO)Pe!k<^8h*)(B;5Tc2&^# z6=sEB4iC*xl(B$1^N}Z!$BJ#$kNcTdMX)0GvWJd$SJuYj4Jci}ktbuG)=tU`+Z2Gyn9=v^{+=x-*OQUjDo z3Lme&y(mSzb%c0Fn*$U6*$|G@Px?M}PtY*9^cE}5!Lyy!r6-ZSM>w_R67#pA0Q5CU z7f1On$Y_FjD@bTwsui%jww`k|nDW3V61hQTb3W3tOM-AuZ}d;9;$1+~uApdL+99xC z7Wi+pKIOegvXHvwGkEXhq^rK6AZ`|v@&+-B^%?>m3L3I(SQp_#N}MLAMbsu{)@M}?=QA{1C(4hhSO!G~aIf7z2 zI;HF}&G{o5nejGgJfKetw)b*b+dIpd|L~J4+|l6%eenj-+flhOa_iHbC}GF?UCA;V)mVr8vvKqJ}P z3SUZLdrNLRll7IFpw#9R*6s}vZWnbxOR$bcv9h7wLb6$bZIB@9HpHJ`QHPl@S$_M< zUO2(iH%LesrUd>P0IP*Dxs+4+Q}0poD}CSH#s{Muc!Re$M}kv${0E79u^&26-zg84 zZ-4P-xV*2cb9r9?`WtRIR6LzVZ0!o+XGjBpZd3c`$%V31x2NE&(?+~F*p`SH!T&dP z^NX6XC0cGPBcs}^#tF0LrYY{TVv)z9`+$o1@PL0<=o7<*qw0eE+i`ItcPZaUviK)7 zmI#*=ph?z3wDez8r;}_BNeJQp(*yK(QIBmWs)=Ec4oeDOlR`sUOby@tA9#MYw|L?&9UcRD};QLX(a;FKoEHS}?vekwabPO-Y%=max zTC|Mk9jMEw&K_s|0sF84*92>f`uxs0YBG+h4A*Hgg4%TdIEo9bT&pXH)Ac*3qTgFq zdaHV)L+WYQf=s!Tdp4SZ7=8Mi&Tf`%5q3lriZr2?NyaAcW%&kaB{*~WZabJS*HJwq z?RPUY;ttAwF!Y$ED6k2TC4timN}?_K3~vyHse16Rg0!VDJ$~b0)bqXjX@viGyDQ*% zXSA7;jdtph+8m1C!njNh#^bLL9OyLwcR>rku7#4_)+;VP-ZJ$837#&)EDqYb5R3f* zH5`QDlrhA2Dz7ODGG&J!rpg?7X`WZY2A^z>&8I2Zwik8V$A!s-uQsODp+T32;kS3e zZW&1-24H-ccZpkcl8kmVhzOfK`JJ#l<{KlQl3_dwAnt}eGx0=C;i!a}ZYX%uvm2yh~z3$yWQCU&(VzZ`-Akr+qo z;i;)7L1Zqn9Ll4B5%9KNtafLK9+(xyg_4bnlmTiWvl3Yde+LqC8Ui&|sp=6B0a?Dn zRQ+aqh*dwuwdsWCt;peis`oyUkR-Fd!@Pb#Z@8g;*D!2w5ZeKf%19q#rYO|6w3$bW z_Ly{b0AuujlQxy1dI-^gjpI3HBnY;F0cK=At(t+D+{0XPcyl*p8W7kB+wq8h+|T`b zg|?CF^f87&Kx3`pPEvAVg`To=e1Zh!vB4hD>$zLIGd)ttZ9`0+mA_uEt!(OEhNknj zwA?cVeDoU1iCKRFQVW7a5gT9jy`2dZq98!xUH229dc;9zU{Gq*;5IL_T@rndGU*`K zXDeIJSiWibS8hNmB-3Ay+bx8abf=HE@U|jeJ%Og;dZLLOCt~^asKwmX%JW;8gcMh# zlmiqfQF9_@Pab=O4{-|xFhP4`iG_+WT|6eXZsW~CW^p__8<~H7h|avX=Q-PpsLC2|u z!>#!DeO5XR3X7UgfTfGunr+&gOYTWRw>sI)ZXTy{z?6Ea7)lzBCR@G>NZdDH(>X5D18+G{vDME@|8G(K7$n&A1cOUc&(Qj&1GR_NJR-F;?E?TZ)X!AN?|VP z@s~3k^z(2V+>A`jKv_<9zXivsZ{mbic2G7S&c&|R>IIVEDN#9G*j=~|@`~Ud* z&U-+y)LV-X0yM1m|0hkyn+>cwk`I$(jSPBPx5PKiM~YYzf&ILH^DhFaxkr5Bams}EirzSWM!@7vA0HH~(Y7g+s* z%gB>Vq?u3{{<0_snIrn5H|L7GR~W}*fhS@Hu+kP_Y4naM|ER6cWjrz_)f? zluqo$q3!N|(-^jkdkN&$gJBx-qn`(rqgGoZ9ye}sq4ii`8N;1aoyiYlUHGyJW%1xwj~@5Pj{S>(%V*Gf%0LB5Tho{v6Pvf z-F5`&DpdUfVR>Mp#!&sQI>ld7vhu(E>6nsDykUvc=Ng$O+^N!8)9S$tC4b`eL%sp*DC{+-;1Y3YYef2~wngEZQGAq~1GzMzA zId`#sx}Ut!1pD{glxxxbi4Gv?e(hUdL;H85g5Wz)?IdyPuc`G4=%B29C$&`cFagw&Vi;mQSV@^DN)^wkL*#3JKP-19ORmZe zkXoWYM5dbU1@1ZtCbQ+NE|F@NUlm{@h$lWuXSLgo7+yYJFbwj>FEQz2gif`t;qYIN zvvA}S3TArz6B?oFkAfRSqfV#B46#O|I$f&)M^oB6@gh<{!K}+>>3Pzsf#t>W(QZG_ zK`iFMJUJ=g_BGJgJ0z!IjPv-86|O*ahLZ~JRVGb_t_}~V`aX+-`*TOBT4-L=fGec7r z7Urq`Y3#PGLtN*o0jdsBr@+BqG9J6!D0NXgAUn4))5~W?(G~tC(i=}LZhSH;k%;7U zsn=L=tIAJoa;umIKcJEbJ(15SSHgsK7`h~37gJR$Ju?O72lTL_kXA3{>UzS|? z^3-&s`);toyR+^&B~=>n$^3P{S#jc@zn?5UT!>KsuU><&R;^2t`lO+0hC(02M4}~u z5^%AB<%5c}*Ak4J7FYHkC~B0HfuLFtgdpjAfPG>PvAZBe3a{A6I~U4*|3Wgk9->d&edF#Z944d{n}igMOm-P-pD z=*1}Nu6x2tBHP!Bu|=y*fNL-(s0~1xUG{J7wYO%JdCadm%<}b>?PyPv}fYVFDgMvGR zK~kAn004RS!XGm>d{M#R+PBeh{{V-}w&1;`z+Hvz?}RK2Dk?+)9*R!zB^AZC&i2_J z%PPd(J+1`UT)k5GZ6Jst@qP<>*kU;!#XUtaiW5-IVhQ`e9Jz|N`&3db+yI$KP-e$2 zw!(Id5lE*n4{^&^u4?WHUu*>3yWHjq^#c(P-y#=FFMb6xC>Pz4`K(gDtrZ9zJ?YDe zlA~Cwb^GT;n@hMLM1%}t|KA;(mEQzfn@l-Z)>6>4nqgpPJH>T>=~oYPg4wK6NvEA+ z0)-_MI29f1nGnbHK8_(gCCWMBF8ZA=QGecDRvwk<3P!d5AqAWb zry`7V#_b{4fPZRTOhaKrl!+btom%Q>Mqok2=_Ae%Y)RL!4MwkyB+Pscn-B>J!ty}E zClVizas-c>)HFVgJx~4cc{jPx7ci_C-il{h?Ij(45m{%Yo#!XVhj6cY$48*0bt+3! zWHu0-hFmucT2-BUMUcC?fI8H0wW}v*!Oc*a@gnr);8)<)3`FZ}M4(f6(Z7LXl+}2# z3t~`IkjJy4W~nmH>(u}U-#L)ar)UM6jZqbo#W>FWs@f`Oj#T~$jy~9-^9sw3RHgbp za{Vie-91{6$=H>psaRkR1-GHnT%A(@5d5NRqxO}+N6>$5mkKn>YiD?OX_W{}P?l>W zq#c&dHiiufv()@Cs0+WoeWawjXEj>~s>IKz{ArZPrx==R8rDR<*45ti!=wwP7)Yc| zvDy0lt(!4anM1M;yA%Rnko%36ti{$)oIB-~BiVJ3{VUYGic zz}q^11WZKov}UfxzNvwdk+Yy|^GxgGwkzU!^_nuAx#P&Izrf}=1ZCnh25QE5aTD6V+Jjq>gTf*&}Q+1p!jF;0_rS)QUJSX~Y z<91vJ@a?bcsu38~RD=PMQNr2n=^ELjIsMmfNR))+OjPe!n{>_$4dsHcwwe$b4l%Zp z_5Pny7*@!fko_-aMA|gGT-Ca_aVc6JF2l}(ZGC!M4S!_gfZwEb!ZbdBrrZ96RV{g< zglT|VY(vL(1yLbsdHaWpXV`vMtKR`h2WhoAqz^knjG)Obte&oyR2gmqL$YPZ*6jFa z@xZ4oHckcJNmi)7@Y0(#4A1>5fg*G>`S>F!BF%9?>n_7t@L-e^qhd)B{Rc$nj6lIG zf`-4|nZ~Zfn(}rGsk$X0bFl{`w%D9Vx?Ga4a1M4Q!O4n>CjHKiY_Dlhj38#hT6LN( z41@8V(wkau;k7?aSET7^o5ndrMrdj~yRbfsv*0(&(LA@-b0p2Nx`8OYMrC&0=qqwl zW`E)LoJy3g%!a8_Rz0{>a{NMhX@iM}Dc!v&L&-y}*p3&mi`kRWie&Zllp=)d?jFaE zevfGC5KiOkha{W>O}S!aeI#z48K)|HE{KC>wmsso6(BjL4{FqI{@X@wYH{q5bKwR4 z4@u})js=y~ebud-sb&jIzbayEDOnKDFv{DHE+mJqsyirXN74Ci2-$IC%|>=DDo>f` zW0S%CgCw&n)IK&dQuwLWo^wPgCEQmJqhN^Z#29+DEB`84n>N^|%*@VOY;FgulTdCu zO}VhkOAt^hQ2Q^&i=4iDZ>L;fYq#oR+@MsttKRwuHU6#DGZn-Gkn>s;TQM@_u+@sY z^g`M*hfaMaEsu3>auJIk=W{8{kd%cw;8mBN+jxr$Ho*{x4uiv@|0P31EC;?uZa|=s zZ?H`39+gH>ew1XY+KjR@Qs1(96VJeFyw612H$`*U(pv4HrVuj@u@}h+BGsiowu#oX z+q>2Pk*+S=&TC0pOoa<4GA-sXU;|sCfv^^8t1g%Xg$#w_r?USszyLJv+O1z`g3UaE zQwLUB1({0`8d(ij+xFf>ZmWq zZkub>WB|^&E1=go{@M!6RS51=?Cz?DRF;BObVVYlRQaS5gwjaO9em8Nm{ zHcIO;d7EO*NjEqP@AY{mKCn8LP4`M92yw$9%+U8tru$;j8^awNVqJUjY2u~uEhkq< zQ|g)g07?Qr7WixCH~YB%ihVYNBzZIpC<9%2h5d+40;Q!>Y-j7_l4# zQ%RkeH))Uy9lI~EQS)m_)m5V&*F*B(-WlJVdpLy9GIvKE&+>evo32R|or?2=MvLrp?H)xTh6jNUJ*xsEgu`8{j8c9pd z?7L@GvQy(_L5O<#`nZHEQ)<|`x@rgTgZ~IHoZ;<^ZT0V1g0k~iHTa3B-(vPGQ8xD2 z*T!B21SmsMx}3c0n|^4?=nt>g z9-%4ml5b#EAN+pE8AHcwY3g=p-m>qd-=LF%wmgcpKz>0lm^bqCj2lOqlB6M)g0&V+ zsw;YtQ?aIQ^3R-^wrY+hC!CRWp149J%m1Sev*b}herw!Ao8Xw;9yGU?rGsq0alzv? zL5vnNP!kBJGVsx58@@gu&X=g!+3CQ*z2`+l{CArb@<#t=62R93d4_fX0Mi@9`*Xn^ z21o9H+AgxmrDHz*Tv-Jq=^s-+ggmN{lm_rFCW8kkEzIVp^Rrev1Iq$Tg;85}JOj+A? z*7i&}0G->x(ze*qk{t;Lw3*pY&6(dNwt>s1ldm9W0){_J|2f5khmJf&;w4;nPsvKX z27{P|>hI$wf@tOjOD@+gTv7`QGO;w~r8v5#O>;P_o_B$}z3avc=k)?9Nnt~mba4GG zl7`KHTOPt7kBgxQ->@48B|(Wyo2SdVfqO_e-?OWN=fAA{Z0k33cL|D@7B;8UGQGux zI_l)(;v3~lSF6fJ^*hTez#!@1N^`jPt0;opA$qIdHg&S-19tAAWiuzM2#Uccb;0IF zf@+l+sChi^;=6oE*Sxm7JD{;Tlj%fgwWLO=c4JW1VZNS@f>)8FDY^3V`^WAThxe1J zl2FhzaN{~2vAvt&Te;CITfkg6iK7*A_pr$V|r}@K9FS;(Kn;(039vzo+!;{$d zWkdAp`kU*(pf@7bi+WUnpiAD~R?*0??Pvt+d>-cD*y}CD4hv#T6252nFY))JHWam8 z^VS)2c>ZlgM#jG1XgAZo`3^?J5ufu|X76N-ms@{%HnF5Ya+0M3{6~^EaTqZ3;(@C9 zpMK{CJKSY8Z@23hR%pkKAm3q$+M(i&1tx=kp8yf_WT#FO19Neiw%gf0ZzrtB^12Ce z2+-?AG{SN)`yO-NBkEuxWYBTV-N5=u{sR`phrQCeDk{x@@N{pNf43Gj#drdhXaT6P zR@zy35E?o=vW`fjV4wd$M*7%W&w#Na79|}h)r?FI1{h2hrbox%`xCtzQSPQ8@2^JY z^fA}NT-`jQruOovRlv?4M7+6Uh3-VFa-3cGI$t0kO&%{jnHm>MntSa`Hg56s{)x1&Wq<-!*d$OUs*|yE1EDPH zr-ISKd|xW@aFBtE1Cn`l0BQppuo#^O{+w(C0d4MIXdih?)bQQ@@{M&NVHUU%Hdw&j z(AfmPw#n_-LgzVi`uR1f1tXuSsbCJf0<|Dy@2yIeWIc(0VGVXbTCsAuFdAwK}%;-WurQM(ct z3oa=R-NvkEZFKeJn!9KNX_uIGgAvgO&9J9YwTas!ijBZ^{RV%Wg{eDIf`va_ zyJ=IiX*G-GU-BpL+2*qX{C-Z}T9^;05)4rPj0!W)Iz^yQ0=tP5z#yDs-!l(WTfoRm zZXW$DqHAO=l!w(1{@S&?U8|bBycvyY3EP!=_W^Kg^`y8 zo$UB?p|(wID7H{DVOA+=q`H~n*~?^VQk7Vo^Y4ZePa6E-Te^&tJe#ODbh~YgxfUFn z)<00ZYntjtN(u2x*r!|1%s_AjVh_(-9-&{$Jy$gtbvJ7;qU88I8ZWt@or^RK^}k~ka~=RPj>G}2dywOb?TKi-P#0BXyPt3#jbck%{T+u)Itb4Zoz!+{ z8*nY6t)|V|`${|y0S&dPFI&}h+EohiT_?Z($nvy^;%tPbRmm17qsxovF8F*6_!g=1 z0{%q=R<{b6H{ff|mG4H_cbm4w@@UFNPE4wlLXg`)j^8*^a=@|$3cy0nN;7QbEaorA zk~Zf|IV8CUsgXm?P7>bfome8_-;L}(7;Lv< ziWI^_j7~#Elsm4_%=|Vd$|(<78#))6N#Xp*2*-*jHx4okiaypp zR-Tccqpys}eJmp)yZ;u&(!^yFSDk5<0~Y1M=jkYUw^r!I9r;vplO7(Op4+KH~7g6XgW;o8Z)f{G}fX&oGQYC`$+(yAW9>b<4sbh=_tP zYQ=uxoEQ#UgXhr)U-2%y>#&^0sw$1L1aPt2D4UhwiS9O@83$yIJJzE!-tP*WNHY#- zeOb_IaUR!Ov*E+LANnlbzJcYqa~tx<|<= zG1vgu=dl`mD%%&4p6hoQYGV?7IQ8C%fLH-eBr9>*{M+vO2r1)^p2^4L-XJ)8?N<`v zg|{H~O@A!mWH8U)>cEOXm5kQp6sXxADc=@ME;M`sodo%#YtYc41Oc!)O&~Uv_(-Sm z60uBclt& z5cxBab8yGAI_XDUOT1f~tXYt4U`!{GV;vKUQw`)QIkT_k@9;6@>92Qy(+<1@$JA9> zc!x;eE5$%eK?}frT@==Tbjm>MZR4?_0apo)%PYSK-6s3R@(=aoiTL^ALP~+bx6{AI z<|(=EZ*r|dQ!;yjt-qVZvG~J&u#E68UM`0IX|#JstEz`{Rj&jD814q%+ZS~po$uvF z3Dui=s|TsH7<)n_?109jN!XDnC8l|_4Yy0Xi>8{(+h4@LhXztYb@3Piq)2`2!?hon z`Sp>wBrRmh?hWUU`1@86cXv2%2?ZjJ4U4L^z^C#E9043=`5w^#_ORi1D{l7*n+w&| zP5~BR2U>Z1gC2ZVn42e6G(!ncUW2({g+DJ!Oo zaFizI7`gam>IiG852c1^CcZ&JKQO>aXpMHMy^GO|?J1rX3V-R%PRHAJKM~-REy_}! zi3*fy+QqXQS>anW7uI+~`MKg=gh0BKi8X+a`Ie}AAkz>DIlvIYcl2`;Kv6?Z0O{xu{))=Z6Ml=; zLm9HSDtjr8IGoC87tR)LSTz`D=89QW=H)n!r@0s(8+%m?s5`RO02c?T+yUc%VR2`w zP0;FF!O9i3a8x!eIb~LBOFuT$;Z~5-Ffl0Np}5JQQlYuD8=Scxx=%&lzalM!v>VO9 zTdmTbd0gff8>k@3)%D$TqDqt3tDHEe^@_iqRy%be(%m6moqAac-LaelVMc1 z2O?FE#?)&ETvc4}%MY=%@{z{vq-n(UK#ZWwEf4HQjV`&sTsMiXkhBfN8OIA$`e`wj zIf18?JHLjG=1R2_^JvuUaeS{&ZFJg32(wKD#hkPR%hsPPEN$hPEC>7%$R;fjmXIfG zah!iB)btV!Nbz8nWQhIeRZKgL@=>0df<*P=gQ7T%Zp(@P&@{6R?<375!D^pD0! zyn(Ij06G8%t)jDt#^~Uem*g+wrs@Ta#Jcnvz*KQnH-LO8;_cK|sB)L82L)JbjENrm!0A~}CAUA@dXR@7aZH3`Q6j&I1K!)iN$!ywxZ3j7BNsCfy2 zSbrGe;uu8pVoa&BcEL0a6;ZV`$9wTl0CAk8vC;83!|SsF49>4Zu7`!XG*W2Ht|;o= zAK)}lt??6D7ks|<`+IHvV_!ap+FHL{tb`Ns#5-_`p&M1+4H>&(S7Q@1llH+rFrvGDEyMEJ5FQ37 z4yW>0w0qck1P*jwf8fHp#2U7H3tm?^dCgYXL;_UFiDOsqPV<{#Ly(R?!@>~zE}wp7 z7{njS{u){S1iHtfi@uF0uU-Y`b=*H!56Y8e-YMEz57Q`q$@5_U1;7Y#7WKLdU~EKA z%Am2EpdZ|{cA~pBKb+@PG}KiPhVt=3_n5xuTH{1gc^?l|X+Dw&M3!AwQZT_kkzNX( zfGqO1kA5gnTMX7GI3w+5Ha5y-c0ID<_a#U5fuH83tE zie4$Hl*ppP@#C#t`=5xZARE@eu#q;L1%EB@ z<(@}!%8oG>s9v@z)DAmM>L7s%=xzfsJ(QKtVSH;jwjKx*qKA4xH@Bv_@9n3O-jhR= zf+Bx;qVvQ{UehNz=e$xcv>D5S1X18%j;q9oa0cS1F1+S*+8)VAAXCFkPtnFPp5K3! z^1|uSz3y7xF6RBihSc5}!wrRl3JiVzxe=e=ce;|dL=jryQh%V6{m4DX@3_7e-IxF@ zHnf(aUJi+}=R4Y=imSUomOV^bMC24h(DuNbI46KYHqb2uPey$qglzI9%$2RNjLV`8 zC(dUV$c(|faP&r@tq)puk`sS}$DngdwSmVUmsQzf<}I;jEe|R|c0Mt=9)^YH*2gRy zyvUsu3NJDjA!kn2vf?(=163>`p;lu*WYvTN=jdXtAuMjy(tWhKT{+bCtocnLkSf`C zCn_O_0_uxV^i8M+1Ekp-oe~$Ah+H>jT(!*bn$(w>aEJ3um3?H)ER0JP$tuEk>C8yf zXf#aP4jm6f8&2~VA&3cUdD(U}Ed(+6s!sw{Fk)vxeO%Z@qOJc*>_c-u%eRIbpFv1A zZ;sA@JxkPE3kUKjY8dK6gEs(4w{*tVh>SN@nF~uR7D5zFa>=nSzIXnXOj$b>O@Yg* z#NlUZ=qx*Ur^mywL_q&+rVXAxJn>GxwO0j=={nVHz=Cb}~%%@RTn6b^& zR6SykGlQInV&)B3&#uol@Qbb-+%r0~x?+!#F?R$)bmEH{SW-e#>a?e{YjRhaiIw;* zsQ6j_W)Y@}5MDQcvmf#`M&L$fnM`n&k!nUcJushgnnJc04tFd- z*$P|pA~bn6w!%M)W+-dd^l_x4#NT1&;Bspto)`%KmxxsO^6T0^g(oN-R^oqODaT+F$Mpl6&o{3z6I@6fM_FUhxt=AY|hF$^0!GL zY4zd2nOuV#KK&)HK|fFR<5$b)^4jkw+Yoi@)3&JUN3@_>rWD#wo&ao;`K{*(|*4d(+So~15(Qv8^OJCtzR0@`rTi!B|!kg*F`&01WtdB!EYDvF&A*{ks12EEJ zM@;ia>`x9qZ60=4Dv(S6!HyPK4)027n(YGBnut&8BLdhl&7?)e?Lk5NTF~>%gIoVuqs;?e30M<-6)iocF7`R8zc1(w)+X$u*_gj-}%#VJ5s6C zkeui2F|O(}AwsO?{J$QfXnoZr1nCQ2Lxe$69s2Iih3dJ0eWad~S9r7HED~{YKx`UA zDE$zjpw-AB6~CiOdND8UelriRza#RGWSz~(YQr<0cmjAEcpYeORmkWrFPXq~1a*~faW{hC?!ibpb#Jm^XzCPcw@zc-`#18 z%4uC@%emYCzF-c&S$hpFl{QO~7)oo`(6oh+b)L*{nj-|*QAV2K6(sK{e-<^0Z?rEs=4pzYHtQb{@+Jh|!N!M&XLu{h78kIa@Sb>)bN@moJ57 zsLM1Tnb_6uhCw&TYw$uxLvSFo^0pN29= z74ux4R3cH4^HRIL^tm_16%CN?iV*c(kq#IL3&IF@x{?!VDI|3C)@%^9%~dfJCkpcLH6xqK;rO8nPST#QvxQ;|9Kygy&_NV;9YA$DOqQXM4k4x4GoBsY zXx6HpRl3{yjWI0e#}r;MUh#OdAOv`;y)=1Er@ngn*8#2*tUiN?4#j*RXC*!Re*7@S z)wJ}GAgcZ&P%Wmt*Z1fpYfH4$+>j6?_@_SVnqA2n|KzG9))x$`&*Yu;f(7aZpE)!Y zqW0~-;?OD9(281UpVrB{=x{;6W;MC~5u)p{*?_&Hf!WRwulaGpFOrmJbmfcB!jAS- zsKyJ09JR|U-#@llDjVyXqb|?7I+)7u21;q@#UJ%I>}2o_&bC^-oUw#<%cXAW*IjoZ zwX^N;?8j576)!(0p^!0`0QYjf@`s(R9wE!gWf-LIm=$-DFzYPq<$gWpCt+g8Jl*=0 z)CcvHf~_^g3xU2*0WOrBa#cQw8HNQ!YU8*H{Pm_fe_AjifbV0v)GtC>xF|uq_NKDv zS$1^w#e@qos@~(RdOL!1frL%s8V^qJ&6YUu^Bt6?@T1xIZ@`yjJq{?DD~BnYo<+rK zS`U9cDV^l#j6qK3u`s+fdd}0x&c6a#6t7Y;@IeLM{5%e^*btGL*}j@!jpQh z@qW|8v>!|3ld5A&M=&SQ-6UJn>pufhCI4gZ(oDE@{qVZuEnA7y z&afwsdid(k)7(vQ%;Qh?Dw(r@3-M=OR%Pv5_hv>wQmgNM#}C#chgeljT9OpUoE!-d z7bp(u@z?h5FXIy}vcQiTyMfCSgA8L2sq}S#LT%Qo`_GA#vTVpsVX-rruDX4SH~eU- zfGCqTfW(Rfnc)eNFq_VWa>%N^=jBRwItZgP1zEa@DUP?TRyIBLtxlvz&>({p1~E0Q z?V^c&8glwg;_#`<0_4Y`1a=|@tvzK|){-QyJSc-S+wqwQ?IZx1Y>etV3R!IXMZGPQ zShE1bfdaG^!>N?-G}G8=A?sfq^5UfhC&x+dcOpjd7gw;ZpbLlMiwdAwqy~y{Nz%qw zIX6_-T%iNHB_#l)807ZlClQu0giJ1t^9_o4?NKi~yb@&nE?U)JL^ z^Vc8&+R01qDsYuVbU^p`eay7J$HtCR4*;&(HZQC{f^CxWTFCi3py(05z+{O+>S2XU z;56J{bG*jLVBJD>avngU}dE+3z+NGn({W$yu4E)ztsek(h%#dG!xuv+hm+m^>! zA(jA!MF`v)$E56A@FBu|D-tlFr=R7;Yk@5_Qz67G`{9r668~`p#U2D#`n7txJlKK& z<&7+zl^u>f+y^R2{hUb2knGvF2vE|Z0(8egPB-OBzF=?+)1R=qDN5=s;4*8913Orq zzaPhGbO$tZXsaw*YR*DAVk$fWrVBq|W5x)}eBI|h`3j+n2S)*gaX~>mKO_Q26HM3u z(95Rb0x*S4)u}_Uizie?;i{kMc&u@^na7M6<$?BSla&zQHD@@V&*6`-yhTT%BZV@Z ztn&{VLoM{|pc)&Dk65D|zsSGmfMi&_ndMV1c!7eaMa~~3)7LQlpU)l>X28UYvctFb zSHgN5kvw4Y;G%B`B>?apdx)RyFStVZhCh5Av4VsZpM<<+GKp9V2hW9v}10$7mw3ON77OV{Ld0R5-10?u{r&Sz0f)~lZnYra| zf8a<-q$zQ!Klzy^f*H!l;5;BBR zZq~EPM=Ts{#pqc37Ww*ta!z!?D)TM$xX6KJj=8~lPN6Q# zr5?sSbYElu0BkKihvLz1md=4}E`^vXw=nURap%hHZ7(L@S#Oc=qqHt;+ud1hNEWXA zdc#mKC=%SIFo?>$-B-JxQucT*UU+uWkEHkn&%u+9JI|kquFhCmpJ`2-@F6ua?dR zo%-&O74o|bO|1qchu)tUXNk;5a?DDYiKH6tA9Wvvp-TYZjdx|_)rEn<1z(l&`%lOA~%` z%dBo0^Q^|u|I6GD9Xs6vqu*c_?iW6PwC2T3_aIN!W(M6GfE)M91B zgQ(1C>AZSKT`w9sQXfuIHay?u`%s~f?bEu;ASscdyZi!7l)~o2w141IYY7w?p zC}g^*)6Ee70K-rHWge0aMy9m!BsgPynIMu)usj&Iv$rhmehUa2n#6U?QnLmP)0^)Z z$buk0jL7r>5c|8$BE||8+*@_0g(;x+udC{v#Y_iqIb6Z^7-FRu^@X2*@ZUMLt1mH_ z5HE7%L(6=B#py^^cEZd=$fl$0vW2pYuR|iMD3`iIw#!gDKrNbkEPJ?90NVrZC4w6X~bYJ1KL#tPV33lJ8-%XpgT zaL7EI%KAy&kS~+TA8d|Bnk^9me6SX(7HVHW+TCf-8pPVVmpD~#=TG(SjG~qEFsTUV2LWcV79f(h)1Mk z=QWO_pmGX&M~Oj%y+f&amg@i@o5hBz25bM!5o!KH7M^D$vhQzg`Mq#tp$Yp^(E5H4 zwT-8fg2cc)ze3axA&Ry;3gL)HwMa0N%2B<_rz!op%|i&_sZ-^2(@Oejj zWDUT>v*0I*LbJ}n=orLPwKRes<>7dAKu9 zJuEjDhnIi6wV~{V4k~|A?n5;ajYjy?Fu>&~d%o%798Twvp7=0-a#n|ymgRsTgQ?=^ z2~bp#d6Fu>dQ>}Gl%OaAqUz(>*#m1#11Uf_-^a6nO-NV-75dd%#&165bnr>t+2Ars zQjmF|)BJ{JfY|Z2D~_iyI!DPN-Kph0+lxf-tc!sErF(VH0Z)#W?$By${T$;&X_Aa} ze%4amLohWnsk;W6fs)J;9|vL5ReQkf99|sMD!lpJ`33^ey7H?oKk9CuFnqvT1-TLN zyrlkc$R?shtqj0k$#LJSz*=aBf3;NZ#*HDl|D#0O=w7Xo?^ieN%fxCD znBZUk7$S?aaX#>JzVIRovHyB>)s_o2eli;rm}sr-ghMz9&rl=TR422gjp7JE@Ser1doYj0SSc&k&2B{q<^jRGd>O?*p&D#=rEs^=Hz!Vy4ixdjamKf z81^6K20KL+g>A~ZDB`S0yPi?c7R7V7^F(V2I8tfNSz=3mvgOMNGz- z=xXX`$}PI{fy{=sV0d!@U`=q|^wt)0AXQ_j`Heei{E`RMQle$scJ^$v`JKMkZ zDmK?*&TI%`T?LT?xWY8Tc_}7T`8ZPd;_sIK7~79&w{Jg z2RMnTw>zKPZvxb2wZ}1kS)-dQb%+WP!`pX$<93yo;wXszns2 zW5osI8o5PJ2Xq)2DEBnw>?>~Sx2jTgnLba+)*TkxJ}cPoc5(P~r+hx7ls*~iYVgWl zsa4vBe)uFhpvnc*n5GMXc*dJIgA_Q^4C&(OO{nq~OC6r_EV>#A7~=8k!zB=o1J@kM z8Gu?Gxt7P9Qu5uvspr65;vmSSH4tC+;U#fYOlH6_7Qy(tU%^sf0Nd+8KG-Hc_-7vD z!8YDAu&z8oAf$>dx^Omp3ujiSTgQbVjX)&7GvGyhj#iJesX!v+k?VWKU%xIu~m+f_kY#h zKzJ^#hhvG4J>hc}>6BSgm<5lKRd?{an7xn=fUaJe?L@SWFuWh11r47#`|VSLDk#;h zOsMndAJjiJ98kh2v)kY~!@ixRpII&{RW!3J^S;xoVp^q49#69Sij?#*nd9+-Sm?#0 zsWMfFH%xjD+r{1&IA53{vo%Q_Vc6ckm9{Xass+;?`Mc@bos3gFUZ<8O4A~;af8X(A z@l1OoSc3Q&%QjD0xQ4yJ_?p;`|6BJa5Pq6|BEh=Q#Nd=4>cL%_K;WAt7S*QhJ zsLWM!J_|Erwt#BInqfkxp2&BLT5NHHCflGvq*wax%%6BeQ5O-v7pXmwjecw@Y`U5l zvF^cDq#SJ{2s0;25<9P`b%wv~lLEq(uth_Puz;ia9@eGvF$Psx4?!yWvAWX^2UX2pG>_s&o;M zjD7VFo|PT&!CN9#J+^2^1m-ND%?vO+(kplkiIjnbqjJ0-Zm5-aUli+kfQ6S>njr>m zgC=FMz)R_>3O~4TEHd-Vz-&K^jcJr4pqYk%dKywMqGkE!5+a8mUJ}{@Fe?Kz!JZd+ z9=ZXAe*`Q)B`{xJEC>>fsrZRR_T#2mkY8KVm=|^t98Yh0OcL1Gc?D~Rk>G5E|ITlv zHn%ou$Ei_zhaD8?pyL+=trI>Mrb9L(+Ra7Sn8fOvq+GtocXl;C-5H$Ij1duRl9l9a zUbr*i@emGgN^xmEMv_F*qF>CMNE0yA52iLS>5%h`5HlSEbbSm~Sm`kn+-xA?6(q_U zfMiA1fk1AeVbPIvU|n6r5c;-%7VI_Xo+*D1CZY31t<_W+Wh@*o#l`}z@*E{W*#J}3 zpxHX+oc-tsM6J#RbeE3k?f_v9Q4JCYf^L_|%~3)`e$dl*=#PxljUun+(pl#g3sh^; z;4V2FI%m{(g3jGky{_5)MAF+4E@u3Q!x8;?o>!pvT4*{%pgwYd{#o^Pn9I?V<{jd$ zbwL}@j41lzRPf}qQi8f#4hKJ!sMvfr1gILYd)(ff7F|%s+@oekV+`s>Mye({At!vz z4jW)!ZC~5ig999VG&NcDe54E0Emq+e4*Q; z^sA@wu*gy>(mSm_W+aUZlHk^EPo2HKFY5c!eG7bBgKh%EnBsOjsJP@mk!3!PuKvY;KECjHs(We!X#lLn=azZwZ#L4qlG(#dY?Kb8S{UJVk+)td9pk$28$#S&oJ`C7loQ3+ev#F=95-=c|m2r4+ffnWHC#?C} zw3D5FC2|q-MfWOMk&gSx=pdgwb%kIiLig;j>pm6hED9jJ&5Ww`My1qer46BMviQ!a zclWdG$W)qofl1FU8?aU#Y867}bVWgSF$szK;1T;32{w^06jS~h@CiW3lD|+TBw#Gj zTO8+EJDSwx8+I50%@rsih{mDF30^M_E88c{A5GN2Nj;+a+VKn_=ZqS+Yo7kAcfzT5 zuki#ZTw^2zu>8;o=SRrzyqpH)R{ha@x0Mc*sPo&=#7)P>Ayf%^SCl;Gx!XRaQk3%tW% z(J)Gv%S^VXvuzK?)H;atZrgf)z@Vj}om9__PJxDGU+nf9y!8FH2i4`5C?(=I`^;u}CPz))7gn)595@HuS<9nUO%7vx=yQoOC(RPRt$^#T-Q;oRvbm@t+dQ z7adjyE;bIC3AZ6tgRBm)mpyeI{g40rg@mcHa_8BofOx$~5u%x!h!2|t@U>_Qn*(mI zZrw&&15V8xxCpnS)ayV&fl&SoJo*w-Cj{jK(BU&VqmD2A_xS(VlR)L9c8AlG&iRBL zgJWdBbdSkvkDg4A=;XshQAcD*f;kt45){JD6xO)A^UEB;ygn~A(0T0U>H`oK$6}AU zVX8M+1j}^%EfzB!-x-EUc1q1e;t_;6)4oC&5WEWQX5a7-!CtU@dJ+D zx;*|PSZQl+o*Ij?dW2!S=s1y%yG-~U-`Hz;=h0m=k|Uw^m@Vw!>wFRLyh!y2-$lX< z8efpU3|l&{4AC|^7XI`Ql#Ok>xNU%BFG9m~dy+305Z(#Q1V(0{cRg)Z1Dat6UtMlSVLYIRdHIc6V(*}y9na$mri#XY= zp4ngJ8jR+GjyKI=J6(8N%-CbSab!e_3}S3awafTwPO8zm^g$NQ$+@`KNTEjm~KiFzp+ zbRAl+OQ`e6pUK{xBM-PwuA0Pgx6A=_&v8h^S+~J!+7|zLStqCHNrE4*DDr z{Izf423gl>*s|e{RUm+p0_x7M{>Ns!1{d=O#Y2bM#9;Hm7cv8-G9w|X1cm-R?z zaQjErNS-!#DkXukL;%Hn9`MdKuW+=(I;dB9!3h3Lj5Y%gE{@= z&?lh4^QrqD>id+N{zoFKwV0t%g@*-AjSI%pbPua{rHFuZao} zw|O8?ruMkz^bX$O!ZFH(dN|JIrsJOa&$hY==_6V@*%v(og~N7Da~OT|XGt(8?vWZ} z0qhkKhp)lva@U$de#+u>68QetO~(~edWB{No7Aw&@+hg^*=w&R4P~(qgGkBzSsFoB ztzeSx?1D!Cwf*TB@s(v?w88z-wFU5^Q_cf0X6RxjtI(T2EH7E3q+-?AnZdx{?Wv7+ zNGFMd&4CZs`k%RrSY;Am_S=G7Os#K@6OGvL9U^JA2U>;8>e1tvl32%z892*sKT2qH z04uALlZ;Amtr9PO5U%x2w?zL=!Nrn}ULBiE^ z#Y50U0<1?)a%5oj9}Hh%hx=C<1D!rnBr&idt!-+$|0qR9_Bql}^U{oHji4$tlmY|k zLe!DShg|ff)P$_2k}x8Yuc{7vM~>;?;j!e!5rOUZI2=x12>FxS{Uc)2;?>JV;Ttq) zFU&=-vuTOj%qJ4hCR=0=dna*iB#fm@ z;^WY?SukgJ4-+|dnc_g|p1=g;!VsL?@o0frJcuY=2$N&Lgt2$Hm0}d~>tTZ}(YGYG zqXQdVaJTW_CkK8ZWS=pBLOZ<^pe%+?<|oHoy$J=JYhCw?@_vv^IalS}F`t!Nf(H3< zoKgc<#Ms^S;*VX_HDyMD;oppN zpqpjO>(t(7W$2cQYvOB-s6if{D8h1dS=|yJsde|k0Ch<5o8rnE*bSpL`Q!J9e{meo zdspzoCLb6T?l4X3HNibO=o;gZmP*a|F@aldntpW3Pr^R(#;&@|=MJp(CKSHz2FYMk z7@$5jvYE^ZbJe!ts@87t)L&3~(*_!zrS!EtJg>dBZ-cvG@N-F#9VE)pOC5Es#Ah}W z8NzvJJ}z4wts?SAd!jvtQSmGIkK6SGZ1u3P5^gvY`-itSq$I)flF-l(onT%LNwx&f zLLwTTm)HUSw@$|RNF|`-YpD@wXvmr!6roMVk=!e`?B$*NcD$(q}eDw$5hTjtLB?j~nTHgZGs8qA%Xr@7Y>< zMz5`Jv!i2r36)SsgBA<5){|bd&68B$2a!VlQGTm?opLhYeJnaql?z`HTX} zf;(Qw%lU%+d+Gqx>dWEgPjL;I2lF5jrt~KO1=h3J=-b0OFvhLc?2#qyFg=2r@7lg$ zl(x^Uf+;@Tuw|RWjIN&@9ufTS?wsjDKDE3*sM<`pq>Gp=d@rPFMQ_KN0b2g?&gwSU z8*ai4wi(n*EcoMcut1E`wEYM^|? zq$A$1-58`I z4aMg3>(j1lN2-;di}nWy)g@Gh4!J43+4H~K*7U}%FNwsY0^U~@LfA}Bc(mzQoW6Lm z4s2gOdUVS4a~^hULKPGzyQnC#kkT!%S%dVIOy7GeHyl#_BwlW6g@Uw@=u-poL;bW> z88bjPsplDIHj3dOa9`v}^VHn+=4BKfMfoi9pR3y`R~PUZ9P>=HJzi{vl!p(gi6yZu zKw022PN`aV@V^m)Rs?|ORjgT1z0MH6i!#rge}fO&hbGm=__rT+)|x^gP9cH+J~eK5 z)cj1@w;%GSOwuu*EV}C*5LzsE9tT*AaQnBK9{u?r>RvOLm#)$Wjgr`KFc0zdiS``l zz^>^MOx(Wf1xyjk%e}$FSH`ZSA>9m1BH0{Q>J@GyVaXX&De9^tJ?Djf#fBb#xsVed=mP{jWvhSr@-#K?y-ulPi4En}FX2s<~6|Xo7%~4QLiLhj5N4q%Z89;i#@f9(GNf}{Z?WlO(Y8dBSfkvYt zc~9*=vD+~CiPTq_I59}J(GDmlky5DkTO>kUsMvjk;<6#pS!7{gF5SEcXH9wRdNtaw zOp+oR%o&-##DM+&l~eQ4kzdu3t-F*>kt(MqHQJq*J7=B?=d+#6 zCsTW0K7CR{AZ*T7WBTZpj2vWYB7^CYZ^nC^oA!Z-W@L|7iH*eM9AJ4H`Jjvi8v_j! z^6tpHqGTm;D;H_Nh!M%Akj7h@Ft@p=W`>mtWp(Xna&giJ#M0d)P=p&pPZ3V!k4n?< zs~d>eRm|Efe7jU`cHA3o5~3OU))@*hNCjMcgk9Ui0&no|EjXorwEbCPx@<%(&Dg_O z1eU*>2F~}>45eZjePO1HJ!7x`aG7!?{h~yW=h6E={dZzJY;Q!yitqol^;coDG&4EP z@y2NjYB9_&pEHm~y=&V1vDJYvcHPk5ag?!IA9cob%V<9;JBI>SdH<5`&vfDXO2tf%4A@}|q9?UGL|PJ6M?E=v97gyW zL0`o-tqF_ZGVljMY!~ssC7{7HO^04a zs_o*#-Bw+&`Q*JdM9TX;_qjn&<>I7(;`Os)acM`vI8z(j#aQjs9un>}vH4@vCuta{ zY%|``{x~0s4KT;_+*^tAic2*IJegfej*Q%j&eNN(lyjIGfVg~ONYxCpSX*96^gTDC z>RLODCWGe^9TXaBFK~Rj8N=cY_r~ZnHSS#P`=krUyda3=rF?ymjh88Grt)QetgGa$ zur{G#SILdI3SzeW&eXI>dokke6dyWHX@Zz$i8+lP&I5?tD!fW5;i`nwTvlL=h)L1? z)3|=3Mo191lavSsr2Z|@^qoojmpbjhhP;JoFR@SsrL>q`Sw^PN4lx{o`&nZ8Cjhg*e(=RSS@>f&Lt}LPj&F zB61(@{E@VTb_&GNt-J5toF>2vpD(uKlpMPTWB<2&1yq>~G{Kd-)mfTQ&BEwW81o3% zuD=s!G{Ynw2ttx}6Zrpud`=Ef#PiTjPC6;MNpoVSW0sRTlzIwe^SL3Q&?>o*@W&IB zHan%&dd%~=H#-zqlwP6=Ez-n!HeNpJPwfr%uYT(EbWjG27AWUb&ow>Eo2@XO)1Iv6 zZkk#*^bfz}{cKyzjG&`zY*hNj7w&2@E8FYv~skZZ+n`4|Zvo9dGoC}lp z3>9o&U<0QC)3V0klG_tL%#jkFin5D|p5ZZVk{<#0e!%f3GGM%VSMgppod=Zlh6g|FqMo}?Mh=Vdsk`vy#77V_ zrbUPAH<7UqF~Z9@PR-6nk26Km5ZwKZ`Z9lhFs0k6W1Q)U}m;gqMi&$iFoE6E) zXCvyACmPPB1@6e*bV#aMcWW*z8>1Hx7Z)P}s-K$PO1yT8BG4^pgt&}k--8{+1lXfG zQAS=oy^qd*vz_J@m*7}S37g~{cOe!$kO{Vit}Xz}Q{snMBUQamcr``*o{^3+<@p7W z#ul_Ic4soAt>oF67AkKvVMXy5>f};l!1Q`o<-n=_5}6v4_3kGxKtbshisJcQzJJ!m zYXkkxt-CpI=y7a`%(qmctgX99xA_*2S3fs;N&_z+jIaAs4Y%}}X8Qh~e;D^ybFUqs zgY&2bT#e$hG-K%)eBB)hLddHK1t3*sTe!b3=3*;7U#8b!ma{XCfdOM~pI8d6Mk zr(4}rdIpOdebUW!KsaZ(abotqE&E*{E0QCcG=C&*A^*PE-*wQU)E^Q!HcG%o=a*a* z(g>qm?Yw!tjfH*)VR>G)o1&lg9AYS{H+^|KTs8I2o=AevT2D@qN~^GLhi1#x!Lxl$ zmGM4ZZW-wc*{7>m%4B2iqM|g`E4+3K-w*4JZfw*Tb_~X zSFtZ3VFgdKHjBlFC{DpuYu_G>v8{nP195H~v znLo}r#E5&g?!isY58#W~a@vxEe?yR1I7>E4zS)b>o85;Mn)0+qb6;wGzdH}w5?k(6 zy=ECV`&Ocaw6fEp$fhtrKvU8PrB6a7sgJ7F&!EHY-4{Dc=&(zGazc_Z$+ zEQ6|%d<%jDPtx}-X(dLUwj4uN&ZwVKaC6wzbF|l`zJqF3YR#$sAeH0Gf;H=aVdJEP zqa`(?X2Fnkt=Um;WLP14oN;V&e;8AaIYXPNYNSIpZ;u)ZmIljsSEcsrdcG(Q^gmE@4_%Jgcj2$_sT~x%9QMU z6i;$D(8EyC{e6GP@Z1+loQA>0@Hg@7M@qO=SXowu_9k+LET?@=I2MT@vx~aaZ=&-1 z(9>;b13g)m51O;^EObs6m%6m>nFGeoH~4yn=jNRg4_;Ox)TpCe&jr9A7xZWbV=K#s zoY*qe?Zh{wiq_;^QftUpl)8*ozpJPf>R>r~$D=&>5J<8FgV>W#2hv%&xC;DnL703y zC*orj&18ru?vCd=i(iwWSr;`q%7^|8tmHY@Bt`XaOzN0Hyhe#lcw1rG!kWKg-|Cvp z;CB}kx_Pi=!QGUk^nMXjlFcV4g+yQbSq?Ydnd?S;85i^!de{00;t<@BD^b@LQM_@R z=bfwI#)0DV$?+!x==KsJl3}PUp_Qm6NCDm1;G2Zu1$^~noKQ0v%xCP$SfJ6iK=wF} z-2prg+uuA}C3`O9es3-MW)}4holLYdEKp|@dG6NG+>2J{P}kVTrMdO{9ntDy@O5jb zf&B7S{!npy#k02?h(=;{Yd5u7`B}j?QNzKt`7Zzl$1_1cc-3O!xD&W?($48Q{z4X*k_otl7b$EoBL=KnuU&j zs5OvuAq>K(R^}-`T1Q=Ah0{6!q`|5FFcd5WZW4DL4V-cc0*+9&;JIRcKsBuahsUkG zv*dk^(7}MMq^UBN_SO}#W={`HrN`2xIFq@v3>li*dL~laL%&sBH6HrOxs^s^)tzLO zOlN%uv?ozKmP<2Bnl83%y4S5o8 zqo};!K^-ZqYS`65P;HjTvQe>q9z5rLfm&6hyxtI`LCc!0-zui)1y~6-PKq5(`+B$N4`n8Xf;(>>p23BD4X$ zt3K-NFh0BwwhvXny-0f{n<}yQ;CF1WQGGvNHr)}py~j&n>j2C_qBsQ$uhjv$G2(HEj}TGodwz!}vmN#M%y3f&EI?Wp7)^3z|mlAYW@ zY~V-nNpASph9@FFeoW{zZMeoJ`ePiU1SVM}d}&Ge72XBhZ35hh^6yGv_?H~QIhDBJ z!Oh^F(|l3`n)(HEY3A82e8)Vxa7M!Ryv;kQWp9K$AGmsTeru31T^Y0LzJ=*T*_<=u z;Uz7f?Bgt_ofY3S$@-NcY9iat!9iu^yC_(>=)-D*pKH<@n5?(>w5N+xO)B$@yKyD< z*P4;b(o#FCQImW=D=^60HokD@6SDDjUI_&A*6nEy7eT|;Cz*xR5mQC3=|(y z6#J^toYo9Ab*ZME9U`-@co-R-4&gTEZB7{LNYJ6{q}@^;gi;dHD!rni@=sam$)Sus zEAo%<<)$Ro?49@Jad)`beWq=Q{ftP&2AXe+7^ja@;HlmX0pMXrim5rh!Xt5|=H2L3 zLr|`Jb(aAH_K*d;bpPm~9j3tkFr4$DeEbZR6P(~KB%1+K4Lx!^ecN=BFeW=>*#-7I zv6keuLzB53!%evz$G2f9M;CQ78?9;fo4y>0f(0^4Pvy)=%BzAG5fQ~^0S_qXiV>*> zPXUms?t{9kb=D4o8!o;mv(qp#v%GPh4K1xQU0sufoE3&{;meOByRo7xDF>#+Pll4X zRE~ws*%%kj&jrp`)sA1gV0A5>*>D2;3KzBgtLQmAlU&%n+IRlblIBGh`6-PU@oUjT zF@z<~&lAT1v(N1{030S+AOY&oU**kaoaRG-rSH^7zxa`R?v@sn@8^NSlyY361dydG zk6S@dYxVXF3bBB0vYJ!B4_Vz`0Va-*#l#Qt!=h?{-W%`N(vPnE%b-h~*NE3}!~i^c z--oO}M=vx-@vlouu49AirDU`OI2(`9QWA^cAV1lqueHpj#HZp~aJk)QFS__PE% zgQ0{KJ5beo>0wCj2Ja@hwwc;VcDc;?R@>%9GOjVgoJ#72pRk2_=Wu5k_+M+jlpyF; zC2^q3k2s}LCnwp87IJdI%bBP<1YhcP?~CG4oDz?iJOZFTbLa}`yaM!zUX4zC8P{|! z2qYq zgj95An}60Vwpi{vtAc=VVe~tT5DW^7Aii;Ujh%VrSv9Vvo{Z7vKtGw=pg&DI&Epap z!IPw3cIUc?$WveK1UJb_zp>DrU7()I?Idq(^4U)4O0!4*`$Yjkt+gkx_Q3rQ+z)x9 zw{aXbVPhs{4F#YA-OY^|Y|MzuPc3FI*0wKZPJX=&Z9>s!T3xTLt`qxI1;9A>!J*Vo z1SI92l+~&qr@9I8r(k}e7Ib&kN-E)3SBSQ@LOcmiOw`Ds%#P=zsV5}bvmg)YcQnnj z3$Y48()NJStxeI|4suYcqqFv!!L?X)jxfom-Um8evhVz(RLPZh(|8l_6>!VrL15iB zaXs_R-{ORXr(jGJE;Rb8Cv=D(8lJV+ZI8nE(?cji=dgMh|-dlKsjAKmM zmGGAB9RBLwMEM2(o|eDo%y~84Zro!yOrQC5KKGPZ{K$hSGBV|yhROrZkdnuuG?;y) z_Id3iK!GT5sopLOTv1lZgivjl-0XxC4#%YPZPRR(fLl|L@1HJNB%xDbkmTt^OB_fOt6;I(XEhbQ;F~!8qYDn^Z zielae?4O(n*0>vz&pS0HGQe+xR7aVeihcYb_KHF#IMC@UJCdJz*{2m9FSM^@Dw5gw z0X$ZY(!^4f9UW007|ccr+N%R*exS_1$Y>hWG&mt1k5la9g9|z%B`Z%420~c#f*$j|3+c{S?(puKg45BcG9+ieIM*fHIX@iGt%rF}8ifmV0sMy^pP18DlP$AFzhZdvCwZ%NR6vRM+pnzn1%LTfS#@_ZVX)>VAb zBQK{Dco6Vd*qo{uHu-Q^H@_$2Cl0tLb%P<|CF>GA#g*hXe+0Ns73Ml8=|9FCwlkWA zhj~ugHaj4;B!VojbyT0QzB@%UCKKvMZG~J-6OsH`DZY||aUBqJ3N@Rel}Ak5SlRf7 zp|@Qu>3&XiNYcLo;sja2#WF*^CxE3!`AQ2Rg5{oxJuUh3)HUo=L2HfDT*wKU{PBZw z>gIlK?eUpy&up6dskRd9+~t(0Y4OF{1;Iuq?#-fjzU3kVy%_>xIUkV3#p`pYqCIW! zO|y4TD_2a4o>vWLq+KM5Qn}4`>F!$?X<4z{gIAtP4a@K$mpL#<+_n-F0oqb zby~{S0|UWOM6jt7YA)D|f3L#}gTOYR26g?pOn1OCOF_wL^2(3H}h*Epm{ zNu!8UMnd~s%?H&om5eoXjv<#5yCKK}s;8SsV|VOZNEn6zg)2dJl?Nk_aQT!=1%bmG zQ|sDdMRuur76z39VP~pF1PT|PkRdU67}lw%DIm7`!4joaYi0f6JDQs|4U=yF0kP7- zKcqYveW*3th3>$07e!7l7d?#-Sq&k;!nvi02%nBK`17epPH8Q&K~M%1oyLihh8aA%RV$;7yPo8u_qUJ%} zH~H1$e@ZcNRS1Q!&_mrnyHOZ8)6c6L#ghMKR~Tcj^=Z{+97M#3a@Wp|rPeAd332#B zkoLy?|E1{_!jg*X93pE)Bu*2;VwV*|+Yd(nt|K0Y9QsgaC_GfOre|`-ADPWzimVmT z(Ds8Bd7auTviJ}?ED$S3Gg1K;r*!KCg6zetv(P{bi$o&po0`yCQRJ;7q$pIifz$}k zFR?w?2Yp{*&qA&R72Hm$Ulhvez^WOf747eu+5wjNn<;LM`r%-}sk3Pzg-v*@j()uH zxj?`Thf@s3xe#Q)_cDMDwr5gVPx$llBP4*!V$ge4Vo|v%*-#7kK#H{GsEw^`;{=sUuT46duS5B#@PCvG_u-QYTOy0Yn9{22E*`msMeW599 z{lyJ*;vZ`H9bd^bm4&|fiRW^G(aT=ktdR}~2|O60G9clKlP)l|rZ>s0_<#E=P2l~F-;kGB4poZGK;2pqu;#4zR< zkcj9#)&WfV$}@Tw)uYF!+$~ri_&XOJvf!sNbF@*H^@@-qnI(RO$+57|VOr!-PwUI$ zoWzLbBHDG!Ww%1~<5z}nAWrgUqOe>6N1_RnK$RRkmR-VQon2V+IBLg41ut4e24pyH4^ zI>AbCIFk`_5=?b;Js_}tqogS^5I(K{e#)uN zpSh0J)HxC++<EQq9ClB z;kWP?ICVe^B909?zVa~HGZ#7-$t5rJ1T#APAbF;psOv_XqwOi@+)zxCxxR6Iz_yQi>Qb4 zCxtk|*HEUz?^x#}RduT~u!jYELyB0I2o!i}#=o-_ws4r5DlNQxWQ6K^#Uzu37M@X( z=+iM-5d=0Ml2iv}BVE^J2;-Y{i9X%FLdu*`5|%k2KJ74P}{=+6EC%+W_t+P~n1+8R75jq6ti z6}0uGJOtw)+5Rta^J{y;f8J^w#j>LSH9*S0)-sJfPGfX2iKCNUnOK2vOvjwRv!VA? z!9YqY`*w~b-7b2@)H^~fz%B^N8A5MMXDBr4{6CmShbz4p+?RNaanZxlsuIb%H5+fb zNaT3$dYJ?^vP+0 ziiuW!#szw^DRuUUV2hg`r&H1Gf1eNdQuBX?U*%s#xd{9+Nbx9%ESG7!4W?Xh__!Cg zFcOko;%FvH$fS1Jxb-tJm!scn-ag-i>%?_gC?#Qi9brN6EGKV#s+I<}V0EO9Vl(;< zuOeF%5<+379TnUSVw~F0ssd<~v6bCo?te9Sy~(Mf?GQlLgvsy&qB6mT{K6wgp`70@ z(U+QOu`{v;Ps8xLex`FNciOw+Zlfm(xGz#l!R$c)_lgw+IHX857Sda(j7aXtRp)zj zvzF1+My6+2kr>6xm9z`K{EQ7Pz{M`1f`q58SC(ve0M-doo}m*;WhN`&@xaXLp7(`s z_EC5U3P!--wA@<0ZnFSM!{2`l%K)aRd+c#Y%DIaR?zmD_uJ&rAIEAgGusg&=*o&9T ziPLoHdG-zUGZD>z#&1MsU}nOXAZJp`;+G4(LdUzJS?iad;pwh&3Kz};c50|!c5wCX zg5vGe*jnHoK53MshQ!Nv%iE~=RZ|dyTVjcJ)N7X3;fLUjA|+=I1BFou@e}3;z18y9 zzz&(;igYOEMm3saDtd6CMy9NF$t17Hr>8{f1>uCgK&Td(%z!Wiv?1}i0x|bDs_o#L z>-AUObkb5#E9P&9t;y@747q_y2KCe|{YK*1&k&f#))8KZr#F6POUm$!T;)b4udoB^ zN;Ip{xW7GphU=M#YA>#{fNXe9wrAK#E5_FCJvVOzS(d4WS#i&2mQ~Ih0C+SIrw%=S zz0`Si&-)&b7J~skFf-L@Y>PHqW3Az0+ZHS9{Xk+2pdvH)+yl3gK~pTMCCv9cv+gmq z^e|L19dfD^&;JR-p5De$OwqVHnwQ6wibenb=3WKOP1sI{3TKWlk>ccA2$8 zHoXfW7NZyZ3N=ZIdl$%Act?E_Xzzhb)KrJ0M;tNzhzn&hlw$_4h=1n+Wae7$FG}$^ zelwcI8uf``7l%5}i+yW2#`Jt;)4yKKOIXMql+sP)vlmOcXdUrXYz*jFUffeDEfDLR zY|7LT9hH*gsYEMOS4nmSERbk4ND*5gUtfe#iakdwF$$u0(V?A_bBH>OGDjYp%Ir6D z&bx+3u=E<*@HD|%*UOh5ELzukWmwN^R^C5#9Gn-JR6e|(8lcrbq}bJ4?o=T>N|dA& zqk78}Nf;=R-u{6VXv1!!PzwZSFZHxzbgS~6){QinD(bH2YOyzD$gO;BDLsWeu%iGG#1YADcA;}|FC!pyj$MR@OwBH3#V=FR$tHz zXwdRv^A?1KX|!v&O^gbXgwNZY^u#9RBKP{rtCoTxA=3#i*0geQLx zwWVUIjt3gleFL0Gvj)?xMlNoO{{ji#s*Y=#P^1l#fn^qQGO3GvepE`L;m%QW5Tbctv1`gq3FLQEI zN0-8k=hEun=Tw=CBq4B|6HuaO_5!-c_#H>wSN)I&ZLgo_J<$jEAGna;O3Athfz7e_ zB(+wKy&eXZdVjSK0o~)y>Q}^gd#HzTMT%iowhyJQ$>_7vH=Abvsj*^+uU`ayF7By#5I*CJ zBAoX*mOcgATg>B^Z7#5WcSCr|P2>ORGaU0Oa?;i+Q&lGSU+eoI;bCnD&<f*>Jd>h_+Hy#ekwi|db zwXpdvmG{Jw_{w1zDNlh=KuA9<2*b3QOY`?Ezkv5O7wtVJ%VXP>TvcC~^9V#o%< zbM~~Fn>)wQ_MGbw)snWZ(EHd@a1=bg(3o48;ioY0H?5n`{Gksz$fmX77(JY0p;g8Q za)w@Q5T#gf7=a!Y zZe{%%sP?=8lathj1xJt@V|KroZpfwRx(!&+UD(K|cmO`Lf2p4`)%>bI*?{F$1V|RJ zHFD>@orvzQv36)YhUs#LnBb2+w`ihuj+RDm<*pfou!{K&r};NwotXXP2sV1)a%RV^ z#b{v}B#(fZjtx=iFLCrpV>e}Qnin5+hVbSlv6i2CudKDaoaxRNyrd1QVtkrxuZGzU z{8|U?F{TI4&=C4svCxsEZ+9v`v8zKIhj7JGHS=EJ#lMtCQrWF-P}-KWa`#=#g&Hlu zi#!M*5L9tlaGiK6lhGpA&AJHuPr|%*5&k z92f9Ng}&$ON9{t3m_#8d+|9ko6Bmondi(~#-nLq&^fxTah5Z3oh=+<^ds8Sf zBu8gljJB;3wCnOmmhLsMsbxBM%bom;F})(^E^`Jq#jL{If1N%1T}T+%wqF%}10{5KqQOUF+*h28p}OxN#CmtUADq0jM3bW>T#1tp_ak2?ypSF-zl3Yde#pzIU!ur$ zq!NJDH;hH4^&2{3JG@-3J@iBuhC{BV(YgVYOSsT=>oSR#yUg z`bV;haRp<(Y(`bwRdbG}rn}KBObkVi#G9CSM(*d~3@GrfqLeDys?UAWoCYOITtIF3 zGh{<7iA*;{XKl8ju)u1t0eoMz$GP;y8s}rfx4Z1U_$pgZuD*Ex7fcNEQ&=0RG1@@fRFc_)j45r~Gp0+`)-QYL zucYKm80c6Z!sz~71q8)s`E;vnMbv2ZqgBd-xG)7?b^Ad?L=9rP`Kr&5_drkCbK8ds zP(jsH^RWTR^vU-fZ!Ewn^MVk4ERI|R_KLAF)Y}BnnfGCFB=G=Ch?HP_0mDpsqm$)B z7ZNJu;wb+LQ0Lhq$_jrHl{G19Ts?lzr$rVUb?#YQ2j#X}Sa+U(wtF|P`+0q_PszS4 z@dq~igFwl@I-=KlPATC2CozmrNsvT-uDM+9njqBDs4$*9;|C-tNld=irX$k&U~V}Z zjZfU-Rdo7TM^A`K_}i7$K=^T3tb`rY){FR9`Zj+*70}+^+WTxbFT26n$VLQYH?ovO zOiu#hK~W`)OQ;U#maF?h-=78=Lzrl zl~&^7$=uV5(Z^~#LF48ZDSO)#8OJe2dXRXcfZ$_?66QrRj`q=$FQuH$l7bnJV-|9@@a_0Y_8o}DoyqQvfkA8fiz|q)Kb<_ zNUQz6an}fi*{wdvopOl;S{7wcKx8c>M%8?w151s;M!)SkF} zx_--SSiBT%5FQm>{&+ZU3ftzr_kvs>Dw;6lPAx(Rb%nr9F5#R;U#Q`aIPmllQd+}W z*iBo!6Ub=>H5a{M&Lc(p3eM6d&btrJYhk~!XoY*o^FiTtvsWS?qJu3~xoroPO;-2X z^zf_F*-C?6q@rON^17p?1|8AX7LJ0d--oLonJ|z-t0K(+RD0_hhGhK zA$TyCAUf~Xdq5w6bAI<~Fj91?uixtRGr>e-gYw(ieSTeB<;RiMKEF7#DAB-{gkxJV z7g4E1w9)5+2=ihtl;>)D*aTN}cU=a!9ax|2^G#^DAc zw>M7mNl>a~p8U(L-i4K`zXT;HCqmZv5UQp>zx+GTZHV@q6sj}oRk^hW{2}AF4RKE3 zK-n)9C9so=(He4E9E`I0iE1sIH!?BCrrmm1bzIPrL8NNW4oDszWuJmlT7VD+y)fL8> zoq3Mu)}Ir+JU;)gNlfz+!Rt9!bD}@Q(fYopxrngc_uS&n06nB3nzL!V>6NyZ5^cOVA`-8AKq+!aW`>sn*5g% zk$yp8%zYM4UEF7LQo*6*&nGj*dx)%l#{+IB2FSq$**;X?zw_{WgIPu(qtLC$E{(951E*W?%Zt6?6wDN4Rf!hTqMGF5KQhh5h+8&JD zcco~jLV$4@rCLgj4@b^`$gdfrfv}U==P(!?UEp)-H8n0<5U5SkILHgRw(!SFI()2= zarJaAi9Zr$*(PUe`YyLQ_`a6qXUPx( z06xJ($ci|+^XA!|q|1_5U|CVYtTAK0#KLQ%G7On?`{{b)zKay zJ5oG&9ZCHp=fW+kJ}3sS8H4mh9MfakC;jLch^326esE(HRBg49U1VY}LP^P}silz= zMDn_&OpI3nVq2mS&w5@w`YWU&cR_2P1HR>V?SYRQxTGr<7vAuBd)-?z&pp%BX^-5_ z0lLkVZ@hZKGuc5vxR$n?u2CvNU$P~j7fNBSs-%V*nysAqN#)doE$(zN=HmOQu&?u5 zQOs(&}LqaAPGvS=5Qo(S~{ zpHELlUTEW;oxL2uN`~q?V2Zv2a)teWeS>kdjZlaq9fskp+N>!$y54oCYv_oON(UMW8m3{2gzLh%+{@YaRbg9 zJfaE6iHW~O-}MD!y-uJ|y3Qo+4jQX6(^(9%H;#*!$I*`{s`eF+c|SQrqPm+A{nEbn z%<&SnRqSc8VU%aMLgQ%y@)ab+37DwY>KGN4H<8hbGYNcOo`ybq=ICaBW6q{R!128- zcO3-V;1cO=;=2k)YHuNRnCXR8bp+O)^v>C|ux3z%o;Dmin$iL`c zt_LS~Rvd&oOW`{sHYpDqx}B@Aw7gxNeZf^?gwv9LT|_~Pa(Yqdq0IkGaeT`0bWbk% zZ#uBiIqMblLW3|5OAGR{J(aX$5N8eZH$c(dbxA25Ra2@tHQH2~zdKIyWPG=^XU>YK zxmUwUy`BE!WQ^;fZzt!rhZ8Kp8EXvJjahBuz-?-8Wj8jv%>4xUO}{g zg{Dmiy7@Gm#Is+yznv7!H8!hPx;e?KfS9N(xfdoT)@@u2_#%iU#jLQMQ4Hu(&sgP~G{_rw#rKYJv z$=)QEFzvum+KA=snTrrFxib?KhDu3~NgpNx6zL%~U%|c-j(4YJt)dQ?0xij)C1|2pq;K3X1R@uC0ClOQ%Ba%|I0@R+t1bmHNrwq07_8V-v8}xgF zU29AZBBX;;gY1SgfQK7l^L|>NgT%0(^1h?So~0)F;M?RFl1f|eW!Vk*N}wdYN6g=J ziYfA#VeNjj04&*?kuVSr&PkqOZ?r(8VLSZ=mql$_6HfHs9;0Hth{X+it_Yx*wAW z?lN4@0aGNci`aqGz`+;dMj({s%uBJ&BLBn1Za{zJ6NHkh;%SAKhfFC6WJHc7^@NP=ew;_iTwkF~7jCgXAh5YLK;RbESCPvT4yXi@npBfo3=7V3T= z!&9|T%zrZIhFr8VYxXCu(Tx*`L%49cdDR>ScOI0)_q&fiXq^)jnpl`pz8h#C%}>C( zp|Py|;1YB%$Kkby{ggghosMk6vr~k5+I&Ls-n#sz!tNM?aY?wK7zQ@JWXsvA6v&T) zUNt8`jLTb}Fzo$sZnZdszhd3KtU z9z)=c=s<$jesZY3KtnDaT@%vC)gUmuL;Zp@rC2QUq70`$x=PK>=eEKefAp#(`Z_(s z$xj=1m^qzvvwDQm`)TtD18%y>3lkYih(fcGjJ+Zh%ABcerREwO3zY%7Zs{U#O!R=Y z5=y$}fbadp#r7tCO#!Occjkj#*pOQv24y(Bcmjl`A@oL_X=7-nouX|nAfLWo*(FOE zPte#gTNA3Zuco-+cEVu=`XD%~2Io}Wx1~wHtAw~&r+LPcAJpl|nU&HIU+3dk0_17F z8>2*uElme|R2d4Ozwec*pE_9#RvnNtFfx?m^5t`vqD#_j`-73t~ z)>T%AtU>kNI?M-ju25*oc$}zah%ihd;B%QGhTYZ2w6C>6@l(?N>aua1nBLX!zp>?N zLxt+gT^jf`byekz6E8;&E!c63!}7xSas+`|wW(6~V3cmdLDtvG>N)p(&i6W-%w6*~~|N z0IzgP*{jVT6;A`vZ=PvyJHgA@3G+mYn?VYIR*py6xZr#55ItnGbk86#Mc)FolM$MuTpnd5 zF*!BhMSx8O58Js)v@}hNm7zTuTRdaKgmtzjfW#(fUP`@8V0X*IGj-2s6NnA0##DvXPz0Mr!6%O^_Vj3wrCal6&GQP@8k+=zSdCCKj zDvTIPO156mmI8<8hVt*_Df(bepH+r`8Cgx@1kzns$c$=tQYFX?$QYnTcT*l>sU7m!$6Iq$7FdM-qY*% z?<$rtK3|_+Oa!^vos1XV^&aFlHExV$WUsA5JT2jlo8W+&XnbUGP(+mrx~z&hMWjSE zp7&Nr?LqbLvWUB>gw&S*S41JgRGr8eHDW=7MH-sbf-S}ucMEjHi3WPpNv78>lF!+` z5oj@J5U|mZFLI80%8a>mIBPG5^t zEq~Wz2VNyIDUkkyGVrn9LyASNsj_oShF7VziAmdv++o_~8!0Gv$nz1;FN2BpiT5Dhp!L|$+N`)ijohqpu9?XJQWXc@ zh{bUUG;Ct6qm(rYWiNa0#Uf&h#;Gm4;>;zr0(e8*^)wrYrMbODZMYa0n7K~>4tr|h zV0|B^*ojieYXNLG(hE`HQ0LkKn*8$!SwA2hX+(KelflxDQ+@jkq6{QtZmzh%mr0(K z1QW$kp>ODv(Yay0sdw3a@+lcoVVS$)&Vn1Z)NH~B?Bx)^LaIGn$~CO@)R3Ib|1E#W z6fo#4J5dzyOBBfd-DDczdHQ-Ek{WCG@)t5Zx{ENk4-aOzYVnhwjv(x?$tIIwWH8?O z8QJXx1og{t>MtMYGaU71Im&3JaYlj3zTS9WCE;b}pb%fvK{vsU4MvmW8s05l->3xY zJ#t&LAZU3|y#4&+8ZpzBnHyy>zKzL0^|LhFyr**t1 zXI!9WN#eoG3fNI%#q?>5$wk%wycg@8o41_KiJP1qhoK?cu7{d|^PJ%e;Ln6HF-$81 zR21*jPD7Vjc^;nTkH#n20<+A44#f7v$JT-pN!?7?gk=9f)Z{*1)~+qMf`s)}H%*TZ>um zEdVbEv}e_WKUq-1KaSP8O{V)kbFU?PDEu3WY~I~t=1Q)HxSz-Qk-z&2O+%YxdBD~V zCsp6F;n)1!?!&gjta%?4EqJR4yGl=RhEMH%^nctHrLr&e`S|p+H~$Q7eiF5Cs40V{ zapUiiKrRPqj?@+t^U(+^(yseWNHZdO784}ic7K5Xbng^`_pW7n#Tw`Q-%N;orrSbx zF&>378sgf6L=2Z%U(vP@F2Gm36;64g^7NKH_E5j_ZaAG~)Z)?$z1+l=gRNW-uit{`nJ++!lXC0h&6 zNILMSwoTq4z=HnLxlYa=aTCXGf!q4`d-tp)B|sK^4%ZQj7}X+>Dv`SX*Rq!`_=q}v zve8-wKtPU&dsGFpXYM8Hf6zCo^r|Xsa18TfYmtHtMD>T>^z@!8%ir{PorpZ;0Du>_M8>S3W1-f^FirCnH&du9-khO3}JLs@ML3r^}AU zZSGrcFygVWC;hGr1SClh_TRm93p*KjZ@wJR6%_p9@$<{@z9yI9Dp&k`z>Lq?F9$w* zX1A}+uzl4>o7<}ZxGx*hQLL{Kp@TkcED7w*A53A>tfx>9DW^F5*0ovI7 z3yVH4o$OE?$O-f_X@JA?vrP-=Bn(kZS@~zsYz}D5RpEMNn2GA^9>w6o$%lC%H4t(6I4D*>F%@|q7^hh4U_`?wQ~fi+ ziY?$_pqQMZAlj|bojX@RYBw4yox+JK8k2UkgYm|S1z3K)s(ZsPRk|MStXa+(rFS#5 zYdh3UoE_TiGJVUkFGZJ-xFFP7bx!a1 z)@Xp`d}sTL#(;8a0qKVSUJyY)*2S9IDVI1i8Y1cmQPTZm>`WY6NP5jhv?Hh z--kY+XMoPAnK3WO|c4@*8+lKd#!+^)4&b zC~(Td=MmeT1hqNulguReT1IqzRIO5-gJFL{LOkBI3JTEl*O-|l9rE7N$B)qA6I#L! z!6FJS7!Wy3S@v!s)gq_G03E9sBT&CH>68X4I9j-w{_xuUQNCXI^xTR9FKh4j&`^te zYEKkcUiQYqg34(@v-^G+aFq~7rd}TZoDDdpwz10WwB1|PLl0&jh71Fo1q2q@JyeN# zSZ>h;GcfCDORSd!VwC8Xvg$gD)78XRSs$Q@SJcyBGuF3OB!I-_?`>tL9^`~@F<9trNe)m*TKgcSHEd&rCggEPA8Ocs zvD4%xkPk`=v2i(?6bXID%i}!WDqAH|>hqIo_r?`v0>mjRTeI7hVBemPYWpIZyIr1b zoOvGt>mM*Uc>O-iDnF5e{aBwl@=ttrSEdPJ9CTCDO)GA(9sBX~VU+3)2x(X$9tAMJ zLIGIn=^^WQ^DMqs;f?Hqwhkbrt9|{J_>HO5GEPB%J`g@5=~iV!^s_B4SG)AKewiEq zNQM#An}iDU-|oKiTdBp-3s-wkp9%vx@7oj6`2SWW$G6P+{52wg#IvaRpvBzWfCARK z>ETJK?z$tiA<+gUEsJH-b@2x(HuCpg=CR_NtOlzG>hkq$Dlr>JqvFS*VsFizbhUm( zB_bQrddF%0kwQ?qIOHmZe-h+v61uskH$M@yVDkhe!_fmk%zo_9F`dT5xW(P(976?A zfyi^1Q@|&HxImGr!?np4Ht!wXH(E|1V#QG>&wF5jvduzZ!Nh4ltMj3eb((b7Pn73j z3SWV-kkc8C8;y)NyLXqO`~h0Fk+5aaG2%00IZ&2TwwuVJ51j_lKXUFmmw+bA;CHbl zosWH>M2`AL88JJllB=d-p(DEt9mj>-C{} z5(4?G)!c=Z`|TD)b=AG3l~uf*gLbC-^bMUJJY?P)B%=-FH6yp3p{N_t+x-~zjtFDQni zU->fNUCoMbCuc57Ws%B+NHV*lxywFEaVJAj+hc8UThM-Nomk@upVWnrfqzi`lFoX! z&LP10e+}@c!uHt5kZ&j8ST?`l#0@Q9SF(Vo)n%L1UB3-{SSFAZIj?ohFiw3@9HBTV zai7@`dj%Q|0Xfn;9cZu&oLYqpThowa)3gk8xm1-vO>&~4pYpDt-D9CM5MtX=_XHk8 zz$~DCK?q$tY*{6!L79)@2)i)YE!Q2{R_1y##X*lJ4E9L@-U(tAYH`2hgY%u_u= z6o*XUsc!U%V4dTQ(#kuCJ#TAU*Igd1x9*V~yCfkNeeSTqCXgn0Tb` zYLao`yBL8(wuJpi2@%*zRC9^7JHriPnQg~uF$_cVPgw-39gmr{>WnWhr885=VO2a~ zFFus|zh!MCRNfK(A2GXBX^l*QgD9=`apGXqBCAL%{8UC;@I^uLTKGhj3x*bo8;OY5HYbg@7c~mtN>}Y8T)6wtyxujGKA&( z5@ac&N?(xWxiSQo^n?z@^ReKNboOVnHSEj}XYV7{zvh{lwOSx$}NEq%92J}vy?s&;r=)NObn&RFot5JRh)@zc$P3)}Gf zXi~_;GL6l#w(Yd|bCQYfn2^Sonf7j%>o#$=!Ns#Q~Pc zi(I>PrWLv7mV$iD7QCMi5<#me4&_9+SM%FSIL>Q6!aAMM+WP2CGPD+0_|r3pmZQKK zLgS08Csz))Wr|cRKw%fD03N0mzZK8^ZB71&6o3iCWFzq=Y+h-PiYdP#mB3nKBU!%8@2W3t#6^SZc*f>PQ^d=N`bh>0#TFLiZ7=|MC93eURE4XCv-RG zOVjTT6S>}Yb^p9i0)N8yK|fx|hR8hk9$!MZm5$%;NxG?)$``(GK(T zucjegHC!11i>p6CoK;?ac3A@XPXM?bPb^gKTuti1{*6c9jH{peGX6wdV=^nBbDrMBofoz{lGt$nn?Vt0kk{N`5HjZ7`RekMXQlPK^!?6eJ-%Za|YMlQw zo2{oIMy2Y8aa#7Sr{mayu3Vfvpd%DYtE2RyC5IYzNS(Bkhrw$v<((BPCA{0q6TX_+?kx;nq3gdKuQjZHfv6* zXc7}AA)UKw$c+7HpT8b=ymWuSa!E~y%ROmP8odtvH2FC~L74IGOAyQ0uPbI5<+ZuZ*mr=X*Suk-dVAIB zYTm?GRK75dI5_X7CrQiS7Iq8zf05uWSyIm(Yem~8!t36UUdfVk7G zf)IEx4ayzwRPnhX#phZ1WEH$-|DdYh%LX9GvL;Lvj`wCuPq&0-d@Ww6SDT$&2UXK+xc$k1zT*Wo6%4Csf{QK@`1Hw^L8LrX&dWvj7{N$*jBy}2It=zUrkDr zZK^hHTJm6NI*pWMEjSq`R($z&sP6Xtm!pZ()5;=A<~^4p(I`bbu$w~AdhfDP=*5gU zfFul59|7MdE*+cDVC0U}Y~sL+4K`5*@}NgXcvO;k@o#MuB=GC#AwD=RCtYbdT$0n~ zCvQBIP&yS4R$PNzqrp34&X4UB!k!^Y1F)WqJswgVdNg`x-ji+&fiQ z=c6L0w}M_?bmC3@VvSI~jr()_0s+w6sn=(mp4k(Qfrzvvo3-<-?T z*HB&u(U>4bPz>$HUn4@j9jri`M9gb9I^5!9?AOc~ZQpMJJ~-l_l^-5T-$sZ#)sYH? z;xkenug>mbUHNF5c+*^;LvFhoXbIR-GgB`k6rS(7$d9&!QJmI(Exkc*5=M zfb;kc0d!c;HSdNNw7&+KG%B2DUhMCY3#V{i5gx?-oR3DLpDBGBTH9c|7YRHFOE@S` ztZp(9=0Jud3@GjUzE2S9(U!%H|pLfpGBVK zE2lVG%z-bFmc!UJVSeP6GOIr=`Wa5jN9RP$fba0?`Mw+~8$)i87YQmRxhTD3$jBn| z=T}z!dkKQ~^`$d3V>)-ne3=lyKbYh6nO@vIa z1~P#>RY-^B=xYp|cATsAt9d4U=AYMhb#Em{r`@9h$RUamWReJ<)hH2|cIE1=b2V=o zpF%z+!QLQw@ZG5MjvmttaBu2FUO%#U(OQf}O)HO<~O?^5*BN4B^-SusE5yNY zZn`5_`td%T;75aV34kr0x~NL3;oCA*p^?{R@Ao9kBgS%uS{eC`J_WX`&K0tNuSBOZ zi)1V-CG&u@%8aEIvExu{Heecs*PF3B~@c>-=p`0u#l7dIKt_(dN^Q0I`drl7I`TA8G6 z?aPQ&Qvr@TL=??v>H3#5EB)y=rb){>c6PAZ9VRjx-K~C_Ei9M9|ItCzY0s{-gYp-m z>bN50?*A5CpU~77P(!+&1mMEt&kuoT!Bt(iZ|GJ zlV}Wzjh*mZ3KMoD{VLXUE6dOCQJLgmCq7%15bw`#+#E0rB_gkFGCr)m=D@~sEj3!K6h1Y^5b!Q9*%fc` zd|z!c!$+B>!e1%s-T}ZiN2zvwO0|(5m(}ZU6$kI`R(V*2x*_m24r)ycCy>l9_<9I# zxB9yDGhfNh_r0TL;a#KbG4y>~6Lv85I}a6E(i?59&zvRZc&=B)snp|5N;PcCaoJk! zNk3l8+80FNPEdHd1OoF%)JkWZpTm+!tnL@TM@bscC3kIOa}jJmbMTj}RTYB7h(J{k zb{^RHQ6h9sH?s>OI0?L|I-8}JEz#)bom2f4aNquC4f)iZ%{njtBIK& zG8SY;#618e=Al2IZmzAX)vy^u5`KO!-eW`Y*a6KP5*VBZq)(RkVxzq~abAO`-$cAy z?G-q@ zccAU*)@)%E>pby!{QAF;&SOqxIkC41+i)rxpD@5UXFEfY>@Y^NtUpZXlp#8)8O7jF z=^|H%ss175!gCr=7bW7~I8Eqj%h!|%gQQ`*LKk$vOSm-Q@gcjMX5AU$cd|v3A_Oe| zwRJ8|YnMU@O_|_$givIk#qsS1v4-heM_K{`H7eS|7nyfX)%eqmJFR^WX9`d_(ES5n zzpa`-+yFgS-@=Ow&wEYW{P)INvIn3rV0m;|6RtoFd70mX_I>g8*x4hxwj)8G1b$Q( z&Dnr_{=!jN$dsCe&L1vcmANgn%`e)Zb9ZX-a~qI}53 zkQ}IHxON+Jy{_-_6*uRdn!%7#V!U16YP)$@w5TgnjXW(}ij3Oa+ReiV`ShC7RW-}? zU#JmrVku@|>69*_NI3^uGyFM)fw7N7_Ok3FH+37bFe3js^l{YwY^yTE4i&J9OvU#TU>rGNIHsz8_OG`Fd*PN|xMoBi*?Ui#<~-}zqbs&)0E zdk?m3%61aR)xHKidw6NxK=Vs>A$vuI3d_>`<|AUKjS@@$@F_>XnE72qe#2$a^Gvxm zfclF*DYTqX0d%hnl>~B=+hMYmS!=|94tJ~1>+B^U>P+45wK#8YJTj^I2K&QApWGCJ4btLSkTqP1Wf(`nUm>U-QBi~wb_AuN>EWPS#)iBBb<-zWX0RM#{j zco^4P8k+t|ntydJAtsIgoJ2mblGaHX%sIpNDLC4u3jGX8jGJnStcJnv$+#6L{1+fp zd3}Yuqj3Sa(N-?!g0D{3@W?q(Xd-tm5adsb(-~eaPCb*Yk?(frVT7?1tuGc^rP(v$9EaGQRU0PI-}ya8-UmMB~`hMotZ1{9dp<13FA zfL9~0tb^9v78C`UBLk+PExBID}nTrJ->1eQ2GXb6fl!fG52B?4Sp0w8d;Ym0Uxi z82s9haV^93v<~uB(49+qMQ1BOW^(JO{#nKa!^o1U_>^P#o3c9dWXBtxZ|+flc0hT;6hTg8H^ zjh~oIM{<@d#`(Nuw~9U=O|Hr-H8Rh|`_>5h7ahL1qC;84*RO43SWSP^kUCM0v?A*ROdCf*iQ4M7=qz`0Sgi#T&_jKXKb z(XxdhrA{VttK)rRm?PR-RcIr_gEz__?zMSoi0?*A!W@h4D=l(Cpd$eB(iH)PFtO#! z);r)I&4vaNeB<58ANq*NYWP1v=y=_Q>W6m=VK{&|C>w>NTz}Ny1(hP=Yvot=rB}L& z*T~{LFGAFcWI(ie#9681`93fqmAIZblcLudH%ZCBTj6bj*N$U;X{W;~hJ_A$^fQ?r zsRH>fxYc)+cLU=`*bMV>uE1woTYJ7R9M7=C7FbhxrUj6nB&(lORTRM=UW!*f77;Ab zVqPQ}S0vJaU%gX`N1#!x9�A=!D6}lCeS$iJFQo@(+~@NzF6ra-cya_{8q%6oDIL z;8=Lfg%jqp+n~SVVa%r(+ zvMaPqp_a2{=4K7Cr2?74)WTQN9jI3J{^Ie=gvvhONB3O+;tqpPXd3# zZ$8)aoO^ZF?Vm8Qvlja81U&UQZjC}KR7tc(x_3ip+j&m27ihd^3?JOiE2-I>0yw7X zwehy$!ym*`sBem1^mOCOn)D`%j+2n|y7&T$ak;+I{t$3Rbvs2@c_0yXG)C8(Os%ly zu(rZ)KpE^Y=-D$O4>#`Gb>P&yR|RPPsmbpV&k&I+X^r}z)c$_BqrPz3UlBV|1cPF< z-!p<0q0O^iMx8HY$_1I3PW;FsNsfn_IwaJ21=ee^`cS8FaU)5X|FOWijPIKN?@yIl z2-gSr#o(%(hazaY zM#aJPM?KKIL($PN%6G@qC9FpF_{)i7&a=W=-RO2m34VC8z(4-JftYku6VRk%5;QX7 z6a_*oGvVsAx2H&(@Q;k6M4NVi0G}k0&_W!7)wfAw-EA^tNf$$TNXR;Kr)QW;QY8mC z`5CjjJ2k4_j?x-9_*#k^QvbD4H5(2blH#Z}sFc8}&7(Ohe$6>aA3GWWnbvo7(&;%@ci$%nJV~Tzim-&Cl|1 zJrjn_JCaa^O$$Lpd>P@VzG~0?yDDIW%;>6@A~XS5D!4_wrXq2=^Cr^|@aY)Uu~G@E zm(9Lbj1ovl)25K$g;&hYmvIXB{)L;`dlUsO%1#O<`P#@9QOAk>`j!Y^_|M+&7-`rg z_dRK3XdbWyhxLXH5b0zs;XX2(7BxI0Qr=Vn$9w|RbC&#JrMVTn>}(L0xM0oEyuA!y zn$y`zd9#}XgSKDj#WVUX<`{<4)6O#Tmp95bwe&|=RV$Y};;g>H z}>Cv81twh~Cs0#k+U8pE)x`}8Cx{6XXE1V2XS)eO!f zC8FsrxQlgi)05eqA4GUxmD+`toV}uywClGY=*N^iml{{XtLS*6TruCWKaGH&m7?(B z)lhxY=(^u$#anmZIv!_`I+DNm8m7nbW}*%AI1y(MUpj?wa;3sn#US+Bokuf|g3G>t zr^yU|RUZ_ITj8I*9bN6jM&JNYR%pgR4)*ETY zg#I#@(i&&f{GPW-n+B<$5l>$DZkr&23b8^lLcv7P7A+X%L>hlB>z7!VeR!l26#Cvz z&lFB0C}Xxg#Nk$((!vTH~=g=zpDUR7@U93T3H=Z8-G7xK6r!| z*tep)6}EhYi;E(|t2~EatPecox#j#?p~8tMB{eb_qsfWW=gaIWkwn7Lk_L*E#_mcS zl~AXMGKK|irXb;qK}r^&s+c=*$KU=|QBL|YI+WfY2&KdxFk9o+U4sEQ`km(6+rf*t zcp#s$q0{Q1l&QkQ*G7dR1N!c$!0VpWH)Tx$gw6wpJiJ*owu!8ZXYZ^9Y5+L*M1|`1 zFRsT?M^?vl_|FD6fU}Awt@CfB%N_k=nW_kQ*fvtC2HXdac`XDL?Ncfm@I8Q^-saPf zcVk5Q>0OC*#!G>{m5v+eYc?p$-$(7Jo50-t$ioW1slDu0db?Yv;=YpR)BdDGd>`W@ z`A=yCkniXqh?@icXkP@x#}sUkI>xF*247`ir?oY#b@3q~)`8J4m^OZ%^l{cH-(1dy zzM=s(#C0k4`%wigBvN)R7YqS|S9NV-;=_m++)&~%zukm}^s<2}RxgZottk4yK_B+@ z_)A^Tc==rML~bw>1(jtrm~Q*aoVc3|BW;k@VO*o*a+{~9X7P+?Sxzdg2c*MF1-fu+ z-FZ8({*ej9tS`DRNTP*@xvp6Y$$o~fSF?1BPO2b91vCXj_dWDcuhN|H)XA;`{8I9< z+cO_?eBNz8`DTBHg|F9q#RCgu8%lLPFB6*Rgx;>wx zwFUL?ik{@Q?SNx5(63YyRaSMYj`l~Hgai%38$fei7`ZIfuL97oP#a;`#)Sr$UAsTB z6ev>QsqRe)vh&+o5*=7y;BgP!4bag6>A0DH-`ftN z_H=c;! zGyR&n?#x}zbKKdnMk2fQo=c5fa3x4*K&Fw*`rN)-##a1Y%pq)%jRHF=!vRF8_58}SH6gl_^k}FhaVkM!F{PeoTzVbU^MPn`S{6sFB3x6|d(Q#SUTg*#Iue+GU$&e>Riv*m+cN^)e0r7!x%GfH5I zR)9C@?JJdyLA*svKZQ^RDn*iI6?B}Ud{Ia~xPs)ti8P3#;`sQH<*781jjZmqs6c^R zKBZi{qTYJaO1ZkkxW4b{GgkUE>niCjXO@D3;LbX-6(8qXoqk1VSIcA7-NwU5EdczMRVM|dc^ z)z(1?HaW?qckt|&5Y@gw#X8Pc8*~_nEDP1WN4Oe8Ne&Qa0>|tyBPuDQN|FCmAjpcP zY(_qhLp~~|CT?cNpgdwBL*}hB>*g=1T`igPb(ghCn`+ z^#kbX?}_cDehl)p|Na)9IhIX@Aei5AiUkK6e24v8PuZ_lGkRxpoAH9l4obc7`EDnC zxUEF6dW<}D;t}$h3KNTS8rOe48KLd1T>@=90}xi9)K|A`s61YYNs8P?YT+JryNnb}!0B9j`Von!@ z%-Qp>f1d#rRS5$hcNs=cp;&lr&S1d(T>!QG{fYQKzR%$y;!wPlC_rlsLy2^)^bv-u z$j;NMgY=u?&Pbt^e7FJi$|~XduQOJ94?DNvf zsDTwmIbBWB_Na;1Fudcz;sfaAg82D#0Rs{8y=7 zmVrpJ%D|1NO|n@z#nG|&(jlAAWJh-flz5yM35`{* z`%@jT3!>;YR(=t;cb(Xh8}mEbV{RDC$f*~?l}w~DSzhpgf2tm?yInclI|*zZU0HaT zt}_YC4=|L8rQe+*$5*~xo(Q;UbTe@Kvq|IQ53!;W8kJ5k5>{gZ943~5I^VzguWwmm zzW2wBferF*-~3Ls(uD!NWOp2R1A&xrYzORRRP!Y6hDMBB-= z!e5_GO`N*OqXhk5*^MD^-yA)A5oqLzYPYtqW#a$c3fPm*sz04JV?Sk6ZW*IOwwelS znDWyPMsVChi-nKEq(JGS?oP3gT`=-F`D+IQ)my>rJSsRaXWYJd50TEZo zC1p+PI;fr_$vWaTj?<`sm`ZE6p?ThSYn-40K(6YE2&A-sTRly}N*uU4h2XaEf6Iyb zVN|%3dCtd^Okbn&HV9w)#TD@aq?YEGr6eO43G6<6Cf|(h@vJ&qCL}4)ne#SoyrJ3U zTFo)N4EEd0opic!u&7%qG~o!Vg!U0Nw~K$It}0vDKbVzzF0ZLwYn%K;%Wsm39MM2@)D@pNDe08QPqQ3yClWM}k23F#rgJD~ zWj3q2wP;){)u+HzwhQ!z=g5b5sD(&5)MI#o)J-Re-gIMomOw9f*o>f|n6qVS>j;WDC2>+nuHQ9_tu7;at zztcvSu$2gI!Akypn@iKOUQ`uKtK}>Wr{9N~qsk<25JV-`4?w)*XHqN{lbpewbh~M?y z+x|$u635E9ieNs*EY3^_$(UN53rlB+pevR3I;-~mYIz$2XOLF+}kgtj#ox9XWB zRNT~FrUj*<7nd#maW$zd7X*uFgRXJeOyf&Ttkh5D6JSR|Ohh3SK6;n|M*Vpa-q7Ae z>?A3$oT$<|A;Dfw2!t|V5)@%P;ueG7-W~C2Ja0A}4PQOc6|UAK-tc&M9`KO%e>&J76$IA;(!2>e5@5WHwehGIA+27Qcil_;jG2e@_ z2>;2{Ns?N&C*U`qvdTtWq6uB_tk<&z_0VB?I+Sye4k;q%P^h`yrS|aa6eS{RR^Yi; zQpMN@bu-U?gm@>u4%iR!<%@FxDz%h3Xi9$l72zIm^2> zoj<0j;<8ri1p;p&bThbb^*;vfW%IO)^6ijh!;*k&EK ztPgzsv%~m!g`&^r|1TqS?Mv3~rQowNtCM&}0fs^Wt|C$zBj8bS*u8i-2^P{}{Z?rA zYWU=vVUTD2N6c9Kp{qNz2LDcY(7kNiQ*u9Hop=5M*w)Iq8kcXhf8=5#mg(@qw2!qx zYWK4}#ty_7&}fF))B?k1`isupQ&4Tur~8&2>H#yEBa7FFu1?<~i!5$YurrZ*-`HBy zm--9W-gZPI%P%Tfon=V_g&F1^?9s-Bn=uSuwX@@MM41LZ4ci@aA8>pTTjcP+6V=T< z{oXO6o|*wkgZF{~U7UaspAWp&yU9`jujH5}F&-E$kIt2oZfrnK67f8`7B!W#E7D%z zrz6qZT+!W8>vT;+aOgCQx=Qmz#%UW>#^}LZbHL)Y~Ea5IZ7u?*hkSdRc^u<7kdn}yR{ zqCKbBD2;pdO>?7}uSe*j8VJp5(t5!Cg^vrtoW~)@{Ck($v_Mp-CW0h%^$$I3Cvsi< zd`VM^7Ex^CTf?N>-5KMBsV1|>V2`Ie7D^n&%AAcdtC*_pKYcI|^pp?}q%%2{5FoFF zw6=AiLCIz;^Y$Fxf^e347`rI92+r)+=lz6;3<$R-4i~Sz@v2qJDNi0?{aFE#=qK+2 zD%{uoYjuCtZMjAF<)r5rt)KCFO@Ss~isVuA(P)|AR&@-U)c8r^Dku0R3E@BpE1=BX zEvI=d9NufylmxwZwN!dIdzbq%30A|MmNvy?bDSo{W2(esa>A!d-5E=P&b+TfK+#H( z7?yB|$5ZC8`|!Ve)@4n>#f|xA8&3LVH2L{AF)}4F7fU^>c`ze2A|eG=}T z?M{J3!#Q~fZ{B5`rT#X1Yudf^47sE?C)}Farv;N2=!&kHQEjQZ-{%h$==rN6}3a-+i zYKGX{fF|P74Z;kKGO6q#ZtdqPQ(};-oN}t=8*703soi*sf)-^a;(zBnpymb0r0_!_ zEAf9)n#4w)lA|%-JWbdGV;3KMhFo9fe+zinRv}AvI^T(?d$5|-Lceg)1x z(iWLWL0C^}5<9CEt!1!^k+gusXp!9||5Abl+!ME?mRxv?Z(W*g-J>UNgDP3d@Yp)e z5Zrc4CqGGA|K=gYOAF*6iPn)skvk@5n}M=w%>NngJQGUL$s}>7VH^j6&LFS(YM~@v zM@g7kf0rS@Wp9k+I{e}9(pcbxHT5sXY;9unb3Uzc1jpJH>2DG;#A0lh1!&wP6v>BP zXADP7X%wxO%dmC_wq{llJ^mtPDPHW0wP#Kzo&VPzNY1uRR%oQGnlP4q%hnxn81<|b z9!hqqX*abwIM5B1Ofq*}4-Pw|k!6?lQ&(qEnN>kH++#G+oWs zOmcuI#UP4MTRkcEzv4Z|#Y6Q1E#xGDZIA^~+B0s#78=BMUMtb$UfmaNDZeXk&5zg_o-rT`bQ26E@$QqUssxBx1 zH|eRX4by;4ZY0`|VMRGsX;`q+-!BJ3#0Nr*N?OzTSG2J7Q90EvsAi<<8k)a2T{}^m z02~&SjL;-_RK*f+H~@NM1G|Coy?+snq;&lSKq4;ZW8?`?8o)B)8pgD{&Hi6aV1v!1 z!~pW#N0uAKK=icCMnDPF@$16xxy-!-$~0B0^-Z^FQ_wh8l&q-tYB}M_@_!KcgtapE z_h*o!o#*t;lj^X*uye(z;dP@!Lp^L-89643S(@~jRm~tv;dY>@GE;|1adn}6Vr`@S(Nr}LnK)P)mh5n|p{ zj<@R%{h*Bf094z9^{V!O5%=ERhqXF^fJB!R4mIi5O}9>;gG8dWlRnlE-pL3k&~!2f zs;%BnZtKZ|apl_~J-dKu{+e~z>2^Gx-6SBbJFH~91P4tTWsCOh2Xftp=x7n$#)+5> z6NLQe>gwlVayZ=DIDp>7-#Ml(iHXxo6Vh>mew?KEVs7V;=rnol=p#Lfp`~7`H6T-S zz29K)A?l=@(CX#UeWT)dc;#@cm0 z8CMStWXl!)m$pr|WdGdN@G>$Xm^n;u>-y>k|#f-*O~gIfqT(2!~caCcuI!?UN68+{WBpCAyW{?r4M;u+ays8twq z($<=R>@6OSuK_wSHbPv$wSQLZaRp-7#fDV0SSgZD3Rx8@ehF8l-aynSg2a(Pdw|`s zu2YWOLm>G3c-;k{J5u0kMci=k+7d6Q^Iy)6{UGWLKU6nkIU;GQb3ux(pDI+_BO)Zl zU#xaIkRoTHJ~8I!&*Lh@o^?@fx$JSs35PXtq;;p|5e#pL4Z<2$NRsAZ2i78Cr_ppv z{t)&I9xl}wuKx?GnbZEjQEB32>hawOwm0G4yQ7sB(KO?E?YUy#PjO@|Qz4ta%7q*U zWGXd6>@5!T?hPH_VE2wZxNDt%f(DcBo1d6_X zHD3TVM8&EM^&o{zj+{zWssW6b^R(>hkN?RIGIoh6;+4#?AZg9>4;%?`ecb%cOcWKW zC%5a)n+~6*4jh`UF4F|FHmQBxWkQ}pA3Rh{L2mR<)DwN zwbcd+pD`hyy8xIMG*naq3CIS&49pB-SDbB>=T>;&%(AV!r}%PPz=oK3?Khy0HeSV? z_|^GFYBs!e&r#QAB2R}!(rDur-U3do-%A8aK-pcnge zREfTZjMfz_^opccfOgi}+UfIjh|n44WEBHn?a2d7`w?O0g(`y733udD@aa4@95g5S zAbOq`7x2o&?u6T`XJbMGL#x524LbIKjRci~66na%A<~1t@}=W2?W0YA70!xY6kUo{ zOs5nbXu&nXQ6Tb>^FIp&B%Br$1yNF2T+RFDFe;425Mi?@rWF#~!N=Uy_ee4lgp@QS z%X>qNl1rU)iEwps^ro+<9J#i8c3p^1;oD@+H*6cP#{s^dF@>Eg|7u~h z?~aJ10grWR4r!AreDJAK-EV}-h?X1)=*bTJT*D*$f=Y}#Ox8oDdSo6Jh{Wh;ziSfp z`aL(+lAgbKTef!|i+d;H0&}u=k(k$e+L9Fja5X7`CzAifd_nEy0)M7x^<;x7brn-9_q%Y+CGiYAnP$)BO11IyOm0uVQ`N@H+tJ&YAtIAVqO#=?sXgP3T%5yWC z$eALR=6D4Kyx?5)CWK-UI+s`UkrG`rUS0S!A>z@gb@dVmb2IuVPAVi-#*BO)FJ=r) zxj8o6_|zp~Q`vw;iZQq0Vr2LGJe)7Um3bZQ98Lu4&QYBeo?gF79>F0&RlTq_5hB~9 z;cYwTJESnq-;mPlIWRDXAW2t=J+61bYDQB4vU@f+#>`jqF$}jgSOtz50yRCV^$oL! zI1VDzTFy{>@xXOUrP6=fa#(%`DSLGdWDLh0(j)PWuK{Kp-q9k;9=bRmavvyuhtA%) z^^`<+tA>(QFh~BkeIA1x)lmDu>=AK8*3)1%q<=xg5}7*oGE601h4nd4nUEa_1{&#M zEM8f`SpWz>utAAvZLB*Iadria^J!JC1-Z~XxN6%FCw6oFf!Y0Ie2^q4 z-!;4R_0YPruZ1Mmoayas3iS;7rQPc)gRvS&Cq$o~!InF75H;TUgG$Co4VLAT@(EZj1YSb;$DC6!swC&%KF>f0Pu2>-eMARbNS8Q`gZsB zLJXQ&DJyOQELMb}Q5Y=DJgyaF(j?&EQQb5gUG)b4yF#ujimI=w0oih8@$(p&5nLN= zw9W`llu%;ylNg&@7^JBlR}BmJZE27iw%?v++jlZdK+4$^77O-f#9W<5n)UoAlkvyT z9J5;CT;Z4RnGPO5wGv|2kI!K5Z3cqjxA&k@CZ$$w+J0ZJ>JTQmP$cjyA)1xt<|oZU)UfvQXfs7K-c-7>_3RWK}a@$u~JP;KaTN9J&Fc525kQp*pf4>E6&^v z>}i#f#G%RY)jNK1KZWmhW|6&ReLWT7<*Dt1VdL#QEq&{f#6kikWR&Q=Y!Wb<4K{Y2 z!rXmQjxbwiv(Bq@`zS>u`3|z~a=m&L+47L0dEM`EwQ5ZT)BPoI zx0g(^jNV)|Y#MYNU;%P7L4~N#f5Us4I)od02sTaS-D7KB_(9HC%TiC?oGoCfWK~== z>kJTC@d3MnY{=!Y-{&QK3y72$?cV@X4~zuqzekrlvV>W*?Is<(KlljdhAA5c3ERxA z7k2z{d}-AlS<5Oh0HTtcybDyHYNf=PM=6nkHR@3{TvfH4G?D$e7gs!Z(p z>%7z1V5FeEXEZR%n*93@8E=xYT-LGWMG_t(8Wr_4(~_BP)(1x1 zt8?l0(4~Z&R_3dS|Hj=4s8SKjxWxqIIJ-Z_rw)JXMMtEQ8FH1+{jM=Aey;rCez_LJ zg$jeuX$wvc5k*y$HV%diKA=u3rww=l{Z}wQ1f0=hUGP!V+kbv0#B`Y%+yfBndIT&J z5jLX|x3Tk}`0e2m%=DO~-VL37AB6k9cX7ObXI)m`4Ibvr$ABSgQFkD~;Z2)nMmA`t zTO^%=6QI_l2^vMU8!I(CLcjLMF*ql2g=CofiBr3UylyAy&)?pBIhn|!z{NgvJik&0 znrBv1*%JQct_iEni~Qo8wdRTx@}1MJev`Y>@+#0?0b#_ zkHmrr;<1_hfE$3eBAPN^-aiouUXgC51~9qV8Q&wO%Hw)Vl@`&9A;DW+9=AXlUo2OM zUvXIv+$i%Rzj3W((3&|T)jA154f&=G?tY!#p>`1~PPO-5#}ty65}2@Miinir{g6@K29N?Czcp!(PIxw!gx)fUxYLobbzTpE#Xb-P56 zF3KUqkr+veXjVBe*+6(gyv&Qp7Pd5-HKZ>R(hsQ_$dsNCCM zn;cgSFIZO#3IfymMnC?J4^T3kX}C(pNae-zH(;$`E0#7h>pmyCW=AT&c)X+vsw^Q?tc(rGWOfZ zQq54d5T_!{u4&BhCZ!6UGD7F;=nkM7nYfH`p%}a_FyF6W>K|AJwxk_ib@_S3m3|Ez zs1H}K_il^2Y_ATlaq1IOKsOyOao9Bgw2{xAPbYZ#TCTd4EFFup9fCxo)z9bJ8WdD> zp0e`1J#Zw`p2_4wFJ-qn>{g4sH3@gxsC}VKAW5Nr(*2=Dj$=ohO_@fMTkqFSE(H6Z9=c|V%+jP*YRviY~bni%E zNA@?i;{ygg`GjmUcV_9FT=7m;+buZBLHpQKlcZsAXgibQ808&$(_Uh4EsVWi51w$)}Fr#Fb=eDV->t+E)$gCdg1HB5iz zXFsoc)jF+Ims+<6O^NXPgWd75AADw<%br3NAk5K)w##?wX*_dMnpAcOLeC-)5O2Qd$mEtu@zP4+-@Lljfm`}$ zV!on14U|$ISywi9b?zS5E8Wzr$fuxIN8Q-RF^%C{9OB`JP;FYV;#o)`j8XbBRh@4O zcqk_eYH8mraVE8V(yR?}hubh@m!ElXvV8z--6YQ_?1flh1rPGtL{L{3DJ*VlG12mG z#{3A8&6G_^0X{)P>C1f(cxY=EzS-X0Px6#B?l16Le`PD5-GMB%6*o(|C&ddnY4QS( zgyMW~UiofJVi1yhjO&|fy?teIv>h`&Er~rtalbzhjBwcX4lu6FV#$CH32Vg%igAm#ii!DFxosC|`xg{T{xC4g(onulJDAix|Pdp36<_zxHyt{V+( z?Zz6g-)Q25U~bCI-&wkWZBB<6t%K8oDl|!{sG(i9*d)Rpt3=v*JQ(Ve+p7x*B5&_#&pRoD0MAki zvyOL)Hjkt<`uRdigN~fV10rC~vn{B6yCVx^=@cF^?Mhi!$)u*ooe44;*=M9zMhTS%y^8wa{xjNJ-&?~?x5djjID{l%murZZgFNFf*Zeix z6!BTSmm#;T7F162^#tld`C-ma4Oj1lF89()90!~w|5jJ53Eln`-wep3s;L>iz&1+= zF~L@(JMV`K2QitJGc0z4u1zkHwcL6nK68nRg?S=mRBO{P7)2qjur+Eo5n_tFi9Z}$ zm4~A`nCuhxyOf>D@N;IR9g(xh&dO@74y2AK!Le_Di1B8y0)Ozbdv#-yEWFFt|mB@Ja& z<^9z-+{y9P<6=7H8lBmcpH#p`Ql-7x>5ilQh3xOB}OkFhGh8e4H*1g2&wa1zC=y<1IoP{$SN!md`G6D z8V5i|-~Iv;Wn2FAN`pk#-vG|UVPVr`(RN$}9p7&VbN)3H1@-Ml=1CFL%$<`|{;WYT zXp45^3^Xz+!mjaj1+3ZWhr-U5t)L#=WQD?j=6FwJsE+lHDnPtYhIOuRo4z-CDvjd_ z*1)OhiK4wa7$@R=QKma=Vd>HPx2@emZOiHi)|SYXiPyMHwi1Y+Rzrj{Q;>db2Z$Imhf-%_aMmt1lm)9pN;~amcRz;%e%v$xL z^>6w@VfnU?jvQ>XQi)X=zmCF>wDWG6w27mYP;I!ExL3nNCyn#2a$zSXXj{NuLOIk| zcfH0!EodxtyKHdKrg&GAt_)t2;zOGyY&Gf$A=GM@K^oiFR}KfKKJs`5DROB-8}Avg zS4b3IR^_6TO0NB#i@8v-#g^(-s9_Gtk_e7Y%@ArW`fwA(bws&C7Dr3oQ4s!L$odL7 zw$3ws5dj+BDa^v{UW&8IAKEZCrX6Z@^q)vXwl7~h#h5heA4fbTLPhCg(3=hv%nRMB zrnLK2HLw))0~!`274cB7Q9fcMLlQhq9Bv%R!r~G=Dhc7ORm@Zhj;`4;n2uH_Tjoc6 zqeyDMLq0#kBx#$!zZ>3W)Grx9#2wP`eKtwkG4rctpLp6-&X&Jn*qhC$9Xivbu%%zuxXUXIeYe9e-07iO5)QHlHD7^61w@NTUnIUv6LbMPzp@Ur_kHzM@Ggo-O|V zRfwJifwR45!{a#imszw+*o4JC2G0zvbGncj+N6Q!99I!HsxpVnfNn7W?4K>KNTRPl zz=rSBzmR*~Hd$$q-jiwj{c?zZR;4Ku;V?^QS+tijV4WN61k9xq$P0oBv?a@tco~Rf zeGcznRu)rZ!VDsS6lC_DL^?;j`Yhx((Go`AUQq38`Cnf%OU1lzmefJ5L%=hKylPN#ydE^Wt}ul3WpWy`stVs?D?sop zLLKiu`=mdNz7j%h9~10WjnNEwHO}?ZW(&`e)_N-;-j02ALWAnTCf!Q&=zkOR<40gL zs3^P{=b=OOmm7W{l+^)MjEcNE{-z0N(8Hil(ny~)z`il%DK}5rA&`MAcumIyF?EiEqMHi|J); zMcqbE)ep%-(ARuxTwQZf^5dm##biYX+Gzt1=2QZ$BUYuzqP{xxOZ z)QCoV>Q|4P3Z#${RBK)O2jx7eHGCpIj>uLN!N<)nOq;(MR>-gz#@>Q`y^kHI=7n=Z_eO&QAz<*@9Hp03HqfMr0TO)pvYH=AI>5-O+}l7ML)Uq5 zUyu_PQnBNmXK+!1VCyXk7(Jfk1#6n~t(Evj$35s>sd={Pf`V97s# zH`n49Q{gjmM;$`D{T0AR(KJ_fkHlValO`Cw8dhJI+vG-$&RJM6+ofeg&DD3j0i{or zSvVRTz$)yr(kqIX%YQiB78K4-blpEVCilMQ-<$CG3;lp{F!j9^7?_qY9~T(Mi)9yq z5FzkybKgw+i7rLh$ahcDox#+3TsPnyT0w%F&M-w_A9=v~Sk}8D&v{>I);kGDjVCNc z%1QR)Ee!($guC{3G5(5`IDRq!8s5-IT1P8ppT5S|7eSwBs`oO{RTmn%By8&KZ#vBnj@L;DisLFpJbSJ@w zU`WI_sRcGYRR!ZMu_@J}KMT8{@DwW~mCb?M6(0o0r}ki4$5RvjQDH;Od9Im*jqLoX z){bfxL1PsW$u&b0AT8J?RqXqXvq9L!M*l|rIl(sqZ*#)#30$JM460o{-LFcqHRPPQZFkuD>MtKhESlez>5mwSb?g&tiFk#CJIYgV9P&1vUoRPaPAR8x-7kgJVDE z1Z6H*5F=MX%a$^HlSb{_*km$28@^WMxD@F*@1-Yug7PQPeHsn=nR;>z;&db=X%aoB zwD)00vhi|NTCtT_$cjm6Z{*wBpL|b?>2Xp7^&{2ikSl4N!U zZWh`IhgT79G;)FLet>CcwQ38HrG3%5YaLtEvbSf%N8Z+cJj3I~qs^q|L){i@Fp#x@ zj+naEFlF?HEkqY~KpDuLIqNvX7%v|J?%yc*U7_WA%s%8)yy<#)gp$)#X}B4nVa(8& zFp?Da*QKyF8zeX-Fp`xWnlZ?EFGFXe-Ti6UBeu$TJ~IIxdts84=X z8#UPj%D5klpa(i+qwBymJ~Dq0_)+wdVou-z z&gGuvSc;o^)4g@1AI)O1*n~6BVY{uRT2g$)%85=xa;n-33}oa(t4o;TU$p@xYH6&# z>p{X7AhU}q34v6tU1dilH!=>u$I;y`SrnVTnny3A`1iVVwVDYU@71@WjW(FWSi2!X zg`Mw;N7zch>qwAay&;6&)U~z7`#_7FWH<;Qw6X0C2rGQK4npIi(PNTi-)zTtR`|;C z?Gv4>(>=gRMMiLv&Rz)ukAnKPh5)a!Cxn4XMKyh6+wLwE38}HJ2?XUQ)A!vY+*hTWI|IK|-G)>vFl&&vS*MYDCVkZM7RbDpR#Sw@~2_%a=I9fJo9nNqjb ze{HP+*Jkads&B$XUT1)dEB{w^VzZMOQ#ypQ6Wm1;8jOWcbwn$_ z@H?dmF&2gq47{b3Lpp{i*XWxjD2PfhOc0oU4^B0~yGG_mGBFz|SfL~K=?llUt0Sc)L(H>Zn%bb0_t(yDQ5y*$!2*3c=Z+2>X{F%S z7ip1p2|Ab!nV=y;SBBI0x@ld=8$deHUsLGlJF8w{MeP7dyswmdH(7+*SwcwUc!05!0hoftY0b%@Zz)2nKt3db# zv?um@QWZ3ngp6G>TAL_Ke4rklJb}*^5kQizg0pUi#?_>77&H7UYBdFN$Yhj5gK$+1 zUBaPxLB5ZX4|N$G1Bo&4(7K3=Po~il#Zf(`gKHln)Xk059Iy)=TTy>&^^z#E7_;5hS~rw#pqv)uKREvlhtqOq`$Qz-h6HV zOF*>0RzvJGW{LAr-OK?bTky{Beno|2hKKP5`ka1)swy!%?~|nrPihTwY1Ye~ArH+* z-ZX1j(`$spmH+VM4Uo!jwzffHXwOyx&>`0B8cQoet3BhCYy>U@;z#r*erEUtx!^@~ zF2@r7L9FXo^ZeXG3Y;NUylN4uZ6KJ=7J!MRn8al`x&3ymwEG|)82~1n!qS1sGcS}= zQ$ChpACV>Az!!Ec-EDAen$hNi$7@JZHM{aNB1Pb;`ck>O;>9N;JF<4gcNg5X(i<#6-~aJ?XaDQ_nU9Ea!T7fOY1T~z=?ub8Dtg=1rm;!4 z5L{=vl7VFR6ACaY4D{w4Kn7WS*dUG2$Rmgc&G+6nb2mv?r^2yq>FvwQ(4P1fW91Dg z;-$ixo~V-TN!TKm3+Yo*F!2_CmQ2f~LfbI{D)jm^7$OY<+70Ah!1;!MK)(EetaYM%)BZ>v>H< zSt)+{y_|Ht$9^k>g`>sL7X>EU5QjLc%c!cWbR_C%GEmZ`2!4?nj!r zKj4_nB1D6E?w3AxZ{LK6&98JL4cjQGk-b9W7PW6kiK8C+QFg%11QFJU0N86I zrdywQ3Bk8mtkjzWe(g$zFK43(ijf?SK9z`uGf0=XKY6pz`rdf#HmG2zRM^UAXK#yC z05%2FnlEZ_3Ym{urxXo%O@h*OC@v+4_qwaG#Y8{n-6P|~eN<xu(45vx%?ew4(lz%pdm=|%3M+bZ?Y=KQm$!Lfek ziPb$eg}887Gb^;n?}5!$0EoevYJ(xsD>f&cBzssI-vqtlG$K6Qe{s&mSC&P)e~F!^ zD4fu72MKQ{YX8y_;_RCxfvhZqZ(SL*|5Coz1XbSmW3 z4{CI#3^967K@^}#&e#hKk8jg5ufxW464|j+{}5OUsG-=T>*soFVaCM(V2nPJXubk+ zIlAY{p`($D5;v8~H}Ex+dnGprr^0{dm)Q5ca#G;53G=ljQY6IxE{67-$xacTbLze& z{?q0Q5AdXebHj!TM+PP%GDM?mWjoBSoPa&+ojdV5$a+Dt?uaEzoam6{yqlhzwwxoC zwWO;U?)^EV*Hoa8umf$W1(-I>ih5;~m6h=Nw!y)6@Zh0W=JpT`tYs-bQL|%HDqWzu z#rBUiaHW?Z1o$S;pH1Ni4YM>EQYIMgqvx~7zi$$F%gB@e_fRhBjFjDf(gX^_;;#w9 z{$(A!@y|3D$znT%*=-9#wkAi#$mY?%|FX+efjP0gN5 z+j2cN?j8TR2>*#t23LD4lgqvlF~6{PXWpgyL~YGY4&MI7Kqj=`QsOmNvaqnRDm?XC z-|FM~sO-TH%NRB3>CDA3TFNI5ehop+<3hIGztD=A_2RvVI>9oax4B@`!>oZAgt zdhWNv4IzYW`ekEaCznXtiJ=SW5*&bq(I|_mbzg>O#XHa%zS|!L zuu}k??MM>gs(59Xo>ELCF!Rq{^5h)`XfCu-j|Y7Yb2c3tVpsBY8)h zt?UpZ6X1a#2)o+ksvHIC;^c!w;BBIn#xbAS&OVR+08wS00O|(2)lVE!7j7mcT7TV= zHDp74L*|XjS%qk8bv>Nrdg<;->3y+9qfanGLR78iYc<>pH@07){bv2;-iR=2iO8BYEiSVnCj@s zOqjHzd^HaCadprX(Y%kYFH5dRns}3M*x(`atAXUaXgjf*cLo|o0<_;@rC<=n ztKlGV@u@%EiCFLyJ__+K|y+-^+iEu zVB0WxU%(wW0H?q!a4p`NaB*N(*Pp^MR6cnfr7a(h=+fzvp8Y83F9Czm5)0;P>;xMZ zbu=_Tiy%|TdnF{Z5nS91FDD9;D;)LIHg|DBMo}P0iv)2fNm|Uy;|d>#k3_aSGC&Ji z|NM7js)k3NXv56vLyg3#F7U+pJ_z$9S0XUwW@HGVt`*S&9@L+>BsQ1mRDim#apR1a zHr1`Jwy=rIfm%?Ko<<>^km{7v!fx11Ltrfi`u2mn)T#T67?MbS$FnzyPSPq$+NC$v zt*hkNWpS?uQou`KQbs1KdZ9&#?U9vM*wQ4#lRc>|$Yy%m?sIc~W);i2lElQ!iEF9q z9n95mY>L2vWD>OQHdD{rKn8pJ0lV410E(w{W}6$QqjTYj)+9-*i#PqQ{?1?K0qNLA z<~IZFm-Z6`xv_6Lr@oS?_H0Z)YEoMY38mV(R`_i*tEn{#Q2C!s`=^ysuu2aD>J{s{ z8A5fh14VA462Xqt=Gc-j%K@*IBg$bhPAB)}V7@A2;Bj;`1*(*D-4mf%k#y6>j0pw2 zZ2a&a+)*6)Cy)a4h>%z9;LnU}e#Mln_5@PVv{5`P5JTy!@|KYokYuN&Qe?-7%z&{t zSbqqPQ;hr`i{&wHz)@WP{DREMb8P#PoP4cuq*Er=E~ZnnxcyvZss!tiNsU#geG!29 zH9uCY?vm(*m8bJ4pOj!!?qe$%*LWdh`o9&9i(VW!(*)c3U{O$sUgg3y7`n!keIxN{ zW2bP{mTS*(8gU6&3TUxZ<(idXDL2v#7f3?LYKU za4xugCkN|i>!toi{IpZX5P}x7yS<)7qsQ&65!}qdQ{ zi1hl#Rp`#`qFOD;Xq1#_-6j1zg%IrWb!sp3|7(wtNEM)wwBF-4_NRfT3 z1Z;rUQB?}BE)jf10TO=MdS*#$3#HvBm1b0hZR0K{)f((8DzDb0a4a6BdrC^`4kac; z`b9IL5|R7DK>`p_p>C~3%70#exHWX z@`zp~<8N$0dNff5b?D{rU!#Rnkuggpcb5Xh$u4ZUnAYWB+SgN3vSIffj&9zAdEKWU zs;i6*s@c;9v^qfn{71GUYxYrEM|M4p-yJLKcq%Eawa=A2F?8!EMB3l46Ln|A(YXc6 zEKqpwN5$4fWz;;P^bp%$&WTabCkxq-TbIoS(wx9aTVLNGIq+_fG1|bTy6opmF=;My z+xN0PT96ulmm0$|Zm|^WvX2QujOZxs^c3N5{OnOg^UX|xAnk|=N&XD8dm*T9nWVQi z>K0Zjg$<02&WjyW`U`|5EGVT#?zRqp-u>~z{$is5Hp{ck8P^gOc%@7(D>-Q`IY~lO zM~}tdP#^~rSnVt9zl@jDUKQdFQ-0f2Str@V=V{N^Wc^3VS1oXhEg`Xy?_DCt((`>E zG-OD)&Z4wmqOd4tlERZMl-&abi1ri*YClzasjgA~^PFMY%YJ&tPHZ9}Dhzm{ACmK7 zPvO~@kWCy*kD3t3FS58G45@mF*evF>4H#PZwi{+~gLUNz+WJ}_-dRU+I#D(*t;r%? zKb+TyvA1kE;-hWRpr|n61($N|9x0GSYndl{`-9L-;y=Lm$eWlSz*A6VvOWfC9xPWU z7(n4<;QH2z^4;T8K8k#=YEqW9sDMM6up>cx4sr?!l)$9hOQ@Th0UgpP;-z8uHy)v~ zNR!7SMqtAv9CMKJCMP~FAUDlS3x;tL#GKNXPkXa!o;W$#k0%tgG@FP#wnPKPL zSiq)L!J#U`Lh2SS`?Mwtyz9sB?-DEe51M>lIcHB+p~JIl=dDp87HQ;0fh zWF?%$3QLk9Ds>#4gCU|$U~~X|)R6J45V0p<@KF_vAm+<&|FFcdtYS5L`(DYJEU>#R zH2Z$1|F4B5Ymk8Dv2sO|)V=BGf$$gI?Ji##cBVobb`Of>^rC@!-`Yb_Ogvy)Ekkx46~(;KEc01rRBx$!rd} z30kVDs0tzfG7^wuu)u*(@hOtQF&3Q6ZI<4pEvH<=-@89|R0O*7jE(XD5R8fPSys`{ zYwGSF$HC(dUJ_2LLIVQ=*hRj<;u*oaNYEf7pFTRUv(ObrB%tZ5Uza@1f0CRsbZnR# z{A)lEL9)()4W3kcoKC`)OM_w+ZMf-_$cXK<6lAP+0jqpMwGJU16*#WN%K^YzZW;Nn z|G_!<*lPohUC2}8>vI=d0=w*^Z6%5FEM9%8mw(Hk>VLM@cP6pmahbDF2;le+l<@|V z8l`TS3YLS%=<>|Z2I}oW8z0ZrfNG6K4i87Epa*Jq zc{F3XM!3tNTLgUR`USEW$Syxd0_L_LZ|E~!Q>q-sXMf3dHUKJKTV zfcLibGd(duw}E>>c2)J5R#5?f;Z;lwd{{>fAwcDb7ie5#2Jz$;GpGzUcV|@S`KV#p zJFu+FkR|kBKm1`h&JVlM{QKU}RbZwOf+q$}IVL;B*0eI(>YWx|O-@Jl0hzvrBQK!$ z#vOYR3)39pAP4}Fpw+*37*JEI{JH;&LsQHj5wpLrjIT_Up@Rk%%vaUqrt7%U0n#t! zq8s_Cw238Y=bLpGF0^f@N6Ms0r74GK0ffSDSb)uzkd7PcCv6(OrFN>^}Qf zv965R*s*6Qq#NN42WJ?z*9RYU;{Pq!a9DZM7;>}u+AsmlfgGFX6a9~&ES&W z)vTJKP$Dl}u%icEl|YHX30|HlnK_A*#nCC8E(~2zlgC!z#O<`__yS7!-OTO@W~x z;EPiot{!u+_SsS06m_$1-s^oji$up`*QL3`>~ufth3Dm>H(lE^JApp)Q2Q*BbLNT zIwIc}$LG&$DeDh?uJ1|?ynKSZl-Pa3-eGOn#Dv2^&C%EiM&77qy{vS3gC3($Jsd0> zV2=o$xEzbA$g}Zd>|Fn-DcI2*^q=3A@_d=e%QfP!s9zp1rZ0Ai1%Mn+)vw0|;F_IT zhsc0zV%dU?P8_B!kA^=$++RlKml)*pwWLAu3zvE#f&2ISxU9?&?BCe%;WOf<=P2ScqQ>?y7aG!5NgH3|LBylB%170b%ORpB0_G$Z60XSJ|!sMtD9 z^QupW6V)3~?nMj_L}Da!R-wFG&5rLGo>VMfK}W2%7Wmj4&3O4v3HwVIMqY#ShhJUH z&v=H_`CEMwca>`Ba$ZXk|W6`^VfvIrcXIroIuRgHqMB}(cSU+$tZ|6EKY1rmAtKHMN+o=}ye|IfcZ zJE4kyOU1kj%%6<)>b<6^=4B1GBK5V%Edgz=UX6uPA(cO8^we-PXhQD??|CxI5Bx1a z&^P8xowewq1OkQmv7G$PDWDta%I{X7>Q%R=+7f#k3<*em%5`&gxzBkq8RYQ`6Z_+1 zV3*T=?1?w%Zn8+II6Mn1ugIy6$IBqM5D_yH^6dIHlc@@XJP9YI4rMD5IQ?UINd|Qx zTc4OSW7t$U!QE^|Ja{iq-1geB&*nCMT^grkUp4Y0JWOZ zMJsC}2~&K#QZ$}@<)1RtW4~N{m=mE%gO-BBrz8mTxb^E-RORQU7yS= z^j>#Kci$Ly@f>(yb!(Yk-xQoJz@>hUHej7g7y8oP`g3s)Qb&7wXU4~9=WmqMC9mrY-Wh{zC9P)U@F_zCdlUFG14QfX4DBETaH{8h zt2`ZB6ual8CG8XB3(>&*G{-2qm=mX{AsWUNM+oGGHhlHLvfo)=FX3jzEdwQ#PVV_Xsg$UZd+RAC*HE*OOczb1TG>Bfy1_&tDf3RRAOQ>Y>f zg|)2+5qyq0l!M@NK|s@SlgO_)AIE!hdg)X-o+oY{<=0mEY@Z_v!Hp(UET_ zS;3eIZ}Y)S=`Uq_dr{9MNrA}?lqZ71vZiNj@O6HZgKJos!icn<&o#`7U_nE>z)~aV zA#N(#=xWUlz*f2QoVVEtn7avy`BZaV<$3M_rj4(J8D*caC}CGcUcm*st^R9us}E-a zMjm$^xxIa?{k~)S6r;WZmIoh;+ZKpLjBG}FU2c`>u}H%{3`NljFxZB`4hTxLRau-Y zJ*B<_I^4E8`QYOF@k5N?mhMrEBJ?M0>!*s?N3kWo6pE!O!7V}Rf?)t++T*G1+3H6k zESWMh4e_Cy)vU<@d-A^`1M08LYgV(WSl&&wWKQ-H9-FqEkWOjjTlRARR%p|=JdfB= zaZVRKNzrL+rp=Wee7jgQc2jdd#1_ws0|LTZrY>kE-`UwCuwpmO&MBIQI66?aS7om& zhDJ>IE5kyEB0r_k`1G0t`mT<;g{>(TkQ0k9jvUogv0c6X?(Od;U5Ih`H#H5aoZ71b1&k>bz&Sr6c`Ua2vUEK@Tfb9uMiZCHWrX~#y} z0!bYel!Ty_GIa~pe|f@(HeQCs3I0flLUXmBB9;qsqbNv`-j1c%s2b)4B!$?$(?4mm zkuIfQ*x|7LykGzk4P`0QBqwG7EOL&rg|Ax5=!V1?2YTK3Wp?NI<&yP&1XqH8prtj^ zsA*I{t~26nj2c-r4-3jk5oh+lDN9bdcG99Cr*G};xZ7z~7E33`2F=8D>}t^-WsC7%-a>4txU=+cIz`9G2W%{-Of|&PGdMrwD)2 zDf4r>H{X+5AVUJ@Ql3My|{05v~>yt3_S93_!Wb) zlTXjLATzG``yl%7jIL>+LduyXfn*IQWZ-n=juYr~`wgv)?>sfBS=nVAFW;S8yKCg+ zj8ys;2%GsdZsZt>D&UlZ>KtX z!-?3!FZg9g7l0K!vHxGh-7qCC&6QsFYPn(41)eYisOKgXQclI$&L}}s;^f6ZI@dao$fv62Uionr_+ZRI zj*_Z?z7)ynRRH7Tbv>)MoY5;hGgv*$pY!h;bI3oE67nQ7Ldm(|dSCKFZk@vi3e-2O z4vRj6BM^NLPJky}V3lB>k&Ge+*95}S(HAckW)&;Rek(qsS!%1c5I{4u?xR`#a)~CV z3otPJv?sB}uzyU5d$d?Zyeni&_`4_{3q(Zo^Nq%4$V!s%u4NDMe7kpU3vZyZ=cm1P zN@j%Wu31TjujiOhhC!BhbWh;f%!WE>3`W0vi{_`m$D`xS4d~~Zc9Fe&|8NBrz1Ih_ zqG6odZflP=W>dL{0d#Yb?fGvep{*hW*f zPoI!3g3k_i^&r_V@iRrfT%IMKR(r8d zt(st2p~pj{G)~BDOKiZRYst%`rJ}H?nRNx5R`S>Xub)BAwx1uoh(Et5ie6?EUiXw6 zfo86#^q+uJzk`gSB%}^U3cJWI2VT>l3iEZw3b)^Z^~7MB$TMF;!hWUKuXC)pGGWnP z`*N{uSFO33NZf3a3|JgjLsY({9o#eY3BIEu2-ORO?_H-SV>a# zy7h`eOzCA_7s=QjLx*Lw+hy%fwk(v{7w70wZ;k_2>U#%}ze${2Py-=*!Mxo-I=VT) z`VA2_<(1P=Hpz34*StSe*R131is_o~zrTblS6Po4aD00rS5Y zQMk{n%=Z6^e9W@;P_;ItFJatb7JUFiW)I=o_<ke0E7IIgYKnuc+1TiCmAj)6Qb6zNW>c0EjtR3km0lfOd-Uj zIIg$Ea3;m%8(Llq4;6lQ-(~y}!g56V9g#i2e-;E(a>YQl;2U{+G?JEs|cqGU>|jB>*E_Wv_5ZlyC{a+v1x#d9gA++GUEG8w4uElW}f`@zJWtO?Ya({oVz{o-k=HYU?~%{ZUywn8%wA1Wu*K1A8{g@W-CQ zH02E&a&^gqzNIN!N!}!IZer61#x5jpj{8LJisU3Km7WNy^wM(x$W?5f)CcZqYFl@p z%x*;yp~Z+Pr1)x4dEjO;HW2^Tg)hD&?4IpAmb}C$n|gPgHn<9&mnabXb8%>&`z8J| z5?DHks|+&Y2rFeFR6UERKAPfa=&tnGV7Kx9(LUtJ>~s6VawH<3vret&1oc>St)5?P zy_`{ZT{bTq+N>d+okaaOGvl)DX$DHI5;IK|mUzL$ZZR$AH| zO@0~=MNpETFkP1^JP$i|t*DO}e8g%Kb|-xsa@c(HLszagdv9FzUB(D6m+N#HjhP53 zZ6X0#E!sGB){h2!E6MNcvtyDCj)c$)GgQPNpVd6^vMDW-wT;+EgK@g@=CEjV9Rs^v z0?(YO&!a;Y1{d!Vv($;*42}sE+Yjl2C+X(|6oRGdu-+(>$wS^?!m5D1J;pfLVZMxj zxf~MVlktej7}D`lSb(k2rjbB#s^yzF?UJ++Fx9z|U!V)`vG%4ZYPsgheW_Ok`>4;< zL19k)36G{1&2y)e3mY`(?8sLwn0uX>d>A%%HcjsQy>z2H*EU+ZX@pUC!EIs%kA5<0 zW~umIdFn$UXJ@8`f_BZPB@~|VvA%^3ww%5BGTUnr@a2!oC}ypX{rE(~UCg7xkdE#x z`Lq}rV2&6?E9cbgLzb)37L}qsI_t=LKlv7rQviUf#+-)CBh2T2EUDi9_57%tGF&}Q zm^T8q-qwkxRyxUVZe9c6Q2kSC@qB5cSJ|nUkS=`&V#-G*-4mWDMRyZsrI0V;Ar>JZ zjnXXK32$25cNgK6%P7Btmq8{f-eT1!yWQy%lO9uc^^S}~1<=zQpZ@fbaoJ~Uqr4}c zr=`bMya24{4qP+(RF;6CJS&Z*_MGGPKiEJs4d)J~1ime;P7)5W=-iZk$#*Y3L$FQs zEG3;mu5Iv7<-D(`u&)|(q5ZCF>ZM&1ob81GFpheUj%l|!CkBFlyZQPl!gMiYS#eYH zQ5m5mQJ_QLCFB}dz#6;|jaAZWw!+*IO;{+_{IWIzaB%*92r7Yv25wFe#!b6h{^#V( zXhV6pv~ghkLh6Ao0311tNt3TN@) z%oc*!ovv7d{wJ$Be)e-kBnqOGj~_(rjVN9%7Mc37!e5Q*c<+Vx<6j@O!* z>5Z~U@qNZ?0Z<*ynm%(Ro_o6AeRph||0ukbU~)l*qZRQty___*BZkTP4TC64p~1ZauqEXBOYSP+-YTZEC4)!CjCw z3QtAD95Dmh7R#%@8L!EvyzKN|Dl-$@B;uk3o1N_)?{X2@jdiIfgA{-UR>VC~7t%S5 zO4f2nZSj14%#pWqS*I27G+|dP7tbqxh{cVZ;e{G+pB0#C1B+UJ809|0>p{V?yXXJM zMh@s5@uStl3Be0?xQGVyrUHj07oj|gFH~*K9wsWQ zV6y}i<%QtoJlQA~SR1%O-`=_#kF0wbm%T9s@K2=gsC zACb2=_L`PNN9sp_$xty`r(9|PMY3PX!iB3P!>5t>RNE2la?A@RFT8x^f_pbc_7sGI zxCCa;#=#i^3|5Sbj zL-4$0=N^(gUg=E&KfPgA(ndk%qF#b<-xW9qm1ZUu+v8{#jA1tY7LV7LiIrYBQ^|x{ zD%<-OEIsQQ*y;QOH@+Y>YpYU@1h&L> zl%_2|cr~6KV`w7?+zeo2So0Ju#UxqkyJW5;U0V*(ADAwgAyb@gyaBuhyK0QU^U+Mf z$X5j;uBLa&DhsQ;3Y?>moEESG4=ktIR>4Oi#%!#gOIQg}?y!nzkS32nYv&_F2@yS| zaiMpTfvFw3>>slQQR}Pt%p7*F|9I4mP#mDOYb@%R;H20O#PB^=NK6$?%lvNJ@*fnu zuWl69$GlrUD|b2M881X=+$~{rPrg5UmPg!6yVzr3aO)65}1l7A=pfBCxT4FL4sr zyGFE-bTHzr%z7Uj7ILyBn4!R-bt?TFRnIkeNxaq{&Ui+K=G}(??=K#*;(Vt+Y;GaE!X?WcfFF@}!0;=PLhDZ(%P+ zTaH#;Xt{cBvjGr)lyC(@H&iOCoA%yq2xcxW+w;-mUY4TY%mV>MnR+ix|Hy?odD2@C zOb=K^b=o%C(b}m^U(c70Vy`)4cbt<&+^rcFR&|#$wj-|6^mb(7+n4??xj$s;AkpxM z`47E&6S4l2>kC#UJuNdQyf-mwnD0$DLTJA>x)=BPy$U1h1lGEkZct*D$GFv*uZMIL z)^TI^GBX0;k6*knHHzlr3$GwqFy+8V5LD3N#1oqI=7p0B!DTC~6}<~-U-C&^=(WaE z8>>KQ!&^{m8c8iAuB(s+W&lsPZIkWwT!M>rjv0{Vq@T7nQ2}m1Ljz90E+uvq(}xud zsbUH}HHE!AF^ws=y46ELhHGo%lZaprAq6}Idw`#Qv;ssChjicM?c?hs>1at+)W@Fu z{J&X&tHlm8S7(q7aU&Xe1BlhR9?k+&J+ByxnReu5nX$7)K$=F6MMZWbE=E1 zD|5>-c&Zdsv0!nL!%sY&v;7H7nPVz9=kZumK$B=MGOwpF8I(!GR&up1ssAxQ9{(QZ zRU9F0O0<((>8cndb!o3|!N4@G0LNnP68__y8r(w`R67Te<*OyO8X`uNfd4~UG!+w< z>SedTL6T%EyBs1gp33`p5eN6#BY!`0f@x)7M^yMT0kPZ}3E6+CkfkfS=e|JRdj=f- zSlL8&Hvp0W%96TW1q{slK;tpI4wza0VcVL?@2&VwL_@ZlpcK4zGV&*Z(y@IC4ibli zTqJm35rH_NXa@9m`RNs*b#;SHX)oup5fupV0ov>T>(qVILb`%^>_8r8f~&KWS2Hy) zqg`}x9oxq6z-pLjEdZi2W9S4wEX*n0_?`F&`_{6JA5o0TsGWma)vTpO1W$@>|ocrwUf# zQBL4e@vrf+vSn8c62;)s)zeT0FMv7pdQ2jNwIzyE8f2;w6O?nm8{|@b<}|q<|11mn_8C_lndyS5ND21>_ZQ z$2i0m=F}L$@03Ih9ra?fwv9Pz-Y%O{#mu9|pgKGAXef(U!|$U$!S`kmMs7UPwbC#$5jjNDg`uCEZ3CpGMbU{FQS$2wa2hUr-_0^Hp zS|WGM9<9~U17hgqcNI`8OhTIF5l8D2Lrt%JV5Ctpmi6@23*bgoAcWAXPy@PGCa)Vg% z#9d>ub)y{}ShKZQG*JU*jG*rAg?s4TBcCw7((hm0ZwcS6ubVHLiJIV+iu3)W zcZna7(-E{ZC%Bo~($P2psSj)i;&Lo1Hd-_ai(Ovj8%`7tZg5Pk-pg3YR+^DETLsNy z3GqZC0!yaT!p2v02y`j}`Zv-LeP{HE`QLWoL0BGRN z*2Pc;p#Cuc|L0jeCjy#t?6IRqv7jF}V_E!^syoG)D{lUX(6Mo@a&n}3lyB39g;w~V= z#{Y5i1Ri~Z6&>M?#c#0h&|*B1#<&D-Rc_omMbX#M5&5_lT2fqy(gYU&b598b5tBKxZExX!Br6ypRjB#LRi+nx4nushQKoYyaAFhfI5fze^Pe*p zFY3yUPXGIKb~q_r+^;&(^eL^{N`A19J~T3(9Z?1J@xg3`%yxR;>1rh+?WfFfV!l=> zVj?A9t!{)YfUL#dDg+?wVdp8gUAIJ+mBfe0!>>6Qz+-!V@_UMN#8qu!5TDmmHPF!K zt(4yW2t$aa_aC9x`U!q<&f_}by|`})Ph0-iCi%?*iw)O`vWq_S_%Z9KLb^(+cElEy z-0hj|5Co_yh5_!;fuQuWZ+z1VWqE4&jW!waU712cHoF`qU8n(Z*sZd&@(;Z1YziAL zwrV-A+6*$Q^2Q`0+nbnS0ARUbePBgj_qtsYopP{6b~$2iU?7b6X&f@w{++()K`_Cc zkxI`XAiZ!9bvliqrJ+!6tK2 zbeNi0>VP)9rcLj5Il*EPu0wtCbAVR|xd#MW!@ow%+&yQ~qE`|QI7saFrMn%-T1Xyhu3-Avd^2){Wfj+Vhc;@1Zb*6%Q=;@N25vs+-7?kRQ%s8MLoeinQKsZ{+7 zvY`p5?AW&g4lF_ugcv=v=8cPHwMD~thZ{f4T)x?D7N46>;{T!rI(Bz8<@&QkVERJE zbuhF@->quiX&AaGD5iE%K57lL(@F3K@C3I^@upF?PQTn4@NGF`82^dTx$8KtkpGq! zS^*d2!A|vd#0IMJyBEFmbqw;4G}^ z$U*-Iw~LFa6bK4J8RW|gJyoCfi2&WN-AD$H3V#n1miUk9=1bb4^{0yBcwUP9trbd4Awv51F%&Sy03?BOKWFw-iyfKJwh# zFTCryuVkT>i~3+jl|w6x1C6?t{Y86Kui0MWgDhm-Q)mDoA5EcJIvCT|`$uye^9G{~ zI8+2_Er3;6K_vrjXkHLhcr3g-I{Y)>hNLN<;b82cP~PjbLUOkfX&Gx>3QK~y`NPi{8!yR5^ z?lYunta-n7G=LHI$wEI)>^G@G8#I7N-6V=C)iFKFTQ_ViDDTvKhec5P1ztELZ(ESo zx~u)mpI6UBwr#uCx%^zLR&)pTUgPCbSjZk|)U6Q=ylPDAKIf&XI7oGEKg`Ji%8zsK z-l~lM@|MS&l}Zu(RU=Ec@=~KA(r-U$G`X|W2MfeJGCsaIu^clt?<})B zTLA>PF$W5v31h_XYt=zp~$yveF1tgjMpYK5w(09i@g4<8bp8C!$Jt4yP449!?-NU^+ zzZa$(qenqr>_pLJ$wEfQBDv0BG0c2>2~js4nBb&@441Ydg|3RtXLX!Wo{6eExm(V~ zfr#H-AX|aJikf!BW~}Yz?qX}27U_~-REWif6%Y{{@nHWs7WOp}9kD_@6R~HeP7*j5 zA}@jATo1Az8K$L+Y1m>909BL#C;;Ind-@w~M=Ioi&FN(hHZQ=3WG7hTj`?ESI3V6~ zHQWOr5~#_rO6m0PtH;S)V-P0xVNKGA%J-#v7?z{cGErbRd_;EDY>hhPv$x2*4{tjQ z__9{b(m!;o{OoV4{znM&5y#<>*hN!9xkWr`=~xLNQBj*f+~~Nk665QzuSqK6{-_FE z?=m;^q6^?ICrD#vg60u-Y&d4%k14Ze6DIL;#7pasZ9FcRVB&wxEJApn^M(G3)6{m( z_tquIL*aQSfQwaV2X>rFTz$t+b*Z_qK+6X+vYf&#m|M-7nKuTt8xTzy)jDMP5prk$ zP-7y28~=?FB=Uj=^>jqV-<*DF0Gf#rI0|(VVH)Mm(Gnnbvh=_ z_?zT@H!*XZv-CEo66Yr*+!S^#H7{A3CLy8yl<_3y7)OeE>^b;wX#=^}yFW@?^N>>3rR@`_sE@DB%e6z3VGv968z1 zIS%~cZ|mDJB(x0E{dwLPmPWhD?>m9Y4kbC^rpWdO*Le4&30Hl{&f=qhL_a2zQr29Y@^%2pbx@-&#@gi&9kh&t@Z03mRvsA?FGp@{Qe^L@$)1~XG*ukC*-S@W3sWV4Y@cZF^qF9`Q|6ZL62WaIY!x=jz9 zNUd)umQTuyZoFQ8Z)bUf{rln~Ehi+9Uv~EU8Cxg9Tj0cyx(p-;wRb*;*=*a=ny}+V zD#f}(i!Qr-&l!73?!LwoA!#I_kJt$aEjO3fTFfPrrYja`G}oaV#Oa+2hP zMhiWH5(!L`+kp!w%*XnhyTl)Cvhji#uO6}P1xSCj6GMslC z9hRGJ&Ezjxmh>U$_E5bPsZ7%CkR*r2S?ZM@~5NX;Oaa4xGG@y<2 znI`-h;)p@L?iL4c_0Jo3isbYD{i~?<{i7{i zn4P3H3SW}&a7!x20^(vaT^TdpaV6%x%P&#RUfv65fW<1GC_=18hqjH&3z>t{7GQ)> zi!u;)AMSl7iA+;tIO{Tyu(ZjE`z+GB(t^i3CgxhibMF)+CQq6E=V*9=hhsQh5iK9X zecik{TK$DKxFwnxrM-7Dpu?~#pR866K64e1=q=1;AA$4}%<_pn!x~}kQT;Y;71rKN zuEdRF2GV?f4KO3?()oAB?9U!cC(a`2#@o6+IR;1akmG-p;UI8G{QlbGwHurNplbu* zO>M2}DrFJZ%G~#EYYQi)g{!ke-LOs;&^_Svm-WZLW8GYV+J-SZs*68Mc$L;-&jb=P zcb-v4e1QYDT{HDj2ciF{##wbgXB&cz3Q_$(nsVV3%oTmw>iG&#}7esv1+z00f z&fI@p!bPPIy|8_V4HwuF8azsfR!OcheYH;ytbX>j#g#Yf2b$8vTNW`d+FO$}BlSM@P`IcSBhZH3ZesQt_D0u2XU;G*s<+RT1Rv=;)E%Ew0PiztlHi z*AQHx_&oab1Lp(d<(klD?>?-36EWk=Lj z7NM}W}! zD{#W3V(I?{kIY=n*5~>`FY4o7)$42^oLapkW#kHIeHF}iYq%IE0fJZ% z$*uF4DwdADz;~c)Gago#vPTQVZ04lPNjO&@eY~M+<^lB%Pk+QZzr5612hz8XihJal z%7Kku_1D9NNKUvp>pw5w2Y2`1U6a6+HT8(5plq zq;ZvB<8&uXPWqN$JTb)cZo26Mg|V#Q_24O^(dnbe_;ktDo|Bt%=XVW^w6Zqn!^$SGWfAA|e*eJkTx=%6HC){kJsh4Pe`l`;%a4SW+ zAhdExGd+pW@Ou7k$F7O2vOFNSsq~~Kg`peYOny5#Z6}2oQaVw$n48q4dRe(lntGKd zCis0m$_tSA?Z!4c@h~8+Ee8xbp(#B*AHykOx+MkTgL5ms;gKX{!5T3>d~gReM|4Td zchEvLYinj#Nu_eI$DrG7elUlDD-B|F3W%qR2%kWFWikoutG%Xze!yhoA;&9)}Zu4$(VyxTwFF z20_Hu`PaoyFD`<$w`>JF>QWN{OaWmPKw;8*-YoVmQB1_~^0s)2q)5GM#PfwcWOH%L zm(j#b7B(3N4?qy>r3j#NOFZ!xUEU@=fD81X5A2YNcI!fG=)EP*H8yzhKfH46p3TE69d~HkYLQ zxQt^Sg?UoiQtTPnmH}bnMNJAUioWs`vH_(bb}v&} zJrl50j*(HVjKCM@SA1mwW0rmBBt`c#1e=WR@D7gAt2UDYHj2t$G5ru)#ntIJ;~!|m zEu?;jtI;A1(y|UZF_VYnBuL8ZOASt}n*??0lyV>?p2T3t7V#%``^XMxC>X$YFYq=M{Kog)1PR%oYbuO>4Zn+?m9Ra9dS|P zC>zKiX>=%c()4;tlcU!Wt0GZIn~S9w5pl(RK{Wx|O0|xMvV_UsYF}p^Jel8s%^G*Y z0Uu+S-l97K#6ce2SxeIzpNieRgh`8NDb@26y!!nLDbn2?(~MRyihH#M^%6Rd{9n)E zoZ-_KeZ6@+XPR;!hj{@>|2eVcTJLM&r4fI_XC_Dsv5%VguK1pynPhT_g@+l;|DpBs z9)=6a{(OfX_N^JIq5N}gzLd*yDc!ZL31OJ-6p9@+7yc{x53E2tR11-)=voD!jQzT; zL+QTGof=vp+3u!uynx6y|Fgt|o^z3?lO4#vsAA!t0i8hq+l) zepee^JjY_!*-f+gbMUxAwRc1&=8xsft0vA!Gr|1fWcIcpRZMQ*)J~hbS{>B_`2DO? z+D5%*{EUETK%5t%7xDm5H|%&j50QsA@gRihKDt<>+-!Vb65F`#|BAx)!;a*300-;dK;oZNn249kUR=_=aYGwlgi|n0zuO4e zEk|)EJ#jAk2Jw@9H(w=xP~4w5=(B#|}cCU*A zE9?WZt5^uPM@}}1z42%}4lcjDr(#azBE;gvujN=vxibduq~)6~pM_%hYmMu4C|rhz zI488qOd%7m*1O2JHH}eL`r&2D_lT5=dgro6iIfZL?&sHLFD3v2FLWR6{{a4OtoLrU;()zlYC(Am;ivI*0SX zi^ZYy;X>arj@2?ejzxQKBa7TT^TRG*n9JoM^|kMW-qke>0B(InPkR=oRtRq^@*kL@ z+O8c2TF4a2whq=tLKvijfJjo-;oXi#BhoW?3`274Ljzl%fQ3h}z<0o|GaKsv+80!{ zg;%RpjFJZ%_6H-@$l%M{*Vv8lpO9a@mH=&DaXWY|)`;K141b{lW+NDIW~DF0kswdm zB6B#k4X8M6Z)Ac@LQT zsZ)J0RiCYz)`SwVW<6xZi*>d7g+>wd#kdRMWEH9hwCQ%58YbJP^*Yx{u|jUhfPr$y zlqr!E+juzf=W@2>$D(U8091+X44+g!Niw!b9Lc5lnvEysf0rs`>6&mG&)KfdbwHqr z<{Jj?4^o~k4ak3&3#{{_sFmM-0ER2Zq4%=Y9~-7f-U`}l{IB{ZJU~A;R5$|PIUWx6Pd;SID|11pv_Hn zxQbWH08O|1E%!0T$f!9y=z~J^IN}h>gDLv z)27qgzgx**nL<%4V<`e<{)sFXjWkg|#shlHJclQTb7HNrBWFe18p|r@s5@qd5ft)| zSIpx3Y;rQ?A||6}USZS@XxAX=XGiKJhz|TC%upwpf3nI`A`|O7%!vax0G*9<%*acA zVvSB4it&2(h3MUOwy%#3eR1KsvP&$JB~TZ2fX3A@(W+0P!~Y&I6)NilRGIA`na}{SREz+=tUqezo%<}QV+mi&&n-; zj_lc79=&wXP#;27JSr8{nYI_gAQuDA>8b+bYgj|?r72-HxKFBol3S2K-Lsg}!6Pbp zi>MhjYZtWxVg$+%iLdof*iD2%!jTC`-mytHQVT3+imJ$|@0wkBVHMmz;xTjv;#=U` zTxEAoaN~WfKl)t^K}|{sm56n-TRd19CO{QaxAh|RIa7^>O=289Qzt|z(+j(`_>P@b zJI$^OVrk^nM-U*?29U@}r4B2@IT&=Z6DM|arQGDZ^Yd<>R}zs=xP#S9JQZes z$0_2yor*PrlZ7GMP`4H)kWSqI358TA@c{v$cB@*Uj zeEKOooAsA&*O5cTZ5`q7hTHnFH zE_3Y&Qg|fQ2krC{0TeOr?E3>9U^>$Ru)d4Sjaibh@J-x6fcKCohWjjcI3hJe*7U08 zQD6fk2V9}TnLN~E$ho)`fM|-o0LzqS<4Q6Pa@CWLI#`ii@*sz!{+o1_%lmN8Im~hB z=cs1;e2|4{qyJY7L!st+3eYQjvg}OV3lh_`4q!TtvS`=>E(#oI0qu!ew2slr5FST7 zo;vwT?iM0)dlpoJpXI9w@4Ck8@HWPS&gMhUWOI^(LMT_slW&0O{Y(It3Qa$osp$~t zSw!z!LUJ&6*VtJXJ8LZ$N?gQQ|A|=}s5`H9l6({`L`WFIp9U!xMi(^SSQq(m zl{jLT+SLi7@$c^r%to?x0e^C~F9ZJpfNS-8ut)sw!wJcy!emTM^^Os*2-k@EgS?^t zm(5B^V+xLne;C|e78!b9R6?kkfFQ;Zf*4`%E`Bwwq_B;OlMZUz`{stMUhU>KhEWFo{eTN##v;GTG57$bJYEib;X<-x9!4yb*z$6$5x{_|9$ zGNf}Pv}{>-F4FUsCv}Dp2cjJih(nqA%-izE=+CyU%&j%J)^~dItZUtC@h(^0I&U2m zHoyxQvuA{M^ioylKp3ZktHc26Os4HJtO6m6D_*O+{F-doSE|p^!WjdSTQ>;f(IAU{ zuNsV=3W&RQ*(}mWd7|CEf-+w17A2_~t@)f<2(swKAxvTMI4WrZ1qk0*qPZTTh{98X zt@fk~{9YBLCO+C>jHGy(@TcDa1yRGm(AcSgZfxX+*|mjUZ!_lsP=^5P%}|wYe0EAS zMn1AAJm=SsHUpeC`+%fv@9`e#J@X4?!-6z zpfkLaJooQulk=c!E(C{PNNq61=chzUT6-MXmWTX1!;!gbSHYAO%`yhmSX{c0o2qlohZ{#B++;Obm*BwqR zo_53{j#RXDovcuBOYo4!8)Gt!sQiuv4T z6dixQBZ0UM26m96LZM^4qvW>Y;55?qhJq0foc^Ymu|V@(qIf|xn%Gb8PXFJ9BB3&o z-doIL+)E(--Y5#G2n}?1VxwRLQeGX@!6U>bnVYi_p5Jy&9qsGRyg{3FDzNK-HfMeb`V8dr50s_$GC6!+@a`f!B3AZ&6J%AQ54%dENk!v+{~?p7hBfR0)B^K z6Tr*92LPxvTuL5!_zJ$lT53W=A->`Rf6nhiAe@{C%R)&ufYXRN2g-p0N34bHE zrv72{#49=Wa$exoJA!$ETvc{FHHbuA!~=i0kdw}mUND7#Plt`{k0H&qjY)LHE-Jw( zk`Lm|oLXs^-EHR=1^GP2(V)rGnnb=cuSh(i1l#}3W%Qg)V@!<8%`Ab2v^x1Z66<}) z4)x|kG{JgE3T-%Hu4!BY1@x|a5wj-$N}Du^1pJ@u5XMC>nGY6>t+wFpXBDR7ht}N2 z3;Z(2Csly@-n~>-@nx0x3CQT7uj1Jl*`6ZeZS=A(S4Nj>Fs+I&xk9P~o2k+rRV|?= ziIHB8C zb8+_x0eG^-P&Shq-RWQeop$&tQKCrMz!jUb9SUNL)0hZ_8p~$%m7#`ZQUvOL&M{nYJJxorUP^yH|Et4rIlp-QbnVM+*wf~&tbWNtIq#}@?;Y(@ z2FDB|-SRZ)>iXkHATtkM>gbkDZjDjccMA1(iop#V{KXEnL$xtZN@R@q*26IeL({&G zR1&QEawWH@WNodap_ryHN$7UhSHLil5DTLX;G`^wkTJQ+H5hG-)hSgs)r`1Zxu}rC zB;DmrTzGRwSPSp}tB~G0D_8AmQ*6p?7}tG26CH!5JM)Fzf)#!;hV=@s2p4T~>0`1I z()mHw6{;*5AP20{0lfr9@E%kyJJFV)?Bm0*gOc%q_$d5Ae&;fhvw|yA1uXdvS}!Vb1~t6qgJCyMVOCT|lWp`)efk2)XnOQ8N;Ky@ z<4xye&iirCg}qBZ@IetzZ4oQUQKE$f+t=oNlqw+iAZ>+Kx3BnU2O5qQFH!0XJy#np z85;fjCGP7Ye?mT#v;x?CN)yijASAUb7B;j0H(+9h+(2x05c23PWmTj?7^$=b)M@^J zTOUr}p;>%}>>T96=YB>?U-arlRr57fHB3j`hz>YB#)(g(iviB@5EZETiZ!0O-NaKts z;5jtHco{mDh`9=L#?wP9{Z%cbE93!`Q-ATC7Dl%>j>YD|&t-(BOuL(_HJVE`z3Ki# zl1>3jJ{3AtqPPo>8KPDn$dKi(mtcwi)cF(ytB$kF^Nd!t@;`T(P)v_Nl{3D7Q^oby zK)C9KRQ||IBM{JkS@f{wbN}Ks#shp+8EK)(LJdZhU)yKf$XG86_X`HE2z3+MONk1( z{8~;1_Hn3F7Abo{IuGp%!PHOqN~l-)e&{pY>DUSfFOL^_!D&*!1y-Y>U(?#;!6(2vMOkLEHc+h64IokM!F zpwC7kTdQc}N;mM&|4pEeLro*ZSH2XE3(oDD0Nd^4e(RTLfo7{Jm=66DE zYkH|{=b`O4vunx+2@7_C;VV7^j^@c%(zKGlV26jwmk@~1n1mVPkB?L(gm88GG_F(d zJ}JrtYX-!6H%VkMm#eARRXy3|NMel)7{=9PzUtUdP*7l-IB(^U$Qbj#?cuAkns?LN zGrVEg#CsFjrKOAItV0{J&*($$cNQwsQ!Gbf5coCSP%uOQixD0L{XoUqUvDCUija7b z?qnOoeBDG5&ECz%_#hm`h871a`ui{`6me?G^0aDPl8Zx2^+`WR^z6^d2jTlj#?e?i z&Q+`_q_l;fK&n<03almUuB$&4-hJ4{k0zFF9{k0uY2rh3j!C`>SS0af5c~uKMTf|C zKv8>i2h88lM2UmOqigkD_t^JlEYM;4>-$a2QUOSCwY6wk+oV{vbDSOC6&=<+7H^h8 zOU_`9s#Xe4H$93t3c$_Mip80!fs|Fc$kIYI^)cXPn^TJ-VUKiXb))>VDK;Jv!RxmV zL*m?0-CpLb71!1ktU@If9{y$f%P*@>?ggR>u3L-`TO=$epfb4*c zz@^2-NE00rH$?mV)5U^q&dI*k5o$I3wHvTeWAwwjpu_HLIGaA-(>Mg|;_5fJwl)3qH_BqNv`}{oFQtR_ zb%kSWPDjFoQ)s0V)axvYF-plEUeVCW2>|B;ymXm9@mN(MRp~3JtvZ z!ktaB2@g6p?5)8RIPl9=x>D^P6V0j6?G5Y3p4~;G&ctaX9%%A86D>K=%SU{DvVr&b#B2G zzc0X2>6MIWYR@nr?`?Ub*NOOAog3zCp~}a-JzzGMOu)$6)!2IoP7Oh9-)}#Ma=dR9 zVuZ(zJRgx>U5j3@oof+7kuKNx;i*{CvzKSegmi2DY^>KT3etN<-DmKf{Gp%)wWpb_Kjh_)}B3+2C7s z{UOmxVPLR<$mnlr0i#w`$K!A?3)JFRp1C{;Yj3lQz^#%2)n&6Jek1gY1Y#Z{6g>|% zc?@Z4Ac^6BKYl8n-ov*QHD!a~De$YoOLz5{Xj*rrljzidD-?ui|7Vsjn_U5Q?TDy4(g;%FZ%tWzh4Q8s)Bk^7 zhr*hK^&UVFPDN$-XT;y6b8~`Gvb{VFhEcDwaTL$B+Zob;4^|@7Qxt)?cdb-e0Bv}X z0ZEnK->uCZi3^rTU8`aM_uBLA1*P&AAe7fZUlk~rn- zJNAg|==FkdZ(qtsd#-as@(!7|wIwm%+U7}PAlh^aUhq=|d1LXXCZ_)0jR%otdDI`G zmYMt0{t^L3(m1*7s6P~NCb9TW{oT}WUcDIkLTk8ddzl`!^*gH_5tN^M5Q*-RFY~3# zhOSFM9A(J}wz52TV;wo8UwAauY>-x<)T#)E`-EMU8y3v<>?!IoRn0nVMb`bAf_v?N z0w87yc{NQ*4Hk125FYbWZxmgc;ATUSXw$GCwP?<-31|$U+~<%fX|J)z5sli@F)N2( zW(#D=FPev%j6GNHj`txh&x*{stT*KObe{Luvc~`YDrlyPz+=^tWXIb{m0182FrqF? zKAfrgoOws@Uc%ZQUBK=DQoo`A&=e0TQ(5zV`{U4ZSIlRqiIpQ3WawGj(T4Btu-TYh zd34B-$gsTPEu-~mBT)hHWs1&XDmt?X=9vUFvx$;F0;QxRj+&bY?^bnh2+^XOIGPl^ zfmnaE4Hxi>SA-Eto#GHxI}iGx;JR@H)jiniU-_E`=qAw2Np z3gQtwEZ!&U!FmWWLhBVW#r+Q)|0_v5Nj9{^PN`EzBYx5a)4d)@eLH$< zfGs?|;g>eRAg|M*LU{wbb}`GgMi1Um06WreQsZ^wC6wdZS%D0$@hRwUOX(|yccLU%FTpLtKY)^mKq<^U92Gi zR8ra&eTqx@O(0cX0tDsH3gHt>7e~!M;83K`ZuY1R)htFm=}bx`xdLM!MWm8ab{8Wq zDYZonee}fJY)PH44_WMf*OZrYQSR zW_qLdnd+q#q7qdV+}jG<6HFUggoDVn1;N z$vz*#ni}(HJu1P9fUP}>U&zIUNr0C&xw`)=&BiJ3W@`P|-T2&a=D4B~^rt2xu8+DX zp7>)}*{ut}Qr58%WqIwu_18@DJ{tb-wMjhCdO)$ME(X|Jq>OPyvgU3Y-5bD;Tu_U1Hm{q-dK+F(Sw z4%uWT8;gMBzEV5z201}04cmdZ$vHCfWY^gmCH}j1A#rKYkM%A47f?X#y>#;^6Jr<@ zvLKgN(-Dri{`8i})mxi^JI|7mIw4&uyQ2oBWq`A#slG+yscB2J4pmp@)7gV#-APOA z#3(uJZqktNgEurij<;X_>!LpxvNBTptI|N%($0??G{uBpEqW0!1 zXJ$mg>@|M@*2M)c#Po!FN=UNdw`?W4L6@an42$!+JMm^BVen34Lvv0TDzIan^O)fb zBdmvTT1PUXyA5z1TmDpG?@-~t7S%mPNEu+!DDjCD{MWZJoO71wzWh*p z8_vH0Ml!j!eVBs`-^yTbEw@eBjQcw^=NQ5VsIF1k`TL#b^z~AF{nLu6g>iJRkCPAU zpJae1iGF)qbm3*4C9{~m2Xy4E0UR-=jz(O7?VX9Ufx3b&v%4Fy{F+EnZB(J_EO#+{ zV>O-@o$-H}o`BF>3uV#!$OrU(Aaay1>zW`!!IgJ(8v`X71|UMYUv!Sr(1C(~Qjtf~ z`7Xm%59^s}zA9v(rt-Fow9dBg{!3OM8(mTWYCS_Dwwv!y!EB--va7P%QEm&HXO495rs2nfO)=~rlerL zX?w{BN5)_PDsiJSYh4(^{cf(bJSgPICi{ERl}3M!mhpWJd@0o6c{Q3^+yv}PCalV) z7h41oo=po|sF@OGK8&3KzP`yUIT`oodo+emlY3p}%%~gSeD*x6_1j>sgQOIHeIBSA0%b)XSA&-gpB;!wC6ukvAZ-S4aUR7W3%GD<`j4@l+!b&LfMRTRhf3( zlFQ_mjtF?t!oY%ZqvEopT)hJ(c}snBp&8Go*_q5QXK{w-8qOQy$TTlq;OMpl$ABCzUV;TucyDnsfDe|R*| zGi#zNc>{>?60f8Qb5AdDt@3I}7;|$+3REizmM-QqHydXvM0sCdOD3Lwc(F(~n1x>|%BT=yAi7Eup- zWt@b5S6;kFRQi{BNOB>%)|7e8t^YR|xPg@U{lmjP?%qNQQtz!xXXqUKZz~q+EfO7V zO=;)!H+$w9P_BexyVBCY6x>pIL|23&o6x)6au*ko0?rl+0{O&N%_v&7or5c`ELua|p~>iKCBk=}9fcw;-?>|F1#VuB_UtG23n_qRxym~f?F(P*}C_Q1ma zC4&JOZL(QT0xL;-4)QqPb-PG1Dg#08Y8?L0KUTv>DO&EuJ_;+E+JXoQmB&f=7B~W? zjP!tt{*%s@>@CrBOT=gte=+RIS!t}ajdOWjlA%mkpGtLl=NrQbiE0mJSMAl#|N zpq*$rh-k+@E`&H0sWEc&wxF1sxiA_t3`J{=35KC5;VobPI+r1Wo1mcIayZ46ziTxjPa!293=fXz%$Et-jEB-I)C?CRA(rM$oY<~}_xYSu z{%Lc1u$>iTCt3kE_U1AFE!P69{6&evW?8 z^`N%?)Q-?}oFNdKmRSLUb=5JO^A>Io^4R|aM> zLvEaKDDF+uPj>z=;)$eqvY+vsLE@9)kEmK)5=s<$o~qH=t#S#35^#;RG2}(3pcec)ZOjAVQ^$OZqvc$IaO_ zKhaYST%od4R|xsD*ONtbT{aiQ=Ut#xGkjDwlsox~Rov)khx&u`tr#B5wYqw%d3@(`GqJ5~g8u2Z!~Qk_GRUJQB( z&ngJuaP}AfS)>y*POpebf0dQznms0IcsA8s^$r}I+VT18=4D$`%Q}q$8$bbqcU>K2 z1@OiwDx^>Nl2(qq?gy2EiZn3ErbUdX@xX|VW+`8lanOm%8X6jseC__+O0@~{e&~CF z4XX|mdu8SbqU;(rTk{4MI?R}pXMWeOSezp4P&}Cqp$;jKOK}Zw7>M-pO^r0U>v=Me zq|7-E->Bj!ugkK;$>QqvH6f(Qk}1Nrzb_k|VXImRdm(1`!dB8C z8+dADg^AeF{2E5*f78WF(y_S1CLc7=K#(&zFsRn|C4obGRwrvy>9#}4IN#&|;LH|* z_)hen6>e(ukGRtw)8RK3XnPZRaV__bsU)_+p^0tVU*VYezRFfa=xSVgJPH9R=A+!>Wf(W+;Cr(>;osOQK9z}Y zBQ_bpb~$1Vt-kA}H5D-+|K1b3_)YPs6j|hSz|oQ+X#G>%+>KDne4mydmk10kJC_2# zY4{EzkGE?OH9<>ePn`I4dZz2Iw!am=ne0WSHJehc@cXshw%BLMB5?z1*5L3ryZc|d zfB~;WHR^SoZxnYU&BPdKu(`$~pq zB)?b+JMVmZ{6*_c%YT5ga!H>YkA$0kXEsLJcNah;ZoI-H4l%+S`NIG%tTI7}(jn@SGd z?6dU`IIfJjxRiL+^sNeTo5kv1)P@6Ln9~N8y(**IeP$RS$YFAwRmjy2OW4lZK z2e)<33tXGi)C^`C2#oUws*Bj)pIpUDs7Qhic*zl@nF{^Ss^ZPH2vsrf{sQ7ypx|zn zNNdXw&I1Ir3)QEorLTQAziHbp#tz%9l`krISmSEZ6SKo7U0Aw_qxC%Z=;qAtgxF+b z-KBN9X$VsP?LY~&o(AT7xFHMk=Exi60_8&78sB3uh5`UQ5B_Q;GZLFd4c+XOVR>ne zYFuvv3V=QQEFw8RVpLrD8b2cY&912{%N$glS>@L&cpxY4uvf8B^Y>cMK9nIg2L8Lo-y z3CCeo=6T?@BNqcZlBa?tehZ6N=@&gMqGOLN3-&2w)0jeftEvOXj1+E)iK)I== zaucS!_yJvIx^8!6MGWXyo+bcz4TQ*6pj>?q>&Sh+Y{F$IGd}PAw5yHD_Nk65Evwc8Bcy^M;OB@;lMGzP!`5Xw z`PtJN!jbT;M?(iA!7-Mah|6K>iU!rmodWPULE9iy<25@apLMBf0EFDM#qa1EU=&px zVn?Pd8Fv?2%mmD0!b2~qC7nE5WeN6(I2H{j>h0|M2kN2azScJ z|HAfCStuMe29;V%Qp(^!;-qa04HbMOhExB~$4tK!^fye&a$7O=vOX2Bb_`Q)Q#zQ3 zIB0Zevef)WTnQ9Iz+c-x$~5FOzG(o7yU=SL`k*|QocB09p>fo4IW`GrtvrBbvEhiD z1QRqtQAB(OekJ(}Eey(R)Os#~)+*d2F9#qK5n#~BePE-!;CRj3?mD&)*BO5Fbus^YAVSs1Ke!STynr=PQ@ z@Cfn;&X!ld3W6jWOrSO~^f1+=oSrhlnzz*VN3rBy!mKej}8!@lKi#Ta`GZxj7!{?hrt6*P;I(~ z$fs$`A8NlwB?MxRGSp19!_S&2D~dpL$VS6y0&fR30A@`M}DUi$p)%cK_7pbLhNXP30O=y%AhH zUAznL$R(@ep0*UtL0uPAP1#vV(2W{(Ux)A_Zo1TVk7&VLD1)IkW?3rtwyW3vLBEWY zhfjlmdz7huBLp-Mp6nA9L879uG}_r}-1`W6hym=UTZ%@M@&*O|;rDjWn}=_X&C|nnrHaOb0BkX%RJ(i>WRsxs@-kza}F* z0^2mRgLmo>PyNa=YIY_mF)1=Di*zVM?Zn)~PTM4yKc8FOuI6=JZbh}Zea@OHFuQJf zP{0*~h8!ubj1j(y9lekU7iE1pQvdae(PrM{NL7zM^#>r5fzU%xNtn2Z#9nS%TK-LOGR+KZXDbO}W?@?ge-SXxP5TU4A}t zbiEclu8`JgifWEuM{Xf_KLDn5#jb+@BhDY-F<`6iqBUj{{>=Rwt~hLeV1I~gpuSS1 z6Xvi_F(v8#Yv@7W)qI~YlobgrQ%a_L^#@+XFijW9Vy@HiXU0@0^tUc-%<=*VfDKQ< z)le=}+uzxvGmuboRkKe{cP^~h;O_EXLq<67<^Wh7;Gi(xc)0H4zj&}>WjuPY_mOwP z-^1tB^AXg4e+7NTjtpslcVa4kFL+s)4h!HN^BCS>*6z%INQHs!HX_S)TvKdq6xusZ zKWDL_ywfEga`t&m?n8~0k&!XyF7f)y5>FF-vrnyZ|Jv-(##mhJ+KfKZHZ6|pO~EUvxp=s0e0HqQEU@#V0fd63;lO z5)I}AH4LlkCUoj;i2{Nq20)V*1y<{#w%JWgXG^i9&*hqSTmM~3u>l>W1Cq3p4wReq zy0Q%u-={J^F1lP3TE+y6b@khDaB+xMdfGdJa}`TMiVs`4cd{T(K9&2*=grlHyuA{J zbf{xsoo_xV4u?dvZe$)OG5`Un(7p6P`^FHBMJxhA=wOB3Bh>@rlR?D4ax}QBo=^|E z^Fb|2X(#@9ngDGtT*fm$4W1R!3oe~djJ z6QTp_?Y`S1c7qmFh!~asbLh@AM2wT}MUw}K=wSE@31;Pqw#CV#EK_e$sTP-V@v0!dqnlzcqRXfJB2-|xp^8l ziQV=p+h7&Jqni4~n-M#)fh5w^uewDO5C4(K@&L0k@%)d@hv=Ts7$!X;85_rbEUA}w z8GCdx{K~}o9ytpw(8G_arM^bLG z%EPY0c~@f~J+*sLDVZ}fiF-q!BPD%0DmGXS@xQ#>Bv+D<7?YN3o3kW@lEAesdUq^1 zHfB-2nM7_==hDZ_ffpMTFgi7&w9w@oaR56&#J{)p`jlJmh(v63K~r(UVj&GiVeefx z?=+oyqE}e>D(V{2AE2u)Fhap>k3;^7uKadML4gNN<3TSNbqpB(=_LUmCUn%M3p+As zreHT;3mm*L7oL`*K;V5Z(?=)4L~^8eT~>uHq63pGAaWZjfTd2|nO zi(^BXKRlZL{;u(7`(E`M(As}J_aYvo6TB>m3J5qE;r^Z*66p=w+(zGY^2Jw^v0_

&?pWdegF^5J7`QM7CWjC~`bD|G0EJ zCm8UbN2aNr9iz-*d>0yt{15~|x<|BZfvrI~CJ3n|RhQJ>%thSe(1ZI2>ihq-k8K6Ff&>Rj9!;A6YhlYe-w;?Yy=Ddzw-k`b!IGePilVZaG6xV=I2vk z8rv%LpI2Y50o3GOq7^e4XTyYY_nEQ`qWY0UEiz%7@r~yIYTVdIh+eZ@!d+xGMl*9q ztKNnMjnaML3Scye{(O9`MUie1fHOtIxUZ2C_q_0ucU=UcbtAc9v_d&*^L+ekyY_(L zZ?S;4p`3q$D!51B$pL^q_5B0anN=%;&SZlLB@dXb96kkU@jpr&bpBz#qBHSwu#tR3TzV>I>mmL z;)&NA&HTs|_tc_&lRyY;7xQY8Zc;8WMwF!Y7igkZ1z$Nin}9ai;$f9kId63}Nx%0C zsb}9M;(QDlIl~-IO=4p9Ar(XGVP2<#pOgDQFe7koNS}6(nR@&P#7=kI*nJ%~?!~}o zJ)iQGKQgc)?@CY7HI?iUr$#HE z4^w=Xt{+U+M<^j}C8qLWXCGqu6n?WmvjeY66+^dTw>KIPNQF?psJtX*46LYd)R304 z_I1-)weP)*6BE#FsGf<#6$|6h>5~(H>hd)zLl&ivfPDjoKq;5LAy@Eli$RAEKjgNJ zN}CO1sS1{Wcl)NvmXy@gMNiK`v}e!~AK~U12HLY)qDU>Ar5S&_1ppW6MoIEE!t=&l zLGk_d6FQfQC&fobusE#MuiHo6LgkugQZ2*G_1>rgOP zWK!8Jprw~CnB6_O1k+d3j#;V1JJ{M46H9n|nEwZgGU;mE2*J0h5(U&$dh(U2j3^7QVChE<$cx^Ahp8WT47b)4i!JPfM<+K;`{tY) zTF2b6Lfx1>l1-l#Rw2RGNf2lGuDCGctx8OZWOxL&Ld52qy)-kg7vt?={ts0Cu~bV3zB1%z7^kqkKc|dv@rM|3A-HM zZ!4sC$;a(;91LlSWXAUN#w?LRAB{YS@@Hgh&G(SLyE;aDVC7IfBPndi#U0aJ=I8Z<(--=aml7b-G&N@MWhZFO3|! zsR0{VK%#v)s`V%3TV|VWVcXUUiqCqGl=f=jpY(b-N}Xzxb7^Tmm25hK2;AQk(M2cF zjHr};5V>20;UTG{h902juct)dQIkGx2Q_%8K0Ls!UKfNr(POxls_Lt zshTg!)>3c;@Lhr>jX2Hl0;wyL05Al0*;K0LwV--Kg_W-vT-cf_M_vF$M7nu zTM}w}ED7~A=etk#%|oOZ8oCad9`ndH)>5_L850na7*e=iYX1(Fp={PPE zGub0R)@sx0@%}Sne=cS6k^wZrB<$+I-g#84KV36rp-X>=lxM%2kA6ta>YUPhwnM!f+`?dYlbh9fs*xojYB984Z2TAD@-n{46K5ip~WA;kj|Z)j6nd-ziD5?lMoXD6&K(%(lF{ z&%PhwvrnQl%9{wfo!u+j5IbY69uugX^`++MZhpe>#OwpUyq=F(S=a$atN8ojWI-GL zQoPl4y;E_A#7UqgIY&+!>fs{Jwx>W>Ut9 zFxjH1K+R>e5unc(p|Tcm6s^WmKj-?Y4@w!PM$5e=56M!;Jx(f&pL$H&B-+Mw| zZqr_5kI&a7ripnll zRh1!1gfC$SUnFjI*xSnenhD3p9N|W*mv(GpC$2p{b|828QTPdu!Q=J9t$xdnO7zxx zk3hg#>Q(_k;hdl`Il$q$7zb4L=YW~_U4`qpE;Yq1ql2~_2-?^-Us%YWRaZR9L;OUx zTgl~OUsSKx=EOGNNT+~3NM(05tKgo6RA`yJ&lrYl#|P1~pa?*hem%~F>V)IghQk9y zmaFxCB^IeOxD10A=g0NPO&IvCj2?Sh?-P9)2!+@+nf$!kGO{G93XL(NlbaiG+8>VM z;99OBxvjkix-ks-a;RLj(l#YA{J25jZ{3X8i6Jm?Qc0(f{l@Yg(8aQ1qPF+&U#$;3 zlcqLZ-sWeH|z{$YQk#!{n5V(8ZZd)2c7`=?CvzPimE=kMunCfYz2!!bf9;|5}^Rz#SX- zhPnUkdQKp-O1L0U(BpYbjs3uATnfex_N$_1GtvMne5NWMx15S+)dcXPuB;($Epx=W zAB=J`7%V;F*F%C&@j3g+k9^*2W!P-&Ujg#Xo`R-dix4YHldf3OE*CAdf~IGV6{D zhgk#S=6~zfo}ZYEx4ScDIGGFpaSvs+%t1@mjy=Kh;eolozd<_RUu@0Tfq{Oa17lTW z`Pn3IuG)^cCox!*V(l&r@R7>0YPx5TVmqfN5-+lv(N$8<18CnX?{_tJD|uv1ZUJvn z4`%O1mb9~%7f`24vRZHL9CT9D##3+4s+OIWN1+E>g9q~|)YllXB7O5;@-dRt+by5F8#Sia2R#djVy zOs=x>xarXGs%7ZCkru(+I=Ax;?*4QC%#~}8=B08~ddOPN90r+Et7|aN+wQtQyJtEH zfliQ#bTL6azA`JcX)=`WsyP$nwLTTSYQWXmrR%oY#&uJ?Y%7kOm^3^r7fLhFng(Z! zStRgmFAQo=Ewl8iHO|nMR-{8j=e@2ErcknklJfmC5Z1PqRFUkZ_`TUxXG;xS~B*thP;^`q5)gU@Pahs{Hc8twgkt)OY!O zI=rvvHrCeHM1fKjj>DeWFuKa-r;ins9t(H4(Q0iCG-t(o#OwLygVkf6vyXHE#Hqs` zH`25RNA`I;e-?P*G*ZztCZtCz%`}UE-sNHNOsHw?D{mp=f^FF+Ag6eDMu^f?{j&6f zGzQ`O#bz&92P#iHA?{Z8 zhQ(>Wk&r1^Ievz6>Cma>=)nCfxKW~4Cr6&-BWZw0vjy=qI9445rC7Lsox)H7P^HKS z3``U<0g8wsFkH6|wOfT|sordI96~14SdLrI4~QR}9Su}?ZNA)3{W5V5*g6wwkWlGU zg^!=l*6-;_n+Y-l>^^C<^rGm0+r#c`baIln4wITj;v>BYaj^^hfMUvqId@&iM1*hH znIzr=$HUsB!*atmwPnol?lpkTXogmMTwwb+jX*i%jPTcPjodvu>fkc|lJJw3wK1qO z9nCmOmo$Fhrl0V6pVX#Ra`3TRWRCpr9=LF2b+Qk>Je9oOspGDtD=Gy&XB=R zgcyMkE> zR5s{HXwM(BOS+MARP3fD&Dl%@k~UKYm=y#Pvm`c!HCpy8Yl3RhhE#!vC^9HyJ-*RXxB zH2?Us^<}qhMf!})Es@adf*n+@I-!3-Gr2c`dR`YIoyKcT{oMV*EyX3q8m+)o@n#K| zMFTE6(Q0n{PCpk6A?)P!Q?Gj(*vhc3B{fu@tJY}dVa{70>X^~)RI-#6zgnf%qVEtD=s$Ckd@-B=jtl3z?|vX{T9mOCGD>U0 zO8%!?en?=75lJAB;YOJrXCTSXA%@S8S!BCs>Qm@`W-`S-71-0eKMNU&c2?Jo&(i4_ z7)Ma!LDJa2le*PR>Z_HJZRH1HN)4!DuZy7N*I#d%Z-~~D{ajd{Rg>NWvq-hqae@53 zmTovJe8MsBgwNGGg~$X0q^Nr*!k>Z=o!R2`_!&$IXh*i~ar@aH;qSXL^WERSq+5es zTD-=}sp^+TuGT;$qcx35(ajZzQ{kcK@XNLzbys7rXsv3of)E-y;2*n%JYkfUmwv_s zpaxdaO%5C%B{Royhu6yd8@_!B%E}jM+3_nVIi0{aPG1G1;>E?)vCb(N+@CWyjNVJe zu^Q9;d8_n8YiIh(-@IS|H%MA!*5~GeFni;P*nbOf`WAkQY0@l+L9jBA1axt3Ho@vq z&r`bcVW@pVWZs3}`IVkK#xa2*i@;p;?s zZXcN!LWOT;Dv-+Jfsp-cUv)lWey40urubtcOf2a(FzX1!(uP;pWr)JtMUCVyp^K#8 zT~(ll=bpcR!3q*a0jZ4`6VH}^qoK-^x9zcrllW+JqMTKQ?id&f!QPFx(1=E}Ci0UE z*Ccwn_wxV_Tay|QJ~Iq=YH+1VOuVBtqoop!vgHv?LH(1EIPE zn8wl2SZ%%T-uZ8@U3h|vDWW&#aY7K;ln=mCgfxH_c)%~tItNe`NAko-mcQB9~O7Rq3c4SvR_YsI~zb@7zCX4k1cCCN!mtr6}H|_AJ7=B6H?dEZVK^$ z&wl2T`s zc5~EcwAxoSW6Mb(yNtmXF|U0Jb!j%74M>7Tf@bj(pnYbj&UBxkPBO@i7R7mtVDM3R zRZ7QFpRtP0Y5pe zeiz=@2@`TEYvLDw*TAtmTv*3Fd!hY-jCQ;tAhuvY#8o~O1%WQGr3|Kz_t+Q$BfG|1 z%fziY;u?N=V^Ts!C=}}BPU!wWJ7bo+=MGXx|MB|vYgKMpFkmGq*t`yr)1(ZbmUgh= zPd63fwe&`3=oKUT^bw=tN-qXaYMFY6Jrc47zmGX0OeY!S+M)oKX02IcAlA929VR~- zPYZOhra6k|MYn`*xWL3H$Tg&lIm6ham*@m4 zpc%}F_|-OlC7{izily(jpfjSQ+%9r_IJU&oC^R&ZON+b_mZ8^`JLZj|6AOBr5km5r zzTktdV^DshF1o|!cPrSuc2b3^(~V7*NI|h4IFV~zQYy3DJZ%J@&Kk?|P2-c>nA8x( z7rS(RPvMe&2Nwp*_S(n`QCip&w^RP9UaeE#giOD}ISN>b?;zl>9hX--?>gPRUoM}l z?p+YsD#qt5+yC`@>L!F831n=YPNv(|}~g-T7R96^k)T`SOJ>zE#D; zvoz%KXmgJTPt~7*qqZ>P+^}<_10}}+A)`A(4P-v^VuhEm5fr75Z=DTxT|s0ovgd&m^c12$5_{1u_s=5_5+8zTsXDHn>@s!FmLwbDNlQvATS209++p%&Jd=g@O0nX-h-=C-K; zxlWv2X)QeJA*7p9OKS)U09r2x3J23HzxQ-!IBFj0|Gl?VzP)$AW7~7v(wwO>jcd)Hib$Ltve3IaIpSvR*_DcpOmqlW#A2xexo;NBdbfgfMt(+C|j zg(U@;Nth66gO6E|s6icOj|b5eA;;6olp2H`?#g%Ysr#lQzEp zuhm#a#?#OR^aUXMU;go9WJ>f2M>fs%lVNI{G@F%4v zpyb6m7fV8x@s%kxP{OO?i&iJvIoaBb(8VU+@y&AO5aAn?JD7Cm)Yj@Uab37D9mKW{ zn(X6o*&lG%2jLua=%}q?`bTx$bvxCyL#Oc}-=o&U^R%#!`R5;~2eR+>A8cxQa<9%zQWcz7CQ%4N21H_l9#y_4!6|Gz*R(bSo{Spq?6rq(sA(ENeZ z+PF=Zm8Ki>$-Dtu7ocbj%sV>7|`MfS{_ z(A!v$o@$Es*r-0fc@5_#qN3U^+z{F!q1jPcxuCdSWftW|QeZ7jo#D~@T-G@rUS={? zEJ_##v-Gu&`ijqZqNQSau!CFkidYtWX$~0R<+%62sdp$bY0Um$!28^(ZAG4Z#Vn2b zwAk?{-CQ`!#45lA{eOVF1Dby%&zZ1p7)BkMoJZkC)&bXRA#fo7Z{*dm)aqGf&YC`6y0f+z!)-~63Jf5@LZrx$m%;bhJRH1hy`pyP2k%6NnqHscd{dOti#+n5Tv1HNE}4_T{d)#4cpT; zJ;Dr=U-TNW20(TmF5x)sKLnkc_Bq(Jv=7Y^!avU*hu?LIX%aFYsGi84NqFcuKgUB98YZH;hy8o=cXFS&_yz%A-;SH_Y=VFtgb%PfWEO z;AOjie2hqv^ebm9;d4@)nIbky=s4$n@2GkHQ-sOAm5E79GK=iC4sxARJ;i=+qhR+a z5S$(x#Q59U-;i(3T*HtSM_>9rT=~1%W2nUPCRi>8COD1#5H?MO{9hPaDyI*Ut3s$~|qH;lEjhWU|S{e3p4?^n_na z+7v4B#Nq^;i#-}GwodIV{+;T+)o4zpjFjsadrMZ--;H$wf_}2E124kwr#6Zoc@vUh zz#DS-f76N$KmD>xBj9a-$cz{q8wpIz%nfn5zZl_7I)kM84(cwa8%Zt))Rr|iV3$ev z0$%+&L`tIc4bv5BUDzL&wz2G=5Ji?(OEdC1WJW2HU&So^0KAN-F~Mf!D3DdmT8dZEa}(?=yxGt{gu~Q z5E)O78GorGDm|nGqbh@t=q5e-A*{SMd>_E!kEVn2Y&blYk!{~HngJ?naV)EC((Ib9 zxrpQ6zcnRUw6i&&0YWchiHiAbCKYFtk4q9_Q&feHn9)Ybh_&a+y9sYU8V=OKO18-W z5M}KpGEsir7mj`}I3dQvk^A-(sNiMlsXxC_1$u*T-iVCv*F6|8x3F_`T`{*K5NPd} zhA6;`%}!|uY9E*;!<4<4h-}ajiaCn>rZd~|4FBbdFl1T$N@m^FDAAZP(;7mx8DwqB z4i|UL`1-WYq^jMkX3-ixD+v7b)2?mC`gufrjg|;huIrzJ|GcRZns0ZIHK|un&?tqX z@QaBkkkc16In%$PPWQ~;5XG+fguVRf%4B!r*Rb@8Hq%x*8Dmg=_?p7}Al%Ob@6=wr z(jc;ozefgfs#hW2}GlE!mVn6c30EwHyQ+|WUr^V_$w23h;QRX ziXKpgrp=|#%}KwasoReQU>$zAFa(Jb@_LTLWi4anjsyXVZ6_uYHXaoNRYTwu3mgc4YXCX`kRU^wRvtU8hpV ziQqWtK6J`SG|NMm{Z5wElBe^TV2MNVU&N`nl;Eq08yTc5!)(v8RSRdNkB>9CL1|9K zg7YnrkrZ=%XlU?{ivbz?>3u2Y3L(KnPZ;S;mE}h>c7H=iL->r{OYFPCGW!xQ>IoE? z3pDn}q%NPyTHe3;wiUk?`smb+C#bU{U7svjZRJaIeht=@nQD9)VS(ew^G8tLM~RIy z?;lrwiuQbMN>pPp!M#;03gG=1lLcERA{GH2ZdLm?$EyF_r%Z;T`wWcl?vrqNXgiJ6 zyk!!CZ{{7BUik06+Bpdj2yyFVGvgkwV~FZ+h*8fuD|6su5j9` z8Kh?K(<~#eu{+L7^tWOhY7N!)!}|BKYx_b~<&4$t&rHtCsuIel#Cekw?Tss0R42#X z%P|rKyB8w^IF#A6_CL0hl_xEI2qby>?E}H1PN!^c-&fdWC7UC);sc1239A>N6EXorknxQA_h-DfQm0D9!}P zm{}vv_(yXsc)D5@PS585wQ-5xU&28T5Itn!$>7a@8|XFhWWlz;?O7J`1a)ExO9?@J zV>i_mp{srE#XB@9jsW{=n4Cw>=~Pg~-5kY#1Vs0!6W`DL>OItTf>lFKDlDoSA$EDk z4_k^N9?EL(J_)CitWX)=__lZo6tyba3FSDtY+yB&Wxaknjf7J#S)MNMV!aFIWvjiB zI3f1KXb=~zWt(TDJ{$ND5lU+s`<28@lHc zbI$0gcOQ7Ole87Yq7bN!mz$MdMxeR`Y4YCp_tNsU=k%Z(lszR&T_=Z@Q%sKSCea<& zG~EjJZ39RddFV%l-@BgizS(Y=iMLVS)Sga07@cau-_jFj3lVe7$!iT2j^ni@RdyIi zONFDfYSI;{ImpDA#f!C;$l=H@PFP)6hg$rk%A2aAzzx20eX^6FQv(U_}%!%?Q|_6nuY0h;3gZIBgErb z->73i>y#Te?N@GE2ux6cvdJm3p0-&B7gK*6Ymv5zdq2)2EA@cYG;$St?&bwID!RRt z500v}a8-Yv)yX^fWUQypRQ#s4Bz`uFBn77;cmyTvpd#z;ULfVaL2cO`h?%lVm<`Ew z1Z_c>kKOaE$&iDTJb1_Dz-zLFjQ24gO7T@1IrebhJ{HRTeH~OZujpk^EcAPF*9(y`j(T)1y|v#|^D+z9yF`zntdV#+J=^gz^@TJYx=)~TeeH;9V-Q&KN3QYnG5 zI5$Z5Eo*mPOM|DDRFi;l-65byqgF9x*H1jJ4pcW`j4^H1+W6P2TOqvCDwYi8sN-G2 zDr}FElNl^31?_t9Btzd#MS<1@aYHzaI527Ro*PNB+!yO}hSUHTkN0_*RVfJ!#;dNL z7qnAUcl0ZH^#?LKjs z4~eB~Oj^5sAS5^%f=_1C_cx+~xVl$=SrY!y5N3AWCN@73=lL-S^G<%k`a$G0V&NWt&#i)(WBMHd!KxCLfuJ#19*3y>z zGoCc6>A;@vK4ai8)GS8c=Iyil=ld09iXW7FF>*;AfDme`4S{P zFb$X8g~yp71Y&?b@A~IMh97>T)hn&0c1upk?b+34)Lq0ovR%0343n*c=1*q+DHY-Y zLEM$-Bu+4AF(mzm-G_tF{oblEK_RzF>O5~@Mln8T5KJ{8Bsu&`&~*oQhp82sKRhNB zf=&h&yv`8K3&)d`nJ;|d)3W*%^6LO*h}mDQ`ssv0q*w8}l^gI^A|2Q{KLb`U)gcjr zvx4z{w!8(`bVyVV#J!@~d)^q@9?|!h5_ciI%CtCN(i1Ic65{(-1g~|Ql9BC>)}tV| zb6+2F?cqBYqWff;fVXi_b-$pp3_6KPa(C}Fpk3GRqoEg?sd^-d6w$C_w*0~OE;{rh z_5zO&?M*a=4mzekrV+kSRis)ksVBfLir%2xuAU&HRVNA||2%+MqyM>xdvt*wGJJQ8J7JzQLOm$Whw;TEP?7 zGst(**KXSKX$BI;yVPJcLCvJ6@AEmmAyc&!ulzsr59vL_~_OrX zgT6Py`IO|%+eR^^oVdiso=rPn)F5PZA3vnZM!Pj_3n>I1@M+13D`zg?ILMqa{I(fu zndlSDd=CpppZ9*Zg9ZlIio8ySrz#__xHNsOvUe>05-zs)Y$=!N8mk3J^1yw)m^-zM z4y2-F=*?O@YK|r8Nj~ba*Q=Tih1c~&>m+>k7x{xVXRvA4{^A`i$u z3n&cKbBk;@1jUF4*+eydPZg%pEs0;F&7J#?l3}dN@br33rU6i=Ss3bn>AOeb;sHD2 zP2CZFBFYzUaTFEKWRPD&kmYGFdJ~nz4^$2j8wg+vqPKz_{~!KSW@579iA+Ecg4km# zfo>xImRl2wJDh>0l{Df}egEP`y zpDbeTZ0AE%V~iRMT~=c{^G=6w%D>(kF|6iqVCpkFvwUY@Q(gxG(QF@Y*GC!{l2|E^gd6nMZV8P0j z1+uho*yL7AH!QY;VftQitreSrDy7Di+xLn@eRECB}>(C-`FYB;aK2vKEE{?zhgia)XJ(~Hf*ZSpe9c^zZ%Pn z(zF1nEVl8njb>raVAK8G`i7P5pF4p1*O}PC`I#!4Y)IUs%Uib$<_f2RBqr@OEJ6s- zz;AVe45guTV0Xf7sBe&oR-9Bf8|h+)a8Q6k9kvJ3+aH(`wISGL6^a$^unY$@;=8Zz z8RjX=AsHossZ;>y4sqJzKY*$xx7S0M0C1ib_b%?a_Cg0?TzA{bGAoJrGS^AR$jKaN zu{IH1%cPpM2UYa9fNm~~LI6|ALKJA`vCooIEeJBWwPYnU48*WcoTHD-n2>wkn{a3? zUH~)Q@o>}+zyDEoP(Fq;2?P?fo%37-5PWS*%I56IG?XZ1TcElq7{5)Ubp#8;YjCCk zHmi?DM7np8DTy{!I&Wa;?N);x-u${9`dk*6<-0h2TJJ(H{&Z}lA@_{_?xJ!;Orh;M z88p#X{QI=}GaZJL&?RrlQmt&I|NNezr7Zc7FC4}tv5$r%(!ma$eZ5J7(EbaQRD9Ag z7P#6&6Wn=tx4z}c&V52}!RzpUzAlW)?eiSX4dTQ+gT$jsUy7gBR|d6Ec}R;ZM&D*i+3$9;8uT82XmE=D zo!kIQ`_u}^+FDjI^ZBcQQbH~bCw2g@LeaMo$uz!jmlc3q^gc&232uTANO|#Yxtv_2 zZ2)7k0D91yZ`c4%osW?&1*>$wK6zKfT`B!=qV?)z%kPs>*o+Ef0j&aOFe1#^^t+9# zcfD`7ny*l3q-c(-5o^N-6)j3N+nr^XWlZ`tGM)V$g{0*BPDPYud2D;$u@PRe_vL1~ zX%OLY$yt7daD+1qEYRZ!$n3NmtMZ({F+#=(GC|m?(zjpvw-#al#MA)H%@E$RWgoo5 z^_&4#+=*7SpS*HyC3HJ`?CXmJ`Pzo=>s*c4HFPyZ+I6gU-G`}w(E^f!#+R?V9AfyQ z;xo-ihVgIb+B2#eA3EQR#hBvuY4^wZ>g!+jH(yz?R2=()M55)6cb+r>q7{0`|K%BJ zxdx#CvCJ1%k0}(|G+t~AIE#q$eVQ^4y(RC+;M{&>^XNk0XPbDUJI+_Oc!kTprnUHB znXBg2+$=5IV?hQ=DV+*8>T$;~p`NClRuOIo5i>87DbHCpH5B3tnS$6c&tSwdnB)c$ z;52gq{$(OLB_H1y1CP&-Y2*ng*1m0-Cfyj;k+0Kyt~qT~aJgbKpOK0nXwMvObQ4zr z&aUyTS`z~Th04x{P%gEPPBK5ezPZvv#^Hb!5b$gJmU=-9aGOzWo>#Nn!}mT-j16+5 zoyQMnF!(4~-Tz4gliUYhtVfegdeq@DH4Dj3mwo9QT}kf_Xt)ScRWK2^P_=K+L*1K=eM5h`;cp`osj&S6V@A<_8; zvGU@t%tenL`Y^v9#lXaXl|=xm9Zx8-D6ljwkRV`oxn<$HLJjO8S)aNT&(-SS19Zju&W52ziDk)TC0pzSP-oIH3m;_**Fk4i(~L-8=jCV z-JtSqvP7U+G(6%Vk4cAa0$^2Op3Nt5TS5y|8-<~I)xk@m^Qg~^kTh3{9YUSs{OBYG z8SVOlCYA`_jIvy8uT@u3UE>8)oXdi%l)<+HEW#4&n^hcobR>NV!^6Ih7;4$hxrx24 z2+uSaey@KzMdvN4cH551wu6e`mSX*pQ~ZfoG8{jrl(Mc1_|DGESbX8#c{&Kora^O3 z+%Dm3WP;q}TqZ2?Cd^jV+g7%GM4;a`YC78EDOUj#x=6$FNeWsdu1(jjNHUyvS}e1NAGgCI^f+tV*{c(Mc?xaK^CvmhLMi@<=56dHvky zkIfZ-rxo*9Zx|Y%6(l>4uYhgZXHm!(7vs~OjUy&yl#nFYXGfT0n5IWuO>;HI{{o|C z5idLGz*B#`L*ruNF$OLT%qrH3lmwiLAjF>oMsYpAk=}FeKlA%&=)3|$h?H8~U5>y_ zlpK5G$t&Lt1v65x9Q=A}9EfH5FUTh>(Jc>cZ{}xJwFGrUC!2?e+mWEo(VK&kDvOUN z-HG-;@zkf+wmYfkjhrMkqeR>=qz$W(kMV>#IXo8scHTY0pETocZL)ySTUK2t{@ni= z(7SnnlgEtLai&{Xb%;>NgHJ*VM$0 z?k~WBBG(b4zG~{x2kpX!2HkW`jqyDC_3;f#%~`qZHgZuToeB(AcSS0Yx9Vd2A1`a_ zm+UtYN;HH*tz_LdeKMAXFh%uf)>t^M+Cr2fQ}-zD8a{jtS@{#|AC zOxb9v>3Q#_>4+?z3^eDGu1yhRMMsB|k2HC%j8<;1v7B z4nVoMlwJHLbc4SkRWAf;uZ6oJe|T0z5J*Qh8;8U|J`DQ0)RqYVI{PVPeEq*6(Ytj% zLOqpF9zY+A;M?+k5Uuhpud@v-yV#58M?_)t8!^mv2ielR2H=932y`H2v!M{4MmR&D$bQ1_yjCRGQvwCYB>Zp|w7htPUx*hk!DB9q}q$MnW2&Q+(f( zxR)#;rQtzr^|sia-`bpF)YWP9VYN#P$bZ0Y^1V>Un6wz~BBVx5A9vR# z%agBAe|y>SRh(Ai=@BvlXee3%XU;2Cv3wdh>fU2e{B7ms%}RcLC;@}nl> zOpDvA_$iwURMm2#P9xIY&gevsK+E8e*~C`fLE66>kOuZAmFm5c;toKe^iGT7gGCs+qm0EJ z8N{?udlM2{Vth{hSu*iv!@^-tj2PW@r|8_G5VZo zgN*BZ^&a%cBm$g$JYJUO(`Hqm_WPWIaiHU*%t{uOxha`VUy^ zD^aB$rVG#*{)Rf#rKS(Qs?fE!;Q$5O7U~1pxlW~=I$2)2EoOBF5iKum5S#L2XfbAOy+v%>*GuYb6kmt{;My`!)HQ9EbV+=miFs4Z zB{??pGaWyv)k#qao(Sdq>{gqf)gWX|@mQ$8oBihx+&z><4eY9v(03(n()vnZ`Nf-s z8VctUBpLz-q@|nrACtAiCDSioyfg|CsmVvSeKZ!=uU#e4_e2_HptP^ICC6Rl znEHbw0zB-23-r=osPZV3BHEMFAZSiD|2Lw?PN{JeKR_gS+sGACK&!3}X5{+XWXBM< zX$I6sYA}-G#&x25=Ddo{d5C}LKt-ElI*e8cF=%%q^9(9t06W4Fh<{aRxUptZ4K9-~ zH`;xcbGnOgXvRa&)SIARht<8AV+5%)<^)0d8G{BZ7wYuDZ^!w`F4{lgyuU@MYEICr zk9gGz7WM|BPp7}n2;Hf#nu=n6^3pcyyo7_CYRv3?u0z;Z0j_=xPr{AxC;;7NEzE&1POowen&G)%Fz?2wAIBxj|XKnePtP&xev7bx~tN<;Y0af>VbX_ z@W)YMNJx~v7%hlZXo;zZl2nxN^V$4O8_=z`d<-AYE0>2{UOQ*{Y2?#{|IwNV{Vpt| zyDs!(E+q>m$)X#e)t^nOLmreiDFA|c;rZv)7L@?P_e;ui0W{BGZ1^M;VAQjkSOf3O z=4PzbX4aVSDA|Bl(lw2Y%3@U1ec82guPMi0%RA1b=8XTrb(hGg6`k+RNaV1LI5nXo~q?Pf)M z->BcZ`7H-w(cMFC{FZakP+GE=5*e4livnc(v#>U0>#bxU8?|tm!$#rL^%`;_A^* z$RGw=IZQM(M#`}WjWK|-Wvkke3@fktSluheK>sZ787oY6{T_~3Bz`7e6Sbeq(2Lnj z!s2{WB&7#Cneg(z?4fAd47Zx`;wto~d&*IX|E!c5(PH-_l{3ARk#eGiG{C$b zVaQx5ik??D%ZD@JHonCv0V)8eN4ul$bROnj@Bl_mA}!R`@X^b{kKp7pQEq@bi~~rR z8{E5}^8-uptCsnbRqEkAas%VuvH7V&joc2)d;Xw1+oW5&%>nt#QbW}BV{G=VRj~r~ zQTk_{7zgQUmN5n7;5I@kxyN;i!NAVF}HT!5y7bX zzN2MCbXsi>Vkcur+h`8A<($uN!668I*S?~FmR3w3jd}mJ9P6)0t_r}K>badl(OzMr zGM2A?^~?E$yGky3vVH(Py3JIm+nqGmg_ z>p0VhOiQv;OC!c)fsM5d5BE`9WA~dDRMdO+4-5Mm9UZt`URn@Rxu_Q#_bN)CXT~K< zU{?;kjiPY5dmC%s|6@{=&sFGE)y57Z%wdQuSLB^n^%4^A zvMt}!Ak`Z1Rgkjdg{MqFd`LD?cnw#lU*mV$)2lty$vKS{&V(qtjxLIbIpsbSfYL5i zFH`Z0E)&MEN{=~Mo#x?VR4$8VFRAO&D6KGS+2s*tY$qIO@4^NbrQ2y#tDF{fwCivu z%DPN*r@TACJ)n($x4sqzRnayjU5K9NrF~rqWkVtqqk{X7lp?`ML@^+mebt>{6=9;O z7$AHGxexmA1EUQ}kndR$&_qKKwz@4YWcRm(fEI(8&hJa3cFUHabMS#NArhNc;nR1R z2b1K{dl6v-UJSw$0Jsjz1%l1K}Dl`{J)iGN3`U?L>SeGdB zQD$n!ck%9F2Nv>~;}JeAG(3-C=^148h&qB08ooopxWvzDq-W!f-p+u-#n0B1@1nxgw8C5o12mh70spX~J33 z@YNbJUKs7wH$rG)hortPg$0T>x{}p=%HCoI5BC03juY!%S~j*-=b#~{mcIdKCR|&C z3;mVmaWx|yfj1XVke%8{_}a2^yfTSMxC=@Ll7#+=(DLPoz`36dPET7tG_J`wHG`Qg zaQQqLt;+P2yl6P&u*3=(;JM(y)I}{V^We;Qie_MfL%+9&U^III&t{(DOUMqLZSK=y zmU2yN19_n#)*2p`#jXZP$1sJyX%b%+=0ZVuhjOk2$&3$y&FD)Qj8^nxze6bJD`V7S zj1soybUUN_JQQs2ZyYdI!a`==fmt;nx6(3hX+hmY|Ayp zxM!WwK@IuT+A1juV6-b?{r@hYLE^YTS=NOp@L?=YOxaCefxb1&{4g{#qSg&p7D`;< z;o#GQrG7ZlOSvi-V$toEg8yMvnz5Z)FprtZs^sUFd=b$$f6cX+bA#eY{X_tkTTYwc zFS$GooTr6H&rf>hWl99)oSUzL#EX6PTaCzw^&5sLYy29J$fZ9G+iCx~R+Qn>z=r=A zX3kq3Pb6gTO0NV}YTxrrs~^NmZdkJ^o0Ci?j98WR>JMXy6hxv2LR?bUhff%9YsY^* zs;a}be-)P;q8x|cSn~*S=uTEJbMi1rD#(P=EqZToCLsG{hn126nIR_<)pA9r2sPO= z`-O2FH`HwTYV%*bjN=YGQsp$L-e&su9a7cL%Ur!3b;e_b{lr=2Ap4nlf-wtC=CM=c z$@Lbrb@<)qjyXL4dn2z;oD{jNFZF(bml~-({|?!62E9Tw-ogoXTw30C26Ww6h(Yi! zuI=ql*t*~Ooo-W~sk$(YP|?@S7`&@Jxuwuy3xCZ){rr(*rcCOWs;8^Y4H;F8wm9RQP&u}-fb2lB81bhabSSU?wi)mx?|VP1 z*kdo|oTX?l_-j-*Gq5k@z!t^)#Z!QgBn0fSc)63YJnw?S`uj`)=bPBV%IRL)P@ieq zhg&(3L+)C-RF#x{cW^h=t&YvIryqb?cEVL97pS4E>i+7?f5P9EsR@^C zPlr6n0h8NpSplpVO0fttX~oSTI4J(DR?o`07fnM#W2F~8Jv^X;1i*vNCxZ=6LR=V$ zN*_50WMF6BJp_&GWi^82FjRd9-x4t6m(!-jXR@r9xghD00%}w_imga zVp5IE7SAS_Ob;QawvvHNUe)j1UMsWO0XvHTL?lCAv%WQocl%fDm_8kXXIC6B_D=LX zQ?q*=AT)JxITKGJT(XvW5CRMp{&=JHkQ=HpSS?($3;kkC)30a9RszY=_JAK6U3{tmf})Jt7|+{)1sx>_bS+$wLq3i~Y3 z5xwnFCr}cEiYu&0j*Sy{Bqrn!)+0b%^v5v3$H}!Zdu<5m6=+)PGFPhj>NdkkMHgsb zz83qCu=9^z?-~qhA+!+T`hzFcteQV_qPk!Gs3Mnr=5toe$Jx6yx5mBeq_Ysd}W8$zOOKrLb?~;^3ddO|MLjQS07+cvRZ?^tar(thDG9 z-rXHXVNB{}Q{2;6aa&Qti>58N0Vh$#I`yRApefvEtn)yVs)d)J^4RyA09@wDLa zAz_5Y-K#w-wU4!1LWOrcA6UZ#Y`wQcZr(c*mPd%kALU{TZH*jG#?q`t9el5J^a%gb z7y{n>t9_6@PKtEbWeYOG$8h4(fU)(LhFoS)LhmvH$V-zjJxjJR7>R*0qx>xO{_pJN zSn;r_z52a<>lCLKF>9Sv9fod^8iJm>eINm+(f<%g_Ks}mvF+6B@N!fc98-%`J@nP4 zu<#W1Eg9;==+>qr>0eq~EpRI4WGTdgdJg&zT$H8w@Ca_~(cs>NqwHdYlS3rM_emg^ zy>rPBz>O($EBAQUL|>UY(B@V(c~WdsMnmJo+dTMG+KCA_iWENE3uTHuMpWF_&srPk zoIHiwq9Nt-{nfMAuM9FN7rF=j3Z57C&@fex+SH?&apF-h_L6Jnu!~-G>iT3%Zn3P0 zvhf`>{>Qc8WA-2-Q13nu)-|0fIHe!E+2JH?rr6%M0LAC)gF6#~6ZUr# z#GU|1$WElqH;0IPI3sHwo0mrjLTBk93f4eCrqJhWBb7}0Mz(P47U^2|MX>hr9SF#@ zm?}_}=PKvayQj0DDo7O!Y)ak4P`>i%A{b^OhS6OhGIdTgrN3ox)lnyjR|-FM?K`cr zHmv4TF1KK$r@VNM!8lrFVsRrQJyJ9<7T#DtquF+wYZTkRIO56;*Xs=db9^q?n-mc3iHkH!SrC4LiCkW%+>OvzW6|)v$ z`;ukt=NY~PU#j*GUh=w60kgWm&{@|cU%e4$fhoX$9=-?m0J(If50Nc_s5|9totG34 zYW|(7M38X)Ln``l!VDgS&9m5`Vq;yQumo#v=mpRw27R>9oc?wGB%@gZp2|Y39oun( ze#c9bJ8+-OfA#8zg|5vFjL6|unH8HI^UAdZO~`V;fLGP6wHVvYSbkQS)i+wo3Cug3rAmy?O?LDBDg$11`#%wG9rG^!>=n6|P_za#2q4u~J$MwLW{^ z4U^^Rk?F|kvBAiOUbNT|usiXH^+{@37}G8oM!~;wiW2l3!@))vv%{!~AfAz?>sCI{ zJ?S0!;0f0ehSR*p9jOzNk))fT7kdVqaY{fI4p|ZSP(bDhpz1Z#0C3ukVX@(Rm$8e! zfJ-(CX#llBIHin#Q79C)->_wdzYWnCCe4?=BniW)C>3`YHE>J<+aclYQ9)y628uH+ z!teMS6oZx-SD~TwkW&c`;M)qWeYjV2TE350$w6^zRvuq!a)cQOKn1>|NK=whu!=l; z@Oj31@IY>kwc2U+gwoy>yIMvkQNgBS+re)LUQu?*(waD||q`Tt6 z9jK%lrj*_FD{Er&55=|Q|LX1@WnA9rNMEHVW}p=^P^ZNyo~6^UTTSS!8m`&!9(Hrf zl^c39;Q)<)q(?Z1!1aYSD1-+{qs?52kO}gyNdVSzhDV>bp@IuHUvY{(1^zm>mCG8$ zI1gi7Zckf9SQ#%k+FP2cVNg}ouA);TNtNr~5h8T@?x&6N-O1+g%Xygme67Q7kAGHF zmR&=#Soa1CWrlz=7?yX?g4Z6Tz-I7(U}U$qI13{(jn)b_D%rO?+-Ire?ISu*EUqlD z{9F76BZc|v=-2GfjjN`%rAFz;R)i;K68_tqPo6y~e*2u}9k9y1oMY49-14@HHXk}3 zcefIGvKG^xPtM6&h#HoYfFkUqdPIziz)h}pvT}<~m*DvU6OmQ!oHT5h{dKA*7my8& zAerS)sNjj+A27y}KGjI+00e(&)feM>ewXnFhE&*75|jAJM`_C_M34bfSUlP)RnI+b z+$Ob)NKwsVmatS{!=Q7in1m}OO1HKlshW?uD@_9#=;?B5#~G`qr`0D6-{{*up-a`a zH!&BZrZ_wS;wWj)T!ytkMoLm3YYFLkr=elrO3#x#Iv4MtznIcZcOJX@Yl4FxeV2K| z+njs3UO4c9SG5JuW&LQHLDGzJ&&=SQ@F(k=(EriB3YT^#7N6sOAL#o2bE8f+5xeI% z|7hfaqW5OQ%_RE2h9?Yz6e6QHY54^>{n?mU+Z{W(Ar#$H-Q)|!Kd2l4y!l*X4W$3Z z$>|E?-BoKaX!Dx$3+@}zoS?>PR>#ah=Op#@=ILcRhnKZQdz2{9U$fLeDPep2d8Ub5WH&%gj>KWOlXy43`{@EKiHd0zd8n;V17~a z@?Z*qTj$lLzA!>+2fZZYz@CA1^v7$}0~_p?3OAq~!Y$JjqJ$_PgPFg#ZKl>QRLFCYM3Y$|#IfE7w49`e>mJ42 z!QAy7inCg6C^>Tt-ItZF)l@k=rBhPlE#s*e9Mvh$vz83Lpz)jv zs9zDM8BkWaW|IYUuIMddk?WSwp@R8T)0a}uLm40)S7!_N*Q(}yt_M`qh-YcjC`2rP zd7XqHxH9S0DFqKo8Xwp_(v%E~(DfEf;LgksZ=e%Bjq?CBqvj-4-YkO5C!1;6=sqBs`^Muf$69(0Vg&?)oR+uD46a z6~Z%X5JYZZeZif!_1|tOCnH^}CZEs0Pb}sm;k?$NbMIfq%<%;6$Zzvq@2Kz6gTSaL z^DIhNvd9}9V3{Zpu{#E0be@4HVUoq+ zMLUxCWKtAp>p9u9K%J8eS;DT$LPdkGL<@>iPoN@(WNWh*Amg5}T)?WN&maIybLl$e z?c2yGkcS}V<{`9>{{4l1eWy}8>{>wye7v|+4gZ7r(LGM2AepM0J^`S*uqx1IWJaOT z0{At-0>_i?lp_4}^#MHPV0OI4PVvfXZW3O94_OBh@m}>zQ_6OV{Xpp!a&C7St=O_s zn98>VvI*J39N?C3yeGZ+@;%JSP6mw#c@uT6HWzAYC2Z5O#ZF*giG@@}0&7=>;O)vu zgmLtXy>v}OY!egn-r3Re*zG)q`;dA8zKo)k*l{n% zJUsN&MMN6d^NH%w%YKQbe$o+wIkCgKR7mv~UBydLOV=VA1u#k)i)WsP+D;TVQz&Nv z9_I3%>a{27@-bF*aJnHsGlQ+2LLqIs*xB#(WT2NSx}80+AQCtkT7anH94FB?;XBn_ zV3!jFCA@w>rpeZmQf^^WeZul&2!V06wW-LdZommLpLY2a&@&boZK*>;Y;A}UjEZB~ z%O*({S07_`6K$#77Krb521o{sH&@_Rm#QaNp(czo{i~SpiZj-agtIqUs8XE`TvN=P zlBZ!MPTHkfuFøgn#Cu_L|1Ca(qu?JYtTvvd^ak~;^oC?G(`+x%^$w9<(ujY7M zAVGe~4Ne+lfg1!%%F%y~OSj`!AeQKcQLo-f;rTV<#{T#siCi9^18~ceXpB|V>{1&c z^dqaPzCe|O{EK`6eF?MY!m?XR@Q2(ubYVkx>R03p6~r%1HZE zf9Me9h}|w%Ms^)y9syc>;BS?l0+fWlNQWv2Ja&zAjf@VJ)CdHy~U1AwZ+N3~T zufCkagjVujgp%cxqo{RI5RN_cN=kh9HoYvSH{_n1Q>d{lYlkUV_ zIqj;+$W0r66=2jiX;PyTHs7-WKCCR3&n6DI#qL@@jYo=;&#fbi?QIsGi^xjO>a--E zryu}1Q8qWMiAtQ;?3R|r_7GB)-C+x!wTS_(0nU75p!;YU~g$g!{3yJrH%jWOUy2a4TXiiwd%gPJr%W8 z>H4X;k#lZY7D)^rd-=&v4JhN=ZT$ZLQ=#i51|H8R6(u6Ft24`-WYDVJIooPfQ8Ejr z2h%5TKLo1p0z2-CFcfG>xvnMnn`D^`?QZ3}n07>`DT)i6S7*OX&^C`Jbc$a3^jL8r zfpkDt&?2?h!{jG>)erYv7)BEB$6=ff<+oj%0buOT018g$@0{12$ukGLxLMBDW zIqZn`AjYe*x0|%h`t>?a!Bk_)(>e2Ojzz+ot!lP6+HSL zA=glrNxRbukpJ+u$sSf-&r-vG4oj^&nivG23K@NRe>f2JFJM_6IIiBk3bw9dgWDCq zo~ASL*FI&5=lKV_bpO-TarRSy9#+MY;g`5|TihkQC#E+y(ah+-RkVh3c9E1;=k#@I~5 zkHN>jB|tKbdLvc2#*W&?z)E6DtBUH?%?c~vC99aLq6E^BVys5K3D9#r-ycVfC0HEK zD|qtgzIg6<+HJEtXhhwWkwyM0FC5>K*)x?4rzSd1U%Zb<`CIGzyHe2KlGU2zQ_%^l zuIf&g19F1=<@)0w*ThTc7Gm$QVoiCz5v$q3i{1Wwlk^8GyLfd9n(Vf7s=QK_T9i`i zmj{gm%sJd2XmoTiXUNoG>rQ38E>?LK1i@ocuQhS3trdb3Pwu8hxPml`?bD1uJ^ao{ zDx)kJaTh$MWLWue3ZY_Up-P|kTe$Gy&GIKaZx(Op!VII&is{etOELu)S4P#mka`(r zHHs78AJb~ZD@OGx-a zR4R3MTY`O#1V$Yg5ad{Zly`6DTXyn<6jBMDR zYF^tRj)@|uod*3QRtrBoB2JB#5%p-19qg7ZQjl(t@#Jz5z0t65qJYBm8DNqhG`p6- zfS7>zqZs(@(Z#15m_g(p|9!%GUuR(#>OQp)wDG>P{$e0|K7fa&=4{Q(5<#9EnJ(HNhoT(bR3&M<2r^bA%re__rQ<3h^@?0~7zUt={{PUYSO zp{{S`EG^GD?GG~&V;H!Aa(I3O8WaonfP{#wYSLO_?tpH_g{RyHf7<)VtU{7?BG{&F zLxhFQdQf@Kz@M8hL(*eRkA{FO?F4Q1Eyj@{Firj-bPm2ZzVqSCIecHVjW2)+sj)D7 z$;ioqMKe~z0 zGnz|nIMw&_sVrV6+wGq|OvO1{*SGGPR)*;R{zFKkwIeXroeb)ua6X+VX1JiaD2Wwv zlGKGv%_`k>xS=G^A36R`0j0Fl&c#(_X}Wc3uPqw&4uNO#>Yvpe#D|^Z1N^8+mbf=L z3!4S+UqvnlJz|B4$4Ub;)F7s8;PO-%D`7DOCViRa1JTCp;d)sBr)`ss0A*EHZ& z{89u~hJ>#)6}JR)-1C7b<7HfV&hRoliQJ=BN>a0K;eHfg)9ZhfYp}8FBLo8uuZsfu zEAp8SDjJ`GO(~K|z3{uKI8yc;OnMjQzd2{#H-~c|#r%kVG@!q0+EzlLH0u?psqmxr zd<&_4h+x}UpbVcb!0$O3hX6_!gGM!0vk6n~^c$Aif8}L^n&dvTZME`VRqije>H9d( z-xrIGVoWq5*R?!niymmd;2`DBt1g@Po4h-pv|&KpmuS!8+6gEZ*0*)I7v3 z7rOku-_zk0c3#Yvtl>-&4xa-JRXV*$}zxu+jtb+&CmmsEr2Ly0nQ z=Gz#1I!zFPEY0! znG_esqil>=n9@R0Pb%oUv7J2NF;EBY#lp_WbqAj;(H>pre|bj(92_4bMJ<_&^ZeQk zzp{AL_C0M(_9&+vsCHi*WxFRJ&TyT3aVd%c?*)wHUs2EI`u9nJyvI2aaZz`!>mYd@ z)!GalBggse&pxVmd8l9EgGmJ9E}_Y%SyKzNQXFFP4qkqJOBF~Ns+*AGFMC4#f4eZ_p5_hTE)UqCqz9=* zVGq<4sA8{KK6ld|r1Ne3eCESCbQSUmX?@4c@I3+l!xCSMfpO9hWFK*VND?Z*x<;j{ zGx2jRrfCY^1~ZfF`m}fD^j}-vy`dG%^{;h6+m(`kT3P>xhbH+v#0;4KPxRZX-Qk(J zfohnW&oAMF2SJ-7$haB_*4wtQKVg8UE15OBnV7VhlB0K~RE{nG&&r2H#w&g2Qz*|~ zg{|9Ezw?N#HI%4xA_*=eeDk=U1sg~UBzcDr*1)voPVH^pJ*T)q4EE0X#uL-z7OPo` z@dGzWkrT-Xk`9`5ymJ`ei?~?jiF6;=WaCmakA5;*Cg-qm3|mj~n+XbICBI>R#)H|f zh-xTFc9JDJACY5Q8C7Vj!@;9Rgux!BPf+gO=B)pLD%2iwJ80^rju53(yqD z{MWWdq`uE-!8(J|#5#k7=6<_2ZLmfWe5A7?xql^2Wi!zi5esspknpC6-l?cYp&(>1i-%1V5&hgJ3nxG1SHg++))8( zCH8b6I3L|exh5c&@f*G}6h(bARPpO&v+*#X@(dKz-Z1He7>aX=Be#MFAZDfsxbSq|VOGfbkdH5^qD(gBW&;o*vg|qE2UfZokqO^s(M50|m{l`zi(0L6J7P^=JEa57 zK==suY0h6TvFJL#@4kw)F!_e{SF_)`9!U~Nkl}~A$pHhmcE?9yh}Je)Zfy@57i12f zplQV0yh!g{_oUgs79=UNAdrnE>BP1X&6)&{7jhrL?q+8aD*FB95xn z1zKs0RlkVH%vmCCkmz?rQ~vFMs_=5O51dsTTf=dy6ly7@*f2p!gpvlPN(xal>T+g* zgk>9y>D58x3r0zRI~2fOnC0|rrm=w#~N(RRS2^9r8xl!vdzbn+|hiNu?5J>{58mwf$Q}bNm+(|U1wjR?^nQ=?!OUs zRc41N{z}J0)xc5=(sM}_zANq5`o5ZByQg%e;@h0(&7MKgf_&Qqo3T-z3CQ?I6w1Hh z${1PrC7yge#P-COx@lrQajS99xwE3xpmxG3-EWrKmc{?vL4_Owx7CEs#gKf25`a$4 z5qZlc6s`S{x&MreR3HV^5Uy+6rIscFMLljb(`VAc?0d-1p~b^{bdK6%v(gh9t+=`+ zU4TvFV@@;2pu|*CLzWN+LU%2aS=j5fq&yzy{Iy)~J%&Dz4F|t?uiNDv(D>r*+g64` zRDW^)uJVwdLb~qL3Fes_4bS$Z%mtTIp!U3L@r9jXellx={7JN@H+_FwtrpduA!O)W z685`c<~2nnKc?pwiN#fj{y1RNEmTY{-O&YO*0*8ko81DAobZJkJw@J8aui~trRrkN zt>)5LYLDD3l{BNurd2z(%1Sd81!J}s4!t;B`*s$UOj%i;r-7ypnlI&FU2Ou;{rigM z@CiwppRB+yRmJ8?(!T(93=UL>x;CRJA+t^2+_89D`5DLUxOrKe2 zK&#jb2awRrai5@DA31_PQv+>aM}Yesc`Vw#_Yu!dO&krkM{eygNeOiM*`}?^QQ>23 zC#|~Ey;VBj)__-e8};n{X@ApY`DaD&e7=(KF^=Oa#F<8niq1OVikyvfMssj>6@=0i z1x+)HyAuxE|1-z49*9r$sc|hff_ad#w&JO|H5ZPv*lNT2kH3RbtTU zGAHm&^52P~#}HTehiL+gOD{=;l=;oVaCTV^+Wrlu171PDNzh!qn=M50dQWlw}hQMriRiV+5DqS}=Ju=l-CB86UTU`#i5emXnP zGT8`A3)e=%-Xp5>;WlK(-98P)#yRiEvyw)oNES6VGvUO4ALNn*j5xIBj$qp#Q2bRn z!fFEXfXme&XovV;0gNS>|2=+OL}sRwsb^uH==|17_WfRL@intJOxz$d+~U>-C#CXL zL?!O%S!A*gt#n!lJx2{T6F|B7F$fhd$q*?I%Jz-USrSJ+AZ#{2g5RX($3hZ%jn!Wb zh=^r@2iL(fYJBxX!UC%(arYv1Iel}S;GB1oM4;D@=_aMsBmNy@5(EkAzZ3%B3AMxN z8YG7#tk6>b4yCP1yAp(7el7L5c)j&Ps%*Ygz=K0%IE_!AL$WnKXNot~0!K6Hr7>P< zo_C-^R_KG`Kwsb{7<3lz^J`Sq`nAqleZ7R^v$g%@bmMdfl%zo+3ouVa;?=Au0|$g* zaJpDz%=y!K$9o|n0$ymE3q|{%;tzExy2YAHwG%Q#{T(3gSt&;{;Tnf*ztI4dA@d6; zK44;0^QRDMh`*ll$3@Cr2ny*}hM*Zh*6<&>#_4+ji_1k0(g4oVpOkwxm) zr+V`60$w&b25{Kmd6`=qq@j1D%U82uMYJt0uBV7k3_fAw0jU`O zM`{BzkA^}0CDaVGeie5g$q)v=7dEp%=)1odLv@>VhV^tMbSh-1xN#0ZpzQjRuAe!) zUMf>K(0m2I^kG3WO>}!XQR|rKBbQ?QM*>2mBez)0L>gpsEU6pb)&nCO>Kpm70{mm? z?3>(kQ3*Ky8tU{S+Qk0<_wGOfN~RQNu1Od2#B)c&y;v8(A01irPcm((psVT&Gzo#5 zubPxFIqh=Rf*ScyPEV!jzNCa|Iw~X3fym~yiXfDtP89|abkK|~lF#Gm0Z8ICCines zc69~D%Hu>&J!Uw@m-1tXXWPXytX~+c9|B<)uODx5VJ)!D3<=0wJRnJv4z?b*qhI_3 zh+L9YdoC(P>a}VQF>{2oJWP{aKnyxC_}ADf*$5uRhJPdN43o(VVVNeERCf24J-vqY zKc$S03;mbuE9s}x)43lL^)9*c?spZ4VTk)0XO+bG$ax3-IkE?OPKop{KR zj2IWya|oODUUzjolRmeS*AptbuUEFW&AEjPtIlSTi{aSIMEd8ik* z14BJ$0itEs2-(wB+2tb+uz=LJ_$WA6&3ivpmszkIac2V)AP5uMMM2-RTc!5jD%^YW; z^zw=9A+f4gp)>B`)9?u9YPu}a$cvtMw~K$<%LE1Mf}nQO(PyTxfVA|$Y=9R-3Ug}` zkYcOAkP&{G;(h|V_SI)!2@0{oc(3%bw-Ky!5> zW+SeQ1CLedU;gQL)h>QAPb}cRb~+FY6q?t~S}O z{K)gd&+jL3Er6#_hm{JhJZx4d)UV`$be;aY}--{ z^QxqOIA>UnG;?KMH8+sPyPSMR_Tl_a59>6}-s7M^wIp!(BwtTyjpSk5Y6nxos(sgX z5E97S<0&*c9YAhcYn~by5JEdID~G+?I16$gzraMy!Ojx>!K1?mUS@GXZ2xvg zXp#P?W}j&{XSI`tt$wQ60z56XCF)@atBf(go=#}&$Z7-qy-|(H*op_-;HF~_o77dB zv6huh!CJ+WH%n4ea3FT1!woP$s4|ZrUJrgw?Y1OQCo?JUTnjMAFUnfUQ=Y#rKj`df z$#tG4u%Hi%UT~?gpRdZG(gi{}09z#KC!{mYGx>gk3I)o7ua#YGYcU%=S3+OyC3Sc| zQy4P$1X+c6EAMmJdNZrZt)btd^=kuN38sp>E>McLA>jBalxw(Mm~8nAMXwEaCkhXD z8(ep-7_}&TzuS6En7_pt&Z?FZVeVKhrN?$vix-E1KjyUW(X1_x*Zzo#fmFof5OQCR2i2X(j3+rm+-U!+Seiip1}g9;2&I14u-nO(TuY`y@Y z9zZO=US)>iCywxCYy#1Z4<>N?!h_aYlGneWnD-Py8L3d3=6rF_#UBeB)0J>h%)Uux zEkNAX&Gj&fY;^p=lLG7rn|$!E&Bqq`0E$-sXQ}!_zaWVpZL(q5FKRhk>w41Yw&trx zSj5V@R@xQ1g-Bq$nTou5f5W&tC(&*(9s#>17)CQ7&~Z zU$HMhLrq*+)Ibih{yoA*ghV56j&^sf!M{nycnhEPKR7>0r?m13$Ks(Sg~cmyS=C$a ze@1V%S3_j-R*s+t2wDk4s7rZzMKhAkdPvAe(soOj>4+8dlXld2@I*^ZV4($dHdQ`m zu~ey+*jk3G`{Qof3h_CpQiThNUGp9H?aU-0ZS#`1=hz`OEi|;aZ32dXF+x4us0i_f ztRg;*v|nL61byYI76LEjAYN$oH6pD!`foo!ZJ2Au@EeWh5EM7A=@P`ECwVZIN6b!0 z3v`ZLPIzMtTi8yX@}^oMkqzxqe;nB<5Cc2u2&>ncw|ZWz!IvSb9CXrm;AgSsyBX(XRP;=-C-s{nYQclda8<2%ZIjJca!M*T9Im!8C3c@P+W6Ir-2H)qa-7M5TH8zJGjgTtg&Xoqh{8@ zXWw^VGpt@8(s+!=Z+HO!?eAR*c(Fn2?z5KW#U3_6(8^Ska{(jcj#+xE9Mcb$|keA*|fQ>v1S_R1jd=<&WqX5ZG7QM7lr zl*c0YWX3aS@{k|bBOqsnKk$(ltuOeQY!iqmRjkWT5&1+`rXNs@k6GLBmSfeDy>i=y z#;~F`TO{$$nrA0A;T54E6P66de0@Bsfq3}gsfF1If;vcsP?m(Zc}UG37oV+HrN9C_ z)J7D5wXb`N2b)v6QszNZU~o6w%3)xW`{uw=2kxCy4)|R6+%y9@#1?2>e}$v}8oxNP z&4#uS+)zJzfLWT{6<`C&y}$|osU~){5RaoY-*GXwvHg63+!;CFmo2MEGa8KdwDx1~ zL}nS=7|qqOibvpn^%n|Z-bRLyvb@37a7YUJ^>gJHA_=Ol!!=B!D{n}&KH>e+HK_Q= z8$fB+oo%4r*cG-5X~*1b(wFE&F{!;5Ll1;`{Es)2N>m=~aCu*p3x}_1uyQlmWvaRd zrasx#4M`QzemYq#=kxe_E$qK-=SzrG#3VZftrWg;dbme}KK^N{IZ=2=9v~*EM1xI4 zx~ztBGU2Q%ZOBNn?sQ5^YX@)0vUnRvRC}#_p`L^X4!lyb_flsK%ccwxvIIKup{zg6 zXt|%Q47?94lZ%88a|{lqyOvaUn;;3@Jbv}J z>=2h6{{aC1;-L(-gf}Pdmi%u=Cz{G_BLhAufb;R>TeXBON&+b|AB5oblw^^;Q@JqWh`TvAc`FaOpgDM~xrBzBQCt-ze_$ zUF^A1%F>&LW%*Cu?7I#bJJgoj-N-%fyk#Eu~iy0f7o8`LC zR=0O83`;RK-~5c~pV6azqgti9XWYjzw z-(`+2tS6nv7#f#Z7VHR9EkEd3H{l^pFK1;4x%@G(>GghptT?9fj>e(suj6EaV?@xN z6C^9$Ehd#XJ=dvKmOAz|O}&O;+cNnDJrrcd_i^>dlsf|L7=VMNG^C=z_%yR!8G>}K zIB%g$5IhemVH{&WY#hsgV`OVWg1gs{jE%0BI*Uxkap!!5d0W))xQJ?gJsT`(0N=Og zJd1)!;%7BhMAVZPvQV2zrl!2bUflV%uIr}9brSqVMk0KtFLlT3=UvI_plYTCns`3* zM*)Sq)BnfO0yjoaWsP~ZlNLOKzvVnkl|8f_yOvf`TTYXE+^?21*MA9nmpuG@RV*B|a(m^wTeXbD<(Tm0H? zQunQS#IZ33gs`WlCp=Mib--}9^-E9*pZw;{Y8L|KJvKx0x9qSPBop$rX_uQANQe6< zT@6cXGB3DAY?Nmhc(4Wdh z?(()to?E4jkLC7fYAD+~OhiCTDrDmJ%kTtB`nyu~S^;O{WQq{Z9e$dJRy3b73c$bN zl(o37fG_%Yu39KoC^_!ZSm(xZd|oY4hBIEq`kBo8ieG17(C|wUJoau14~G23yFmCw zYj3)h%^YS#*IHebg`V_h{u}%SpC>zwjOqpS9Du%p=SoMnJD5q6Mt?t6s{2hs^~l%4 zV_qjs<+^Gwa$|@adFAPL?o!v`8)giO)7Udqx%H~GzlbvkI}7(GyXGk|U2>XvA+f7g z9xCS#9BD#uo|#ZT5Pxw%E-u8{1+N68eqJr1p5xJ!&o9Z5j6C$Q$F!); z;?W5n6yQuh8`qY_sdN;}xPKE1z~)PO9L3L(X_2mS6G+2xVrM6fxVWSGQiiTtnDVlv z_dR1_wVvV_FLcsN7QP+b&z=EE0vL?KiA;Wi*iSuQ#3kgJxNe*<=OmRmT&JtvlwBL> zIMz|gJp{!RE@5{&Yzws6!<(KD_ebz?@yAgTi@14_4h0a`fdsO+)bp4FoJ~A}A;~T> zb;*|0yvCy1y4LAWcvh*%_zq^+A9DToSmFBBil!7tr1!^@1`3p3O&n>WqBa8sYf4U! z=76I=KDN(ROJZSjh*FJ~=n|TKZJE>{fY;4G|NElV^Jw{2D!&g+t)V{ad9!fco4pWm zgGAOsmvfk`evb~%pwH4X#L~*9kDEe_8a8;eDxChjUXw~W=M&VplvIi z5ek8=Aj!tP=t1>xn}WNDuICex6vuyP2*q`gdN2f;9_R7?U%yM0NL<3)^JE|$*CjXo z6Eb=Ai`){By6qc=FlLRdISXptEEa~HFn^h&2zxo*@n~ui#Drj~l&*>Ih>`#oB42|- z{}9l(mPkGB3TSkBs}Rc5FRS))eK7=dS4kQY*OScazf>Ju$_ElcI>~qY^gyAq59-k$ z7w%Jnc6}J_or^RrL{^OHtB^rKKe1{2*7Z?)GUqSlo5f#i<)I-#^vs@##oa#(I%0K zz*wKcrChlk-AhPqz3wO_)M1Z863G0x3r$;lSU{76QsKFqI_G}|Nv5a5YbmK3ec#PG z{6g-VnyB}=%7EYf^mkjn0fU&xBD5CFkQqs3@~M%^Nz66p_@!kfNb@FRR}vn_8^+Dn z;jkZ01Fvare#6i6y81$y-kk>UyF$J0LjEx>WhUw7mxGbZUceL>%;4Y=CZFauA$#eIbTDR4I9^_j}x}5#oBO~w3v%X+3QF>8oR9HMjg=)PNQW>X3^ z(T_8{Wb%#!%QR?5fCt9UY_SW;yL$1(^ml?Y!YH1S567|d|0Jcml_4APs`dYZWmVIR zuJPpfckasx)rA{Zm}_Ik<%heO@>{e9ONG)RgkoY6C z`PM0NmGKgO6-CfwX-qsyCN)$7CxnCz*z(%I>dzL#Ny_heHH#{&4faNRkfAMkpYr2L zJC*nnff|UZ{O1%vEhL$EjZKtV2$sm9OF{L)bzL}M`lNG%w<>F?4c(_R07zguX6brx zY}r;12kfAc~DHLx6&SmPhdf ztpv`@&?7LK*eE*GA~{C8ztY4ARgl?3psr~J5=nroC7KZ=g=5f)?OdsLf6tVBNO8|9 zS(lI2Q?zgg$$vo)K=|C&qR8B*?(~?uDUsx$OvxHzlpA2&v*dK=Jwo8S0pO5oeZiSX zsQXCJ7?Ffv`2cZ*s=t3b8RGUu@TyeCJVZI;HrbiTqi-whFQ!lF7c|h=)F#!yZQi`Q zw`J0RjpgBB>RzvR<6~>i*WG5j3=4`-gga8YZ28OpF!;IlgYC+55sS&ks(-xUUCFh$ z*jFK2;a~Y1C68^mziX+X{pM zw0J)?j8LYuG4%X&VCO#t6$GZIwE0GhV%{vKtyV8KfX>URGcai-%ARZ{Z$c*Uefi|? z4&Dsv(?VEpj9-oQXoOd=6wOZ9hki3K^44QY{r6gpe?Fbr`cOM112ZRZK4A&(g(+9@ znHILhKUm6*N#VK$mH*0?|4F%WiVis5U@oRpKjuOX+SVUJ76x7zeTfGJ!P8z;fHolG zWRlsekzl%-jz+l5*MA0Z-QOCmS3m}pk0$UTxtrg4H+?!T=rS`17q>C}qDf*NG5sG3?q6E#H(o!8&vLzKlaOrX(M#|<8yjq>BN6nfIvJt+ zZsu>gx;SrFNR5t1r3%jLVE8sumXO6MeLE|yR=d7>eNY6&-P9mgUQ!Zt_<}V1A~{yY zvqyanj~A&kgYZU@uNykbSJOZxeIH|bG15`Jec@aOu9M~U00{tB4BmM?&lL=*uw)L1!$e`-%e#!uc1o-8&!AU~FnkU+mCN%RRB-FT zVl>^WJIenuyw9Q%@g$q}V)YaR2l;ky=(nC#p8%#(GoyPUqKP`FzBvf_uB&^&6f0g0 zJvg~XOdzLvk)yST!^iL-7=%Dz$XAHG@}O*q^sgwx`o+LB`6BFRQLck9KSNq`@*#1r zLbY+LTLCx?6|`Xo#%F9DJ2%u|I;6Mt3lAnV29R;hf4=xSjqb-Fjq;EG*5qIHa>Q~$ zoVO4Km&L!2m+2{hGxcXQoX;Jis9R5p9=gI_=%}gkc_?Q5pwolz8BmDB)%=qzZWMYT z!v;6VB4JzZ(%xaysY20c9WRo8K4cXI!H19*@XiS-sEh7Ms(%2GITw^z8`#fi`9=0bIHcZkoOM8qS>i2pE9G^Nj#V)B|mO8XlMN7f|3|j5Izg3N4 znlFh_dp*I45Yx?h+~4hANF3u0*=^+QSqq)23@=Zdw~#8DKPnbAdcJ7=ruiB3tTl!J zB{4miARcs>ruSW$w$d4+72G1L;P}_k6W=JG8n|2<^CY7pCq&ja91oVr(a7CO7*WZm z&=(scY~a3yF0q5rg0!LamVhiBS>~{J_8!D=doI=b$Z&1&ZGL38%UBdo?ew*M0c<|Rtc;N^3pf`HZz#rGPD7 zLy3+(edHx6*@(!S-?|FPb74;>ceII z_;wN{9BEW9~?#avB#l0}WVPEaD*Ata( zs{(3SS|M3@N!l50)~dSw^#4o6;hhZknKihH$04~v8#R=97YE)LnMhYUQo1LLE&RAb z@P4<*idG$&)Hxy{H>=OiGn%=bP&VWpL@0If=asy5gm0##RsQkPXZu2G_wB6YCdNo6 z)#p|{)@rL)Gl29*if^1a)-fhA+kyB%;Q`@0b*3?KP>n^B@_iFbFzvX|zEUOLTV+!d{ljSqx**2vIRnGWfQWlt4bF7fI02s$7J7^q=) z7tbw84NLEDpn^P38?xNsR9EU0qY%tyftWeYcHxy*Msz9m+ikao@vpx!s9)m9M6NTI zC{KxlM&q&35_ySY-u6Z%r@XGo7g3>G<)%FYaTS^QX6mu(bXr!%i-tZE@u5I7Q{I2Z z(zAg7f=a)BIP6FQ*eZ(58=U(!q};W!wdS$Wsw3b|OiYm6ncD4Up@@0T7h=8`eQvAF zi%`S2Oxg6z64F&z2Rxgq@XnJ?oPV~Obop>%IAp41_sX7bPbpo9NJjumL=|8VpE@gS zRU$xMY3Q~6AT13Uts5OcQ+HS7$)LgsIaTDnm%4|?ZtwHK>rdlS7ZdE`m%v=>Ii-7jAug3a)u8 zORs#heIY=c1&gmF`#rb_{C%Er7&oCP99uPT4wrZ0<>6OGzy3WL8U@QRq%(^pM~2ma zS5h)Z%FY$2M6ZQa*N(UoPm+4nDWjR);NdK7DHTUKA3a37#rCoWdOgruIltA9E3)@E#@W$XOkz_Zl zJw^|j_*!PWlTM+za=w4hq(HA1L?`z%{`P~trC@wUrh3Dkr>1XFX&Wg_Cv<4c!$KzU z%er&oOoxX;6B2T&fuvZu0WJr4_&j~~w~+t56P_d=Gzg;}-<_M+XTgO7?rVJKcSox% z6ad$d$WAw?G6QF`%&vJF-OC*i$4Gu+Vq1(&Zr1-dtd$+-QJx6R2X~E z(%Z=2J|_nE7KK74@T|yhzV194aYveAsvM*^f59uJ7c$L>y^l6r>D5> z^jLQKeI_6!4s3wSTE^@4c$EjACvQ9?9K}$OF%1t+`Ee~?q)PO*NFhS1WS?XjWEsZu z(Y3n_)n^V=X(qv*_}#!>wJv=QdiMg6b3wypMN1bU$UjG_F^r$P>%pa*$Cpf=suqbX-DjWBv6g|N8XV!TTo42-X_yY z8yt%%Ajkybwa%(>&21qlC64?VM?d<(>m^q)TtGXtz~-1YLpKJJ%l zbQEC8!7rrnu1oe>gBiGkB`IIXkb0_e-xTJPSI@L$hLvdep=_(5JP0|)coe$)af7F^ z!F8>Kt$bM(_i+7`!x8Cwu4-3j9teuDY@kJYX_$KZfkmQ7TuJ$;r6BV|G%eldlVLXA zBV^9hcsN70I?@dGjgJ)|89tVgsSbIQWfq26iT!Yz8OK8JL@`>V2@Nj;`90e_5q8H;sI+^HMzrq;8NC&{KvnLmgDB8reEjX(M6EkFj zmTZ5dFSUDOGj;X{hDWC{UkW#>oQg&rld-}cu}Cu}La$T`F?nqES+EP^FP`}(&LMcn z2X!;1su-)Nw}22}MANC798#Bk!tCSu-9~){B)X!ivi}Q=dQcTPGd?f~C(i7l99Wqw z?t0*)=unJ)PosZN^%=dwq(00i{15E^R%q~Fb&#)G$}>pzpd&t61%41;L|2@Z@jpEc zY#H2_$1>9rLmu$OzsFtu0Ew*-SLfUV({=FhO`*Xp?uS3Hf$QkY6)MOw+A%~D*Un@z84yb z)#751*_%5rRH%V15wZ#+joL)~!k9s9%nj`mWB*y9gat|*-CSxx$ZO-8d)YJgpKsAP zT9M?0*6tp4$i{X^^^5*3eD5RljJvKJ#vZN9qFY5pk-4DJq#c|XZk7fmE|I9a`hS&_ z>7kR?joFIinsZbQQCB6^Rgn~Kccw2N5F&bB+5U(CB=@tcBzXGUAR4A>5a#8`5(~X1c}_f^X1(ke5uGja)DFu6bPN^ z2qCFs@*B)qeK~lJVDk(E+rHT}u~5gg$u6-FmkAYjs8qgO44p3dDG=^9RokhbO`WQo zsB2D5E=~L}MY>cO7s?kTYEoSBjRp(*7I2cLVU`mpsJ-5Y{z9hH=3Af(%sgZW4;e-N z5$K3&1@}Ct^X5XWkHcBF8I+1sYKOHY$2TU&YAKqiRAbTN2oM2#q^W<%sf7nDcSf43 z4M#K=SiNRfx>?4}K_4GUFiQ$D!o&S5fYDoPnRrFl)`E&^a&1+mHXEvYHnC35-1AL_ z!c=2fW97c;_PX0k(Ehib^-E9tjBkuOK2p_na4N2ql(@64aLhbr4k)d0oWt2@^%^~S@?U;mpT(z;u;z7wnxY99YHdUqFQZnSs z8d718;B*(7V85~w%JWsMIPZhe(S{k;V5Tt1FVrf}yY**4LYaG#RzkUfXn{~w@Z9e_ zN>yoKfyZB40^WwC*7{*7rd8*s>ihlbgBQ@`FSf;VX=jDDeB6#=f(I$rRT+!y&wt?0 zPg2kEe;SO>VPoH2e5gxd`|uz672q4l6}DxXD_iNPLL0@=##)%mXPbb$y5#}vA43s# z+vm0Nl(0aZBLQgKl)(|5wSD^vwQ|={sDDJUKKy{k@Ej*Ywg_)K9|hNiHAQN`UHS{MvoM{|u5)nWcl8q6 z6r|-z#{68PC)6dZ#}6e8)?gERrqE?9%LUM_E_#RR=yB7G`(v&c7B#RY#8 zy%{I@5ZD}*+n|7Z(Pie?9Epnbpa2&Mzk99jZuP#;Pc<%SS2gEydR9ts8x^$Cf-|+M z4CA0~YjwYt(n!bA;XFw@R0Kh7Gn>dMZgEEQ9vY^kL5R)fh2pR z?pqbkV!}&v=ew_+*l~}bqk-aM97bzj7dDrkrg9G4^7pA#`=y7zVSL@%2sxB0zC^&Z zbMu$%`=`%49o}br1q}Iv6_Oy5&M^i_of0wV+D7#GMUf6lgFmDig*}wb zaYHJ|4Y<)Oug%7#m_*y$XO>*qmnNH%ztMC#|1?(;gaTW80qH5W1PBxMKY@=O42Hy~ zb6H^Mk|Et_gZA$KCDp}+Zs1VgybftP0nT~Gj1VWm(yDbYeNN7u|NkzT_+hB|DnhVs zR}d`|fG)92pk*oezHT)gj_(4TbGuJ|u1J7isQAjT|$paY-roTbtuG=eMTVgKgo62t(bB|BaQk6|o z!H7NQ1mT{6w1W!E$VG`jH&CO+p&pfeZr~RnW?v(30ZE>EIoD#H&+?jVnq8v-N{Wn* zAFqA2y>X5VU{VN88~)#|P8caJWi3^yvH10{Z5PbpyeK$6b~^yJL{f-YDBmjjl5I%c zGeY+7i90nR1$D#@-;4$^z>K2kU%WXE(TNU)lMadXM7`E%_8MJ!+H9JcHO9m&8}4El@jPk$_4c6kyy$n&F7$kB8mmOT6wg+<&yyZ-}29C4b^4j(G9 zf`h5fod2W12X-TtdDSeiKk0{nXiepN7XYo6Xi&)-Es_=X84*ZME;9~oneo}Dqm?Qm ziSimVn$si0VxlxMquZ`Z9vZ?%8yy>uCLVOXq+vAS5z3K+IWGGw!d(rx*Fx=}D_(N$ zg7>hip0VDrwd%X17(dr2TJh(}4uG#+KEb`{^h>V$U~nq#`#2)lB@saC~n9>;*H- zt!TzzJS+88radY>f7u9pncGNHUpCg!1u;0RPU#R7DzCl!AuHUSFTU-iGdG311}SJ* zLF|KZ+*5WTyyT&Au!sJ}Gs1GHdIf64Htr&}3@FpDRHx@96;^7w#x+$j8qE2dT(d+R zff`E(?eOd~5l=K7?Y^$0zFKgvZq5Gc2xOS8PRz6LJ4gXBCQI?j=mgVv%3SsM|WZ0&M-0~bB_kq#2GGD!f?PA`Lnd<_XG zXhmb7&g%toXI2<4L(ruJ!^^Juwb~G2;O=&fm0?0h+9Lr4T|jTKco#DRvD+Ll!!1@V zwLdVf=PI3SGYjPu?i6~LNMv8#1cBS)7hCr_(iY5KS6RI}*!=hi3vU;|=Q)wa1iDAv zW9QYk^*-jF;r;ID`U0BG$p^0-`Xi3(IhEqD*kngUR`cQiY1>C}2kKwa96O*t!91zs zuj$Vhd+CMb5fVgr;l<#XzE&9(Srciyfug32|TxrpKIzDh3s#0A|HLv9xSnGO1s{Q;Wx<~Y_AyQ`RrzR1T z2ctPH1UQkRUkp=~LA}w2=XGtSnW(d7gp-3a)m0TNOmyMTrUBO$S#Tmm>#^APz)PP% z8`e$EoSVCXo(Am!T+Ah=^@(I-&Oa%-pHMB84b?L#L78$$_4>*Xz793F;$}G@_aFY~{o1B}mu7 z9_awx`AfSJIfkI_yiNBB=DN~1JM|wPUf<1fj6TFoxWH9vdR4#L7L7~#!HGKwXlI4| zl3dDWh>t)V0=7hGi=BZ*GF~~Y?(}AWr=-WJCg57VWbYBuSb0)KypCgE(r@Ork8$*I z0I>%_A(OL1e=D<>vjT(iPYDuY;oed$X9rMQjW!sEI+#%dVBYLESY8O*k;lMA?C#|@ot}Z zmL;dTc8g=u%*{)deo_!%^S^ez1TMXp{P?&Vk#dKp-EMG$o>B~`Fz{7kq)5rVq@njD z;^HhA$|^BitMiw?3YH~p7w^{<7y*0-Ho{~B+Q^0O8Cyu&?!nH7GpPkkvmVrv;pA#` zc(z0EnSs%-`xe)Xwafs)xVEt_<@47-8L-JF!>oGcGD6K1lZ%PYXiRD#-;L!AR*pT1 z^KRGgBP7pBc7rhm5@+5a1gL-x|2QSU%i6?X?f=JWGa5&F-+jedL9fo)`Hal(yH0_d zgQuP`g1I3)_YhYSB-KAaH51))x5^ogU~@-4grMy0OBx`SZPG!%idRadbM0s=b(8*c zz{AZ`i+XENL+XFlde-YA8Kk}WyhFn}O#ER$>le3EW?@YLh7B7ucc+j;%n%!Ebf zd#YO+k89F<2Sl0@YrExaFS2?&MzLcW)2XTDc7bd8{QFsSBeV3-e;OD$J4B7u4GjH3 zHE1@cyAqs0$~m!2DBS}wT71q7m~*!}Y9hh5Zm1)R|547N(`K@i7R|GW;<3aDkA$b{ zjlmRB!y-6qWZ`GW7gh^kZAsHWvo6}?o&UJc<{t6wfF=5S#G9VQlkkBdtVNX{WiWpj z1enn<4CT`m7|kTv0nBLrjy?AUG!v{)i^>7tHKA-{?%~&7=`e*WL~a_x1!ej=xvOE! zpedMdlHN%*t$B~|vY3=)i91J=U@t8)CU67gb-qGz^0Gqlg6dN^I*_N-3aj76b^d#1 z$ggCK2uQx8qx?=w5Aa#_!wDGJGRcCI85cSQX34BZ=61oHJ4ANSD}@Gc6eEB!q^)22 z$U8FV4s2l&2Hdlg3|2a>+^=`nYh8*)QzsYRR?^Z8K=ug)q?Ay~Fya4vO`4b9FQZfG zeFGzUSZL!0*0sD*ZwytJ2eA73_}D9>Nq(y`w|oTD)Js?~zq43kal?`^c4 z(N=k@SGk{5^k~Z6Sj{sjZg*fcr}(Tky16bQG=ro9Y`wwgec12L`i-YOU2H}MUN(O< zrh&f``9fVDP_dCL7+;hH95D&WtgR1eCthU%e{7vyR;n^W`&wV^N70}=$9|99#pYEXfQ5|(`IG{ zi)*{OlB6Au%Hu<-Hi#LfKapGV$_m!PsB%>mM2JqDoFv%KZQrDmT$L+K=04W2SPGE8kyVFbclKecrA# zjTfNh8h^MdBTc&-I3a>O_T?^Cj0|ysLD`Jg@1UrmDjoGx9nAcFd109df4@lBTQ_Uc zQY8}zYjr=tyu}%>&!xRrh-B7U9%f7ADxfN?ty)Bb07SHXU#Zg^fNZ72ie-fPgBi!*S2>hxEJM;8E#x_TKmY7r=l;D z%3m;nThq9a9C9I#K7<=yM4S?;7UlF4Ax3ttB~mj6S3Y9?5I}8DELlf(l3mFu8N9Z1 z_7!pPz3@6kT2`M18ZjEN8KR9@JJ9-tvP9xJ!`s({+jP{5(j!Gh^}Pds3<@aWNn^zq zZ<&@2fvqC&$37`x#cE;^LIfFy{PZNNx^Pgqb3hNpB{! zt~eY!PkeJU`Q|M^Erz*!h!!4F5xKcWg+zhE*4&j9SPBa)61MxG2e^t$)#kqn%mAI$ z^9oH%8Kq*yhF!3176<2bb@$EqBNY4`>ki2@5u14TWkkOeFl#Rtb!>q)fEg*X=flX`Y$(9=W?#Wiy$nB>G-m@QU{^3F`mYJ=yZYjZ&+Hh>1jntoZ& zxp#2@d&p`0ELmxbcOjqZe{X{CqEB&7{LEL(L zB@V|i9So9IbbBv-ydaWqUI@kse|WkY3&k>H;DGwLpO{2157yLr%aAY0_;zlM zBcYmXQdsv*R~V%&QrDkhDN(4e=drB2s__fa*Z;nFdhI}e1na`1jFNBg_14w=8rVgV zI1>ellcPf$y?U8^!q{Gx+C9F(0hBw(c7bzHspS`UjhP7k5~NlxXiEEVeA-W5yZd%; zG{)>M7xa#SH_i9#xsaf!Qpq>~NUW5zdndXBJ_?YwsL|9%1!JO>Ok)O*Yx!KfEPgG7 z@`Rr-#P_C)u%%E?;yk!0KeAkQz<_qzdpM9vK|bVUu8{G~cuZkr$-EYXq2huJ;HVu^y(j^KnoDhM zLdakNb>=+?$14Dsw35Q%rrmUhlDw+A@TiL%1Yj`%YXAxf=8NJwNgAnW7vjBaEN*Ig z23R@TsMM8JazgtYU{eWhA9`$)x+g9UDtAnt8Z;*9y#%i@P>dx`(n0Bopi#SWgYo|= zBeU(S6Mvq>Ka&Of6196j<<#?SsQ%0N{wCJpuhH76HQ3A4t>;ejy#7zn-k|9qJ0!c= z&1puyQo%bz%91N*MIc4NA)Q+`#h{O3#gD_Ji{TL`1#VAc83@wcs!1Hr5g6dqRsZ&a%Y%@?KAmf zk}bOUbwXB69$YRo3)C`)%=*Iyp(W{n`fTEXu^xFFpA$(qslHHV_jP^3kI69VjKS@@ zs4@7Mz0ViP|2WD4Kila1a$Bkf_{3pNeQWyUBpFhaQyP$;##|MkqKM`DiBqJ&K8EBu z7`?$$nB)Fb2OB|A;ctd-;weyR*={+LczcU4C5%&Va~PHTu#S5 z@bH}D+n9Kmp*-<;;>5tWdB;Yt&b(>1BWT1-UF7gAY#cq$?%moEFA^i0^-A*NQC-$2 zE9eDv<7xn|4@9W-3S#3)_UkmW3c9w*NLz1z|2R{B$J1z~ggj3NsjKr%N~1l-!CR3m z_yx^bAp*$hC+l}=ywdPH>xTBU_fgeC1J+gRg_i}Csx$4|ukHof?BALhUT7V3%ylCf zK8lmXOIs&1%F*e};zT0)$HJlICiB07K?3Qq6vIHWLE5tqxv|G71l)@t=4p6|0ykyn zLYHqqJJQU>jhxwl$xS>N#HN2($U z+yXiZ(8lusCD#X^mljw?``yt?aiIu9W^@4i$pNNq4wq|~A@Uey;!NR=&` zNAym5qrUy0-G*#0=DIEXRP<5$kT-OcD6&&c07qq#;fZT^Vs-ddS$(pswmG^6S7&c? zL`Zop9Muz^*=JC8U`p`_{gsnOM!2kEd+~6}7%R0$L$27u$T;j>Fke&3qO+`MAdg+X z*SKF_AR$W$B(=F;`dl6I_ZVUEnEf%w@;Ol3!I<-Ipkac@eYT*e1Z%u&g)l_ULp|1T zZ#v=cQ=o?BtFDG*qyR%%YsARqI4EJ_`o#Mgv=(TpDyUpeNrRN^``)l7*?*807&KzG z#n$(35o`Ugq<_?Px>pY&*?4>m2R!-YLq9{fb7*oh2ph<_B3Hh~=NK8XWRkijoD@ri zrHS65;C%2QzD_`WdIK`kKrv<0vfL50>Ikc}oM$W=0G$E{l~H?nK!qVK$5(^o-~lVj z!x!0QVJHoMf(ZOLq0Iod-J707@L!~Ck*g&}5N}rrjgR($JWWl$yOZrxdqWJdNJTmg zEh#0jIN>uIHG0dyZF_QveHk?JO!x`1rblM=4)PdEmk}g{$nMkXC$c%lFJ3&h)HyGE8 z)#IdvB+rZ+zoNcE3|`XRA-9h;(hy^{^RtZb$qnpx4s?`xtX&-M?UZIpWzcjb6T17b zPQ&0D!b_CfF;wQ#2@c2Md&bQq_+BYHdkU=A`3HI{Cr}G^8=<7byU;JIQW*_-*>^sJ zL_qA-AWRjKP06H1L-4w6@7U`#r9!~V` zo(GfS6-MPMz0q8ZO3Bs21LvGK)9dXnwvw_r5>RLQ$eFKCR)o0vzZFS$-?sDBd*tNi zdsKKcY^EQX%Ytg>H;-AUCR}oX5$-9{gpEu| z?w(5AEEBJ>sRK#mtk`w_cJi%u5TyEuNQHkDDc|WPT1AxO!klL(EuK+ZH=+eS$P9Jo zd)lyI4#zHQ5=wb~*N2mKYbJ85RxS`}M_Wx{reDOW5 zu+<5{$Ra2G$UejF#d}yqKD@BWl`3?y;aSRj(anrtl(4qBOz9B+ZZVe_9v z=3W}H-5K}YAM)3sl&)nOO z?~%c-QUsgTtc9-tVs09R&0a!T2~ds`O`={mT<+7o_&UF@HNV1X&rVuTr=hQu4;m@IK;#T*qg_ zPtId-yhdLk!tMxZlUoQ$q)SBI*aNqZE+=c7`8OO6h8HO!qsLA&M$TI{p)$-S9_2C7 zRy_*(Fejz8DAMgUUfGPf-HNHK!L9t37L*Y`AU;metS zsaCHN-3QqTCqj4TpjxMAQVh{vhq4l6EZH+@QZ3!T)~UaS30b7K87WB_+UUY1g}Can z;fsc%}2>=ZwMQt8*`uB^F{yKpn{O ziGna_{n*@Xt5-yWlJJOAmNL9|Qc-Y;eEv(=iSkAN*2oC4XKP*+5_2WdluXO~H?ufw zMfe?y5g#tHND~p?d$C`&>|?OT`{5X%khwN8ZOaN_+0!@9#uj=wYZ7z9I_{=_3Dsya z=_jZdWy$jBGejJ`dM{zOtqcY>n_uk=P~C}tTro?3`u$J#TS6#3s)#(m=)s|#w6R~u z6OnA&l&$C;&Joy~x2Sg3;J5I?-cVVO7TyB!BgbJ$WGLJTj>0li_EcKYZ0qvrUMRzN zhm~*XDmYIwIrS`MK8vK12|3?TA&~DtWw6B+jVK((iLzj_bk|yF0YvpVgtBnC)3C-) zYZjVv(gR1B_XC@845ONgKSGcS$^dCH(g+!=6F!oS+X zcrL@nsv@3774knOCf%CuQ9bZ&B4+|;hwPdE64+eh;uS~Cv}oQ;ij$|@?~I**X(Z31 zyzYsT8rpt84rN#+safE{#`!Y^1mT}riZ!8#JS6dgr|=81CgE5hw9VFzi1FhX_~O0|(C4AP z)T7{lD3ac(n^8s7+ryQ@rkWFHe9 z=HXls{Mr-_u~QOTCBz2w35sJxYt^jhdjxa(OB2C$!od?oti49#B?9We41zBt-RSdp zy*c57bE&te81}hXy8x2N2iWfeH=xSrEGRJIEyNtjN9C@*RblxkkCV7G&!?U3fZrH& zY=QdqI(Rg>M39~U4DUV|V+Q%U*9XJ+1f(WVme2HV&18#$jJdJB;Q><4v~GIQlj`um?}Blu6pkgCdtMrP_!_Xb`WoCwBp#+#CgP z#Zu5mRmj`Kk5GnPsL~JmC_*OnW0rKb<)Z~vd2n7;o_frez)%(%cuid>muXt+9;9(n_zfmt~^)1FIHsDX67 z7zD-ET2ix^`jAanH$n3)BSjX!Y7G)1yQs=a6jA9IF5BW9k<~=aPLS?Ml-KQU z;C2d`Zrr+jq0fHiGPPo7I!Fv1N_fOPDO$Gh@e;Omle)GK_*G+|k2Vqv6%RHpH( z4~n!mZyEnFq5p{1@}fFgOVZ*97`I+pp=ao!x$A04_}~&mY26;foRW5+b2JZop(Xf);lAlgkwTL<0uFz_&9HIWeIt-95wf$gyUcVF2|0L>m^!MP` z$ut+07)^Ji`iqHI)KnvY{rL5XSY4unIKh!LC>-SP5?vhuI890P|MYzNtI@HvnC6YUvOM9Ou#gOQp)3+ehU6>S(5mw zd|8HDB-&K{ClflSR`zaSQYqY5Xcm89Xv?bkf7YJZejJ0=itr?Z0M zwSBJdp0!3Hd3A0CpxSb$O=VFxT$Et`J1EY98Zo}9RRZJ2xVTX%{xt`hV%ysVkA1x- zfO)LciR}bUO^!8wU3OW#)_cXq`$X9}mSaljMTHh3^Aalf?OX5lh;k19>BOOw4+0QB zYF#qfT_Ja3@r#Cxv4BG+m;XY5F>-xxu(l5T;ALVY|_sVoc?+zH_(1M0io=|C;Q}~ zsP2fMcNY@SVZu<&Vrq|RVCqqr^zqQ4b0#(L_a*@%b7lDW@qNCBgXg~fmC$Iu>&JI@ z3aOxQQ!`XO_6Y&9fCY=)o}qD?ZFwVwq!Ky`ljhOXh?R4qi2)a({6n$QVEP1qQ8L(> z1{Bf@Q4HZO&{VIxT2&o+y@fxk_Bcra!pxRT+FjuZfi<%B<$~QRIPWiLhKFTsG(4eTueHouopy?8 z{qMF%xU)2WBAv9atET^QIsR`DMB_fpPuA@Ghq zQW5RS`o--JdumYCf(Id38ua7XGq$LVpLf=|)l3)&q^E))NPr%BWBZ5DR-@&jYA#t2 z1E0Y|f{9WtwhsMc)c1B#h~rfu^|9^%OW|<;qN2L9H4f{CrCfS91k0=uqHI+?2+RZ< z5xsfe5}ruma&qO9sg>hgRm#&?Hfn*~(qE zxmoA$WCQv?Fom)l4*SHhAqONY=GEKL>3dJy9`9vWQb;bX-QbH;ZR(Jvz?^-Yz$%N$ z4=ouFONp@MU$fvcK`{PD4o{W^78?^|0?q!uM-)IqOTB{9^J~#NGH44X)FamPXHZa$ zbjl-;61UV&y?!Ej#a$fqx>+fv@uwudJiVw@ADnfyM`os7_JaAb2-iT9{$%gbQ+N+v zZEvQl9a1CXBkt%zxu@^w+{-=P0E6dSmBgni~Js&R4lsr|mX$#Z2qzVT_ET;|uypn)hG8Vzx(Dn23n`*mb7Dz@^ksu+e@*#~rQ(%hIL zLvTa!Cq>5e$|7J}P6}fV1DhGW#U?QbSBnCR^kLj1w+MOVjQ&rUQr5`+twnVXMpTeR4=HR?u_9SU`&*UWA zr&&tO5XK~!7o}3JvGeIcj6PVRq77{b{V*98ar^Bumu%jA3eB1=`9DnALrlALy zSiX;`vULJ~`N4*kuABnu{K&fC@^FrTIXtI-5T--}bVX{*-Sv7V$d3+ynwk@aeoGa_ z4-`b(eai8HV_p-F0+lQ!vZ5XGLI4ND@@ux9U&}tk_JJ0G0yhL^*T!6-Lr<;uYnCO>y1-1y*>wiD4gZ>q_=Th zff14Zk3{YMzZMHD*(3XV$A7Jb3d#Q4jtE%k87JPA**G8-c_BofAxf$;2x1z}E;+uT zQ6waKFLTg4kqdPs*AC>cTrlhw4q!>C40{tT?wzaZezx#S>rs3lNOW2t9#{uvn4S}C z4hDw5t+viGS$2~MkLYG93(&Jcxh)KRFLg!S5mPC;*fZcT*J-5$I@l&V>}>DX2(yR96i*3{yt7S}QHy({QLz5E zBQDg1!UDoE+rks9!dsSZbdGx1o=UBB;PfHqJ)mWX|0!I|Ju4l@UaEfx(Z%Vl%4L4^ zPXBG}C>v~*xS@RhlY8Lr-aa;&p!T$73D5(IH)c#X;QdIYj65`(2v_=2Tn~sPe$Pz2 z*wJ#))sf4UPuG>v!Tx1ov(1wDYs4C5g*N2s5c+U%J&5YXV9%cGgxCqs10*!ud2T^v z$g^B9qjPE>9HU+fDH*4)f&SDzoEIhQ>kk6K)>AD7uuuUag}?aZHhMPmMJab`|7`Zx zu`>=S6KY`%6a}AofcPvtO?Ghn!?D!B_zI4j|BvU3ebkM7RK~&=)snbzZjK~#s{AlifP4c@_1dJ43O>=Ad{g;kwGhEV0)uF0&KSZ;MTGn`x-f9DPx1)vC z+%-h((R)40*@E%`K<`1d3>lU*2|F&gc-r zIy-@zrtHm`_V#Y)s7T*;%OEgPhEw(`S`9tv)B;h&M``))G_!Yxlxsy6;EUdLmto#_ zntMp*=;jzjeeEa${2`9sb3BncDF$hbyjYVXmIT2wcSSCgBn9wvo;9@6Gc<1DM-h$R z*~Ka2VI`21>^%hC#J;VA!zxK~25M=q@Z2n-;T*^wMdeX(Z=M8Nb<~je292oC!<5ix;c@nO>Fw!83p-jJ0AXM~_>Gm?)ZfvNj1e4G&?R zZXyna>^$uPkkUyDHt276*+rYD>9I_JIjKiSL!^vAhUo720jrM11^js|kIgdotw`bw zBS$L@OD#Nuk@S&?9HG|oV|sM{Sl;OF#)HOZlOi?LH!bC=$u$Y*0epj(lKB?hK5ArT z8-Q1px$%($d~O+aM$93kr2ua+?+sO3Tb0*y&j6@+nGIeVB`FI>OjA}DzhDkl#soOF zg}NxYTdpHnWEE|Qp;fW2keHH7OVm^oH)!<-74l#iRipim)oPSs8_^&giK4?!{X^7k z6CiK4alsva9@pPmBJp+d!Z?=^lZ6U0{NXN3tX)SeTK}}C%k#aGRb`VQ^P5!-PxLZj zYiJIoL#THdJv|r1B|kgPG9;B`=HOkNG_WB*=wUlR@z~5MnT0|uv;(%-25p-dvggvs zPLJ@ExFrUV??rkI$L0rjK>u^|=7|ky+alCmXW3 zHORm5ONX3;-JybOnqViWU812vm2t0o8!{%e z(v-vdw!cs493W%Ufkq~I6_~a-doFnmG^%jLrSm$ArVpl$yTh{6Vft#Hx2k&S4j6j$ z-Q;U%)a?o;pg4{dM1Uo0%&U0qg4fReIgA}F;g~hXGP#BNkC@psL=nLawm(SVd_B=^ zmDo&i8a;K?s8q|j(u0TnpV9NoWKrBuD_3^rwm8>CUa{3{l^uYh=S$b`RBKi*s$QBr zkRXAg+7x~ zeIrM>++1+?N_;q3AvYfcN1ptQLVmRpMD_b@di!Dt2p>cHc-o)B{_>0dBK?=f76sVC zueY@0tzyvC!dX6T+h09!CxIA27187V67`iq7?iU!LYM=l`29Uk**7|ZggjTeiey_| z(6`CZSoW&mkj*3aeqIQEiqMS_-cJBx{(waPJ|Zh{3@W@j&~;}3`}|Rp4(Kd07H`8Y zuYVPW*maS2AIeajSe|2D4f6^-l;MlsiNriXJh_xu@H?J7?i>F_1}k6SN`?&ho7$VM zts(faFw@ z6tXR76gLJTv6>S!q=4c93HHOpx#j539?S0SD9#;MR{LxnftZ>fm@0Wr%#-_ROdOE0 zjPwh83Q4$b1ak$?`C72qyW^ZSmRPblT3VrSOdzjs;wPpt`}h@+!q2}w+*X^Ywrf(d z04V6Htb(~p!&ecBsG}zkT5cpMEPz9(FI9%-nf^zQaIiN}ATjt+vMnlvAC2+?u3`DA z(8S!s57W;=D?rM<6hJ^VOIo&(AnZd1TxDm!Ts$xP+Zr5C%zML2fwnx)eE&6N$}wc& z{qqYirq1U#rn<46Xa@&a^@+;ef7jx#_R43R+R=h#;OmNkM_uWXGS%F02hZu1QXvKL z6FeuV59*-Qrj8+XQY&$K_P{rTi*^yJ2EAI1R7ZKEV(s2&2Kwr+aLU^3^5bLlhINMi z!)C@xpJN$+k_~L2eHT8omuPCqParYT}l*j|^)FkIw6j z*4a{f==y}!7f!YbNz!8NP;fGAy`(@A@lao8z=n=6R6h`;VPALqN zj7?>~T*zeiCDE>M5Z*4+1sBzE*h5D<+HGcqDagK}r@q%}1Uf&6&u2U3R^Vt`5A8hE z&1M@MHl^WL?AOsXk4*AaDwFQ2=s$!7)I#rD7|OHusa9S@un}{CgNWY5ui&~7jx>H~ z&3a5hP{JHA>v3fYdgBM+CgP}jf1xs2e|%vXNtOpR)y6DX{#?Lq%`D~aV$XP}qokm$ z#{k^NfFpomzze@Z0HHO>cdTGaZHfE?$0zt}<~H}fN~#C1|@W>!rJ+By84Vl`AZ zaQvr5EkUV+QixecRT>A>k>$etl6}Nx2Dv#}+VZf2~K;oUDh?XtwN^(LQW_+Cs%H z@H(-TznZ~u6Ira#tFQ_Qx^w=v(-FHKz@Rdo0kLpwUiPKPT?nxbk#Gc;piT=vJ_UPZ z_3taW`!@A>%$ha|>f-k$Yaa93lA{hSBZQ5>FJxgLr{Hv;YW+x;8X1yGV}za+PIT1E zRm~bM4Kx4&O)XSa?ZI(r9}iSVQ1#V)oq_Hn@^T)U#B-eN@@?QN6I7V6HI#Cvd&d#I zEYVjh5xY2`bu1+5n%eW~4E1pCxe^SZ(m$O6oDpx+tX`WFzbmFcU!&I&1Gad`U|I>EvzwoXND(dJueie^jYzEB^h2R@yfFo zx#0d1nt5&AEAZqjsAI-WCd&_KM{-Q-bh=jEkPHg^!+*Ye!{3Jmn)fNQq#{rw{f$6| zl>dY75CI^OMkbge9OJW+(cN_M|Em(`7CA1^q-J`lNr~hXe5Z{%N6C}#UUxQ}OoXoy z1nBYetsuVVk&yT-vc09}Gm4H%v*(G;7fDASLYVN7t~H|%3h!EJC1w{PfK6ixG(aH9A?$me+TmUL z(K|4r?F^K*^x~7+QV0cL^SqBddEbk#(MI(rqAe2}_R4yLP7}t?+|&4Z82sHL`Y)=_ zIK^(m#Q7xLT2d-kkpZQQ%^GW7q~-7lXHw4^q&`4d4Bc%V`4j;Uf1;Wn<|-s`HvF17 z)0zk#dc$ZhLcF7ldcjTj75#RvYtraVtV0fC{sA$EI{4WA%pAhen^}QBQd2Vr;G=V^ z@Gm)C;U=I;UnxPwgo`Y30CFMVU2-RK1jTTxky{I547SPaXOL!>4W>$tG(N90o%Gx8 zH%*dmE}^jK9(axuwfUUg2_S99--dqEzxr^%wYcEy@l<7o(w&eN6?qg7WJ;5qvdm3# z8!ckWCq84-93d5o!%?5~W@s77VmJS;N5Eav=2b4s5=IN|4HYBQh|qGsIqcFY44flq zD~E7y;fXF?-&zUvPD1c#SM!F=hE1tx0%g6`xdrt>@09>9oB^zbB1ImdC!I;_oy?o# zL;@^_@JcPBDC~&k zt<|NWXax^V;OYxDmK%6Uu>yR!h3m?+sUSK%^CSWM+vzxr20J8N4PO4gMz&&Wn}a9x zw@-+IUO^6mkU$z~V(51s$Q-xqW7izSu8k&{acf8?g7*cShTTL3YM8O16+&K~aM7sM zvI@XjNCs=AnJ*4C7adG>bAao1$s;8?WyM@dJ&Xz2&bvgF$+c2hd5i6v%(eY;%Iswm zpG8lhHS8>jua0{-06Cz2N=4vFCp^5na(&QN1$xmXeN`flxDq;X&WPw-k6OoLA%8Nr z{|{FFW6Bz9V9K4V!1;QZ#PS{8h~eWyyzRg15p!L~FokUb_aR3RX3Nu_W%F9(TFkpS z>Py(4F6+pBi*kl$Cd-TZ)3RExHHxhFopM&nv>sOaYfLjv;0h>4I9zpDL)NSeS-g1| z^0Tarlanw;%Sw^6apU0j`V=(f?CIlIP^dl)eK|F<@>0bL+9I<>2G8Yh6)bTgm+%1b zREMncO()k=zg5^%lRmz7QK8r3%^bYrZII0At?GfdnB*Yvg)y8q; zv|*_&Q_H;~8oCwyhZgIycui-~q|WXmRg0FlR;GsaTmDTLpjBy#PK~P<*F|#;`BFWq z_7rg&2Ku+Wp|vkjL`2&d25NfX{Q1%TvVrmG-yo zXPvG3P+m{Iuku9<`C6~VdZ@NAuh%he8wQHx^sr-xu&@^Q#JBHN*J^<{!!#nMUVE@(39**s z(0ak!&PJIdvLwZQ+TkthERe712DeddIx_6IIiYiGo&e-p%NpGojRUdiW&^&+-F;#_ zS%oJ}SoStau>#Hv&mU{LX4 zoVw(9uOEB_Fk!?}Yu;}x{CYxW#p?@dOjO)E!6EQFr@RTW5yQgfXB_Q=F_vCNDVl7s zV^tBR!zP|_%EbmwBeTe?!st-3&iCZ$>H$<@^)g^s>MfND_r12_n@2vZPGDyorMt~` z>%*|+ck#_dnV(Y7g3Vt{Dl^>XBOF{qxrPZNQCsiZGqKR?lQJn9qVFzKJEgr@0l!{F zSC0aDZ?azWA!B==`!>u*|9jDMD|Yl|x=%yT-m2#Mg!@NqaI9acK3smK-2Z!(u|#Ke z&qHSPo!zqBjf%&@PW41w(d8cAS61doP4Th^y7U zfagm;2`eu7MseqjhC4n#EUk-`PI*g&bEU)w8$2qV|Q@f$*U8mKbEDFC$aBuuvm9ev+pb~?gETS=X zKTNZK#*c(FT$W%xUK8`?P__LMiBuv|t6%X)nRMqr37IgmqhWS8F)0;Q@-k!{!loDq zIA}6@WD1ixCNOmNSV{c|f^`?;){W01Uc~0uoR&{vU7Aa$+Eiu!$scEaUem^zbxbZi zGLiavlLPBi31P?z+}^VGQDMWJIE2HYm$STUsGd~mvQ1aa?+=&YsMkWm!0Y}K7iKKT z@}D%+$V8kZ7SLszX#kR9g9U&plQ^Oia#k&$Jz4jkhq)u97YJS6$MfAOTx5&rNzjB| zCT#FXD{|nLKB(^bEC2bW84eMx(Ii@nN1E)8f&=-)i9RH~e=1yv;5*pZ7OZ<+if}$d zDgfT|<;^kB{l95L#Xvcxf`>9O%cku;r5aT|J!CO#z$+{CFhv z7F_}PBIIi&DMYp|mOQMc@Xq`u=-LEdX~@o|VvpuIQMLjh8Z!w1n-5JKOkJBb`*4%E zY`fq>vZ}Ig^?-2{H6kiX%}iG6v=`_hv6LbEf4S)}gFDCUgnsh$O4~%TA%_0t06|hl z3t4%&f-sCVRU&?~ayg$5squ*k77{W0uJ_{3D17G7E5EY?rVio;yDWo9gVvYDw2xqS zO`1~9Lr9~8wIIiw$*Bc1SDbeq8A9UzB-ytwbG$=-!JM~i8c^Q#8G+DFp8yrkCVOlt z$dK?{Z&sWWI8gf~e^$oMgimlUZ}PW_{fqX-sakAfU%bfsA^+PwF`qhl{}>)$-ELtb zAn7!KiN_UNNRx4`g7uCH(cm{5Moc|MC0ePCHx^TaFqi?0BXb$K;>+lX>sm$0vSwv9 zTsq~G&{kXCV^SC}-_+n_dY3zzrjA>7`FFIf2N%B0^L2ia8g>D@pNSqK*U6~JN9C~W zv6qAa6;0{}^7+N3b@l|4x$aG?pe?d(u;*>~LtH#XMR)Mm?f6|=L@%_ypSKKG>`NsT z`}NSTGLNrnNY)0a2c_R%nkRweYvz~DM5|=H)oP1=oVHoEBynxWqXch@&j%EZL~`M4#`jT`j@&CPsP*qNdY}C&DDIh08&sB>_?n(fOfLwh zZ$`~07+cAxaYB{?um<$1AoT-$n2`gmLHGc4@kPhU-)7B9@qqapyu_Qkf;&$x%G)7V zRzM3X%9YH`b|=3GbhLq8p^{aJ=tp==lCcqGJ*1`$XxiV*1%a_vX0iEbL{-sptDCs| z#;{b)$O0o@A7osd^kYyCGvL_2+Xrd%ZL!$>?IDeWqTs@#zw9=CyD~x&d$!t0 zw3(!oC&qjh+)egJNMZ1>j%4c4Of$TF6B~U0;wPdy>s>RBk6A~g-? zb}%IwviBfJZ}ipF24CWrLy61D_SPY|5m#v;=Z_iPc|1zd6oWH;;qM6!$42$k$vI>71XMxi7^ z;5G1fGHod+hHDhbnl1(2mw(o$NDOTg2l~PN2Q3WgrnekN$DpEEG0uaVUh4s8PFZP4 zs{gba#G|Df?CFi-)a`?Q2dYbC4nGG4SpF7Fw+Dt5(%0a!Drrj_Wt~yan3W0IgA{5u zPZ3rH7_GZfCv_FH738x&l3T-GFMRc=a_y|s#?{fWF(O`&bK-y8*Jh)<#zr@H zcU`bj?P)@q*WB;FWvGVrHBRMgKOcX^%ouOL?*4Oh^8)BCfSgR+e@zo)a`+3L2JyyS zY@Q#mG?>cC4vhNjY8DV*baxOe@UL1n7vt*cBh0D0y>yS)7CH+h1dkV%69hfyg&jt`g zO>K3gUm8;HB-wWF)`*c%1PhU6q z>f2If?qg~Pv_w2iSygqj+TGxThf`hM7qgP$?>y#KjnPk;zkBaM)I3`zm&^_%DvOZY zTgVu=k>NSUbJ;=G)bv$YIi``fqxv>pv`SltFAP(9xdX#Q;AoJY`~6*EkA7UyeO2ZK zcovuG-M>;N{-lMl*x zxqI5g$7-U!L!`lqkjJXsb{om5EIK4F_Epv`49B;V6uC2H%yU|FwgB3c3Q_fIHx;!r za7+y_n5xa98Q(3b@R{(neJ-l9S$Tkz6_!{5)9x+AWzX_6dtvZkX5P(OgXzE1S^59) zyA;ZSR;&$rA|x%9Wd}cx5u`>S_$wRT{fknHrgsfuyi;?Z8*I8_a-M%?o9lP89;!qP z`#zS~*%O;dwp7##wplJvL!<~d@Mi!-zFDsB6)3w*VpR9(^Vyzr3z zq`5s$;cE1>MHy0MhzF|bARovHFW7)c;(|5BtKj4Id|MI5MMf-==J;5IxYH4_L+g*r z`Rhcw5l0+xiH5M>1;*Gm1-!X%HvFhR+P(Obg-VHl{=E}B2XV)!+J}vGHIz_y3T3uW z-a2o?r31siA(Li<-C>GBKW-^0D{JHBk>z`QNanZY0h_SWeTmn#ce&kUy@B>&_s90; zROQHszfJMJY9Y0h_O58s=^)WLc`Ase$gANr?M|TsmpmW_?#bfnz;)pEiLIvPs7^N% zy{PMs`KZR^xdVEMQa} zV0sb^){I4iszr}YZ=!cAW>ZR`8Q0OmngL|Y0z(~|5Vx@2^8WH$=PM67ah6j*un^u4zM zp2s&S(+8yz=ZCl)(x&tg*31NijM6J4gWuVlPMOHM@HzmCv|L-jmhEO&Nea1(dovEs zf&GcoW^91H1v4Fjk@H}3l?Fq(PQndzhPkO{xp9K~Gx4ql6~@!0U1chzeBgAn0vlK! zBNO!)YsKVOy=G!NV1yw5^e|2U0UEy~q@2q=9s_YWVRY{Y3}l9J`ZQrINByvrv!!g* z&AGLJ*(8dQtpubKP#~kGe?7gqY!C%#n4=viXIk<@vVdLwEQ>rDoB}KLpsN<)ZQ-)RG7v8OlCDT1U+zf_D0MFt?yt5uNK}UypetY5_6s}mNLW%wX#m#khZQ#d=!u5?tTi$m;7Wq1_vxjIUHEVqfWQjJ)+ zr5o^5CjEm?P-!b2gqW+jWm-fDmT{>C1?fg z_ovi!m2Y~yZw$Ic3?o}bkCpz^RF>=qRjN6ab^(uAkp0Y6jqNr+kYj{axte=%$Kb3g zWwJlFIdFeqO{6^*3;`Ojn^^qJ{Enny@*+h{4s3k5Be-L~pQ#lJy-o&&Dj0Tc9%Bu| zD3H*{2A&t`9`;E+$YoEuT~lkAwS8Le;U)yM9a0ws8Ll(7l*?GkkZ=wuSJdy#=8X9` z2D73yQ?4XuToy&GL~J~(vaPeo|H7ELUuntw<;UQn;fKnS05?+co&d+qUEYOh-0J%q z5FnIe#IoCK1{H&P@Iqud!V;d;Vd6-#)`m5h;eH>uQZn#L4$}|ck1a*jT{;7kJ>O5b zH?%KXhBzz4QcQO`u{3P0!DokoJ7Abrt_&^WZ_9w;{cbL#w@l5`=%Csczkp+~!=-t7 z@44X;^}tFQjw=j=NE4s`(&GXV5OBQTh7|vPf-r3dTQP882T9qS(tji&rl%6f9jg6G zuylCx%pUk}b!1M}PINrWlCKk0J~ep7XhLYj5v(AWT{?Wi;YK0YeMBoMjkB<<@zW8D zoG$+&K6aXOXY;xjG+1Glpc#z4z1fU!ZV`&k07r85=X}28{yA=BY80?9`9;(IjnUVvhUfW1~x|XY9^>n zreKh=1c&l3>~cAIW0t<{WabKFeESrF!p@1B_cEoUlma_fb@(SdrCRtec#Up_i7PDM z$#FCnj-*>E#ENVoeS2A?k1b$!I$6urDOZS-NHKgqpY)AR0;9xdU{YU`0FbAw7f*kt z3OvF%1CV!@&QKSKkMdL5`Uqy!va|qOhPrXnxVOvXYvP_-j`j6tDYsCsAJnW?k?F^e zwZnUjj$Y}RmX5{yC}fm-K~wuxj)#mE;Fyxm1o^Pa(CTA%%PK>Jf1nlagVn-zdF3H< zkd}1iu^RKilp?oIH?Yo&uXEy&(+m%8qj3O9nKYCx#J&^%EuDwEs>px%dU-&sROvA+`(yypRlsKFxQ^jkgL;4jCa- zY1PI|fj)2o;+Lfok2^*BBkIfui`HhaAn5UY>2rvCy_2`A+B|8 zMSSqwd32F+@=eaaA7BayVsT017G!;SU$Xr_f@JJ}Vov$p)X1X~4Vo;l`qcASb&-Po zhE{rO6=@Z&i;JZLg=={_LQ&wcUttAo^KDWd(_uK|YM_)}<*W_ROI4+Lp*}LM;^Kj+lJrVc<;mWMB?yEda%#fO1({~0M%UqQS@ z9s7EQO~xJ5u0RqlKFrk+$bh1S*YMLGv^jkY5b+RS(pPLJ9jitU7wy<~voKTlj$9dJ zweD0Cy7?6oj`9Rp;uviOUA~Q!9_FNo<5-b~70tjv;&u;@aFe`jIX#h%sRfuumbFuJdV{I^8Gu;FQvfZsC?59lRBQ_9%2TNrUb&# zod_7K=@6#q1o38aDid6R>{%Rn6thl4?k5V7xlTlYG0~XLw6b6`LqFAF z1&0-mqFGzfc|^3gnrjOl3RdF}WmEJQCciR}nQV{D`{?C(=`*p<6>gizRojQ3H*wBf zJTr;MNt+!1i)0EM7}>1Y;{t1uJ`t%T`iB>-9U$geuic6yBth38^PqmRX_io)dsU&U ze!hI{L1!MWhc1dVISsfYJY53TD_;Y}!A8WtaDTpa%(%5#e43ctW~#QFR;8jhCTF;$GWN8Y$Ref$T$B`TsZ6R) z^A;4Qe1MW0jaAyBkg075i=@{QH0jf?+D|Dnz5u<8BPB<>mg|Lps3#k`LO}Y5ktcEP z7(`_EFuDKs1VDs{33F~z0r4?*Pgsi$R+K|lhMzZclRpn%~pCtUE|DJ(@17wJ?ggNl>09yW7N+}Jf-k4(58y=yvC)5rEghW8`k*;CWY!5 zKbg}eYOgy#D_&@%8JJa|)j)&r=V4#qn0S z)XPHyDs9-OJGf*RnA7KS$ILb37wHk}=38R|0H|BR)|`j43X^BhywOB8!G2z;E=gCY zh*^NVU#WDO$mLKqC~19Vke)zXlVu6buNF7>{?G4a(AkqR#Qrv2BE;}ruxK1#55O0< zXCF?bRTbo=cv}=1;gd4{52K+7ZfB zui{L=vafk7fOvZ%>Rk)Ff!PJbx5K;cphxiNUJLw1_hl#qtLevyZr=0jTe5fg>EY9I zc3Gf9joK3|qe*WfKQh zZ?rpgUbgcNr@I*VLQy5uXL+tvA{YzsGV>X1d*%gVC@mT-Sdf$TWtmn``5L#DdXV#2 z%2F`sXE+Crp&V7S@vjLOvS0tejNZVj@CF@N(s!}RUpO)B?JCO0+Y ze9Ct?%Ysu=r`wH&G*;|R^X!pCdXc3FxAT*;?@vRaB{3JNpMbb=kyrFdVgJozw;S))VJW13Ct2@2{_qy{ffv1gis|L8yiLg;P{_iuWHvF#g*g9-{S9e9r82 zUjIyZ!6Pw(*%sUjx@`<~Ir>D7y;=vp9R}<3^@_>KsM?Gi7sdi4Fr5|e-|AluOK3wW z|I!V(58%%1Nd?Sr_2Y5FNBaVgL~?6_4=%#W{Cg1t@jt=!esEv4v>M!P&7`!dHRU4g z!#|Ct9BUR@+)eDBg5fjf>3goU$D(3<*J6(p4xdX5Z^}W-{Ndn6 z+-}XX$vt7J%5$E2x3S{(>3(wJBfN5o1)*7AdpY|422rCFOo}??-^_Y~d2d-d{`|*K zT=$(dv*Wm>&#wz0o!Ea8F2Q5|j6r~#z&oiP@d%vL!O)MrnQb%sGaIZckIP!IglR09 zJTMPDWp`rD70CdOQvZzEEV3nFtYeCzJ;MDc-aYoT$t?~B6>h=`nAgdfU_&5Uqcc&d z0Hqk+-79YUISaOqB`Irvo4+m#Xo3m+B=$T`$k=D4j#YdrfgEw5ztqlgoFr48B{=i0 z*72yUaj2yIk&e>?I#^0vc$aAYc@)4q?seC4orV%%=iLwQ%T_i?@1n3!^xIn0gCC+N zSn36pcxvps&JIw@5qnBKu(PX{MAf?w-xw15@uuWHYk>q_Z|_uPwz)QYnfg}5 zajUW9E&NEjC3NDBS2r(9vET5w$GF?~O-<{UcbxfKLFzhQ4G4N)yfN{kO)PlNE<;aM zH%HVdK_(;x;HFHnkS*c#r$!!!yK{se-`E+(ZmT{o7qQ*=Y^)%xa&?@LM}O&R7p&0NH}y`KpTDYygG zfkx>1xg%J)Z4ao*B-$MIh%2{&GfQFN?7_^n=qD{JV@ZK(UM>BiS>htdk#K~)zD?dj zs|mj&QxQRB0I2COJfYnPQaU;wUVY;}jP|5)_HA4bN#vT1Hi}?jXjFpy_b%0gt? zWIqv7o7JyncE6{z<(9`-Ut&P)KV2u5#dIazO%eVlPKlokO0#5>bsjxL8zU7|NJWSK zHYQ;yJPF_bQ>fF3kjP1JbsM*WBq-iTQQ;hg7VteWDfuni<91;LaP@} zKYY@%jRPZ;zjg7p|2?Ey6tb~YU9UJS=l3XqpkP7uB@8CvTR=QXwTlAfXfkb6kqabP z_@Rvkx@;>%;u`Zi=#hBAr34J>;Is@LrhKoja?s@E9*d-GJz;zXB}Bw8_N}lA$4b#< zy%Zs6y$GGf7osxiJpt*fFB2bVKWDxUHCTnbxKow_iJ`z>^ZL zOJP0N#{H}gUmjP9;I%gm{I@0GxC5MC2qz~etya_qA0#p&nCF(nG7~fgFSdx)bUwU* z6m14Na*sM`BTvPV=Y1@;W#MYJjQQV*@AygM9_uzM3%e?szZX#1IvnYj()OS_jXY#4 zlkrQ17(ca}`(-Qn8(_Qgu%v(Y0G!`r503hJO*_vXw8qsR!TBwWiSk(j_a$8UxR?Z@juje<(2 zn~uDCSHzD{x(hAtB=;j>^CO%5_?AdZ^=V6fW4u|s5(B= z&X{rre|Sbb#^(Tfx7x*U?}}oFZnB59ACEUth@6-zB{s`n+M<_Fof z0gYn{Ui&`V11nVd;oOsWs0BpP62y+>NjjdWkD*^{FT7NB3h1^L(@nxKj*4pK3A~Cd zg>1nEu0pEU4y-UOStW6-KW3VET4k^l;6}lkR~_#vOnM%{5JVn!oJx&#KVWT*WF6%T z!tW&97y)#F!ujssuYRX4gS1*IT1a-5!CToLxtwiy6aS!3gFDV3TQ8YicnbZ?{E(|{ zG~E8XRTDDSb%6Po^uu~bUZ&jqfa&ysPQG3MI*tS^LRmF>*zbcE^Z#r|PSMBeU`C^6 z&bz_jl&0arBJPw~0&jI3nDJSq;u|3xt^3aUD3X#cxvjFRFAvN@xq1 zVG90r257fn(gb4(T53mx#~a`UP_@$mAQ0`7X2 z1M8dmP-HS338b-ODd^ve2njL4uyS)cUuci|knh-LkpJAWSuYPJWaU*`+mu-&=q9C0 zHN$vpLUNB3Mc%S6QuFdE9}8Eq9Xk3Jzk<~|>$dE<{ni1Yh(|nT4uZkEp|EM(>o<8|vbGo9y?`S-%uvtz2YocLV!&ziJSbO&kHR6UkA(&jARFghBP$G1kQ&9q7 z7wTs|!>a;}(N>c*qc9H%&i%m7?Q;ZBt!e!>G_+dkgghcL2F{N4b*eYsQdrg*vqngI z@Y86{?tQcP8|y?i02oI}T(BBFk^-5q$^_N{dB|Q9ls1=OM%-byL20 zz#R%;QKe=9%RrC-g<+ER|1L8SjWMX!reD*eOcR|-Q?BRDZUT#9GJ_k4zm-WOHQ19Q z_)ia^=pPGo{GXNs?E#D$$8SgQG+ih6fF#mXJa;s#muqBp>TFGVWCL1r0d>#SxL$^hiq2x$ZIH4z? zI<$xw2h2?_&A0Be06vj(kqu;{yaxkOH>P4wo*Ek;G1GGbyPF{PYVR3EJfk^b-gko( zg00OSbhEEIcPzBj7m$e}dEt)vK8NUj##r!=`lw6RqbLH|G*$LX+>b%bSEK z#L!A}ccp;$ZZP74!>ym6<8YdrifM~*TUHa{fuf*7_WR5rw!WBoT`r1tpxme#)P8;w zl^2XyC+m|La!f@ET*O%tO}y_RmE_4vF;g&tGwB?|DCs#)lHSh<8XnxTQ`9COskadc9r;A4oH9MXm_4SVnYZ64_MS_yrHFt<>)$ zbW!a`ocuT>sHYm1&zNzV=te&vu4}PAO^SCZ)V!1KYkmgHhL_5ZQ{ZPOIwlPd{L26$ zTjLaxQ1j~c0irS^s{fwCd>w8XUy{_Zh>3=C2QfvazJl;4_Q@`{y}IAlcc+TxPHKiM z?Sj^DSBoclKehHILuieVKW=k0M&fzVkrYEh!AgLM87n7?kp-UWmBqvaxW<5FOUk|; zPiW2{(FkL9*P*zB&x3hATE7 zZg3L~DyVW83kyH$@JELz3YlYI%99Ptx*IrM%G@Nfa_y5%zA!6YNeR`mJ;S=&JGTtm zB7Cs0RYn2` z%sCYrZo)Jtn*2)`IZXwzMYzGXEo-8@u%3=b6i%Va&H^V8UplY;NeDs`=~m!OgkDtp zAVvNA_j!k>9cC%=`16NXW&lxm=hO|Z{!-)7FvQX+XG^9R0Sg8IagfDMi+Vn49IC1W zzhvG;<)?Lde^!rC-lFBF3saHDFvQbCahF*0NnaQRfP}xvSm`oFX^b7 z5=^xPJHir8N`L_5kZl<|q!j@tIcmqeRk(aJ!(Vy#&VcEAd{ ziUc34AkiFf>)Gaex{J}Hh0S9z>}^p3QM1&OX5A}kG{8wB@WKI4FWhGG{w&f@QtIX? z@Tj=6qL`m5;E2t6sl9#^f%>i}zEwev_P6{nR0n{GO{F{+ILqLnCs@QH_izu@aRKlo zAM%G9W%Weut|mw@&F?HJ$aawD=d&Q=kXTZ`frRi4MEvnrmp(5@lhGisMV^CYR}`p+ zOq*UxhbWj@eN4ieF_jUy0-hTVu zCx@&`s}utb5dsf##p;AQ-1O^O4-#lYukhY&VxuS)3=EP1)-fbE)gt zN^+LtPLBSbkHR7P0?=J2FspYMdw z)9NW(_P#4Vh~fE3+eLp$$F@MBqrh`+_^jgzoU1e}#O@HGW91Bx~?)KK->n1?~NB%I)X;M4dkmV(y+*xZiefufUU+%;91pcq{U@kIIvi%EHZ@C`~ zz_HdG>-e+)PFzwpZn&Q^V|$7h$L*!2_ISsFml*EeA%V`0x>O-~1tFv39U4>j>8C7) zIw-=5Szn&0OR`g~%?4OM_hzfCG=Y%RLhmNc;m9QpeJ{gM0fnv9;wZApXAUj{4AxF% z3`kJhNly)53?I>_SY#aI;CEC;^4SqDA+!HrRb@2{1;lzhUZ&H9SNdkBEU7u+cyQ|U z16X1W^fw9>RRN}^UD&~8lz;qaS9S;5WaU>o7?kxY6%7$u0zTD;Eav24+&j6D&~J_& z)ULq%8@$uoHpM<`75f^rDU**W(7=2=46eqD54ezHw+0pUY2g6&^LGrpO)ABtoSF06 z!*$-3EF?!|9a4Dpp429+(EFy6EGLM$m1%Z^y47WMcZ1vgwAQueZCh#7?F2VgW%wZd z^LR%e9(k6pU7w)1G@=_lhG~175zQFoya$NZEO+j!B&2~MbfXmQ-#A<5Y$iRQvt7bTaR$EMTm&(F1@85 z^4ES)&45N=5kIB|ts&{dZstO*7;O~5NlVH-H&WW`Kw!=Hdhjy4)u#&?cML{1G+PBc zAF*!2TqoFqnl>Yg2XKM!v0DY&bY_oQF^aTOt;pJcTA%DV+sR@q5Igrv&XU)axPBp7 zvJkAO-SKSSyvJ79qpo(mAXHMLIFNm!THJ`1zZ4Zf>h;hPj;#?-nT+gLk27aGIXM-m zHcn>Nq&FkuUs-M=e~kzMYq0xKWAX$2vYb{>G9{4m$7S}VNzW3lTyMzM;=Lu<6$y&g zB?NzyM%hj;1#v-VBq08H6X~ zC)rN+6+5P~wMgED;|wtK^+8<2=A6IiPItZJh_$5)^%l zZgrl7tjLhvE0MgrG5t(S%*;mnW6AVA5SiXtaNKZ%YB6gGP~EGL(S%oS>HgizMT2+A zgE>6(OQ0_<*RVlQnTKFu=)oYNgb^U|O;>@6aWu9OO4GV1cdN zrcnLgLFhz-Ca9XtGHwJ6`*ocB^jvxtj@&feRZ7t*T)~p`;Hg^0B$AMMD3jM=nh<&t z!*rGTR|e=CHzr==ZU7aP!;zT+-+C+SqJ`z2)KZ_`f?cO+CMs|qxhrcUX0`}N4qjli zK#I8~H;t#(jB(iGfYnkbRY(pN%}W;$9kb<&T&P(UMS_95+p|Tx_+c4d+ZG=wbTEiZ zhmJ>&DdYg?SF(evb2@(h46oEPTjG$|5SLu>xMpXXV+A@-#ky?Df&_(13)u99m6E_R zD-Y;Yyn7e%c!fB@0PJJD<;b~F{+w7bUwf2!K+pcr-KI^kJK0Mgu$6Ua$}RB%DY_&z zPhYo%w4Y-SjiSd#k5)@L^ibD*_ml_=3~nx+S4Tl7AAl+PL?7pIT*t3zZ%i1@p#q1`N8+!ZT(o85(gOu@k(P3#F)9l%yko_Gc3MYJMl+}}6{{1dai zV}NE736AS@7n#4o)2Np@BV`OUy`S&l$5qd+DIty7pPE}8!pU3U$7Ab#!S6!=&}eNOtw?4J*tvR^-Ok?jbVY|kN=Mwm>j>~qVbw_KkM+}25m#-Xk|8nk`K(Ax0Tk!Iz3 zN76?Y7j%ogo}O}^B7*a(LCtMT-0x6WPt2I!H&bL(oNjgm-i>Bw*MlxuwbMrm3BBL% zm+9%lxEBguN!pJOg;l^-aQT{}w(Cl=&iaO1xLz#fdrcP0WW@`_1-Gxbh(W(Fy{BNYW@|#ntV3O}%7fR7l{rNcJ)aUZa z9TfnEStG|w6>WP!W}@8F5U!L{2FrOomb9V&5y;n?cG4c9?qlZG_a_~6 zsZYdjw}F$x4{G0EBMf^6lJL!TEi{ol(`5Pg9iMmG{%i*UIr)9kLEJ(;4`DLKLUV>4 z4c_g8-vTh4wNH+hSRV!TK!{1v^>xc`cGKg&w3~7A75rEi7tSnZmyRM9L9=ZXJLM4H zJtoDh)bw5R!FFu|uaO&9Q_C^%7KDY+pRhCmXsTBwm88~j zyYBZ9HxaK_m(JsxAgbZaikB3+WGcm+H^>Bu^~X6#Jo(qHxq=PYkum*ua=ZJym-T+| zya&lxS5NuEzKb&uJ0oKvGo`I0E)a`ot?-gn<-1HYfSLNziBQXO63wEU6V(uYbpPOx*(WZ*BeN$x+6q)N?Hm-`zzY#M$m=8z$s_ii_s{o(03-;*K;^lXpmr{3_WWAuG>zAms_1i%=*C~IE6 z;Sf&XGz2Ep=nB*;+F22vb!lYu3^dizG)vUgHS^Fz>?8sQmm8Py4PmlpoEU4Ie3o5Y#&Caqquj?zG|AXkp=!ppCo%;P(tpxF zWr>v{-0%^*ps*0dwj=v-P-ZM0#V{d<6A{0B5MXT*v|zIfYd_y>FPtf%=O5XTzzAQf zZ#@nOb}2Rf;?1TEhjfy`Z;obxo$Vd>S!+8zm!TNdsjgLJjoL`TXig1jG0! zp9Jy?+O?YG5NSr#mTr#+Op2%*O$rmM>_W5;^R8+}B3JwMjm!thSNq0))br6*2~-SF zx8g+(#|=Hmk0Ke61Izq*+_&qM6jGjho^Eqp1YoKm3L(>9LT0!pF=Q?n5%h$~@8%QX znB^Y!o*crM@TCJ(u_Smkx!0bldCOh3>Bu-JtCY%R5KpQrwZ0zf^8)xVicb)wvc3^q zNo<+uq1%0F)tAc*^BQ9LB*boVVp;5Aj#Cp78LyQ@Tr+REH=8qtJQ^oq7eM?$%?k_1 z6zP_TH$i}Ry~L7x!x88f1(@E@gx-Dzvs!qsnBY}Wo116L88ef{U*h*svNVvo2(;Tt zrr|a(IR_U{8x%l2D*3$JQJv-x<9t<%^>6eKjlNIsSerlsH?1p&*nqBy10|f?9GDg0 zn`(VN6=@q z$`XQ;kwbecUTQ%C=ye?bzeNN&ta!`V9miwBluCMUne ziSRo0J!=xRlD)<0oIhXV;Z|0~edp^6gmiZ&D}GfW$iDQs{!jj*Pzj$A;{r24iT-IFifak_Z*GvIAKcLDf7M{HH0 z|E|`rnN+SA2k1o%+fo-l>fw!CQN`_lyHf?ILq-Aqc57C&CQ8WKx7n!xLHOos(|OSv zB+pOQmd9FCS(Kewvs!G)$!~a;7xg`{kF}Cv{g+reA~YRId#uGwR%n`L+E;u#IPX2Q z+Fy0!J8wV{kU9v!-Nhio%9V-SNkhtQ2mdq!b}PH&f0?~TKhTildFq1wj|We+v`!EqVw zH}RgO>5Q1qFHZwA(FGZxe_GNO%AXn6ui_`L7l5|46iC8%1ML}3NPPFX@J2J2BsHxp zdEljk^QIr4aRWbH(1AXd9dyp?*foEru2nJNRiK;P9%g3`2cu~m5@N(Y^(>r*A{g8+ zG0a!k4`U~xTn%6(B|BjIJ46aQ0Ym<~G*f7{7ah}qwa*TUXqr#rH-+hB0hlNWyICT4 zsBjdh;;Tha9ZrDf$?~vpr*DnfS%?QK&71}NavP>;>oU*qSO?eTG|#R69JK=YPoQz> z&cNIS#k^fKwbE{9sg@FxN=0sV*dXl`4~4Zm*3G;i@8TpW{X%1mxD>uwy{Mr{ux9RJ zEn-!pvt|IwGwCy5N;e@6o~vjBw&8k2CltJ&W=3IUfwP1@afe8mV0Qw1#=`KVkX@-M z1}AH!g<@N~*Mm8{E4D7ln~_C1%pndt9p8-_;QORfu1g7OSvcub?elGUHz5@5C8|i8 z&hNS%iexY}&M+t-my%^LKnq#%7;K-+|L_vma0tUJF~n~DTyyGD=9*wwy_R-EL~B7Q zSV>be{+-7+?9PnsTb#HN2(Rk|Wd?6ks91@?PuLs28LG@1$rq@_7HY+%*T3!G`)pAg zwltM)O`++R7fN8YD7kf{Y3y9Fa|q>ldm?@%c||g6ZYih0TSqE&IK{c#0sSidpaNFU z6i2z_8QT|ak>m%a>+=yI`J*j3@qrDT3ZB|kf3zH9M=oio&U=kNbin_tWDw?oZqelr|>ZX~d& z!a_OBvarkc9rhR~Y2^1u6=`8tUfA$ams7XqcY2#lXcXetO5GuaEr99YI|Y4kCx1Hz zrzI>W#3cV)_?Jn-YhC8lE4a<7<#IMfTB7LpnPndO>Xhh@Xd3b(#VrN@j57LtD{TDk zczq}6vC|u)yyP1T$`gWRj5T+}Z<2h`670SnKSmqWo@5-!!7)>`vB7sT0lw^;?X-9L z9!JF0bi9@-e!dQR1=IR)lWIauvb>>c2Oc9e#;BgxjZu>rCO`G_SVMP*wx26O?ROTo{ zgg0~(bDJY%9XMn?0K=_Ia(@1?%oI)7WP;z>WzN`ebc!J(8x)YU&|dbC4Fn6K?$KF@ zuY^e)txurF9R6r4l^--$T{SLeJi=j70@9fbk%VqT`lA0={dn+Oc(F1vObjRPPUm&bLh1y9lQDGUshiPj z#fz=eL6AexD0@|Y(@U^u;Ft^NPjXOiea($svB0DQ_74L1nR-CF=m&ixD3`YuF?AR< zmX*#zAG7H4t*Ht8xJNsB!>F_BYzCV%#>=HWEiL2!#O$z`n>g%6pcZloTRq29l@WEg zE|NMJb#o?(XX2&9{LH_LG^v?gNpS1PpnSV*T+TZ>&_QbzHlaY7bBvR4%IQjU^1IiH zsE>tbgl>91@Yc$aPx`hm&%QB-Z1u$qXEA2!1MC6M9@CFf^(Bof>t-PKfKM* zqBJNs2p`AD^8e>grbo~vrha9BvB-skkYi4Zz_FaD)p4?ZoAp~hhCFA=U02R}hz$7! z+*8LUIh;vJpWk(}dLxV4=GiRc(+cSJ_c9ux3Yp=EHcT<;BYRW-~BN zP{46ZC?s$+5CJTDHU1716HS_BI?Z}%B=NbX)7OKrJXUnA84(;6N>eA4c`t8lPkMzO zq)xX}tjh%!FL@Y72X7g9tov}AxHwxNGmY4eKA2)tF&k}g^LAZF z|EXCQUA99DfdDW=hzT`0I-0%Jc@3nZPiwF}K!hzX>5VGk$MP>xz+67S@EDOH<%d-s zNRdi>Wp3HENA2MJXFarUy~+kPY7Y3f4fO(DhJByI93QJga+1?igxP9H<`qoBx#h4X z3%lc_^@pwn@D0lA&)Whci8;LNzy`*thbXLoQE2g*TP3mGLsD&JiFQ}j zDw~<Ft%f$HVA7cK^AG4ep|uBV0tN605M;M4l9DvLd4XgEjM?Rri+njw zI)`;SBan^x#lF1WHyy?vL%WEJ`E{jt8?(FDg-6jz{_$vAMA)85P$zi10Iyn>zeMW@ z%&7n~xdKDp=Gh06@+kW>lh$9GETggu!na+ITh)9DAx(POihQZPVQLix`}E-RBeyfg z2E(hk@O>>) zxcvIP_-;c}e`LX4yT(Ep{(_aZ7?y?CKvAnL%dxn71$cLQKm&~ygr{TFLK&FsBpjH> zu~s4sso^o#%Q1Z9TYbdH-Ymb4?F;08Yn*qE__I5`IIK{!@v^Vza&HHq_+6{CBG168 z`Wa9cr&bhP?aSx3o+v$-Ehiby9pPbk$8dX)%yy`Cr7Y;;4$I!9QH z)U5)-e}sbRTNRfU;Vf}b^NJ{Md2y2edBnxY{=RRyv>hn~=Kzr(Pt}CJ(>4k`m`{^d zzQI={GV==jvYfBqLZ^6-EGPW9FL@Kv8*}3m3`8^?==D zymk+u*GUTfV%N;oC}1X9*H2$4+ee5ui;HA0%Pq3!*IuuU&e^$^gV+(q#))Wnzc~+7 zGOpqYr)19yxu_Xp6AT=K7E(FpF`z4mk!(jgCmzC*qqBU|pi3Gyo`XKp@4FGHJ#aZ< zgx$W;ETCX(ASvX8ifybsvMsg)S>FKm>uOqf6Ugh5#Me!VzxW11cn0F=3-ON1|0T~{ zoJz;Bx{ri17cwA|QRJgo=3u}96T<#vhi4r}9V?vB*ag?f*Ozn4R0t1Zz6#>cMFy)z z?l2%`oc;7Fj=}KOGN`j(jp{s;-Bx5>hqqOLv9vr9^|}pc$1Z10$175ccBPmj(33g9n(}pJcBX@0^ zVl%-e=)e>*inZQTZW zgE-J>F$-q5vWZ54GCf*CmMde^uJTuCwV#g#RUx7>(uKvIr?lo{}DII65 zkg%zR8+LxeLBJ)o0O-o+?xu#!MS{bB*hk4;ZrnXKLzaz7 z?TD_FuHg1MtOB?&+l96`1)4MTOeqWxk**mQN zC{mmKcMJ2|`OyS131jv|;SUm&C@vs0pd`8kfl|jR^r3d0{VrtK_=5mG3Z2G)Bjs=p1>%9R|h~OkLUO4648N;^1W?YxoB{HGj3rmrH>(^ z*1b1X&D0ZOw!@9LrXMgUD?Bu>jx_iCDh!$)=xKim<98SV#4VnBmDV#^FvzNDJTAHI zEMJt}RgFU^hPsgj&L6^>(e)@k6bra{^F#a`Ztl#n{KLlmIb95XvF{0=^(H^%Tt+S{ zDPgB7oisA%;cqw@{^ZU6hwK;+2Za|~+gOE}CdZ>lje`T7_|1Vm7%1)g;fTvBuj^Fm z$yT<1I9cs2lvfCEe-9c$<`8M>vO8DeX{<^*aFDbwFoZDo)waJ->f!o?wX4c3<50-@ z4O1@O;?iYZh4Y{60p{WESvdM7i?ofXLc;5_ZTiL01m@ahvaGEPCt62PH7p$LMtVFq zts*Rb-gD6(5!eFwf7ej8n%*#S1&H6;&a3_ov&REF)3!{rMvSGEwkvT=0yx*8h5M9WlsM)PX%p0el>^W7wqmkKv@_1a&zRM+6xI?Luc zI7FNII4XjO+(TGnE9f;gyiD$vs`LRadstq=^48Xu2`~h-@Elczzkvw~ zZUneLXh@F|(PNp7do8Q+F|d=pwhr$Pi@#mTiNJ|EPq+q@L90-y8o9*bW*^vvmT>VF zL7}Jr{vgJ0Z1)P5S<-{uo%V;E*Mz1hBZ8_}(L?zGtr+K<|9ss8N1=v5KfFpmij4jl zWI!18;>rtU9&K+Y=|4pJy}W!tNs_xteJsMx<|h=*b-2Bt@~zvBvv)ZOLa+SOzHKP0-MKU7KAx>6J1ZH6eM*ai(Qh?}mMfJxxNqU5& zo>WcW+i{DGpSXaJYCoCm9byfi-T`G4zde4?QG1YjuU?S!Z(w7#qG023=WgEo_RSY6 z=1PQyRRRII`OI6Tj{jd|F0m4?P*s=83vx7hnAf?Bk+`b{Gf>rwaHgdDVvw)JCzX6D(P0P`>ETkbH*kaM=Kx)}R6 zf)*LONf>{s=T{fi7;XL2_#=s*-dB0P0dDxvEl$>_2hXxxV9>cz!svZAS zq^%-|GMUb5yw)Sd(INrEzu*v!5QXJQ9j^)j*%8nY3}u!B7{y&Y&i2DS>Y<#p{i~eA7smNU-l+T%zC&wLsbMGwD$$Fqm zKW@pK?Z?V`1RaS!+_pDo{>CG8JWE{Kz8|P+UP{p;Z0(iyV#E7Re&;N{Bt5*vs-GwY zX;Xhf5R52R4D3M;a!2m)|AcS&bVmA38ZAg=VC$ySJU)U6!;>M1ILXY<>n~zdxA*N< zz|_d`-3dn84%Z1ry6b$p@Fbi|9uA>~%&h;EvN&YAtMp^*Zs#3Mg=fvzUw?`UK31ela*zibiz^A$8G1CY5%PDQO7_nTMxpxI%|KhICt0&v zaL%iR#}{X@bi>FmQ+lg$j8j7L?a0HXIyj3WyrJoVZ-FMP36(+WXU`Zwvr&isEw}>b zzOfAB#|c)y&xr)+xqoiaEbFJmRmO`LhV-AhTW6kbZ*>&Le9GYt=M@KehK!mOTpv;% zJro4yf9B_Y@eySen~{VdymRdG)2PXNc^S^NW4=SxYx-$r`6+8=XbKnMqoTzigA!tY zhhV5JMYoog=k-n-of?B8kDX=^zPocc(AJ6e@Y!@r|CnbiS-wjACD<5uDU*eHs00M# z+Apzf(n=B*q>a}3!h=Y!MxSg$HHMBwLa1+lbrr0+x>N$5J6HI3ro^m@cG>8h1#yI%7m|fk#9Y5u>ryV|g147PoKmF+j1>s~MO_lQ zr9VI%?h;e&dxi(q{EUa=9U(`dAzEE3W|b_0LMovYoha^neLspIhWM9& z389P-3EDCZp%1GAY(m(Xhpy`zAM~Ez!3}AScBO(Y=11t3!Os-=DuI0f%~Dq9BxV6p z1m(nLfFYRGYLlJfVsyFQTbURUobDR#TR0|f)*ZCtN(^2+Jo++D&+J z>;yakGbeAE;|S$L{V*ntO}iw}xE=kPq@^NqK7kZMb&Hh&B6WX%-gS7~nb1i)jxehQ zO&M$7-jY(U-a{*kagaSC(Jq^laBpm{WQIP^gJnY8S(uk4QbUUWcgyPb^jfcg)aGfi z2^>@kaKcWa7Fcg*L{ian8xP}KVPBxt4%Zy7`|Ilvf{on_?_MSgb6V_trFy3>P|1z7 z{i*20hXR~)D%$BO%}8Jev7&i#_1F47HB?f+fI7zZ&(g#;(dOC&jj29_rRL5~Xn;Mz(nJh|2BFPY8_Y+H-wM&8b) z&6cTIc94Odkt~-P$%#J`;)PP{Tu6{m*d%{ur4)mt3^0%krg;nV5Dg{iZ}w7WU0dV- zP(&!=c4LjE$etXc-IF*MDS7ZKbvQhFi{rZtzWP;q~{b5(GD7BDUZ(Ie;&b1M|NhLUH zE_%6w-{29nQ14LdAIcG2|7hh7W%smFU-aM%W0xwHh8ZO{*t(rac!j~k40i@5%ID7E z15IFl3Op1S%fCG(K-TQqur#98B^B3J4a{C*y8jjNL7EZ>=0*5lD)WL+2C^Y0e zf0Yl3I%@jiK8qGgku<;uNepvNHC$FuXcH)E)jz6PVYyL1hGbrumNk(J4`E_o5|-%< z*W+9%Aja)be_eqRi18xEy`TmoN&0URDg@wl;P_hWS{r90k<}2kINZ=xwp&{Xn5 zXM$ANxgJ%I?b4ghH&U%;6gj6bfvf@I7WH&V$>QNL%4=4ly9d^g&!!zND32B!J2&d1 zsK?0u0Eu70Uz~BX4}G=6SI;U~oc%++Hhvae9o4l2k1aViAyk6JQ!Vs9WhjRSfj38iJq z`r$3K>Mzz6l55Yy5VR+x1_=;;&DU_R`% ziM(T`-@qAho7x!5)@WaZjPIBztrj)a|2xsS7?aKsuRZEfT$L5v zy2H36Lrq8F+00Zdg}RaXW$4w*gu{f)&Brmld&-SMb*3UjQ!HUMY<>RzFz|OVa(hde z1p0#86-b3Sqe1<1MIWR`P;aRI)Ns%;BdUqQ0rgOR>f8CKKc`a9AmN}8o+KL<=DjX6 z*FDBuxMt&xmp(BLE1T3a%5CwbQ3TneLQnkyOsO4?L=pCxa-B+!G&Q4(=zAx1Ya0X56KD(*(&2s@(dtus>!Cb*;VlfR z&_N_c+|svkB-{Y{+r1)d^5r*!ND!J{2{hg-`V zj*fW5*>ijiRx<1398adj{vCx*EAyo86hY(hWqBM!vvp1eFec~P;1=lbV(JDtDS4$6pXbuoYXpqW zcAAZoP+{pFeOa_-i%Ch;M$}w1(5Y7#%AUXRb>GU6r`PK;9jiokq5jKwZlhN^qz^1czxr85T5`H_}>aG~%oNO}0N))^P_Or(w#$hr^qQ~S?A!^o`G*o6Pc&#Jt`TDEl#)_N9ChkP zlccD7D02`o{2&qvAH@NS;gKvyNLu@l^sL95D-fSi<)(|{rawskCA)Yr8cNA79UE9V zGQ+Im0}lItae4nL;!N@a`743A+?n!r%_5Z!#s+jv_qaMSiCOOy?*#BbpLEO;G##u2 zPx3Mbv)6e@RYSlaAj(DNF;t1YMGPAiJ&lO>?as|=mOZ9?(9_p=G?7a*TySHM*$d?< zS87)&@>Lqf;(tJA0B!76l}@S}f$8sXafd{KBW``L5nI$N7j zx%2rIH2)LrTzad5kel&pxyNm2@^iNty*shFf)FYwpm+!$n&k3y6$u+P7m1!=#kl$gZ!%c;N({P|9^-cA=knZ%q1Ylxq^rDpNw zBDCh6sHB`kSKyvjmJxWS5LcSP@wiuD0N9#5n~WJ;~MzW!>AGgF=MlHN5R zgsz9jUy3?x3HMDZDFQP=Dwb^5wbuZ*))WV|sS@yw6jx{<9oTd|^EoPzuV z!8_4R?cg-OehLul0L)t#_D;Bc)U2Cs!SPB1D#lc~37SMHo62IyNgOr6n5)8J3ojO0 z8bGuv8^NRf8BBiP_6woY=k_?-Nc8eeIgiu5e~;EV&xZD-o5_dj6+#Tt$%?|x&GXa{ z9A~MKmX7stO|oslKVEx)Rse^dPmPM1pYaM(4wn>A#9hWLHU?yqe`{W_U3#Qj;Q?c{ zy%_EV)&|GPF?=%8qZK^mxpC6BKVP+cQ&1V>oiQ`42_9xZAuTzgB;-Q#$+G>Iyz-s# z47Vty51_Vy)c!F87qcIK5UzZt1Gl|zi8Sg@7H-xJ8pA~s%ksr+uMH2gBrw}=y3-2F zfTl!H5;RS?%5oyKyXC&M5w5UD9WBOaidXhL!e@pzUMX^|+BN1(TTdmaQJ`pZPMkND zpfKJpP;}31cfDkk!5NJtuV-QR* zair!xu`tJiYiL#1Ws_X%(Vk~#G+U`27>HQ#6KqBye0$ehERD)<9NaBLjV3Y?`g??}mFu56bM@06&}q|&D;R+{Q`o-F z0>U2fp_-h`kxjD{dwXGtS6H5vk$v`*BCEFEvb2Bl)E?yf#VEJz({gMrlXALIqig^1 zFvrq>divDn8{0V(Ubgy3s=<(tHI!#U%0LT7j$ABg&teoA6#km;E`zkwGI)Gp?G9Qi zdfal<7TiQ_2M$Uu6kN<1RR8zzWFY#)|CPjbX4sM&LmT;WJnD>#8{R}v^ZM$34jJ8k z;OynfebbxhYTIF(u~}q86_`TB42}VNI$u0I$&&I11iMj;$bO8R43pM00%>2!(Nt z*BZf?fc$jkv@y>Jv(Y$OC_b_D)Fw@cHkT63y$xr}IQLNxDy(!L6J=n!?W3M?9XV9f zlbN_Qe*HmRG4ptEFPCjHQ>PiWhNyB5(^%y^PE;dJ6UX(FrKs=FM*A`NMW`skCCG_E zUUAU{#(Eyjm{essBvJtVzb0G}7ah}+)DuBmVpHgv(N8hF2ng+W95LB-;FOIy&Xq!= zj(9(`R0uh8!x>N&R=2+d;`?m5f z2|XkArYZ4RCE;AHlW`Mh$LS3AgNO64pk;@tY7AwC9pghB*Auo#t54M-$4?mh=kg$% zVYu=8(2t3@SnVxMYyzPAitZ?KM5b>kSvrSjj#Ra`qqWiAh9nHfIG}VIj^C#)*y)5^ z-KfP5|C<BR{P zN3CCHq`8KPa+bp4m582$%PAa-Bh z)n3C_Si5qY?_EptwLMzhxp|#A4$wBI7bH=g-9??#oTKom>GJJ&(}|=5ziGCuY7S}@ zLkd+|K(c^5kCdT{DKY-J4zdevNlOwtKjExjiYZGbWrY1zlfgJ-U4;0+ruv|tLQ!b;W7_{dDJ>r#%CMCTT9L03bH z;lL>>|2bIpnR#oNdf~eBFQ?QGHl`1FW~9d=3RPW0 zF(0(mgkFRLloB?3de-2{PoOD)BUK^I;wFt&W}43Lg%@GiJhSqVQT-C&vZors$L}aq zyT~QwHx@LoKH%0dI)|kQ;11-JiN;}S-Kld{66-DIj4hA>+Ri0(6Ha<_o)6`N#7wM^>6~t9!d>Kr(SkbzHR839%7*C;#8Zt`4AbNWBB#Qrj>4bJ8tpd}jN9VYkf zs%U;o^8DjkLZ0;TPz*oZJUviv`UHOy<*i1>+e_K%C7qTTwkQm#UJ1-UiXTQNE(x75 zmz)2hydUEC#nJtwpCv{At`?)x#h-gi$alNDCPbH-dA>b*G+5vb+WB2O4x{k?H5f{C zJnS`fQ@GD{e$D=J7?LK)o1;bM=%u6|9eX+Ou`E9*CiuejLwH(zcVQxTPPWXLd5$x3 zCh!L??iaJ@J1j$W@;kbH$Zq5_wMG2rTU$Et|6KlA&GYI++iZ~;o9c^wK}Oucf3geJ zr0G+%sOb0C;MWIXlF0`?4blGzqZ#Is>^Rs-!u>472`QRHE#v3f*#=V#;(cOsMBG=_sj)x+|f+{zx#jde_Tdv(16 zXb8LCiFdUoZ=sgniz$6OUYvIiiztWjF`p;n)(ca0`HiI%y`QA?$^`$mpluF;c;NvS znu~%EZWiyCa=i8+*t(LNwN;)O171*uU@kOwjGSPHS?L_+m#{g`yIP*U#g(=ESq67-L-*Q6LICYNA0ZvycKq#r(YX_K%IItkj9VYRXi%qDBl0Yl;AfF z@|0liwM6Jwpf9o+eSsd%x~cD#tm_{Vr%=#e_)gvaue>SZX<3bGzVmC0Xdk65lpJ?V*=fo0w}G$$(3?F9H|(!yqzy`?#=KU$}1&j9NE z1z^oL=CJ!-<8zqptcdLc=o%0IXZFNzq|p{)SJnuzzU-FVTiADSgOp{mflY#wkh zX6?wJlS*RLqmgh#Tms3!aX!G#!sVLrQawCNO{4*nap&1Jy0G0Z=i|AS65V4e8R864 z7%$Q(nX5qM;J6?;y$XL;2UKr`#@wwV#NA{mJe$uvM%Z!m$_+Av@AP1QaUbMx=?Kg|BTObRfJ6$0XU8WB^q2qP?Sg9xcg(&2b(ZBEg4yQfYv@$$P5;(j5EE_F;*hABFP7$2t_UL_RTSNA1h- z`gPup*3wf;Y^p7KkM|Dgzlv4<3WE`RtI`t8qhwR(}{r zrG$`-gxViiPTV8^*K_c~9Vt``t3L4&56$AM}*uqSva0+l)RcrBD_ zX9~QAdvHHcGIEW%2Lo1c+krN#7C+~We$bm`0m0YyP5KTIWXKdM5_(TdY&~m3I6`+| z0v+^!@B$)_7H zw-%a{icu0&k$Hr!?nc^a{%lXT>04Mptz;sP%jyMsU_BOy`|T1Z1|jQmb}AS~GQg1q zfw$0iQJX1Y%xxnY!AIy`6;h-iJ&|pHB*x4eq*V2aCoGTt&hi*4Vpp;y)vJ`uXEnsM6!8135b>SNqL)fn>z=5dZG&mLhe{E^RsY5llT*7F43e&wF<_E#N6*M(pa{djb zHl)rE?8BEi$k{mdSTzZ4O@O3Iz68f{^8g^D1?GwF>-eYKsM^T*(cSUwnJ(FpQ1HIX zJkO?Vtuc#|ZW)yPQfep}$Ri86k3K}@DdYx(c2R8Vt*6;m{j19vKyoU_8NRzf*!WJ5 zuvD{xLYMA|%m(fRV;4{ZQgO6eaXB3L|#>#;lheoswp%eK(1Y+vk zj0Y+abPhy;jB|RwkjoE=s7@IKeE)O$CpMhI-y^21sm|+>x$=l zstp#5U@fOJVw>0!E+ek6Fj@)v5{7Tga{eaQfLPW^@Rqt(x#_UZ80uAUS%B+40g1XU zXh|P(UUpAqFtU7KcOA4jftujtbsib|5XUU$UdJ6~^0s6;L$oKgRC1yg9%RtE6;K+7 zlP)aPD`OF7PI#?!lov#5^gq_}j^I>-XoC~IGjm!qK0u66)Mc_}pd*uke`fgYExB?< zcx|{A22O`ne@R-kzZR84wRKUdsi#wk*7mzoKnDzGQ9h}AJBg9;K>Z3&HR6SP7?7Eo z4VGb9t#=bDVM{mq7H^ORKDMO(qmhb=(RAA(=hT`GM`?_$2=&u6KYiHAf5zA_61?Vg zSg3A|6cR&`iT4&7^zV0%`fv^sOBCccQb#k3O#f#Sbm4x zMsw(EIVY;y21CQKbPtK-y2+Dopp82@ z8glOEuSAr`{+S`)nud}bPQ6Nu3itiN*jOO_Jejo|Ue7CU{~~8ore!ABN<`>@j3Nwq z)6v8199q)OXF~pue3DM3a4Cdm&ms|!K%8LSYUA3=lrf|1S zVgN_4Ybz7wsL6#V6Mi>YHZSl2zjWgfn#iAY!CNDgy^A@2>f2?l_>J8ajz8*d2uJ_R zPsKOBDcZ82@4qX&jL~R?7D&O3WrFB)g7E$IAS`l|jzYd($$+F~-)N&u`=}EnY9qa3 zuQ7mbJ~Lc`Ur3kZv&wVr^FeXSWrJ?z9H^QSs17KW8rjaJdkt6e3MkvT%uZ&*a7gM4 zD2pKA3Z2X!)|I4TmK?PJ%QP7IML2DcyRHd%;R95w^CX?Ja}E0XnY33o89IzCHk+QW z3{%koo&qxh{>gq&Xsh>c_7X#tJ)QlxzNo&#zgF|w3G$qz6jVAxq0-ncXv1rh^`v9# zttN51!gd1R>o_S4PgxC!l7l5m`x#C8ruW&a>4vD6d=uu9rb>{Ls>7leO{e0dhmLR@ zjeG2hW;Ty{&`-A_+Fy*q*0ji>BIZs4TV5XzmmI6|ykf+tIh1Hg7V4DevY-Co>=gr# zz6g$Zc?xNU6QZ?=^wBAIyc{?e`?=KK5G#c*WYA)7Y1qp075i!Fs}Ni2k7)FUW$Tob zI0;o9rQ)My8fwUpGH_pMXV&;V!8}30)5UA|J7Yt_!-iFj_qmz)(gbkmoHJAE_5{_& zoAV>e{zZH;?@$ek@c2YAs(fJBc#pqDzP&ExbYW?9!Ff@1$~dWl`i92_$-wb}25eeO z=)w^HlM$@m#yD>oT|3*=ez5d-hUU^LQR0O3BNxwR%+@gl7*MaTuprU|39G7Q{S<6c z6OcfGEq*Og&b|sM#O_5>Sqc*ZRP32a;h=uOH%LELqDp2o5L8YfMSuC@_N$8ySfuMr zr@@*Pkt?Rwx?fl6kuNMJU?luFH!ZzJ7{VxnJl&A}1{HXN8PORPM46~>8m?b$GEQx= z`(ucX?J?Ob=qe4RA`;LYC9Vzwo`ybt{X_L=?R)L--qq@r30KZ3rIX}wiZ26nbmY1^ z;846atfAGnc+ZzP#hqDr9~fB?tgg78YvP{$WNzQKxW}^ZA^BDjJ7szb$xMXh`s+`1 z2~xD4OBvvhbw(E;l~eLlm-d+5;7yu zjqN_~oXCH34aZNAI^pMn?M84*ov|mEPBg5U;b`HN#s?fq&faBi%8nxU!d*l%Yef61E%OME9V``GRJNm48E)MXzt~=NJb?ar4Sge`me%pm zaUq>syo=Ne`eZo1#MYFoY7Wvu=>?(jPt zKc-~%+GiVV2|e2=LDxbHRoP)ckq(;6e97K)D|{mN3fIQ;F%u{NptYbR2+LZjgwyX# z4M>2t6D@?n72C(^g**Em1iUuGOKh8ibxsLwEE4V`-EvMQK+X%oy7qk2oVlsPgi zy_SKK9iLwP?z+E}Eo7a-`|P;N*(}~Ir(L5BtNW+8i1H;+;FRr<-YwFyXpobE-p@1$ zAn!tuWbTt|wluPszG&k9%FH$K#cLMDIegICer;cmk^q9typ-{3A zeivv9oI0Fiyqr==ui0T)Dgp<@ZSMQBxxe5L2f9B{-3sI6@Kg_ot!rSq%n7- zaRK)x#65R6?=pi{Vx^bdz3#LIg{Vf6*uYR6HlHbp&+S1>z2?C}U63wxV-Ob#=+LE2 zbFP9zI9_2AZu$RS+o3&qVRYfM#eN=$oJCRZs)56rK;Y{N!E{kypHId%c-`<>Pup%b zP`H*P?+jW%hoO;vm-R)KrpX0)#-OdHNFAHvA_BDIJ5pja-D9>T9=8JP+~GTKd64dZ z^0!`4>~TY^T9Y(VKY^S`Eg+^AKzJ1oxNuHg^jiN-xn}e!#P+(Lo|gs0kEJ-D5g9(_|W2! z<#HTC%d`63azW<~LnChyH@dI7r6JoyS$ER0*|0pe7^rzwp= z21b7s`i+sK#y8TxUk+?iRDPM@z~?2gKbSC%bXaBLXf)IGFZ5U8sHd6V+@B*Y%(n;g zp^cZEr2_%$-Mjv#spW3sdlT%)(E0hT=yTKLHz?YK?Oj0sJOa2*({&32cD64&7WJ7) z;f*wlbcOoX;#NK7fG#On7HBj;`xV+*_bbJD8(~BT8iAcbD+3jnhbu)a3NOrJC1h_C z5%dsKLWGI}9n&>1RsCDfWf99oZMhV9klTz*@p9vc9wJb;#RkNS5#`(~jm851NZvOT zXZje7dpcRvfH#bI@g~(H^XHmXDSeSR-%e$VAC_)eHqjit0)Fd>UFkh8*kug9hA1Zc zcT18_OooJTRI@`}nFrksBF*xhc>wteoTA3P-bvAs>4*NGBm|T`rSF<=@&5@jhKYgq zEhJrOK;w-7;L1<5F)&_WX@KRx-u6$Yf2M;CX;n5pTt{Q{fhg+O(quGRiz*E|bPkeC z3=rXh1bytj1rSIXs|^;>+`q7M=6;LOZbfG1OZK(?O%7(4!jq}a6YM*2IKwtVq2Sj z#|0P9Kh72L0v_~87(s0B_`?aL>p4Ry`jl)f#H?JT(Yv_yubpaW4YpXkPg0&kdbjB} z9+nK1VQ)_W;^qn!MEy{WMUP~5eO2D`XQ>+~K`%L-lb9lCx*4b6Z)>Fm5{;&Iv>*41 z!=*zrrRW#?X#Y|B)uUq>Ve=iuT>W}|I-ra)uU9Tbq!Mo3EHc2WYAb$F$B9kQzHkN)UsE}hYOGl2pD^UuYB7&siKbAtj>;jhuY9Fy7wKAYiXjZQ@F{0MoFNrXB>i(6Md zE9PZxgtc`d-~MnU{qFu6MD&FY8K!%^WzhSWcxul!D4r4H1T_HTORC_GfZFzIAUyu3 zGRITG_A^vJHX7Vr6yQk@T7m`%fcOf$yO<_AplFKpZ#%r#@~g|iHl3EwALcFcSz^lK5l|{g-nsV zG~*Oc)S#$I9S7Z9$YbCzdB(t*p%$os@^8{NPfisZqGB)aWg-^J zLLr$8fg)v5Nwc7<l#?hUo*gn^K@MyuHyDdp^Hi;gA+=sps)RWvE`M*>>l%l_{sw8} z$FqI;Haz?P*(%c|cgljlyihUhZ4;NB(#ypWZDKf65ICjE|NKSmY;fn&4KPTD=jwml zf;qhI0$M}XBo*99!&JjYJwhU|3M)ALE_I*Bh#FdFtU^AIk@pm$MLymhGKK@Hn&!es zf7CwI($z^AU$Oq#_~nNA@E{C5u*Qy-u6RTLI@aX{zFrn+H(D&SY-<4qRP{6hl|WCl zq7Ug(fG%v0qq~?CFI%V&nhRxE1AC-~gtGzX)nbdBxl~EC^v*{;=F?QZ82l9SQzb^` zT}ej$z+lmnDK#3cw9zy5rV|UC)63vhKFaySFh7UjC-rlRkYhfk8%HY2?%K-0%q*iW z78q6W%ledCx*-9 z*wzh{Q6E5PS*G3!s_%GxFzvlKfrFW;S&FMw2I_j@?+dNmm0~NQp@aLwZh(Io{Oxe@c7K$ziQB(stqWKQ09b#BQ+VUq^ttvjTmNFTij zp`VBc)lqdbja_-yH#XTRcRAI`9zBir@;MWA4Jij@18P3WxVv0 zwAOc-QFK4r9%kr%*U!zP_MS^Y;rCX;83CB_?CamO%MoYnbO*ADl@kF&k3bYJxSrd3 zaCeHu*p*VU_{bsfJa)&*t??Eg7|Mb{BvxEm^&p@&A6PG8kAA&E5!ey22!Cnaz9PKl z0mxaEY}*$uN^B50ResDA4aPTAv4w(Jw<487&2rA~u*1^pj)N0QPJhUB(_yeSpm=y> z9P-N;^3q*Ao-eDUx`h7L`|c7pI>S&mgHc&zLnPOVNTtJm>62NMA>3!p(yDVc8Z8&J zjJ(k{2X)5Ih7HZd9ka$>MWQ~#Z-P48)NmD5#wBP_;*G6DNCDeIV#x`9Av3;5f=XL- zNk>DQ;6@p7Fx&<7dnrY#`M#2r_B)c2@3u;u!Qy zQ^9byfJ6fh*FP&&XnT2+#}CVh-n;=VtuLy*V;X|Df?^9(8bdRA!0Bn9%8qhncjgi0 zu^m|l8N|AIxW&`hQ%^BP??Id5V^`z;ZaZYYA?wk0sTug%+=-#p1;-?;#1mTO(nRXH{SP;;KSG|l^= zY{}MEAEDxWhK+1X#!xZr`FbMb9P8dD<rPqsF zLCvgM#Rm6v8nqSl0cFPn?Q@;+OfZ^2t{Nz^zw~fDCAf?nvZjF)ZAekBk9q)a1NS~} zXGjaU20-8e`r{dl<=x|w#nMhH{l->%wJf3c4;by@sS?90v7dG9JQGX^T4_!*E9l81 z%Z_kSWr6K(V6nrLZ$KOOKf-AI5*hqNudg+b07)L@uxZuE<>MQh4013yQ>n<2)A!&I zDKkpQqBs|%pHxqhvq~r}^aDF{)XEF_JR{U5(YcN~!wTa@ypX(CFv{r4hzJ!!GEQXZ zL@l=4@|d(Pn*c$AfD{0sPw9p8=;(B&FtCNEDq&cDD{V~-Ph}$|2ig$wZIJn9^r`9H zAChYLW1(%!^en!f+iH^FRQTkcJ>DO&!q?|ZU$&*P2HXYre$gb&viW58lw+o~`}h2# zk`hG@L@iuGP40ms`Q7$Sp73g&90k1@Cwiv#hgsM-{aocOh`D;v(xH*o0#mZHfNQzi zela-uHmWnb(t8Vuc*$OmeGaO8kuH5?WSFR{b?tvbJLsvCB|i~z!VJ(~9}5o{f7D&_ zT7G9)+sSC)~9@zFa{65ifUy(+wH zU#^4V$SRCnNM>CuOj9B3_Y!ubV!l%_jTXSm=xOd_CIm>}oKb`=ffIC;k(}KF%^Rpy z&T31k7UEjGDKXg#VaIhh3Y51RZeQI{^C2_Qek@2-A^-zhl zULqbdDY+NkU8VSfbSAJ=trlVS3wbn)8aoxGV-BRG?sJD*Z68laf0`G2+X7;KTnQUw z*L_(mmIS?|UEo?4tK`l5gZ|@Ae`ZZo4;|s(Z^*F;Oz~y-6M!Puo)@d>0Cam{iE^qM z$_qzF3UAdZX3mdA-bX}JfF;Shp1v31^&laY{87a;nsPzJR|lb|;9m*M)hCsB`LfT0 znqDV5_bveshSdNlyV&$jtn@eaE zLm^85mYps!FjX)zU;HPR${ERB;KbA(PsPE%C~(OcXQ^+D&ruk9W_+9>`|+|+EHqvZ2MLZHPl}0y{lA|BlN!jm1D>|QY#upf*(s(%B!o(_ zQqbT->6>Do6|%Lc{c4P*R>#dZ9M(!snsz#9GHJPL-e3LE>wo&fqHTGMwFeD~klXFHr`oH4owZ^@cJEL(Hd7`z3Muy#a+< zxf{eaPBihqas_;%ut4dG`!{N}uu!qTwd5f2xfuKSe!+ku9=8C+cgxA*k8fY`wPr&fHW{v09}x5W69|Fk!az1& z67&O`3*46u^uheE*@@_khwBX}Lpg+w)V8f~a2%28Fnp8}3nEr&Qa&FTBhfj^v>yR% zLV$`Yz@;IFjnNd1Hyr*|aMLkQ8t*~5=}SQ29y3ahe~9!$Jdl+PG+9J1v(6tv zg%H_Qu5*MuHTB5mi3dAn4;mriULf9P;q+YuF~eo{CO~GGa1Sx(`RA~077^HWUcf)% zBNuoG7=QHAo)%!y?$i;WsIiEz@{xVhS?j}Jr#Wx9e6Tu9D%3;m489eRQ*4?#^eHPh!1i3SBAg^A(IWzd>=ew2bud* zb$Z8Zy%q^(=KZ>bS};T`b)&hrBQ^fIK~WtTP?5E4PHt}2(o|Kn) z%c-4U=tw$jqN$F=OZHm|a=*Z_f&F*VlU9tv){Ni=-y>2+S2+o?`69N}+EV2Ut@ zIBpu}S`ctpi^aV%rk0b|#4(2OFS@z*OGOHY5S-iU7aLk`gL<)ulZ2&nU~Q}L7Vd0DAh0vleP*Y3k7Vq-=yZcS`A$6eDJweGKG#m>+mtc zRWO?j&?iP&AsfdJ+745E^7sx{1P88I{a5`@X3VH{T#zL`Jg~^!29Y)ikot}s=d6!r zdM4<^r4=*JdA=_PUw#41U4ny~Q%8GB%ltAWzz9Lim)$Me0z+MYM2hHHvBgkY`w!dh zct~bjxUZNGYeN=p1PfCtn<6WFe6bszaV#l226U%&6^k93;kE}%&^Kp_h^}?)xrSl2 zf)O(KnceI+hS>` z=_RxRG68z05p94Euf9Gi~U!e7ENQe^CRZA#tOVbZKF+$TC%)6VKVcJsH@QDe~4f zk6B{8^t4v9c_W&q<$`7BsEUjq%;#Hg_zrJ8s`xI&m7kW(7_s_)rXsc@@AG{Vo+q4+(5#LPHm%*fpa>W}0tqclPS-h@04Im7${1*PRBmk1$VgJvbt4$&wC!gmqD_rKujA z8|c-S)ja}U$*w7{`pkMdiub%U8|c!3`PzT}X7cWRKMtlT=ME|zt2m%gIX;xT z2{RiScLe8JGg-Czbl(y#lhJg)D5`ixmakZ%&VYw6(=ohB@S#!;NUg~bj~r_Q6-*R% zsL$-ntSQjnwG(?YryC3`W@+h|!3t-Tm;WWWxF%bW-+Q#ZY}DC4Rk@~M8`PTIIz1QT zb4%;7NKIX60IirA%}{d8+^fAo*H>gFS9ZB=$la`%#S!X#FzYu@72V z58boko=!y#0JkW`xU)^;IVtLcX_R4PQLIP<*vZII2ZP&AND>_+SE}kTO^abu`8W|e zn)K`Xd1WH#zB@o@tWM%X+=7+5rI=km_=~%Sp-aR9@K-YJs6J6$l0U*qq+SyfEQ(tu zVB6y>bP-_c%@s~zA3!cJpV1Ym32NJ)4HWhrd9GRfk@4+e-!kirQyC7GTOOqhsL+mkvM7wi*l*Qt8E(v(a1?v_-?R9?4%Ai2a^*g>2f2uJg{2AGW`o( zh{|3x|8INi!bwSWRd4A6`DdD zz+Wr5aFkGg3|)yP%lpm~x-mOb$p=!leq;_N2zsK5huR-^B%=)y5XXKPcw`Ju(@~Z1 z`)eijZ;oKRPH~%`2_#?CT8d2KGor`dP1MR?`0>?4&e0@+S0ass<*`aEA}lUujFz(0)gt6% zDfGh5%pI~AYxd+(##Shxo?D0BGlxC7$qpO6FKn0vryFISVa%e0NyvTmM-D`@RYtDA zpOiQ7;>}-*jh;$5{lR_Bq#pDID*KS=dmw&~%>yy1(#}yYM8=xu%&Lmxf9q>i?*|$i zQC5w)Ia0~>rC=eul@!Ihek|Ntvi&g}x@?jvP*l3m_eh%$?yFGuAt}33SLQlrHk;^l=Qq|;wd4v9-q-nL>TID7z#q)-B2p1 z6(;MHK`>q)=q)R6>F1;?&FeBe50ue=K8gSHQZzP=&j z^Lxs}AGdbC9;rfM8MPwq$?m&?2(;^dhgLyfj${SE3%|R;RW_4G%u&L=K?5`fMOAJi zh7r5W*Y|$}FEJ3@gG<%n6$=@_-kR-3bVHZ#1X1n1uTIK74-o@cgXKcw zf~BUtpbRPu=KWQ;rq3^>|M{YKuQl)7`nz84XiV9l1qGswYj=R=B%UdcsodE%^>0-v^73 zdG10d=<9|Ema*!iW=aOZmMw^U1*5b@V6m~4R<>}VEo9V5PZG#dV8LV;Fjnqtip;Y~ za=IS)C-CvNWqZDB-RZz=9mmvT`^ zC-e^;{wFEScS~x65b=(_7|Ogly6-6=Kzcm;;}NB*VZ7?#11n2*=94w0nG=*9^O5%ti|=cg z?o@<}%;z{%bwAjvDd}-`{#shl38zKhwZ&ZlT2f4;qDkp-j}D?b*wX+7M&& zlmK|7Esp_XN{#i*!}|vBEwc|S*nwKQxYj@gi*0adB-3LO)&qJ0W@?l`zmRorIba@u zH~C7dbBX{QnGHOav<57V5PpD` znIIjFfxs9ziPEjIHqltjbU%!(*>5!g{E=1fPrfUw)BNask9~G8_tip zdXB{DG~)rEVY^v5+0AaU*vS^RE6kuFS)ubBdQP0QC^;D^Oz#p-O(nI4Oxn!FDu5a8 z)j06K$5;-8T$%&|Go?fWx^g7*%^c}SR(S`s#}WZh0onG$n+>;NuboHi=_rUt&G*f1rGiF@BuO~C31lrqjc#SHVuoN4c2L|T9MA(KNEqbho0 zWBl>JpLSXMWx7(37yX7LZj1QOBe7K}X0qyeIA3l52`D}Pe?p+UO&MhYM zp+6*nVYSpCIrorwiGyfBWO<&hHPpKdnh?ZZXfuiiKw4F=W$UL;ge(NI)M&|;k6+Z? z*WD}OubH*mbhZM*S_}OPw-|7D{2Z|@c3En(sQd&#d+KBPt+34vT0Hp!6}3{2qnA9{ z8f(M+OPpvZ!_6jL_;lQlw@g69Esp+FWu2Ta^&0Y-q4 z4PSz&OOZ>%bNO5>Rt;@5BJA{}) zWxDI@7-gGAi22M0C{f9M_sxF-Xm@=Y*!n7$_FKEg$~Q=D9$_zGqp$Otj{g~!oN1Kn$!^(k0VKG5>%w<7 zu!+qHFco?h3v{sE$oOq?;NHxd+!>8 zQU$0d6Lj~m4Tpd1jK11eQ2=p%IRYxvPVd9=#O|SyJYBZ!;2e~^ldUMl`nX9Jtxuhq zU8RG==SBL88I?nOR(gjN*KJ0!$gGaP)4+8jVzdiGstp!;fqzlx+B( zSf~8MBawZCEj}ZyGv{DNvk$ZG3PNuwr#B5IKz>+Z0Y!gUh$1=>jLhcAU_R7Mf6{kB z@wA9=EMvJG9!@aV5ECt63gw$u+)I3{3h}tlD!>EG%$KyFi`w}`uRc{J9=l0H6 z_<*?KyW^-98L@3mlVrbpA%yr=`oxj=Z}@kUSi`qdsW}?uKsj!BZtyi)M^lnev;u{V zI0eQk1)-k*J4k;Z!8N|E-eAO$uP}KvYHE3*3rhyD6Haa+*D*iUDB;_62me$=;>4zs zfzazbo=BZk`2v}HC2!1}6uI(qeIoxzii-(%GrjuVhYEME-BnMdm0%>O{P`MT45kZMelm}+D_r23l>(QsjHuNX>9C`ldW1jK zdM}{;-md(IhKi>Ut^wOOQW}m25}?GDrHy%^O(`nvSbWqnVtTqxtc=8xD3fwHjW;V> z955`-Z^kepeF7_pSoFq`=#gVZ69U2de)pc3QpDm-C#RqvrV8`zx+U9&qMmN^G?$}X z%^2zOH%W=+fP7i)Z~sAl*ar!-e;VM{j;=4vgb1~7G%0EAbN6>8A?niE?MWjkAT+w! z*?r*Kl*0NV65h=@m5pnBK_H!TdMr#ikEze`7jo+^2e)p2md~_`Cz~hR-J)d28tN0JNZKf^F!4RPjl4YYrocj5>U9`%>d?g&qD^Gck|PL z4ctAZ18Bjwu9`D(nYwS`%uD9&Bq#Xm)wBzDP0M!XF3mgO6IaK9Fw=ULiv{0X>isE8g-gqYVp4Mt15N$&0kNy7u4G-)I3?X&M~|^n9ecpaqh| zTgEuOp$*)VL@+_!cY%u6GneTF=^A#<3bq?yFFMqi|59SI&_+7G!C;zIHV?oa(W-%n z4e**}8vw(6F0N#`0}H}1NGt+WY!bH}pD-#uzirG6sl`x?HsKNqDX zEhMdyUK&AZfK^^cQq^y?Yb%)YRM9?PxM?=C3--;mI(V$2nl z=dmXk(X2qN9bzNa?tojFn^f72VpBP{$d9H076%(TU)uG-`oF>tL<=esne^{GVU6-y zXHJr@#1x{Noje_Ks@li!+28-GKnZ!>RZiH4-`<8>7%L zq@=vCkk%lrKmL-Z3Bd>q3cdbTBfQr11H5K-z5n@G8!w6!sV9S;(7CRc9JZl61&&u| zlNp;AmE0z3XwE}nldhih;D$1M%PV(i0e&+fqP-+>Em zW+k7j7U->oMZ|^lrl+mNCZ}!X%UORsHJJ$2Pm7n`IK%MfWT>BOPht0E0IQ8M_3Etv zdY~)!jdoL6RLjM~@o9al!tgUS$XfZB!IIp&C)QCr0u%z{o?|x!S(@W+J7*1w@M6GX zZ$~?W1uk5_EQ%^UdF31Xscm@rqSLh+dZ0AANBJJ_Him@_k@H~s750x$N#06IK{>UU z%RY<*w$A5V-6zFaNKELP(nM|y-*NKf5Mup^zeZ}vsfLGfIqEEr63vY;I@154nmgFE z&w?=M+T{2N4Sm9c{xirerlIW)m3`GQ6=feAB143q44J#dc@~BFj$9_`G*vH0{Y0m0 zgELyRSY*A@Oy=m`nh^FHmYBcFS#Ux~Rx@0%8SGKSJ{1pGwaTOf7IViLOL6)#Jy#6z zan=ch5fLD8IJf8hx>pdmppCi7TQe9OZL=XT-wuZ4_SRqkQ459$FS$4YdT!nbWhdp{ z=rLo%8Q2x5YKE0OE_6_FGkGXN`2Qp<{NPVgmBfvCq}!qPr0d4%q{F+azvfIGC+N!= z0oW;e<5xKF3(~t$vD&TKk$NWi1m&7vL~3CHHBhCqIOKxu76_fp%!X#PIqC)dN;09a zB57g9fI{E~{EMmIH=!HM2m-zQfTQ*o6bf)3g= z*^7%fv#n`7IK4p6T`th7ZwZP?!3FB6oETVZ*7AS3m8h?snacRt{=>hcG93~PFHYWHn7o~!KJ0D(=2sNK(ECbdF%pS+Pmn=^EGV0 zudC%Wa4FXwhd4k|I?-0qI-7PY_y?8HgY~G40r0bFZ)HNUl{o>|G1T=^X@qq)Z7>M$B!$(u@ z6*_A-w&Sd)C@ymgi~zpYTGaw0X0_!;N*X?|KZa(#tDuW53#Ynzn_H%XKuCDpG}VZe z*)ZPH>w$9HW5zdoxJDlh6%lLrZC@hE5NV{qEViC0-+(zCUXr5d=9Sgxa>yZPY)@F4 zWTY&|XzOkTi==yX8$Z-;|CcG6(0arjgyq8wVQ2|-g_UXyvE#|+iQ_qP*c0jVCX)x$ zIq?P(I6nl1LK#aec~AnOMI_GtaeR=bohNT2)DMb~-}F4imiLFRcI!l;V(`3g3fOgD4XLsL!oyjC{$I|^&VDzovJ8*U4sI~>TP7)m@F#cX(j&f|9<6Nso8R)gLI^Nzk?6zUy zYU1V)Qt@#FKV&sqTkxL>!yAl!|3a$lV27_rZq!dIFkzn!m-wmHJ9BK7=7Lmn++}ied?s!K#}E(21YjBr#VQB~Mt;Y%IC4 z5=wC(S&GdKxWDdTiX>Sy?4(kfiJ8 zKx}7}j2)HrES)jYR5}NEa|Th#N^_XJl|=oVU_2ElktC(*Yu}-!Y_-*gpiI-yk(?9$ zzlyi&*9~zQCRG3wn+=aCuU?HI;Xq~e0q+~7!Y|Y@VS?@r13lgr7NZ6&N;47|k*1GI z!i#tBoAz@^>+D9L)KDFcGQ0vv3$m4vH)KQ}lg|>1shiazc{&#^ax|j>L>A~x! zAC$b%L@`2B)8iSwKaJ6A6?c&>L>4j{YCPLkpPXlWSB1hLtVZm&bFms^lhd1y!?A1L+nAb*?QQsY0K$1}KQl205%y)C3f9xS*i zQO}02&(i=i;(=?=`+nA8As;1p>Lq)uV;X4?13eZz^501y0eJkbcxg>Zd5}E~IH09( zZ}>D*3cbGEktlKmmal|)-BQWjm#JFhyvLGmkC5mE33>4}=>Tq8pTzlAD%E*0C23#K zFA8Qfei>)UJ#{sx$$&?MMkqzYoQ~>viIph{JRB7^t2U46o^*V=bpPbCCjYW20|To- ztCt!$e9Bv=s_R*%*@-0$aA>>))kn0&V60KWNkL;)@j`g8F}RVGNs@_{yOp+96x*)N zmMY!U33zFXR^c;ApDl3;bQIvMQ?`TY2qlU%&uYtN2DO)&>>x=(FQzQniM{tIxF$T3 zGSvCS<|paq?hT8cp{2Ms^P80?3T4^K2e4!m}tDfp%<@7h* z6s4t7pBl0gcxgeizXP{BDBWVr*jF4cmaM7(mKABTlxz2bMav^$FkVO3gcRG@Prs*iY<1|Ld5@gWdYPX-u?&(Z;X zWx3Pbq)4R7kDo4c`0f$wzoP|r<$Rjdrjlg4c6i);A(tTHfr#Yc!CkMrKp903v7%MUlX#NN(<2@iBA;1#x0nfOLV^T8uXw2U) zvS+Cu_LL)QQz*g(B`oD_3**NWGs>4B=uv;}BFiyK;2$Ns^z_hLHd`jW=-D2#!9%Ih z^TCEyD!Qvu!+-M*CKhz1vp?w@Wd`?5&0zoz9ne1?FV}hC)sU+&%z)Q1&oJfC+ERs-q9ZwAO}*u&LAq@mdBX)!k*kOamG6ci?y`!_=meAhwN!?kFRBH8Zd|?zRM^Ti4<3x zRxmmNNg(Q@BDS&yB*XmYPokZ;WeTTDO{k5rSU(#Dd{3{hz5skY3~olC2ad_j6ZG6& zIJb0Gw_kdk3&@&nYnU`z8S#Cq|MI-GKHM->ez%U5x3Eaw2wqaY2G<*9K(Qx7U^T$M z7?`;ylF1@oPXqNR!)?foR=3f5mUyy$KUc|l6Bb@Bna?1$ND*iez$2MinWMb-#WS&f zu!z9j+>UEbp|xv%EZd7$hN&AHvs^C$0w_3#KSOJDzrtq6sj|%uxV-5`D!o?xS`HyF*8nrycd^ThlSK*~lnK z@=->|U`o)#p+svxgC1}>t{lG_Ge!X_ZJEWO2@~Rm%lVS$C?quiSSPyo;qKCJbH%NI zK8BZErGXlFGwWliUlT9ed<$3C#vW)(CgL)&QTirRallfLLgzVmAd!}m>#7~Ooxtgx znjd|H<>%l=m4u?X=e3EAK>bZfgEx!f#y$rbRPX+ESJ<2kw zQFFeC&Yh13MJ}6|M}BTN8_niWCV?imRLs1@9I8^vA6{{>P#`lZu5+j%J-)EzUA6|K z&E%1ER+4e>4X+?16fGEvlYZ0SvL_+ewo0^6L!gdu0hO>?#jzppfbv~Sj}gOML4tiK z59&pk$EA@z8zC7=Dby*NS}LQkF;g>&ef8-ryoEL zrtcXXD=wv2Bv8QMIyzpXk^*zHxLWdQoj296Hf0@opaffj%-k04c3l;(6Eo5x+3MPuZ;tQwo<{MG(OJ1_ksI(RS&+Ipm*J6 z?0Bs`1fSi~&O*R6&8?9R=3zPYJZ)P{yn1v_s7cw;(}* zF8tB1=0FNKNy$?76d)rtB4Olw)K?$1(Oa#50{J9MLxb_&1A`%q7LfN`kwGXohvmtB z82)ITo+a^Nt8AN;9{DI%Z&e@UMJb`B#(f$7Pii60(pPblXD6ZPK%Yq#4@dcXV*`=% z`_@A0^MU*@k+^_V>__NoV{WRIc%pE0_n9rRF6{e7_@?2gzB`xH7nESyG!ByO zU4bI^EO`k7G=s@pY^PcF>B$`jO=ewu|Me(COC$pI<$Dd29T%_pd7;-@hu~qx7dUCn zOt)udY(&`3CX4gUOy8IXl`Jw%YW8R9L^p?q-U6Kb)f5SG0ibr}{mM*1b=lDqcDkZ_ zH1^byrstUBBD&U~;Be`wkZGQDgT)f|{p6eLOK_D_%8H_Kt2oUxJ)=qaW$L|G z!jA`4sP94vA&Aha0D9f??x$*ePWqWS#F!~pSRz{Gapr(HgW8eZm9Od}i1Vawy5qo} zwyzlFR~VMNj5_ksjkYJJ)NReft}RM++`4$%-QZ_4+h*+KE{@7br3Y+ zioFHxzvN$t^%K}^)X)(tokn9xOd*N$A3Kx*^7At(rc@UbIfl|pAl-eZ#gP^Xq5b0sEsy7XOWfQ z_-N1Xx`XO@-_Gx~_L6yb4so+{Og%_#YN)L0GLJ@5AE0DZA27^CPqi>M$1L0NJUuZz zr2ouXa_I$;I8?erV*Fe(piN1;_dXoLY^CznqT)S8Y;mhd_)j-W8MB0Sw_v3SQb&X? z#3aa_^a#2y_AIO=?dea38uzXOE$x)>W4H{l(9NqNM{u-iX}=E_%7;ghV~OA?_6-%i-|2;k*Wd9`xAit=g*ZT!GWQ z?FkWlZ=>eZb8(y0@~AI?vr!*A3#;;WId8%-t40NzTV6~8Luf65zMwvGVh!jp;J&XQ?n%o#0@LFQTi#@GpuB~u+$J)#7BJ;yJmsGBK32f_d zOp-tuR1MSkWaunAaNQsB0jgt-P2t_G%6cRt{H|AVu4U0e`XDt~Qd}xBnW7XnY6G3O z^RxQ7{1RoX3VUlEv(&8rCC230-P`->JHYA7mRGYyk%WZS3bM3lckTEwBHAv|zkf$g zv0_3UwIf9NiX2Ni3AHi{^34Kj{Hn7eJLN5kGgP^+6QC)DFb)I@ZV_^UnsNq6QW5Q8 z1*f|J4J=Nj5q_@E0Y^A%cM9%lKbMB_G$cQ&G>Us?y5G4T62%_r?Fh1vH7R}Mwu#!6 zR{?|I8oB?u8LIS6%Ore`<+*h7hd%D7{_8h1kVC(sI(6C%RGf1}y&EO(vEj?was200{t#$rB1ohhken~b}z2Bv)urellhEu9fx z9(+b+q}{w0)0IuFFhdwkc9c+2wTp9lDh=950X=^7=TQ7Ik+hm~)*qi`M4612;-nL! zE)EI?ivoLc8jA_rsvw5|TQd73nPt?CeFi0OgsB*9s_Pyj^QyA%8T19e8G(R^!Jr5$ zm9xktX-Dm~8fpVHS=BCtofc&Edz^7o7IF|_`fI5S+;Q$I9(P!n6ia8Y|y zc+bz1UCs87e`tOB!9?Q(lCI|d%smUHum!oGY?BH$&ca*!+d$*PRA`SS@5YI+8@j-7 zXN`24hjVKc(9paYrgvvi`njFKAaC}$#YBqylkD9+wpE&O%Z7(EyX+}#-9ar_YoQC( zokKOcKLNYZj~^_9qJp!X^4=e{BDZzZA&G1qBh!*n$MWa+ZU0*z|6VXz-1*Ae#@Zxl zlt|wK(Ru)V3yxXyp}~0*S_qDl?*2aLH_w4FMj`4tYms7uCH0FD6GmtMlFPwRIZ8}* z*fZsj2U(2a>L!bCcCeuWu0qzlYI8#0o*tYj_!QM<>=AT@luSyL6onzlWcSjvw&FvJ zj|Kc6_;UKn`$n7zv}Q{KfzE9Yw{vJPvCdA4AlT_#{m1@Ub;R^V9E|j!8@IHuCziMF@mZV@!(S^97V|CJ2?w1>d=`7b;$l+tA7f59#T z#**2~!_J&}otqkc2%nm{B;L=zH-CUz*da4#)B&HIlS8LVPtUI=PvjxUBRMY@R$=TTS|0rLW^O9iO z$uRq}$6?S-Ft&9rx%R3)O1+=(jfIhe;V{lbLyp$QnSL2@bG#wX`sGpZJP5CktY|zP zSO0sWWmyDIL&q0U`4TWUe&{Pf(Ow!R@u3*cZIBu?KO{y=x>v6As2k23HdaTnh)nf#StHK0 zNpCI(*p{6*Q*+HeSR2@8T6w@yHszG|<^jhYCNENJ>=Z0|7AS^|X}51Jae zFxm3raWlq=AKb(O-X1YdZID4ti4CfGy}%=wgx@DGTYHa((I<_pjEjc!Vh28n`X6^u zoAe_?j$Jp1?GK=kDD8Hvu0W%>oO${&9)%%VB_t3#kRjKCBZ5mon&$owqqLNhTrT-1 z_n%3}R@@%PsuC1~oCUY*yG8DR)%;-5o>5@@y}wT8EVmHR zqvgDaM7!R0QGmV-G0OJcu|j$QR5(VQF#34}#|J7h1!rx9I*$+wrnfmvN;EI2_e!tC zZ!L_Hd%Ahb#fqXnuc|VfTlHrjP(J;fhO^8DveXj35Pf3oa@8b6#5)S-gzF4_o$vP) zg-hJ;8C_vU7ARAB8Rz&*E+$p716O`HTSsR2o64*eZmubYUfr^QE%Vv6V@hI-fK}T? zfx+>KrkFBW&%#9n4FU z3t&N2ccEE@M|Mm#x{!Ym74wS?$V~G=qZs0DFT*|9;;XzW_-R?QumfiDQ2LKUlgovJ zd4RUiu0ct;o?>Wi1GT`*uevz-El-H^Pb<0jd>Vg&g?^q-F0jy=;t!IFvG=h>IP;8< z0?7%2>2x;XA?tK-46CI!*Z1Y#2i$ve$}Zlf?D8}pP=_q^)t;itf>8|p<(TmS@j-zT z%H4m+vjJ1OVs}X3f~s2H9r@bCOSeB*C^`Y*P_*8xNv?R(OC~O8`AfI`w3NCs52PRX z+G6+umNHN;-~AgG+f`8q2CQ!K=VLGQL`|UyX+V({0z!kjILv-|CBT;+($%C*b#udD zi(%bE0ol&(A_iNwyvMapmA3+CQ^?2`6Y^}bZ7DTn2FKcSg?B)3DBruaE;?obDNA zrbt+rUEfi>>;=$^hsZLKBHctIvyL@?dMEMp4E|h&Mo)}{Zt*(A&*7Vp;~nZV>_ltk zuygNx#X@rg)rRS50jBg6@jHo>)Kcpx94$@;2GolsjI!oTao=Q^uv?FjaFay8j!rG|{+S48h=$Lz4tN2|fVC zeoOStIS{<0JoZnj3n{S{n1FSxBvoWQt)zqEu47DY(b&5HH093hd|IJ!$w)diax_e` zRe0%N-spVcC1J)*#gp*_JUNF+1y+~U`-yC>SpT;T1cxWy&&Abgb!%Z?K;QZe%LIj4 zT)OQK;x)xw+BOJiUUTYYv(S;)A*LBAj0`*Vv&|;-N?juZCf1_5mNFr1gJR;AN)!$4 z)vA<9`_T%G$#85x6T5-5I;NbBQBybBlc5Hrj`m5td6oHVISDC^j0EgK&`lEk*bxFJ zIqR~}Qd~gfgH4ONlzjn=4`W_ku(z7g4peyUI>HF_5pRs8Fe~m)?1erRyaRNVWaVzEqHZ(4sh2MF||vEOhl zsil4#Y#*64sPb(y1Ljlx&88$lYoM0qd9*m9Xw21f_s{&fJ%exdKid*bJ)1pqgFp$l z6%V!LJEw>m@e&ucmV;W;DvL!4+YCI^eEPM`-z^YdP_$EgqZ_!{E>w3<25}w6%FI2_piGT!&H%7*d)2nqx z`SvwmuVfu8qa#gqJI+f+(HxF8zV_zvQ$j8yvy9il56m>^4(938R?32{YXa*vs>9cFDf=LpzMIR!l1Di*8z z1Jq@DE3J2UgPk#7q*WxC^KKs(7ZWC5x-ADrC+LH7ul31y;%#=e>RF`U9V=Fhyjp?Y(`noky znWeTnA(JePL-pi{tf#l-dj3=JEDF)0Z28qcl%43CQF@+0937LYLecj>(U{l0f<`#| z(53xWLczHPb@MFp(YdCD$mk(-3&ptboS)w-vh0P_2R#7+vI z9r@(x4&}5wKS|?h5GfdXOtQazr2FP1>Myg>3TZ!g=j@T#sy>zy15{D-s?e$ZhRhkx z?#rb=^H@)^p<&PBzS^1-FHH2KqiUxA{I`O`(ydSJ(lNrtbUp~EVL=pq09&;$F)o&< zE0Ix1!o<0osGz*KUpaFgG#=X5o9oD#z3%k%UyZJ?l~NNM<;Ul5^p1mN>*x)EA2WSEJZ`6kX*9x=0FQ<#=?tnw&(yOy*sn{>Qa9qvmg866;MRCP>Q99*1|P z3X0H^e~1HOq`O$>48QBC47KG(-~TZAUgWo5ZSO+wm#ylzIN%-&HgcN>tSknJ#6K3(W(>s82slgi-b#WXTXnjW;I+462}mYE)47^^ zLpjrqcK*A7BsG{%T#&Us_E@hPt~ZZhbf2_)l~z1O12j!qM(O}A!YHfwW^PUsmz!=; zQ^jI%tTqflDN{dY0oGpjc<~($G-_8hiF|xuVbB1e+dRi!$YegPHhkHggMp$U{|^L% zB5IQnFK%CWS4miV#g>pGn`qU|;wIoXACL^*h!Us*I;JcDGy;?9u!ZkKlxLUg8rSrZAI{R=n85!Sfq6Be7Z8;;cbQ2)E~))MSUZ#3!j^ z@N&L9rr@RxlRRP>leAznrwz@k9^AJddodr$ekDRZSadwBjkC^kw?Voh%08fTU&$?Y zxI>^DgLrh#$#1F6s-}l(qQb_c-f{G9Y!mHF6Cth#-EeOMur#mtDyOAi2d8Y9G*TKW z!uAq#(&BbyCw}V33znYQfbvAC=k)+sKC`Z4C@x|^#H{A7%{dE5%#wE+1y-OuNrAK^ zoa!%W>c|^RU`4?5epcoYIses8PqztG{h^NV4E?Zf+I%V^zLC11k!vU@X049tJ_Q4C zS=}#cn8j}>W9?f8mk(iH9sLG9J-~Ncl6{Pt;@Q;0@N&OtSYGo#wyCRC*Z_FOms~a*>`LxM#Z+m$ zStWgq1is)~PS8#KflO%n*!8<{&?OVxGhb=;APvt~NW#I})Yqw_xO!b7(zOfgp7U46RC^&Y1z72zxz#kB%@3t&+Vi@DoLn ze`EiJ2~Wi!i)GKun>I%}H@m5UmJoY)NvGQvu*(6f0P)Yuv(vVf{>DDf5X}4VfSC#_7!&{#m;3B12e^J-QYo2E zD7Owpm3HrqDx!I%`2Hu8PEoS7k=o8Y>n3aNX-$n|lL9?yBm@t>4kRm>?&Q_lZ(hLa zebkfO2~DsU3goTW?k7~?4}S!pjJJTC9-wSr6`{5r8-?(o@B#- zI0y@IDsi`D)P~?sraldzf6UAZ@`>JGf+Wzf9wpm<1zmTG;$;$^7eaZ#pvY#1LSReM zVM5U14(hv%3jWFWP~b;E(Z)(yvuFX4y2<`0)Yps;90@k;y5=xsQT2Ek2qsZ~NPR29 z3jej_+A(d;;fiJ_ECR4kUF|03U^h8CyW(;h-karvS7E-DktDa5bW0s{?++drD0^F6 z>yftm%2p{mKYMkROLVQ;s293v7@Z!-1( zxl|u6=Hg^cJC^fEI_`z6u*^h;gVUIv=#OuyBgqCF+mTXb>(hoh|Zb)6=weg5&>8EC2taN z%s|OFV!r(WtWyicU-PqKR(LoN8!$nJgMIw4^?{7TC$}(PUq99#_jOWq5%Vb^tlG>m zY8FN!Mz6`>K}~9a63BIW^PP^e^3lzje^P5Q>>b=ygW3&@ zE7N^-_(|F?{W?Hi1S4f55?TnkyHGy+w5+H+-f1H!!KBo>uL(>aO^|(-5vFMVK%=i< z_mpBM{*Zcq4V9oR;nBDNFk^TXhUf#dkM{MpOLvvDYpLvyknUYn_Wc=+Y0YU6J7Rpn zg^dxOr5d3Mc`O7FlqSG=o5?mJ9M|ElQNa~wmQCe7b3p+M18VJm+)Z%5NK;O7%aNL~ z3+7xhe7r7&gPo&LOR3$bYy|E)8-lGKlOaGRXwR0hJoq*(fvq2;Dugby3z!8`!Zk+z zB!lNVIiWnHG4YZXc{p`xe{no~DjR{+5%cZR?^~^%E3ucPJ!*^m3s7-W&K!Jb@FE(k z{L2ufi))s>7JiD+rFzl}qENUPnC>D>mB`&?pyYTDv{N+xq&Ujfpz{neK zRpAvRAr)yrAoa2_V9MJ1sFJ_t4}!U5DMn0J+L1g(c%sRb^&I!`-4BV}A_cnLh{g>C z=y>9^K5tU}!Aty4%qp?`BEunTr!TCEBWw|=V!=A3u%@NhCxOzTZwbc);GcSJy6>5a z96D3Y4^5d~kTu!QY4pnW+dItr9ooXs_}rHmH_83H*o(j}-B$vV(*2{0+-}Lg21PRN%o$$>)F3 zy{Ui9N6({aV;#+ZZqZ`>`Xt?Q2*)EScC42e zb=wS3NekWbMk59>qFra!`3Hx(TDxPJ{7GXD&k*1sF03tk=YeHW5k@i-MnhDObo+*+4npsRU@{3>nHpa zW}O0SfUfNrAxnKH{5`3ODNZqPEF|ImQ&8th(w=C_p)SO3a2h6=E~C1>y%h+Z?&Qkt z>dF2S(PMod9(&m2&^Nc)Mm!_mpTe1~)M2R}jU`AXT^^TKJ_(cq7ZpX|q zf1-yBXD9p-zpq7w%_h&+a>b>>iHs}>=H#}N0MG>=n4U3xd)zNPWiXU!?(rt9nJmKp zk~#$^2f{oO)_Vk~AYIG>!pOZqCn>lKRD&WR)~Lu&h&#b+t=pv^-h>1ALHFy&Qr2Hl zDXKLE1v_T)OyabQY%&$8mL2(V!9X;YdkasM3lRN1iavvut^cS3&Wm=7QEcb5&6b6d zxy*iXhyo#$@Fv?YTukXr$QONIUMAGkNi&^!Q`9K%Jx)FvTdkN2q2Q)z;+cSAt$HGx zQtNSk-v#UGN_}e{Tkr0tzdZBT>KNmcbV-$aEBOFF(qa&UlF@sH6U)yDBNjQ8HC0M< zpnpZu)paE4Q81}?enjY$S_tt-Ih&Ku*U-1o!D>jeRZ1$~1SgY>zm*e~Ncl#PI`j3T zw@GHU7K}6mHsLMjtq^WAuXk*}J~r(|EdQ6NT#oAg_T-TCQBDSr?D zIS)XAg`j`2Krb&EBgK(5iP*6sv99CI2Q(Wf#cRP>&4aPSI13Pg{?-NM8aRE@KDn9$ z>a;OVyD>iL^!C!tC$V-v!?aM&o~lV#ut2ToGqH>=U)*(?%S8KHdT$x-MQ(pR=$%oZ zW~F<$f4gA_9W9nJvcWl8vfgz{*OcUo_SrZH#$l3lajE$l)6OZ0-viIi0!mp~76D4$ zOEgCIlTi#lRa5iws20gzE-h_Ov+aAK1z;&F?+*fM1*;Zbu~cPl10NzJ0vs~);yi4` ztf+60KBW+AX_ia$0fgr_c+d!cte+h1^puuT@e=bF$y!KOFO_8 z8W@#Cr(EmUh6)-|!*e}S!u>y%A* z)?Ac@&{_|c`P4j5kfPr*d+s=q$j_;WSsArIsrQ`j`L%X7hw}RIUr3RDD`-(z=H=GQ zT;7#VAb`a?6mPliMtB7Y-0oIaG`GTaYNQps^odaYd>Uhp7g;S#h+2x;bKx_Xs>jjd zVoYO8;5pGV7}Qz=Eh<|qf)VM5lR5~py4o!Mq&ChSAKjVsQ!5PH2C=0%`JDTBEEbJk z>+(Tg{A)Ij?+6fai?YejI2=!{eO+?w@R*abMu)iSyDe6fdsOzyQoz|)ZEY+}%aFWJFmq$#v z)dNeQ4-bWWW(-Gfy`CD6>cpUYDFrhzyV|*iia}+h2A)Q%zLEG7Z(FYMOEjB^zEcPz zOHbV5I|+LSHD%j=`O6b>)h;vHdM-0qxuk+N9@Xm1D_Kf4UyCO#V8m5L-??D8hOk5_ zUj&m!^>3y4ToxIXxMrQoR^H422o?N&SuW*P5!3In<^+!`NG3j<*IE$P3LOK}L6vx) z>69?G$PotRRgRbBEC;D(yjX~=qbL+F_xZQCOLxJJK4p^8=tn-dsLN zhZM|xh@`=6m3NTdp{jW*&I-o=9*sqk@&OrOPznW0Vk`5xsQ--5u=A$arr?iRVK3w@ zBgb^4m;P3p1?S&iwo4JZgtsn*hQ6B(cGPId8ww`L4FVFO3S_l7`5mC`!ZlvCU#Dn> zmJ6silW@P|TR<>Y)HIlXKSRP~)q*-~9Y(p?2g4iL&<_7RYoJ<~{|8KD%`H`goj=QA z6vxodq(<6aB6rb6#Cc1xRtrJaw`uS?jJPPX#sTbK86F{9b32+a?SqBwG_z~a)dAYn zdB|vIz$(G+$?OS8RWuY}zDYP{bAhgBq=oF2#Xz$^Cy$ADtng8b6KI!0jrA7xVw~?9 zqWOG4?HbXX-p<+umJ7Y{*r3973V&zyi{MD?shN_(36X?biLxq6U`W(%WZrRQilv%A zk&Gf-8!pFA4RkgyN=;nWE^BgYZHk~rR0P&Nl%!&JXxw#%L0rE`$gto|lRHp6cn%rI z8U8i2AWLjHXvS|Bn8yh;p-G8OtC1s>+mpx=ZiK0O1a)*@;GyBRiXs9DVlERFkqF^f z)-cJbf=)d<)w4#;xYL!ah{+7OTp_(B)|gL)sLe6K{%87oIqmmN2d39^6syJ#FOLhl zWB~Ju%fL_g;h#4d>GXt8i6ggw-s{IB^m*FiVzko9l9YmPih&R~O{enQ4pOGWKHzcZ ziA&)w5q>rDw`oHo7#O-}kxs(n7ad}dW`k8u+w9)<9ph@(8U_URFkHOi`@^Aq=Myvi z!yKBZJe2H)*9V+PkADp+w|bgoz_*7$Ww43I!oJYx)qlfFJiSn1y6IVe8!%!HB;mM{ zM)8|Qyk&2(#$*3Le0fyF4^Wn~i27c4<&O^+rNj)`oLwDXANb*KDWq_fKW4(A?oV8! zOx!#mtS2F2Cg(jEO6p~iC2?f5Hoan%t-rz8Xwx)5YyB0ofRoo8m(le(1_0EU@KaBZ zm}PNT(!%ol)}DhJMAwjlHJP0#;J;kD{ttSy{tARUZKTx@oh!@?jySN#iec}azO?K= zak0Fhnf->ClMSEpDYAbL`8`3$D=$!;s$tFV<$*z zbvXsWE$SQ28n;%a{t>#mh8W+S0oBjjfq-pz@USY*eo87QFMj1$yYOG zmEC^uxf^?aX;_GeYa+v|iPmhzy}{)+j_!i{Xyqm%{zmYUS00Yb1GLXNNi&x zyhq5m5jK*z@o0u^G(9W*E!ndzoo1|Rk7t`QIj$3#acZ|pO@g6Sm_>(@B+}cdCxvK! zL1weD`!9^~OxuHL>l4F^FgIk(7UgT{%1iWB_=3RuDmpZ5U3Gw2`Sl#spP8P(>n0i% z_6~H`)FF4RX{;e6#|UQWad#>=BU(cKwAZ@;{S+xKroJeJ0J7%G(1olIABsMv))*ZqopDvMvwZlOy^t9Qt}xm`W)AY!XzKvS3TYoPoOVVrobIM4S7B?>x z^RLOGLuS?ac*X7<8hw_E0f7i+)atE9+;$$GS~kkaHw(Sna|E{$iJYAK&v}ofs95<4 zij0tH=#4PZ_KuH`vXMY)*t7t;Z>;Reqrm_(3gqH~4m(UA+Yfn`P1e)!%d=>_5Be(P zrhP#co59auuhU!Crg%4>+NCYhT^gHtJ9fMbqc7@e8uBZne(+-4<(7&{<@ zKkt=Q{ApMP&-7+|KyLzwi)#4+MUn<;&LFqf*~q!DCFN54)SE$vBukw5#6AAwqjR=U z2^Os#=xG^0YohB!i5Jyl5RyFxwjn(eds+bKbdC2Ehb2rX*%um74A_xMPS6>Eo8p0E zzKQhGHr0}rb>6*D5a@@swhbq}1<4KRI>2& z*9c{*_PiKLtbw1t0yt}$S?%mZ5`C)k4UIRydkiJWIW)Q*Y6i}IO=B; zX&+%?E)TtQ)AjdS-`1Dw6cdY@T=@ca?KU=z2Rf7raK9nTn0X8$so=(LAQs?r zvNr{mhGp*<+pj*DjfQ(4;I1(QypHFPh|6TD>|yWRy^;0X6QEfbQHEZfdhaa zV|pQj(`A;ozcNf5%xWvC>fh@F`4cXAdvE%CzqXlAS}p!z?{*A-yKL$#;HXr79n_$5 zmNv9ilj{1o@J>Z@7b}2%e%){i05bZ)cGNAkYj9r#IHu4!h@HH@c41E5etEtl& zUzl!P8_^~ctjvUB|JnlgEEOu9hOZj5E^IhjCZKtkraOznC=Z0L*7Nh|k|4tbf}^e_ z_)4csHO+{{h=$D}XTAmAyU(>$R==1VHxRNH>pU!tNv%bYbH;*=h_ykwND1J+9Hx2{ z0(BZfreJMsBuZN{M5ufrEGquxbM}Fa2+Z*>nd?^$H%BPseL>H8u8I3InWpf;)Nn>R z1~PLN8=g(qYTie26sTv7&-9#Z3!GFF%fQJkZVgf&hzNjLT&JB(XvoHvE#nSi)i&24a5df&bE&Fq5n9T&RVr*dKoq1!%5R2Nb#AMO2kT;t8w8rZ!b9C*qxRA@`g27)O zq;~ZTm4UPD;GRLLHhHbxg`h;`#>^%Lhmju(sv+gL*UZMXV#oRS|oWiXZh z9jGcdqHa>}J=!iOX2m-tnu>g$Iu<#jByI&N%dS7h7VaQ!;V0zoecRw2z>hS2QvIO-lPe5w@hp|5d z)p2lR(`*$wa~Gzf$EuHI!jjIN2!qjcf_h_EuAtD*ZvKki~)fgAbZV zz`BXOcGGtrjG5y)evuBb=y-mK3b9+ew_j^ml$5-w3-_=yl^Rj)xw90b#nQ?cc*G4L zI~uiJx}H@23ofB zX^@Yo(Ej5y?vgEvltRATdHG`%5vKfI?XikH)Gsu?kcQ{kuHjr1nnqmvpB_}lRQS-d znA(YqRz#H9#TFRO#t|j&kG3V*!U1@a9b4Jtnzx(fKFD*9a9x@-sSPBer2VBLFO_vS zR;nN<3JepAr_6fJwFJ8TDSU3uC&iX7B%7J11bFdhfd`n{-(td%?CU5rxCN@#!5h_$ z>!I4lSH+o$g%$<=MgvVNM;~(!{e76}xY{}=1R}xKYl@OB=Qufj0E*5qQIo*v<131S z3{)Hoz9~#4-}6{tu>crgvSVRC{#Exna{!N_-sIJY`&=&NK>G1_VCfHfArJBTe#XQ3 z+r^_|Hu&W*YC%bzJQ`Lr>I40ulRX09fvGz*6j8`)WQ6ZS`3si)ZYhvYKD zi^%w>g3Wc`H0KWUKR;I8oFA!%=*OxW%N2e@pgd#+({84s#Fy3zZ_`jhO1?lt7xe_v z*{Q6OUDntDE&1uC$%A44Zg=9#7)*dh&Nebx=9S!^YI6?DIG=Q<@J54IyPj6K8AlT| zo>;Y0SMXJXo@I32S&9w!UzFt=^Hz%&jt}~@B{@3kxCMfY#-dt$H0!UASs1J&(H&4^ zmA!16C6|o3xzX?(?kqZO!*g-6-432V^8+Sc&vk8}gcDu_Mk%~V$8yI(#zJMMaLUrn z33X6IPKVX_)gP>i2`5p+1n*TX)9Bmb{QYIduX%>4=t83djq37qUrQeB0fQ_vfqjwa zAiJ%Ra9=?Q1VBM*mTlMw=D>qNM0a_Ek}!%b&Cp=|0khX6E3MQ=Si64fW4|ZLO@g8A ziXmrit&jz4NnTuOZAxG4C@rwq$q>xNJG66+qSme{`UD@Bq$!xhpfDiCb$^yxhLWyP!tSwEq^GH^q+@O?Y7{l8%LOh)7kj z(FbZ_*}PnP_80EVbAkD#AW?A$?R}q-_6^}Klw2)CrX{yXs`%JgQ3(|fUSp|*I7W-* zW$>=QGMa|siHvlARSBGV2={te?lpij-Y@A0Y9-Ef5JS{mshE-`Y{*T{um_0b$6XBHaOd$S093y&ytnFs+E`w`s`=E#fSOL z7NKeAe9?oN4-BtHuNgcepqA#t2I+0u(gq)y%MNass#zCw<>(?-Q1aXWi{O0U2p^-p zcu2H!{^j4$7d2v25iP(CEUFzDh0^NxC%k5%+syoi-WKX?-Ku7!$-$GW|7?&o7QqD)B;X`kPr)q{Uy{i8!NLq`n5)(PPCp!FATDC{n*QCNJc=5!bn zO(Hm1Ni)iJ%=z&Z5=8(>A3;42=pEemuU|H~j`tO_w?4>w%3ry@$yja5DCiluU(w-h z1~R~tSQ1K_9;pNEO9O03IsuRspI~nnEbR_%rW~fQ3?9%@eG}KB$~8LNR90+(vSUYU zWf#0IF=PeBVF*x}MGb9Dr)dZ^v$iV{SL-lv6kXH+=Rfy$dr-^?MZ&%C8+b2WO}b7X zmjXwchv7HYy(}CQu%sr^xc5LeB~&6YK(mhH+90X{jiOADmFxaOz{)~3kY3 z#!WcgT`awiH1F~rkX{Epc#m8rI&iMqsw=#b`>5NvVm z$6J!)_66%^1NaNU7nzh44{6mxoD}xf*0W(spIk=-4Ynp>t71|T4WHn7FUq`{h6gIU z^Y-U7uDkO){3)u|v-~-uHBZ~z8MHlC%O*ZP*}?%D4dRy}zCJ=!R*l_P+Ln0dOtFS- zB%JI9h-t08+mz|rlBGZD(B#Mx9V11FSC{^X?w?`gff#=UDt!5M7Q<>CWsj0Xbgq&Q z$DM46xM3io)MZs#h;rfIS1~+SASn-3Di#|f;Wa}I%-mBu5N}@*?OR>A9Dcx+y@W`%WsMJuTeU1#w+)W?2Skvp6MBy3iE!4I(MH=&vf6=c&D3I z#ok8v=8-m&d%QXPTO7y@*U%;oV+s{*M7j%t*;LIRuuk*Ge7k560mvTs&$s%;H8@#B z9F*EKvLQr(?TNn3*!ZGwd61M=mk37(0`at zn@genqG`G7GVDp#66}SOTO%yTnZ6*nZa}UtaPHa{x4PSSCcuskikhA*Ert@XOsCIv zTP&TT1p&qX^{6yC#Bv*UHn#WQY1`CV%`x&V@g-T0XTR1WCXmx1?9aZU`dky;1HdX#+=95^6zLa7 zww3nn3}uM1iL*|D5{(ef!sME_dH|w;)|8^2D#}uh0~nAQUL8CvBGFOC)MK5yBRO#U zJQKs@{_Uf3-b`zx((i-xf+%5&hX?OZ#gEX`$u*8dhsMfNl4*a|(oY9&i>`Wb0Eh= zF<)xQahIwp56DRSLL6al0<0GC;mP>n7fCMOiW1rDMUOH`VC;z49vGnq`?%XXhmeUm%935izjS9j@nYxES<#~qcVNwvEmmDwPB7AkO9%FI?$0Dm6{98`>X6GDx3{ih#V5l{9 z)K(u?vF$;dQ7dX!KaZfvT*y%z79%;a#}K?@oT6@@?}65lx2F1C zB_us$gE5?%j*&eKFZ&s|SrV6!{FuTN*>wJdvP!V)`BEkGnUuc1!5llzpuP>_NoM0E zUt=tETFv0yf&15<|DahHm3iZSY%^$Y0kt9&f9&Zlkao};aK)k!M!aD$@6I`(gmNaA z$0Ut_&I<>BoX*M4j_K7kwN4NuQLhxIDQPL?I#1OtT{x7%(nhBGIORQ(^bT+ zFBxE+(uB59+&J_(5aTQK?%WzyF@T1*p08%!v6MxZ7-K?+&NAQ+aqBhRTf2HRrBS_3 zc4ggim{~lw$@Dd|Cj)nnxFDA3`)+NRyK!kITp=}JxFAhi$Hdgj&znN+4L?{rpg8D} zDIN;KF+dKtMRv@23DHb{skWhyMqvLL+%fZ_Fvk<^KNX6~{2wxZIT)WjFCa zO>|X=?wXVDqYfqI;5S;qLdS{UHmEy&oyv`NyYWcxa4dC-{2pcqfH=)~^o^TkH zBTRoUDM@TF7TZI+b=-ni`?=*$uV;Of7qZq@5hoXq5G8MA04B4NTkp_$0wktJgz|FU zC-cAE6c3KRtH0oBH2KnnU~foKI9c`7Ky|&}C)E-vdw}SYjw3dz1fAE}7QiJ7w$Z3F z@&ibUJf5^*_`JdqxxJF)JeEuAq2)y5)L>vP582b9 zKdCw&9Ze@n&^+Z@xKSSGf6s%`6UO#afu+OKt{2KK9Fo~Cbm$;!bDY8iXSY@QxYq^j z7u}8#%y;)arZe9Z?jPULarpgqm5QWg;uX=B9tWG@`U}tggmr;lH-5B!aU8KiWSSXeJnJ?KH93h_Z)4ubCTlvgVj-O`tHnOi8u7)6#b*rzn~+ z(q_2dqD9r;K~TwlkCP6`TAU`dw*_V@;eCN-SyBrl(wxxe4M7c4f>h zlKeq@aX$|mt%GUss+Z&rmqs4IV3J@OIW#@+(pV%*rFEKi@=d&GdK9<&NpAg( zWBQC~thzIop!g-!Z$W++geDNpQBReSM@HCS9GZnoo-F~qKBXEPO|Y5l=A?^&>k0Fp z+;wx|!_Bc%<&c#uBa%i75ag}V-0G=!HGze5N_*88{EorE=UWHzb-&)nGrg(K7T>23 z4}QauKG6y3V&9L3d`!&?1J5>*D3(n5kl85D&Yilq8WXpV_-eQei!N2yYN7{a0$z<* z1541fcrDXGmjcVjcR0(i(RmrS!H!W|-Zx%(yAI28j?vBC#glIo@6vrrbjpZq zu+HvT^1g3(ZH?rv9&3b2W-Ks8Ha^ReNVuxY8yLONaYeYwn}in`c;Zs4jqt;MmERvv zn8S=-GX-a^mZWE?Rz)Vtq&r?YF0Prq#!;K>?TtuA9~pfOtlLuu&dz<4W)C}fUk_=L zaN^ReYb@`SIAhOGP<&G*+6OvgAW794qs97d;~XV8x80r(H#Q7gT@8WrTL%(`91y0G zF1a94<}w%72s0fpp{ZVK2e4j%euWk95!Y@Sg9;LOdzp*8u2y{mS;-FgXJw5Y%1vurk(659t_hm~DwJXj8Z4>dD zcv>nWUf42}C#!A=GlDlf7jfn}{d~eS;ANU)z7kl(cHy8qnwLG1c0x+_wc%+-dxE^G z7mM+jZ0c~%tr&zT-+>>SrDc0Az}st_pyos{xNd)$q$4Gx&AX*&J6q~cE^A}Gp#

K{j@CJsaWOF zAy^1f|ND=B7a36h8d+TChZasYc0;!w6qcRS-U_C%6Q*e-NYp*4E`~2 zIx}8QV=14-Jd;yrH2Ex#96HK*=sIS4`cp*$`&;Pvh`&JP-{!iBDxu4ssPnVe43`sf z+p>VmYLNCwx~dlUelRmTr7$Km2nE=^ys^#Eh-^+9$H`%*|KjT}?;haT-95_jz*ORK zOI*YDVz-9&$Y;cQNBsW!3h||a2SUK=m!D{;Je0x0K(jsqD)3Z6263wmwm{|*h)gSj zZZAT%qTuBudIMtrHxfk~t?cq*8Ow!-hM4F~yJ0GcfyeMZLAy3It#t05v-vOt_xBZK zD!C47b;z_!AvEQ0y1=8Wh-iND8!JPNtik<&lA8(X@F4PgebkjTC;yP_Mik-ut5%OJ z+}nABOLilNt8Rp$I;6{8dhBR;zROm<#q-LFv!f5(S#gJESnV-O{wCJ{@N`rqhZU(G z+beWhaZvd+RUaQt*w0lSRxsj}V2J3Z}RSdq%2Lq+y zQtVMxSt_d0DcK2{HZ3gjUs`JyT?EQ=2DS7PeK4kp5r`a=nm6KP=0jMFi8Yv7nwM>Y z?;sM67~NWOD>SPe`3!QM#YpHFBWwk5V?!)u&xH$9^%=UZ;ZQlQ2erQjxrw5SK}`7A z@`(veY%6K19Qk=05>~*$(u>L8E(j2s2Io_wTDJ2UPSJSe2wuWumg447`@7% z3iAZl%P$={H1HoS)kQ!H4Ra>O;@v}yqbBb42qdE6=5u|H70tIX=-3AWR%sO{Ea8)y z3;?PaTBf2zab3>!<-c#tGCRnlFhzbMvH?}f9J0vNqdn&Dz6k+D?4xe`nXbW1t70>O zD(T_Br5W0c{CEtL+k(d%Sn6nV|@vd z`j(XFvO`cs?b>apNvtP-U^J-aJoBfO-9#tod+d&O{Ge21f-pXHe?>Ke1gnJAQehc* z3NK#(UWij{BEKB3n^R&VaLsK}2UPchO<6b|h%)vO^$&b=@nJvI!ZQxH2S@jucW36H z(dw(5LN*jOWe6c%yW0ZRZ^A5|J{`5TA>Um{uZ-8|CEd}K4kWP#;f}YN15iix<^I%T zdZE%8XjCzXcp>!VW3!efHefO&X~S=&g^n}# z704H}SQfOBrXO*pH}AqZKb$U)Fq1tI7x80`slV@$*@@dGWjfJfY;3PhFds*-G_ek` zlJP9k+HJE7l3t=F(p;K<;^nSN>+$4TiWVWJHsc>T~-lu3|a1FeF zd~g~Vh{vEC!;h>-G?UDvTgF%as0rA;fK&G&sRSsvhQXu3#Xleu;N#V&400)6UU3au zrN9w~Hl@5>(f2)4xAzOvdoC2=b~}WXdYhYp=>j9Dn+&X3)jx{}XD%pSK4krL&1B+A z@#?JR3?YF73*{(g@o!N`ha1HZwy;v?TqX0--w5FIl{`ov%103jH8uW^F=Pn_UhB<; zBx>H|^JPND&NWp4-QEkt#)9 zReeoAC*>La2YlEFg%*8n#^$o#7xfPaY6DY`Mk`i>w)4>~;-uiTTTG?yIY%^Yio3@c z&i9rqJoWwwiWf`rk2B~Hu%-_jQ&+69V4sc+VD|%a!}dIhV1d0q0o?Rs23Iif4vRZ{ z1n{;?6Q(fENn#$OOjS4>f%P{>7#>UglU~k8w*=dTSa8Njfx%RHef2f=G z>nzY zx(Nt3a>bN*d>%h|(Z_B58rciV=}pfXA-ikN+j6o$!B!c4?*qBfd2!l9<%pNME#y#4 z*bv=QCEJ?Zq%IZ3PxtC>zHD*jB#Z3@Nyp?&mvy8y=56_nkjmvK+%A}9rOYrY?z)Wn z*XDe#6vVGPS{_Fa*Va*CsZyH|gC$D|w(bzvElQ@>Oy%CDOxu`PqciJm&=~(2g`~k1 z|8|JNlV;vN6~FsqJ7-&5h@d-Q z#dI(@8CV%*tXZ0@)B(azD|hy#gRmEJcT>T+P3SX)kMAcATt{6U{i|`l?M`G3=i9ub zgLh7wp77#MN~b3+EfWNcD$OtnCYV^R)fGNG_y`5?p~k-I1)<@@VMuTVvR~=2%b|)T zj*1BfuIy-2qwpran^Kfq_XkQoqvU>F^g1A{DdkaY=*e}?-$06Pw1Kwiky({v)tDne z9}u-OIc<$`n0`V+(fQX;J=VUSO_Wadhw7#(O7+ic{Z>;_O_Qg0^PI!jvz=5Cu=J0K z`T*i5_=_3ef}=rgbh0qz;?TLy$pxzYzaYCY`t41-RlD*MwJxX*P96UQ(u-{-=7NJl z>#ulE6Sb*cWyEg(cHcmA%1NtSK!FP)Nw7e^znT?^g!%#H$jQX6_Qp5LP?kV)X2FdU z#hflHK-VMQ$ypa?hV5~}Y)WD6&U2Mqu&n=tp2VibEK^(4`bS}Ds-sw5W?|$Wz<{VG z4~ktX+-is|o!H~hITtZT+(0Z7P@Aad7IY?dqj@6+s3KXE_T12vAe@C_ld^_cWfRn(KBJ{k9Y34E5b*t<2}n(vEcOovzA(ja+8Zofc0<-TYDkw-Qpte&TiMnqjG09b02 ztH1ovmGY0%^vxl2X0kPEkz6`P&cfTvcZmcCRO&D-Dx=r9Y1fDL&H|TboBdmTky>Qf zGIhK%>CcaO8}`9qs}5fS$@Lg@)2%HYbD2WPSZ!GRw-{yxUtEeGW8ELs)pR^$a|K#;+XsJ$Y*iHIS}rA8vizXXSq zmjW)S%uCtq-YD8|t0DY@YigO?3NXL~?vY6z6wdGQjOc<#r^Ro^} zHk;2Q+8iPVGV}_%!E)=Ss?Ky|gJ0JdL0R%F!1jYLX!5V$mEs(RyIbF!0O|DMs%q+( z$QrpP2fDhhZj_~9ruir&RKA;hcpcC!2_&Xg9YZFOWxR_hIg*PS)qY?!l3NIw@|}dq z@gXeT1a{pA$9_E0Wa;FF$I|*9SsI+7H7IAI(IsBgq2J7)a>~+gTWTCLYBh2uwTeiX zQUO*aeSB6dj`drn_k+)GF^PGdxJ70)GmLv^#}TD^4za`Z;gyaov-W0_ucik^dH2Xa z-7V0VYi@rP?Mj#_Zt#2c8>ci#FA(UMu3G%t%FUgT)*ljB`(XBk<+!>mh!wyr&4b;- zF2dyDmptiLpoa4+@utWcXCK(#-4Khf{5rjejH8lu4=m!4#_F(%WCL9Wku41fiDoP< zE}S3Wox`3y-_l)kDmZU|ZD2F>efY+OoWt63m~~J^xat^{k{@ub)AMv3bs969iH>Oz zQ>_yYDbb(LMYfzsSei^rb(=aC*&|+n(k0~y{?w9AU>j}DMDBLrc4WI7Pw1>9oun4We%33r6u~7+$v%e5f ztKX;2X}3z)H^Tw4YaJYxGtVQEoq!5;R(W9+7sZO#Y?xpN} za(9~O?!UN;dIofoCict*)7RBUsE+hg6X(zp-U-QTh2v9Dw6NU!V_?J$X}XTyyYqLk zLy&CIT+~z`#UH{puNqRUmo7{9mgYrzHm8yH2+ZE=K6f`rMbIsNWh>WR(ZM{JxaAAJ zz4@(gun@m@_(yKaR4HzhlAh~Eim9P(m2UTNs3|HOHR7Zt| zQj7cg^~Qqr(Y|32Hy&H}b_$WVHJ9h?EYzqoqMv|_kgQ_s2VdTA>O#KCV{C%0NFS`D5i=O>mFKicLAKt!tg}1e26(R+2@SJW}p zAR+XS&GHA~NCB7on2JxCn;xU>k0Hpl_r++o%(-KSt`9<<$um*#W2zF#6pM4G`2gL@ zl2r4Nq(WgZpA8l}EFguCkP5+O#5rCH^`fsOk6WBO088i20z7swp8-&Yv1>b%eoYmm z*qF@ZzusmInk=g>g-e>#2cXMY?h?CjcZD*^6YLRl^17_8HX%>L&`9;KB7I(!Ks0Q4 z$m|*hufu!D+Q~YGXv!zw&8lxn`NOYnzSEI^bPu@*4)4Xphr!%YqQ*wY+A?=rt9F|4 ziT{Y_h@2Um* zr=0+4olewepCEi{Op_rghj%RlQOEU^{lU&6p7==UMypgSh0p(-)W)cnDy#W4LUXUK zCE`8Fm&<&dTvLlEVVv!Xs|W=Vu4V`H8HrlKkycpa%YDmM zZi*2ksS_$f6|eE|?*jCxLM=jHh$Lm0^Pu@Zdcd{6>lXQ4tC7n?pr0_>9bnylgcuE= zH*TfJCAO{~Ba=tVomA%p4lgQ6;tTCVt8h7WEPH!Vi^GW+fG=@ScqH3D6v!esmiXx+iY1@!-snqhW7wKpU1}$Wo5Wg8Dd?II*&{iK zvlf6KN)=O6_w9Qve-(^{>pIW*N%g=s1hj8-8#m{t&ptWFU7EvJp>>n3=^O<0`I0*U zCl7-#AatSvzK}5;2$&_1Gbu7m2d#C#>A*Wlpy(v?^6(f=7`>fwjGs6Nm$y=C#Dt)O z{Qyn;P@`)LpIf+z295eDNLZ)b@x&c90dEYL5b#I?vy@OYE*J5*aXkvFs;+Y{MxMqK!8x2yK6e4 z>!VT!E9stUdh9@ZA2$&kHnK%M!U|@?-3K1Yh1i8AsjfbQdX!H8a3cEiwg+!!t5$#W zSDX-19$f!_?%Ig+B^|h4YEV4$R!mooBS6tr;fEw#Sc_L@0KV}PAASYs?;ex9Of?Kj zCsE~prY+;7a1)Bza zg-jz}(q_j6$f`~ThB%bu_QV9~S_bDA6&((_)VIq=4D53P?PB$z1^);rSP!|n@BOZ@ zWosm9Ws%&-nE}L-ypf3ChmfTdspiHBAWfvlu|914LZ|K;1j*SCDE)QZ(1~dCk5|%4 z{;cez@i8d%!uCJsWYCgGo3%>qmO7sd-XadB^U>1i!uGEB-ayIg`Pe;g`ZJsg>oN=g zk};B%amtA8T(yi_&!z9qL zDdS+PmLRGMH92^Y29y3pCR!b@zpSTf(}9(Lg~M>NurSFE`FUL0f1am4tdTsoRT+I< z`?x$oU@>+0FQFx1%{ZBZ(ONN=40U}W6*md*NF_wxh5@Zceqwhx5OZPm6y_-xdxn}( zI;h^#ZRZ80sg{WZO;&=;>>Xr@B1!4Jeqxja@3w%Vtqe_~=*~SZ$ z?$6%$5^Wu;ribB#euK0X=l6R4-QABY)>*U1_WvblC76%P7d<3 zY4)!CdBDVubv7kTGND2!wP9l^nu;3&#Qg1XGWNYKcMZfZa|4**W1V9xj*^nd&&nb( z6v^fwBv&FDx_q13kw`;obJBKaiA~q@3swP3Sn*d$MEbk|kNs3UQGB~4xd{y856vb( zU*p;lWt1j)=yiOcNT+sUKs*%+Iz5CR2fG2nVr&W(I{@ho^S097Y9-YQL-g?xB!qf# zA_gHJNk_ogo=31x-U~TU(pPm4_o(9zi;K(;l%Xh2%6R0f;QF2Yxzo;3kEb-ZUb*}f z2fEFPYWz$r6D!jdjZ%#U4l>}e19vMEwIX&gX9 z!XMC8sN(caxn#kJ+U*&Z1$4SE%-R-nX%c1}l-pC) z2rk1PobG$oPz-K1L>QSPL+iSCYLZrpv9o$oA6#3HuVP91!RQQV-uAt4Gvt$c^{#0I zO_9=93}TE2l-vaAKrHXl1_z=Jqhg(YCvC(Bzxu8jZ7pYhW+0uZ3dP_YPLcu~^^$r@ zOH$RyK-6%;`#4M#Q%f)O)HRvDT8@Hv7z%k=h21FeW=U$oL_7Uhn&Y(4IK z>akad?vy+U!5yOD8)X#1w21BB&Aj;mVT2C7Tgc+amVrozsYt#n73XSg3o?j1wTT{~ z!J7m9>HUwd7F@kZ$0;Qxm0JpO6J1}~zSNl}gz9m~E!`DJ3*)jowQ@%^+=x)TmWh4l z-~%n-V5DgSPt6l#ARN9Wu+h<`qU!SBi@vJ#*2(Z-G#J24%>oL{wY=WOUBT-5w7aFe z+63gj(zgA9**TfrEFr!wHmbLm_;}sFuNA>b%i|1V$EqD;Ypztv*9g#_=SVlhk5h<7 zx7O`JjrAhf*rv+soEwv!++>An8^Fi>Cc=yUdyF_#-!QK9Q1idPq_UyxmKwl*EzGyk!S2~K4s)+nF$q6$*eH^dlW z$w#FhF-g3z2(1Hnq?vvu^s4$9tKF@^OS=nR9RExPAqJQ`qoMMqA}*LFBQD8zxnkAT zcd(}Q`f1b!Vp4RE$I=Lmz-cKxZSkQ7JD~7yW8-u3`=`lINV%D3K+<+ft<(y-AsZm8 zuDkd0i8^uH8QA`5Z@%B>2)ar7PM11xn6sYf8Q|v&`UcJC5cj?2Dg&yx33$tJlrTQP*{4|TH=BcFe& zVKg|SsP6Xb&QY?C1L|4x9H&ML0HAZ+Sp0f4Sr z=+zK8?v&ZbNhACXJ16-}+%vom?m$7gCnmZ`%9La>N|6}^1kf=r3Sz$)w z$z{?(>{5t*cV4L{H60lgUq&meyp`0m+$(7K5V{74c#arFIZDP^4~}={uL!-A-W2y{g- z2iZLS_e83mR%Cl~q<^hT9u@p(ZPDbd)K`_F34u&T-8OVGo~R68ABM6nvBS#`Q&lBH z;vktz1|R&`p*S6zWxiyS$93ZFl|j2`kEgi7ptW0njVo&RcrHw1e83XLC_I;6NjyAy z@jAgPO2uK!AWqz`CIRXnzyH8Y+9JpvCjaA^GCTCcG#F#KhukdDfEj<3RUm8gxPa8xE@g@y!$E zZOHKwR`1h#5mrS%6B;N5*&kPHv+%u~1`zY%T(-thAYFkXHxhc(cO*j6hAWhQq!~tc z++RW7ovuWKcL)T=T1HXE;;V@7O(J1ZkUtgz$oyEgt#?%OcOh&W7*%L>E)zzY=ss>{ z?)G@~^S1jP6>xf&tU}YgiF3fsc*IX>+y7!)az0A{TQhvZ8f6F1(SUS+mFp^w35Scr zO*~tcE}oGp2|7c~H{hW!8NHjZD=mtxN|lyQs&_`Oyw8&%$*)31cA?&?M*oLV?Xt%C!ybd!h;JqK-Ir$s~9D_qa%w6Gy(v*{>@`_{CT{F*!A zV^QC!_k0=UTK4Gnhp|j29gX;kABQpdtx>&dG_c7Q| z46$CH!zwLj6+|ShJNH>SsJ9+;{g#6B81t{%B`Ov+yQ>JF8KW(0??2R7(d2n42c=90ABmPKH4xbU*~E zk#?B;!$MzTiIRfa`=M|dpR+#JxaTk9xitKj*hXqulyOA90Y9KG1xw`8lk7iVI;_;r z0j5lIyp15B>TI4H-n;2%P(D`hmnff~QO=MO+-hvRgckNB8b&M3dhX$V`2qqHKSXP* zRvxZO#O9e>=L;2VIsawFwoggG|K;;*KSc3ZKo0@8uZIiS32vpZoR-8I*@az$B`#2- zoj9c9>1R$|ZnGJh#Tdyw_4b=(5AsW3>Ts!YK#||s)~ytpqmBUf*@rQ>7HDOTWVVi` z&|x*B{=euQLo0#p3i0Pa*6%K;gY)6ky6z|>m;(pwZ%)Wl_-b7Jv7PpJdkVZWd$sLS z9>GSs9N_9;VNnZQJ)TH>QnH7|VD)5gPPm#A66e|aM&`1f7Mc*@H%U2p`a%UAfCohr zGDpt9wSCQOL);+E#`HZapq-RL`n^)t43#h{5kk#))bM1kJTKLA5f>`d#)LcwsaeO9 z?V}%P@K+zmq*q4t^h1ZZ`8_fy5hkZuw#$V(=W6BIGy`#l8`n+~nDQsDoiL^Jsbvx^ zHqv9QyN)(k?L5T0Ih|xhX~4Z#Yw?ZrNG~o0IkQWYfaH?%!;YflLB$yru=7N$wlPcE zR{H$$!Ce!*pQg%~s@tLO#C2eslkOhgm|j6cdcgtm$>S!}^LC70kV&7tTn>#h7JYF^Kut*LwL%ko7RmfX7KsQd zu)%P;3J7wzE-p}5ZhNmSt5ye@Fi_0TlpZ}^FGON3$yOo?yJ$0>4a7alEXZ%K#lca& zGR3yKBZ_I+n_AlE2SSZhj^X&!RYn-zcw+8_Lz4Uw=??HCo6Mwpk(p2|XL|kU)N6X; zbdJ40ivt|ce76}?m^MOt7EAKwEs!wnUn~w5FY+-);Rwk`^l*3bsyR4#<%zKXCMbb| z)(=KNxZ33D5B6-sE);Y-3Has4D_|N5VbGi9r(VpyT>js|ylx{iHVy>Tx2#PraZNX= z5R1`$4hBqxeV+(uA`oQj0X$81Q2wBTja&pLYbuLO)Ok^@o?s?{OO8Gi;Oy`Y((5Ax zP-%fab(x!s3vU8fn1PMNfqNJr<>P@| zM~yG?bQkLWXk-8`J>Qy?ZSArx{k-`tG*K3q|6}gTKJna|yjIjd+4>wkiB{_JxMktS zA3-iT13kwo&}-o!iU|GVfv4T|>Ogl`ldAt1V9%FO42%U+>L#STt_+}>SlYmYQ9#;l*gHe@Ud5jr{2 z^AwoW;LiQ{Zo12kV(Kcv(D+h(vgcxS$tHBP_mEPR#ZpH^4BA2a-&uJfXbR^QpHRlE z)_cR4AK=1tzI^{$D*BYEz+jUx#t|*ZHK!nD;6dE*M%!3P?P1C`13J<4$dt?ntMFDU za*G3&nz81m9V_E3q;0|w72CsV^ZSwS==FQP%@j*Im?pR|Ppm?`w-W>Xi}ny{Pth zof&DCJq@r7Kl^j%pbjPsfW``ikOoOv5~M--9I(cY=%uK>_+vxjeHwUS0zT;Qs6UAKC2iV z;>~v@5^Hjo`DxB4Y2yt&#J!n9GP!OGC~mEa?=0?iC7>{PiSv4BGk7X4WViCI8wOEi zo)(KiMD~eSi8^zRxF$Dh3m@l?#+)_HAPhhg0L+0##Uv5*kg{O( zGx=UowXB>(=-su!K&d(j>b4amyCpQ$2KMjs0L$5aksX$#93@N#K)nkyzRu+)zKJ-N zKR$9O{CTSiU)x$gx79Hfu!{B>e@4X~qSOZsaQSF z3Nsu7R&UO)tpUt1H(JHwWE0=&_b$>>od6*wgBTvoG5qrdeEI63lQ!6I)jjtZRMt6# zeRMbDl1;cxqvR=ly2FHj6BAh0OP+CYx~QjDS=2B5V+wa~#C33!ifhmNJp`t$ zfaXQ2ZtX!W$YtBre_1CNp@qHsSpCgd_CFPW;!<;^Kp!eZy|#p_6V+u$PjV;+PMnmC z2HgnomOnB10>FF|)cs>in=l$!sQj zAV&tnFhag{6!LNr@7_}hDncC0H*U<7**Bwc_kB5}%M9A(oc_u5^X)VJ3p8-Aaq}ax zX`s5~@Q5Q^2dp^YvU9+VuAIfmK6f?YR z-|i4JmE^=(;gkw-Qjwg}KLxdAkSU0beP4v6=BtUU+lH~3)rZ2G){Y`yn=kqu_prB= z!CQUInQ2>2QkyG{btoIz8BYpcS%ZgCFeV)iT^gTJ#e*tB{iqM@Vz6W>j3*L_VB`^> zHpz>RR`(F%{Ty=ZGd9vjMf`z;yx*T{6+GDFD@c6X!6KvfqHY&D)EYBr>y>6lJ6<+U zu?d~ZnfJo6vcjaZKdrk<;cmO&D`c@*ip7BABPQEYH@Kwc%iv~mlbT2aJwA$X*H7yV zKsI+TZ_JrkBcVC}u#T;~d(iH-9Wh_149VmN0=lLNKw~V%s>lBnc)gi|u7^=ugoK(D z?YYfICIhN_fa0vZdouJ@jN8Eu5wT^Tj9PKg$oV*K76z_>7NW|L+3dDv`HE2t9s&{b zAq&}zYc+XTo#E;KDXCP#v;Lkq6?rFyfOY^tkfZJA(I9-6V}T9L46S-;{XwfWtEN9XLAhry~hf7Zrd7~xCu@7eOsg1kyPlpmH1 z-YS^4LfWGLn_x5tnTi=KY;-V(Usuq5`NL#G;JE_dMQ>~q?|^h?%)7SMKy|m zSu1MlKiSZXBdb;={JUuR*N<=(WH0lgf13O9?qKUUgfVw$>S`O9ApU2xC(j|)_kwteq2uG#9Q-@PBOQ+Ptp8A`DbVOUV zVl!?b@=U-Eg}x8BwS>l2Z(#tTA26=0iqMQi_G7Kg+eJ6j>tKUKd1rC2ZaIlw8QUaT`CBvTJ$Nt_%3zeBn!DibDhx(unGbt#vZ+-9K zqjTD5GvDirCOpNAS^rlTtbNn4*0Q)O`n^!G4|(YL>aC0BkEqxHD+G_6lw{v%B#?n) zLz^ONi=0u_^+eI*^POD@P3!{{&*Mww=g!~%7^WWr*fuliB%Uz?sQ}esUN$7_S#T5{? zaDLBDsOclApfg?Oi-Yj_8G@?qq1LfsiovmdhMtD(UB|#49&*6GznNgq42<_c1)QIR z2l~-)=&b01;lwh&9WBqT{&?x=uEAg6PdYrEYD_B>-3mM8-}uD7_-RiG=E`z;b9WBC zxof(OvhdYZuRFW}QM@FtrKK^r?$w?Nmpf!zUI0^^gM)RuD1+Hfq`{ql<^J9(yYt@`zu_ zMgpjVj0UM^1*QV#KJva{S)m`7X|Pxz*?GeMVM6T^!Au4n$|It6rL_JUmlgWq~A83_46@7CCZHNJg=AG`k@J9RD`41im0wD6P)6#Ltp(r-}g?x3o~&d;sK0RT`C1ZZC7p zvF!l!Qa3msM(ysjYzavvq)rT=2R{YzXP3R=OE*$HPbd4FA$w%t9X86u=(fTL*6Cekq z!iA5_B9{(^3>Am>vFL#sm4qpkKVz3t-$A3I+yN~$>ghe=wRMu3U3*^2JJwohN9r)J zS?|qi#S3rOIT!sXj)DMy*jEc0QgK;osMB}6$9k2GO2a=vf?PLX*Y0AzX$e*{>JY$~ z1?O;W#AzTfR;_W0i@32&~lV$-9Y zWC104QR{vsm9#K{bjs$DSL$P%?s%dJ!GsO0VZ>Eu}vlx2Cv>2F$G222WadB z8!soWLww@aF_i04sS)&l#z|Aw?IYW#xXWk{{097b>I5nFAokuhrsv;MqF;V zzz}oUeZB$6s=bZwQozA+{mC%opIiQqbR%nlj|fQD_4Ver!|of}jREf%B7%Bm2w<6b zk3rIts8DAjr8f1a5Y}PgZ`yD2y=oS2X+ZK(5)7{QKh18e%_EwPqZ=W&5kTVpm2mTm z4>`&@9WEGd=R&AXu(#45Wu6YJ=g#U3skIYx$3rtqjmXo34 zwdYMu1`l2SF4R%JW7pQ4SR{696JTusJwU?0U;g^n2kto2Q=U`^5e!Rcio-M;c;*#* zP7k+$W<<%sxWQXdaSIB4CiXJ zdO(n20M2o8%$MB%$g9kc(GZ-4ChV1ABL!1rQ2QRd2Y4>rE9}}5yj5n5aGyMNP#nAt zdJ>0Vxm^&P);L#bw_MQb65OGZEA5oO$HA%&Bl_loJgS(Uiu##$4$ref<(YUP2ZH!| zSZ2)T6&?Rst6zehp9c()0q>}Q$5F(bT4sMR(*d6|F1hBqdD&1&l$MxpDMKmfQatZc zqntumDf(aX&O|>xx*8eTezA!2j2kq~6@2_R=2o$~%5ghK3q35`JOu*Js*8ym8xD)Dx>l^wu3R0-WEdzHfy@Hf7Mbo+nSs*TeLo#oLgO zUjzB3uz?h7#ACVhm!(|+AE5?^>N!0h0tOvc1$HzCx`1%N6E|NjxZ5d4b(LEv{4*51 z!{$ER!ObYPrJs*_I2E7AYI(p;sWQfQvwwBqwCU$k^lo^@-3UzLwgaIM|& zav_HDWBj`Muz~sP+1#QF@i4WQT8Bk?6^}aYRKQq%-m$QWSu;Rz%fb19DyLeh2!|_} z!62OlFYCy}^QSgM{@F!e`!K9Z0~Ehjhd?125i)p=P+$H!qjXvN->y~i#I zOo~v!^54yoMq^c5a!NHqv@3MZ`cbO@a}g*mG;OVai4G;5`^SPGn*E^EQ{Q=Gh4Mso z+S@v~{+|v^ooL;HO0*Ys+pu_yAQI-@QCfm)E6rHb;OYU~O~m6b`Bx=lN1+PBV)7%(LA+ zQ>{w@-c0w%ixerlH0jPuF3p=i_Y6UBtqT|Q(nn&33i~Yk4`%{_eQZ6)RUK9Rj#FV{ zxw|d&8zkN+GcK>hRckj@E7eIX%J@0X)v z=--#V2h&S}nte@Tyanu2f{mBh-#xdIhjaMo_I7xc_-!{K z&+R8F<@CP0$$1yCY^Q1_Vjg7k1hf|w{#PiHtd*axKp z`@yVoRj)C#{mPM;>?qRv)x?c8ekAILqi8qzzJt5)c)j||6S8RSF4Z}~SAk2dT7qex z7{#NhaH8+KCx2H4eFv(6M758SWd-$l3Yn8;6`|uZd(zLrz(R`+At-F4qc2a;7ll*W zYOO#Ov)jjn8r)@|IfaEz3ZIB{9m&?5tZHaQ!t}MCCp=2bM1i4&59+0RKMd}Mn-y$+ zHIVXntZ`nV2cUEvV1nZZ$x#*=90EjodbFPIcx`;?{vpQY66#6ut1A_N;MEK(icN3x z9$-+QLb<3&mcKNSUBmaKh+Uwf#m4soc@?>MZ5@gk-CsAYC+e+)!vMcI%)VXTysRAl zxxnhL7XPYjHmK4kM+cZ_5QBu9txdmLmlJSc-`Rtp%RSFBqGcZrTsYJ~c^g}=3df)h|0k``l2eI9D3}g)uy9!2( z7Tv&Rdhjv9^_~R%w2zHDMDa@^^7SXKaBh3HrJE%0XK)4g;n!yv!*0)%S_z!)AgpMOm zs(mbD2}kQ5W+!cj^LYAmejyCpkUqp~eZCb}0=EvXaj()GIp5i3Z`gQU3q=VF>W|TH zE*w423l#g%Sdskc!tmS>DngSiafgs|&#;Izd8e$(VG^Zm3#$bFDOb$027?7LGWMjZ zdb~fF&%X;`>LEd2zs0Nd1dX%IlHA2+p!(rkEw(U6$@;d#1Ms)evDcZq?gysbkj}pk z>dTjcxUrn)FrJ};>^Khixx!uSO^}>~GxIQ>_T+3}7y>hi02kF!9!ikG9RQB+KKkJN zOAaY{NDu1@FjamBlWn-2uG84QX%erE~k%~}c6w4?nDK6)>@87&D zMV#fB$_S{Ln_tTGz`G3(UHaXqFa@DTnP{C8HiNf#IQ zaMqZ&8Wu)>o9P(&eJ_qb87X7}HpoBdEcQ4xM$93iPLl?iYX@Je!l8O)L@0UyR36de zxTyQZJLR70PYQv4KEUrt@fnf9AXUB+!&){N5sW(*P-{eNU+H+FTOI4o;!t+mk615` zG#}HY6Az`fZ1^FO=sMC^m)cix-;Lw!q)@QIY(DRR~oYV{fagMN@R}V9RJkDm(qN&%Gr!}xB(8B zjl7|R&Xk%xOnbdQ3B9%lW9aE~RF)+4fC6i6u1? z?oej$B;jdE&sjBenmdXyq zcdv8B!jXhe)hbkO&h6{sSabu@<0ISa3jOlqifp?uL>9E9r~1}`0WS5_h#56rxl9HD zto#|1Q8p-3NFXNy-J;_r+Chx9-X%eon=8?PFfHTDCd9^m`3a-aX{GVz0M54ouJc1>*oJJjn`N%d^TO`(}zF765 zr#tsryVsF#2IVYEpyJVt{eg=LPbjea5>Mp z+B8HHRG3ss^%to*ctW`SRxbeJf3^Q6BG1~CT+@{K>5jRf-W3z=MxK)&v}YIXonyu_@xIp%Fa$Xse5+#+yEy z;s|tUkw+>FWIO@F(Idy@U}y)DX;38C#}S$&S3tAs-z1z;G{Z>mxO#i5GzC;HSs6nA zRef3Y);{NiR@O0Z@9Fyk5!z&W>wd<3c$Lvl0{+56Yv>9j>9fR_&FHM1`J}_2ZOlN+5w|C@rGVvPH_|AOBB>d1R zOa;s?|6>e|5v=I=rqsvtLHfk@?GwD6O4Dk3U(}7ATQ?_eJZj}tJ-`pOEV6+M&IUtm z2cK4Edl_B!x-{}9Qj5Wz?CX{|!^})A_T%IP30vv4y=rg+zp%Rf=B&TtT+=WG7{MVh z3A-bm@=e?YQo2ocI!BN+!@Tac^#>0Y+~TVqOiL2Auk~EY`ymVl)LNtlb^1{q6U})# zf`g}I0jGRGq~fIVxR7}!nAGf2BBFattfga)_XEszu-Umq#5c+&lDC|C1^l05_ARf4 zU~*4ic_GuniLbmFLcEx?u*yKy|B5oUGUB1Zbv5K(zl&$d481-?cqq2WdRJrDUWrVupXFCA5dDg!1o zaPNnKr*)?4L6Gg@a4EH~eR!x9$gFFtg>S*BJ&$=v8^Z}%TiJU?bX+UUwR3N9atIuf zH?O3(&xmxvi>N(*3<&RLB#r|H6y#r1TrG${tt827((IiiM3=C6-?D%Y^5m$KOyF6j zEoacg^8R}I?twx8cCq

}4G=i9m4Y1V9^84$Xf5{VI@)M`Q5-UFO6h-ZBW1s_~Z z+>pFOF5P(liY=3(CmX)Mt!oyOETY|s!04!N$i~LGK=k}B*PGvE#US->xQH4OMOVq> za$toVoi&}eh&IQYoU3^?Y;?l3Fd!pR@)rm5#O8;i^QIl>>&3qxJaHvp(&|2CfdSEQ zzb0outJ3Nc&VMoF(7Ti{j-NJ*ZwAO&dhck zcES=s>No%mo+kI^K8Nl^`z*ADJq_fa(bp|;Vz{W0v^aL4sdX0yRD9BAb^ z0FFA%l(hJoK!1%>-j`FHf7>(A6v}^B*?LR^0@$L2n;vecAmx__Awct{jI*|r=gC?j z$&(uqG8OY{Pd6^o6HdjqBT=6^V}fxGiMDV4#7@}fcJSfyD>AGYz0-#xCzvr(gUI<) zo@?k-KKZ^OT&pq9jA+Sbxx%|y69pQUYo&Oka^DqNXqiFCf3`=OVaM=g22Jn3g<^)> z@|bLtk2%xMT?R>Q<>>B=DJ3_;(Q#w_m17jPuua#5+0^|+k;;H-;LFSXs2_3_btrKi zpP!K9NX_AyU)7wO&GNGy(q(eFER76O*W~4l8i_G9;r#~f&S~77ztbiG)fm0&)LF&I z51$DQ*zl9dQ$bEMhXAeT>-{eH%Ga$QH8?~a+6XzsyRpk6HAmkCDspS``nMLE^nksC zpX)x^Gj3HrR95L$^+BZEy&ga|5QJY=rfXJcgTY~VPyXpq7pMBSyaU2v4;tmdH@vzI z?O!iVrhO3Lr}h#>YIbMP7ckcquUTss_<$hlMbji}LzymZo@@8B^HJ!bsYxDcFhFV# zxOERV@sLrEo=m)$5_Ajyq*m`6$LuB8`SdSZ*w~fTi294C&G3(jQ~$!g;3<0kpIC-frD2wYAyE-$ zwX_p`_VryTWbn}pj0Di=x-z0}iaoj{UP61b&rd*^BWxS=s(EIr6f*%%nwl_mPK;l9 zF)NSi!4$G_m-*q{_S;W)X{6O`zz~Ah3>&1pqVj@p;BnX)Z+BKb@CPNfkbrI=?I zJWp;SIDTVEgg%LG%9{1bVOj*qSrrpS?*MDN9W(Ov5N(EZpgIH=!vM&i9H^s&3k>We z+w32@ukN)qS;cVE##dzmtrmx$aARr>24$8K0GydK8>++>Zf(v^N&3IlUAAvfKeet( z==RLf#0QIoI4jfeg5Vc=KnJc{+3(X2z$(+Ez?lTTG{eFop7pj~93?K&BC}I}KK|j; z)Ex0JC`>KFLN;KJgZe)NaE^6>ur}JNl!4=5n^w~+F&l;JOK>j}phdEKV3X!|_Va1r z4S`ApX`}6FaW4mr)~@CtfUsF`b9ZrPYZ5XCeF<^+dE+tv@Xf$b(mtU*UDB55n3;F> z?3HI_lpxR8U;<9q`Ts^Z{vEwRDqnSrCLlhqCbOo`$_Ax74Gx>i&_9U?`XmwLPE(_n=q0k7YwC6hyj zATkx9(t>s7!)pcD-@@o&EH#24RBc|GDD-?v-~(q#_RF+0x(i90jzv}tpSq^Y%;9JS zDWTu|=*2J%dWM0kN^$zKrOTScNU7lr%waf10!sTaTU>5v9f~^rc9i*;|K)li+6g3F z$1$|$LMn9~kchm4S~#haBdEMNE8di^_dh$3+(w^kmYz&uZR7(5NHU}gnLDVcslGj0 zTDeMcKYfacX97TeDSlPI!2_fkpf?iKWLui}psaYFnPEh+eK!xZ1Cck)kxmnu0BMlI zMj5q7Bd!r5I=tD?|CT11LHXJJU*Y~}{;3nsIYkGOpU#d~j__ZZ zRJ6U%?Vq_c+1*F477mXD8IX>L`x5H12@KTM#xK%NopjJ>S7hKWD*bBM`0*Wk+t^!- zY~tN_<6??_m;`Q%?n+tPdt%hNylzHcgu9t@u!v{|))H>|UC0{N4y*+d#ejMz`Y^!w zKp=cu&P4@@f%mW|}yL53+rqP+_kc*tNC+>EHDW*!V{c1CE}P zqzCqw))-i^J3A6auXq!K(Ggx`V0p99_@lDa$rehO@S$ecyRV!q>Q8@cBq@&Qj=e_> z2zo(h|C#|RMiuH7qtmfVOb^0G=%k&;Djhgmu>}|sG+s3hl*hkqO>ocG8S5ar_Z&n? z|5yKFg@$SqXQV=z8vZe=SBUTsJk=M+Q2j&aCQTX6OqtMG1S^-%aIY}$$FrVWaIxK| zDc?`79l0pNKaxTmrUFkxNRT}6z`Q3n1LUaDuEI> z0+V>8Q-?5)1xeT)FK9m|i+2f1=!nx}bBU6uWuXMQef$RTl?WN*iDji`M^Xn*pNNvi z_Zqj2Q}Gzz2BO&G{qK8vJxV5v=yw!9);jM%_pEEKVJ6+VN1l9!c zGU>F4k&)$^={pK}@$i!Aja-;;dpN5M11`O10{XuSIp)33eFw)F(9V`dI`MIc!W!f| zoZb&U(%3W!4}97BVuCBq>c!U3D3-hyQMH0W+-GVp6)6II3a8uh`ph|#thVZ&I!mXv zZ$#uea%u_a%4U}9IJH*<2uKexNkppWc{*g%xoig!g{3?OKp(1VJU_9HLf}M(>t3GF zh!k|)pC#zACwHuJxw9CC?DDs+#|@tdh*Jm}`Lf$8cafgKa%f*>c9m3a06B3#t*F4lg0NZ@^7#Bp- zgJww0_CEQ3Tmi}@@5kpxyRsLymzHd`at-q$atgHK6DSE5E5T7FN=buC zG%;vIak&x!VV%^o0Qi>mMxg@*9X55hQKePHcHOV??1VtiJ(N*}nX9S^Hi5jW0Qxea zK%YqVK$1FzABtYd)%G@!QB4(K8fS!DVVYKB)t#$$26#UB%Ht^y)k!Z{u`9x^eKBu= zZUNy4XKphDznd*wwMU`x9`b51qXtnTFEpPrj5x+*^FTh^EWASdL#RyJ%OXmlGWb zGOFgL;#uUo*A2t{RGS5CG2hT5Lw;Bnb=6_KzJ~ZO9q`oKY?{)v=@D~Wh3mNOba{w( zNOjkTKX4B00+;w`K2Beu#hIkuhv|86;`n131n16BC$^~(Lry2iH7ji!-NiAm4Sx1I z*;y|9m^Wd9vHWH9{1e^DGg8E|Q_wc$^Q)=7KtN-j*Qwj<1!YrU+k}AM2`YYk|62oC z%k({QvIqCW7`3*cNKW0z?pZOW9n&WO|8q0TyEuLyVzXXK#dN;1@! zoUrAi%Hgu`H*oa<4M8MXzTF^CO#eU`HY{Hqqe`2@QSPRY${LVVz9&D%=Py%B__V6& zs_8s@1N(b7SLv155WJ1X4Fo3pcnJLNBvlGso_S<;_Yxn^mNQW&`gs!Dx`B^WTrIb= z_n)I326)V!G+KaI4lrSVKmN;S*b!&R8+dk_iH>C(s;25Ome1X_Y-42&f$gGUO-Au8 zV=Udf{Nz^=B`}q)TCPrU`rjSlw)LgFwIo2Fjj>riy8y+wdE01vNinvUhGz7x<{yEN zpD-%}d5R6M4&rTV*OZp)17qjXVz8^_jr2& z2`0j+#fWrQxV-DAdZ%g2Y%Ggg#;n4D@(?b=IRf-1OQ~@kXU(&z#g+zlh-N^YzHGX;sb!#2|yBCjzpsZhcl?9 z^y54zv)^%HQa`%B7o)333;{8{X!KHk;12`*@y?4iQ%<5qA4E6I3-(I^B*x*+)QSzHC@!lk|fzLoi{V3 zjLiDM=f6MdAY#f5`}uOS>svHm6c*rbzBz`5BWa!^y7Uf{4TA`8hPQf^jocN^H3+_t z2;JB{PaHzYBEE_BJ4`ySoLFG}h)Ym#pQsyA{Rnyx?~GKHC0s~)X)+e-$v!{u%`XZ` z1;|?qK9(>i6_{+54ol}t-I#wRG3n?jZr)wIIPyq(V@q%T`oyLa86Y7HZ-dxc!$1q7 z8^v6_ilp03D%jQl&?2X47* zZw0b*RFYE)_RmtN9F!Ik;a((iOfSn9`xR-YlJ2BBMZ3r?6=10bVrU;&_(rS{hDUB2 z)ECf)XG+6(9ZSs(HMXWYO=DF9Q(H(h16};$K?Q%U043zfB8%(?T%Zu6lYW{pMxBzX zLxR_2Ee#NwA>2*_55!<|*Ssfb4@HAn%h=03jxCh6M2-cYNhcdNGz>eN`kY;gwJegR=7Gk`&hp2l#`6z;8aR?-vRpOSit65{S`e(|$xn{|dB# zrGlj-HXbt{Z|!M-ujAxd#K@#l{~ahN(^C7~IkafU2lV;OE^doWypicAU#(T!B4ruK zI9Sv?50&%~yK3i_KEJTS#0f7!ECh$J7rUT}FywfgrBbD%B@j#ZE=2@VVr|3A>6F@2 zCE4}Hc49Kwd}LjqP3c*n0mTfFF84soNR26rZUBO~FLLRy0!^7e%)&HiIMk?ed5IR@ zMX*FZ#0|Fpsq_Z_y|47>IbOakv~z;hhZzuF+JHx}wh^ccWBww<$c!YO1s!=c4$XxQ z4}7O;DB~jtF5_iN$O(ZUj4_Ad^R7Pp-nfToYIlr868XKQrIn-ld-miP$D8GVk-pJQ z*4>6-yk-@+N@CzsH@1U5YPb6nG!$(1O{dTQ8kGlTrVAc=7Bl^+sczwOp!tu`jV@H! z%Z_=8s3YGRtGcc(vm-j_*_b_h91W6j1!-rGwgM70CSZ*~30X5x0IV8Y5DHvZFgj-= zWqK3qnsxHSQB%yZ>5IGFql#TNc1h70oaGnQHX-9?w8Mp%Zv?8;7MP`Js%*uDcFqi@ zk!#ki6OT=c>7;{+>n^E@oxxG)#od59TMek$u6+p&CiRFb6saWQoAnL7GG?m(!7wur z!b09L!$9$!e|ax^oWz_^klhbDW~APtZI#615Ceih_`eE~habvMk_KFh++r`{B(O3s zdq6OP!mOT<*dZbGmve~d?h=`YOAbGef>Z$JDrr@?HtZsD~xa? zpVg#X7$~M+RG#NKn;&#c{IgZMzeMAvrIUHJE#IP0jhSDC)Zs-}vU3gR%KD|;FI@DQ z9SYg@1rx}@>rjj(`Wh-W>3oc011C*E-UB)${_g$3ylfo~bP^hy0Mxd9#~(cTHN9e| zAva>^!HuR5w7Z(;|Ji$1jdwj5#LxV2_g(!sX%d8W9)}$vpj~!%a$dKqr^VQ+@l<1` z0X`WhmH>GhbEn$b@gDvmwJu7N5WBl7fWhSQh-RkC^!tbJqHd?Crlf)T<+8T5RjE;R zdC`WmJ_(zNoS$<9t>dcC5S4!7P?SO#p=CPc>ToljuT1c^^>*9y`(R2 z2finuh0cRc*IRDL^mZn*Jw+D;MMWgHpm5PBQ;I^(b$F|Qkz4-GV=6oAAo{yYb*|uT zY+GP*dr?YaUS(!SFV8>8BTq=7DN|o-%p+Gl&c}yL%*8RaO~o)-2P#>f$Q&9y0pbNy zD)_o^o8{*E2iUkNjjv=F`44QSe99tM?J=i=j#GpVg*KiSoUu-Ab~A`Dzt}g@PW!b_ z!KHOGYhqAd?#8kx&@pf9q~WY&L0XDcHr%lHJ7VSCX_%Y??A?O8-!FE3oHJw|4OUuL z$~qT+H&5?4C(WL-1*Ivs-431_D=y>Pa~poRTLW zi`60$a%EzdwQSP@9#28Z7A6@oP=*iDr1qsj;L;kKSsBeZ5tIpDpZ=5-OMZ3>!nzH& z^1;H=fIezN^PgCd!Cy6Gv{ zsV)dB-na(_T3{46L!q$60V9i>ZHnbn5zJ1ZTq%}OhQCrxL3jI5kYbD63<9hC96BU~ zIZGbw2#<`VS7ZS}-sL8sP<5}o5-|4SUs}+_JlkXSG=hqRJy@tt$(@v3gX8(0rPW1@ z%gzxLSEn}OC?}?&>BjZ;%5y-O^81XzxED(fbUhmxu}M{M^AMz-d4=5|cJ~-qM(~!D z_-9Y6WkEZ?<1mX@_|qv4A>FRqGVLW@hJ`9}TL2kzFL$&WUUif53RAOW;t;VHSAVQe z&gBI4sJduS>I;WBhq1CJl8_jJoo58$b#P`tmbu#f8P_I6?0@Y4Q%zDV>7D`7D?GP! z+l9EAL_U6Gvk>fZNKQA-4*i6l$aP{_XJ~856T2sY@N8szF=HyijO<^X{G#_+QTa_G zfm7uf#?b5-m=6pFnpQ1o4W!;o*^HH$v_y$v0-PW7C?dct6rn(BL0Qm?qf2jqlVvcC z?Z};^&2-I>te+PGIpa?xU@-n2hXCbU?4Q=avBF?*jz*Qt2 z!3=o|tyFGJx62-rdk1SY+r{%RIljc2?n{rld7SZH_T_Th2U3>X+^ABoTzKL5)=j;9 zNa53ZhE-{#?>o(5M*oM0&1+CbiC8>pV60W6>EJ%iOf>{ustxt3p$v=Xi<38DU0j+kqTN4SHJaJVKk-iY35Z5&OESPjk!Oj7c zA$W8LNgLP$p84A(qhHLkRP}lm!8094ZWtiQ73b&RBUlyGDZQZnOny${ zen=>g^hz{|`9?$JdpRX5pzWv%$S7Cxb%!b?7Dw~B6a=&CwO`;mSGwuZia%sM+IqtK z-t&F&iULggX|&qy*4CPWh zgb5C_#GpzK`$I)2>@@!DpiVS;Kje_3U9@_{`S2=wXfV+G-!ei}Ku?QR$I$D)JiyIw zpCIscg-#K1^fz?0Kf+@a%JL)eesDjH$EW_>awGgZu8e#YU}|Go(w=g1xX@y;e*(|t zpw4ST%`-PY>Ydr8Ps<7_tkR#YKAL2H)MRe+v7YQ##o#_TBIYei^jQxe?>~Lm+BlE$ z8J8GCh>Y9bJ;(IMcNHrRp_WRu0S>U>x$$x41=72I(8HlTTR1Er3($+1F1NUV@GB!8 zzPy0>=9xir4F@yx&}E#B)qDDcRT6aF#o7aCEEL*AxuUV-d>fx>(r);IfTpx5NpDP9 zmtS;KDA;d@OTiNX$GoD5lA-?hj++IDuS!N5(rSf9ck~#V1 zpN_aajPg`lvhlj|a^+XV<$-i=#&Q5==XoA0-H4w85BT1_AtMUW8jYMEpg;PU;bE!A0eK>7%5%gi)eWmI)ib=&9uxaQ=f-hya?M+a_d3wgzfSp&$z0dl7Ga(gDomltxJlPd(PE}08zj$ zp-KxTcMEv4fL&9Q=km`U!73NLuQorlIC(OK-q%BTSi)k)30Zr+C4ds4otP0olMX2B zq{wC&IurkKe|yXt7pWk&3f3r*6*@sxu_7D*ueJO==9c{Aw;nvnhS1x+bdwHgE;Bj= zE7?G9`>`Cg83_4m^LPQPw7K|Ob%}J_E<^LQY;JX&A9##PVj1T#x@0QZM${6z3n7oy z*Q1#7A)OExW{uEIs+-^=7Y^z1ERTbjrndXm2yXKCm;|Eg3fCUm3h3h8cU%TPLkcxPAcXv&TB=tKt=VZ8489uJ>G-1KgJt_A%G?NJ{Lo3D@11% z+q8SoPXr*~o8`Egh@YOZG(V7B|U%lS_iUD?DAbeDa;W#aFj*}cP!%$du$sDZFDf?h_)iju}m;jSgt zW`~RLeo*X1a*p~aIsPFT9kHV~nbnHH#P3ABMyO06Ms{2JKP$yfp`QgEh-n^E5_kn# zN=6{w){~$1P^w!W{@QxYo$1ug>y&m#gqu+ElTY4XK(gg}F6II$fKTh&f!TkS#e`xs zwEA4 zFQ3T_#m={dM-l0WGH;gJrO-foej#K?-Yi%>+jnzuE+;s8ojEeHqi+Fg-Z+F-YPg=t zUquCSGUBou? z*X?O00%tFl+Nr0O2A*5{b>(TYy8cb*B(6AT+DFr)ctgE>-D<5ut5(t&PxND zT&<1Z3)je;n2&%O4L06o zlm=AURV>W4WR8Q1z9UPC3*br7e(n{;gQE(WEW+|dc2%>n0 zsc1L3l!IPFFT3${tlZQoR*4o==B1$1*#Nv&(F1Q(jSSg-LDLM8EtVXnBk`NVV-~{W zf5UyhdpZTZhb;>5Qj%afG<;P)BvPyiynWT_tS))J%Fi-)%}3DLT+1a75MUQ(ISAbS5^;W3s%r25`E`1p8bbJ1c67lOJPPOF|s3^Z% zfqU1#CVWQ4dSS3I=jM5%CdmU)h_-CH>M5G<(42!x)yLE>mZTAe6K zD-p0WkpY48<);_7uRCqN%nO;k8yxkP*v_uh^+Cu&tM)vji$lY5#GhI7*26GL)PX&0-wickH&von|HE1H3A(AiFen0Jv6cJwA=ZJSi%P2(+5 zYO+i#RYePm0(AZ9??4BRexW34+~aSY5`d{jBtLQyeu{O)gy=l(@fQx<{wHnS-QV16 zR!YPX()OT{i9O9h$qF{}F5W0`=pt#krddvfyEi8wv(0j$sP2B8JLv^vp&=T*#G*Yl zR2ox|vx;G(h#SL<8E+n)I)<$bC)z!=;Clo@#}&$jqw_ z-Up1)*Y9L5eaW11E4M+uCg|tilY94x4e;lbB0m=aH)V?h5dM6Hf>_rP(lOkDzRXn;|3$^Q`APGZXB8(K+; zbf^t{GSGVYSThbOn*O5eApM_sHi@9IwN?mnAbhJmIwOhRZ~8JW#Y3!VC%LtL6GQPs z|GE=;Vzk@&p?GWcUhZHJ%}>4^-v`bI32WVpuyV4lIbqyk263)|@j6ttbwUE#GtSM-3{FG=O0D^bt%+B^0C zyPq4qe5KkJ$I>Sr#79&xGxz$14ubg?fy?q*Te9zh0@N^>7^@wsD;u|>$$O_s~?w_`z3u#UZf3{uM zq3VWSfa8SeZV${pV%_q-S#zu(p9pVQM{B;(`4X+M5{7L}tF8P-RA(0pY7#8Il1`FI zujZ49u_vTqtV;MI zRE}TJgV@UjWtotVMjxR@Mh`hYW-`7dqqn-{gH&W+T`Nx&5?FrsROM}EH~nY96{vhA zq21Eikl80LQuO=+I(4tV?0XUE1ty+Nh!MnGI@m*b$(qK7$9H3rY7+d^9)zI;2~ghF zQT36wX;hk3KdK8l3muUy1*91}pN4!61UEhGz+v?cyj|T|X_>}#yuLHvNn3lrQaWms z<-9Am#A=bHlI1GwOaL6An$$p+q8X$KB{>^qU&$OcY{q@%5l^$nctM76{HPQ}B%Nz- zpNbfgQI4v#kSCGQ6_;C@d19KNt&zjQoDH-vC!xQqt6q^)H-bf8O9fT=PvqWYwH?Vhc$7xt88sfcQE3pHA92mF+>^Cq;lhVns7%qzms@(-(N=1MW z5rkZep+QyL8rH`emu&kDRe+{FfGDIX!e+q2v~uTW7@Sh>>ju*0PBF~-?s{-QbT>HZ zU}QULY?wFMlsF6uI&Wk=gk06y4)YAg4EBO$lJ82?KL+Q%(bv#>7VJQ8gWg07Sv>c+rpSfnmY<)du~nI%Wo~VwC4h3 z3+Op&PJgX#`xyi`YW}6N$EL6C=Gk^c5_KiQPK?8v!DjIiiC#yVcD2)MMDrPU9twid zo1i-9$L~H!>cnz22k`Q|wI|{SP}-ZYj|QC4nAt5@%!{EzK}Y3%=hbL<YBoPAkD;hRp zSCK3HRoxjVP3O^HPA$nO7V7lOw{%J3WQIyNfu=@hc3C($%a&J^P_Vuvr|zgUgA&i5 z?6`C$Tn@i6G-kUxz50&50wi@mAN}>Ukig#l$+87@p>;?QK(#PE(3%sWu2MP?rOxkn zagbS;)X@*KxxL)NkB0@+Kiq(5cIsFkbyzLv#mCle-LJ32({n~SC93g-sU^*K=hc= zB<6*w;n;!_sfB+b6+{Z^nBkHo6V|oMN+hUvi6t zY5gJ?stxGMKUk_&g(9q$#pt}7xvs0_WTv5p^IM0~)-~^+hB#gHOSPr}aZ{rP;JZiA zgOVg#wKk@AN*8RSOToDN=D^APdfD=GQ0#zIZxd;({wqW(%sRVi_|Z%i8kRb#Q^#;x zHi%9miAgm2EJl6AKxh(`^J@i$RKXhAT`d6L@LQ63eT2*jT~zH8r*52;*3k!d?3jN- zg*cvC1*?Nvq7G|wghUb?UJsZdG>z4l@zDjX5Bfln|CvIJLcJm$LJRRM@g#;OtUv_V z4gPd&nV;O>dtDBN%}9Gw>i|bv&s{T6WN?(a&CMv9>iK(O!FjJIJJ1_y?KgDNO9do7 zo9lrMl*Gte-e`BUiTR80>Db{;2lzoBmy>RTm1A%eefoK;Ad4z?Bx0Sr*WZ!4`o#Xf zA_Pm}Cgo2v$VDS9{VDzD%B_{L6SGsNC9c+2fKP7rYo5I0^FHQEiZ1`+!@er+z}YSx zJODNS<@W|?xsd3|V53101_r$Dw0El)Pb$cJpX$RFY85xQl{#T4pe_ki`1|L227Fbr z8;#5CXtjJ|568&c@M+!?gL+J%eRC=jUsHU10GD*eofYJbI)+f?1@BhGBiZyKvVS=~ ztdgpl)9^K}i3Gc=mYD$al>_%ezTiGIgZ>|)7rvMBkzE?@K?j~m;GG+3bN4N2lSenW z^>gZ`tt2y7;~A?6hSI*&&QZC!#0`4E;n&^RVOW>aEY+#Fwuv4s#>J2uAhCNY75&Z$Bg!K=WUTqY zT5gb}=Bi*)*&u>0b{!7xuGr}_`7BkQ{vKvy5i9`I0pT3cZaDnG5(9}Jdcl=7m~&u` zw$9;CZM!A}?+^J6m~iJ0uF{4oE9!xRsf_M`V?#P+0^lw@`^kT;0wB^l)TD=+bJM-+ zTq&p#CP>aH_Wt+d8i+x*$Pty8G%6J{2ceAY9lN08A1gPyconTv-*nZAyt<&7?(=u1 zGEU!gNeY)M2v4u5Z9ta7KyXn=g4uIC!yAQMDfi`RLQ8iP;tOhqDB|2TJXU~eCf3Z# zpp_RD%Iea?KP_$_9JK3YW8**89;xCP_M#YiCG!n0%NGy>A+)_|S5l3?f`Z_84p@stcJW% zLmzeg;1LxgJy0m(=Zk8TO%3aTD1SPX2Uwv$wJtterS#8gD-4J(0D&Rn9j+?$LlYjQ z2LqPAfMl+7+Es95Op60*%%3yfNO-Nadkg^yg4wfh0GR)LXX)S8PVe$ptEV_~#Fw7) zl$(oMi3xdg<>BLXS-CN^$41w%jH;fE3>Z6)Ini?KGNAaO&;?V_M2zL^C(awaLBl>w z9BSegT;Pq9&f{iyTFXz1`a+e!`-3XOMDP7l5^GGGIlmRkE>V!_SGJa)_ST1W?8bX? z?soEiqi2%lq-%5HY!?|gX+#%cMp~8nQJUBG+w(v16a+ndGSfA7;n>Uuvm`pgm9#-~ z8P>8GV4;B=N&#DB-!>DvIPR@9O59n3MGWynt9^J3tuioeIJ`q12LMAryuYn6RLa9h zrGANRyh_fgj|?uVIxi*U3`G76OqB3} zoMRN>uQEqccX2P`GGaaNv`kcv=wg^Uvfj6Hmo;?QI(sZ9a}y;NuK*So#ZJM>T01~QVwL|IVjfF&?)gJuBqdTz2e?^kPz+C_IM# zNcDtqWZ1hQfNOGaWdIDc){3~k!S1C1JcXwCS6~0^FX)<$(NN^M`^^i^7)b5-+Go(c z`!?r_cq^_QVlnWunYgK&OcQ&e1`Z#ZShR*CJA8$><<-?N(WKIxzbX&f!0a_BXv6aq zbLbZF`mYw+q5>+%oF^z2@y$|kqB4?R7f=cRsA!EVPgH^1qO6Uy8bz^ZbHI!|`m_0( zkWn}>fVUOSaxa28-5{6L$}R3>5A$|ZY>UTjkl%aY#=WSxwhn76upRDWyt6p>&9U!dZ}!tg-Fz(QPlG_p&)Rm|Wtkc) zaDIJL(9|NUXGQTRr+c{b2?+4P?dwfq(ALJ4YovS9YW(R=HEx(mwkE#dpJ++|7x|lo zO(2pkzgC~)eTqn`$dQL5TIH=54|{^vRU|WSikKsZssYba$W4=MWL(R;9Tcfk$cQFGC+THp%Tu!p+jeGn)S9oGFmEu74Pu z_YdFCWKY9$-ulFBTDQ6QPTz_d%fy#{f(dr7<#FNR#ul(9Poru?OFdhX$n!s?*amYa z?eASK?N}kxW2WrKOB@YFPpP0o*@4n%gNdFaAPKQT%6qY zo1~DO){8UA8M#4)ZdVtZuMJ?~(5X)D^{L!C*WvUVxGY%%L2J4bN<)ru8s?p<6%MT0 znF8HBC3q~5*y^?T10F?u{6aoMbSSHX%}&q_;aG4KR7#F+=w6owXD5NQ+o-oB4HAl~Asmeu{v^3xm} z9B2sYf=_VHysIZ&_hKcwqUyz;Cv!lg2D!YA{*ZR)TZ8NiF2qTP8qxD1)1~aFPjCQ9 zp-W=e0EHyIjU&M2>DsRa`yXLWhNKHX2AtqgfVH&SveFe7Bo>R#k(tE!;{uv99W9l< z{g>yPg**{M%_@`oxiGG(7!PR!VrE_&e*QmSg0SnH29~Lot2QQEfD^9EJKz&(zM2pE zZLb}+FQ@)dY!*m&S9zF}fdz$?s-1`2KV2bUB}t!5b3Yl3$H%_5nQ+nt_RNMhBcxOw zI6N}91eMe@G=-I_Ak@kry6v?k*c7Bx`S~4q9m6HIaTQkIO!_JaOt7R`MlgS$afv>6 z5S|=8lWz%z>huJZtQdIJQ~RZpDq$_K&lj@RvxO4QtFdWSipLsh|JJR zV=KU4K^%5w=y)OWme-at|Q8KPTS-Xs&%p-Xr^WSK!El2Q`v&F!KJcUx$q{`Qjch&irqbLUc2!GGI3LoYB+doc9=W4OMN@_8b;j7=5coy*H3!SU9lK?k0 zRPtn0WR#)H|8wmoV|(l3j7~SCGHFblqM~~it&mb~uVUnEYCJvJDBD`yqIkI!%^tTw zKjekRM{5T5AMgMoVM7DcNX;A0E{0V5!El(%CC1(sjh}I@w8D}J(&o1azkChu{sX=| ze6OiFZh?-ZnZ-#-yZBh^CC}IK7_wmOapR`6cfavj8l?4ax8JzzIODIE^*QB$o8*ChHe}vWxSf4^NtGXOHv>xHae!U zfM|I(QjdV-sW%&MXw*D%U$VyFcR3frkKTeN)9^!HZMSy6bE-resnYG=QM;=-oZnmw zbg!IPfMzaEi13~^YQc5u8KA0vgfwpJ^#X;x&NxIpq{jn4xPLfH5&HC*=h789+$^@?>VAyJ@LS# zVz8T&JP5;O7~pd#qzliwA~(@V!r{FmRc12kcNOz)q~%28Y6#GJ|~2asY5E|*P& zv0o4^<%ZN2xU>;ngR{Vkh5r3&m`DG4zIGWW1*y`_;pFrm7UbZ%KP!rQtEK6l53;l? zax%g0hyj8BD69D*zo7cOU|iP{SCWj+OboM=_3z| zKlklMM#?8Jh=3{3}sv!;vUnDWO&L1=_!@bth|3{=%rFfEd)VnoDGYbUCd+Yy03 z7X|L-@et%2SBi+Na92L>>T>>wWM+eS7`nX5PA0CCNHJhfs!EuZ*Y(*`DA!ew^^V|W z!|Zmt?P$=8LEKuRhy4nWyTVT0V{nNxjId3H5rOKH(pjlqR37x3c=oY&?hfu~8ll5S z*?M?}sn5p^zPGLE{idz7(iJds?(xKAK9Mr=$W)E7|w?>JuT_9Rtm#_a4 z)Yt$Ohe8e>5=(w5w@^usqH01?vkM*RE7IE1m zDxksrAjtBJ?Re!Pg(UTWgb9Y&GPx4h&Z!(H>-i$uNf}GSAASz^rV^Y-=(u~py}|u5 zy83Gq9~E;n#}04!6)sx}Sb+(;v1eXNIn0_`*&k~N-ocTv-j`e0C_bD*d_e`o|j{b+0psH>eqR8Fj?*@8r<0IYg)?F)j(qNJFAY5uw*X4AuK@sx!3=M}J}y`K_Ci^auc)S* zYhEFA`^fEFLw!@>L%L;f58k^}Bdktx|tc>S60?$Gq1IIs+)63)@b zt=A}1n}59LwzB~>pu^au1?YE5=qvLGmt}yqb+dxT(3n6pE~#ZMIn_pR`>vO`d3R&} z2-F%72k-Gu<=08nj%z1c_d)l9A{#b_So(7pzo8(C6XVS5hxhN)0s|DUIB6TsdXouI z5}uoRV<^k*=bA}wIHfH_S7S^Sq)`EoT;=F091pyS&O+Hv88Em8NNt>qS|$-zy`SkX z$9^CZ+1e1;Ag^~qkU<`%vL8X;((1D74KoHh02jxFzR}&%|7kerzCfHlJI2ddRv~Vl z8K_>9?U9+W77_!S?@#sT!j7$%U=`Sj5ji7AR|zmO9ZWq1ToE$jrEJ}otFjavNoetD zT^Zwmt{sR}H+SlCOM_fGdoYxe?_b%%$nO9Q4#L8Gd&+#yTlSzc<#T4Z4{g|0M&Dl{ zZrB4dFU5vZO!>SUzQ~D*GF<97Re82%ymTJDS z4_-8G%r?py3fpBUnf4N_lecDmzrLf&659y98faER0lOXQtG(D?`d1q;8J##-?g`qZ zNioqhBa|;RW0MMsktX*N?rv`K7i>Y$1XoPyE2|5_HwDa+u1d4;({|%ZIq{J(NFe+W zYZ+KuDM)pEAphKX1|diCM!Iau=cT>R=wuY4V%`-+_oT>>Ppeq_X$WjVWz=gABC35& z?)OUzxEsKuN}S2B)+0t(@U^qM;&+OJ=Xk1X^!rWa zg!Dd?eiSvp$zlpd#fxf-#_nhEy5Q;<$UqPJ^QOM<`Qt(bFP|lxJY#`t zL$PX)Y#m%@f5$R@@v& zJ+(|$;D&A64{~H`m)zMg9zI_MsSc6>xv}aAEp{<7WKH!?uMW`r&x9tHLJ@ee3f zclOFCj)+F0gCoh%!Pf9ciZ^CGVO!_Xx3Q)uya*s$!}Egf>ypAaBr~H?F5qSZ6a23? zcY{F;QD)b>hJ=tP$ZaC>;f7`9g*mbzPo)N9$6md`OVv|-UN(&>{ZkMtu}JdPOzLyN zlis)HSdY}`X?kPV7+9w32Oc0+2{VbUxPq9W@QBpr$SI&;ahVcQm+%wH15^5Zrh}fu%p~7&*Cvt5 z{IQ^yz!2UK)GWBXD33FpE{)~ix0yHANTnB0GQ-Fb_7wbIPXs)V++0jE#I%S7rzz)N zXc&*z(oPYNecnp3!eUS%{=;>7Ws#qOZqLzUH9mxJz%(D+Et2EkXHQdtVP4Jo(6b9; zE-psXB5PBd3-@Jj-z(wTnna_)8#%_gRrCU0*GyB|EPQ?6VYXGg)B%*0n^V&(0VE(>S3>Il=_}Ur^NX7MlLvKYmgwRv zeSIL1dY4{SPP@#<%TnZ{^(g*l(Efclo<}-d>}$6(jg3GwPD>Z|=n1Qij5meKfCK1~_HrqMpJXP+sOx?4O97tG<%@wmT@SJP zD__LB!(Ra4!cx~iR4lMQ(3>`Hh1iwY(%{SecBxb*?L2AjLKS=|f zL1wCbBC~FSg#Sk&m8uTwOvP5P`Xu@_f9J{GB$A+{u}jY|S|IwdOIDwzU(-vG2=QCQ zj_AT$HDR*7f4>Km>&EwM$~B||($uMKUc|1JY#iI;Qg0Cye_=#lVd@AJH<6N6A?Vi_USKAdIJ5)F5P+b{|oBmGG;hbIL@1-y#c6BJEPbAt>Tbrdj-A#|vd(Nd?kCm(2?H1-4P?hEm-CFQt+UXUSzMCki7G^Sb-1SHpi358x=L zEc1u{sKs(?5!+2c1A-k*xP|*|euUvg_n|Vm$ad;))PvgxEnY4| zIF;8SkF(!=*+xEL0*;R~|=0 zBUTvz=#L9vkn=;V==#AQ{^tqiaP8rj4^_93v`Jw?om;n&*TH|)yW0=^bFTvr>^N(P z#=K*gM&R%Q!`6+25A^w?#hdh{fu0hEnlj!@PD?=l&rR`YSfwAP8yRq;dXhFI^Y04m z{raBcz@@gpw=A>=j^$6Od~K>SN)(iTqvXZ;%5lY%+hS`tu2PX8GK6S50f znSK6CIK;Z6=46EEV3@$kd{TkNUF!);eHi=(>%a4qK#P0@=P@!YMm3c{@Wh*W$)#QwSOk;BG_Z!8Y_sA&w5Wb~{`x-XP>sIvXbTFPb*p9cuEE{LZFw=w_8 z@RYsI{IX=lCp5H-THHy_Tf#cUpSCHCru*n3;S;*~GJ`f^f=Xp483}#DQZRMTFsNzt zdG%ClyGeY2WtFI3ZDZN#@{3hKWz4^V&?!&)oIl)wUpdbb4(FY$p(+X%Kuh>LwLvC= zOCG$$$8IxmH4J1cfWuzC$u6^zY4U@nQ}N{oLZ4)B*s}m;zLZykhVk<2xKUlxB|G8H zhmy8zyuTAk@xS>~+@Ia%iYe**@>vM~eWy_Tm!&pV2-y2UgG5W94snrq$Aq(AmC$0sTRt;d95p8oB!Fb>L_N3ALmghglOUaz4yY$3^b zAQ-4O2f1e!k9H9VUL^EQlcTJuB+xGy^!KT$3)O zkrsjvC>GB!5hrIxL)AGho{GwJ;ojj`ckK;SB&=>Losgz!;A-$=@{AETi&zovxbH^SA?gIgnjZ z98d`?gePLS7(ZRwZ*r%&^5mjpo6InD_3XLaZPT8awrMB*E8$|GuB3GAJoU*i6dzso z%&EuS{%>!G3Xo>j=Yr?F?FHaamtj||abH7~M<9s3r_eAG{d;o}JGZVKNe7`is4ukb zydwKI6cXTu%qzaAH?c|)4+-)ndXdaVGnxAG$)GDRTGqnZT&aZ`eC0eU?a_lji%38> zIDY3p=D|`(a8u*E;Qokq3C4rTu&pzpjQN!=QVGJf6Z_&7vb)nFB7Aj*9u^ndccw^v zY#90?V!9@Yc?nV(bOZ}^++Il4CV9iuUF%-1n~pmQXX10CCW_~hS9zUcNlF5zXG%rb z-tKQg7y`VZIK1z+8|$DP&cLPTs-SPKTvXDN!oco5g9pXM#0*nK@; zhrr>S+;oE=t^EOSa@IEL$WTGtfVeVd>SfLY*n-Kg|6({V%+&tg-E*_KEta+@O}%30 zvB$|J(WwMU z?3@!N_oV)En6{Hbt(#dMw!nLlZD)xD{K$B^D#QA8<8#-#DoQy-I#TDBNC`jYG?5*F zMq{;M>xand9>{WZYSO6Aa&z3hpx}k$_(;1nZf|c5PkR|Ji{Lp?3zSk-HSxiuo_IF; z;=%cW>1+Q0M_7|K>4p|dkc)dD;qG-YOiKad>>ZsuaLK~8GoQ~~nivtaZCc%Qmq=?Z zf=hhsJxyRi6%MxS-lDl;^^d0;^dRHF--8GLV@oP|&*EU$fqBepjLP7KXE{v!yfnt2sYS$lr68h``hRz`JI&w{qE>kBeZXJ)&OF1D>u z7jUT1eZh+KYM&EDIR{Vps94|@X!RSsf|K_M|Bk!&WyZ&La z9sW-BytQ>5LaDd6`F#3l&NH>XuLVciA!Qud(Wun*es;G2d2u(e?cg6hAH03>Nk=eH z-1uO=lF8Z%&4bN2-q*9JrD~bIjC!ff09clVd^F^32;knEclAb`6b@l8+ixsv>g+D#1OLa;DT z*`7%^TePIuE{1d)6>YlXmnZMS<%PH@`7rrh7iGx6_r)$;p-o(&T#pJ3&`zH!Z}p@z z>>z95B_dZ3VvnmH?06A}9%=lHsw^%wTZgSP@}Ey)zAn;+PCGfe3#kL%_Nx9X323$7 z@0!UMdPP;%>uR`WU_h_zdbN(1?+de)uL=WF1vyGJqRPGvb7RVw+3^}cP22#E01V1% zrgr{HnR{{XAu};g>jeN66{`BHd)GYfbG1Yhe;FA72(QAENyG(Qd-2G(?yfb5uxrsh zEPL`3kt$76IVdx(q|xF@O4s%Sj_yvB{GK0k{GCZ)%x0S~Srxh;-?`yPc?@`bJy=iw zNOsY(5fkSect5+OJSmtfFMV)&CILL-_h>4DU34r01{AXN7N`deYOVL^O>@9KSrohz zz(Pu+62^e4n5BaK&nmGjA&)FVkC!BaTpB(G(NaAUbg=kR|N4dK!uG6OGT1jj!X{#yAtruZI2WJ}!pE z58xw+H*~xmL4k(9*O?DJ2Bh2Qil3fweNb))w69K~cU9~4m_Kaal}4wL7syPvF#X`} zps!CreEb{8jF1Cy(G7AcI>IDR^n&Zxl7UFp^_-Iq%hqh!hC%>3ahzCuI%e#Z%5&#l z)i$T4Q;0toX#LL5CDfFJ+ZT!4n-<$g&Tj$rVtR3d5GBVLXeMOFSFdb~hY)a9<_vAK zG4lU5^6V1nAiZ@fs661=Q(6x&9W9u#m3(|?Rnh5vaXr9de(m&VVPkLvA=~uZqfdY} z9006mv8}!wDoMIS6ob!}g}UN@(G;R8gxj^&PSs_;T!|}TR%s;ZQ+?P7S{Pp+QVZy{ zi@2xSzw5Y?v7Y5N89arrwAu{W*Q;ua2?cjEO8iuWHAn_d2epiMefUDi&A#XYAH^K> z#ywc(Nx{Dz@FOHQXcR{cYQ~#pv{2mv>2^YJtu$Y<@!*loi&JL3nyNMp5*QYut~S-Y z8sTbyoSZ^8jOD~6Kq1SA&G*jI4B8&5lz^}Nr#x71^z?9whGicF(>R_Ld~U!Qbx_YH zt92>eDdPv+;sHW)U)G;by0my9TxO$`ckE7ax6NG0ibi7%KMt5Ta2`n;<^y5stUX6Zr%?T7xAq3;OB zx-z6iz--HtixAf&`~;g;#VZp(;Tw-^*vT!2fZ0v}3|5Dy#C0xSH-o_g`8kw&)LOxI z>MEh^M_jv}kG0vy@J>^R3ovI5K0^0q(#kgi%RLNJ3w{FF?q?ruc`Wvb6x2CS>5RPx zkJ=Zc!FbuxASUX+x$_kt{=Ik)*LnWw7adQ!-d)NF11?p7LzUO`ftA-T@;N2bB-uhv z3=BC58knIXC+NJlXTN+7i2_`_n+O(o!Y)z-Mu8R;w9yf2@*oI4CR0(=wBbUB&4KkW z5C!!T8@=>71r6Z?=823oZdQH1+^B3Xi-S}};=FA)A6GraUxl7K>k@I`J!nc-@fbOm z?I;5Ab6Y$Yg3p8*l?)4oA;EsYnNpRwmPn7}jjTMqs`YjDQXbA?oj`)YN?7$ZJGMt~ z_~MDN8JiL%*m%ohlCLm~FYpN|W9!TK!dvSTw0s59dp`DUkKs^fHP_I=2w@B7Wh}G+ zG0u-stJl}w6L_-SqBesgoN;P6^osd|)Di+C@1FCZWYEJU+=m!eRpj@V=c7zPZYzJY0f;G*;qkEjWj zCRc2N6-W?enIj>pq4l|h1C9;l-^dYZd*W)Ucizio^D$Z}5CSg{nom1OOvm3==^NXW z${F>|fXY)wBpubC8}+NY009usJRuS|OHj&CGMA+{^AA#~95fCvguigvLe{HXh<%F+ zau@&UN?vF(L4)K7+6OsGydZutzYC()uut@DLIgMhiLp0f`BMqlxs*y&;*BVh&?eSO z(;J`Xg~hnXL1a^sJhjW%`nWeD#^9{2UC|%U^yWG($##^$pma<@G%6!k?E~zHPEfwy zcgHU$cN>caDf&yTe}i2`eMksrRM_+9#+n@012vy|>_Re5fYC@MkrmsIwppb`91?rz zpc7&Mz?B$`AMoeM_>GKK!5yo*zl*}J=_$srG>K+h!$6MytWp;iaYlWXtIgDUqGizl z4&HC!Nq|Y!^CB3r!k5IbG}~cr>w4EkXOo$~n~K>Y zBJ(l))}(%hn+=V)cTT1N$LjLXx6M|RapJh-u)>_(=IX*=3wKw*b%ScIrxm%B-m- zTD{k%&6s;+sRj#{(o`{7^)+5Z^r<<^83+@N^cIlGWnVf!K4Q(6klcFVF(}$1bl}ut z5Zo~Fb3%9I#@1~5+3E^^Gj4uYL*~>#UWGC1XA6|#YI8S^31lvXmixsY#!Lf#)ZG|- z>*TEnV#T}L$;uAwsx(wh_iB^SiKu8mO};vR`lrf+uLl(7dfa6OD0~5E2aehppB^#uo=*wFjg@p+f>c z48L1JHf$s>PSYmI@ylTvXKL$QMEh_`{+5=L!lW=y(D;XEjUwhY{nYH(JwDSjeU{(; zRF<)&+pYos+Ybl3>51yN)gmBV;b=dU6&ihU$-DTaEGOgFvv^k`6B?&Yu&U23vZ zHun>GVfUFG8wHVuV0K`79&eBNRSRCVYY9aIzEVF9V~+JsY0XSL~x-5tq#fn z9}#3bhJbbf!=^3DdO7muHsrLZt>z$Dec6uyLKnp_2eI8hCSf>8`mVEA4+DdRP$Guc z3yziJMYOGW=l!{cpO5@LLPagO+>b6)|4icTvQL)AT-M0|#mBNQUE!E*5#uJ@S1hB; zoGMCM?ofTgPo9va(zKmi32BB7EQn95g?`0t?;-?eErzZoZe5)~iO$I2XLt{;9wwL) zgI^dVOm+*l^?TEfVZBd&clb}BKBHZz_W>1JuhAr6Q3+vGgy*e)xpDv66M3HZVpr$b z#|lzq(bHG3|BrU@g@`*h@6DMH99k}55ZaC2Fax-Wjj!cT<%l;g6vgauRF#NNp}Fvk zdT5>M)seZ4jzmbbW_wV;;zK0aM_0`YhaSEg0&KaWSyoa%L4bK|L$umSAY=t9P{d@82+c$wz8_}Pt_)mFiTz#OZ}oa*Cloa=SIbJYzy!Rg=_VS#|0yw&YC`oVz5<9%0K{?dY=-wrjRkJafAiYtG)VLKv@5s~ z#`%#l>X+>qEYhE~IuB^tuk13Xdt$~!r39!na(w!Uwww1FLiSQLG(ljAiSpCQcZ8xS z-Jwey`hYSdCtr+;x}G85J00WOg8X8EJ6_F7$6*;5MaD(QiZ zZ#dqtfxS1`XGH2$;6C+FJT+;vGT}?4sWX>tsN;X5xFT#Q zroViU;+)E>*VL@WG0wZttxcUGCtG4ZX@1v=3m*X&h+57km+|f?T`!00Uw&Ek8PefypcKeWgl@(=EeLTAqD0iLGRK4P>U(Q*Y8;bbiz|pBl_;}8poNe z-D_w_9s6TLH;U=BjQ*nAR|OXz<}M1{&h3b@pOc*io1<|(Z0u-BN?rV*5i}>69Vwk! zyBvH$3b&pdDAY4Q=j&wQV3l=O{4M6xDlypC;t)kh4pc?NPG9chU)6gPY6L%#XDSieQ}VF}*l z$Vbc5Se4}Ny}knwgF}^97BDy1+8`d-w5^bm^@DXeeSs2-;N*rnO?93#0N- z7l};*;FsKFR%XBFF==ZTAv}E#ifYzSNFXBWl(@d4*%8cu7&`H)aH)r%;t0_D@=VWb zqd}ck0P+|J|_g=eDLzmAsHg(U~_E%l> zJ;rK6`%x>l!~YP*+iw>!FSK>QS$^BT#sZBz-As58CKUZH<#BL}-b`C-e=qeBDH=`L zxaF+AXtTCb1@3V1uHmeg?Tk)RQ^Y^(J>R`G(gMA?ndYi333`vxLzeqM{4)5*`36;aPeX5!EZb6x6@nwo90t8rp4a zr7l*SyOoTYjf2er*X2;6qr*E~2whk5z|GM2W&vsK@s)eA)(#C}LI)DEka3ZZ(J`7V zJJFe(K(e5Jt{>)I9rRzO3&(tuqXU`mm@59^U^j|_#(mb>ge8c-mi6Mub~oQw`2A*e z$yG&0?bsubiKMg;Xyev$TqNdXge_UJvTPzyPqekqD=vsbAq@g2zJVr^gG4T4GpJ+- zZV@qCHomAxq7TKRvs5JjepLx29p(WqN8q_1KGpQD`uCGcJP$BJYumgkBj4l;TCE3u zn-nS(P7&vPs-~J&fv*^i!tr%Ni=(7FMIph3lt2oAhfPB7y#%ygW$lciLSma*%uo;=2!kHRm(#Oh^=#jAD^2~Q(1 znKtpq%%qHZ=mMheKT-~d_m&Z&3}(!b2+GcCo?Bf-IZWh`KVph7JEG<>(4Z>a`t*0CIYuV~HMA)OxB57ew0k30(1d=7emKn-uyFHJrN|40 zSevv$n?M|qX3sl;rO|~JC~rl;yULdFq?1wc9PU-(?Yzggs#nlMP3K$ST|8!Bn@rWH z;#PchAk-Tj8R(62vY_k8uAs)jWakU9-laD~jr{19kD%rNb*)-q@&4V*1=5}oP?PD6GWO5_8dcE%kZ~dC3|uR~6L=A{efjRI^wYW0 zi5lD<=w977BbPSQj{|IsiA@D?;t+X)TiSDL% za1j*?Ck~JnA~_=1X%Hr&EK*8|N!I)Z)XOzCKVrT4zE~VJOW!dZmN*ch>i}wzLHrIqB_t?qrO`P;uvYABy5R8Jj7sMi~o33 zvm%PQM=WUq!$A!D$)*Q1S@jGx%dOaGZNV%LMVu6=Q5*2~3Y&8aYrN22(z05_dXg%P zB6fQw&w{xTxN`0)8wo)!Gaoo78PZ#rrZk{jkFO4fSC%V5Px-A6NIj4+6Kl7h-Sp5; zxyffJ%92^K7P{`TVcbQWBnOICNp$Xg#(!*hsBd~UqQxEwLLROZj6&YcQgVO^^H)4s z8oJlN^>{RO`X*rZ(o^U@R1jDP;}X%@@%OXf4dsgZ-&#O%&=CXjQtM2Lrsu!JroIp3 zv_{Ra0_-gv9&t@lYS|YQvk9}!{yLm9`8mf{us{)G&WF?%a%fDUxmk%>Vr^ruwA;Bd zax$6&H+Bp?hQ>addgK_@N`-iy!s*Dk+RtKPkzmz=5Jv1KC-zrE} zPp6tgs}{x3Exu^A;;!{Oc|9Fn8xnmv;X_V71Kn67jL!@QBz^TM{-F?d@3i_H8%{e# zdO~GhVWSRGOF^$(J#G$$LVUe~hH^_iiiCDI_t?K2WF&v&p%ru$_Bq~jqbRWxW%2Vy z1+>8Rox{S?NRc8-B)ql{ad4fZX_hbVIC9NCAL4L1*emB|1 z*!cFvPOz_~^YEHzUg!y5S>*idA2L%n)pI;c1g@TPgNgY;!#@Z{e?B2bljOpKbA-_q z)uc+>TH)czAfWIDdWXsO4F}ylej*pylhd6Mx$79Anm22`FygPe@_}S@*Ko+Ell;dr z%_R@9a`^pW4}u#%O&%@L^$1eGbo6yj2w;f2hRIAiGOd-MTte#C{P^Fb9NGMh9$U%hJ4&T*1Q`vsZgc@rx z(QGk9>4&nW*|AN3&NCyLecA;NP&S(s9P<-|Z9Z?GXck&I(|QBSx;OBg9q8FoKXHWL_;#}w ztU|-61{sJ(UsYjP579a%QYNjXuL8&l5E1I3H1`c(r+$g??x8?EiGQ<%`Q{lU7xoL1 zuz_bbawO`e-)0*=d{4j*qzw+s3|b<2xVh8je*Fppg zK4cj`N2n##5#s%$0-JfBoeC<0z7_}(TadVx!p2%i8hD3?kI(DtP#On2`UGe$o@-19 za=h7dZMUx!AnFTM$^wVC6WHOVWVeBBwmBESDgiK#R}41>zQsVijrk#W$CzkJiR4{_ zsN$cp(n$yd686<%%L1wOdKEfJn>jDNa}#$9oxxl_J=rwY88ukeb1%z$E5p@*^a4tW z4zcsv_{a$5UZ|;-EZ^{+pv#DxRt-D7U@ei)Kl_lbGo6Atvi$M#_-%BhRbNPM;$bsnN%w!V$6(g?iDC?Z_p`8c0{^Eor!7SHUeNb1D>S~OC{dRAacq_Xwfz@Ut+LFDWiwlr6D_6j^GSAs1%sB zK4MFMLs{n0Vx(;e`DOq}VIGYl$_cbHyeF`ea%0=1Dl+fJ+D;!4M_^7PB#5-!CBboq z)99&+vR6iZ529U%OhMC99WlrL%4k%2{@k}#oTKS2xiDSYFV9X%taeZ~vnjgNIqgd6 z-o;vS^0S0xTVVQm6hc;(5arWt#K(*t5~eJ~OMFr0XU zRU*Avj4_0;4>vNOWUObehG#LhDOHPL54}<5|Hb{+Z!J-u3-@0)a|I@XJ`U;pUYL1` z==?)EZdu07OB&+e zwOBBDf>0?L+HFlPbwa?4{Vi23mp*m7vsaFat=J1Tc$271Pk_K~ecGNd^GHevh?TF3 z23a=BAE{&xq4^7p(MsxX%`&vN+rDQ;Zl8j&CzxPN(OtDSAzL4(sFrZ;cWA!w+N z<@#D4Gmy{-Ez|8s0tGh5rDYI6bq_ofs?+}Q*Q1){zEbG|OiqQ{ zhIGtIah|op$#=|6f8SY$83mdt2b?UNE^qE}v}8HjUyd75InAzH(THIC*zYwlVEhLI zvi{efUuyhsa7c&4v_HMl;S!bra^3e*RXs3m*H>>!Z=fAjBNdUbn{gs@inqU;v-sht ziz-sfbnUQbcVaV`R_6^p8Yb#B@Y1HLk56-{f>RZ}vnNy2$f`Yt>KtW}K>sy}uSW{# zgBu7p>|HDSs7(c~p9}?K$NK(#NjxiEr7)dzS!prc?&sUDd5QU!0f%j!el_)$`l0(u@#YqGL?%Zo&n0bLk zXTKACzX@P@L{XnFk)Lw0VHNbhq9u~$7*H{p{H?cTz`{(gwGkV)P#P&-59siaxK9T4 z)b7E}v1aouRNkyTQmIOMs-Q!@Zcls@z?Wc-6y)k3V~(wJ4gDieYPhteT|ho7L&Z{J z{Yqlm8%8ft1u5c>1f0;<{CIbTd8S09b0smtLi)+H8B($9Q+>Hc^mevMk2xX8HSLWM zJn8_nX!AUx+XpVnpZ1)9-wxrNW;2=I3`E;tqD{~5xcS1wWf4w?BBt$aG|DR|SP@Py zG|%PAL(=ALm*He8&Xw)lZKuFoRtoSfIWL;9coy4y!L4f0vPY{F!efe=R4whckJ9aV zrAfYdD5(k94lCh(Y*_~A#A*(O`S6RzvM1b#+&K$*%`dodO@|nv;}fsIA<- zGo?z18dK)ADxVn#U-7R{Dy~1`9a(R2X_af?KG?yP#WN}XeJ}thzspLP!x%aa(qjvZgF3r21$`K9#66e|Ni?HJ~)Iab5MAzCqD(#gXI?T@Z0? zN7_ViR}Iy+nu&fkR>5Tx>!0ON@sVj_Bfe=2Pbt_`*bxAERTxyoGlu?DTnM;hUf-sq ztQk^L0#XB1>WF8s;djH!3TYWt8&OedCK6Fm7k=c<;amO?OXyGWHkV;LZ9sPg^AMw~ z%+_&G-bLxj8@K$dIiCteUFP;d#}W}^12#EpIo;m(we`H4^m$qb*nOlGy)(SW%|IVV z`kt$UPi&;0Zg7j#?T90S4)m6yN*iF<&}U%t!=ue6^Ip)m#05VcSwv+^|Df>-ips;* zSJXCl6JB@gJ>;iykrgEVw{+e+=+^ZnPt7EuzDfOVMMfe*7bB3n!2~NPh8kh~8`z(~rMlb-YQvEt&Wd zdmz%8i>_&rx-E290NN##`9H7&@ssE}+2lLMhBuh|uw zPp;>d-A--SRrSq-{$#A)nE$6!80Ng5)6*;Kpd3f-QCMD-D537tFoC8Jg;)?UOnUDR zp4CT^Yye}rgutkdq*M`~-3RlJn!t(Y-5f(G_b|v@1Tp2a{=4@|q^Mq8)#b(iNgd^M z-6F9Yuba_poOxCdbYBOVoNGTdX7KiG4n?>aPvof6+-y{_st3l;FaZNpoHm%(4|cdob34|DbkdE#*rk1Q zy||3~d4YOpk|1^}L;9A+3cMl-= zf=09;t4+ zCel)cPxeQxG+$IpHJyoBA$J;lY(>$1t}g&7M}h!x7)kgs<;)rL%+lz!M|n@ylkPS- z?gAy>Uj==$wg`yeTt+$x6Cmt)m-tZ0(r$vNuDdY>Ttn zZoEXu20ee~jKfh*9tF%5B?SuFjo0e_?SkK{vvQe}gK*C>^XV5fu=@~TAg0X43Jw_F z7OW2USsT&F-|O3jTBS$3npSldk&vo;lD+my&4~ok$-nfu&+hJTHaXIxR+rJQzSh(a zs|G9Fij*1Tfj^rxzH{gqzw3>b&b1uLB$~bTCFDh40iogH>|*Vch##O(8{&Ltb382F zfhHUiMXvCAlbW}ZI|+Y|0wfW1rdio?7xU7!{b-ijmI8_JS3!)xN3M0xJrQH`gZnU~ zE`)6+N;UEt)**WpnDPh!IWD+2JeYPJ1`NKh-5b-@gFgWLEVgb3%ZIvfx zU~nB%i1S9F=umYvy)-@K9u|PGKQPs`CVV}Hq(cS8=CzF^Cr%3R<}(U_viczBR0VGbMAkoAuM6KLmH!E%D?_t zpEaEHh{|}+AHBZ{^jnTG39=Td$g{{tz$9ul>JiF#xr;J%o9tGmAGt1COJf4;xD4>u z+uZ=y`jbQISjOamq}=%Vpdw%M_f0Obs8hc#NV0k}@LQf^tmFsM!&EG^Q0^0Fq1_O9 zj&3fzR#o9WYN|iIg{0I5(Qo!<%fn^m7ag4lWUMTiNwqmf*2?DT3JLOp`Y>#JLzl+4 zptiY+Fh<$>jZISfPUwfbn%1K0B<-!;P`uNrf=6DBV$7 zB`O>6{HC8FV2hFqFI8Pe^6N`n*&?>dD_zAHnA>4^3g?8T}ks{@=@@R z&}H%1#)yA}KS@g5S9=y%FEeTpB-xhl5BeyS*A8Zs*IC;-?A?10j-w7<(J@9%e>|)4 zFSwxQ*rmeCXE^btpv-xlMY`7by+D93Y2@sGOtkOkqxN{#r3Z?$*kd;w;%0@{a9H^) zPesKq0QG;LSm*;Cdoo?-cl!)6gt&}b)5j`UWrCsvgup1@in06yCq<)jl2Z4ZoNXFm z36Q@DRyjEJoUOIPj#i90=4-gVzmeTBlB-q?+`7f2k7>OAnb6JKGLv)?;jmIfj{(QQ zE4IUAZoBDxvh0yaE(Al}aJ?hNmCfg|dGud}elyx2j?aICq2h42VqcoH2~|p&Ck~vk zxz_HE`ZTc;8g&L=64U1PG1;?L^Mj>+=uvcKY^u*IZ#;8TwkL%MdBH7?{% zsvnWVAZE|MEK0(oyJPiI1qlook-0II!Txr$c>C(fDU+c1w(ZojR`4F^pDuB1!SlM* zW3Mm&p*7onSlnIy&M@fS6FKzzoE3RsMPpA1Feg2+c9i0!q0;p%rLGeB?gnun6 zB)KJG97vSEHs(RhHO1_B=Eqh?4~73L2#R=ju1>+1Y@x_ujPQLrxGkvvp^3`PuDCvd zqYT{lO&3qlxFq!sFu-KGXZ5u)$q$w8TNP*0p~d#TA_lp~J#5Qc3>=r{Xd#qCDTn=5 z{%vvp+jk>I)A44?N*RXDm)TLj8LuOH6{gKY!9mJiQ&6is;s%mWMoaNv6D;U#k1J?> zo1Jnt=~1)S4`FwSW+*V9x_%XYoRxw40rW<-skj@Ait$L@?@fdWzOvQRc^|ye(Uc^7 zkc|ffRbG{A=51&pnE`3m0-~UXpYc0PH^0B8s?RpFS zEU*xj^wom;JG>BXK)=F^UQJpkA3zmg;6tE# zzz2zo4-Jf*Pb)e^khOww(;@d1&IUe__V2+t*Wl3q(lyX-ME0))J0>LH^dY}^EhAr% zSBts}GSyh=Y2Xm!c?L}90ZrhgV$&rTUoI|7MZ~w!ecF&>0-S;y51QU0A6)FL-?~ z*c-VODg(49Bhu%HuAk#0Uvd0J7HeFaN!f|3L&O%BjzdiQTp39RUps0~6^zvB{{8^nbrOlu%7zP@8v-&BP^=w+KonDT#;y_CiT{D zx9OA^gd-+sx|exf)Rd;VR&9~v)dzptx%yFRQ(t-8b0;&gasE2kL}BGeQv~cnpx&g! z^)d8Yu47$I|Bs0BbGJ{57&t}@2Aso3$}`GT05Ts1m_+c-Mvp`nz%50dO;|7U5~azE zPg-|F6vrI_+qLphr=@Znz^j$bxGE?tFs}&F@>BaYNPz8O)hYJ8B9{4iwV1u_sQtU5 z1O57z_R=+_g$hErB@SL#!SYANCcX}wm0ul(Oo1lo;VC*7-gu!y-z@{W%Vz@MP7sQq zSmifvFpTDM%<_j=O(xuR-QO}a>|7FwlWPB*VvTEW?->DghOy-@EIFh1NLxyG^?LL% z8cCl{BMB|kP`|;;?&(c^eA{D^j^Eqo-rasgok8%LU_;=u3z3^qD13892AS#$&pOlh zHlxf2fuiJ6^Z&$Q8*H({rRvHUkNp+d>coeaKEjVngn_h3MArjgd)U==_6s&>`neFJ z1o0;U(9+`2I;nl!QVDg+K2T!`bT3JZ6mv%2Qp>@w@?8m|lz0yBJ70W29APi=`b5hY zV@=}WIPo!homMl8v`9^hda0m{aaK7LLL2K%6L>Bf&gNVWZ?mN3q@liJBS#%LwRB}} zEvu4o>Ad64I0*0cqN7DfIi}O}bMx(cQYW4QFd=hfm-{}+5y;R`51P>TMjWSb72VNHfF^&256ov9e`8BmD~_Np++cHa(P2jeR#QG zG649Ylq7-Sd_^-Wt7Ikbm$Oorq6b4O#0CTm{TuBUGHFuKBr!OpFS?OICLsnf5gKC@A##vH-FyY9D{f#gO@ubYsejFT#9;j@7wNis}Ip<|{{+*N!P2AY5WB0aM zKcRgV#9YUl%GGa{=h}>P53=L!yL_^93lbRJc&UkLZ}ASBabMFu?Ra6vK|3!{(cYdJ z=|Z9{$WU;!N#vF4!Sd~JDb;y|lkH*ICVBR%y$E7CG^9XReQyZBH4k4^v6yXOnB{mncI5HyQV!%~ke|_XE84?M%lB zda>G_fj#kPirTtk5YXsDcI^NL&16dS&wI0-DaGKA@1xN6l^PB(s;#0+OGtRSCw&Gr z1?{r4LtLo~plWxa&OF?bKe2q($!l-6R=)dBj67oYp`Z7ye752 z2(!`~(MYMluWQKMfnIJh7y^><3)CJ>&r3FRjXYe!0X}AF*~?$McNr^+#b(eu`QeJc zii^UMj07*ui7@u|OJB%l@KKeQuK+IgkpZr5Y#k0)HP9B8+UM;(h~C82jJ>>Tz9+J= z*t+}}u!*#VF0^bt;`1ZL^Gw64eSP#kmWwuhE>vmQe+e6Cv|}P~n4vM6Zurry=DKaI zK-0NrxH1{@-53?=2OwiNcvEZx-hG1pY0_~4Ahi8$OJ;D4FOW)3M`6?}tTta5oxXY~ zlOm98)KnMz1#(iY5l9%V3=TZC-`hqN&PbqDJwh!~JN7(*y4M~82#LNrjrm^to#@iX z1ikBi;K5OpGtGf%abJNQb&tuOsXpm_WGa9(sjw_TVL2f6r#p`cGbE(3jh-x~R~axE zC=JMWKD#T|91>z5Wel8rvhb+Z=*~oPuHQU`Eu-^sFyfyg6N3{&!sBTsfVs2<8 zCLMepdQtOcfnZ*45zVRGu>sb9gip9^cqw+*s_5`}3#bE>#_krh)5Cu@#qungTx_c% zMdWG&Uf`*-;&T20E1vzz?gEO3pj;wnHx?EOrC<~0W5cw%>Z6)IxOH@DVk6U}fN ziPB{=nz>B2nj6Hw@fW}WG-+))+Wa@oj%lJ*)pDT$-=l_qbE;;<3sqbPl8sp(goMy@ z9qkUog1qFFw)ZR3mlK(!TXzm_{A&k8z3(HuoWDovY(Pfq2G8<8;^fv3sLKT}`Yc}$ zz&jr|bM}q621qM{tV1_ds9C*f7uDc7U9#s+D!1WFZ0vHm9tbFj;3&_uP?C?8#feMW zJ<8=Kqw4(evm%zwJiSrb2v`fkNr5vVh$wwuAkYt%(*EfPTT&yO9+#m`0R}Ha$2ZFt zAc`_qtgTMp=Y9Flx&a=DBA0hu0V+E035mCxG$w^@<=S0rU|;)QZjv-+I#T5*FvWtn z_QZne`?l-zhm$NNhNFa*p{J#RijCx;bLe9B^G<14BMia zL#TjR4D$yIfj}r1R|>1ix~94uycY|PrndWay4MYwls=#& z&~Y6aW;!Wn!Z2%v@PfHYSK)F_Vh0VcdDcoAb*34&k&<@2{a;hz?ZL=hJH7+=7jb1l zEO!f7Q4T7Rsdol8f(>+AT*_8>T^0A;Xkp_tQLtZZI@@k>GcA*48=Q`yc>1pAZAol` zJk%223?$g$Glzvn4tMvi$DASUFLHN_R)o?>ZeV!ZD;rc~YP1RjC!#LQB>;B>0BU0x zNlMU`GsIOI)u_7)1HVzm(Op@|Dg`0@gi@iA1+eng%8&Rh4A*_7B| zs`k~eq<{J_aUPT|N@-0k%dpm7MTez+zJ<>XC;q5e-Ishh1(;kNw6ic&Ab_F!k6?hh zdHjIAlYIYn;w0IXEIP3r2aVf`Fhyp$gY}J$GpWN9ND-=+EQ} z>%d;#FA%+o zej%l+cgu=Q^{ve_1b#^c0&Gm1U1(fkEDmrAOA4T@99=JrM#D|}+tXJKI^7xg@dtg< zn=x~>VD;QOMOH3|9Z`%H?qEABW*? z(JuN{UaK&S2Zv^DTO|Wr${QH`;Kwnuz<*{3Xh2n>KN2^5K>&9jLSYLjtZH zFFT0Urxx)~yOs{0Dx*7nE|GO=!tfad10*)SSciEe5qFk6&Y{F8the==;9^Ht!|MFvk;de8oLwCjDU0m|9fRVKERCByp|h2A+8P=m`Dbi_Q#g*1o5u?J zKKNWY#)b;6sp#B1RYM1!$Qg>9=r}9 z2d@tk;YsR)iwc-dn?K)TU%s3sLj@@T#DMTz2k_%dQ@$IV3b+#ju8|2RyRt?+HA*A8 zU*TWgZ|u+Mxl=V;qm)@RWm=7n-5E3hiP?>qUHdID=EVCY?{GJD}7GNgD+m{@ZJ*$W#Aw31?MF~H{l~S1F$w@ zuh4kKAl{!+yib9w2g{rt9v}n+`-;5{8Xv{@OxA@AwUvd&p?1%@S)hgUPo;g;#aN8AgQ&eGPRf8mQ+S1o#u^FcD-BQF;RJH9$huCTTf9b zqP%!kNlMHvd^;KbFCCrP*LjJ#OcTrWiw*N`Cd8!@X17e-Pgiept52Ei?fTW^ii;`& z;ZwUpTmOy-el(xH#}Jcpu|uKM3zrvkwB+GQ0QtE)P#;#?s6CD99V$VcK_)*U0>R%I zH_`}Zha2m{XV^FbH=Gm}KHgTnpjS2E_Ya@YEtKsi4oOU8`5(PvW^AtoHD739eRxh_ z*nkI2V`dNx^2M)xOp{FoKwQF8--OgHO3)A1JLm)uSAvRsxS={(@XIm5a)I0?iKEw6 z(~m8o448#dsMzJdF2eJt;YU^BOS*?}aC)XkAVi3J??XZPney=kvgN`8mD+S>X&?`5 zINv1y6;>KwoP+~m4tCmV(EYAc^C6<%k63Mo96Bh`*;p+Sbp-D*4bvP;ky5{1LMji)#5rO$TA2Zeki4B;NGkTwaVe9Qg)wF(tMgdroG;CyvXm!^QJBn|; zuKWOD;k=mos6bi+5`K6{mKrC%q}&s0qKqdw=t^ZpJw)g_XK&))fq zff!k{PP1l7l8L`3No&a9ArR5cYARG~Ry%zmZzKH$fu|P4zJyj2rO^*_s~T6iPWLU0 zThGvF-ZZYlynVivReA$u%EZpXFyJ<8v$2CDK9C*bUGKj_mu}O}j}&E^fm~%IOEe;rw?sU1bI%z+2C;;2bw$+nNxtdM3QU<{ zFbqC6pF5C3z%ky7PProUG)r+Z+D`_wm9`U1AIMq2kfvMxeG?s|N|i|JXlpfg&i`ue zz~vv9&G3Iym~ajnDx&d(+jXwXC%+jh`a4~^;QZE&dO2uCHU^q5|E_X2y8s_|?Ne{g zx(=El9n$Oly**6mi1R_>H2e&3i~$vxIpC%>n`i+tEnO-FQ_lc3bmWN7X|_zS1y5Z@gY&T6TLQP*Jyczh#4y4QoB0T3v~lJ!`&z~) zG(uvF6x>1(JiPuYGUqrM=(*65n985xP@R)g1J}0nBz|0%BuIq5Z54CaNA-Ia2RuH; z8LGqpfStSOYid^HLyQCY%J_~!YLumG{l3k)156wb!933N8h{qDDf_x>U{e#^kFq${ zt9RT}`cDUtWElp>FDH0_pU5Ee8bBEdww?Z3Po6PG$+?G=O@{T);dvfqFAa}imhz0t zzW1QlI1W*5723a+76~kd*G<^X2;D(R$>ImKgv6pelNgQb)oW-21y!3!Z0stQHuXg6 z6R@CD3rResgD=jrfEH7YLnj*dhD8r1w3d+8zo9M+5=K5S3uo@e4LHHLNxk=+AR=-Z z%Xi%JuBKsyUPg?-!>&HBciNWl5bM{bTxj@jGbr&lwRkG!J&fEw=<2q`;skLr9!+nR zig!_cCIJMUE5Kj8@Lc(6EjpnL1-gDYFF(c$u@{G1-L8`RulIJ7DQ{7h;M3ml&6n}J zyL_OhK#?%4fy?}9g&!EJ`Ic*OauJ&EOdbbk{E(cv=6ju4#S#0(MLxkUGezx^sNW(4 zGnJGYs)LaiGZ*bV-2|w+RW~dJ0&VC49Bj_1Of2}NypQa|(QOwxrH79-@-#Nt_MnLz zn+mr#bX)9&vrU*sp*W;28KpGv_o>-1k>n65h?s@$0ZID~oQW^k_GGasA+)r#I&k1Y zkvVqZQ0B2Og_^HA-I3w89W%@DF1`Ka3b?W_ac9UwzRMh?n8$*%!X(BsM&6&%v&TC* zW6j1$?+!_+p9jNQgn|JORWNO0RL|hn?le zxe$J-fh}ELN{FoTLv|O@D(Hdn1X2$&NQWB zA7}ToGS?D)Ke?MvM5eR!QgAgad49^{DIk5w5pU7)6aG&CL3$gj9zmPe%RgnVYQ~wZ zaED^w`U%Q=fhbWS?az~+HsDc!56O_i%_u#mc84xRkHU~d6_?=ArG#a;$kVJiwc4L38vmKH`jh$zE-;C zBtVR*x}VBr&;hDb6g4^8uq5ND6g>6~1%ctSXTS)h_#pCE8|W%2@61BZ%Z4uYy*=+V z-*46^3CiCSw~>DwyIB(_yzbm%g?2`jT0-y7A_H?=()Jx0UfJ1C*gcpU?2#zmB?hQv z?w{XpfND)=`LDNm$?>Zt$&pA;UT8uhuR}~Q~-c<$fLM@{x^N=rM;Gp0XBSz0>W7)_zIJq zkA0iD@8eBmuMc&x*-(47GXS>fW_;9M>yW_tIt*VO0-gz9O7^#;6K4xyVgesrdJEP; z^O6jAq=)CFy}x2{I7nW8U@xp+?_$(8 z7|RK}cWPg-o?v97$`~-G2fkFctDGI53ZLXQB5$V7FVd#?gj=TOXJ+riB{EIWyn?$5 z7)fI@uC=LTmHSDU7n-ymfylyJEFzKR3R9`5#oI*lKNP4M=*qj2?`!d? z{dJcgB5oZ6f*32+I^Tw?1S;z@Bos%;LyYOhSt%pX@2|$=mot2dth{w+SNhs6=+d*9 z#oH8=ucsq9_`Tq?R_}Qz!P#p`RPmb&iXM z(?oh`784}!F{f~|#8jDmAmTsZk)b0@M5Em#W|;a;0AnV8lfs?daLwdK-;m^Biz^~E ziGmoUQ9#}Y86i4-gXw%DR(-e)j08sI%1r+_ajinveVCS?MS-Fy6TQ>IWh2_VA-|Rl zegGk3lPZOMdS;zqp~H1D$8^{3zHCQc+s-$}RqKeZZ~#t=AMj#R9!;H#5YJ*s;@!l? zOZx<&8Vc9Kx_4aMKR?o<%TO!wC{(%x=Ar;>0A;$3s z@9@&6>*X+oDarInqs>q5>iNWWDnqVCqy}7)HNUTGndwep%#m04d0fd;S7JkY#GYC! z_g0y>jVMaRFz%D1vW?q&z`Tl92L^BtRluPca3OsTTEOZMg^vS(Ix|%T|7ClTEm_)U z#j37`3*Q6|w((|nPLe4fkfk<>lut(3x-?F>i*ksr;>uh$hxcLnhM5UL%u(x6%r=P- zuS>&3l@KoG6+hnCC9pLeh^b9h7xM61RQXYwg>HM5!=zh}TYfM(lXT`nV{U$9*K(#? zbbnNNZ(a~=j_}>BoTcu%jG&DSm|9UqYc;~w{+3u?455?0bW? zrE-SXm}K5BMjuCB7@%f00P=m+7enxWrR%j~FKgr0sphWIDJe7MuU{ywlE}DSw>yC0A{| z(9ox=ZUXMr(X##8(Ij9Uf%6C3lafcesJF)EZ)sy5Qq$;m%u@y|)DSV1^_^?4tIvnx zg|P(9LWv5WiLPIF+x(hP+`0)r#t`;#=`@GcldR#nY(jh|!8OoI1!I6UfyIxP)-`Oi zImU19-7ez;DiXo1xBrWohpC|hwDy82$=6jBuWj@Iw!^V*1P&U ziW@+6*neVaQa;9fqfej@)EoQ|V7G^Y8>cN;KDI*vE~^?2+=fpsMXyZR4VW&D#wnOH z@1HER;Zep?bo%J01K_CA$Dq>|IKh_S)&iynf#Hg;txIN<8`2%|>@G&Br+b_|d~ex} z)zq!*t5Jm**GOtSo7P3W1^1uB7K`7gfV%Y%x~=@H3I>w!e!5Z zlL42c%xjdMyxCrT#ddaYyhLsUKcG*xCX7R2XS{QY}L9;S-bc`nT?GAuQ2Q17YG ze4d3R%~Se>%8pX2CRD2?XgZ|)#tbWQCK$ytHv+qXxLdz)5Fm?T>tb*HJX}hu1gh_$N~+quKV?<0wm-M)3*k$yCfnqBfB9TsPb z`ORO7V=I|KB$6@dzMee)IAZd_Cxcf{P_vI-I^Ml$5m!_#1&T*R1ewz^JU<-G3{t* zJ&D<=nYKYelkeq<^lJNN4oZlemo!ItLP$_*TmZ_sW@unoIwz+??+;4tknt zSVl`u3Z2~(r_ej2s{UGjn&uMqpA%%HlQ0u3{y?fpfQo7DZ64W^PDdFEnQA6XV!=DM zq|5g*r8icly0jMTUJ-PyX28gE#QvWmyCp#T#ggdwYfbZm_q{yu3L`?an`|z!bMYtR(4O4olzIU4FEU>_$sG7I)*UPftYT`;ZWTF4`_e z6go7$JB3lQ+6(bj@+2vKUjF{aeAn_m!vOV+E|?1-WCvOiic@t6W&W@8925V zu27CVji7-6aHqkfS4uO*eX=1nfTbw2zP}xAdLG63}+@|mG zYErcN$|q_HRen5!PE_*ikCFP-*<>_aD{Sez|vAMRLSas6!- zaeAx!OT97$`Tn+Z>7@?fo+iU%u6nyoZN~yWD)?g;aTS-UDxJ;j{J3%Ce^GXKSrYZp zGgH~){!)_g)wnn0H4&UqeI0fHhAAsy7*zYFjDUz&RfU#e$(JDY%DZ*e#iN53rYuqD z)epQd#$$9@fUsUnH%=0_&1ASxJekf7gGLDIgj@b%o7p2r-lOXRkW50{fe%U83 znVp@#hw6C{I<>YX#q0Jbqx^$a@Z0Gvgv0#9H7E422)j>6I_k$7uB$13Ax({bivyHm zfqFbV-ACA9D?OyRp4BaE9`bBN%K+n;Ib z5Vfov(=SMbq}6YjJm_CK%YEs^iXDYU{lL&~Dk(muIWO~=WSwJ4{v&bsU_VQhOlVAw zEL53p}a4!C8RG`75z3O%*6uJrct z3Nf1yGPb`$vss4}msZ;2#Y;;}Fb0$DY*@N=9AJTX+}i@T*^?fH*-8vxlBoiI$hdjHhCUWOtKH`6 zjN0mYn!r8#5rKx5r0zdeXHhla%Z$}KIaG$YBHjZ33>J6fGS;7OI=3`N&;lnx2ii(l zONRzj_h9i+H6Ec8=`sQ}232!0O}{a88&DnTnvvCht{aHA5kk97;N2qGyAN(I-kJuI zfJm?R@?g>7=yc(-m1=x`G+)$MwHcjDGq(?~i(a6%ti4ieM^$0xX%lyG~ zB2KVA23p2()O9bXZ~lQ8KkVT47cpn#1ibfgP9axFe;4JGpJzUGjWzn*yk z&i0g%oLWLs!)HrAPEs^8gdgsebWlyRwl?H>;&&F)j&??91`baw*7gKHA~nX6kc@sZ^ z$FF)5v2@T&pazZq^{(C=D-QcS?(a~_gJ1xNZlkaa7pp$hSaoCc)>=ScG1M|#(T1d- ztwGiH@xv>>?Nae@G=C$xldARSzL}iUe>2uCR|?WA;DU&_A&3JSTdME?O{~A zMk7*R(gF6f-HNx2gJf%lgaSvhac)+r%K7YZ&wq}r_#WM;FXHwW zp?sK~boEeW#hOu>ogp6$l}pLKdu+rJWGxmYnPrTlc*DUC7|3hy&-jDQCJ0JX&`+Zw zmu~chSq_RW{)S-?z|%3o_+8XjKg|=QVgS}v#GtAeBH=Yy30XccQw|7Yn^`EByH^t( zK5C*>SOy_V(Zqea96RpG*7ga!>v0ekBI6Z24(Epy(m*w5U>ptm zx#P-FYCr}j`C=z3Sv;7YRy92v$HUZH{4F)8EDQYtB*lam#jVf~Uv9*rHz8E2;_=iE z2Pj=&6;Pu}7*LP$6Urh=S*1qloi!a4J~yhee%9e;DGYUJmb#vQjkViQf@66uoMHdX z%li?rH=6m{zb_&kl*U08A46s#wB~~j1$mS9ft8}G4Rq31?vPOPArUJ=cLZUXLqHdf z8n5E${O&S2)`=j}52zTMolr})uBcF($_#5;(3M*n7mU0bj~s>+A|vCN($iU*!XLwB zPj_$EN=%+HtV1b`=>|C6jF%jfKbo`uX9nMpUI}F22U1J8k^9F^j`?(NFEvZP# ziGF2%JM6894S~9^7JI=aaSFdkTs0ka))hDeTo7$Dtq(@rgY}Kwxdya>e_Bg=S49)g z;Q&vZ5jDKqykyta{P4CgOe5e*D9KPT1MXb$qd>>PR8a|Z3hS${`uVdhgMF(1gaCnw zgMQSVmHp4Cr?24wVstBZ-RUfT{LKRC5LY9$7 z26n<8mbbQTm1Kv^o;4{Sej2GYLu2R~njcJ$ zGtfmUW*ikkmqfm`hDw}c6*anfu{-*n&{NkNF9saV>)=k9tqjdBc8n*k~I-u%T%nMu>7tLdX|fc32>Bnl)J@H=hae$ zlCsIrVpi_A{u}16F^0468m9VT!?Q@N37raBk;PagQrnKnkhueh z#6E2GjvQ_$x5x3hXIs4XskhheiufIp-(`BP%VQ;nH3NI{A!LvTOUoc*j*dHA)&oOi zh4$n{10M|$@^{l~>vJ_{A*?l74Y6RGwHdRDDyWkFwzT^k|x1 zN!Sns7g0eD&t7%8Nf4(t%3a}%Uk`}7E+ZgqJ(K#J@0W9Iv82GTz2Qmioevw?T|@?} zfAQzRKb^3xfZDz-uTzaaH{-wPuXJi08as-3q|K|0L`3&qsYx;OlY-rY7;uy666)~-RxbQS zHGEy|=%Gf5zfoA;y@=q=@G9s)8JPn$J5LCwPE@W@be%$Q;927z1nKTNYR`EMT3@)3 z`GRiXE9Iguh0G4$p5S}F5`7kxP_6NA(U3WpwS2K9A~OpT5(_ZK_fIvIs%Ig=d)7&IcT7>L^8Y6FYR2vmKDtgljySI6t)W$48$68!%URGF*!?w(Ww3;OvOFt%k4|YrF(sA?x|bh9CAkP0 zcn}&)KJ`)?DdYX*;t*MQ?QVjdliuxyMddL12~Ef(%4oV!8X48al^pJ{d7qPG0f$&b zn}&)qA2>!lG;b-zzwv$`=W{EtT~^FhM~sE>#ffHDYY%w~IyBW9+AqF%LeDri?OOop z6Zc+t9%bUe*mL~!AT}>3$RJ~~SGz5|^X}4p5i^coC_U@DKWDnl@Pu0;{den1g##9^ zKeDmGc)%AI`QExu>%wKPvtiAY_lC2;s+w(koP_uc?H4{x(am4mdZGZvzN6vaRz@@y zJpJ^jcPw}cb6iQHDmen^>N>vOw~?WX6%P&-5f365u=<8!!qg^iRMx*d(>u_}su;pH z0BH<*iNq>UcooR*D-`kbC?PsZOagT2f+Brni!Bbk1$HGo95=BT1k(hu9lqpIntR*3 zp`VHWc(srg9V!<=gZXNt5O&%m(0SLfsQ4K&dWWZ*hZr#=2@M3E%1MByz%;`gOcpUs zz><468X*h3N8v{S)98HlE-$v;v-#gV% zo~sjRe{36_(s^E$-oxjbQzQAQfz*=3yb!Cnr8}Q$=Qu8m6h#x6)C&5QjMUGb!>;&c z$2-2$ONTlq2_m{B1%=wpPCzZlzE$f_`|)zU^OD_Iw4xje;hnak5^6=B1w2Fv8@!>F zi=?p@+;34lt3Pm2qb+$lIe->nh5jc+3HeX_ClU*Q2Vz{@rwV5OO6ZYk88A~BMI_=g zN{HljXyfTlK zjYdxq6@aReAWQLZL|M6a4ceuNjmnl$tM$c7JENHHWH4qyjps}!?>zTcFD%6$<-IBO zQ$vxaO0^DhQ3g8KZrYu^I4Y)?D>E})$L{~#A#1tY21WbW3`@nwrWai|U7@6BBZ+zH zCwC+jz-_w6T=ygM2e0}{DkCy=l6?)rjV;-CQTRK#E_nu94#-K@@|qF|9E=m{0q0aN z8d@GS;IUki+Vp-p|>ByK3Ta?YEvkF;Uu@{9gj=qtoh0GW9{5ZtC zzFskHE?#!gW8X)XbZ`)2IaXIC0k7&`+1-j4gz$1sI<4%iX66w&s?qp6&^hB*6F3Eg z$uh~jKW06}S`zA;W~I)}JG)#@Ayak|e0n&@Nj z(YhSz*>h1eDa`^E^_gzgf+X5W6naD^DWTCVq0JRm_lp~qLm;UbPx6U(!sX4p5cu6#JF|8q<>FLKjU( zB0F{gzbf7CJL~!fwd~)~*0kNbjXr4JAqs;mkH#Mfgf7yR!=}5((2d4Qj-;Vg?1!@r?W|U}JJY!V_tqKEOfPHk{ z#p$uWeG*A8NQypo7oX#jWbCa?xbCCq52Rgh`oSy}%frrch7+qA{QHgv4G+d#%3&DIn$`okYxqt9A1-sOY&-X+!Oa+e~5Abtscs z&`*|z%6lO@O6THN?{=j5@XHy(UMypnVg`^{Pc63L#xov9kkDD_fM^Nx$i!N+vr%N< z^XlTGpicBoLXW>Qw&ux`Wr?n+mP6AUy>FM(IiGOrxj$Sp+3Uht;uzFZxDRe_J6(VM zI#nF+^DAFSCj#$w*t>h(&cEK3CjawRnyBl&cU0;-)-py?HUfya6cB4&m4ryjYr-D} z%k0k>vNnZ&rT&QUg6RD>7obHAVowyON5UR4o?Kd-I}o8vy-OX{nI%F25-zBjAqzGb z`ZxB{CSjDmxrGjMpGqeg%Kxi#)i7{|bN}4|;b$z^o}Ql*9M^mLRc-OYpV3yLo!TGQ z!MmgG?TBFKpRL||Mw};?+YQHS=Qu+|WnBSkLLR{>`By;oKKbYmk>8a*i)}Sa0cWnK zX6>~NodxQnClLQQ@kE6cGGHr6kTYWPP2INUws)cC00nzL-M(Yll0=pp6jp9BTahAU zSHp^tAII|SP#nTxsC;ymAgH*s9PjMsN`-LRT5cd>sILn3}Ou%9bt0 zo1RTQaujjRZn5WAqDIzkM?MW<))mgFb(4g8dR#G1R`S+%akYNY_x@*ceMF^=?9Qsw zYu7i3-|xgaptG)5>zGFFX|QuWBBkGFdm$BCPyI{X6&*;8MJ9kyg71zc)8C?|3KMv5 zjS_`>SWk7003CrLmdYyBGN8}$3)bdc9)nGTQ*69A=d@WIpjr4aNsoaB;gWme4s)Gn zncVz(Y?Nbfb*eQz7cG+HzWKVA4HSt{lUc8vJ0?{_zgg;Rqik>9Ii%Vz@qN;_pi%eg z6*Tnd$tk}R()N{sc|leutbb^7dGn*!=o+O^I>3`NCx?B&U7p|X&0}Zih#c%V?YSuM zv)-6Mvcw*`9}~I-|LKW;GDX)HDd|e-W>Kx9xP`VHp2})W;q4R#XOmg@6OZy8SV@r4 z;b6TD?)T5%D3PS{8P(bmqHGX3=eOQqG8h_D&oxta0{mF7& z4c@A2atDoH8FA=5LN(zbIvVi~Z5q!wQvdyIcGZZQA)-hL?>tJ_+ywc#JBy9C3lUg2 z=c4Bjp4nz99Rw}nEb6ddkRB}e1K=BTQ{Z=dzUdi>lq*;QKGt~ZlyjWOJ*l@wv&0dX z)x*)2-5!-aE}UnYcA?ilD&g`qSjqINu=;}RB#)%@y==CBF%@?Z2o57*+maKsJd%LBH9WpXd8bWdML6wIO!uiAXR%eDWU>Q*G}Kuw#H;GFzbHzoC+m^ zO==AK$c3Z{hcvy6Fl;Mp#Zsevtltkss2!ewT10eL!?UYCZ$L85fod}4X2=wh3TI() z&n7ZMn;6mt9k{dAt8bD2rWZ<*^SuNKXa|=Yqz1j$m~Y2|`u>nkhU~Zn^l4r;7?eQ% zhDg1LV7h&`51ofY=$Bxut$a)ZSPKPjq$3Old=p=dPx>aL*Dy>ZFF`yJJkE6MoT^)* zJShhIA1(ZO-R*TatG^(RofpiGzrF|TY#eoG-m#{t1cg!uO3pQ_b7F!XzBBUa+W3h4 z*?ZQ%6&cGRP*dIZkPk=6RBL2z=5z%2qqU&Y9w+ffhvKp0sx}DBv7;=G<7N(j$5=T%RykpXaEkZ>`x zmHkp+Yi*gAlNfcPcNd19u=|XQVtBO%^=uwrr1NF%pQ%9uW*IhRReWYONdlrf@i2-NrN*_~iwK-*YkQE2A0# z2o0v6ItP({4~2U07~gy-e-IxbMEcWx;iFCO(ZiN(`BA}PQF{E;-^#0WzZI+mPdKaI|c`)Qk^Kq?@ZSCs|D8H}TY-2ToHWq+dLS)*W5hFtwZn zkH2ddm9Yr?)+>5V3pTm5i~!@vN5iUi*ZPiosRc z6a-@?hj(VJ9)Wm9bjYxQ@_4p30C73gxCk9L%I8wWu`X+|JtgPv<6X%1S@PFz?h^N8 z#yc&FaEQugN7m4u(f%p zLMB$%Wn*P=N#*yKnAw}(UXNqhGSS#3``iQS)L-d`j=6S*`G5;|&E++F|3U8vF(?JX zW0zv?To0p51OLnf)+l$rFtajX&s@`j)$n?>I_-z=?VOQ%USc#EM@o@er<#|)gtS>_ z=^f;^rN|d|%q@XLRy;@a%|f(q?;h#T_cGJ0Qe2dBD@jB`Nl)Mi7M_QyLWa|i`5dMk zN)Ay|HA7lw=c1S*d>5Y-Eh47~|LZLPea)EFm$oE%oqe8n+!MeGk4e=;wy)~97V^~m zt+`1~DmoVVTJ}q<%yp>-eNRIyr=l-`a6cCV>2}F zF5O9TOLw29fu;*-t#wTcRgz86DaCTs<9sco3=RIM5vl(8q8QKVH0Z2!+r2qLj*C4{P}NyF|rn9i@V z7K|h^_PX{iWgnWq`2g)C5SFumiYda(z%-)NZ#zbmg zClfzH9iy|N`wnk=r9G389C@BFujS#?u^N9welEE7_ETq${>Y7{MuhU>*cV*wH`Yp04f-*afsUPKtc)J4wSE3uQ8 zD_>++i2$1-&Elh-meM6P8jH^lG@!@!s%+uoMGW@35^xf5=|?LGxK5Gqz5h;zDM$fO z_*?K)Gi_u`F^cmkI5={Ai`>~)S;lV3pqq#-FV|b@ABnfRqv!XneP0dg|8-zC)jA!Qe z5R*KD=C6OjUE9-G8lhQ}?UB%17E-!b0uMCegfn%*aV@U7!-IXH$!}XfL}&3vifjYQG}uXnRYff+uBroe&$e#%D4b;1rHjRrK9 zzYcOv_t7fa68Uue$rmg%V1*KHSgLi`<7s^WTM81io+@$?z`Dkk)6xUD&+tf2S&WV* z<%a*Y1Hn2~MjOPSik2`8Vgajehszfh+cg8Pm8k$ByP2#NmDIvosm!uPyIw_oF)@$NCOf;zUA2j5Mh40Y<4 zGYJiC7s11%W-9QfDs&C=f!3SbSKoP|+KrF&Sg2|u`|SJ-p%@T22e(}LOs|F(P0b(BHp)))OW!>wD z-RMAg>~c%}Wi@y}tVe40QJ(8OKFG_pD1ECyz4x$KR+HNU|5r+28-@|0l&FkI zgyV&BlzR`wTz>~|NXHY6?c9fe4N{U_y%?yOxE_F&2x-1@)xl&3?_UkLt-Xzl-VNkA zju4Us-kR!($n2w_E01_U9wQn0YFrW39P#=g^PqQi37H;gDNm1hGDWi%(h+>bZUKKz zP=4+c7c&CY>~x++#BKM{S#4G^tMjrX7zqF^;Ap|#L*sk)712Qr&}1rJ4X4k6Uv9?P zbKGSk^GQX)n+!9I7ktMk;^!5o=S0fbYA$nMmA=N}cx)5Nbblp=UmrF&`Te%{as=i1 zQJwCVc^X4G(4KA$gGAx~Hp+_NhGY({nJ8yU*G#D~H|AkM>@<#KRv|i-BmhG${{uekK_;c=2nI| zf3nj|Rk$~yl$;}l^W76o&rA(dU#J1v2UoE|yn$I}dl|-@=fWLx*`g#ALXvEzcou;5 z>#Z|QN>X)elf->D9tqs>oC!P!J#u17F@ClUxlx1r8R=`O7QQ( zlmuq>Y-xCsDX!7-k>!w?ME<1~T_M(1kA5WR{P zggO@UKykO%r`=W(tCX??tFfV_O-uPMrk?6+lZtB9eU~NuHNDtTQkfEZiw8QDnuf?uSL*;pjnf=| zNY68LpU{k*S+<)uWd(>1^9gE)NDM1~J+BO#!h3n}gXU)4Fki!@glSE)(l5njTuv9Z zMEgFj*c@#2oJg(>Oo$*Z9FCSY?T)j!dmBE9_#pJk+N|{`OCbDL&sz0oq47;nG!wBL z;bC#__8BTqpZ$sQDcIlop>T5g8p84kerB@I^OJ!Q zCRLL3=9#L4_@B^4Q0}a$4(!^H!^k?pG&RmETRKlMrAn3RZUd;WbWq3}zUifG97RS) z9if-oNr@R8{(r&HQ_O6m$YjqWB}AuA@NyqSM1?OkDy&?hssMIl0lcgCSh5CB-#+N! zFp0W94y)8PxifhNel$0kw}h3CYUdv6Vme$1e;5+vMnpN=JYI<4~=NkA}isYa<95B0;hQCW|fBq_hd zEPKoC>8xDTz!R`>Xn2aDCNwJm!%%=6YMXuVQSLwEoOw7fbeT7w_d-dgb#e4xv$18b zz)yjd$bzRi^YM>@qv-;0L!#u%#fB}DiujrvV_7OvJi-QB|1^)Vy~=$gwq?Wy8gTl` zrNz{U<}566*k<9p*DtlkF&K}L4Z}RuL;`-z{MgUojqN{i<5?2=K8V{x<%7_iJqt@a zNdfP!_yWfg6-xozdO))I9> zdi79{OGX&r-#<1a1j;xz6gkWUj4jG-iTnGY&+%VuE-v_=wL^3U#Hq5i_pco91$4?VK4gcYvU9K2*pe= z7h0Kf?wt`R6*JN#naP2746#LWMP=6tAgF~elrc$ha0-6XN_-PiloJR0pAnH;aAvJe zwA`FB2XS=pc~1UpI1H51wDp0Jca zK0!gc;vTuut>IU+F-su*3>k;r{PJ*~0-#P9BXy10-;d_ur{o3$1;Li^!XC0Laj5a0 zR^l;)Ll z?*lzYa~61KQpR-z_8hvV!O=Vegt^VxL?>lIRC6rP;PRKTK>`ok3h4`-Hqw_@`PNVr zA#=$F9Tbt35xeHH2^Ce*{Da#wp(Y5|`@_a3?h9gyz4D*7jd(0;KYc)fMKJx(?j4R6 z?;`2Bm|Gr+lji$ZK{^CrvF9YaDb^14GI7g`1zaX9Wr>+`=Y*IcgcC;xOYMU%F|(?) zMIwFckw4csK$X{+u3b3+^jiHl#DeI6ELzQ-Y+rPa^eUX_Eoxz(I@WlF8>IXM@pjle z+NINrWhFXoy!0?EHg;XNV@&hBt1_o7^(s;32vwCb@wRBfDym@sQT^YJSW{ooWTqoy z1G$5XaM<+fFDR6dPEa!65tyTD#lIUhHeV2NLSUz%5c$qozJQ^GZ=ljFB?2UJyV>U? zg0~pNI}ru5Nt75bzx+6J(CIdi)d;MJJAKxrBC5SVJZ6&xIE{*LI|3U04Zs7667X6d zq1t@kC@ggG`G3-zXKr*prgFO2!*nz6vc|g`8_r_%d1abvNGnoz)zW4l0{dpEItQ6S517$u zktQW7chTypH`kJ>w52DsiZ)3Pk4PqNdV7BAwSi=CGuQ8*6V$5HDB**mAwi{>N(9O$ zWFA*QpG@ZPqST^`W^-eC0v(uJVgq%X7^0^*KJAzYAq8lM#}5r>D{9e}@N$w~m+;-lJq^yLflS{{jg z`-SZDRiR>(v7!X35~j1=|4M*F+GM@01>UUaQ(0lsmM97-1%x_NrlD!QD zCglRUYpV>`4S#l@nBL7q9C4;#p$q40JaM*x@=7$An4n!(4&&ZVS3^hNeg@G1GYZLb zu_$yQ)hAkBJ5}PK02ST?2W0RMK#O*JBa~aV!a+~t8m%#))Ph096i7SBt3%pX5C=DD z5rqH-LTqKgAXxDU{GM#u$_4?gi;|-!?r=86>WPS`Wje?mP?UkkR(KZ`kBVpcJ#2gj zU}BY8BE&49GRk$qz9YexBdiHsGVv*&w_<(HG8Q%Z&TobvTzvCKdr{pWpy^|IsOyN_ z_+g&4K-f$}Y1L)md(rn_xmw8O{FPdh5e2w5D+f^B6e*g3dgwBy^L|gxJu>wG#hE=a zC7!@>N=@+^(E7uR2OpTnge2&(uf6nrpMs<0dkRvHjWg@U-5hNPep!aY5c)G<^og!6 z1@bh=0tDV(NCJ44pHjoJvpL`g!JVV>J-Gle$r^pMEMV+MP0&Wumi74u`xt8VU5t(! zfQP7jlZCM(CKZ(Weal2f%zw`D1C9PWao6pWazk|P`~K`&?|u4H*J|x=dY@N7S+rhG zM5sc8H{jd2WX{)?FMkwSQF|M2w1N~{x^#>KL=!~}5DGUHF^v$w;sOWwbBuy8^nMrs zc=$PIq1GjgVuh__eE<8RzMzZZpJ9rW=#`$v>6t73d}nje7iBkq--%J4?b1$>ph=Y( zw3!FjwwHhyBnlZU$D%=DC4GNWy+cJMha54bH8o0|!jTm>*HE45@LpdK@n%CJb@0U> z%TJ6WgE9N7e~X~9;I@vqVmxjHzQJ||=fZ$Je#=6(ejmMoIB|_jxDoh66o)Icsex^G zsb`CqlKCcj)VveQ+Vu2lsAeana)Pt{=yRL;YS8_9ixWB2H<;E+GC^*a2xJRdUBJZX z|1_iLx8+`V!@&GNNyf=6CS>QiiY^^Y5IRt{F3HC^t-;7OxPvT&=FamRvVDh|YRN

cVRLYg-|6c$Fl~o|=A#J&MRoWsB6O#7N$<`XMp?A9xvPLRWQmMP zOl$of(sa#b8O&SVz#ZG+0$+;=5W_`ru%v3h^&eniEPkk{Ddbg@=<$eSVuIsE<**lx zA}eUO#S!pB?y)tP@yMWtGOs9~|dCho5)yJ~p%v>uyS|$j_tLEHgp6WZaXgN=9{ICEn$Nk=A4g_?JP- zd@!Fu1YB(ZF%m@pO&r5mu0OtiA+%lDVX57-Wb#zUaTS)z+{9X=VzyFi5>@n^b^az? zzqBGlE&HVS76l5U@O|yJO(Q3mtH$5;zs`m0|Iy@b^<}}UHkFSyPPO3PAWe;2*44)1 z9Dq~|zp2s{e?-Rc%*@Su8!qV46Vi(sC$U9B19q7B<=nTQfWZ;;MOBL3BV-z_Pa`}{ zmPV)YJ^hz~4>6UTW*MCiE#>MH$p&SPIxIZg{qpX01-k9}oz5xC?bPVJVu)$TWT0Rf zuy6&w+0v@)bH*E3@hzXO#YBBJidyi@8B(!y5bHuGYcmtm0B1qh7_Ih-7iEJKdjNCL|6fgsXA_;EZ**o;Kd3TQ{Y56L8_S;NNepZGZJP;tbxFzW3 zvqfl-qqVz{qFQZAhGrTnr3=-mm~%p%PuV^;zfPh(k4BK+a=`G*e;tfit{DERJ(;PG z!KMK?W^rZ0`=6{LgmcjSox*Y+2GST*>a^vhUiot+I?$8ooj0n5t;^=PY zqh3cS`$Y|ZU=L4IW&p#tQCYd%pwU15wD z)kG4?BV1EQLrEQP8T{~DFg3UmR;FF=?Rfx$9A2}bMV!T;WnDGNqseLKnIvbUZuVG< z#=FzuW-kU;yfe_y0$P2Z^Icf2kmQZ5u|lmDh|#001{|(X3@f40iwue?R5rnyyxPLL zYhGyvm-W|9x&{E9hY}p-gk+i9`s?ZvkdoVfzd@Fz(VJ_D386^j^{)<(C3uwbD{OZp zC7nTcj+TX*Q43_9Pk%Zl zQ4^6ykV76sD)ck5dRv_SSX@}V@)-oc(b$%k&aw;tv1NN`^m~pqGZJ{4#|vU$xs{== zz57C!y&AO#61NI)w~b-BkQ*fRo-lX75t31(_=CG&b4sk_81X+{q@@zQdM;`~)n}uR z#4{(s=Qi2dSjm~bes+`aV5#zVWP;maK~Szi*EgrsjHv;6#4JBzr7Bkq=1W#G2M?Hj zUH-JOkm-fi)|p-A0(kgedO4clsP~-fKC!ac=d(joSv>5g@hWgR$>=8dhwLAb+x5NC z{y1vH0lu_rL2@6g)>ZJ8m8_wAV_I4#k%{~&*622}28h{ddH89Hw{*HWJjzxY~C8!JP!8oNg@w1O+Lnr3B1_JP!)#E+ezyfju+$JWW z(rZsA<`_dMz?1Rq-*ptdbyA>84=@isOyHQycxG4^>f zRs}VZv$3}XT{Ld$boR;5-%1*6DR^Ipm@Z@2jll&lmuTAhq8~C4hbkLjO>Go9d^4f4aQ3V1nJosiSP6kYb($BCnlnvgN05e3ZIHJuXy>!=RJ2!o`y>5Q)ga z2@kGQvT1e-~DIGXyu4{16#OnFJVqgmG)?mLT zRNPW@%672K%)xq-Zkp0dS)Jmo!Uho$%L@1CM>M^^C}$AE2MyqMumTxFL%8Siuq3z0 zbFL{*xUJ)$IPL1Bhr3?Wri9>p)vyZK(Qs$Nm8XXBzZ%F?HU*s$4@eiIrnWlt;~nHZ z_Mb`FeEn6omlnmP5eh;8^;_oare+(9!YDl912~sdOP@M0mu=jY%6q{k{2=@PPqlwe zGTTo)(dMbx^%v<-+Vi;gSa1}fnf5uMfMw$eN?KuM^9JHyZ%=uoRxv@(jt}OJOG}g3 zw}AwDMLjSDYgr?!$5oph#+#IoAHZCQNy|-ivwgq5BP_}^@m+)kwni4D*z0$4S*;gy zq{fcovX({-v^Hl68=^S0RGkE1269A*p8&t{&45%+121d|b|}#bud~p{lVdWS>8fUD zLS|Q(|IrSbw*xTHRm9YOD%)8t)4JtCnlR&Nz-MY-yYPz=flo^}vUAaDUgO8!?`a;i zhfH|93P@?h?oI9=5mbZixc&lUUnh-WPqu((UnF!!9V^~!t|y#81FLttV9Ps;5rVZh zW8Q>3fFy((Y^z@ATMbp8LKr4k-@d?|?R;O$Q#yg5nS_c&Nnm~m#(@Rt*NHv6&t*_Q zc37}1gXD4XO~p~{=YT5deYN;BO|@^hnMIg__PKry`^?QK262aQGlPxoS6N&V_HClG z+K8D4?DMD0Ct0^d1HH&6s}w|_(4=iB0|$em#d68 zv{}Rt&Wc(itRhmufN%5Hm3IOLv9`BqEIlss=J>w8YVE^$`r@_i{l;+pLC=o{GQ5r9 z%{i27E#sM%L1hb4T+DVSmTWPM8YI6`PQBcMSx!5>P7jn7`lx|n2HItw;YVe)D9yGP z0Y`Lu{<1z-TTO$^6x(*&#!g~6xU{XLnc4E{>NrH-*%nk3_g@Aq@440CQcTNa?3HX* z&1n4Vf`A9?1t9>bF2Zp5ka2k|?jfUy zA1)PmH@4hkiUlUm>PmE=&_+(H8!k3Fs3Bp(9YeY4aCd#Oa3$r&^%ggjt3B@b%OP** zMh{sn%Is=!S{7ckZll+QZc78~=5;lpDPj$2FOcu(gLWq!8^At`Z6My}{T3m9OQx!}Qi94<*chbgNZR!7 zmoG$Yj0nRH@4yUwIN{{GNt}6@5tss4E3{-du(;oOH*O3i(KAjS}085 zV-6cnP(an7reQ30Lf@_3&4X=Z4{3WOs8$_kxfzAoSCL9VOAxaQhv!;CYuk03`E3;i z;Bd|C6A^H(b|iSB``XJ2xcc6#qkqhHFKm29tfLRls;&Vs(OFWDRHpJD-}7bPrt$ZK z!Ho<1SX-KzDPRnM&`SWwOc449NWTfrNO}Of=(;|{i>zmF>1CyUo&wz^9?N8A8WUjc zzZro{AHqEra%Kt)(kfjz$$`sG;LJ+K;p|kR2(kH;@aEeD@Lhp8q7dU80tp!0a_Hng z(e95-0=4I7s3JX&JD73+pBA{@0v?WVCs5~>-vO@luT*S@IET{~JmpueM|GN^GKu+k zp5K@-#3upd-c|cyh#Xg?rN0z@@K0>c4n!bcl-hYP7*wS*UihefzSw{V?KALzhO1z& z+hCr<|DIT`v3*R z8Hdsp13+_l?6*sez-aC$=L;j6i@VpJt0kuJ*KOmClGbzxB`U1I18)!Xg$kn#XO{0Z2|s{FDI6;;aH079gF0GufuwmPg3$bv7Am)#d~W}`joJ@tjE9uVAyb9f`rL^icxAdx%Tp@ zE?o1^$g^%FcXFE_KZUjnUx5r4vQZSHvwSq-<+YP5g9Lz^**5OqY4fy_F+AtJBmGyN zKP7jvE=ouJJdfr+HchSu-A#CfR>(#S72Xez=oDfGf04`Q=PqTls^SiuLnvcROMaf& z+PFG$s0sNM%NPn>hP57Bo1F}|tm4zAkAExdv@;QwNX6!r|NA1XGUE<^9d}P^-V@j9zfp^GcK@7=NWwjNVU@{Y@qpPq&J z!l@SrqqO9f?ZsExM7bz2n)@yCJkvS7XQ5(u>2D#b2A9TC`>5+T8X-^uPlA#fd5SVu zm*C$EKbmh#@`Keh3XvxXh3Iu>m~NV)td#B*7-|xoRJ=J7XQ?3COVXj>dqfBdY@92aq5}PVjU?8-HO)*Ca6_vlmu(7 z{4)Di@RW(*1$LNj?>?80FJX7mE1O_swtF-=-sKD(FEJvWr1rrly54*Ye7frUdPLpW~@I-GrGbo5GM-u45Cs#WxY-Vwo zwTRCR9|!OrP#pRVH@fFllnj3X&w!5*k!ki)nlUZjLv_5+qSkWIv$Kw(6q$+jg>3!a z60c^FxQF60W{?gK{>|}b(5jP!;?`c~>3o5`pqmsnp{pE}JuMxjH_^L0)UGO)d-lp< zu#KBE6tnr2II$Q#iwQQGZi=35Z&t+oZhBCGG8fujM6VFycXSxqyuDO?yDapmAjpjO z;|KK18gGdr8cZ0VjMPiVvhl(&b zs{v$)bm*jG((M!uEDvFj*HR3c?4h4!OL*8lNwZ+?JN-2mH}{IV>e>TWIi}Sj55We zcc7}Q%2!jSN-8C89l}HMJkjo#tqhmHPW(tWZD#(}Z#U|cH`CP}Uc*Y!7`78kf>rt* zp~;-C9A}F>w~UK?S_{_87XEunEbqF}PI}Fqq>tUNrEikJZnf_A_818dJ~`8Ca&i4Y z2s&rHXpp)uqgQr_@)+`L-GZdtkn_u?fKFBhaTfrt34Z^15@38vOv;@y&2FYA8{hs$ zLdLudROCEI=5egi%cv*+9!lu0MP#_%mVW2flu`Omj|Ss8QResX_b)ntsDeBD?qmP% z(|!2Tx25iu@NS=fod@>kq;n(%%p#-8u2S>+=4n-@FMkFX`#)PKw_Xk8#_EB(Lu`tg zXBd0Nkm+Tf#x8sR?%+Z7=|bB*-sLrv;mFZevj)ddC9FT3NtQ~)mHWPGAJrDN%ZSxDePv(Atg6+JMYwaLaRFJE!!p-{_KT9A$JoDCUEeb z_Q&;aPX;Kkl(b|>{eB;sz_R>)>g(Hy`{iu1q%}rkz&K5Q8hB}dV8UI8zfVAc5*cA!&q@#N`6Jey61Jb`Ry%V*n`HA}D_vzv zG*^=11cB-sXaz(c7W8LphjLkA@5tFVD~bH=p3IK7Z1Sk|0#|7arau)7TWx^z5E{FO z-Wh%g#-v3tc=O6G@hp7mZ`}C_o;(_QIPSlcOk{MchvBYKMd3l-`uL^6w#`l4| zJ4a0;3!NA;TiLfStS)v&)YeFZQ-?sQy~!D874{f>#CzJS3hpg6Mm}HyD89Qa&Mv2M zWoS`of-je#lMWVdn3kJzj*q}seVp}#1==w3c9c6~+>1?bZFzE+k?fDf+Qv#vpkfW| z@pxVCOuz~fand)WqE6JDdk%wIBpSnE@`+|dX+@Q7CCceF9H_;VV7Cp?fEO|Lk39vi z_=^MsSg4eSl&u0j^HKz{$SmiAGvYiL^;RM2&8vHj}Vqzz596(-e@dTwfRsM{V>J(&c zrhOk&YgD|T%YI!3O0Rp-!wmcs2)vUNLLvwjk+fq%ra@`JS7#OQT>8Lg%a6i8V3a_3 z@ntXHvmL5KidD@in>h~Sq6yc>g6BeCh|LxT@^=&BH#4SW_9<+_;~!69eypwRL$v9^ z6Rc=9r803lD`q{m)@CpXv<$H#I-&X=72D3B!jh4+ZTESDICwVU50!o#D}5$^oFeWqpiMpX+G;x&x$3Qg!(@+zmdLQ3mzh{3F6v*vjG zLg~(iL(P(=k&w&3qY!^>4kesEC}Z6`BS4lAFtH>)9B>ZXB;F3N$$5_KG6=YY1l`EB&#`~E$FH}SsKw~>u-w#6ucJ(xd7R( zik73kpRoGEZ$un?;_;UkQSL0o8%3pjTFbD?CEi$h+?qrcfqiP4P6vCxS$y8`H7lxM z9)_Zh%+>;BbITk`>TNJ0-Wt-w0jFegx-8rR_^+P?E(LEU)kA|E z=mkCvwx&;I#0(itKcQ`5*e=K8lZC;M<5gjhaKHaEw=I%!gCZK|ia9n>xt;5NIHN$4 zl$tt3wFe0{WtO==f|0fBpNCel2R*man9R6y1#c|^BgLN(XkA?vXo7Zi>YWHa;|-;C z%Z-QS2vghDRdjnI^X>5dt^s+Vm( zMQavJifW|?=bcLRx2Zk2e%+h1MF>V&E{vXW4?A@mRqrL$_f__|H^{MM=JcjXQ5t6t z>tFkGmt!01n+=rX?~gZ>P$)82?Pgg{$~x2OMNs!iT>juBtxzEP@RSE!VCbwe+0V1& zT_4uhuiG)i#y+jMeE<3NmhNK)XHPhagyOak`>;{Yz{yw_97PT+;^8*PzV8wY}*IRfPl zd$VaR5_bTYj46H*wLnA1JavVEYTcoZr){qyM~&mJ*2PWvBkF?=(|-C1SkK!h^@3^A z2@bBxBG6S25-9GulSy@|e&6aeZ<IIY7r#ZGZa$x`Xa9e8;7P$Q~Nta_|hNU;OZH~eE2N3-e~i;0lFV)D+5 zT)_=Ow0mhxB8ajo^StdNV~~2VM0Wd}D@4kRd%yJ1<{1smSuF@wgLF&ucvU?ooda6l zw493G*4=DBm`z|j5G<#fp}19-?dB7CWBT$6yi<$iwGt6qEnvK$rqJbIf(I1 z17(uUODMAZO~NEDX>jbXDs>W^D0&lvfO;8Aiba`=Pu4mMGs9S6VxQU$|{froWig7CivX zfzAOiQ78l>;#6W8D{>H^+fW^qVX5&3E=rIw!aLLGmX=uI;DC#eR%!sOM(UuJ{G)qH zrf3Sv^Xnf=MrLsQRDE9+KCSnGO{yDHcp_Px0w8S0<#|U)zd`3mkFS0p0DQ510P}JP z9R7l;bB$Bvf4xy-Ft*z|AA)phpwXYd70YUxgs0?+R{B*nNKa-xU-t!&xHeyyWbTe| z6;}}KoxG06ksPa3eEW9>YC@u+jE^Gs4x~ZYnmhsQTI}w(G^C(WDfEF^U|K;P=K2 z`~I57=oeWOVh=qnjCS-MJzx*c#H$E29<>8_#3GJ;w#O47ib(8@FRuoY2;<^B2#AHF zTi@A4l)Clq+yImgVy8xA^I0BD{(1+%s}y5g)DCGKrbZH_Ofr}X^~lvnP7&~r)8`Lu zJQ3#x6!m)W<6)@~4R~nZ3kkeo9I_t^z(2KIsAd001xD&PDo=A^7gnn1F?Dtrb~hyi zV>f%4qEO+c=99F5B(97f9tABjqs}9NTE~~gWm=9o*#ekZw&s3#awE%}84jNJ!)XBJ zRi%2p8ictYj3DsIr;huUuj_)IlHyI!H>;xt2pU!ak-=7P6-w_@bo>+3jcK!bhMSp5 zLauCB+V6RExfL`1%4DT~MNH|*_T2IuX#y+qIG$*Jy@r@GdPk;BP9=s6HKtLK+!kop4SGZ?U%($#-1E_4xyAX~kq-j^F1AEZ-zR*0Sb?B`*tidSVAmya9(AAn zbi{>H%!x+|T!IQOClbffm%@bjS1_0rx|nuwhcLMiJt3#ix#q-5X7SORKWfFP7gd=d zl)q6j2e#Q)mrQFvu~Wq|0KlBK`Hh}4T~ZEY#-m`-xQJZ!rA@553;#6grCTZR^2k;V z2%_9caT~FIk<}f70-#mNFJ0G%9(L86A=c|J5^0#-6;t{8-{8E<0cF3`5# zgxp)9UzI7}wv>_VOvOYJC=zeikS73rD8qp@Ph?#s71Fu_=Rc%Tl;|4IgYn+4rnvv-X}`IO>7NjcUn*VKIFR_>AUYEr`JkXT?;q&vci)CYmrz ztD{!%lQELMP9m&HaiYL1IDZK9lmYV{pXBaz6x`F@230+(5KD6mDF8!yVrkytg;{?qe(Ee^)zP#jD7( z^FSEu{#JeZ$u^2_J*S44XE^Q7c2=tHT<0Yb7B<+d`^*~%F+EY$N;8QU4DPDQiy66d z#&abnjs3PtvI_!&lV##=#FyyO2)O0a*UsNYbN6~0S7<684c!b&;!1fq6!U&8TdH6VrEfh+F#O=C&SkN^)9bUr|J-&2P zl*O;zTs^i_#WrqU35g9GO%0QXyIzRfWc@qwr&C4Dg;L*hm}c~PJv?-i6V44C zixT^&o7_6@(6dx6qW+yJ->ukW(6nLVvp%2JLET7X7Y`U9=h~JP_7;#DtUC#Ayt{0@ zY#FtSLiZ-%?*u^+bL%frhq4qTq|zAmVTu0ad-I@YgHEwOV;%k*aks0)CIkgt-f4BJ zgB(cdhcWmKd>^d67gaY9(Xx0I>VNV&r~5i=B?V(1eXD(;SjH{K9ob8n$98-$9}HKL zk$GUZ?d2!;yp_Uo-ctzZP_RR>A^SaC5vg%uRDuHx$Q`F)O3gFbs37FS%Ht~qD}uv0 ziD+8bIrBHxd5GMxs2b#tjWF$bt%s_8CHssE)e|-Wy#S=l*}?#bG3MWmO>T5q_b}!p zNdP^a1&zn0JFm^V5o!MVh&nC|9h9khq|#;TXn_i!zIt{{&dXCRpw8n=dP|)5k-T9F z=y*TS-xnH>aSmY{fG-hm99w;Zw%*%JqC^1-O~ze6 z&9NST3QYm@$2wb(w_FP&CvhfETjy)e?P)E2DHslvP9)j_6mV#I=;plAD&IlWY6E|3 zIT*8EgLh}!^g+uL$zd34o^(4)Bn%bk^PXFMVePc+v0(a)A@2FZ-bgyim1$HPj8}CH z$WlLH@;Nv#jd&ugd$%U4OCYzZX=kV>>uFFuq3zI4%drw_$epcVHN=x*U!I}L?01Kv{WCZr`6#Jo&i!oyR8@#x?W^tyhY)$s0&D{K zpLto+c$QeuE7Tyb#q*CT|G#b$)gp95qdOv3HVp*NBRxO{FX(5liQ%FDa$1j^7m+q= zS&lJU9q7df)&aCS@J2ouNh0LtRsJZduYUwbVM9-ER)_Ke*>yB z07uJ6GHo|GKY*7}NkbOPb_W%fN8J`ng!uZhIQvp&glw&@Z{ zi~wlmVJ{5U$>I<|iW6Us>7spx$eVp3#O43rZS|-yuP@tHpaseO#RiaZg zgb1*2lu#HB)%v{WGHUfhQI5T_gQUcbUT?~NnEP-KEPJU{m8q?Vo`e1=0dMt#MlH9= zW5IwVd;Z8Bn&zbNeucXk&yYpF%)1qLDWsAVVP$9!>+$wxT&$SxRIkOc-9c%#p@q6$ z%Q3a16{--v+PFMYe-rQzlpG~TDjX(`O_Z>1f5jE=$j^fD^&r}LzZf*Fg9?heYZvB) zKe$I2)Q!>)f>%}6Qr;ajW0~yl66!3(kmb9Q$U3?J@dxFy&Kc_d28LzB+X5=1p-Dm? z9%8HbYl#XJI>SU9pHI!1*4*o`DD8vQJ|yPe*Orkm3rF|_#egEPE^!`DWs^_#t3@)+ zty-M%Z+A$)sKnO?6)GZJ8twG9eV1mzpK6K)y&&*&RR|tBLlU&Ope3KHCc84OI|MkA zj@rFmd8(!0ClIRNOD8A$*mWgAC@wx&M0Jt zwS^!y@t9EV5(oOVY=T5$h(w783c11M1{bxy7lQ`YNKl>vJPT+^HC@C;M_5gqBzpO( z=hjaJJ3X(rVUf_&GK80Pa{tzZJTSNJHSIYWk4{_pu=Nj9)x~R@a7ciGQjjQN}9O zB#O#OCr&HZuQShtw7EO({1whlTkho(?RRuzaMyPln%vW9hCpot3Cc#5m87@RRRq*k zds8n(6LG-;qMDJ}(Srk-OUrCE1L@}*q?C(^VpY$t+h3uEI2kVOU(dH@jo***pvqYhISDN<__B$U z^}>9S6C2k_>TJtaV0R1vXs;nmC0S@CF^lq={@)XRO*P8C)0OQX;MGk*N?NL*FS4Zw zvh|!yI{&j4Sc$8P=CAV9b+xP6al-Gqi!|%HuNO`slsh=HJ>C#mKPzpNjY;YLmItM3 zk~_PNWDUF*BknSsEab}^0OB-i0RKXFIcA{kQPqi|!23$>JiRPXhdISq~$Q1r^JihZGt`v@8C){=&YIv|m#K#Q0OaG$XTB zv1$bH#E?-B<{SrVKIHq@nt(ZfwtWX>)lZFte^;7(E`~YX(oB=SSj2Rkrd@=b?|q(b zVAOT0G5^Qtz95%{p%I$r&Wv}Jmd*XYQnUVgDbhY>0M)~gni*Om`W{9R*+kaqp=+P@|&w8P0zF9jp+zga{n>jG56qidvgsw zH8>}i5URxzAi57lB)b@a%O8;yk*N$D-)1+dwf~c=525hiYyJIWG1L4qdqDcmz)MYV zLm0GWs5__f-*$#62FL@f4;x!Od-pZN-JR-oT1++FT*D%Ka^qGjv~gMD_4#q;81(y&s$|l z^iXr;%QarWZUk z_Y;G=sd6#*Up4JNpU@okM#;idRpM=;0djp5&RcOYYxI+NQN3PcK{>g#Vt=mVDQ7Y0 zw3C>0*9+Zx;nBaGEp6>fW?;XoB6`gzU}I@3jN0wSm?ogwmx8$h89MP*geoeB%91pUERruWCyHDySjDWV~?h#;QnW{Z6 zn+FhTaeMs~T2PJ~p}W5*3E_AQ+RVJL;vooi*g(}>rlF}%Xar>{QLP-*wR}ohGSW5H zxp*D^q9S+;C9}dro_Xt$q$LSS2sxSeE{gjA_pvi{wHNqz+rXTc+SHXv)sR=X4zK0C zj}`^2i8^CQ7O`4aUt}4S3!KsXP^qS3Tl?8EZ&s2CvgYn1DeJ+ULFNMR|k+SwCWSOkN4vF$|9p#jbP%F2h5CAv!{224}C?+<-x$zKpK+hc}bn zr%6GIQ7I`G!8fSCvDKtRz3vrg&g{e=_Q+QMM2)q*w`B~2q@4;`ih$M7<(6fx)11KQ z?09jy{eN2Xl`>MA?z)=u9&jI2(i6(Kw+3(ACFO25Pk;;xK@?q~*he3jRdiaZqrA2o zas(MnXZzs{b7TF?G>{*8Hh^cmZTt@!X_FB?dOVgc0gH@zB-%_Fo~J2lkuerd-oW|l zer5ybHVLyhY>ycgW)4Q8UDeoVvbj zDvZzFPsh^)Ac!aHG>_vlwvl#gj^JpE)o5#hu)V^M009!e@=ue~MLD^KZN-wp&0NJ4 z$P9-il-!+5o(Ap0#!>W@?uH}kcCOkeCg(oe-Wrk@)~x5$zt57cgleIA%x$A6wDsI%u$w?hbzUjn?v-Js9Q(-@h8#P)g0h>I^@-X^KK z&}zfGS_$!o*!x8nwCkpYVrO~18j^iO{(W>14hb=kT-KGu#FD{_5-9EwB5YqtTky{N z!o`4_W6eC_I&nlFLCiry13%bFu1}lQ;JVxDYd8r6^fG$8vXo1@su8mC7au2imT*u8 z3D9FxTi6&ZO&L~+_%9IsbiZ!ggqoyF0GDDljyUMZsS>Rq46f2TO@s3BuA(t9&is&3 zWr2V;vCA<$oeI(YO5w|%T_gTpBQYyN4HI^wQL{h98X|ik`$W{|+Tb-)tv~f=Z&}{D zs%H645>kYLYgE>!ZzA`egU0K|Iq+;^l~1NyW+hOp8x$UDxDq|Nk`P@*hd(HaM>lUq zi!;vEVo#H?zP!Nq=C?$?p-{Yj01%+!ozKv$btmldtqZJMw6p3iKLTxm zzKE--s6IRBZ~TV3p(RsfqJS3B(9uA+gFb`Xcb6#zL$IAb%e zC;SCTX^%1ZQnhCnCWn=c(fm189M7YNUMb?EPKAL3X$c+6 zIn7Ps{gEOaz=-E~-U8H@!$CA@T3!l}5AoxqNnvHT2Rd&9gMr@S;%Wv;%47902A^8hg1;R5kMx|ObiUME!9I(NdTG2v<;DJ>z{@mrP@-}a^ zxuQQnH4Y}u-p5wlj{j!%g7*>K04Ba4%@v4MQ9xl`KKx`2nowP~1xJ}XxE zD4j!se#4l#J_h%zF`fo7+H-a~%hQl^1;tk^u?sKg%^yAq(+%CjN>^-$@MjRTvf|F9 z=8Pp<_-y?{UuLKUjc9vF`To3mSYwvApaMGc;FBMwq3E!0$UNrOH}6#T&1)DC5cnC@ zxynY;-EI@~QB0FZC&Hio*Z$u-LKq>P8!cRqMMKsWeCVT%Qaf*&tu)23{flOL_S8;K z>GTf=K5-T-Hft?6z~6^Zlm|Ig<(O^V3)$P%f=m#ZG4olOJW1s=Rre0#2CHJaROkCY zEIxFiH_SbFiYh?uwf)UlAg)D@crxT4tE>mMW*3G!Ps;$r?V^GE2vQ2)k(BOn_$)FK z6bF3vG(ZgWOrJcb*6*uZ zwH07$D~*r49Y0{>u@;0R^z2{ux?Kf57Ci!vi$hBTPs3(%AFsXSU&LR$_A+&ep6MK0 z{f%@a*uJ1sqJ~2eqcEC0^_wT0xfryNFN3K6o>5r*2D(6op1;cQZUiG(U&b>XJH2KH}gPEQW?s$-R)@L zr@;U|x^i)45mF2n(s}`-ju08fh-xx&cKh5XfZRsZR~*pv1LTgs!11x`ry@T|J+r$G};`Ja1^d@6${_}rVlNUv_dizptej4xNo_Mny`BArZ9oUxzoq+FRP^};fUgJ81Hx>! z54E+MaOAK3nOxC2cS|z%Z#14UU)+j^zpz}TAo0!lHsl(co6uQCPnOk{u$hqv`f?eR zgC|J6mi#A;l75TRbuyhkApVr~dUX(OH)G0|xD_xJ?usQrdyo>IyqRdz26Jk!?kA@E zzbo$VK&M5?DIfKJ^}>a5O?|!i@X*KGt(GxB`{Jc1G>pRxWT!6(B&w8dco;V|EhI0g z9?cw;{CaWb(7!2KRyP^RA-MV)BCzeOQRa^6KK>VNe(1J|08eVHWRHemPzJ*Ca`ydk z(W*ikf>Dg}w6Bx7+7p-4g2o5jDm5+=d2vUE0I|6Yx^G2WB%G(zcxw-seS#$#aYnzs zeT(8JVg|htkFrzK%G!oZ5@7mR)6&hmqbAs3P3bLolDhZ^T=dxV(W^7&8n7h|W9`?! z^{A&ca>ul;8wzUq3s||~%7k&8cACK1E9gJxwMvk7C{`Mo$ykTIdpIUp&_qqu!eoyo z)5#>OX5}^;+&6b1Tv&mmv{RoTewgbtbd!Yd-x4E5q>j-#m>^lBUBh^_dW@6<*vaWG zAi;vVM!~0c=|4-+7hF0G77VCeq-cu6@ldTcLc-l-GByuv1B(kDR*~7OH1&&f5_S6P zq?nVQ%n67Z5z5-)^<{rFy8OR-vrH{FYz5T z5@lP{xF!Vkj0Tymw!~VGp}4+@Z-eqS2e|xIoDSH|0?f4>!w(Uc5nuT}OBWX&`>~r% zLd)O*om%`B4!n1hK?8`($NRL{qm~IkF*bfRBOje}-uAehH5jpT$;Tm-h{z6w8I$u& zFAD6s&MEC`PH-5EE{qiuTQkT#*(38$$~tO3(^~c`IFdYSGA#3ppD_DJW9Ic=xtn4L zm+S!nKqwi%jHSU5fZ`;YBu30G#`V2BE`gFD-DH&J*6Aq` z=7zY-oCb(6R8(~m`uGfsO&1^XbTI1^LRg>l^(E_D2N~DNVgJpLUsiW*=nSta|c+1|knRAL+myA=*Y4wrGe-)M>J`B&jip>C04TpB?v>AnH z&|>c;h(VWs$4{^tUVKWUoFU*?=jrBeQJgw)gZ;o-3~0p5iW+19)JQ_y_4)w2>0>d#w8Q=Rg!z+t2`+fvC!cZk$`g#I1JWYYZW&f_F z#68(~GA$YXJ}nSQ&nStI6#d@%IOV&1biAX56lpKY@m;t5lCpt`dlC2Y$YYW3C^~hThEW z-Oekjd}of}L-LN+9O!&(?$5fQOI2k_D$VacBN?uLEWqF;el0!ug*dZA-wYnsLiq}# ztEX)fJfuu)rCunV%s`#cX1I;w8C3x%=Z_mwG3f^L*Lk_{KG&7Uub@DFi@XIzZmk64v~P5T8J|9`uOmgVm+p*SY^w|=wRMO210C4g z^rt9!fWqCNHfWB*P!4~#s2v9yr?HbKTYp@#W z4>{n*u7iH%^*ZoR0An>3F&4P8oZIxkvm6kYcPvhmm59v4(L)h-b6PS)pcyf z@5SxMg3u!`zHGy*lV-xGT>62{X*p80%#@a!TpDiY70WqpD%W_O)nt{W?tjg^zjtMR z{=CPZfqc%_PXhC%Jy0PY&pPI4U4rWtlG|EHiDDtv$i>A|*N?dwz`HBYy(a_(Jaki= za$!wc@mJ&yAng+OwRK`Hj{rQa)6K=y4bh#w>?X~SmZ9mw60Sf3oJ;M0B zt801!oxj(c^^N@z7+*&*u^ke(e3EW5X_F6T>B#n#(Wh1z7Dgc0{ABSp z&`5MMyO_Y_o#pM7>Jeb;v@s@2fv77Y{JkAtl;Nmo zuHWc9mxZIT*Jk^`AUI?AGNa09{TkOB@j^>OiOmfR7E;4m3t%J>Gn%A^-Beq~TKp)I-?x~h6(Fq{yIT~D|GuHteCm61axnF}&sKwf+# zw5O5$h|KshyE%Z!Tvn3HakzTUWCS~PSL>JrsOnz?#ggmpsBn$mN}$CzLcUc+f`x;Y z;nEHjRu9~LD-?agTw-yLg9~g(svgdMWs|9BocX$u5CAjt^i&hVolwA3gXDN*yCfuW zpo75F^w)J^03k8K0nrQP>KGc-r84YJT*#L+(I)IG80D+Y5Wz zfC-;jZke)^0mL*A8ZTKkLcf{$g4sR$k81}2(c#AJjd^XO(3KPk;-lPsIk}0`a9|I<->(BgL0LT`p%?j*6 ze3wy)GvUS=$sTxGcDQiS%7`dJ*5BfFroPJmHh+u~eww@G1dD1Fnx4`>cZ!speRD13AS<1rxCh2X1qM z0Ygy74yGJQ!^W;gj(%~=t;I{C% z2&LY{mf_DDHoup+EZQ*%=T8iJ5a>ru)xKt0JV`PJ>Amy>IqdP2ft}y(#*UgdLlU9t zzV%!d7Kb_o_JG~($|82taH>`R!)T`RF4M)$)!Xw)o(s%X*D#q3d#pppz&;GJ1#g3Y z|4BTPCcau9yPn|);CA;a{%St$e&h9LD2s>DoRu`Mv}VT$Ts3E*B{XB^zMlxw*3;IJ z6fOPa>{@S&U+T;&w3$- zkQ+ECdO!RgA$2ZdBwaS*QK~8{)L{lYPaE-Y$Om)Qvc;752H*nAZ3;LBo*Sm$K%}$@ z;-Yv5_ht)1Mlinzw%?}Qx2C*w%PzFN_Oihr_=-J&CBRO~^Gs4~vQQ^Cp7TA`P4AUz ze=%I*Sr}5)00`kj(Jo=E4S>NLlfGa8q0_>Y#Y*udZ2L*=>DQNYT?|F;B2DeRf(iNL zG+@Fq8gGP3Xcj6BJwFP5&xO+4M7T=By3c&%qZzMHQCIs~pV~hW(=qkOp2Pr8W{wj8 zA$rq4Ih0c(j5Q3 zf75!{b$%F9)mUl#F+S6XdA)}{&{_lt$9*SPD@aq~9}{%gdsyfNDVwN<@e~KuB1z^x z5h*jKs*s=K*{LpYBMxG;F$viyjMr>+#L75Ot^EdK$V5ilH*+Wm_Ibsp&r+trc7>w5 z?iO~R5U^byax1LquU2B|{aNpcwqlWa@J7W157Qakp-s8ZHWNkakCA(YUd9kV^arS- z6yhnbzAhgr4eySX+e#+1KaJwG^Hl1u)vGM*2uFA2Y;Xd3o@p42y~PB08!u>>PD9@A z?OG$-45p~0v7IstxwNi#XL+Xd9hXQz+l?pk5zZ}t?X}ihB$@+^@M~DSUzfeu(#cP} zoK{&l+kf;N_2Xt;O-#C3<~!i(%aIlygXf06R03`z-dV1!*IGHYMm)a+d10`pJdl}0 z(tUuv1Og-8(z>7S3%F%0PNh!UuL@AA;c_7AT;HF=`95{8Y@yWrTu1RGVhlRub2qSq zlN+r}Q&|sstUMNMqQ-iLyU|<`G`hS;kiq^*Qg|_fcb|h3tV-`?8q*g0!Su{=yAY+Z ztc9KtvyUxNjojiGx{vP`rd%KUHVu2Y7^z_Xq>dwidvDX(6eGGQU<_A%t&x^9{g@@J zl;|l$^B|xjFSRIg`$T#N7?-)>*vS7Aehr!6R+elW>Nzc<-lOyf=D?zLh!H@mHz?K- z`fk0j^X9Juf&>EkMtv&V_xG_Ji@(Bww-Q&qdBUb^(pWeYZ=5qBcaklDY-VOd-h~u! zF@J5aX)xnpC!1v8sTJ)jM#P`4j4X)=IOqgA%x6i@>42Itv%I90p+BS|zJ8xBVOCR& zYUOI`w9d6ixKR8%7iVJ67p*J)!kpfGNJCq@uBJV&8b67eBo3tAa1<}RZrI3h?YrMp$_tx%b`zrW|{3QpRSz}GZJ@Tx}ab}y-1ctqr zZyuy9IUz5SoBJ#|UX{(MxEqpo{GX5$Z1`hJPWh_>4CS7CW(Oo(UoUhpw6A$Sp=Bir zHf4hoq;;c!RqiqS|`1izWQ9GZHJ2pGzr&qUv(gr_x zgGr&jZfLPiIV7>Fz=lLpvltL}aRo3_?j?V=0NEvOd`E?4bci`M$8!jlfx~rx*nrVt z|7eb;n>w^WyX3^@*%GUXIS!N8R^6|xIfjpeHg+B!*&9?J+!H4F!M8EhtlNpRyrDg4 z8+%FZ2W$^`Mp2(Xo&CYW=U#)YMyyn^UO(U_x<&&p&qScc0u9O#?b8ssJ)$O0MBl1V zS|kOiP1hj;5ahmkY~bksW)8wi?3M<_kv<8}tgDK0Wy5nTS%Y-glyKp6=v=|#C1+vWEw zn-BamI=cRVSNmCpb~I+;mu3I!`y2uLD$vfrW)fia#1%NrV9|Me6MtpgdY`JCb_o6{WvPytyNI3)$|vgwex}=_<0V$7^?(Y!x>HV@z%SC#?uB>WI_~*}yA6ej!88|^O;j6J1zh*f z@7$smT4!7;zv_0lz`YuIW;u~PGv>{5*&D-FKmjRmtMr`wa0MEV93-m^1OVu@eaSEK zST~&&N*LPU?G>Hxai?muH?{ZkTcqMV3j%bQyFVwW7%q@-&=mX*iD7<^jy5N&aO_@{ zG?6bi=~Os2p$wIw8%Q3%t;r*EJ6OZGLMi3l6XBNHX`g9PSL&^xgY*EI@FO-Y)^l>o zj|&+R=-u2od~;dWc9Zh^&%m7Iw3NF*N*Va;V-sR^@-rBM zSLZ*X4`0Y19}CHpPq$(4l1>AF2$d2=;}x`Rah~xv_m1qQ<=PU9;z5^GSS3uMG;@ zp^b4QJ0waCRt&Wlkrb4(k9i{A0I>K}pl9Wud&16!?4Ywcqaf+LHh)kl={dPt_9MS- zf>_Z{Ca(T*#ACLcs%wwdT{FISgDDaI})Nmb<_p7`~f4qRXVO{@LNQ>`Ul?P z<%W_f=2P!rQpuig+XH&wX0Kr1x+CHWFP}Y;+5*dXbn%`}^g^kC;Zq4Q`v8H}xY-cX zqe~A6PyF+?OOV&93OanxSUh~#1f-ZP?r9g&72w8fRrH)vhGe6D1^Ol_AwNRr-K6I{ zDj1~+zf3wJY9FHHtJ+ z5j4RWl^Y@Dx?7D}2Z*wUW=_er`G1-;p#k$$cvMTiI|fc-k-|-#|ATh&ple6P`eQu~ zCvn|<5DX@veM_$PX}-HD&Sr?g@-m{R0t+(Q-l(i?|ERA*{r%BXPqSV!15U` zP=LEgqVJ6sXqDVeKesV9a!du4T(*QAZGza*-4GR%vF|x$5DtHH8e&BV_EFSd)LoLK zoVbtW2@@Xf6nZWCl%E67plhn<_TTmkWl|@78cbC@WW(cheXI0LB?EnsA_+(u#Jodd zF`#kUn>BG)#7rkJdce%DSZWlm>&dmARziM;<=fIgP!`Tnt*j`Ypu_f&d8g%l2{_9A zi4@$L#<+ODdy9A(piNSppZZLqQ`rU-{CS~kS`%s`|9ztt2jK+4q@VExryRC};trec zqyp1g!JPlQ-8`b+NSPmZ@Q-1kFqyIb<^=RY@_%yRU{RC<=01qnH(4B3-0ex1Y(Lca z4XMMmNHB-O&+Ix#@XH73+P}jsXuD+dHgqWZ&9G`LAKNaU11me`9z%ZCA!qPBjTFs0 z1x@f4>oa9I3qx&M8{9r}P)8yh^L%cmesxrnlc@N=EI&5^rL0IDhE`LlV*s$^BJKhhg5rGpc2s67e9r>=N*5<~F!7fDQO5)w2&P+7^fl{a#0SC<+pUFyZ?)a1S*E6C9=4(^OvkuJ*D_2hWA@ z;1?^^NX_5G0h>S-$i(%o!+A7L|vEiQVY#~g0uTL^jXkW9wuLP{f4^j zVJS{z6r?ze_t1|0jOsrXQug?BY4r9TV&qQ0BZs+EZEhYx#w26MR)x~O(`Y{VX?jX| zf|P$M`y?X|*B_2ak?u};;XsmP`bc(moC0nCzOSGkb-i~#TR$KpN^KHJCRc7TCjZ4W z!CHb=jm;EeaP9x<1m*@~S*{e~Oz)^TK$QX=``k_9s{00b20Rps2?^i(}7ed7_m(j&oFMIAexJXhaE*=XQNMUwb>|Y6=Ck z8hMMLcV>p(KoP6xh)>mJj%VoP7V&qDB+tsqgjo^y9oSzJ584>aIr%qr`h!M`S%+bB zdn#IT@jjE&`- z=dy-NbhxTvE0+@5HT#%pBLIJZS_+4G%GoF?R1RaAu5DJ?Y&~uu0?`cD4o z?g|#$_R_ejTZq7a(pMMOx3;ogsEw9mEG&=4dgum47r1w&D;0DFcuys z;SDyolUGu8R*DHl39=he5Lmw1e29$gAqp;x zjjWc$VRAa-t+-l@u#zEC>bobdKpY#yY*o1pPC+qyukZaUWnt`9+6KSHL_Wzp5XAR= zcbT7*eTVMBNPFS!brU7o*l@|uCG}anX9o|eZm=r0HIozd9x)Poqo}=;RF?3a+?0#- zSvJrbjo-g1{b7j{gJCHTvnvzqjrU$IPo3#SaXQ8^enR@L-F?i~Z+k1$FYB&e^J11M zBvzXx0z;P=)%z>b9GnWu#(`QOAsr+u{6hGkp3V$QJGS~el0ET2_q-Okxsb+y-W((? zDW-t+r75j(b|1r1%osy?7N1cLgOyF2s_Zt+|0^Vmoq)^7O?{(XN#&Cli-hj+(9mP7 z5;Ma~Gg2QJXRGxMMPD3Ap<{ZOzL1yxqxwc>1dUyp@fw_b8y`h~Y@ zL2?(IEUQ%cVSST1M?(~Cjl>PeQ91%!#uZz3N4pW!!g)w^$n-}4=!zWp#sq=~1L2{* z1O20?UUS$}_w`_#GID2Pwh)8gY7O!64h6wCI%GJD(kZSTy-!{3=&Yf zX-M!`ag}4B|AYSM`v$M7=Iw?5( zpnOX=f(l!;!V#20?SC_5sRC5$oe5~?NRc93ZOuH9vp-0S?O8O~F_lJqxaMcd*)+=d zK!qIz_9Vuczxfet&U>ws zg!Q3Ii179cVCV{JptNXbJ7ui6tWTm;sj{^}vh z5Fy32NZ~r?&bU{&vtS@=PuXUgm8A9x!?h4+Ho@}*7~(Ap30GL@RbPATI`#z;*nv`H zr3}K`7A*Z>mDHA##Qr!uir1E$018)iRPHgzX^0YEP_N&S{EBLyL2$w~;AKNKe+JcX z&NG(s<|gIA#=stG^s|^qV?SYjbt}M08q`&gxY9bFuIuWq0WlvXk4+XeO)Us=bHrYD z4Bj@rXcZ7Dh}1U?$m*esF;)0ic<*Vu>gQy2vKD z=vVVXN=X|rto5Wu>5P`28P)QH`+sfg zIYsWD0}89|Y!Y@x{1Nba+s_}n3J54>703L%1)5IAz@U^XPo1Pm7q)wn6&>VtH-z6} z9sQl0$~L)6ViO2Ve|+#NK&Ah;m{nyoMqf7ZvA*EK=Q5h0=DDCWftEMvy(b(cB@7}^ z1Z6{ufAg`PTo~F1z3@+t`|jhqC& zvviW_n%}@E{jI=-tBW<74mf$?o*9+28gy*DW_1dzi8uq}Q^YUdjm|i{r9uEp+WMb^ z|bKK$reqQZ%$m}hXNrxJA5b}|^V8`=Ja41>*? z$XXg+^7%OMVfG@Gr~MROs9ph?qT^_ec#cS{nfc|oz$wXx%GvuluS@C0`>ekBOE8PF zWpwJNmDjM=r{31pNqkvhQuT5np_Z+Yz%?PT|3pfMw>(K2Juxm!eeUFVv!Sym4+Ex$7i9Xu>&X;_9eFTaiH4?=}j|HE5tCio(COQkN z52WtYZlsN@p{$&KzzkY?4-xQ>5h|p~d@4w4`&F}ic5@x+UL<>>-brRK+sXR|E6oLi z%E6fmtN47P+u(JH^*@$9`b?O^=Mczu2ALd_UsQjO(*23NZzjZF%lu*ebJu%NOFw4X ziwuYgkNzXs(tNcp29nlk8S;E6W;k%}_9?aQ1izRTmI)!@tz@IiSJUm(*RTn~}+;exEWSOBB+N>d?E**g4ziOc0} zYzXV=i5pZ){{d@a#^Z}S#=4f%xl^bCXf0lOkfonULK|kO{uy`rPL&-o-&yyE&Dz9P zl%9QV?t?zT0|x$eXgArPlk}k&d#tyP?4jy4Shef(btoQR=VRP)@a#p)l`b#q*8cX` zmxvCEmjFIB|7g!`KsrBNgO1MK@k~>bPzf3=4ZDFG^oAg&1ib#eJdL*9e{P4b*KF4a zsCN7Jq5{;#ehE+btEH&4dF`w+Isf9VsGj-&D}xiVpg1ug+zb;$s78!d^4{PlbEYC5 zdxRz{(m+}&bjn{vbMz6mVkMvwI4rRHRK6GdWpb*om%>;qY~M8BD~#CBM)_*LIGVPU z*Zgnp6^TL;6q&2+!}-|rbmL52NGjs}V3+8t*Oas6B@%Q;{%#f59A`4zIXjheu_ax{I}ev)81_Behs>hO+om-Swb*VJHt z1u8*WlSf9Dxr6~v7qw#KV|?`e;AW*Yp%jpQ4d7mwSh9C|S~%e~yRbx*hHHUsM8vKA z9_B-)L@nFviDjuXqBM#yx&5myjzaP_E|^g=W^1moP4`Bz$3s;5hKI@c(L?seQFZ#N zu#hVKxyMYE1hmoW))2cM7#9@5Ef9GD&Wt8?MwSM?Z>vxGsE|V5Qni7o#Z839#p3gD zvLUi+G+|?eMk&hp@C0L>%AXQ^We7zhYKF6%Q}A*)1vY zH?W>orwBm9h*SI-TUYa?+E0VwRZYYk`SoG)+5ppxq;u6)``N;y0W`m%p*^{----t% zN(^Kf)c#&l|^02Z_OPZf5J8J$o4jzAPKCF1o%UUD>FA*x4T- z_ey3DR(kPJb(wJ7*q^q?hYhhvO25i{h@G(2t6|Qu0hLvv#+#Tt^7!00h zsp0wDs@rl_!NGlFh)i@v;lCm>Zm>9x2RArTF75qFyE6Y)*p}9#xIDk>EpdL<7g8pE zfZu*FMRh0u<2_DBVw$%;Z@{{3)dD?Xs>OX6svr=2gB@omJ2bJYrFo?d9l!Kk_MZ!y zgaA7i4%6w(Zb?!BKCzgHAa60Kg3SFWZhQruD>zpB6YWP*GIlV~78yyJV3J(Y$Y;gs z9Cjo`TA+zZ5so6|G?U;WR{x)2&uM$R0PIX-Ci6s=0c`;XV;W!NrZwF3=FNgx9UExS zJKM3_(3fz(C97aP7B~w$d0%_WTpZm})-9L!0}djo6z#yXN+Fs@vOWn;PePnY+=;UB z@U_hfY3tv;-txQSmOt@zC}Nhva6;%$mnMM)g@ES|AS+tz3*Gr`)3=9VNGK10F!4S} z7U4$4L(H+gVADz0rSo}fNNBafSw0&!f`X!)fCntV;OKX@^lHp4qens$eZ}?-rVJ0s z<$rxN1T#j)L|GPlt-X_Foc%zf`lRF=&5$8!&OKv}ftclVQR4m1Oz_f*n%utHW ziom*JXQa(!A|Sd!$a^tq(xRmRLxko4VlJi<)d43obAx|2HNDrP7V?_>Jf7+mK@YYo zWuwu8Sf-+nHAtp$2i@<#3<_PZeRu)y%y4$?7CFZO)Xs}j85H|P!uT;}ef7Kf@la*9 zRNz^tD{`as9R#`wCcHaB0{9=yoJ;H1DS@PEwdb1*HFOY@u}nmb?Z92}Q*TIO!+?n| z!y#bOQ)g~VJ#eI|8+SKPK;o=;zm-Do_|wqFW`N=k;7<`@azvWGj&FiSjGb48iw9vP@??^`8&Y1VkBDspKvMK{!Ss;=YCO;=zbh&p>!XOEVLHSaW`UaxY znitS$-d-A8Omu?WW~aPAz1y=x!L#q5ma{k79|7FngnDzqLR1Tw<-!oUGbM%171OB9 z=F&0Lg)C?#{)x+s9g^83YOjg@HEj8?O%%zARk_*L{7mY7mBXl&k2An!Jd%cuY>4Dj zzPamqt{#-Ggevr+MfCRt0e?{{v;%W2le2 zl%Fz4)e){(8;9Yw8^?(s@l!0LKMcU^AG6}Q5pS=PgeGwMLL#^fHTRL2VtL8d>>qa& z=Kd zb>k^T=qu}J%~gahd+0_F1pe)5a+Lqakz%CBe(cv?<-wDu6A}~4IZRsTgHpuLs?;rAAqQNxHL0Gk zF4ZbkDE+B1Jf!HKgHG}x;jvUrm>p#B-mID|<~)J7@#g4|iUUbSZZ^nUWPnh*@w5z- zky`_?8o3oEke*rhNBn=L>>E>L`i@FpD_}xM}m$}QMO%C`OB zuqhM}M3UjcS4sn0+itH?a=yk!ujE*cAqt)3Go&+mcP?;krokRfF!$A&FaX*BaAKjh z9vx3^w8I*ACs_m4jhA_JK25pSaw3}6%2W{5{EoIjr@-YgPlx!C@N}v8jgU@N#j! zT@w*O0bJfXxj*CbMPLY4f2e94P3CNMet}s(5dJX``Aq~G%$fkGtIYOafn!10a)bK! zdNBTI=n#$rJ9zq|aP-&Mrw^S(8L^tsx~E69e^~AeXHHaqC`G@1l7B3=MUc|mwXYfq zA(_4;Ze?9SRHoPAkVf%MsW?BWM$rxQ?q44k0@3a${|ID5UcJk9hYHm;dpe8r>Gs%n zk>`7AjQs<*DE9TGlmVx_V%iDB=nd5iSaJ8Mt`Qn+Ee_5WWx&oq9pW$NodV_tyT1P? z|GSFUlhPRf(S@R!B|Hd5JaU!9qEMdgMQ1WpwAqH=5@75d^E8Qaa_*=_HBMP9&{q3y z3FbT2KKHF$fYV)V(6nJ+nT)dzdKhFF% z5+BQ1Y}w*QlCugCqO=ZUJZ*~om-7;gt0;8;2>y=Zy;}7h^U?K_2Z1aT2jK#wE%o6D#J#4hDi zj}yKoF%Bb2@EvwzHcCDjW}ane{fF4I(x2XeOLNnbVs$9-yR`H&lfJBD37>0BPLYlE z-*ZQ@DbCp-9I8aleRW`J&Y<I`Fn5 zcrbVwXSjhT&j(U5O1Ohxjt^tYPZFA}n5pbi?pk$=>f5zV1Ibpu4!tVVX4eY?wd7mu zuWH6@kOW8>*9yB-g^sI9f3rOV#Z^OMXK?rk;H?e>kO5LG6Omd^?;lXhcM(Ob(vqXy zP`2-&MO_)cNoOqe2d-XYJ9!6YaNH0d`FNG)^?!0IXRu@z=1LQgMl$aKZp)fSpBxJ> z(E8l$JaDrnOzj~Z&RB@w@iGz-5K6vrWT;S)0JncWq?bcn>Di`aufFUVGK7D;Y`_{f*y!-n7jZ^n#NVBwx8%TxUOk>|KXk4*cJf&rOZZq4(qY*lNyiQ8;Opg ziSpSxS`z4nL7@FGe+fmh#jy%<_4P+5nRFmV?w0!lJpkp=**a7fA0#jvd#hhNJo!YH zlz}Z?Ups<>b}irye5_g$?!e&G)+`0K`BkYz{Q?|QWF2Y{HgpN9TSAF^fs`=4xTr^s zcTM9FV_K_v0RLO2`WyJ5b3~N9YB;72Xp{=`fY>&qOxo$53$B!5?%usA2;G#P{69^y zmu>WL#e%!s<3f)Fgj2I~O6?y~M+5|g=-*o4jjrGbSE3zq=Xd6y@t36?m4zmXvV8RH zpaqR0Hw|;1c+UiFwZt4t)D}3bSJC@F@WC(afuvkZu^G>##cJVNj>t8iN-C*LIfZh$;uV*C5 zsvN*!fXgJHFI0P;JrYjjs3gV;6qB)~&HQ#szC0V4sfiI=+h4?0->j z-XD~iO2hI*%(EIRDS0f2P4)m$=Ib=1E;Qs9GQDgG84;2O;gZqqAnKxJ{+7eH1#`5x z;g}^P9t9nErE@r~639_y1q47-UxQTb9M@IBt3i80!^IpRRm#x&c4)_Nbvyl0N<8@R zH&nyjVB?)0-k24(q$BYZP}x!Ti$1d&QDd%cp1j)xdC3jFBtbT=guqX+T+xmCkS&27 zVz_2w|DvYR6^EJ{1TRuxu$7U=$*p7F`}QjLN*gIVCZev7x%Q2wT3n#inyFpXV#Pe8 zH2HEyjbl_m@@Ew^ww@KhKRXemc|u%Rx0&s!+-gx}g`*bi5aq*2?|p*E#-RgE0y*w! zm~PQQrY8>>HG}!Pnavb+8}(Ai%R#PkAK%gJ^O@sFt^7buAsR=Ec!U&co5~d(sH|P? zr??sb6D$Hx?shW|?M6@1W>zNQ@sxQgKi9#V{jla;`Nx#v^&Fe1!YYNR$R3{-UfmiZ zGH5GhXn9(Mg<3+z0qvQCgZX`RVtMio>oOzb;-aBKyz$_Q-S65Duu8*!EE-c&80uv$ z`2n1Uk<65D&2$;$+z{GCaWZBbq`U6x?CP1N!$e~MAOhMB6;-BbroG<__MKc-O+1jIg6=QAN zhcErjYG3*?UH-=LfoP`C%c-MjmD+oY0RbJ;@k2hmULE5M;=_9PjC4x4 zJ4R#fRsmTXu1k_q*FhfYAbJDI*9@ZQ5<&fWa(ePDgsn(=p`H%yLtFTtH?wNX|Her` z5~xNt^2E(PDxvbraQE2;IHc1u$pI_h^k=rW8xtp=6&l`TJ58{0>pkNDlnS{93-GeE zIX&w(llWoD9a;#8rn@W)(u@Q)!eG3cPdoWaXLchN@nZS@?rT&xu1pFhV~Y=kru5wH zX`tjRo?3I0?|W_cBIqvVQK^hLAk(tG42`t*oLguWpct8U9282Jpy+Z?scgkzWB2&e z4DPt>Z3~(!kr$S+r}B!R$qG4SUdH=z%W(3C*2bWX=oply7ll|xbe|QqI=LHWY;nr% zegRqjN8D?j2U&=)(p(A*Jk}mFIp3b)=16GsJTWZMJbki;LErrZZyA~;WV&0(m^v9} zyE~Tm2ojs=ww{Y!vL8J&4(voOY)5Iboc>-gX<#LVb-k~hxyyq5C2B_ev%?PAZ#ZN_ z&~F|u4O0Ia|6us^KN(e3%jMHqDlY@(L$A#3&fv@gfF zoZZG|^x8+_a{5v!@5VH79+60$b+6V98Pm5Qp#I*E+466(;fu9ccvI<=A%FltlDSCb zMiL(Y%`?4CfVLIv&LV6M%YzJZKDq<;f3ufWfgzh?(5NIieB^5vo2 z^hw2O!S4UwOfTPojJogu#*(5;^nX(tyzBEEZ5S)P(5E;JvI~@CSQ}JhgCvRIFZp#~uudKIYc8y2m@A{cQcZT|ep2@12o#U- z`Ie#zj&inZ>fmZ0fO0sxLV|9eMY6}}mfMs)<*PosB68KvfJC&|i@9CABd5UvgjY+* z5kjap(tn_!&~_7eBDk(NS~W3qNKd1({^%Im#Iqdh>h|dJP8_EUZ8cD)9Scq4F$*KR zNMw*mxEPjcySwxtc`rp5nrFtgLL$r6yNnX$%hO=u-5(BHMzpYeH8`h6^{Vx&w)6_g z-6$PkidAh%#6gqI%rGwpUWH4hxDVd2gaGOCvj@v zS~SPFxreResn2S|9gGo}}Wq zmS7d>3ft1P?%tSGr=&Wzmb&rtd0i&pYsz^K0<=b2RWCYx;ibAwvu&(D7b5^$;tmZI z0vDI|a7Jfa#l!sA^$nnI1rCMaR9>Ooq~SO&7R^op*hW()z{BwTX`ivqc;)P9k$0$B zUwlsOHc1K|tHBs3t&4O6t(!%g^dil1s0RfV+>g2M(pks%t3h<;W~u)|Wdr~&pSzZX z2=rJ69M$|e>Q%3+`gOA(qWbL=z$S$r5@6EO{a1prtw1k88mN zVe}5iy#vIQEeu~AeG@KJ&sKl>YpX78Vgw06&jn?x7-$g%zrYorNa0ds6z8e0yf&tD z`nN_1qNNTK$Tcj9zaIHMI!~@0!8ZI<4*w?}g;IpUSq!2hV8ar9O&u$nb)Y|<+&moT z!R3Fos(>(+$4w_$D?ibx%M71^>uzA9>DMsXwPQt4e-tq!YqbasMgScem?7^5s&2q- zWxphrw*T<Kr0Q^+4oM>0G? zre9|Wh4si~E-&dFxSeU)hybV?n2=!wE(av@FxlYZh!3&d=*|c~s!|x&@2Y!2XYUs5 z&;2!ur>?(`n0k%+fh!cO94JE4@_etCp>THJYeu1Dz?8DSYYhmRr{BUfCR!Rt7e~Dp zm4Gt3B7SLb?!~cx{AoAgMDUJ~dky%DhtzGe^b>?~%5~|y!)=EvEFFgH{NxrM)8gRZ zIfj4J|BIZggLdTWavE2MX7V&|J5KJPX^w;_pu3CSBlVri1>XbrQrq+RW`KN{E4w%y zT|)=bH#GX9t+73IZWY<}P^7SPFhVz(z(3vT&mQsCADi7d+>fb^Fr9b=$E6jI#-rkf z$KykB>|;FPQGu)?-OR_Yo5}|v0|D1wLefA{_7{4cvIzS$iAZ6O74I00G1go+^|`7Y z*1n`MS)^OzrQ&{E1b78P88*KzaANNC`j6h(SCi8a|FF^}`9ZnKOV}yI3ZT+<9E1Si zgN{0nc%UKKZ%B8!`^78Hh6_cL$@VwlIp!kV#E>0`&m+X!^O7SIly-krD`K|rGcYpz zPJQKHyP==jGVMmM2{LofUASD_(3p434iuUH^#ZW$#!#lPpPO~S=m;#A)Bh&IWK0cR9|=6o^&fr@aW=bnAovAkt?G&~h$MQILkJ zilE8QcO+t4dWEXOtP8}zo)qGm_#@xlVG&5yR4=%j~R_l zZ*!hpREHIYnIg>vAvrxSmcTuu$z8E@AR#tsHNpK#Q4*%kiApesK5K#o(SbXpQq7_X znU5jXnvYRoo20ZoMJ>`8*d8iRhaiEPrn2NL^D?*AKJanzA~%f~%|$7nSI+tffe?aj zNhqNIm7$gYaf1s5536-vGw}rL)7~!J9OaO}H~nE$5D`6x5JA%>*tUK9R&>MAx9*&WLrOA=d_`O}T-P?j)RwwP(nadx4a1DT6fhwQm_<)WSl;dk^6&!X~^0XEHBFr?Y# z>DPnbarpJRO;HIM#yZ!}vO3&vU~=3nkmWa96610VC?J*Mls^moG0P)$FJCZNtTg=n z@={KZSXx&TiWpUyH1D+Y2&#qlh^qvW`sgoHS2B`>yOQoc!_C%-aEVXdtekw{SFgS>sFrO?eCj*$^zLL|CueAE$w>s$AhLYIP0U8 zpNpMOKTh{D%L>l?P#*Im$_Z%~LnOYzK)B0E=HE_zQDE92E%?h+anU7!2kMXiG968$ zzjn=I=5_)*Y)7&Z>zOP?0~~cJSSF3jO=xgRu0~@SX?J z`;&&h>xa}IVLn9hUJ!A&~qccxy)FYda8W+h!rPs;PzhRufIgbx6tFReJb5Zh3oE~{czZL70k z9LS71Q?xWRsk5E9!#--9f~dqROkT3E$|HQ`J`8WhaP6^(RZ9OX+Mc-o*YjEF0JN|+ zJ{Oh&L5xjA6UlV|E_#^1JOe4>I+<&_qEZseoE6zr&`QvpJUjnI&%podoHr$Dz-%eLkseeIc##wDx zL+)=!04At?ZaCT)_xkURjuF_n;#;?c+Cv-OJpOSLEnL=GB!0p7$Flo*mHr{v*0qp1 zo}a`{I+OoaAt4V6ecT{5TbB@LhlwUqPiuHDR^N<{&96j=a1ws^6|rtEQ&$oV z@?}dS2G0l+q;j;1vpk$Ypb5WWnv=gd4cFbPF=4IdBpK*8R(;B3s|S+fbd$6Pbu>r_ zPwjNd+}B-LK&&oVD(s`xH zbhkU=@wM23J!X*`(Wg)&4sx;j+vwCgK!*sk!8POM*H2|Z99xt2Qh&8b^R(l_PN;NQ zlO(r#)D2=5R|wf_jU#B!0jW&9oQ$ylL!s3abaB#oVh)rKX^KPCu+M z6l;N=FJ(xK^>%i2Yi}aH3x;p5!a}E1RDo#Zq+~gjbm{~(7c=7PZ>R`ebwYd$T+(d6 zYCu1?fNWq9fn$#80rWP^H%!c3*eGdp@&>W-Oq!YwORR5yiXs=%W(G)LU&a&_^(AUcq zx8jW4A*=Zmm$9&$;*+VA$|gp;nv~<}R4Pg;~snz^gpl@Fmq3q5pHJA16)fF&4IE%P}DQA**cax~a0c2*z{$R^Hnwmz4 z&AP0?L>YRCMj1LsL!3t{B-yn#$oHw?4P;ek=HJf6tSa!m^!c-V9>a+S&ysVN{xQ&N z8#oA!{x#~L)qAuvAnm_4$~$i;3UBcud`1U~#nlXkU`mHT3?#O11fh?V{JxQE^eoPT zwx6e^=`k-RjdeyhH5Ju&DeXp5T|VWFDr=5_IR z;pG!;+8<5-Hm^X?OkmP^WI*g+ggeUdI}+tWOeMJe6dO=a#F2w_5UWS$sMwxcL7TNC z(k+|f#q0Iam16Rvj<(LqC%$d^S4h0WmklgpdMqJ(7zfeX{vM>Fs!D)uw`zi z&lOtH%(ziQ`&>K727C|QH?cHEm*+o(O7wSr_0vkd*yEM1TQp!iJXSzDqguL{{R`9| zT`ckmzr~bU!uGbZK{RAgKIKm`=41}|aXGE6Q^+XLM;A5}gLdg7$ zY5cX;1V*tQYR^d@|IgAgo{wUcy-e^SV7`1lV;RHMPy`Gp#-L@095ZRaZT|x>0ko4& z`=?_2;dp@fXqR^f7ELh($4#i`j+h|o^t0%9TMZ76hk}8BKbgnF9?s!3!axd z^#jLq_k>fKqXP8kLG$AsI#~Pw#nrgN9$9$-PSEJ`pH@u3k4>pic9Y%bq*ad$^iuzb zWlcT*enn4NEhe*atMThEFr<2N%HQ`sxXpLf)#-aGd=Hf)KL^eE;qNRBEA*$7s2;c^ z#%7D|*@vd3_T~}Xzp^p}R1A(UmMk=gbxc89FV0<97e>Z)Av|Lr>fC7JnT&3XqB!Ba zkcAAw@OsUcWU}3MhmZV_J=r_AaSUvt-^RE-o&a$*%wqUy^)(IU24zfJftKu=D#E&e zDi|$AP(DcmZqy(uxv&G>1PMQ3WjGa1nfgzW{CJs-{&cPiMhzDO^HvX@(}Fr;FCM)D zuocMY&HJ8bpknv3FAV=+J`ZS?6FF05Hc<_`&M3BvNgj zd3fcBF>)j4@s!5*(pNhd^bNCCeqGslM0-}G^LfW+-3R;o@kzuLUdPvHU|nSVD{nN5 zBRV8UYE~&kt*#7;AqRRU6F=aoSU|~b$rtReG4)QpEej6#J&5hB`?8t7lDm5_r9UcU zKWYSh*(hF_M7E2w?dclr{36b-Y=+5EnZr2NSFQOU932NDPLEuSHhd&iq6n2%!wMqn zCat017GC}|vEs~%^aG|K7i#Z<9g-B{jd|Nypih`6BXd}iv~|GgZMocXRV0)_-=G`g zjt0KvOI-ViXhKvv3a)cNXx#HM$w{FPS6Ub2ah}Ht{o&Fb@Hc79EW2d z7Y2T8yP`TI_f({*0F_FUy|?e&*Yv6~;hmV09tMF_!6>>tlCDne(^-HMw2h1Nvr=MS zvm($F^1F)osFYZeiHLs%7|ETFdH zVM35~J_<3r<|hYS)4DydBDO%+UD!Qm!Jg6RzLR|=bOYstC%wLrsXck2b4BxA0D zuN5HjgMaPcXFgy#tf=4h`Q7|>xiOrh0~0R;%2(2({*N|zm>OX2b>`2&I1jYp2uPi(hnV&d=-;lHY|-}8RdZ>Z#N|UhZq*&%$(7Zto*59D`$VG1 z>5JfEa$Ma00GN=Yir-4(gOo&a!a#7(#I9jLPy?{Z*%n*n8*<-jFyVwC(zcrSUyky4 zkMA|Z^vt4HFw@B}{y~WoIy!X{1;(D<5(et{??6kL*HKNK`iRM3*z^dJ-vTvRL*T)z zsUC1fuwW764z|GLNE|r+@16sdg|PaSdg(&7Fet(U%@O z$HhA}t(QJ+U^jkMCRb4+%z`hQSyRojd6Q^37otUZdn)X{hN=I5;TN!%VUFIo9XPFQ zX`o%Ol7BO6Yyje(3gZFx8eQldY0zxkE_L~T;8L@o`}iyxtKAnP=sP0>>Lfk57l>2h zeVt0bqf=(-Y`_jM1wT1}pWeW;Y(U@JveY$C5a@ppDIhGwEtYR;nYVJo<>|w7hy5v^ z*OgGL#?>x7@c}GL)*2xjP6IW9%Zsy#f>6oOD^Lhrh&R}TSC9yZ(Kvu{M4dR4vgEaN ze9Ht|qkDjrQj4f29C`NCmC0a$G#q$bK9RfD(~RnemoS&b1;l)pQ96~hX0$J96tCMe z|Hj*1N8p$yoc(+w2;_$JWhE~3UV)jsCl$lQkeD^Gu(&a|Gu>%)FHKLW0LnOx^lG~t zyI0zN8w-v<5)c_<`dZ$VOfBM4q?MRvz#vlyj^e9zZ;Z+Fb+jX-mtsE@+X4CS>Y)jW z(EIQQ>VfG3a8|%z7}md{wm6f5<*<86A^U7a-o-7_|30<)@$23b*{XmlMRi5U?G|O1 zNLfUAUG9E4vQCO`D3`2v>?|3|eu%jVy3s#t!Sui>`skJ|+9;h*CCYhdQPRJWlUi{MskFkE0V((x#Nk9ta&q`NCtI`{bdh4aYf8hQwe$XjPWL80uFJ33WEK4e@`QX?%?&?ft+ySZFgPAX`@ z4Shjsk!Uh7L7c!JyhK?z!w#rlgX)6xPdRWbV?9s!&YoBIBx!?4hvJA^CthSc;!gE3 z2#Djh!V&JJkNEAVk@$KAz*DtnR!`*E4ur4Pz`Jv52?AZeG6!j#dZ{T)y&3&P&C)YF z$WI3I7W>7=)-B*i8-r-Z1A93aNvTs8vcwa%gC;*JFeh@H6+nA-BI*&?mnpnj>2R|x z9nf>U$fyCg1okYA7N$Rs3ND>_v*VirBmMVUJqY9~BPUTE2bHh56FOH}rs-YYQ7t%O z9r#b*&Y6_I2q~T*qHbPbSnz#NQU+}2^k+8@jG5+nrUGfdZc2&Eg^DVq3k}OMq3cHF ze_J<@ag^bCZK_-!-*)SBw|QEX)TPs}L4|`48?DSnzLr?bTnBhFfNhf8AMkca6F+BY z_5^RnY9`U!Nz15_p2@=Sn}ELdHaYSfU6(?B;TlH#8*|XW>I>TY>8OIjK?obFIM}b5 zYF0u2{!~$c85b#IxJm_6m2b^cutzs9mMBhXW3n%?2?<_wqxe;~|@}-L6eD5j;9Vyxg zg&CRpte?Ai0?5c;OStCupaCew6&Z4z6{w9CF%tbZ5S#N(A?ti)O3Fmr)H1U;+4m2T z9s2QCUykB&R80`G{1Ivr%U;ZwCDv}6;9g*=xnrd~DU(O$*FQWD^uNc#q*GtJEV8z6gf2&_6Xz_^OXSjDPRr6UW0p8MI=|zQ1KT2jX&BbbsrXJ9d;3_Rq3sBovigXtEPr$&oL|n774+D8P5fTn_BYUaM{3%wN(C z8YpN}WQ9e|pD(n-*iq>V*!Z^mqIaGgtp7{zg53iqB?pNtT?x+CkH0$wO|Gk35sQzp z)d6TEaMGN!ca)$h9Dju}`IL%$LQZpO5eYUs&-e=R@wk)2$A0W(rqp)xlM~j**~Kmf zc3ZO-6+7sEX2~2#tYw`xkgH$r2~#X#?_9u0EgWXKB0V0FWT*ubm~bcueE6S`_EUQo zRARC?AE`CD5W;sCOsI=r*zXdW^jiQ$K z4fU5Sp0Li*%8WPM12*-?i&4TfX`eKRYFX^6d9N_J)Tf&d=Y1pO5u zMAFQSyUpzsIYfe(l?H#*))Y>%ysa%G{+R4WFYO{La*RhgkPg$gP~a>H?rR!GDO5D< z2_yNEVB)6hb}6Iu(DYj7;!WHTTPhc20a)Pf?Ap#ZQnY$`REu=N?*Gk>GrBc1I?l)Yfbo9M)m~Wp?MJsf{z)B=u8M3FPb_o z(hZZLv|v=^8}*$4+NJ<8`RMGUXF*l3zf9Ex)ols?#!ak7rIP`dphcf))}ZTQ%Pqcc z0;&PNmN^Y-rysZ~qNT8wW50x%1U*!BWC%`uuv8Q2Bd23Im21)A8~auH#$Ee~wpWC) z2@-UO&>V_j1}Y&SPJ+g1|eEe#&1(4SZ#CX`<1HH5i7XzW#=e-SJi59 zPL2t72si0$bCe6uraCWDB;9CtK|k^hK9dj50n)@qn4lYjFgdhxOgEQsm+FsKNTSR* z*80-yMWf7i_H28?afZS3gHWwsI$umGmqqAl$Wq5C0bEH=LDT_i2Kktz?JjffO1=&1 zaoAi<+5MYS^%Yf*j#?SoRS(V?VTqtL+TA9iQK(>y(VjYL))rBS+uI04! zHi-Bw_O6Q3y*tC*yZ_m8)F74PTg=C|vzMdM18fMX)H7kgBvOsvu)sb0*w!Ez+>ZzD z)Z|nQJYlhbtB#FICGFqHJ3Toe6CcqDnMBAMpe6i2A#9(sV-C&ue~?IT$19j@Ij*V( z_<4NTYNgTqdgRajpnRacFHYq{`OvlR%lgG?;!X4W)>&dObT28g>#eGp1a;fIB z+;yF&h`412{f6f(N)$>qG|knkI35hm(SPBhNb10&ta}_8a$0{c?hpSwZ4VYQqZWJAh3}=mSvv%j#7h1BK;xa6M zP5uEY&Mk_RSK%E+2fr+rHa@_qwhJlM={VN36Qo{jJD8OfC7DmluYGw>vGMYwiO3*~ zxCszgHX(`hdAg{QOh>m~RN@vh<{LX~SALG>+G%CaGOLM^6WbgQmOfV)sAQ)awBX9^ z5des`HN%5VWLv{-?k&iAE)F^nfmUt#ce1x9SqtJkU`d97qlTt|uqsjVI)sOj8Or2$ zTl{Gw%dr`X65MY@*l%Z7j@U+TP7BG=kjC=-+^VehuF-HLed6Ix{je+*L5$rSFffC||N}kCU1#X^4 z5w{%Fbt;A=fD~2%;6_3w6RYjV6LJyV%C&#>W`DYGP>**BmkT2$8(bbzEV_~U%WXpH zTKks}q9vDZJMt{IL134b?HsM`N;btXsQkWrm%E9PBa5a9_67FP%g_6no+xV7&&@>H z$9@$u)J?}Y%P`t5A|uI@Y&Q6p(mp&)&ta5fu0Oi-rgr)1Oc5B^TKX<&VUl!&64Gqi zIZVrmGRKh3wa6E8oF=|+;e&jsMluYfOFx)(+(7rOeQ60+p3X=LZO6v16fqEaVTNkp zUY?EVx2cC9lL`X!dG!hpuBjV8SAO#pFZtPsYR-VwAngP-j<2Z1ksI?Y&1W*itBr24 zNy{>%=Q2JZXP&VNxfv5zrbRMxwRiB`nYwT=Spn)wSHJw1?=$8#G!FOEa^Fs_29S@5^wl6A(RU|;~x z_vmRw#90Wp?njwMl+j7_39ecuwE$4^efy3Nh>xPqTYT~5_nmOtCz`4mT+fOUzzP-( z9}@WIZz+Z}eh1syui8>6H)LQA4;feRd`zt9#?bF%d|;YVdqJODqmjV@J(%{0C`d{n zihq)!_k{xR+YzGA@@hu6Z^8{-KKEw=z+M`hz?pKi;sP%c^fvBW+$uGgrp$^O z!7v7rNXTBAG0haDoO6ESGhhc(Pg6-*BBW$g+D{OWau6H3U1X(^ina4tBjxWq+C{<0YB)hJL z=&m-0z?boUat$i-vle)4(!P+F_=PA%ieJW9uF?I5kgs^H{p&vYl7Ip;UHh-9ngGFj zSoywYy%b;*5hOb7RLxg;qLoG;!^0?eKP<1p#wbiSA{U@~b`J?2IH!{v#j}izi2p61p>iK($L?+RcfiRDAIJ z4=WBx3z=%{IvVR8cOhutA( zy)=w;y9je`^pyVoJW+MXB+;)>M356=)2(}(BkuNWaD(Pv`+D+fH{2?g&(yTrpm{xP;x=OdD?N0hcNY%-24&Zr!V_!_u766wLCrvUj%KBYl0N9d_~oE zOv7#fj7r5z7=^6EKk$7+knz&)I9~GSu5)R;*)B)uzaA?*;nJEp_pLhNSb%y;LSJ1jSKN7<@{BN((EXz=Oq3ut%^T+tu~a$t&hP zt@&Lfw9o%@q4TOy{sFj1#N66;Y}1GknG4n{DU=%KGIaXdJnwC@eJvbg^{h*3*H|B5 z)sSty&08Y?7@rTz9*!c_v$AOQGS=XEOAeRrrZPv4HPX}j^v}Jvk$$%p!OFkNQk2L- z6eSVcDuR?5*c~@)c$MeOVZEgvO+WUVixNW?q6^osn~gmC$ExtM^(gzu(YB7}URIqF zxBz$K(s0T^w281OFRNajYy@&z={Im&{gJ2%j@Sp`G5GrP)S)Ms`%6yll7@T?rn;s^ zAW`c^4N4!$ObD*)Gt*3?N}&SD4<0Uh2e3d1<+_l#Z=_i*mr9VxIQ(pqV#9Bn&=5sA zNbP%_d2L{bv-@W`K(GQ#%Upu_G|O?z5c!>2-#dxE_;ccx#BTV`Zo@;U2m z>Q}Zt+?87(e9d6e7)`0_g4DE%=pv=Q3s##g%%9@Gr=K{XCwsCElSl>1kc*V3tXq%g z<+h7eodMBdE#29}58Gy?O&(*7Vd)DO{W8U7*UF6ak`C>n*_Ue0`%);wm#Yl>pK&z1 zb9zFcgM3ad^&^DH$q@6JyRJ!+45RH*jXCY8i97S7d1dcd!8ByR>a5%_Rvtev}(XX0pWu@t z?^kY$u__HNwbsv9;DYuFResO<4-RIf=n*`aJx{rtnRh!=A4|xO&?1Ha9#+`x((F}o zdB%}SPW!D|RL7Jm+4+-d<`)D+p1%B|uPGid@T)d&x#U{RLuuS|YbBE5)t2EYB~ zTvD$b$Q%vso35MTi4-o6+QYzriPYS>0Am_;2#bU!l<}!%RcMcZ+9kLPX+iA@ zI1mT1p%njvsM)Q9oL!MalS9KN3)aI#fn^({AvwEyo2I&C6Lg!Kv8L9zpNWFzPQxMcxXO#pmo7xw&gC4irRTP~t zri!Po%!#BeU(KvWL~t##r;N1t1yc6GI*bRms)g@{Of9*#ifsjc%n`^Rp#r|idX<;a zzc!f71hYT3$7vH$ebN`Sr3NbHwVh%dqJ6b@X@_!?mI6|Ss=f>kP5>!@#SQqZh~k3T zj-jT&J9F7GinfqM*XX4Q!oBBjhxMq8OW_GGo1}cdTToQjR| z)%hu0wG+tfp=o41hxV=#Bx`$;R<;ftc!;?N5tv{Q6~caaG(QNO>`ic!!Km)rL%&J($R-P=mtATGzI|K0z~r3g`8eo|8K6Aq0d$?mwC&tra? zNk53BE+N8Ud-N?8@5+;;JAfbvEibch%#5z7k?aIpLWjR~(T;>NXy))-;nj`6oYL8-+p(-0%4p4wnIFLR z9V&d{dq#L5HcSQ5RAnZ>oe(o9jE>C?>+ayX?iQD0x4%B;=+Gz)e zpTdjBEeh2+2)gA?I3oAyXfN-lwk;pPK5d1GdZG%U;Q13pt3YlrmLF^_9vio1= z71{q3ulunG597B_t)v?wECx~5;iT|nq`Rt#1*?|&NZ?S|4og72myisP%U#MiJKeTy*NOg$dn!-7- zH=v(;fr3e5KduBbSOT*9Sx9{UD&|%^Mz8*9!Fi~6xVFA)KN4ZyrC?&QeJcUz8qZnD z7%H)d*eR=N2TSl#b;82I{N>YHJdhwE7H7B6)riO&u$r)2*7myQ39n`!@A(C#n=(NZ@K&8gi1?T;ya>1@ zoF5G5e{^Ouzg`8TrT^%OO}ipBRoQpn+4JM`fBhYV+6}bY!KJAK_w(({lNs)}+A#ZX zK`mM-063K&Gr$>sAB3M&2hS;DZdyO@(o+H6FESv}oa`D`dy2txYp>|{IbHS33dZ!< zau5vVCSAjz7D-(99h?N5knbwlRc$kD8?U#}mMQdtB1?5{fJhF(l}N=eBuXRGqC)%& z8L+ySj+rHg1HIm=poFhXg%HExMA&Iz^XYkNvxAPHTit*f8ikyRLW!nyZ)r+Fac3BE zB@lIX4hS=(>dLB%3?Em5P>`yPLLN$&?R^@^4fCy^k0UJ^J_MBpsoXlCf6HK9oESQ+|ylv%^71t@|^<^T!`pgA3P6|@-RgQTe9SEDrE2I>x; znhR0jX!}ATz9*e3;tjE1%v1N-YvP2%(CSnw8Jh5*4?8ytaB*%36-&(FN4;-$q+p!g zkI1fO&8n{2>||&)*?48z(&b{XLR0n;8`iXu<$}OwG{rqz=+isypz9sc%O?VhFFKbQ z1dcTm4j(q?UOCZqiWmcj|J%Ak%gV!5X%44E!f|3xl8vlH?1U4wI7Iw%OhoSkM@&#t zmN2PNP2>W=yWSSU# zm++7sVvxTG_+zB}M|a?;pmVM9_t(~dO~PasKUY>`dyLyN0vM=(ZQ5s*SFMUm2#t|j zzkS!>he^xMbF5sd#%}YmzBeI=E)rm7d;tkf>bSfz{f0zBZi;0uwBNeFKUk=F^e)+e z9ABOYP|HW1YCc-dlY(m5y=yH8zx$_(w;K%Q&$iGrOc+<^{{YgpP!pnS(7!CjmEeO_ zUUOboNXR>3*7T7=@m z{RfU4`#t?d_>iq|p4+aRc5076z|b)IIlJ@}jdSNY$&ja6tE!zamTJ&Kbi9)!L01s^ zTGc$b%ECHH$7%Y1YxDT9{likX1i~R<*(0*M~HfsI+-KehkQ| zuwl3GnjXTY@_-HO5rR}e&bxe+9;gc~*-raC!4oJAkYo5r+TY5~x;0UB5g_^RShGk_wm{mo*U>OG9Z<5XpDiiV5+%w{GX58+MeM;1B=rHeocZ1Zh*-Cyy4Qg zUu(nu<;so5eVDzmo4ns`Tk9oflnL;nJxM#^1k_L1u0DUh*LIa2b{mHC1pE%UEGzxBkw1 zmoz}zGLMUlsFS~K$8@3%0C8Peq}^(nO2XgnO&CIK5vpUtjOIkw!XaiYGk$w->&r|L zi@$o7WU={JKF6@#ml7r9DdV7;3;44^eP9q7I$dy3y$dkd`zxGxy98foNCF82Qpihn zhm2at&bZ^iNqI(cJnj8$-eZxXPqJQ@vNfvN!Z?6P*7t@$no^$F`hvp!_bsw5mE&5) zPe@({Kyi!!&|trqchf!k2Y3{iMnUk!W{Y}9y~~i|~q(|#2)~nT4eqEqc<>b$xhW|w)b(x6xmBJeH zTx&tsoceuu;NdGEydjY>tdhV5$Y# z?B$6OUZ$-$`=nDfi0z8Sp_BJAH!KiQJJU@I)raLjtz2R5a0XN6Y4c^=l=V>)UAruQ zaOIR@u{I;B_Yc6t$;#Z0l~DCSI#M%?;9CV8*l7P3WL;qbs`e3Xt+}ZIr^gX9V4mBiw}GLg;Q%u}B+5Sq_Fl1nE$t*{Db~_dyD+EZGmOAirXq!5l|%{E?2tMJ zwLHcPMC&3Y=FuZFAj5JGz+s5lw~QMRqgNwf|l+1ik~2D_t72S?Gz#*!12_5N@3hCA$X=1Y zt>LEBJ$&m2hX64!UM9Hl3oAsXYZg&nhT_1@d;gY$RVc79OMhX(@$&&==%AB}f6aad z6oOPn#LssibaJG8pt=!+rJ>SnC2Kci$rZOlA=9QJxe5K`Bl z0dg{&%(=(lB1+!|yAZY)D&@u`FMZdg+688PtjOd7Jns;OrU>jjb zXV}|uF9W6~eV#olnfe?dD+Lu^q%W3(E7Cnc(63$A5%$+vOnV6`wfZY`94a|1J=O9! zM>3x^k0$I4z^BrGzPr4kw|BEXkFVTnQs=ZV(>lOBqigokZXOX5sb=Y%rlE@GWgQf3 zuB5cNnPs{t0W>u->?{+`!IAe0&-_((I|Jh-?MXXAP!8i!HuLych_|R`p#qK@8z3NN zi>vqdfmhPt9AAqs{aIx$oR$2D9n2HC+6crdp!f#p&vvcw*qQ1rE4)w4ks;=W;poZm zu|H+&XCdZJ=TMGzpaLiFtF0DVIb?U;1w-XIQJe~1cqx>pjQwq>MbSVj zpf7*xBU2q;5q8PUkrG}HQDhIorE1%?1e%f`wEt#eXGtLf$T-eulTe)A(gDmlA7k)t zlJo{s=T{rPdyz6;^hU_7TeDsOW(SnYg;+6IJo^vIve4G;^j!tK1rzOLnUzz&w@3nc zLru*~l=Nr*dF-UN=XoZ%@>SoCMlNBH2t&ykDpdWXeUGRh@^v=E_3+coCUluy(MN~5 zgTN>D__9|;f1)C#*(?v#RtJ9!aEIFLjkEq`?ir82rA9N>22N)YUiHfSidxU*R$G7m z!UWD_G^qq0i^Z(9{x||iDP6V(K4`;b9JHY7d#OOyAB-=cgBNSHy##FfM-8rup0&b+ z>&;eqwPj20i|rT<9XO?jn25P}O^upP>Q(tk&JbhD;my)F*;2ckTv)}vh+ie#`s;d0 zlzQUB!o&2VCFTI-Ys{1d{C%kxTd5jhXvp?&(y-^}?$u;tvhj~YJLQszQ2#Oov$#c< za-(ZF0a3eHB9H8Y=Ouc;lCb3^yJIb(bT}bM(yV>xjftfX@jl0qLSrkRx*t9?pO9Ro ztGK-fWjLmV-+@W|=gsn)%q;xKs(O(}nb_|l0m+!dAr&b_2kFz4GrqoogpOiaBTbJF<~qvbl1s~ z!5t^YKnYr{nE+jGaiQ=1y4#^^>nxze6Xr;WV(?QD{W-+-5wQF9;vmQ~tZW>zEQ3f& zWx!C;OKV+L3Nz1olIAhpRNFBucf2{fp@Z~S;|xY3U!+L>;E3;yI_l}6$rVW;Qy)G) z+MAO5b%`-3uYK(X-vFidW}SM;!SB{7j2OTgav9LsP^!k0yFZ@cBzVWDLwfmar$}kG z(EHz=0F|oTdIz5Oh@#-=yWqJ(pkWv|Nen z?Rl2;Npz9A74Xw@Qux34?m|LVE~gPT(%mWwbtR-Tjg-G)7>_E%ZgY!;jA+n0hxtwq z{-J|X%edS}W8=yl?&+`!&1(s!NR3wX#cZ*r)WBlkX30z@oPisJU> z8)zphyJZl#g>Yhr*g)E|ARuS+cqFZAU3EyI+7W>@v6t%L8Gw(Eg zPoGm@ri2Q4wxlY8nuG|gDcUw7il)mZaYTWgRVtJN>!T(zR_2 zDaZ_T`SwDpf~F<0a(2fT}2ABoB??;_sS8MMVEme1Kxs9pJGjoHnjWtAA4aD zvd#iaRcP7saWe-65`H}zX9Wur)91K_uD6gXpR<~shJ91pNe;3AW3vXLsS_&Bs!MIl zU>PWGc!`Qy>JkOfM{&)t?1o3U2geDcdkA32NbdZJt4n2^@X2(H{NEWMvAT3gds*HD zs;CsY;bIxL^4deC&`9bxL(%KDs)n2jw+zRgZa}F!%B9kDpTo59UOx<(qRX-Du>XJ! zn4-HuJR|Y$r`8}h9T%naBKsvW7o3(tm6aLa(s4p`qqFet)*aS0T_8|z*IHslE9mg{ zoE>(j`yELLE_*uW2$~gA(j9a?KUdAfiLC%G45uIGTJu-U@twWwNUef!eT3hBCZ5wG zq$Wt!NH|UyAM1DsVnFX!hc-7mNvS!U`7FV?VAO@%EkK2U2i3PE5ZAn{Ekst8i#h9e z;Uqe@teB=Ki1u=L!ad8#)Z^!%R+)!O&}%a?y4=Qiyq$~?4=aiQZoWu56!**j6^LCi z7zIZXta@oJ4lioK7g=!XEs`$rVzM5~ZQ?d8;_iiWqkx0|@QUnIsJX6vOb>|R*HEp{ z(*l@|!hL#|PJ_hLuxsA6a&GqkSIC~bu1rfEFam!CMi9#3@Fm~WLv zgjfAdZYtg2!Hp2EMin6P`S1LkfnCYpgu63Mlem1*d%(d2@zwzphd;P07wJmCi;gcM zkEvQ16WI^;fawkFBN$m?9$=6J=Ka@T3Y`L5;n2czAM|s2o@5b$^Il1(&XS0E*q6+S zjl=q?wRl@aBrb?=KoAkJ1%zybe6ax2gG9HKYMB3ezHOr~C@t0hR1{+=k9DwL3icCD zRBFS_iW5T3C1tpW^CGnYk(Pt zO0$5b-O;awa4upLm-!rv2yo$2z>gi-rF9|UKNLwPuEDUDw6-5(iSs&hZWgGr((vq! zJ=I!pbVWZ@DzOp7oZr_J`?UB~1$85gmEAV6*%Ij+&&!&@i5y#XS|`>|e7 zZnQ@3qk^9Lq{ws|e@lsjzyjlk$BNIK&KHWSi9Ez-SXd^s#s)g1pzD_g&aO+)V%LVI zdHD_RZJYKcp4F2X+DHppFdYYbY@cXc+ZjRY0|xW62v=;6N)4z0SSg_8UboB9OWQJ! zCST+2oOFcO%4jtL_bKlkAwB%z?f-&7qBQ+a!iH+>rJ?O*>R~NWt}EzkS-w<3{(QW80lP91tMj>12&|ceJqkZ68wP+#lURDY z-#j7a_wC$yxe<3S7amjn{o|>1C^7>)1Yjju`m{@B0b@=}Fkf0wMnt?$!*rI8^VR!N z{Qi$M(So^>t|!FIN1(x4ath>}ZFVri3_I_!AH6L+k^ZU}+}CmXF;|_x*h_8iICWs_ z4*9vI%raOOh&$>77OW5}8|n%gUR53A126wPoHnU#N(D&pL0xBM0c1G|H|twV;)&eo zSP0OO33}LI4%$<1lkSaY|8F~h{lsHFDJf^W*SsWk|5;?u^-;ce_*_^sbNW7~f)h{) zXyW0hu^np5;#i)c1uO4UEX&^C_v!>jX9W!yqW>VK3&z+>B`L32h@s4@tac|KjL zI`A2k6h)Qi5hZGMlL(brGcobhZ}f@Ve@n;)WxFY`YWuP2w3v*bn-D$jHq> z3#oN^v%vMNOk+pr`jwwN6F51pDhb4^=`aFwM|(85ZEgL|LFfdeb^ljN2t^c+s8Z z!Q1QsRrRu(N%lvE@?{c{a?=>b10GVeS0Cs;T(4OQodo-rPV6|qVG;QuF{wx$6zkU< zt}w73!1Y<0f%(r%`nmu59=rW#e58Y!=3FPRakB{d`fIm!efj zXadFw^8FsjY2JE9rCtl3Uw3-{K|;L>!fMZVZ|0LsuZwx?u!8)9daoJs88nzR$Q-m{ z%y`Yu3d__fVU3bh&a8b2os_b;>2ayx1mNjG56lC+t>V z+1))n4r zs!2FE&Z0>2I>r6GeP^@MZjrfQB0!kz zN3@T_K(OO78Yu})>_8x5)Asx7MX9fxa%-|MkS^f^FI<{rQG_-S)_#}c48yyiPA4M| z%a#7-G*gMgn3P*nu?;DegBfPsK0xgjQs&8Y+u){&#A15cArfCzhg34mgVa6eca7Pi zZg>(W)44Ix?%Xpuq#lau{W*EsumcNoDoB2J(^Qf$VzETIyRGCeHR}okNU~7SJV=x< z+hK|eus!5aZE|_E>~qlg)UzEyQ#VpGpGG1S^S2zas$F0Wk3*sFNa9%{N7?Z~aQGQP zjb<_{&f~Uan%uzhD$SIcN3p1AkZ@A`R4VVSaLF>4g(}kxS!wv9*LF$2)1*B1L5~?T zlaFQn;APt0@1Uh(GB^YyFvKrcAzy0b4G0M>`zC+?sPerf`ZhIR4f~CX z$L2Toz&kcUfH{t#wKqo|NT*nG5RnpCJ0qDEHp(6Yq4*5J*YLNG?q_r_1Bm8APu%vK^pm! z?AROOPWue#+*(?r<;Czo-;%2q%fvO!eR_0fg21S90=l~Y_tI||sqrnrbavLvGnJn1 zqKv^Jt{Bqma9m})EEF`{>4P@oD#q|_{Zg?%In{uNBgMs7bQj_W$Wj7s9oPpnRqHPU zz992yp&~Z4P>lwr=<{|?zYLe1Fd-2Z-+OY^%t`%FgXAK&V5P58^rvEV=BTSw`o^?Fz_PRQ z!linFvJF0Rx9B|e@%+5(L=^b~d!@vaK6{BVbrV1tyj8ZxPg3?qa&a+-%f>?l8~88) z(an-mYZtlW`DCgvJ-na~a(4>xp;0Si8~qDVG)#xIU@ZdEFYR@z7#Btee|%45!XlUR z;l-sJEK-IQg#JIchb(Y=3+Xp*-Kq-t3hvPEsS7ZRz{q14mPS+6*M5QSq6eebn5-MD z0>my1tvgBkjAGA=^TaLgVBdw?G`w}t6kpLZAuc!juld7pV75$x6`|*6P>tIUr zE?l5cDtKLu*g~yIb1{0}ddSvhU$=S};ZaP*sF)`2BPi(*ZUJi*wS`Kce_srlUc zGG-YAe0O8LYuLKdKqVqR&$ZRdo#eyl=|O?3ZIa`upQMGyg7kwx2Fei(?C@QC`28{0 zXU8|7bg0%Fl>jm?+f67vOZ;ylZ@7(Yu_6;(Aaki0scq`fAd5I1hU9WNcc*l0JA`z{ z{zY17>TLKug@<3IV#pSjwU8hT_{al90jdcIR>}or#a~UMrj}uAcv>Pqaiw56s5bRV za#(CDY-skoh;Gjxf&7KabRF*Pb)hTjQwMeT_op+tuA``G=^=#4YB_hutYQnZ;Sc~! z0f7w^oUbgz>4W0Uv@5$dxVUroaBBAcyg9y5fNyh{5aK%qr;_lkA>-xO(2*-z+&n~q zqeicMWt%mirI$?rS6A-KcatbczwpH#v%xoso<_-QNmRA`oeT}<2-##UQl!hXyOAJ> zXFr`A0h(WbgVGu6(0UPJ$Jo<=XHfus2E>rMHu?)hfKN$pSAq0u9<6C%=s(eDYF68I z%h?3gij#2a_gMlebKim4;MtlED}gID=qEV4g2USq0TC7G?J% zq$z2IZr={BDE{uZANb{Y{=a7#BuZ-ZWjA5ts(E48H?7c1pnGmy-f)W}r^&s+ed<Ji;_(4P(iu5wF zCtR)`@ioq1i!G2CqAK&?&mKTGVRyc$bm@3aKjz-$Tb2=`mts3`#I8i9!L7R2 z8-_b#IBt^**2+-Z5;amN`@Gc3&SD&GO!clq9X~NjwAKxk?F6Tu3$!7G65Wo5*}C4{ z`B%-*d!!2Iws&c<2QDKjS(>6Fr89pl4l!B_Y)k_vkdtJX9%(kM9Unz^n_ZgpwWLjR zu7+c#uMHmU1W`Uqz8&%~hj_faL-okx1aN{{!xc<|FA<-Vt40jtgP|6?Wd9FiI_d*|`SKH%#UPKqD2Jy0RDh1c1K#ujr7p=g@m6%|vUUavUZN!X?2t%Bqn6LFD7R8L_ z+C!1}a}z0sz@S*6^uH1;z%_^+wlzz2z2hKHS6ahXx_MFx3tOpQZJo*keY5SX~9m%iFKBKa`IGZ%+-nyD{1GL}G zJr$nhX?aZ7b4txI-=liJ0j#hs3#d0hDW8>~@G-i~1ROn}h4cwFVLnzhRlhy)iWiBW z;QI7O@qn}UC6BwVl5v0?!+@>?ivgorpqDhWKrv9Zdx=&Z_KydGSCR)=HL!N~(Buz` zehFs)&`*)fmz?mC)HUyo#1q4p;`1qnkmOaG8*i#+j7b4LB?Z1P$V!mOKd(Rp)rk3I zwbr@!2&jk&bSSsIKSH2b0z(d|Z;q-IxJTqoExg6+$LHb3z5d2CYtGb8l=TAh1mk?m zmRNt98mX0aZu8y5&E~A*vCXZnhzp5ezwzo_LDzZ00;L?W<+0plk|1~GvO#%3=*TK$0&(e)nwi8Uagiy8LPT~2{{q_ zn+I)%me%z*mJiy1cKNF~*V~T#*W)s?(1Z8J zsOFOaP5Qo^wOwPQl4$6=97XORdOqJFq=pGunaoJri!UZI2w|S$^GAv0K~UJHAI7m@ zlU}7#xJ0~%>+BvmdN=pL^R~#{j42OAA$TGB!9(vBjtg*@W~pwrqD%JQs8<)WAZw@S zcE=;AeLPYaPI*9@PK(ATt^6cTxxMViJ2mt9lQM?(=uMyEz;U%EVxN*29CY z%)-kag_5}o$u9?u!ZWbqydThLQF|TNlISRivgt_XHV z?9@@{PGQ?W)p%Tf42?P)$1C+I0*M!w#9c}u&$!e!>NNK>GlDgZY1Pxw(`f#khhG#p zgQ8}A1>)zPXH*`(8KG4WLKX|Z{msf=unVZLK)oFWdUf7ElSVt>hZ+MUyZ*Q0c_WC| zMuL~OibmMn#(S=wHTkBUFKlh%SLfP-GAgVgfMI#Dq|s5RtV-Y9w$AYqqF0=UF*6Rv zyuul-kKpih^qiGi<8e%!8KFmMukxZ2_4Mnr;_}`swK!Mmh0?-t!%F7dg5@Z22tAZ4&R&6UpPMLGAtG~`t2{H}7nY5}+ zgCmQG^48q=T(1NmfD;+-48=|hwd;SMaj&u0oA3Kjyt~tSw3@@yzxAVjbk)qjooBc8 zaQUN4?C5UnPcqY=1{)I1_3P48Aa5i)xKcgIhgCb-tW&KlBWjmClTw*=PDWHv`@O!e z!Ui-_jO`Rqx8b% zJ)L4{Y1RttL{SD{n2}`^DtK4;o3O$C!V1!QhGX|q7csxJ;}^UAjR<%*##dvE>N%s~ zUPF2^ISynouHhW9y!F8BH#j{x#=5FLW?DqaVw_}?k|s1O!7Qp5ae-)kiGT&$DkVFn zz%>L!IDOm0TEkEg!|3e)l{`xp8BqdQ`s&<3^PTaTPKhBklhW#XZo5Wr?O7ZodeEWqshd0 zPVS-1v$cR~S<|?E`@~ZE8bfwM7#8!u8Wq?j{6SNHeNnK@!Am3!D0`Z;T{KUn9eKd* za)ifTeJ#MV020TIM66L^=573Tz4UrN>WWj66IueHVzY()TW+WJ*G@^VEIxK5whRAv%l(Kft z@QZrRf0=(u6UXJR74p6;SvUhLHZG{{0B!ANOlI0Cau5pyo%>SUKW>h1=ohTKH(nKs z?J4JSdiNx5G^)kJ2RmeE)<<`h%B0a5B`W;(2@TFOV`CNMJiW}qL>l*f-P*Sq(@=^p zf2p98W4NS(wxw24D)S5cx4Z$og-1@TVSP*&r{wiNidXhEhPU%r+v}{gbePI9UZkm+ z`w{YImF!NenVbe&!(4*%6k|55Xi=fQ>2p-F#~iRz3i4{YOJwbG0D-Ko@-&AmN_h#3 zZr3zr(STSu5S)520O<+n)O`8Kq1zf6JT8mS@A@26_rD=pQ((SV! z2w5X9g4lf@cpRd3L&lfBN%pk7wn|I@N(%11O!=Rt6IDp(4~+3XGaE_x_!5KA@&o5l zVx|)L$~#{49@{$5z7-@yrEE`%b#idfvFI!{>_e*nW0%|8WBap9MWn)%zOrrc9 zrNX`|B9y<)&U$6Z3s01Z9)wI5I$8*T$L(7%(nu0)#bMKK$z= zJ7dotxqayb7k7>Oj8zy6eNev)Iu4!GN zsMr2;g3FzKLH05;&%C8Qn%3+sw4ew7M$2AxEmXUUYI zkJ^jta^#~A&gZaqRpLtR}?2sEO;`@rD&4iaJ2$dPnRb$BOhKLIK_Ngy<6;`ev#CBoEA8fIR9O;ch}tR!y+#e*wSilr#wPpB{4=&;&Z=xmSOOjK*lfA^&U~|0eOY4iu406J zB`rp6vVbOgw#4u1ViB&8#MV=uL(>kU8#(E-)EFoB@+_(p64B20ot?+6JoSbZ3Kf*2 z85q+yn`>7NwgUR>`~&0<@sfR8s<*eBwW;_YCQ<{!%V(GmwQi$<4+S{2Eggj1mL8Ts z4Blq+nVG};j}{alFM^Q#ef0y0cg>Yp9j*;u6fGy1O>#c(lpOh9>)>#}}mvnFJk%t63&gOy%C08?^ZA@4K z?Q~xb+x;CJ#Sq#Ck4MC+A5+>4LI5p5(!aVAB+ixGtA1$3791ov3LPR*i~JA|z|SPF z_qJEY1%jGzJY;?F^#aKi&m2vH1yp?=Q09)g?=fut=`-`XLIo=+X#X}|CraVka!Y8I znm7bg&^*QFYa&skD-hpTU4nY%F@-+iIw-@Me6m(99E;-C#}5(eGr_i2hfn_bIc{6M z-NaD5!ey;&jA%-kxDJZsZK=`Rzzu!3quK7_w;f^V)Cw6;~^@fN|T=BgpQT6dCh|Kwl> z9PB}ZW^O}0{XHLj`~=D@*q-iW+Wgs>+D1s-k$#DmEn^6_ZYt}jF)Uro$}er#!Uz$V z?49~(I}FAZA<0vk-?d0}3tJsk+dL{`=wFA~Y7XiATa-hd49p&u?F#xraIU4y+y<*y z7oSoiq7eHCgWAXY3^mJ`f?IJoi-=9Yn?#lL^bx!MD&?^ymEO;zY>eV7Z(^)Lzk!_N z-dIIf#2d2Wy~VyAV7&Kdz9A+hrH4Z_1IuEzWp#I@#l~kTpRb>{TRXO=+qORn=eU`q zNEOe9P^PqrRHAXFq`XdmKex{_{}m}=2fwa#EX5+x{{5Z=NujMI3!@_zUEu!gtoT4j zgtd_ft{MRt=uHU%=V7S%wXa!DL*Rqdn$7*cEjnBva{;0!gLW!GQL(k zmCLB_tBbI>)Vk9-O6A&~ZAF^f3r)0KU&1X!!F8$B1YVY_)a2JFplun6gCCMiKOqf= z)m*U2lMPd8!Ek~=USwoC;G!;2n)-&H@?o=NK%CPFYXRhLi9MU0r5{l9RGToS_QxX} zWxalAB|2?G?V^>$e!bs|Ujv8hZE5RWU*ITPCU#p5*Hy1thG^ktUy`IluzC1QNq8zU7=2dH+C-2hy*! z_-D|RE0$t(GBYaDIjTR4>0=-R+)%dzEWo;W8x(x|S!R8_i@s15rp~1AdfmMSw*tbl zp{WC#wN*2habfIwGf-0654IQ<{Ahz1$$>h{8L!UYMqxS0t`FET$)!PXG1~{6a zkRbDY?fqjuJ^)}f=bl1(Crwgp7?5Z(?MwEBb$p;MNH#HS zoKS2BpmDF-MzNPvhjxDJT*N{%ALW8vm|k=)qM*|JQh>#XY*~*p-~@5Ss5dRJ=cU3% zAo>L`ohMM96X?I1M)40hGfQ0G$DME>3S8(g2S8I2i9az-{Ic^xF+JWRnJ&+;bJuk4y!EkK`L}gOd~uC$ybz zl!*_XICk|KQ+reB^4sbglN;QU!AylZDvrbYAXo3yW$>}hfcNddoDF}JMUxH z*?mMOSrPLG>b*=Vt-E>IT0gDwvI<9tSQXvcX3OeXzTw`S42nt3^v9`?9&nc4gKwsS zD;l*%&)T9Q%qK;f?A^hBl?Jgp-V;BJY`kQgo{7B1t_QHY{Ah=Fi|*tQf04x8d;IHo zEA|K?L3?b83i~X#V?LL8Z9EiKuxS*P2xKjpIJ`TU2@cu(Xx}pWfa?4$z_y~P+UL5I zR_=(gjvb&9-Vih`NI#dmX4v}J(i@teYx8Nwb(pGy`6u-!9oylTb2Ba?7RoxlgnZNzZIu)+D_nst zv`-G;waKdO`na=19Fx;0lzx?Bbv|ALzUQMTbEBbqsXH5~!a(O*_aXkA8PK>TM29e6 zphjBgoIbDiaQ2&K z%ZIU<#6P-tfB~UM8mvT}Q))`oB|>N1j8q86G7%yaz1n@_d*85NwU#%#GD}90Tb4j$ zP*HEw$g2*eXBw=2p;{3gZ=2mEV8h>zMiGQ+eJ2MVblKRX+z!E@9LiIe%f`)#Jp7M9 z6p+;o8c~@iP20)__=(^QpI2{mS&Ac;5wT z%33@qafDYhK=|nHj2*jwn@#%SM5zO&?)d(dOm>!}Q~?&DZns6lkX=^?y}qL-96bo&6bpC{?%QfZ_~Um|M#}cZNnoFX!#RBqc96oDu9u{%*>;>dr%bJb|hdk9Eiz z&C(vOp?sbWm?rR%uUG+#8bj4_D8}Tq%HPzusRefO|myQ>kF@JUpo7^DwcrKa#R<(ZE0X?zX@BguC znpK1L%zIa}l>K2BoEcVe3)Il_*ET?(WU~iIt6Yag z3E0z)=~f`6&Qkfug{Y(6oxhgj@=t2L5T1}hdMlqR{@6Nnd?|EDN>WRRZ9MH7nZv`2 z$ZA!;0#@4EWHwdF?C3SHkK}saUHhJ?MWjdB?euCRBuw|)Jg4%YAQY$CnFjZrLts{- z>t&mg4c=BPY%AVV48N~*G{VIK=2jBN(1Ee-<)$ABo-;84NxLTO6GTN7OL0$aIq%+^ zbpX2zFB0FQLU65gNc~5)McxuR_jNSNN(7Bz*vwKvB0Ht|Txa%j6H>0}rROYmr_*PP zJ<6)j(KkC2x)ckQJvP!~I$ zu9#%ho^--)RlyZPtbxUIDw9U6k!u zl`JT%$9NHo8`|z=d-NX2d?|lrhHaK=kx)j}PmDJv*Ri-BrQ4z>26h^5xMdQ68$+1+ z+F=%H85GHNRnVA*0w=`Msq+WXaCDf9p7nSWK%8+?A&JI-EhGYt`a@mP&UEbso<(r^ zv6{N`tDw4gT$JGO8WTtbC&QMsrtC9&+aDUXh87l>j72Qi=8tN3c5v>%e$*OuqQFe! zRp~Cu?(=>d=RxYqD^Zmi+J%Cy^we&k^G@gOBE}6PNX`y~0_*3sD>5GfX?MZE1Mj`* z8E5I4<`A;!d)D~blW1sT{fMHZtQjVyLP&^x4z%kmx>sAhDx>Np1~kAm`=A+q*=a0x z^U*Id)x6EbdAkB?jnF?z(7Z~Aj+|2|yK=COQzfP<9rcc(sV4?-9<+=&$iI^|d*cv2 zDaiiKJ58DxllBGgl6d)598G(n+q1juq&C_(F5az0(2bsH@=aVe0^u$p#EWxVx^Jp}&}Vo{ zmD*D&G%-u?*zB^Pl|8^@Q9r~g)kag1WK-A*W@?W?_1n0c)dsVo0i}5ZYTF+aW+S+h z4>0yUu=0!sAINtvh6}ma%t@o0cyg+Jqju)b;{*q*7Gl=mqH9{L1V2(p}XY4Cv%}XqnZICeZK}CC~{9AAMYTM{}wEK$4j|w^8(9q zC<$%ee#5_|8Dul&^v?3fwj*jIu2pn8C<#g{Y)ARPHZ3o}N@jfk!r}dTv`QyN$hv-j zEo3TlTALTCuaUw7vlKb5z7HF|*Q1=g%bslcu%{!abo2Q5U|I$0l_yCIS zMX!EH1|1)3tR0&>d_UuaX0f~{1KYM6(9U=nym68mR^u=EQbIj)br~iCU_lVy z4yP5i?uF}ZDt$h%^$P=(WkFDt+*$>Be>xlx zMBPU0RdjfF#_lKU-nI5U^^^1=hvTqElDO@!bT*4%u^2V8CmzHOH*CX_CZYOt7MOcnA2=B152AW>zf<%KUAYz!ph9p$g@+MmaK9{Hb)_sqip6irQSJe)y zDXNxF*~h%Z0j@0q4fXCFk7RV3)7%Jo6&iRtBRQ6tXBtE-DnP!8-BCj>xMw~L{$Hw- zk=4e?O3N6bU|HvJaQOR*V;bCKdHjeZ^|J0bz&UhrU}s21anS)f6Sz*RSw(vL;mC$> z@%bVRcwulKWoqCfiF6x0@CED1;f$Xjn*^m_TGy$-Faw{T zbY19dVYF!s72h*j(|Lf&L=u;=&Mrb!I4g!t{!hdHZ3r`gd{|)|)SQ4)eTm3mdEY~6 zKCNEiiA8Y!CTfU;+Jt#X^m-T18BL|St;cUEgd|~`UgA^dfD{0^Ix#`bPLs!mMxi`v2Qsl^TWO|=8r4RWgE zx85=Y6n5c`_=4N5s^>wW2Ee>d@V~$Bo6V~8NC6P?M~`9&Tz8(cBhE>6#ASb9h)s^B zFbR>IlsYYg_`P2M`7%~Y$@{9Bq)!LSCQsum>c-F_Ni#Z9A%|>i-f6=)o++Oey8_6RHLMaS{BkG*@`&XL~@+z#FtNJt`w)G{ZmnY4Q4p#26HP zbx(zDZ^mITvbS1gR?)DsG~by(_H&k`NsW`j6FOP=MbKRrYLk0H2qEZmFG12E{S62* zMMo>;Z+CW2IC^;Q4{}k(URUNE0G8}`wkJ$zuKY?Qo}Xeh+#QdKK+%W7Uiq2Lcu*j$ z+?$}U&!>7gUj)O`C~B2!Qfries-{-i^rPiE zF3cHrgx7y31S%RcU(k=^5Q;VvLtWotq-ztPG(Nmih8y2%|I$tUU?V7O#$gl+8%%{u zp2+EF7>CMokMikKm)S8~e zK5EqrpX)F{){%zn>&u@*qcPLue{X!h_ktC^x}-TN7%h8nu2PCNZs=QB-^7D??l2K3 zidLIc1iROpz%W(3p8VwNV0r#Vw+bDU$=oJ#p~xq*0eHi%)=4L-R|LFDq)zt@A5tqaf?_nbVK2KpiN}w;^5@d^3(7<`a7SwC*YXJd-uIvp#n4w~ zWoA|-M9j;wi8)VGjhqP|{Lsq2?HSQjr7TPtPe4vi-;fI8O*2oMw*hq)i-DpeI4AR> zo+r|NH3(OOxe;UW1C2miU09RWwl}#!hi|2$UAYI(VVu*>)*tJ{=Am4pbK;I$`SReA z^@7VLoQ!DN*XQ+eX`N0~72`>*g7O$xI!Q%Qy7k;* z=x-twQ`86Cv_Sw^8gc*)K7S+}LY4PiUHVABN{Et)Hj5-gwJ#+6qZcc1{V*#AR2YNY zQDgc--CY}ko8?x=jp|!&dov_+E@KKy>rd|x86g%x+tSKhrucF{fM*%kC8%#w;`h|m zU6L&pfq#;1I~PsGgEutXM_A{<|U_Xv7+P%elszz-L#*_3 zRVTPOkW`n6Nc2y!CgPb5!Ir<0tL~Xv2391ismXE<@<Fn3cDCU^W*6^;<9XwpeRmw3M}!VNbKpiW$P#+ zY~VFfAjsZE^K)39K@GpPtq`e6IGxeij`g7p=!-G3goSL?>I9ix+tXdbC@xHQhm4SE zzxN5XMyip;g)luY+X>k`?SA87%!Yr<`LriN#BB%-cvi@ zxAfkihU}LM#R_2+2rn2wiLym$Jpo=XarkFT((4BpJnb9xOtK&K@t*5=B*T~LXpb4_ za0@c?s$sqm?C4ZY{d8e_%fOl8cm88y$V@<^0Ac-O*kgzH9VP=pWwIcuQ!v7Fy}!;E*@TY z7fy`}K9eWsv9B&T6;M?#3nU(+_iH$%54!KzC->iaKB0$uw}httTiNl_O|HH`Ws!3* znT1r=)<8EaKb`Y z`5ta-m?Cf>egd9I^>%{9r`Z1IraK=}P>qBHrYKF{?R8;%u&PMq?(liii`F^-coQs= zWiff4fy1k+#|=4x#6Um_K<;%DM+B7+aCdS^y4AF=U8Jk<_?v2ud=&fp<`{DE9|0XR zsKTyV#7sCpQSXf=FcO_Q_Y*h|7-GZiufm=e;NcGoKL~IpylG{!}&0nxzKz{`(SO&#BD|iY49HmXmUV5jCU5E#Vy@!0W|(8%WL8 z*Qt;BPJaQMsZu!_Kkl*%sWQyik-`)R>bloS^wv1b^DHQo=bGoSrxhb+%5F&U#x%#M z3nRr(FJkL+|FK3*Z(5>wNZJ!WcM~QHGDQ@v5aj2pGtPto<&ZqrK>jsSLBhlWvxVRj zY!$RRXj6B>YK=9M3wJNuOBy_O0~=$Izj>lZ;znNl$?{YAAYz&h2^qj!V6%`gtFHtf z?WWc|@7g0c*m7R@=q!iq2gZaxK;LO@;vG6q#)JiYmBB9LW3r{j+eZ+Q2Nuz?+AE>qfPqF&2L|)d!ko{FObUn9^7N!P!{G445Yy;>B$zK-Cadt{Wcm@yb{xb z&6kEbg{#jHZh#RpfGuCf3dI+-9Z$$@K)G(>*sp!#e&>)t(l{w7@qyFjZWSUBHz$EL zt>F@;Y^x%O)B@ZR^MGW*AN3@Bkcq641LURYIaK>CW)eq+>VfZ)=Ymd|78Pf9YCQln zi^*gPEA@Z-BfoT*d=|!<%g-FZ$`;hgZMWM|jud$LbxzhG=+h1LnSxdRJ|U?gkJdsrE{~ zdS+ch@^nNtpu$&GW1as`k6fN}6P6v+6m6_@5on5ozwf+pOI$^-{X2V-B2yoOaTVdp z)0g+vR#65fnryQmGaF5!3?@`-qKXIJNo^r30AcoxZuGc9qvt3rdz0`YqSwAPKM4*N z&%yNiE=BzuxAGiZa{7INX*oZtFxapY89lnC&Uc3U6+v1DJXcUsZ=Ox%Bcm%3Oit>!5-T-ekCL2eOkNF=Njf@{S~(5`ni75j_LuTL^xO96&9jW4Yby3#9Fh zm&G1{GS8$ze{50qZALm2Iz`Z{sU3BCga2o1&0IreLc;ckxE8J1jGq@HL%@Uq`javL z?Y;=RRO1TOjP6g~`##CIOocJHE9>ZcX6x&BW>!xTPP8;jpZPD^B6o(di=+-xChWg* zY8(h|-jAlrC3fj_mKhKBhyvem(@!ovuaUU`psl4h{()S~8~;T3g;I|UXYTL$Cpb1n zi7N&=mDo;jA2fqvJLgg1S)c`**T&Vl_gG!N7m*by%?2!YZ}?U4!hjPd5ug?&#)A`<8rPgMvukr4EZyDLDbdTOZg5b%9@>7Y&#~3k67ckHHmg!Xq^N) zW9I;cr4T8XvTrQYZTEJba6?m-)q6fy#I;AVF9RWgPbFy^MsmL=yOo_{q16>+z(!5W zq(odI>NH?g`3cLsba5iCsk{X)TUfO2%bF&pFC$KMgKdw-R*qa7bW~A>j&3J#!k+fF z5zkwc@vq6ltwpz9ZFb$oe86xXMfl)g^Yu(D24#6ZOQqXn&AWj}f&Mx;JaI=%n`3s& z^6gZFNNQy0dHF{NcK;L$q6;jqJf?3f`1e_-Gwb&MCM1jaYStAg7lK9=kGIrYGe1?C ztOjVk7Y<+Q@_USV87oI57Fw`{V0qwT&E{39o;8*MxqEDLrjthM7~|q+X*>4`n0*w> z#s`B8SfC4Uqt*U7nhS$k#aasVax)o!MmheMgTSgXq!+{&@-^O_IQOIg5!ZzlM;JB* z26qD|rK@gTIR#7fI`7q4vlPMffi@txFFXLIl{49THE{k`3;BQnzADXwe5jeFg$~PAj_g@Z+p1aWf42Hvqr#WIE&dTVODsSmq6H zmz$Or4FaeW1E!gU?;t(OCcodj#SU5g;awrhi$-VOo z`Oipr?uky%WYlF$Xb)L|BYdLdX`oJxB)(IE53!HBU}^da`!>gA^mr*%BIMkgxhLyg z-{!{B0mKDboj1H6KLMWLQD8XZSGS_u>>2{$J0KkiDhvTF0SOjhp6GyW;%2(|K?K*7 z!JU_2;6cpp+EEx<^GbNRx#_z9ff9ghovDYL1}QA{8gGyoHWzcG;YrGg!VP!BsoKUc zR`x6U5QZJ>n-YAF9f3c!{WGCDWWMnJNdxW)2bDFr0PJfR{-quSy>F2c{w)m`;@MoG z|BM47^bfFNp_L__Me#ubgZ5hpwvH>T3YO1}()Eq+J^V|}n*d96yWWb-=rX)~BJ49c z6h10!psdF)Gf80-Vni2)QXT7bQEaE36T7yebfxfZtg!sIGebp9miXDZ7IlA{gEM;%kFlO zFiunYYVFImKE#QR;QlF;!=olfawcxURsxd#07&Q=x5`#VjoicB&}*E(;Aq>-0j(PJ z&%sKdwdUL~+7GEp?bN=T0Oh=jC>m*IJ(J7vcNj7%)!wcnKbD5{2&7R<NxddrKVR=HMTMoj z?GR?3b4Lf(GfS$qMEM=2OF7!WZu1vh7lX*y$P-#xz2Wmy1l#{pPj?WYQShgmgIVdN z>jxkYKUEh)5MnYVV*Seo;fIzYpzY%6uDxw;2iDz5tKnUDZjxFDQpL{q4Q;X46Qmp1 zGkKTI_m@|eGGg0f3L@v~U)S2SHb;|Z9R7Mg${ByXOL%#{d#INc7#>sV#M!;e6QOUX z`vnOiP#)Ff-+*3mk-?5LO|VR?iS4?WMlps2Ikmo&fm#tvRjlr8{d*pvRbVP^1=kN{ z&5H8gX31r^FH zEq@&0k(6Mmtf-5a(jcsJRa&nXz@HEmCMH&wJACdX&yL;hv_FZXC59tu^X~B8 zQZRUO+kSbFc>2_tV@s~SF4HO(d!_>qmVDU>1;22H$v=$y?4X(U| zPl=LNDB=S4;u~VJ1yoE+)n$zMr1~Ww_CKv3o{vaA9R=3)lKoKc+QY;2^NQ z>*Mo&@hTAL!et(?lMtLhn2GwOH(2&=n*cT-X>}L>3Y6^XwI4i4qvNnlcI~E&JK7fs z)!ZxmluezPCyboul8=CIT$siOnw8;-7i{%)c63?!1q0$yh#PY!px{0dAg`nU!p=E| z-he^+?>_aRa1~+7H=OVU-5n!^YWHJmQ=T4q!-6auZ2AWTO1YeZOdyAHD<2NW>_rUZ zwf@?pYaqEr3U7l(M^Y+Oe${SBA&~xCxfWqEJ*O2-#m(wbvvBGg%BU?{+yM&EYLkEn zp$pfh@+RM@dj~>lKuWj}O4d@w@W5I*eMBs~;ehV4XMqDImeS%DnLm2C9lg2Pbd{4y zEf!f#L#OKO7`SUQ)y*%Z2d#nHb0Ui>VTX6*5K{?qb)YIHwnou}Z^9R~aDpQ$lpXCF zXKD#@O9^F+sXb?{LAZAybkPssu4k&cQ;f{hwsC>I-FOkS9NxHzi^0{DhK*^zzv zM+%ya3xa$BKK5OZSODNO?A0Sp7V=Oj%Yk%XcA4>hMdI@ECS0?rZblkwZ(QJ_@|7$+8)j5%6|3_~89v@?pfl>0P2w{-ZYa<*N{h`rtggSCEq0#{fY zN1?++z(U)#g@*vvU$78ea}jgfZ@z>G&+_zdC2A1Hic7Z!V* zfXG!gyeVe)WiR6Ea~B%?!t-u%c2Rn@fW5%l!3LSrO<*O9QPtF7?@ja+u4YG)*$>c2 zuzDnHoyn5RDr+PXl7dckeffi(Ih(2wsCt;9>kJF_^GC7*WdQ^#5H(~|8gRXOUXsE^ zybRk+6TOcMtY$re&IG9pOG&FFPR*H?3-gU;39l#htD=B!GJjZupt{8PB3Ie+wtt`0 z`q#0`wh^$QdLgOStpdN1+3C+5xM(< z^>HMLXMyxnCgtW%htrxRHgtKcREGy32GMtW`=f|X-5TwtV5}8{6nI_idBsmjTDYH? z!O~s@MNb=*T0=67D|pZW5zvtl51bjVcL&RPYp9UA6TDQ?^&3hvK^ZZ${1P)YPh?GK z(u>=ud={S4Z)l1G0UJu)^p1pJiL_}E!xW;|aHO@p&b3b%or&7%R-7Nh*|(l~0~uO; zN?-$q5c+6G2GTFMPuFTzn~=yRcGo7hwF(N+T>1C2AQbmhIYInPlgrQb_`Egmt4v2)zu=Ovx#*?a)w)YL6GBk(YbSVrhW6 zTDQ>7DW`^>H7dAdXgDP9fPQTh^3uAH*(%c161F1-RL6(O z7PD7vXDJqTQPpdD^?qoI-?;#l$u~Zf0}Y^!2i5IAYcDCe4+SAti{~czXHJw^r^v_oPD_l7Gft^0laYe-Pz3#%FOSK<JJj`zx` zCVITGAS?vS>YFAC&m^=i{;)!P>;qQXp z{NL3X4DoWfE*rXASU1l44TbTs^z@V@%D){1E%GCM2bF*@#;jEsL&}V{|G&MZSQ!(q zXS%!xBUs_BPvh_EkVS}5P!XN^CoW`s&!_CK59QhZI)w(5L&D*C`^H9*oStBDo2XgE zTmowJMWvxrHy$it)$G<4m@bJ{^XMZ+0<`*0@wpVH1qUAvn>^lK9(}lVuaVz2TfNMN zrvbhp(H{#Hd7>M%^ufT7i3J_*0}Ugs&H6}{wK#|w&k}W>abX8*Sf5}a8-BS+f*GrT z>YQ5e}W@Vw576SA~as3HA znjrH(71aEao&&G4vN1wo+ot3zx! zV%d#fE@$yAUDGtUya5GB&j?1+$RpERkrhn59jV!@0$9f9^a+(!FB4F?rU&*r_02!d z=#oZ;lIfLCzDv_gCVU&}Bx8_EHbMlFBo_B!fu)kZsmDbtgT$myJCQ&;NEonKxOHm7 z1hy)>8Y+oRbvL#mXymNVK!pr%DuKft9U8^RuG8&72Rnb-T8+hbp9TCcb2=A?$~j4v z`ew|Y3EziZu3!}Fwt<_1^J@IUgMHm{IC4eXY8vyKxuIhWs0YcL(acB1W!r-DMFk+1 z&bn?#lOxXRSY**`F%um5HNnLtI^#UN*D2ugtA8;qUtQ=)pmC`K@tuxJE|Os+Fmw)e zWiUp@uY8ZkGoH}<*Oyw@=FLo}^KB9g!{K4N+x$kW(*pUtNN2A=7Sn&^Aaz1CvjQh| z$VIUvP~Plrl;s&~$fJ->t~hgC{if(Oo?uRl=mlp({&k9s7Ww2mh}8pzsh!;>KH`~> zKT6w+tZf3&B)5PzFdv{15MW5FdtHBe>Zl^OWadjHPu`R) zPTtw~N_9(*Av<-LVMI%S`99wKM$kiu(&2aMhIW)II34)OrZm=s?t#axiy2mBTwaH% z$!o=^*enoE{#@KvU6Fu3imXBQq?gkpX#A*eu_#FASfPhF5wtCV0i8Wm@=)jaAVFj< zY=wrZo)4z{bOHDjC<-47tIZ=fM@8i}kKu#_oAkB7%AjT)FnseU=}I_?U}DmbmL?lR zhZ|^lPb&JJA`_!Q@+JNf*vsP(EOe!~_@yDq=g;{C_J?U@(=nEE!-J}_Ki9E@84Z*a zR(Js4rl>ZpdRiL|2YfXz`J(*epoX*h5LoI@xIpdm$>a`$cC8g5<-Gt%DsM*=o1H!Y zLpf-0NDXUJnDMu0-&s^mP)%=;+}yJ(8L8KI`m>mj)Tz^f{@C&^AM_b(bLygNo|BL! z`8VU2{Wg(mbaAX^d?`smZzX6Dp@awg`B8*u58m*Nya+A> zrEbv&-Qee5@EFju@+|ArUZMRl;eZvSIaDA7M zb*_MYx($=qH9Ty@9jfnyyAxbKusiC|I`YlqopkX|V_xm1)MDKpDKoDOTrE2=!W7a} zUP=2cF&i-#KqhU4Xo@VtHDre}<;D^tHJY+JIUHz8yi~lNnAm~$17mS^d;Wp)95%x0 z`7k&M0rP-oqF&;-CRjf`OoK4QhzXV1jp17oC*Ty+y!%F1wz_B!SuXVSeD|<5l3Vo2 zyK&>=2;$IZjadP5Xs5GM;N{EJxNWkRB@$xVOx1djkbRLdx-U7GL{ca|9tU}cKzMar zQ$Cm6RS?^7Jfj%ZX_$Vo2Iy|$OIZb?e9-O$&RV)@lH8}G)*yw(yLoe1!!p}DZL8(c zq6Aue;jRIA|A4qqoZnf@OZROS@(>U>C1!_ui2#Im!s??{Jpsv)NUX$4gnFAc)T}Vp zDms`;WI%l{>mQ`di#iSGv_-1?n3oX#?mwc1btKFUY4PW52fpTg|BC?Q68f*KLqZOi zxiew6_T#9tnhzq7DsSOhl0cABx}Gl0S;EIkhnlq6T)(lENMf%Xp5ewJ(bfFJ`!J47 z5%0%%P@OH@fz$=dOVU&j9*?Ghk;JQLpOG{O1pX!*S}$@|LyeMdV3{_|XLqO~{Cp23 z4ZMWla}$VtEl>2fe`^}vXRqgd^~EIb$o?B`pYTko>>o%^@)D`ci~DTApVIP^{nqNc zwBCUG{ZMk_!S5CiMPM(o9o`ptdqIK8dxn8Oxf9YrPwE@CPhZqpNI6flop#kEA?-^) zM(Fcysd2C9_0c_?XQixRT;7YZmz!jRj(7pQUwvz9qhto|bbQ+pWUK|FC{XR3_c81( zp7_?I(YitdE_0_O-Y)*HTcK8Vpo2t$trwoF^ZD&)LjD-`H#KC$TD6eTFLg%Qk#&fz zKx{4zT<|&95M>s|cA~2g6LX!kJ9Bq@=#xAhUI4C#`k~7|lF1<=ioKJ@a3QGn8rdrD z?=!SuB)4g{eHyHH2AT#=NH4YcmEAD*AQoF!;UckjSSw!a9vKq>w$x<6{* z8|e=h#!HnM6-WaoxF!TS$C{?jLb^30`P=^?e@ew1{<_^4yT9BecXM%ai0-6>h1?PN zo?)qf_ivBdd@{Ed+If#oP=gBc9xNzh04ZADx)&vS(%>ut-^p#WM=p;pMF%WinXY-NB~SY$vbG>aTi^H8LQF08=2a%EQ6vRA_@bI>ECj z5r&vW=$_iiLgGP3p0!=GjjY%qLqJJH0i7$nF$n6-;ZK9@KBZtvJWmhvZwrLePpsx2 zd?(hfwpeC$r_s?&fAB}@H04lg-t5>N3Fcqg5S3SM)-!mT^C`c?%L-3>i6toe)GpGw zxa2Z02F9f>A9s2|-$MKcG>bQj5jYXM**9tdF{6CCth=zl01b608ID~ceDgY#{vlS99BPGZ2w%nB6hDW@8(r`GFS$=YaTWTIAr(&B{)y=_v%U zKUHcfzwZ#;xsNL|``c5$G*0tohDj_^S3+?91`9Z%f$F(E+fV-!ML={zd*q@>acImE?X8vAUzYACBn_ z7TU@oegQ1U=IH+*EdorpWk3(>IWGMUOh&Nsnx(!h2zRN41Ko7CNI$rsyz0zg_m{ub zSP^-T$XpUnVNVuozX1bXbcM5~9^qvQ`Fx~p-i^;b?qQLl9N+9fQ*Z7`$1#JVgCkPs z<`(q~+h)Tcm~~9&$|ymtFProI1F34d70IWY!Is>C_s0b2W>e+>@p|`hC{p{ymq%gt zNVHM6p`m1hcLp;X{L=uP}qgHU}^p62?X#M)nJ zc4!BR!-oS;B9SG3c7B8SYl}R*fQ29dH`(&fe#l1#wo{-B<&vtmuDzBU>g*b~;};h1 za#S0oVab1(IdN)$cXGhr+~bh6C~S%p?M=^HX2a0vq(5|A%xxXfeFAQRvT^l({jWzR zCrNy^F-)mR`uVpr3e_Ls==tNj1NR*2YC@eR?u4W~)}5p2ntx}Xg4qWl%cAL$7UX3n zyR1C^!|f#Euw#EGLM2uGi|EOHXa-X{n-t7!fQwkWy!O)Yb=ZNOzDC?HJ-YCi7>oh|$N;E;%>f}ModgW#X< zKoC=JcqI0o%+{Uzvp4CNRMye;AYG4Uq!_322um-;+!3NXup2ldzR; zwSa-$6HTY~>;pBW^zR^4TON_hUK3|rZ%8j_{GQVdBsR^$F5@y6k6Avc9~@|$CsdWd zLLL!lg{{1Sh@zvg+tl$(m8Lr%NCAx0xL)L(TNV}3UrJ3wqmFMOQZ$mvtdRSt~B zKIZE#wN&Km@;#I7v^XFjotO&|mca7fA@d7}PL2fM+HV&}v_c|(M=WDX5X4Pqg%Lm? zFn3t6DX;&4> z()xrz8^QOEc1rO)jMs`cixx{HE~oI~kK-siUSj$_B!w-fT-Q$GeRdG`UPl%XGFg9c z^0EC06>9R0w0W?Ny5-i8C2WAIJwTnnbd@ZOCw^-8QP_MjjI~MKQ%dH|)f;243 zI`5LDKiGMw$D;1f+G}y^L1tv~D7ylaE+YXQ*5Ciz@5z0YC|)xYZOCA32<&Wciw$o# zWM0}a80cEl3s2+q*qf=n;RABZ(3qlZcsH5<#h(}P3_4*~+Xoa5xt-<7*)Bt;>VyO@ zo0soCVV$n&n*-rDVF14aSuQXhW1^q3Zh=4a!M0FMj#B`ck%=jyQWJwccAEOMK~j{b z#cSS3#YtNqZTlAykU-C9hguucSN)QfWnbzc=RC33&_MLKT+q!=6_wlQ*wP9+mAQLf zZxf?qVy;nYAb@1=7mqcoD;0J={a|$z?Gz)le26#IqSIRR@Gq%|)b`RnQ|~*T(_O{! zk>|kWPG-`8y%@9aHZL0@PMnf9at`oh2py(6KHjGzJRYz~1eY|ef;`D*SmmIjaFz($ z4;0imD~?F}Ny(dE;|Hi$=3P=uKZP%D5@90>sk+>QVbST;_}#`$cD>b7bC%tOD`LFj zNP;Qkrz6I>otcfcjUF$yrO&)Gr9$oqAA^UwdwerZUMKOf7`xZso@0*KS?ovgTyoAo zD;W6Ds|b$m{X>aX%MU+3a{_zlTu^rB(JuExT{iHTcP3{Zt{(t)ZyDEIf8UM)czrkP}08AGS(zAAP97op2)fV@t9%Hjxj#XtpN(x1y8oXwk z8@{CLIW?rr(`r(|wqcQG1KZ2B8I`CyNB_0Fx&T=Nx--QVp;Ha2+>l4v? z3>W$VM}s&+ikKg*;yBRDn_c(Q1FZcZ3mM1ng-C_8mlVG7xz5d{OIHRq-(-`SsXHAM zvoZyd(w|Z}SCfpg_cxHW`eZ?hJqkP3Vhsj~LhD^SP;G2ozs1ieTyrKw)2+k`@+?6h z~aCtBzJXt3BgYH!Hp>5 zpp{a2JyP9J(9})m6KV_{`I`Jnkp!p!ML@d0pi>gqaC*!HejqX7ngza=O&i}^7H3M; z?3HtEFDjTZ=D3gS@f4+8eRfoN(!e5HU@JR(&@^KTN+ql4tdpWRm$$Gos28W1etZ&t z2~&pvZg7TOZ4(`MH8Gq=n~V9VAUdyJS~()2H0<&xKA5@|#f$yi-27mScT7qyJ1LfT z&wpBiClw4Ws;S|-|3&cUWRNHGnSBo1W{6@nd~;~E+?5-_@%VX9#F}F-aCV4=W2>iK zJ)u9TM^oXmn*Rel4R~qYiE|LbtD5Dj!kxbF)kRQ+yf`iuy8a?$+l-a-prF2y`J&~2 zN$#KGWNT_gqw0$yHG5Y0@vYco(KBvR# zOQ9GMyChONx`L33IIqIxbuc_Nt778$l~ zTrDxJs1h(@TXv@-T7QBUhEkE{@@@~7b1q}2&m9d=tHCUW>YA^IXlsv%nfK5n8w7&j zjW5p?cfK^y#&;@)*5ap2IiSzWo+YkT^H0AspcpbJimaWHYtj^*0!17CD)cLVQCF$8 z03G{A4OUHL!Og;Gyh#G4boMU>cxmaDI*BE9PzQ?W{qn5js#J~P5Dk~;2I2y z#7N<&A?^>t#PcXb<3dDc=?8vZU#5Z>ZE5$dcg+(a zK6kXWX!KT}8(awth#*nB6RW(jTUThxDD6V(M1Yj(5Sc45!oY@?_ zld1dty@;6edw?sZSV5yi)C;Xx`C)Ygd?{R3Z_X02(Nl577ROE5V9(devH& zEDNUjR*VfB+#%SCG=qT|^Gx^a2Sf~#^uxdS?U@)Mif=hQ%N%*IdWi-fS3W#ju9^g$ zubz9oxBgdOr;xqjhm**FE`*#vB*&ux!(BI&7&7>!?q)0LR5XnGY7w5DFG$tvWXJ%1 z#%%z@{=v4J>eXf{CS=8nXDnGGL?b!Ntov!YRRDNQ?`R zFx8zz#Z<10v{T@)A^(>Bfjz4HTEnTVFrkyPEi`NdoUa+a?gl29OE=C26)q0j*NF>~ zQITJjigL0b!|Z%wherO~{Z!UY9G{i3{Qu!2Bo}{4b8tNBy#F&n+QU_r6x>%tp6V>u zU_1o0hEj`&i$AMM2sF~qU&oyqOkwFS2k!t09KrGfM(=w}WnSJsBU@lU|mvx%*KbdsF;*0MVoHzNLc0u(%Yv&`LZdP zXR4>=g^J5V)&-^!IC}2=((VKnEhV`m51JKg%+l##J)b=;#QAJ*?bbP<{zx1!L_9K| zYcu!pv)Wic5PuY6G`ftZ79^5{xLo|^_Jwqxp+TTOL?ClU5Cq)+d$&fNxFj#m!>avL z3?K?m!Je>bOs1+3&uh737qyn7_-x#|s~Z3=E!j)FTa-=pK#GF}GYMp&~~!y3-Setq19tlYgYQ-kI6%N!CX z!R3duK6#8r=ruT#kCw(H5eI|4MlRg8xK8x=EvLLchg(MxN;4lnQ;d=Y7>7Yfr+=!f zfiOx4RO)iBcmHtKG+8#YL?q$-NT!C*h#l9KZDa8I=~s2(qR+>~0GmB1{26rK10u8p zuL;kHW2*#My|&40{aKt?FC5{ED`G7p^*M`s8%T*vvRGq7rblxwX-&hXW0;IwD(DMX zmY|-hOPdoC+n07#!-gkVtWo1iU^7^=yN>OK3U5;A#(41CT~j~HC#ExHe=}I?-Ynj^ z;=SHhrc8e~hV;Cm4U^Hk>A|B*XhI7BoRL&;H08@h9y8!B${Zr3qA)3T@&i#|XEe)w zFSSWh%T2sp=7Q%M5iUQ0{r(9%z)8=~N4C*QqBz~JcYXS>%QJ_jDY(N>b0lh(dousM z;4B)KuSrT06VCplwoHn%X^w{j0UilsGZr#dEZMv;%bM-twm&lX8ntVd)x|c4H}2$` zYU6s_u9DqUfupfO>U!Q`Zv06-7V>Q~uLhOtQ?$e}R~0di{R^Y1FW>aTB13A z0dYLO-Yeifk)S-7(??s5@WaGmNXE`(QmbFK5N)pZiKmd|eBnD@*l`MD#FP>J(#^PI z{n_<$ zlWTCe5fI2N%E|NcK!;ScAp=8OEx%IPblE4c2BB*oj~qqy7Rk??ny&}@PKwVpja`u+ zvG1f3{}XEc&FG@-#DMp*&oXJJtzu_im_x(vyWLq>@7gQtUUAH&5QBL9Of|)}4-Ka5 z86%ejwx|twJa8(8Zb(71E)7~WO&C`&QoxkF#nbu`&1IFgQ5xzc$6KJc{+v45&435d zUB(`a@H^vG^pb67u`5RqCwveQ^v(s3q0Na@3_yz-Dnsu_66YXP?7Yt=i!>>A@^Q5a zbei{^2h=lsrha*L5%IiQF&hSWtX~XC2ut_{!Mg7hvQdXnAX^Yt=&JRtQT`|QFiXGOwBp@3pmbpvs1`4AzaaN;1-oWRfhP>O4GBPH{5qNm}|=|_%-JxVljBQiE^FUpwr z?xls(B?JC=AUeW|<$k-m2JOLk-kN12ecp(h+gPc|P!+%Jx8q2^!o1D$M;}480mJij zWtS&pc^2??@YLds8s0x&qtb0_xvTyv z3*tmy5jNwYyz1_6b4{N@?AziUe2@Ltneo{i6NMe>HM9#3bii=!p>$v+tMP6r{ZyAp zhZyvE-qEbsfBu1(Fi}8U<;E|?vFwgA6*i$Y3jToT+7M_OxDY@gpR6GQrNTMb-j$`7 zMhu@l2Xd5W5-Uv(_vu|vboSh7@eE#XRgNR|+y_tFP_w&@`ET9r_>q3*e8MWhb5Z2h znM-j&5n)^m_^&$tKq>qPi?QTK;}7cPp8C>54wciUM>$bN0{!_^#UR!Bv7&W-w&H?` z`NH^1fx0Tq;ebZ$JMWuh12Ldfjx1w2h8g8`dr5EMji|C;e9B~vdQg9W2$Rde5LXLVXQ@vPHgrAd@#D@LySX)aSLAYw zy0aWZy<8A*2?xl~tFEw`JPTtUCuRmgppzyV-C(D4M4iN+-c#Cs$jrbe+jeKA;&1PV zxMMpT&n;#Ajm3c`2@x^ID3L8wCzWkFgr=iJY%t><7Fy2tm@!JkNW6I$ll8T-I`FE5 z+WFPgyidQO&HNiEL)V`s2`(dd0^$5UZ195k*rKN-!X`&rjF>!2^>482IYG&5iH-Fo zB7X)hHvfDnHM_I3h?7Rn4udR&24Q&+`_lq0wA@JYC`?UT1gRnzHECMsk?)H+^DnWNQkJ^?O z7^LWG0#3iM#tz9XG-X0=tx?oqP>k$@tka)|Z*MS3q^vO6EHB?CBj+>ay;THI96wN0 zZPFhg*x6^AKwS~>OS|QvweF5c zTONnsOffunC8lh$#O)l^GhWT;4jYWP&)Taae@AzXOXnFoDGFRJJw)IK{>r@;Uy)A0 zDgGccZleExD4qIzuToY~PSR-+k7DmUwr!-nN&79UIB=_gowpXPDPIB9*BryK{7po8BID>`1v%D@|j=g(1-PZ>3&>`Dx=GK^3ed`JQ?avNvsJn^N%M<%m>< ztuSuSUKGS@v!40KD8!taqmlLWfRqW=!C?k0kS}c{+7LCysYe2q1)9r`=pr;PtFZ&( z`6EdyGA0~7f2B%5M1w13)51=uB*Ke0_Xle+wx^>UN>yCBYs#k>ko-qZu(!x>1Y_=AH~d#`e#E7z^5l%cLpT3t zsO$Ze)y2RmiiU4>Y;#I<9tN7FTK7q)eyI;Puu)m3I)UYm(oUt@T2kQgL=4paH^23f zygFddMUNDLNookO@0ODIK-|H>q3oq>YVp0V^X-yJ1%c3fT!VfX zztyT%a)0V_=h4UFo^RDn*-DD4zvM2TG)v)jO)_-9<8sD&!NBg)o!!eCG8dcHBu}1y ziZ#G^4N6vgdtDEyOvXKCs1bN5d6zvZYV__P!V_tr7)mqMdB$!DclfADUkL1#e$)BI zu6{6B%~B@w;TO3hzAvB125l4a-?M@td+W|>-&D2-(_fy`szj>wK*Bgiz)lkk(5*v^svj}BPo&m^L_7YT zG%B%QP1MKW#9ZztSlCPvvu=%X&)|GKIuMZH2q(_n{hXhmd@)f#(qIS4#M|_BUn4b3 z+9)hv6x1LT`yU5iT%SopOdS}Y!e#i_&G?JI`z4~PhsLIS)s_=Bu}1|@@;MvJFVG&p002=XuegAwwbm#xI4^5H2ii?ZQN=`-^mbuH z)Is%ZFIx0Xm=%d1TkK#*=+`-Tbah6K=h3(KN?tvLkm@a(IFt=mc*lL!jI2(`_7XmL zdxlk^pmiS=E{0?-`7>#U)vy^F7ikjIRvze&DMX4`U+!6o@$nOj+2J%#yeUeI5J4Ma zrAdk<9U*O4);x_-z=@ff#tL-zfW;O`Hg}kY;d!G36s+-hunWmZI0jm> zIi^$jc3PYDW&)hw3mvbySpC;62{Iw$;h!k56L2U^_CmwKl8~Ada8gai|JAjBFJBn4 zW`%71_RZH5k~Rn1rzg3FqzuE9qy;KuUzDcImC_QFJ>1Yp@wn0|Rd+nhE{6x<(>0~b zaiR9!!!;na^#dh|S)0(Ol&(M@?sm@oRO_T6?AJf_z;Z~WyhVo6{e}_MmQV$hIy+=lH-JsbJp&4lDz!s}a?d_tXzG zyw19G@Fg`X30rX%sOyK|r65s5WAkA{2}SKsJoK+&kp}Yc3!bDh#H{Dm9 zfkV!7HzFeryR>Y3S_A$m4KqPUJJxL;sNL zPbBO^6+8X}I}8r<5_&t*{p0Axj6B5S?xEiVz=Fz+?3!`A=5G73N&6o%F&zfYuvuGH zP@EuEmXade)ly^SzC)}nxu>pZGi^wq+28-#gsu8}0~WkZf@%`GT$UfLJ(lW<+%zo+Fy5RY%)FVt#Q3KSI}prbYlzDjIr1L$@VRJC+ligrtvb$*7)*4 zIMBLp)DhCawol2BWFsDq7rgkIs?8&$cx-ltKM{C{(hIbWV(n%^f0zgAWMAQ)kiv;u zjBk;rA*cGWZ6f42^3e;Jx%fX%Ur1c((MKUO9-CzMpI2j3VV{(vVX85GI@~vkwX#th zIFX4MZ0edDjtf}g(|4&J+I14C#y_}NwCt6y5%8?cqs&fuk2xIm#C=|i;(5(WfAc9^>#f#e2A4?W4*7o%|JNLA%Nk~saqlZ2 zj~N94Mz0;Iy4X0n_D&nfT5n3k&u3>EFXwo~ty+JCuTX(Q68FBEK({>q9Z-H`nJq2a zT2T(tlam$&1n;g2(MiGpa}r*?2aQJky{PHW?`l1QPtDJ2!m&L`1c>>Q?c?|Ba>WC` z)-%tiP8M>)AkxPQ3mujUhl|frvWjEZM%GW#Q=3m$>{pkw%+u_SOdPxu0C-MnnZZw4 zRLL_8oh42V@>EF?SsHpi`AkCm!guVc4yigOJ=t(Ha)9FYg{Esd|Eg?ixWE=D}^iv3w`fhYI=wg`>=OLMllHEZ(N-6V-N% ziDvfU020#qfsM|k*Ds@PP)$4k$?h@j3xf`&>qs~tnnG&gX%D=dmZuy% zjus^4zxK^xNb2nwDtYN_n=q`7=^Qy>3Dte15X-;t|=Jdg4P=<_rVN_=si>k zw89C)g;(NwfTB|s7A?{sCyu*k9BC9wjyAQ4PcW2|!*fiCKbLpfS>m~FmP`}j+;pUU7n-B4M`lC%*(RuUW$D<`1T1r8y_-!>DKN(kc{En@%)1^?ewip3~TiR#-h6 z3cOmnb6Om{z13BW0F*ApZQn5qYl` zw-*n%AXob0nkxRTj@BXtv%`W&Cm~HB1r6fysv>{yS`@xYXb#?E@CzPn4)zcj6`Uac zE_y17C~4R)2Xq&d5?q? zcRNOMq`j;tFK3@Ljo9>$ErkSIVVZ1DLsE+eDn2Pn92 zr-a9gBuZaXS`S~g9yonzY}&>W@0i;8`{Qb-8V3Lm)2drqnh)++88yZ>RUGbIOR=D& zsum>ojaI1xA)t0y{5wcE!VJ6U=%Fp++AT#y$x_ySD1oq+68gEw9Y@uo0w22#kcykz zZIL!=BIdfjwyR7+czh%hEXht=YZ!0AyPI#w2fCpmJ_Iw@Dzs{$`)waf-oDb0Bn;cP z@=Iav=0fAN`&UB5&()o;BZwdaEm=5&(=~pSwYQA>_XWg2#KqEo*1<=_>w{Io@<6@E z*TYg$OrkVpxl+zAoBNSW6l|~&vIU_DbVptM3S*#c@E7DlEJKv$5(iN{B zs@4Fdy^B^!`Dyn|2ehse9cK!SovT;yfsnSU;w{?v0?tqn@rO-sokTO1ffh1$L#bI` zzyl)F8*(w~fUr!0nk#*ub{(n4@gxPyg&I*Tl)3_?geB4gJ5jxqhI{$?vpM1Y;*$m; z#n6iiU3XCzTBce(UN`8_d2Uq05*bL%_A_=~rY5k2}o(Li7>4Zn~OuSHeYj8LS+lbw|ul z<>j-m5}{TF;{TjtYRn|{!`WH8fITDRbC`ZkXl7D}wg1Rz^eEa{@dD?d8bnpfWOs_& z`BQ@O^53LzIhEyrm-MSNOzQW`5H+$6$o;DOSU(g={^FPvZ6+b_77a4oaULJ&79eqNwbzGt(Vy zay>L5?3#j?JcaQ?)>Csj zv_xl&Y>D%#H*cLIoWB+i=UQGVDhd8qYeQIvifO7x_T>KWr&6t|v({#8jTV~3w2ycR zM3UMx$df)LPmyAiR~6W-GnSK$34WC=wxwp@LQpdY3=EM6Eb07SGi{t(>lpw^MIAuN zH)uKZyxHzR7SDx0DI+FSYySfHZ^hy67S}5m)k>FU(OYGC4(|EY3X0F9llZSyKJ<2e zo9FY4*4LQulvFPt9Fp8m_-rqCJn)ztC&7u8LgPl$z#!Lucz(XG?$HYAs!Vua#63e( zPpT2lskkw?p*^U_m5AK=#IhWWE;SU|%8R%dC~$_mWa;83-{R|29?F9DYYjOJjD}Wm z!M!RH_Uy3JEk&HhS+Ot}NiYIcm z#OFw8Sa6SFRJ_N7X&3{hjh~pI%F1v^XQKA}4O&=&;Lhbd4tEKu`)W6v=;sOaXm%h0 zeJsV=F=Qw_xBF1R-aJEe%A9{{Al)uw&DD2aM%tt=$bMM1za>!1F?G~ActWoACuwpbcp#k80H)01ex9!D@q_MmNnO zH8WX}fHQIDrcL~x8&d(!>;~2dYY?)M9{R~fz*w;0)>?;J`$+^nf;X{`Ot+_78Ef!N zOWEtX|8(>qwEW~^A`voK1&mGO)gZ>dL#+}9!?HnTjPiaQayd^C2UqU`2LUYzX^8~# zSC#-Tqc&tJ<;`U)=JthBgXtM|F~QRc2rb^-qzd^e4+p;)g_d0}BYkz-bY3HW6miZO z?=4D@yop=k`Be*^*=EWR-Y!o7#eCvw-iU%9IR?6twS6(F027nH$In$v?-qb+!Elld z0HjyTYqyw*=kUL3*Mv1561&c`1a+cH4gqA#cA?>W?&szvf^R;&kXOd$5*U4lUI(fZ z4XxnP+n_ud)a)!Ml_Bs{Szg6IsuYTxmR}Wi<*XLyAzC~y_MxzFCNvpJ6tO3=((QU$ zTb_9800BAgeg6!IH~{8fLjtADI5{g{L-^GsEe%vzjQ(_jKne%?LZM>KALNG1g(0zJB)fHmZonZtt z+-*tg57t(_uJ{Jz&|EN0b84$j<$MmonxUo5+A0U%W-$aZ4zcI^cvwq3-muDS&pV&L zpNvv>BqKE8aB5?iHv~|-PPP&al2p};z@Cz!M*fbg_tU&~g+?+3#2im50TPvS`MWl> zqTD;s7G(^XUl%1;|Zah9pPv=w?;ej3neFr;|Cf>Lh+SL}7 zgXc@0rsKcj2BaIy!jLq|z_oL%*HH+(gNruPK{I^>V}M5Rlw|zCQlKc-$miX!++?b2 zn7g8&KKZ)w>wn zs#Ekp;VHY=+*Ykk?KB3m%2-4V6bkx&ngh3*tGiw{{VTUfHd#X@$ZO!5dkcj|`Nu*e zfdWU$=(dta>W`7{+4B5a{=b}~FhXdK5y9fU;O&a{vQh<^FHV!Xwen*P{e&X==)q7( z1UO{sV?RwvTC?iJSiYTe1;H?o0_t0esv5|dORf-N)Dn4*`e`34y~_qu4tjQ-ZhJ}q zlohp8)a)+?JZ6?Q8yJ0g$^v{jZIN8u6{v+5#mdB)eVFjF`$Aa#n>5zhpSvG8UbAY5^s2^?w%8#aVIFpxFj zVdy@tw8IN6li1;rM_wK||9o_jiUhhGX9eA!LbW_W?W-tUU7kgZYU#(Z`Jd<*=|qY- z=zW$$ca$amjoHziGvW4LMTK&IV~>f8pM3k<+#F_MCx29e%VcP5$hQx`q(wZI(n+xC zzO3*yNvoG#oN`DY6WS3p%}EZ*i+f9YRb=1Nzt%D-1InY{#;#s95v3*+{Nb~4HN0t& z$)SvyY&jurw7eO~fF^bsef`wNuTKt9}kh?nSiX3v3>Y029nv zpKi9|0+j8zB>WRSB~-V{_4Uu2Ov0p2k%%?E;$oTP)g9~4(!G62=ZlkWCZD5cdbgZ-VEW*;|!3 zL>F0Inx-6)ST{XdH;BcMjN?qZLV+HE3Mj1y$5NcJklF&s8{DEPqb3FT0kVSZHAguB z3yq?*IB3{T+~eorRBX`@nhUoI2m{fG~&tg2D|QQ6uO2IRN!e zg8xTO6kP|U$3Apqvs^6<+sddTvd#U`$o?Z}m$3`Vz)+sEtn~Mif4&`?!zL95O%UYv zTE7_nNjgekF%tIGapEFGh3a@zU}z%FnC%Jr3OH`F-j%X=dnl4yD#F?v zETVWqFgs!Vy;y`klkpW67v2v02se=wO5p@C#q_=%ZfTG8nD1%5jg`UC-+j?Wcjfxi z)?wYc<$O`_8etbJO87B?6du0)=RqsK@QDI!id<^_y&B~Tg_YJ@eDxp6fpT=wNhO`+ zfjg$VhiVTRvX}+Neo%AvF6Rh$qQAhefrJJ3N{YD;+fUV-Kd^HeI zWA#f64*vr>30)N`d(Lpdf^n(3^a1UBmBh2$d77XMAXvGWqYc~0q}MQTfPNIp7Iz~B zJ2^85=Fx(lyy$$MkKPB5^alRKe58^T2_ zMJ?vc`m(o(Ko6x=0QcZo>8dCnP4xs1+N+cQ<}hV{1-egqlF@l^q5u_#>6(cm_0X4= z?)2G0=SRwI>7b*p?}ZyH0NxXK2UBz)tnsq&xehyq9bmyLjnV8@bAcqxC28TBkQ=uo zuMxH>7uk%hu;#W5Q{5OC@aZcv_Mi6)yBu$1$WZd3+KrMf|N%W-%jjDhEVJ4=#>OSn~)#!(q<-SP!q zw_oFH#`qIIJ?ZQ#?I~`gh_2TLC_XWMX@-y}3CKM0h8v)Z4{|{S*jPzI0J6xztms9F z?yAO@?|-okxMHXT|4yT-R!)Q(MK{ku!Da1oHIBGML5I@$(oBTj3U(0P9#=xg2W`*w zv@AISc~pst6pG#Mq0Pugkx5e^FrsNke~_ePg0;-|s&3#UE%fw1v5#Tt6JbPLUOEm+#Hn7f53Qf@ISqOwJ zWDZ|XX3%_lCZdXeps43}02;PS>}<*7Sz5NUz$V=7*FbVK!~Hmj6^{bDm`OFwIRx+3BWyV$@-hsk+FUIF}bhF5;I zn~;MN(x))`$?L9ydD25L0xGmvQDH#i<6e~Nh%Y+vCIn$vY1?RxF<$Ty2SafR_(Ga_T6z4Tp%{n|iwf5Yk8=s@NpEEy5ap)@|v)c;4ZL1|P8hGugZI?HNSYK2L1H@2Jd z0y9>CB%j(yeiqxv5kBJC{oKMA?(rJil}tR^ReEDt`xcaR%(F^0@U)L-*SLot+vn2; zo9GA_OmEh?!@%3mTsg`ii*(Jzkwn#=(SB*Ll0{HUc4@4j`<|AFMioH@@~m|8RVh(5 zWtKZK%v_p%IQ*=->`ML+YqE({$1+ucpb5!|rX$VMqK9m|y_JWd!X~+y`-9uJ9&sm7 z`F5_Dz8-cTjFBpdk~HTAW0nq>C3|jRbvRW}pzW8ZPH^%^@8n)*4*{3pz;u44iNG2_ z4uZ^tG@isfz>v;4zoyAcFJ{d9E)3y(Pa`Kjy?1@o@!pKt89b<^3E&pTQ>=!F^xMh` zXY||!W5QksuI6nyfp~Be;sea}RLyR<*#)n_aOvr&&Fvf#9!M;yRlTgB=zs18d#u~d z*n`&K_(~NTmo@8DD(6P{rJ5sXR;?&qcK#uSSbQ|kX{@0T^2Cgb!U&=igWCc5KxBAW z5ykM(!CmR6#li^`{DL9xo+!#wjgBsT!k);HN4bI0D8v|%gkoe2&)6kWUPOuTl+j}c zy$bU)gSTAjh`MB%ueSy$4p>1j$vAP1vu;3p({;6~;|v$VyHe0`2&~ML!U+SMVb*eO zmSThXNU4Qsgu5vqyAx=deh~!Fl!hq=lAM=#A}^_o!E+x!7j9Js6{v)6U7$c0sW@jL zUK&FpOuLkKQ@fWZMwNZ8t#yz+ZP%nC90RQK8J%inL)4pcq&;!pgsl6YwM#sh=J4D6 zv@Up8c4Wo$2{!#ssQY$P9_)h*Da3GR28JZV5;G*Z#ufZ zy<|q-*#-{ycrG!Ww>!fdNjfVhtK1L7Ent+OYRZ+5tM*%Kr>11)FU5+K|GS-ZyiG=W zo-?gS4P7?`QLgN?;0R65pktwT-IO<}x@!XeA2QhCgr96NoIELev_wYk+#oA6r@=B$ z6WLu8K$!vU%&~J15r^R$D$4=`8LAQ)uEZJz`oH0oE7DkKxN5YxUTkyq`1fMB?|9(C zHjoduIs{NwC?Y#(;EIM^vw7~c{1l}befNI47jJgK7j{h#SpVcUR|ro|?9op(BYB7Q zw=`J31!u!={#5i$J`$0pGO~nBlHY$^J#vAX#5zD<#4@aA7ldBr;a%!MG?lBwyn(eT z&>E#|EJ&~}4XH2lwhQzwXfh*t2iA<&*19mXn5s7NBpid&w3 zL~`m=QBgf4mV=z#TAI*b257Li02~RqQ-UtLXJypvs}l=Z-UxA&#>WsD^!+)?H#RC4 zN(->8v^_9B;1#As>PF@ToX>1ObO-5CZxI3E}QJB3Oj z&(hcml;#opTz~~worp_9Iq6r`_LOH|pSb_)Z^j{lcM!qV~aE zdgu6XEPt$gwaFevhC`65xut|tiA*keejH-!c54=sv8~eK2*N_r-X?zGnAG3=TZL0G z88D@c@g&%I0ILl_Ns0-W7V^wNg{U3i4(sHAF;e4V+d^>!Dkn3@l3ag@IVIROp?h46 z-CN^*bBsQunkbP;5j{}(^);lO;GgCsT2)hxoMIJW0>sVx7wK$1OiaLL-Rnd6}XY6iXLYC3ZbwB$=GI$G9@b%{p6Xn$JcQ&HJ!>n(vPr>$*SW_L~br z?L-S~3Vr{1+})88lCrEsOx2^%z}anDDfk;09VO(1za|Tny?8QE^suF2OS46z2Be+& z+Qts7JTDw%AD^*+WTofKM$UvEOW{Rl^1{RievBr~&a0|ED&=K%mn8gpl8xMk)dW}J zLB>KLY~7)uEKy!qps|ys4PsKe=RLVqaHpHi8hX`;dIJ5(gA|kJDyg5};%)vK7r~Vz z*lFjw{%eU>E(3t2$(}PEOPTyo!N9_GxNU*S-r>LhC`77Z9TYXb1~TUvogIW(-K-M6 zm{B@7RIS18+-YbcWZNvde-;Pjd|*%ZVS(8@qbJGOy{>_Rf5Q% zyA*Hgiqy`BM>`@;WiO<8N$9PHzWJ++fYOayhLUGpdS4{a5X@E~k&$2F1w0)EJc<0z z!y6)SQRcrW#6Kjx!$iciv(bx$BXi?S2JDDd#X~^Z;}tY^ytL2-E04|$7#A|6Lox%B z|1pGZ9oU>(PILXapYB#MI#L{8Fz=01AqQxZ%oZ9!^PKkbcp%8iFe!&|=Nzq?g{VMm0s$2OK;AY|lp!F7GD61@eK#x2^#u?lCFL8s(FWQ;6x+ z4xPoW7p~?(Xzu`57)sy2P&xdXF1YEw+HHA8{Z!o@TvW8eQ$OdJIvKpY;}`|*b3-2F zR)crN<+4SP_At*m#mv@ZAq)VmP@ox^i#!k3=kq?PXKQfjv&06`=_WG)E5<;dQOTU= zS)LX+w`;+zmi!9L_jU2})jdhu!uC|zC2XOz@6I$=Ak)9%y$BP{cMN4B@lTfMMUemD{_s zXyRAxwHXo7kS%^&X5+q?GA)%dp55poE`k&zPrzVS&|Kk`ApnY618ugz`9juMkcGjq zK2{Q71Vt3n!1G#jBesH6GFX~YWEliO#rVcYf}y9Nr4jf%&GN&jhAf~Q0kIVy=HLr) zzEl2=RaiKo_%HXAn-~k%GJYo<2O=_O)=*YomV^EHh%7?&1yPu)&?ms~GrUS)vB=fR zo_U0OHPCdVzk7KJ16l)`d(Ki-UF@<`}tu&inhbu>FpOHi&QD70z z09udD16c^Un$y>B!MIU1Ps7OjP^Qv~Vf(uV+hiL93=>r?id(Z0W%owGi}L_Awe6Mk zFsTk-EwYwhom8U4#<`PNqF6%t^ED&hY0>~KmxZ`glir#P5dUQgrA=;dt49k`kaMJ+ z+Zs?QLIjsolzK|%Jm@ z;mAPw`~2#D&imlnqN{khd|_GZ0B^TNLm-BaE_}98YP@~7WD#DDqs`}FVM<8*m4ti zsW^Rn^MISZ61}}cj@b=1mN^;OS^NZPB1LV+iqDErlbE@i$^Mdb3M3(|55hOrXXdSf zds>~rp&H#TuVb2zka%{yuzX?;+1+eYXaF*V$jq;sASTSSo5ZSd+_c`g^Dw zydlA@ZWt%&=8BZDt$`@AA{DWiE!WT+HXQ_>scM~zfYGnCQ9<%bnMT>R8 zv1u(z!PBlS{4o_o=NU4Vpjl-NK*UqNizu?>V3Wfirlk1x4~l~$xxNz{7k=BT5iDr5fLUR4Z1dM!HLoGEv?xMWg8StT|bDfMGDQ6IK-~) zl>E_o@762_pgW3r~5wW4J>gxIm02K~(rgzdS9W5(Y7?uJfdkZ4T z+>!I=^9XB7e2s_cHFhkDPk$K9{vrkD1O+rtZmm<)>56fF$SEntpS`0AD6M!hb8&qE zfeZT*%{^Uv&TG_-8k1U@#RLF$F~K<`p)2@3gOqn*bmu@2&6&z zRKn_-s466Uz2al>ouG0q9sv+DkD_H6XUuvsklq)vMG*r@P^8{f0tKAAC7vi+^=Tix zyXn@`72B{ObxIM!u|ot0^FevcrmP_ zmjf0(ncGOCogT<>nfdE83}NB({Rusz*#>)R9|BsIMVz62mr-;V#pMB9&5*X z8$+@+wto{=n7%(!I-L@Q$Y{fFPH#(Ix))D^#vP!my%|1+G_?mFYHHvxS-2*PFu~y4 z)e03e(I1s$Wnr_=P?*(=S|`9`GJLZr>L+UJ7$K{!8XwHhxKJRRqbV>W+Fotx1|dg} zH*KVyuru)kJtoeOB%LE~;1t37-*WXM`qamyz+tJ)-&;~(gf{w;0SYcCeEU$OMTa_S zC=hU0EX@0U?2j6kh7uX$Sh8i694lam-nD@vAjJ!aBgkg1Gg#-E-Ih&s&7HR)XzU1@ zgE1I4lNkU0F+tcrreC7Ran~&vMja0~XkMy_$BBTeky8NDXyfW{*;bc7mo7`8yB z)zvFq0dDhU|Ez_ozvw81G@7j=ZgBor=&}2Of_wGq0QIDCq%T&#tHrQc?^B5nc>q~J zroU}Y`u!(iDd?V<*Zo7Md)$MDojhWwhNW|IjkbH&*IT2YfDxQG5&Fdp>bgwkdQ#_E z7?Kb#Z6PxiB=;u#fOTJ0%+!G?hlGw)oVP4`V}{WaHHhB@bQV4m=ML0W@8!~=FjvAR z;(L)|9bhwAOUy&Y>IOLM5A3BtRN6sZfbbpuz-K!Z(_IY~pI2iOjc&HCLHMrpz{6TG zq9PI`=$1+ym!k#%Tq1X+PGrZ`PI(^~fA$4YLZk1i4%w_*Lrq?5**hIZdmy_2lMsNj zTo7AKjs7uDycsQIVgo*KkN)*U2Qz!=r4F@5V%nLj_MbfY6$H6Zqka|YCV2fMQKAdeA%8H`^u>kI_zI1I0JsSW~=0$@02VzI%{Cq z$DWc488?u8fKBlPPY*1DpbH{WypNE3@>6KWa{VOn4oP_;rZ?*isg_#p0!t=f^fz#d82$~uv6w~z{o|1M``^5h ze--4{L3lG49{a}2*GHghbdxV0xv|xVDU5{-yeN_78UtaHCJrs(kCs5a66AdDg4?l; zc`l)@891fPvv>m|-ZqVc8rz2b`yhq-v`@3ZGCT4MkR&`dNsF;1#qQhH1PR?Rs{AdPzDph;2*lec{mV5Els4Mu? zdnSnSy(1VJ(y-MzOd1DXn>JD23`}zynN3H3DT#OM=+W`g^-=%^sQGZWaXeX43MP1V-P>^ai7s_ISe=n2qOpcm8a5)Z=cRgg)3tW z^Pnf3FV||BQzM`;W`^A^nae9`7~{!_n7{ye(@3Xo7-pG{=f30PUGaZhy_ly@X*L_t zk?VX)lMNVTp_)Zm#6na9)=V!h*uZlryqSG{$J|)7PBLB|v=y&k7eho`uZo|Xh!T`H zWu`?~(wX8Hvul6tmS*){gYm3LE%kTHX@PViEfaD-19}y@{*)ysJrwzJ`5*jF%Vbe~ zy4005b8PW_Rx7>q{@*jlJh(S~&EsJBaM|nAu6T&>IaY1FfiYQv120VrF|PN|z%K!X z9GT9ok%GkjCPy`c2s3o#Hx%B&D-)iUAbOUD2J^I*{eCV7BK9yu#|i3ICP4q0hGCEX z8A?!b(-*IKnFMVGe;{1GQt#m+VW~Aj#5vss`y;%wxaL zaUea1}#EF?|M`{CpII4;q=8~ejXXaH%a?kOzB@J z4qN7!Qx+0uh+)_ztI=mH_kZhC`XL59tWj_`@!9^&25x6m7iQyN^>+@O=iIn8 zQOR>Wd(fzHcX`GggLA6rcO`uf9`@R^b@pldQ!Cp$s^dhr`bpiDR6Bpax@u@b*t8jy z0EqZAkN88Mb?^qImZ!s^hStrWW{w*nxk}_OucumcYSP zt@Gmv-a?g${ggB3G)8G6kZpB4nS+9F1i^DzF2peNF!&`#{>Z1~AEhE`2-GG!I6pNi z4GopJ4hPYpgA$TVQIRjmu2Yn7Ejw!+?6_xo$nngq)y*Abj#oQtz zY^>YH_DJn1jD$KoQ`ygdXf{2z6lCOA~PO(sXnr<_cYM9`Aw{IGTA4@G|bhpHO zdVix60To68se*N}*`bKCibJxea!v@5dh&IW8U$R8j5L^P;hMX0fDen72_G~$qS7ik z-&vlqJ+OSd9gbSi^FQ1p;H)}ji|lgGFq(#!V&%N*&pXDU$8LkhxR4>f4|s@`zc*1d z4Db@V@_y-&cJnI?y4cXQXcBx;2g=C|cb|&>Gz3Vzfiy&X^Fo8WS1v4#Lw#4+_Qk~Y z=i$x2(1S6-(#l9*ex0ppOW4tTiXmiXzV~gq!$$HpviufV!w72&z+2->Zy+{Os>d~xEreqaX<9hGQxYJI~$*)pSfazV3G7%R>*xjI{q z9JL=G5YBE>k(mfz9SPyomwoDANf&J_T&O`&t0J*z%kX5UO8?OV-o)o-N$$-j+chqN zdR{?ye84Y@={4M#@QI!ZBpRg)PV~|3g|Ppe85tP=T_J6F*!1)y!dk1`#+t*RlNS5l z7<`Ff(=8QHqtkygF>W@BFA&@Ph(+M9gN;^l%A<`hWj4**ib&Y!j^A)k~vKUz0SsKz)zNm0d$eR_lN4HC=!pAQ9ndA$TVK3sa_&UIr=hR3&8}HlDhWAb{mZwa(-@X59>< z>l+A9PU*qLZbaQ-wajBBU^!VF+j=2jc6zx)I4LQd7Ty1_sd@4%J(;-J%wn9LG8j{l znF`z1QCK0Xr?Iahkl2Kf9$_A4MSTgsIs0N>IXUE5>4+-tZV_pZ{G3Oj%ymp$u@PC3 zbj{U^iUbfAx;(8WU%0(mQ;=YN7{R#9T%-2$veFq9j?%7ye|)o>USb)^9(Kl@=(oH) z=wG6nJaM*rA64JdLMoJ?m~f&vQS9Y0dkj4HCv7%D+?YSgD=?~o2`O;{&y{111ij zgSihoMfY24Acf;PcmhFVoFlD+N6DkXnZBv{os{$1AI2d91SU-F#Tj$&fh$HfI0cTM z;Z2YvGB{S0a=IOX+X4Sb@!0e|jcJ{9h&1P29XM5zp?h=p;Vpyi9Cdz=>7K>Z+URu2 z%Xw3ZK@)CQ3!qfMLv3~@%!n{JJ70@J{z7shO7#OiS_=n%rBdy}#uC5siA7M*D;G#l$hc zI}@ED4tf+#5t(RYar`xG45H!MRu7$|G`~fzM`cg1eF%E*`Uu^`$i#B;bd`KtO z0wulD`lwS|ia-HGCPbN&V(Gr zk(-0AAEW;Y zMz0_U4Bff(puh$-WVvg$|De7c9y}j6LQt145mutuo}2%!Mne^YV(aGb?OCm{jHY#m9y$UJM)JfQ{UNyn&p;)!)6Ap&6> zU7M#NLE_)q6BKq`on-S#nk_1%I+10TvN(x0BX0O;VNTfd_c z;2mkNyr1F9QtdGi9!@d!XO)^=9`y96ECj;7lCFDpNCJ{DTwJqJRoMYxm_cO?7oMD8v`(iw$L#{RSyZ>s2%baJCIuq~_ z|(RM09Ge0bpNUHROj<^c4 z$UTahy1UgkhPt3Y9uEb*GfBt`U4Rs^36zVo*i+j#0eQ$#noHEqaEF!3s`AW6g`?W^ z;ws-DQ`qLjNaV6eD&5jl;l0%y5qX0+rw3!5OyNc7$1Avr=swf$pvRP+m7rqus%zei z<*OeY*tV%$kPHH3eV-iv4v0ArKE2kdK1PFqM-0C=XnwT5XT*6woK+^X&GA73R?Oih zS>(&H_yXo9>1IhwjB%TA1+U-!dC51iO;Qn+S{BgyJk0C4&hk+%VBFa20sdoGYvovz z)CrpNyVN^ObQ3A+^?-fI8(*(BuB8`4E5lcrVN%v+6dNq*ku~*pDCZ<5S-Cm%Ae|Eq z^#r6iv68zhb6VWRIWa#~dVw??*q1@;mN)v^=J(kV`lFjkQh4;!ji_FJ0R5y(r;A2W zMv&w~Qg}j^omlQ}cw5x5po&MUn+&_?HV5vde+XdPSokrxGf$Ig>{?dvmC^%_tVnk$dN%OkKsAG5+a}ok z{nYf+Pdk-EU40h zx(%HzaG57kK=jz2bJj-oYI*VsB?^CBC;Aa*fz&Ouv5M+ck2o~$YYWa@^@RZJLkXjo zLgx+EVAY1M7?<~w216&cw&s9;(ei;H7}*{BCIJqeOp(@Qk1pbOlG?4sSt@wk4K&Hq zGhmnrW{NZ>B#-|ohD)(n&&C1{a;RVl0X9FBk;z7cy43O*!{UT(Q^m}`7C zcY*be=MWle;MWGOX+-Vt5K2J2t%zzH5*iM2qoui&m=@|W*gN=of4cS< zQ3PAZaB0`EIEz~^9E1RF4M%TGX(oO0&at`xWb^Fy?oeXh{ONT z)u5>5#X<1ah3Nk8HLbiO4+cxv-LB`zN5?=D8yL8jfPU7~u;D9b`aJpQ3i&CM8<|06@si>X# zg8IuC8#Cd-8!g8oz2#0-9QS69h$R77U*QP@_yY;BbgyI%Ep%1Q42aVu=5}^=1C!BM zc-yB8#kp>#_pW{f9#aLC@qc!MMTrP#H#i8KEv>f?t$AGt_}NqV233RaNi+(xslpKu z;H)E*jnlOy`;2vl(C|eI+yj@TUr?p{P{(ZpFG=7FnZcG!0G|B9gJiL?36fd3Eje+o zqh1jdt>4In8x-AYqP-hL5McGJATp)&;5dkRDpW@-6xIzri={vy6uTDA1^WpiL11`L zTKGdCJV8ieKzdt!J@Hds47jw{BcrN+7F|PuffElh&HWV;YDvjP+9e%P`h0D>0nK2t z0#S3;t$B_30aL0JVPQ#Zk@O#XsPn(=iHB0E96)74J0iHgy?MqeH!aQ zz8%>MqdYuk_uvxT?e&5Flw`e=Z6?i{T;Ng$@5r1_3O6d$sMxpmyp0Ps1&B|%Q5=Rr zgA?ugm(ML+U`=**6KXjDLovvu7ayZ~CF6dgLDS>DMK_P9L#qjZKCwwlh2#8#2(}|O zJRLF*R8$*}cfLDwpq=QTMoIM-ThGA;AZ;&oj7*YoYu4D>ke;$90%#AEG2q&dQpt=s zq`P(vSWb;NT~`q(SxRUlJ9LX-l_QtSD7w~^L~_K%pwH2JzAX^L7;$ooW@1V;gMjgUG|6&utt^B|CG<(2WJX4GIpt6%%PFrQwvnIaV4B;{$EP?+wnKEy_#wzzC)4Po<^K-F z%dUYh1!;6uu(Z93uB}PQO4JtSN3FjuRpFTGd#i!Za{|=0!hI2UOWtsz zLoaYVrt`OUywc$8m&p&erO{2<8MT5dD_pxWY70dXC<>D6fL5YXkuh!&AkeRSAzo$D z&LB@++#BqjyWFtowq|4JG?pIv-BzVrSEZta_d`uz&mvn*Px+5n^5(msrEnIE+oJmk zx+}3rc_E@4AkuFSbQ>{r36T*+L8vPnJvTWo-w!lfxodbB)C17^G8**8UU#Su^19X@ zMDPe$)I;BwwY6rOv!^sSSlij@Ic@hf0qa*`aqWdLb^%O{H)zz2U%ll;EL?`scm zR6P0#268$tpG8rNS>Pw0A6;fpiCJ`)wLgxqZ$c>fqWZ6Z5a3G996HLSoN zGPbh}#2~jK7zBTi_^$yd9^z!cPpOc3I+E;^Xrv$Q(MOAQ4vGH>)^o*S9^i{QXPzxZ zb1Kw<3I14oT1KE6rY9TRg&|ph&v!f|kPF90|KaHW@&CJCD6(3$Z0I1s7wM6qk(Y^= zi1Su!D3!OSo4h&85k!rljsUA}nekXeG0VrEzzeo5S%j5z1zl=JUL23a*cyQti+9wD#dTr!mE=$P}u+{GH6>P(K5X8J0l}+N9;1 z==@jo=XSA<7o>>pTn{3XlsS7_IAC9?hbm3Mz~Fv3Z-O4Mi^e30IbTeUxn-dWOq zKJ_M)hT1Ab!~e}YlL?C;?U7&xn8Vh~ntLbc{u5{DtKY)E@#kn}e{@4AZSHSVeRCmv zYw@5cZ{&Z!f<6(zR>{puu0J_pf+>fO-W1jh_9e%?GAq5OYdvvRz+B2T)YW1u*{EZ4 zl7M0K6nC5qAg&^vtTMTKQ-N7=t1QMGba^>HiL$QBBFnY&JH=X0?nf6F7ql0B!#UI4f+-{bl>H`&*wS_`kOv0}S)vaY(AiY+>$v>dCs{w3FAiaE-j$iO1e z9hEgHULW_HoW&FEZ%3|B87fQxFAI^~$KtY~pZnU&6;{GCL-#dEvSt8$`ghLHT~AWu z6%ShVOAK35)G`tE3t_s30k!EJBv@?O)F^~Mn4qQLE5A9(Q7|=#oZy%&?K@L{1N|hR zotToNSpBQ3c=fAiHupgrf=!?z+Cuqw8a-d{CjT z$1pe!f-94(dWNv{+J~UoxQO-X*594F^OwNcZFZeJ?TqyoXnf4b7QzYKi7jfTeFsA5 z#;aI8h@UsB;@3&G2%9jpw$Ar@wCaw`J8KTQGAt7wTf7N)OA}**PFWh->?9jUoxV(-KgSItSZJCBWOc zbVy;IePJ&7OYBg%+y$N>k2<7%t)_K!7L>ozzJIATt#EWknAkWCb`5^d(ih&YMvq|P z?Z$lYw%%3w_TbslETRLNIB@vfxNs2|@nPjQ|cZi55w9y|Rl>H)&J`M+cZ-*< zY_Mrvw?W|!h8wL4yW<*R{Blfc(w9gW>go6)EN6x#;>I#B%IdoXE8ZLBu!H9d3PsiN z6;wv{d+{{$McQmn4t1swTMU4sGM6~kKT>?nR4Cwtsl^cV<2fD|}QBHgxlxokSzIvzG>e!$bYk`-SIZaaQ6CM2TN4*oXw^e#>OAMts z2y*&qJlJa87nVa+hO<<`puW}ef(9p5L6Q^1A+bFq0*`Civ-BD`-u+;IO za?m@&_i_zQyp>1Zss5gz78*U`$%%8M_%5c2Of=#^a7B0(ehB_6V5dMbe{H0c*A#1Y zX?%0waUs}6Bwc{`4XH8Bt+dw6S_EL!aJprHDsj61H{osWc<$HLFU$coC8HXqbJ-ki zfiNH+i%)2hDGR6{y2w99Z$$OELoXNwkkmdebE?!61{bwh{i*B&zJSAANxKvnbVq0M zUXg{%S*koHO`tp5)c1VpDPr(4EdAWzNK>ae#_gEQ`T@q_0S0K3ahWkGjvff18rGxO z>t=m*O=Fmpn`!m-O5|Wy@a^m3IZWE#`AiMN;g?y%QFkR`k`^|h3AemLk~gN$%z~27?g)G%x zi<1xALiViviDD0dOb46A2=wfsackPAJ!@0f)AweON_`o6hYvEpdw(v)DCCh^ey5Sn zu6$sTrGL?N9!#R!@lI0sH?LnuM`dNLA3QVuYrNrdG_R;<&j>16x?)>tdLlBHX!(?9 zIM_?G$f|`}g*SF)wK021r>0@g)y}iOS8G$kb~`yVBdub67c&VoYz6^+bP0ccOy?u@ zakc@aF+m$VsrDxI4;Y~ngKeL9sw(97Uk*$p-yr0#onf~QOjjbLb0}l)R$k;g4GutF{sDp*F}u^5+Nd4HN;3ky zIZb9?>FYsW;y#hWVV0XrD=9PQS&=^;EvIAZ(Yg%qy@ja~9CH&xqAjeajO)=wS4HS%E4iz0hJ{!x$coc;zAW`h zK$p8T1St1D_Y0*l-dJ->_4jv~{)UDHCDsw&YWvcQG<+B=35uTX>>$|j+W!&q_RncG zf21sl=M+4=Anc}FUAZiwI2Ze+gIBKBBLmjfUHGu@&#N2p9v-f` zeYcK@aY?Gqs(hq!M;}~>Lnoq}`4OZ)PLp1XEA5O+Y{WzR8CjMt6z1rR8L{5EQQOj{ zd7vtddC}xdG-CQ*=HH`D;va&ygaRMOuaQ};T0g4+7TeX%P(9e%mr>d7@z;IgbZ;?I z{p8QxVjc#WrXYhxa&`IT)p}#2iok?s#4@aBSK{UZ8$76bFnxNW2IVnUqiqGH%5pwC z4Nuy?<(`_f%EzdrmSUBn*v-g}zkh}%wM!-Gwt_$3CpV1i6#pLzQw$=Wq)JL4I7=l` ziFN+^`s02st2hk}%e?^|oagz)`-6am)Ib|dI^78HGv~kAKmIvetYs7>M6kJaE_59I z02sNCgX4(CGu)hEnc?J^jbuAK+kE-)GSpN>F2rnPAHV^GG)SpJL-F?hn}Ero3?`!D3c# z0C|G`QAa#_(7FJddP@VJuTT*adOi{*8r&#sEWIJE4A87#mX`1)OCTE@aaz-xHa+L9 zWW9a2UQ7e6Hf`FFo6xrM5s|~R=NaRokq6U* z7#amTb2AfyB5Ve{&Z(og>kKm^r{7Io`|4hvM7XgEurvbvuDy0Wv)khXi<%tqh)sY7 zG_GPll#RW%yN!ycxRQjTtASqS9-9*`Uy3l zkcr+o^tA4qdFq+q_=di>7?i@Z7pinJ;nwoLm%5SRTt0q)fxOx+Y$PpiuB5V zgaZcn5(9*nd}WlvajGy}sqpxFu(6p}b||vnlZ>l5jBkj1YF-bxQCIAyDJlPH@CxBX z2zP@|o1a?~T6Am8XzVM#a{I$s)zM}~JbJFR8qR4-og7{6_$XG^slTtIiMt}E_Q&L+ zD(f;;v#=Jj>-=3^JlwJfaCuCRub%xaRt}ca(wyE~4<3w54E-3HUVOAJ$)S3wogSqQ z!X{#jB9DACKKK7NX6=vQsGkEh5}>k7uTft zNVS7M93KP^*Mi>U68=0U8#H4GGf1o~$UZPKd^9Q`*^)hux5?vwKPfNhG@9ayJkm-- zx0y4x$RC`!Jn`!a7@D23(pvv=hLED0IphQ#ETl_0J`E~g|Cg@6#Rkmg)U$2IQmk0? z*H9r|Lv=*an0;EXZIm-18VLq~yMowi?Yb67np|VR?7i!!2%Va068C+cSH_a3U;tg|hau#!X_OPDjHvj|r6?lgCo)yKM^22!Vlemf*dT0WltCwPY0& zXvJ#p1F8i9+r#*Bz3~TZ!Z13W)vG_Owa!gE7TONZ>KcZaBjfF@3~O9-snKyr>~}VR zfop~T68nN*5ac`9faSTKlip@YrcM%zdy}&^0LTEzGv`A$2CUc56rl;;1nt-qs1p}Y zZGCK9lIpMa2W#no*u)ij%judKRp?sG^oOw{F-_#Fq%dH=P)xC)aqxJmXGa!HQ5ho@ z+h83l0H{;m6*ievk=_ebQ~fW;YwVfNm5gh%3i47UTP9;;75f#&&5RNeZ*b$7B1yh+ zN5NyM-g@o}v?v-oI_!qV%F+#?Y+VL3=-v3$2YkHXGI!Gs9SvNu-vjHyg|IkSs1Mc0^G5U5A2t)YCKDDgFL_^sCUtu=Q@6rX6fXN73~TC1|guBA2yU)x5#y z6Kfxdqy}R?AV;rk9(Y%@huJM27CP19+V&$bSPa_3m+9xav|_ep{V)cJoFV037;}Cjcl6^Kny@*k4U|=y08! z%sy=s8KXEuO3aWoIiDX3SlW15A|)P*H6G@p<#z64@N%qYvFfD zOrL-i-S{PLkozyj+La~hk5=S+SINVoAm^pS@ z1P^I=ENHp=E&YFuQuad7!+XmcB)(OVE;*$wO;%zQydi{1H^6q8_RATu*wq^Qez>Oo~FS{M6kI6-b#}IQCi;tO&VBs{$ zY|t^iy!fLk3<9gq7R_OERGlkU&vWdV=)b(ox%jt%Rj2g#(0B-}yUbI3B=TPzx0ypN zPW2aEkI%lYsc|xCInS86#C`t}} zw11ii1So6kon?>$Yb+u#6_{k1n%o0Ni z2zVtFD5yaP(ipiZFV zkowtLgSLR&E#nCd9cH$%YI{Rn$sup6CQof(IbS*%Cq!JyTjKI+l&bP&UsZQ1dZtI; zh1zz3IJdink~1IDo@2!YygJoG2psqAIA9_W<{D>&ze#p?!vC7%F%k%<65rfSXlB9_k z!URE0XGMGhe7t`GYnuXhl|W;Z7c(MsCp=iLGsbh)?>}dnj^UkZtil(zr~Y?;yK=DP}#ApumDL zQ7Gl(*7Tb3@+UW5$!Cz{=6asJ9Ok9qsDsYwrTdNli@oIWTkAcKm1z-5ss*SneC(qN z>CmrBXq&A35$T8!#x6*?U=g5YXw)~dW;#0It~?kZ@{v_DjLjfcj@z%!Q6;Ry0XZLs zaig$5Dr{D!;J*kvMHYBhY<$)>8)?|9%(%==y#vUUx4qspedvNfIf!H$9cm2N5V#+z zRVkJ&ZcE5k10Xe(cL41O6#`rKj=pR$c%f;&pSQ%wVbDgd7+&;P(*ISFoZgM49t~$@ zD*?C3ljBF(E5o+{FMW`}P9pNaJl9lYp4V#&UtvfDt;|X!*;j8RlvRDqMQZYO>n@!g z^q$r~7+lF`g=v>HwM&HE<_Eg~U;}zp${h?ksta<7f37!yuZZF60Ww(j0a?3Q3?Ivb zFv(9DcK^yVa1|`0FPHX~HC-_j$g=ygY=C(kbp`QiFlDHQ{{c2$vTxMXpHaHljr0Ft z{Ya!!#a`}4S%1j8)mG(0xs@*Z+iAi_m`4 z88K7VonB4}lex|x1%UO)dg5Yg6Z^%zUXARHo#TYATrJ2m86xz>slKInSFUKoL3wRr zf)ii$nRUheQf=ubd@7o}oRZ4^{wd8_BKHOd#`qeuM-4UY`YmIbhf)7>{C!#WW9C9#T01HgwJt@+YJXUFVL_0pYsBTS zD`5(&Pk#~|l+wo~RNW{il=}5lp@D}ihIAz5V8MeWzl^NJU-kC~63F56f{jzgR_R(t z*_QK0Arxe^x#=-})KSxbG6h^WS`y8Nq2^L@8LOWEx>X_HHSj40)a)Y&1quO3<77iO zb$6?wQfzhqu#7TQ>fA3~Y@Z~^`yJIjS|lP1wbs}B8Kh7u z+emmMocx8crbyMb$Gz?DYJ8Xisz5H(?&}FY>?i25y`Q@}`gfg$s&7BJE$SU9dSo$z zP4`MMMJ$Aym2UP$8X#gWW1b+kHAV;8|e zX$Y(yfyLY5wdWwt;2RB-gC};4hGuU9U7`~Bq-6hp8^>Z^;`=EWgMEMG_&Khh;;oVT z&!^^Hx2_c93!AoV9(XqAi34nDBLPJ~%Xewrr!Ynx zh%+!IB3~}cOd8cm?F!paZ&@3ME-$o}{juUd)8mKnpEYP(Mee&=TkBDp)4%C)-`JCf#>^J>u^cvK??Tx)h$A5CaoYBrN`fDcL38mBo zz1fgWbMqE+XiB0`F~(p}*+Q_?zRw0RZ%i7vR~f~?N?VdX=AX((Ag|ej4N4VgA-N(q zlA|)O_B$01-l}uJFyut*Dk`5!C(R2~o5GP#XTy|P1OGT;XPQ$ECMYUzlmqsQj!WCT zu;*#mWv4}KqAx-m_u{GbpqsLm!wqKi2<{?GnMB!`Ssr7pT47qmI@I0;`14gMX(G}H zNhMM)&Rk%dJABy7ni!WG%{#TjVY9`Z0rka(TS;aDEJvCQDE_kl2r#`PnGnIlU zIOS3j8yA!oKqJWD#jIdHs-gR}5DBGSl@{%qebBcdAET6bUN%TxZMtAtBLx_DZ{flO zU)UA=;W{TTIjB9Xrp8gD_bwWdKC9OD+9<}iqiO##4)=Ha`!BXLK#dydlhXZ3d5NKZ zL?s|z-A@vgphmnXqLn>#eyXs1)w9~a4BYd+HrU9ErBdf4^(%($GOecnaa`jFK9GMl z4cAylRE+g!O)wGfaY8@?-RsyyA3D>(KPnwjqa8O@jOB7w2BqB;DjQ5HBO|1^FHPkfb0dXMkF0QQb=%Ht24VK?R=8 z2@LI+sS|e9e=SJT!%m#%iLVL@h0FDPE^^{vwH#>m4 zySh$^J2(;iiyOrvoTc_YHxwk};EyIE9puy(v_CN6I`-80ycVJy{_BIEOmQIA5<^iT zYA;Emn0T%O4)g@@>D*cLXP8$b5Tc&3nbAU&F)6^C=}bqLoK;tU7hOyUgp{PM ztCiue94+q@z-Hd#_}tEv#Jw+w2K!TevHk=WvW6fRj|PL*a5)?C~>`NcEFYz zc7WIw;}AoUZC}q?a;z&I1yCaBBv`rU!L0uk4Xi7Em%$K`09vKz6NZS#xChdKz z{z%7hI<}t%DFUG7nBR;!f zXWjUk zB=fw=Vva>$-`?CZpcGC?Ly)WRkc?RP&mNh#-<2PT6Q}TixX`N4P#^n}yD&%Rwel#;o$E)(Y+KU!^a!;v6pAwkMmh9*_KYq=A9zVuTN;Oy67crv|H=v!04-#&Suf*?^Ta_ zUV$>pP)GRRL$A&4$_fU5wE5^^{pqDMY%ik{JJ0ir-x<&as+op)%NylVy92AOKze{m z>Ue`D?ymVM0k{9*f9I!Fro=FBK7dr``EK}Fer^*2d}MS z38na$oM5E}@4iS1aF|Kj?r@V8!sv(JwY0;!X_G`f+y*ufAX*k8gi$*Yw#$16IQiRs zf<^Hg8yt%vlB#KXOR;0ZYp3E-@3WeXLc=D+s-0(}UYe8lmg94Y2|=k&if_-hMV7~i zFEM}EaDW8BoLTZp2%!B<9&Q=pZZT+Gfb_(I1~)b3-2ohbPozqxiuIFpf*uNVnm7Fc zCvJ)w0m6>QZG@%gk-EfR$TWW&Xme`in^`OP_|4hP=!3ZA~PG$f}Dia*t<7$FOCgi znsG2`*4QL>5oY7KO(Zjcm`0`(AiX|_Wippb`NSt|DU8{q@<4}$)VN9DDfDsV6 zi?XGz8(uy*U)3bi2@>qL>3P}(l9LCW)>{x?l$9_wfB6`R2m0ij@ca@)gO(~7-X4DV zbZNXK=_fhLTV#)I5?~b6ds%PMT^If^CoSCVlXL^E1m)TA*DtQ6b=)#pPin>4WjDgF zWM_?ZgRUC_rI-nIAqF3Q&J-3I(h$@i0oAJcyc$gmsi-gml>WQl<9TM?^bt?mVG{^Wu-VidA@yngE+H9|0CsvT5?#r`RVO2z?7 zx9VHlfBsWp9SvTy>yMN6(E~oQQq9}Auj25NG)ncDIDyfZkXl5`-2LyGa#JESoOAgK zH<>pM)nYvo2JqGw?{~80d<7}HgHVRLB*_{F(yyHLjq}U7F2a;n;}r;cP(R?qv0U8R z6(z+8C8(;-#t$lP zaKG$VZ2Fq>dZa{d%|q_LM1zF8z zgV=g`q^T3+1z|4?{0nb+u+S9$2Z8Ql8yY`6|MN&G#1A;!ZswjS@lB;Z9rUV6| z|DWlsuvh{zs1hzd~n6__-I+l|@}5|K zYlP&Or?lsM;nc0SZA9f(r(I4TB|~bVa&n9Fm55USOF*>0qCEEd zsP;{db_p*yL*?|-plfIWQ@&iioZ&}Ir~uaiHp1e9uQrg zA}P;sDF1}UU{#vTaO$7$Sn^<1^~npLh0Ir3q1x7RMC1Wf&3aM@QKLls=0RO9knp& z`iaHN3&%md8=s5L+OL!*&oyl&&N8C8H)qA8=1eE7MBTR36Ug%4jN=wRL6&Xe9lmh+ ztj2YVk4L#*p$-2qADx;?&u3#8SG{$#tX}p*RKrf=aRL}(42ZR#+#miF2Dgq)M>H57 zhX@67Csb0KzeWfNr6|E`LkVl57+b_Ij>BEWxBkk>aa*vafoHLzAo&m^={~9^$bibC zjX84NO^?{R83HAupN8Y(LHk$k;L`^XTF%@s3Jeb0J;}o5l<8ivC$b$xVU5(a%v^MN zPb^+;GqxfyWWIc^xK0qRRr^g1zw3qk9K3$>u`#Kul?mk883s}US>MQ6RiBZ4vYeOM zC~!Ayn9vZgGSd`OJ1M3xc%&z6L9BFB{T70)ubiu0Bv#tGL90whgSNWk0_}>6Bqp~J z{rO;JUdZloSi4Q`GH#no1AkdKX5MH#g}9%tWT^gS=A*XWZ*_a692)ci${?Hf+H>}h zRnX>}SbbM05jxG?OyWI2Plt%6=A;YdzF5h<4fUrJPxAd<|m zF{2mlBZ3N2QgTfLEite@fJN@-2&9J#zPGtB$Bq|7@ab#JK2RAt;#W13hU$TwbDX2V zsv1aA{fAxS08Fxwd`LW5(>mL5!t4@EMv@U5jrG_>F%Q6a`#VUA`_OJ_$Yn@wdaPMe z9!^b*z22othdT&V!idOx{BrFJ?0n4F&Jn!y$&D0H;_n#_9QQ?zt1?Sxnpb^|w@VhWPzId*9<^3Vk*op4`2f`%IQxwC1sqZG@68oGw^~cAU zVo+1zN5qhBDHxtFO(uTkV1rPug+r&3!Mt-fRGvRhK$g zhpwGtygQE{Kq@rlai=OkHe>Z}QVGp)6GB!BxY7NWKWT%<^VTIR=0j)7xEXR}X*9tm z+E24;(}W7MTn`6Rm>dM0-qXbDdm&>Z*se&3{c@#^MxU>dH}TgXO9V7W@IYq%468W; zR^(ui+;x@==|3Sv1mHN>pu^<2TvLV!`=BCV_>X0enj3*TLsEan^e9xzi5Cv0U3+41|^7__H`$ zJIQnJ_=(zaw-RsK(5j7oV8rR`U$;PK&wF6_Xe|oEGE9w5((|qmX{jhs6rLHazPl$#`}LnksZDneCGVZmyh+{BDlvZxctXx z8q(u_f%n@XULAK&)8_ZpJ5Y;a@I|javdYSTH{DLyjIbtX?#gHC7o;Gqn-rn zlXb&ST_bq@S77aSVKKQ(n_IoH_*!`=Y^zH-g^q zkl?K+)v4JPJ?6;Hd9xo6Xn``BoAO5MOe=WjWhsK_sIH*-5k>EqdF`0V%c;;EYBOt( zExkq^Y*HsZn^YF>ngvp!y!OfTr|f6!b;bk1m>cth-5-nt%Xsc?ku(B}0mtym_7C=b zZV|{IK^16mYGK{?gx14hlh9@C?5hgbGG8ABL1#-V;-Ri3#>lP1Q~o9i5=Y+7f6KtM z6%b|hJlb6*#We;*TT_@3$hpylhqLjd3Bn-;&tYan0%F$!l_^mS>S z#HYVJ^m9Y)7wqp>V(O!NoeT2$LKNWUze)+GRnRQe*CpLdVjuc*4Q{!eMYTmN2lD@2XfM z+!t2)yON)v(gv>i{gammpzJp>&>vuwXpa<%HcQ&o^BByc`qFY)zLhrsJA~~$`;&#{ z>nD{b63>*T=vD#@(n=rHUD*_EqAS6sZ25#oL8$$YcCrtEtsHBzkVOiQrfSU5^p}mL+;4UV=dRd zO2TSt0l*vkIXBF_%Ph49tYTK-V5NmX0fhk^uq141l;LN2)CTTu@BTnb0Jsq$0GxW* zGO$*n@vZV4OqV0hVc@?OVz!$X3ntKj;DOt*9!%r+-xLUJR$olczU#oV(m!g%Av~D- zw}8Q+7B6zEGXMOQre%~`BkpR=H5tQQ9X|Q6hcN!*%nu&<5AHW$IqI#f1`tW#2m!Cr zq5hoP&i29mKYBq+V1j^F#)tuy*ahct@Qf`-hdn32x zrxYWtA+T_sO55QTI9X~OR^(K~Z}1g~cm_q_vPM;S2(9T~Joyae_050#c$Py1=O-JU zYA)fMP+(MG%#%18@-U1tn0mtHg5gInd~$FsY-Fwdfno5U4cA|Du*vG^=Y1nmReI*k z4B&4N+G2-5)MhgWmydz;X>T?BvMZqYWxDgGF0B$3zOL3xx5ldCtBxIW!4sv~`od+# zz=Hoq%aU%mf6ELHI3^CdUN8hmj^VPs(r9a&nw3F~#1Z{JN#_Py<3igYi?zW~&~2fd z)(y$5TO(-)QbMCGgmT?V&Y%z0KP1i%}0@! z&(xa90{w2NIE+l~o82+dK@vsi_*}0ne=JHmVz;w$|9+1fH}dN!P5>VP`T>WwN|Rb2 zHlpCMD@{L@iat*xKGh}8-TkrtdG@qzA$Ljz;>h0e>U~hb=qV46{V&h^eEcGA@0TaR zHxm-1>Ocee?Dk^{6Zaj17(iZE;E$N&&;FcAj&N9vq*Ke&mldFFCJ=L5+%9If=)41E zPvus_5HaemaxxnYAAE*?LPyuupl7@&HQ>14LSu_C1vOuFJ7&ycl~1hg3lg;D5s8aM zu!_Kw`Qjq-X@U)K*Am1zeWI=i61J`K)^tZkhQG|fHWl(YqQ~_>tSnN#?%u$lQqYEW z+|%`qFqEKt{G*v*gKYzy|K6jU z1?Iwta?!kcA0OrwAMt@wB5#$1PgEtziJd;)57w3sc|nSIw1EVh$aILj*SHb;-4ran zA_v`g&T*IieoMW5{%fF~RkU19+W7N}t9_^nr}9Z!05?4Pryv(J&p#xIPy8UU@1pE)0U5yGBAPOkxlsm zFoIlt^=K~{9)lcK30!Z3`DCLsn(T5u`b8kt{7kyzovJyhvpP|>^Q9&l7(^p6-*Pz= ze^clmsDn?9Eq>IYR*OTf^?sK8l^F;rgR0;B#1E@ewS&{B)#Ty`Wfgkd1Tn+Q23OBd z1g~p|OrY6|)a&c?{MtEKyGMGKK!IxB)hZ|Ej^%;wo#v=bnL86cj7FzOQP7JVw;LZUX>+tX`M!d>FQEj&5ipC;35Wz~9oIaIO}c zPqF!J9Czqyq(Suyhjg!}yF%M4Cm!Hw$yZt$x_tLBzg!ecwx?inDwPuNCHl)^!M9-< z(gU@{v$z9w$XF?QxcX~(NC*sbU(1MiYOYoo? zDO%R+2_d5OeYbWE%>^mal&c$2E~g}b7je`NZN~lbBj97CK=U1GtHkr9c&nvA@imYb zBb=2^XtuHPqmCGdNrZ(chHey>#Iq+Ql06F;o%299#J`Mmk4LA#1m*d^iD!<6F)VBK zYN^ch7Cd`H3v)}dDok8Q>I*Qg^R8jj1O zrM&83I6j8#B%TBUP_J-`aQ`DXUs^H)yFCF?k6i^gH0PQb6AO z`9Hw()(b-vV!3{vA5GDrA%Mxb#gjKSQgWBN1`7fWYI7Hlvr{@!V$AU!t}NpoluFdX zPby8PZz=4aq` zrzm=baN;I|JWaSJ?j=>D>^wk-8YxUcl#b)kddl@&z*Ue-&@h}T`$>RG zW3Nn5EOf2?-V9SWJ$0ZccV%^xbL)QTdQV~bJJB!HdW(P+YK#QZt&I5w>nABOkwDgp z{Puk1GPbNrqMA)wvIy;RX`UmU%4^$u&?ewl3J|IY@vYcBv{#h6WhuDPv^$399yJp)VNz!jM>sUr<5B41=c4_Ik-d%JI@3^lVu{ zv$Rdt`VB`^a%5c6E{n#gK%QB^awTKU)?a!X)B_OAL|ZMYO2cQL9lm~zwUBp(1GYjs zwlam(oh{;f(z-F}8X7R7LBw83Vl9#Ko^N|o2|egcJXdJc-h))L z(N1?@-it}#rp3tPIPF+exu;`dUTZabMsU&oSX5fm*Ic zQ>T*$m>LEJ5yM}Ao=f2Z1}C`Sd;N-Om4Wk}U&w$x!;eIR233v)Fq(+CTww3w5#W00^`3Z09k`W_;V z#J%I1Og@;p6bgdJ{Y%IiNm^YINfSuT8yl0|3XgfI@VlBAz^@HN<%akG$4lr!8tz451<2pv>hF!TQDngjc{0mH&{cvz4*mPrrRAlf9U-uu#t z{$!Kxt(1+9mg^GrgGIdqYZXBEeEdVwzPxutJHl}i-qEYG z#>S_+2|9fuV0x8%SdR6xtldS)SFPxV77(V-cG^L~uj9@DG3dq&9k72d{fFRfgdh+dm}Vma%i);Dd>7&Y71npA2H9a-CWcyq(o74$5auuHKJOvPR>@T5cA0P z-8v^0i+tSmCYVUu7S{ZfQ|)}yPxtj53lKxZaLw4Lr0sPMZo1LLSp$3fA!}KVaVPpGuEd>3)k=*TR7u@)v4z0w z&OS-R4WB-UcbaLPs)Jn<<1`#(hDn94hKDe&TngYWZQy5 z$}GBpZAG}sx~FJ!pEiOE>>wkwzJY|;P@ULH`M05=+M{lT9T=(_cLEI0lqu1;kZ!Z; z`OzG?Z1Zf+FGlgGR;tNZ=@T5%RPf$|Vv+`3L@`^ZoB^N9(qCo@g(2Pyz}TyXKA#Sf zcXyF=?cYk=@0!MrN4r)}j$Q*;}G8 zyzIxw`&rptSzz6LX7_+>r)6)|a;0vv-<5@>Te@~IWp6~{UQ0%IP_WrjxcVb+di)I3 z3Hdlv(hIP5nQa@hO}=n!gI0ceAWsh5w^m_ye9aWgxbJY$fwii!*cFk&t$NyhnnR9} zN!Y1l+0jXf*sn8&cdi+cqVW5*y~*^BLYl8z_aNf%5pGK9LAxk(X@C%zM=5 zU9)gs1-E=XRXiKKI4lK|yaxgbzSM^#I! zIUIgq?ty<5qLm_>U_YKJqMh4%3^IRAru-L1#c}%23v2u68*jJ6rZ@XGW6s@gWigI~QB~T0H$ejl~tk_ysfe1;nIAQa{ZJf4km3Z=oUhX_7K2!1z z41~t7(1zI{@0bi694LG9fLA5T#U$oQTSsx0UYaoQ;Ba6Dju$YDv@d1RcVE|n0HG7k#7T7K zY#NtR&QqKBf>I5w<=l1fp}XWZD0j)0v1(m%+bETjHLP@K=(&YRcy5{&p@jxQ?daoI zXuV@$YIQVr3s4J2tEu`uPw;-vD{!HyaMk^_Ie^=gDNh8~c=zu-SWoAeg^Ov6&u7%r zjT}4BL7eur3bA+>Az|+8WJEpO2Q7$I?YyDSrh|CO<_zjUT zl9DSpxL$Yk!V;=nocAeq*V}X+a$FddYIR(dcitdgMzNP(gh#Ph2+p8r}kYfiNIWghQ zTYNsT0b8e^TkJ|v1YJL`kbR^l;I9y$G_RKkT23tnYQX(v9|+@GEmnl7bQ+A^#ngL@ zyptc+H_Kxrl*9$4QsB;!veAJ3|v1lP28E~pA z1{xFq&(y^^adw9#1RReJ;!<7(fw6!qF`TK@Gj9vb`oN@ng3Fg-Ge7;mQ}w(lV9%{7CQvmh(H>P%>YQ;kx+l2^G2SEL4NZGzRHXy_voEq8OSz0i6=iP4l)5&xhzweC*~1z&R`?Y)?!z4(<2`I>jr(MXucg&k)uqUH?`+ zW;Q3coC-U(@C+x7<8W)y+HARN{R>1Pf(!k+Yy(kF|IiLxbk{gJ--y8*Q&ABpGEnV9 z+{27g#$vz$QWybG32b5A&s!L-x@}T_F*idn;*xU0%r+X$nkgnx&|q$j-qs6b_9I+M z;I&M|@Xd<4CZj`8kXR@J0rz#kS5Tgbok$v30VZ-ki2^j97YT-R4!Fu`^;<950A}_zSu7VFK~KXS0&P{B;x37x*>ci2ykbmFQGW99Pz2dT{HZf z|I2J2%Nb1Tr*qRC*DNMt^*A*OA+zPeWvv*;ZfU8l_l+E_!H57_ zb<)6l^Oh^W0py*odKpkbZI*Gq6e-+wslSkT@4N{6HVvw+U6s8Z@IK<6YKMVKwo;&~ zIalWLV!wtu@?!ro!j@w_L0^NADOVj>U5zkJfvlk8Jpf%6ppO+OJRj0RTSDTZT76~c z1hn%<7LPsMeQQBchwso7g}ezTJ6jGTE_+78!jkFY=b+K@Lb})E8T>>;he8ePx7MY& zX->%=<(KGu4})kNi@bpmcWG`!*AIuD=TZ(3FUJM~tK5%@Z3eQS3``PMMWD�M`$bw@I1^r~tr0%9~BK zLN-|zwS?}G)IST!+SfD7Chiy1QEW)cS=q(69a)1)fVh1!NSji_-YY~Kk69CTHGLuF3|3F6yDD92m47j)5Wgl zcDJY^%suoi68D%}ws-)xq-1M3w7JiKzJXb_G?}T@8fgij(Y?tA7cCQp)74Uk9VA>4 zdyw#K=GeT;T` zrp}bqx90!yBSiz!t;1(Gub4Yt2oX^`S%khLE&MM3)_%l9T3?CVz6rF@_|V{1Mb^R zsJ)U$Iu!9qgL100j1UX?oJ+5ObirA`PC^jGuk5hCZ5!J9h-bO9bI%(f;RmadFzt_W zh|&E25g5$1?4$-$!_{TxRSsL*3r0K8s_UWz$V;-qRSC_5HH0S*h|dKM3-SOYWSloD=r8m z{qeN|DioO0y`WW9z7KJy;x|MM!8-T(lgBI;Na4ju0XU`!0LQF$6Y~;h1BwKwL5`l>&7onlSwjE^oz z^n@?O9V_sL6Q@6@-5Zb^a3(aJdgO%UY0I5_cXWXI%c~}j!=z|4H;>f#qnYC;teZoU zWJK*3Xk}H?KRp>ifJ9GMeUoVB3~vP{cr1?Ao0>3i)g_QO?auJu@I=nON>^B3Bq9Y_ z0^n3jN}7c>nvn&nt&d`;n+ALq54%sz?2)T&?f zR@MSY-kOEh?Hdj;>cm%eLtHDXyDitHzzL|sRVCSMAp#;B#tk#x<)Sf3GUq$k-E)b#FEFP5LyJb}1#ZGMy!>}F8!e1# z7II^lI&4SMzu37Zi^QPbfZf-pUvQwF-p{Vqo`4e<>mdEf@g)~kwNd=!8C7;uGN580 z;#k$Nw_10FNB1d|O}kA2fm+zE%YSWdfw4;P{a$Y9?T*}}05U1I#N1PRxRt~TO+igQ zADUg9sGzvuJONe&S>e+yvYL zYO`p;nBA0zW*oUnvx#4ygl;HNi?Y>^kNN_W0c#mVpwdRJ zLTF!hrZP~Yt;f2H6E>FN?6U(Px#1>X20OqyS_Zl5Cs_;#qq?e3#vy?ajkz+i*vSat z$mRf2=u5No`*Qq!o`F+a@Sf2DM2{9Q9uq1mGn_@_=JvQn+N|eDQpP)BdP1pyj!11W z3D%DwB4&P^&7-?HKCctgcrIYbGMtH=#DS2p=b{5#p5@;$*`3R~mv)xcexR?Y+M_Bn zH$Yp&_O-piBzWpq=P*R5^-!pOHJN$TBjQe9Daz7s9ZhIc2hxRl2BG%p3_H^fJwHU6 zI*&Je!RM70RjXVGs`NPGXC=~2IMI3ZZfC}iy3S4J2Su3W;z>UT*yBqFw7{6k*#e`5 z>DH3=@{d1kS^_~2q2G|oCCf)^rbKi%Y+~S~jyGiSFCzD4)4{_QzxNtXqEJt( zRabuT?^C!DHf$PTYUq(8ENY-U6_%BOYBS>+n|B3oCB`&NpHip3z7lYA`@cr<8-tP@ z;kjP0;EaB` zoCDj1b4Pq)dcoswy9DGCwIA)XV5BpOh4DzW%Fx+!3UU*#e#W=qYMwU#; zK5KhKB$x$oMH^F0B7IUB58`-D(XOVZw>NY&>eLB$b@>@7d+^ligdv<{qmBIQBWqUn;iK{f2hfkOH)ZbQmOlpkhS&P z^LZHJMY^qX1{=#XUWk@*wScX;fVPH&+Wpu>)w0(vvT7|&mODCk(^2}7PVNZvtB6%j zJOMIL;|T!R6{s>8_A+ym3jCkvm1Ra{>tH77g28si@$lD&x_R}-nPpoJ(14ob=p8$AW*%Bf5Q}!}icR(i-F$_qm$tDIUHa=wj)Z6vVOf`ylu1w+ z$lXiYDIBW4?~(XPqcA`24`&JFhIlV>mLvE!_UvwzcL=TEi9RRbtk0F&unU;kBTEW* zi=$esFK?m%Afi#CGm%{)<&pH0-8)K~8h-vMB!fFri^x1@w;kDdx1OX0lj1$Xb%Aqr zG2k@z9Prl;^0A04W><_1WXOlZjazGQ#C(nn9f5Pfq@Xa5%_r|08%D`4GdsS=3OOEkE3L~Z^EjVN{HQY=smp?U$jama7epdt`28Xcx$`U4X>afp2vZm@dfKca`^jg&YJV7r{maDhIGA&;3kg|Fq;U-i+yr*zFuBwFoTs z=r45QC_JXDBtiY$1(FAslT{}=l1GsXl@%g806q_@;z#xg-t zAtW}21#v=r5G=_EW1hk0278N(>Zx~bRyVTCvMG#mR1mYXNbQ0x6vn7f_p>(*h%WuW zP!cZ%fA(!w1%uO69l9P=%w1G%0jP9cR%yZIgF%aa*t4V_`n5g8V_o`t!70c|M3Vws zkume|atPOQ)N$S`^~+l(k=nI}0)Y!(3N#_?XU=rO4XhP2S3G(j2{mml(oKc}y$8(j z9B-Dboq5~C&3a%oNjIjPQ%gBYtEe5H47wjHZ4uCoqfvPC&I36bq0F)BxC5krX)s#w zK?wNJ`R~VvQ2esNLeO|Xck{*r#Y$crf5lVDfYtu~z|)0SOanmb_oDle^%TF0UZ6TG z@@inf`*5`6p`_lAne_Ra$omdx(orB8_2)0UnZXuPF)oE#9-a5Z7WeV|2z3g+`tH2< zJ50YB67|tzcB8;0gP6154@s>eN3Wx60SeBpM~1}L`K})E?D;exN%odpZlpta1pW?z z329lc5j#{>TUNO8jL1YHAf5dOo(UaSEhr8;)~H$o0CVnUVVh|8GbNd5V|S8|PybC; z(ilq{GasR_8k~VAJ@@-|8s2$A7>(F!hdb?~kJ=pK+`*{f<%97XZVGzwB{vYyd}}Ya zYy)w6yV=Bt2D~*B1h^nDVF(jic9iF*u~5i%0GfhfC*K^Q4sMjCNiFCXM90n^{+Qcszky zi{^LUQ&ypmIxAjXxGwSz69S-wsZ$3t#Z;)V;9qb@`b$Q;XH>EOQ;4Op@E|mswD&8e zOB8wFGmYh`y=Zf(Kin%1hKmS<^|EiRwZ4o&Va}W6e(+H}EeyT3<}W=%^Pi)L@e zzwa)a!l?V>)CTWmy!~bLV_5fKtYSz0?~|%C3Z4*INA+^1Dp~}0ha=9%QcVI(9Qrt` zlmq1nka~5p6D`)H{GM1vfY~F;Od8_mlzU3+B5@yqW<*DY_rk?#xojk!gT71QQ{jVB zZTzFBPBdGfPxWeSd>#t*q!5m=Y=O{(!ima>4gRdwFkTq2QXyN!`kJmi zLNICmI|Dq(K6>j%mWXB>rbF)1#d-j%q^w~O0G@M6M3EYatT#i z<%rl@mu}Zr%qMI}q0^dglIElK~2t%=2$g*VsE9l)1^XssxbWOL5o zN5!*BC&O&-+D`5RYkcba*p#(fvwCNBU1KW4{LmE~dP^3BjRBTfkEOn`+p1>-xjIX) zId}8zw$4n)Q)I;6geD{flLkcE$%vrhVTNe|W#pMRT_}XlL`eI*-nJ;{zB&qczW7>_ z=?U(4I~|eo3ZO3Hf~DGo>88sF$LNK9s~iXQ;t*1FVI*i`a$(1i?ZvW|J_} z-GmfWW*#DrCHbez0au6W%3gg-YwLmYB*H`Da`RMi^xaY`C)Z9qs>D7~$%+BoRq=Guy_V6^LKb5t1dww380hfuG{T`W9%|9rO2RZOu!mGRqqyj8kd^eHZ3) z8++YH=ITvQx1k!H>Qilz5U+}wP7exZn*tXd$Z*I1KVBhEuKQzRuv1=;tbv5DSwSQX2SiKwzS{I@Nc2PCe!c_)hpO63Oo@0(k!*5$lKHjAyn(BIb^(61lYN17v)zD zZW(P(>LYN(5j|eG|F9Z81y+kY$X-8~UJ6UK$@cznDkhewsp=L_*Ejvj?n$WN^KkJ` z|2SC|)?KeK{R7Wx@|nS5W4E0klgREfJ?C9K8u>hM>!=R}4?+%Hofjt8TFO@;Z3`oH zcchUy5Fn2_$%Jxmx^-7*)y8oLJ>a$4D@L4Eaho#RE`=I0*5QiP#AgsR{dU3a>AeN! zGZdop7trcGy73*eMjC`P?-{0kdzaR~1S~JEy^(b8y+CJ0B*g~>s`EIZI30g+8*WLL ziN!FIO4bwr3xJ@I2{!nfCBVzWCCW^3C7KAc+8Trs;y#(?{ zs6%8W6u?cKEU?6nGV<(+K{&0}eSq{;M?l_W*fDq1cVq&W>7h~h2hcUmMZ;rAKb8=| zkecAV#iwRffPRP)LNf>9+cxFgUDr`ap?l`~zgc2!1Lt6^yYt zB3SzW`)tiVt{{X$ePp&eESW953QKZ2mv6_|XN7NjL}K;`BFpZ)>sqVqn|-k@?-NRB zlKI(uV|)qR5^ZIHDJ5sRy(s)*azqrNrEi&2f=|1($LTZmY(Dhwzl@Ti;HK14?c_CT zzIJ4I^cd;QT^vy^PQWqDF^SK9h8s@Dh1w%cCh4VoQ|+8%>MOY68#Yk~Nl`4YDlzp9 zDP4^C%Imtw3jYv_m-Dsrj2{9anr%?)c|&%^Oi<{u4%W%lu7_TUqu-6+HoYXpUi>L| zTL!3}jt1ZP?X0LLV$9#V@5{Hw-rZC}M@pf5Ygjt*0(ywuv+&toU+0fUUC1aF^}iUa zAsP`tKn{`4NjJYz6N^1mC;VvGB#}{3UVd10R_h73VwM?M-bh@2{!zX{3lRzx=$Sq` z!+VX3>*EY3pcE&Ms z8x9tP%g>izaJaEjqeAv|HBub;5#z$>Sy)w2y__++u+sg5Q??-Bl$vHESdH%WUi|7a zC|(A-8I@l8DT{||noZ%2?nQ8RbCq*v+*e|Zli;1|13@I#{E}Z>9bw%v#f4Gh!0i1I zBG6{lR83kD&#VjAiAWg59BNO$jfE>d9SbmuCx^sSE`l&N@~)arPZ<-gA?Q^gL4YgG zIC@f^zozD%WQTec6gQON2m*EHFlNsf*O9)5AZYaCp&zH!q<8BIE_ZRxTphW7#K^r> zUH-O~evDHtz>Hdi-JpmJ6_t~QktQ~`ZV7=h4rEXVn^ zR&?uo>4{wtS})K4bz(_aZ-Ag4i=_?AZzLsg6P9j%6vUJTKXA&E#5*3Ul=Lr2Hyety zhR3l?3J<-+2<#!l-2^3cw=)(9woKuBZs77cu;NP~VZY^->hb%HK!m$oMs+jaq{hAo zq^E(DQpFbit87{xbS^?@YkYJ0spkWhiq=RNIyEv=Cb1vm^)hhuj+(@N=;&i&1JNtu z{|pb;xJazC-W!2BGzNKNT8F>qa}iYMw%~N((J6gaOQ$~qqZ`3$N+E%T-yY?2k~KzA zN%ys$b^$+zMPzV0DlwE+T1ogupGN`7G+o|26l`-jq5C4`HC`&D6nhHc>5abd@&t2u zCiCy4PM1QZ4J;fjB}7c(a0VTv%@s^=hN4Vhp|@G7^J_Z>SC^LZ-=WAr$)`H5|FBYL z1m_!JFxZtC3(9z$_BnjRsC?Y+8pUVJVHf`TMdREC7E#s)P)bW*O4A6}fA}HzowqS~ zWZhN9X4yA`f3sO5QSzka%$6GYI6DVO(UN>Y(O{csz+~vwmkS}zVXX3YAOgXr#2F4BnlRaS;k#8_j zFKl!}HSd|l(D3rsqu`vVAw%-E4esCRV%I6?ythz(mky?92n{}d;mCs&aD&D|nhA^A z!?IEL!$kb#ctXu$fe1`$Axqd$ZS8|s(tBAfkseHG4LO)a*cJD~3qw|t?XR25k6|p} zMI~z!i;yR-!&fk7&AE)X-r}&QwsmlkU%`HDy9X+fs~5JvZ~7~msAC_ytkqTEnCNN{ z^$ffRjM}~@Kk;N)TIWDIj2n+wr5^R&Y4m8m`XcGQO#OZ1vLj0$`z9N~cHqCrrcq5- zQL;fSsYlY&px!F5@_nxYd>t5(cFWRx!DlvK^oDfUO#r}XEf&KrT}=-@*L|5EJ-&|B zSYi;Id7-w9SHrpt+Hw3NV=a7)C|)2kJc32qIuOkr)D0-fgtZZ8!T2jLCnh5X^%z9m z{~??vO_v#L`Z_;<9IhbmItapL-Lw7)G;w}o6or~mO;BQ(Ut@JAJf=L!FVPDt$LIcT;D};r??xt2wfpQcZR+(k3WId1$lr<4PM} z#$SSB=g$rna>Sj~vX@dMT%EZw6~z&GnUAmDF>*h{*m!FJtA_-K=vaQIusgvY6UgY5 z?Sp^-PB6@`$9vMbk1q89!?e>;MaU=4fio9GLgtOnXRK$y%!2TR97~8CnIM3?jc1`^ zn^pQ?FsEqM?XsD9^JyGkTrzl8YS(LU9whB~PIWsM0lf58kVHKiyjG(8_3sNX$es4@ zWy+x8Ltqq^G7qLvF-yO1G;=+|0GJ$af&*zSSk&B+nL;M%fjo#F=sXb*5?+EQm9zb@ zH(|TBG(4&M{^6lMisZ#Dk^E|#f=I5X8!)h&`U|l1NcdRaTE+*A(+Vj^B(s< z`JK~XW+#9Ulz--nB&b{~BynMJ?#`nCk~7*&b_{OssASKf^Y{9_GU4bnI*+wqrD7SL zJPm#6gm7a=Qn1%#LXcs_cRa90mAjKz$HH-utJ3lUgY8LgjC>DF;PIxI<*=>wY^+1( zI`}7M!T?sXZ0edX5;sUA4gv%+4h}B>TR^10H7T_88?sPIc5P<&&?DaN%kk7w?Kv|Y zxR~EhE8A0lybmgeMRflvLK^efO5&^0`}^Hsn3*E`_NS*sYP^7rskp6qyZyhgW}dgm zmOgnh6$;pEQuk@DvTU>C!DUL*9F=RgdIUtf_y-YXIEqKL8wF`0UOG=(l>}XTay%2R zljh=|C@P`cnFPVr@En*;$vZOa<(lMl-5!P?`RZ{@O5=}c+k!GGYuO*wZZ<>Npenj2 z6l?L-1D;d@7*m{vMn*U0*YVp=qmW_PA>)}4Y6i0Ma+k-B;0+A zkyoD=Nx@4pU|-#c@+#Bja$=JaV886MM9$Q-{*^mLW;u^M36(CKy@lsMf#`Q_U?}I_ z)#LS#K`Q*)ITGwYHbP^KsBBTz*W#_D_VtsBTIjFs=g2~Ry~7evA6Y3<+)OAbge#E8 zjbsUr8be6CcBK6Zff_CJtaKTA2K+2r%MMUu{___0mZRre-tF|C12y2sJOrqEEYe81 z%vtZBeGyd{1>DViytk!m?s6IW{X(0#ll1b|oCwsX7##$8nmDPv+(Ui)@K#a`*^PF~ zkRII*#Vti8pq-f*Q%(2Foj;~N(S9mQO^56IQ>=@JRo|ug`cYS3$JW)ec?h%+ zxlUdI=dG5|cz5IvJUEp9wU0!SbHn}oYGcb;-3*8`b9ys~+e>wC+n((7Ee5cJfxF<2bY z>m{svBM&Q5MjYBlOQKBlP^_{=iLYmWql~wYb-vq@gBOwv5DmHfv=}XRc_TSy6)Tb& zY-KC?=VpR&v2c*~>Fp4thzf>GwjH|8Z%CZte15V)&+APvSgRs8>iq zIo*vUgXnTScMI=HGJ}TX(-y5sg5QSew9vNZ>dq!y9v&yxghxX1IAa!xzzbN?5QtX` zS_Y|n2p!M_630LGb+qdr=oXw@A?R4*u+z+lf0boR=<4T-+^Smi;zcHdRzEfE>aK z*lkx8Vi$ZpHgGfUPzAWw^THlzZyzy^TIxmHV+oXA2WYnv&^9yn``cvT0D~kyS^+f# z{F_Fsqm2bOQk?Tb;DJt*r?+J;Lwq$?%~WCLdcC?>+XG;#aya#Vz48(1ic1z|U5Bp? zzr6-9u}j}aIQW)WiVxWvg(x(q|CW6=Pz87X| zfrp?Tse@f(yWnhNdUH#a@ZHZPQ9r$N6S`hP?aP-`KNNvCguC)?nfBJLE}i2Ddp6%; zF|Zd~lo$F(>#QCb`{@-OZk*_JZRXw8pX<20U`cl}y~HgeB^XjUhU}d+mr{JD8xZI1 z)!u~KrD}T7LGNK&f`G85se=&hgu=QPAa@LUoW`60v`wH2$?2igeViv$#&G;X^TP*% z4x--oT13Kc6K%`_z0)wr@W8?cFv+aEiIQ^XzL%z({ZF_8^tfIy2Q`466L`eh?+@P# z8yEq`me1^Q3k8yY!04G>oftJiy_r{D`TI1V-C5FA*&LcJTtmF)mml}@Jn8eS%%bb< zu>ZjYn!wG=`zl{p;7#bKoP0t9WR?Xy+`PY}6On46C+Cu0-k3GE*bTF5QBe6d z3OLk!Ti(IT)fY{#8nuUhyf}2g5(+ZAu8Yi zApGPncYc1`2EHQf)r;zjY`}paR}*kurM=P7_0&)AxVLCK zUwSeZ+7B*0^a?Dc-^a+CpjSHsbl7V#Mv+t%8{5y1#+CF7%m8H6vVYLoq&=eTnV=-2 za2r4{od4@hSTAZy3^ePbWe^u;Jge0)#__ghp_C1?ds(Lm3Zg5c#)~SO;F-PaG%`za zJN!d}{XmeBO!-Z7&!;_(pjS8JRyIkAWx}hf}muSa_TRwJPlZx>0rABF=-Lst8`VR>sWw$J4Y zC=c#w^rZSHu^c#?giS?AaHN*n~)vA*-J}d5$a!x7R*qP$q2a`4415 zHRqTjg51Y_4w{#I$x#SMbY9jAjB{h$=LKn6|NKD5mL0^T^a*t)=oYJM7ovh0yZ>z1 zku!{Ka)4(zJ@G%>TMG&Lj+DGW+$cI~B^>^3WQ{DI}b-#0N!4Ar=i-?<~NfTMOh_=Xi*i)>ypH z`e)P)JEsiZhm%FpJwpQwX|hN;p-s(Q@7}1fk8rGvIr@M#A;W=*?{2|GuR!T5PR{wE zg))tAwhX|6ku~6@+%F#O6M{z-mP<-&m#8RpW|CiHrkRU|a|1?pF6R zxVt#Lt=eVY2iw+HArw^AS=O3yWYZ_1bkpxrZTL8sSf8Tag;h189S)#(@V$>VS-VGd zY-mo1+h+?KY}AdREEXl4?SlG0MjyiqLANdws*PZyZI`epX|b}HHY(rW>Bn!*pMJ_d zHVN4q^kGzC;s_75SZv+pPU4S}C)G3v<@8E1!>*+g!>22LO!cH1F0uXsM53Z!Cc`Q& z9Q!~lM_9h3_a2%y`sa&83(y}~KM1oQ2Y>nOwNw|X`rHOiFdUzUSCrK6Kj0ZKImlTc zS1P;x^Dy7qj?v=zOW{h2>s}p{Z4ob-e{VPzWzhwTGS|KTYn-LTR#QuX!_*aQ(Xjva z+^Yci;3D(+bJja+`s$y6x?k20eHhCo`3NZcDKg3JQ<=kQH3{SugM~dErXIawrx`im z3ZU5?U>tP8ixG4_eg-y>p}F+0`~`&+NCou zt_sZwtfUC?zuf5pLON~hf`I!CyDN&{H1V)tQ&y=+ubYj?D(B1Ch{6hV;BgXAp}K4v z+FUjTF+}jL6wW)w5W3=61n=#VTkB;$jnA8vUX7PR(QX2c4vB02f9rMtdEf2$rzQ0K zGJ4gh3KKaNMq(a-C*Q&7EJ%x!bkRIldeK*dU$m$+<^$mu)|TzX23$1d-(-R)d@uiJL*vQSTS!|JOLj&8Tw*Us4N5`yKxk4VbSi z3{2Y!bNPKwV5#`d9@TJw3bxYoDSdJA;O0V>E)<`M2hzzVyAShyDMwK;MFnOH?-RH!9O08PdAgNXcl zPA#8T@TWYlkZ4hGwS^UX!Nq-3$hDIOc9Me&4um-gSqe3RDQO`{na;^O-NV{?tpo1O z6XvG)({pb*Pby>W-qJdjcvnE6&!nZVR@CyDV-H1FaDLGT!@3SF;$qw`ZsybNhKaa} zsZjNKGC#KBwdhE)OT&^Ycbr^JDW}o_-#E%T*=4H+s&Ozt>su(wO=?F3_k?QoKVqAn zc(IS4tu|~vy%{l;vIMiz?;9lC(6D3g6N|X5hji}K*{B4{O;ve=5{&%%+2Wd8mfsPk zH1~4L^E?B8I)6TmeaJJj77`ycf~*paL|;amK8MXJa2?^!FXL39+pL=E>jj8ftX;)sHmY4q9d-#d_4_wAzMM&z6Lfym zB1+G8+CH3`K|lEXn0zex<2udq3fZwAL|39k_4S{gjh3WLNHQS(wQfCVj*D-Gom}fl zyp@~af8zdqB{UubgPBLo?7`sG8;T~x6`H$M&>ln2q7O@pM(OnA-@p{)x&lNFP|4a; ztR`)88S@E7WT$FhHGxf{9K5Uy{@G}f&0}-g; zhe5O&%bSmr;#{;7E1a^yDz3=@zw{%j9tk!^im z48e;|pN&G#Rn>7 zqqFY1mL~8Tu%b+|o`WyWi-|NQ={s8e2GP8M1=7I`Tc6#?l~m%1+M3F9lyp&QO*Hcg zj~Y*uXloOY&N*@8Bj3RoffDhWiuqCbl28X^N`rhnLoSNkpCixoD}Hy#x6{|TEwI8z z92@gZ)-B8uoZeN83|x3$DFi|dKX^5WTA=BD^Zf2R7h-sdVNoP~?Hmx<_f9--bxI5!%IpPX$^Fjr88)h5hYcuo ztW^ack-gZ`G>HH4D}nb7mjaP#m8Up2cB>D%f`i-u-nSXcF2WOhGU@=xzI8t}{=$z| zXc0AHsBmiiofG-#RRQHLtz)}Z<;NF#Y6kEZ#>(8A2_qSb2eYRrv=ag_@wL`Zv2MT1 zA)we>d|2oY9l)&zWe%te8-1k|Hx{jW*kZWNC^^#m@UB${Uq_z@U29O%mGlrTw<8#% zOI7r${XuP5T8_z6dcy=)tlbeKcwy{xbXt@9sd#h_9>b7u-I-4&MlZe~Df%>y0ws%f zA#?ZdBD#=b9su~})D}be`YN-zV+g>k|DUTk*zuI3KNxvo@RSH%rV`b{%d6|x;Qac~ zkJ#vpP1WF}G_69iT7|+nXn3ed`Odh_aiGxJH7#sg*x%bWP9`Ag{tg9g%`@s_fpioQ zD#AkCUM_aFId;nM2BON#p)u~G!!_bhn^enE9>MC}Zc9m5bn9&ND@z1YTpeoyfz&0_ z!14mWbWR>M#cyp|?}BvVC@^|W_8Zfw=x5=(;=cycY)h*FPbkBNc|yScX}3S4T_&{f z{MKgkv`a{@Az1;yYA1=8NhUH|MH-g&qQZFqMS zyyA#AWvuG5bOzRXFU#vAN-2w+h#AekQaEmMtvCIEWBnE+pazB_7GByp&l}Seb!d*- zZ4aNL51}o&x(8%q-Nai*q|4&u8R|zGjl4o45y;74T2IMhXRQg@(_$b3EB`@ZjgpI2 zFfOxr0yWX84>`UnOaIx!vvNlfPunQzMORCdnfl^Y?db*i36CZ=G72Q0Vf&DT;s8&h(;$5`ITDwB1ig|2qvEO9EGH1_mv zn?a?K4n0RAHu4RYfyCOuF_Ee1YlTB!7mAi?>lkyDO$j9nA2}_WqjDFs)BkUkZ*>c0 z#vC7-wz?x;(W~Yko%Nm1ApCUlMUJ(b{CFqvq(+QP^>B;WB56}&UDd^r*GzH*ZEBFF z)xk#!2NX%I9DGm0#H_LdExRK!2~O*{A$Pb&h*Vbc4>Ztj*#`CUkkGCp-Z(^T%2c2o zToKBQED$FdL&bTNEo=PtHgCh9H2-^iZ&M*I_a?5tW*!`XF&F3HLNe|W;SOU8`IAW) zwQa9~H05`4Vtw>t9@ZJE-gDv3mb+RsTYom~0QX#Gc11E*5YUh}!n;FdSxwmfdNMC} z%b66L=SFqn58`i4ev-tiP^FQqgy@I_i$%to-b`|_zR6VT zd1~S7vciK(B-bTTu1t^dtaw|QwbVprLX@Ljq+Y~j7z|AB>$5ZyT_bazA3RETG*AvslYM6mq2w{Y z{*q;4Bh#_Y298RM4c|KY_AE9^JiiPatRBK7?D)YH5f0z?tWcJpacp&5EO!JmhVIyP zL2>Qjh$H6qepYsS-?;xoMw*H?5@OLG-1+1D^J!eYk#!<#clwK z=0oqvwI2un1N#rC$eg>HfTJ5VGJs=RYOOA>N2{MSIB-&kd7U}fv5NJ=jvBhW7H-En zz?^HZ#No}XVR!&~-ckw>5B`!pm+5k~on0G7uOosd&UD-nszKvs&#klgfF5kBDhfXy z{z|VkiDwEJ6~e#v)y+^9+KF}jMck&_D2cn~VNWc&i8Jfp<;({B&KH#*S~2A4-q(!e zuKV_%)uIEhQ?4t_U9xr}n`sML|u zn1?Nux@l_`(@Ty!q~3sdICOb6^iTn)sfmrt83T{=-q$2+Q0Km%A$F-F7GhH6t_y8; z($*qk;{<%M3fr^Rq zMrbwRAiOgMWV#vR8^AT1Hnk4<7fs*5Ya4VNpOS}@E5Kw$g7%W=fsxXroZIRoXC>V0 z7O!<704j}E;_9i+d*f<5fdpdq0gr?j#il$vQNI`)B_~aruMUv(NjI>U<9LQ&8)_Hm zfaOnc<)*7C-9|F~|D7^y3F36Aa;{D*3(Z5k72EhMbKKu$&yY;j$webU7j5S2T@|lKLCoIcCejLt zTAuz#h{8cO!?obXLTuL5rsEfX0F6Vetq2xiJB58{rGs92C`*1`PcDrt5M&bL3@Li< z@djA35GbQb8q!6wdz5`*Yi2_wSgP#M2RE#k>`L%>>aoC)ze3a;u2$ED1wVkL0Q#r` z6;1zS3!Z|gxqS(J+|LTbSX2P`R}Cjq8VjJA*E3zALmYsVd<<$}HD{w2*+e>UEw~E) zXPjV5GJUh8WDSL4_ZUNOJ(=ZCCL%kE%9|J#`2AWO>BQm#!mNz4Jn+F*ci=-R``5FZ z$+!VylGN-*QQs&6KH6KEF$&^wDj5@Q6SMfZMkZ#MDK$PSuQ6F7dG!88xm*E~o_ zp~yhh#PLTAycq6-Ivpy3$y{;%y&VyGpH)szPA#y>UMW>BU8a*cYi?i4wiAlM)O&}E zOn*(pOEfDsKzYOr7Euqi%95>Y>*CkuqdH7d?#Qki)7^_<4v_05^+yKq#YyP|D_tlV zf%524^K)>>ACKVe*>VyBPNfIKB)R&?osgv6Fq3M(v|o4S+fV$+(*03YL_rq*eend& zp!O0>=7cWc2tt?cy&`45yp462uLY0%VZ5^mJnxXC6sMg^^pxQ(2mkpfP%ChaKgTsh z(1Kr_FiG-Y#>>z*#vg(Kimv(5R#RyTdGPA%g>-_3U=FyV7ODFc4C=u(sO?80Mlbuf z;Uxvb+~C}6jW#Dg$3G|@iAgvSL*8O3^af4a9)F1(#e)uS9jS+(UJYL=*TuDG%$roiUI=jJc z+W)RXEp7iJ7H{TZs&7-33OT;IaSJEpOJ&Rp(4S`O4|MBhCoUPyy^YjpgF=>JLv^sWb8mxSvt6#%37*v6-YIJ4G^Y2;Q_+IMV$T z>(2b|rk7^}AXP_k5x-^cdJPTLge?PdgSOmpjo^G?wuCN@tNdOkQ12rZMik6jy?OxSqaWhOEszG+dUy z0Yel#_!K5>iK)$iXZmDJKO+f-bmZz9ZWjWp7*ThP1%MD9aqlSjpZMpnF220|iK$+F zMHbE6hlmczh~zee=tbS`YTC|&ajLm4VDoGHB&^$CE}eP<=8-?}9q;FV`4`uzUZnG* z%BO0Jbh)PR^j~vhcW3(8Sp4+wSd#K{n0nr0KwwpOUzJubc%s?rVIp1aZ4wSRdEkKL z_o6?^4YD8ec=$(&h9qGf;v$$HzV$iC zkZJC;J2D&@6~GhgKTS;z9b?~#fkri6QW24E5M_1zsSe%m%!lBW(umhm7m=Bfu$-aL zl~I#ek_%^LBW!uqp|z-+>%e_wNJ_Z6p7%!q8C#8dS7@3Pv=3pNnR}CRkCz`AG%=R& z!!O)%EN-B^iZD?`L^;fnk|-x^`jMEtKiJ1U>b)@IbP8wI@4msn~ap3WKiW+pN$7y7on z7wpQe?9UJ!$Q~Q(iP@+7vu1*4aJT%cUr8ieE z{;r{~-ebo)xxQ?>N@za7(|8kwp#r?a`HAaiX;h$#EsoO9s=FC$igIX2W$ObiAG{6- zd>i*!GG8Gu0h6J6#vyZkJtv^BUnua>4Ar@iRJd2*ihYFd2n+pQ+bADc+i`o;3(6P$ z;()zEmew>Pm^y)VO9pW8pYxAs)wVzw3{TuegvvhRx^z(^KVpv4V#xygTxKdXUS_=q zWCK2gq&*z-c8R7pYB7rHTOe-?NyvD%4hOs|(z*E!ps-U9=S^eZ2`6rl0bGfw9bt%O z-?4t^nh1+A{D%Sj98a+^tV?1xwIh&NQ3A6xdPk21j8u(-pjM@4ps$8tO;(sFOnT zww~ac3`c%W^*$Ehti*(ZJ9;J3@k%Y*R_B*N`Hsk{*_*R+m)uN9M76*oaC-dq_R1nQ|qt0a!IXTvmax+eJH z6o=;0B0d|1)QF~u&#v{;4_!lc(%6g&$??=dqoqz!z3Ep*Qg>J1(LRYf`LX$@fX?%k zH^+}a+^NXUB1{xQBJkYq)Q@P>v}1)32gcwYU}n=-0UQBO9sokhPYIl(YnVMG|_S$0B^Y;c! zSq6TkjVWO`3~0Lf30asS4ec!ED?h|p7`2HnNq^31M0Skldi=o zxXZ&lj)N{L#t)Aq_g^bct=)+}lw_yLyrwh6GVa?UcgIC;veC2dSLogGupj8AY)B)C zcgRZ{h&E?~_xsh{jK^BKyFHj)=f{7oE(XYfbppeyY!5?V;@cS-D(uVYj{a5m<3v#bF=PMw1LzdF#oxF>DtrKsI&W;5QwpZafMAp3 za8|jXK1)f(!+Q~qeS;cH>wotwx`G~Vo3j$Iuu zjF`iD_FJd}v44oW@SBx99wp^$!8cf@X_((>m}!OCOoeooC`*ws_niva4V+FTn8^vv zoQxpi`WtQTFh@&(V~<$46<=)c%Lh@%V*72MBPZACLq{A-UnbcWL^@c`=o4v zt~sk~``c(vnxCI}(not*oax3eGW{zXD`K??h5d`x`E@T;il-8dwLp+Zu?Br$_sqS= zC@|!@D`vphGH{K6BVB*ljhc)BJ02R-DbxfvA_vd@4vG94q*ZJY&M7HlGm#%4i`-F` z>gj53mYMFqIo0bWJa{W#L9AGg9UEIgaJ*$Zz=fl4=PhnI`Q9#(L6AR3Oa0nVa-z0+ z#L4{9>;ua`0z@I$2_=mYG_0$z_W6MSj^5=ho~PZ)l-p8n)a_HbF7BS#g#U8d?;}?5 zWU7f29)Ohz1ldQMnr!OG20-c-{`5~6y5x>7!_N0^(-&$3KBkm@=V*7|fT5!arXxHI+)~dwI0f`b zJ)L6I>{OJe=sU-z9p9ewa_S9+%6T9fv#}W>*x2Te^{|rLE6S9c~QZ+sz02HbukCkrXLJh)`Wc+O)gtAm({u3LZRSMZC&U-LcL^V8%{L9&!QQvj}U=GHoPLYumm^F!9bjH30>+rkVu>jeQ2 z{cas(X|;tXah=J?N0GcDM%7+4%MLG4P zT!%IksvyRn7;=!b`z2>1073moqogU37EhXtpPxWNX zJN#_LBs|=lDzKQWDFp>q@4sSU`Q}RsyGU(&h$D_q@F6>m1v;QnJ z)g{BV6XildV9~PShe^SlFTI?GKV+<}2^o=jh4s$Af0xmZsAhge=fJcS(GJEjN^~FB5mef1gQ;@oi ziWToyu);_ww~0 zQ>lbU$ezHh&WhcgS$SZv`Y|eko&gSXU5tEOmi$$RVRg%gS!FY*3-rDQG&uF`V!u0f z6hW|;b`iYqJM8!FHWR3S@d2QbbLq7z{)ZEaT9tfmBj%VTix21zXD8~F)W_Ax?7r&m zT&;qCQycs;!8HbC6(V#h{Y3wMuEOrQ3B%;*$aO|@EgNHM2%>67Fo~?^ z;xY%E@pCe|4k{2P!Yti=^2m52=KXKIAyuLcoPFbPKq#O2*b=bCOp*DZ^erwP_j@1R z(cLpG;oWmohYm~uB(Ab>7jM2&#f~z>UGyI5prPiT4P&TB2;hz4Wb#EV6^FA-k+{$3 z+paBwWXsCADYbsX94U>ix^+iWjn(u z{TpZ7m`-6uqEtB3x4G#Sgpnbnu1c2ML7OKyhZ{o!kT^d|2_f{t-TmUxyxyFu^PRJ9E$)Gv(KwFdkvI0r#K*4h%uGuxvEKVSP1-zt=qjWI%0I4xZA)BI`7<>c- z1Of=$1wK^WW3vk;I{p_cgrJk+Bsj<&TUze>%XE+hOX4@PD|;o>7a|P_>#C#S zonwhInY>CvAdD|wpiB81?+67kYh3aiV`zTISA6F<05?OZ$XmtlQcm1U`D24e`$m%g zU+kFZazMMP)9h*x{o67Yk#jYj6zqKu%t~F)+2u|-4!pu1-iCuUbkUn~-9G$?!QsPO zY1Mh`H$#@6KKF)yJ==`}TgDQ|u^dsjU#D=PLSd7ZPhU(3r8jJ8K(h7~ok}I2sm8=F8UQ zs9193{IomPZHhV-vBVM49#JA&OhkmE(sW7F?^WKoL(&LjlcgXx@12WDEK}aD-kEa? zou!E18>7=z?!PK*(f@=27he(AnWRYKtRhlXAlXnr^10}#O#{Lr_9&XSb-!*~B`Dwv z%CGh6(Mxt};8d19$!Yme2=K^Xy#f7&CB$EF9ClTw)=yVbBwTXrsiJNWKb~_#348l5 z$v;j~;5>tOlKJf$YATTD0646q6$n*OOx3cProQxmsD2x+m+7UgqOTgNI^a|Dy zb>JhK3!lf|S?Rq6Yk|!F0wV$&ONyaolEBUUO837tH*k6fBI4t$ zyO%O>2HK$lg7}6;o;1tI8A8L;la0DnXt1}!JP=Ir<`rWCO_-mGlG`YgS(>Zqhu`T7 zF<#xLFtVmZBGlF0M<#k1G@#3;W|>F8+vca1b8an=OSK(i%ZPsKtwMY#h)1Dw>9SF2 zU9$I%@-g~#; z2ydM?e6RbtNh-(;r9CXyoSye6Qy>TwoCpY2Ii|Ojt;+4qyb>?eA{@eErZ;@Xu47C@ zjELt(iKjzJrJC#biQG}?#FaSIu>RWnm~)t-rkPukowNP^>m>cnm?z9^^{+-Gjq;HL(rtfg z!UC!UGnZQ}e8}}v8nWXjg8t%#bALe}H0$lA+y|PXyaI_17xoSp5OUOfiLseaKyD9T z7b013`_+f^o#+_ho&5RC6d%%9p3vDNl!MoJSe`Ey_g{2stKFeq=ruTpZs^EpAYKV< zwTl{#Fl<1x25NX7#UF-if#Z1ncGTUjZJTo_2;sW1rbuEhYa%b`^}3w<`jSl|F97t> za!DVY4Z8ECM)7UhGQvc2^bY0G=^bpILUp>m&IUP^>P#V9)d_Wft#PZ+7ve`uC; zq(@P**i~oEY;qgd<@v9W=?VeXMXu={T3jbNI8ebU#u8T^f@p>lmwHuBg!Av-&btXq zg9)QjS=%#lzj1D!`z!odo$j!?8EVg3EK?9Q_zu8vSXh0jYJBVlQ=t3I2nnkN81bK@ z-xFD- zO;f=?xQj?Tow~gw1>Cy#CP66^;H4{5f%S7bvi&~&YFtG_y6G^n!@E~%EX&y!C<{i7 zsjf4`b!H1XbE-#>4ADXuYO~~DeIuPgO%|(dR5$X9%H6k|-BKI>zNgma?a|)ZkC@0V z%E{_IqvsJb=Fsc)yq&qv*dFq!G5zj|M4)?TkSi65F2Eka#Hr)0LNuYzRp{M_k1)0P z#}nFiq+)u3d63mceDgrkVKUJzG8!w^HsqC^FvpK`HB}v?n&#!+y8c+d`}Uz>L99P_ zQkY>gZmqMslZrW&0|%5(&3OXce+6t)#cN^#0yijkq>%dE(M1a!QBrR)bn{HjXnm}b z4uW|K1GYjyMq-2;6%h5f0F_fis9H88B&LxUc%w%no20w2tAy` zYqo@hM&A?7-EW>DHqUUre*s1jMquA@vS=icW_vXLu&7TlQU3|&Di%C!=S*-*&R^*? znYO#udw4bnoRT04M&rB$=YKv(CJ@$isp?AtAkcWV`Osz@UxVP!Za^yIk7y^E1CElU*Xoy`?CW@!@o4GkNJ$P^Vs*fZ=9){9Zk9NlEIYr2K@ z^VWJ-O_^-J(FRuU$S@!itCL0U3sKOwVNr?MeSQ9r%(&T9?g$ZM{ecoo|2ex^`Lzy;$bgVhIZZ=xk;ieG7e@w2~ZOeqFb&SH@pev^uZHTD?cnnSaSSTi0GP6e@hInae5~MBd9DxY@ORkRB z(n}R}G9^DZx-R)LL!zom!pq_6H`XqL*Q-hnD2r8c2~g~7#D({zN+s=g_<0u{lze$e zWx~6Hkh@ztQzNOdnnMAMFp^z_0(uV~H6l7NX$R*7Ps!u?%^&4o*^>5Quc!)yHd7~su09Pj42L~l zH3N2mY<>>q1S}{_A44#|>M>U0)%5)l+^{X9U=4mF3jhLriOgxMLvJmcUX|zG4d}?( zYDvm`+cY4EPZ+;VPz}k!fDQ4Wr@(}7_fL!Y+kEmo$`NWyY7Jel&hI zgH`+ZcnA0X@4Ii-jJ{SFP`fRH z3{azhkLJ=T)?Nr>hyCFobZ@!tf>)?R>U`k3ZpDx&fI901-4n`U^a^QBeWsdx3jbE{ zfF&_qAL#Er-??bqF@&CdMH8-ae${`nIki!`8->kZil{?Rz*6OoDKG~Y@wY1(|G;9= z@HsJM<3>58&hzzfF0RCx3(0)hcXSKX9n8)PB=anD|$gt5A3oR4?=Jx97?&{>ofq_<+{qQtW&URg__=%istjL zv{Zm;)_PE;eUz+r&Fuo`UwBh_WjVQjU!+8lFZxC+BUG4?|9jQ#b~Z_m;)7oYCY`YUuhi z!_%ApcLmGlfNw!)Hk}eTyrv*We54^T1a_(A?7N})ABUT|96Nt}wfP6y(tO^1U9R04 z#zVzue=TVX4JC9kzmKve;miX(F$YB!uG#;TAg+5LZEoLtEc z->B2wZQ3M~SQdFC4b4fAlT*7)2ux9F%nWjI=cc#W%Lc{8-iD_A>4t?GKZ>JPf)7#n z;mkR|j!O ziIQ%Oxb<;aCzxZH0|Y?#7o^s2DAWnKfL(F^ukIm}c)rW~Ig-8Buux;mf)#o>zoo!f z93OVw&@>K8Tc)cQ`EMkKOp_(@kw+_7-0+U28n9}C#E1ud1cD4K&;p#eAehU3D{@i? zm#{JjJD^7}$C;>aX#0m}V2~I}qcyY3mtT)Hq#t=`Br7gp@ZS`f#-$fB!s`G5dKlP9P?5UIALU1kn zNy|C;QK519z|+*6swrpS=B&dDew9n3QB!6V?VH^Uetvxm4?X*wii5*Ji8b;VTTvii zv6L!PF81LP1Sq7r6Y2Z!zg)%-r za1jO^-X{sSr$8(?F5?&pm3BlvRr2I8RP?;!Ud{HzUnBIwUw)bxY>%{Cl=HO&SqzJW za}xRbhll-lg*3a!4Z5r;X@^yq#fn@Of}?JrWUITDyjDLO(@%j0BmcwLe{%<)=~{f& zE=F$*MsP0QmZ<{|c-S-#V&Bf=sO|IFtVHt$(ziqiNq=Sw=;?#<@vWH&On4pjkj8}L zp4bfXPg}L1CnGBl;8KD^4KWnK)^4(}R)Lt8UX%c~iH-M&PB&tvJDy0* z#~d^KIU7Kk(?hkmANec4n|&AnF+k40x6j6m2k{3T6E=Qu{>X@2vJMGc@Tn!D^87?^ zIB*wDIbEyl?I4p^*o9*V|22?EJ2I38r12G&R$0mARb2adUiD6}#Y!RV+R}4c3sa&g z;|y}nJ8-WJ5NWfnjmkzS-oY;E?;t4sjO^S67gDfjvm?4D?sHoNf*VE35yPMCnW-4M5c&4yeTL83ih*fxHXJp>|NF9XJ(mp_?;5PhGfyk zktNoIi@*o9TYf=Zz46R{R8I2=n{Hya0_#_mu9`314z2Owx&x*3FE)KQn!sM1)U56U~zd&_*lDd=0?Uw=p z$b;|}H^qrdpP8PEK~u*+U_09|1Ny~?of7(m+kC5xA~2@l;5lXFgW5&v2%Cf)Tjmru zYSZ562o?oM`UzJ2F8nih$(Lm7YW>h`C-C=v?v!C9bW5S(G=awb%$#4q_(|KliVbWz z9;$Nnrmo&P<6(j~DBY01!92i@-taSrT6J;*hS=!a=vaZ|l0fIVgqoBg!(d8Rf0Y&T9r z(E{|S3UHiQX!CmNM%I@d2T}X?LuFrW4N?yCn;IH0ZA2Ozt^zzOAB;_w+^cS%OM-H@ z`F)sVRdP8_L5d&63jPjc4HJz<0%(~BZ@q8FuxSZ3s8UBUh6q4NEYRVym+(rD|LbS^ z&{0_qpyPYkjk-P3+vwJ0R&=wG*dxln%#W}lsm}c#mrt#l^Xd6^vCrs_u-T!+SHm@R zsXT(%TbujV)I4Q9V%EeCy1d$+oDHnDq?Vwnf9MT^J06rV{{Gu+3dXT?_LC1cUe=}1 zy;#qn7PQ53&VuvKC7Hr2QfY@ZSegWWbI;Am7fVXO32X;5Z8awK8}uCke} zjhh-Rx5w3w%4UW>GbH@|kt0J}SR3Oh(e5flTKp_vh1>Tdl_O-c$Fai0C9u|2B=B4i zR}=JUTq0AvGK@PT2&P4y9wZEuHDx}_Qk=5DATX)YFi>vefD(Z>^%IqU-2pFIbdp_t zJ?@Q;_fU)1dX6oUcR-XIt3W+Ocqi(L0rYiBwu?!9^{aKc+$gOm_E6#9)2#hNaZCp< zF|#VhQU$H{D}6MAvZ`ZrmW}=V3aItNBQX_&%x_a_Kpi)M!B~DLMM8K>LJ5dfDV0@N z5Q-C^=h)pL?yQRYynTbdrpfg98^o4tf08kaqwH{r$iJps_#YkkMu%u5K^C+u9rrXX0P7KO$*7^n*>i&&-Wx*kS%FAOE1$Y4Yxn zd#Hra`wJ=fjtz^IN|1RyI91D?jz9J*2JUX&0$A;;OX`Mm^ zwxQ>lnB?|gY2jj-GBEIWz)Ry?mSQm@4Xn9ak!8FYKmGOL#GE?1ln$=i`ne!0+XkAI zxQM;#?EX;4=N5W_ycy)`Q-*>;g;QREaY{kqL(50G_SG*ky;W!CB5m`EHbi-_J?MSt zBvE@3e9!y?CUu%ZkyC%?2=t4GIrkQ~1eqW-eRj%6i0dexc#|sXG@VKmYNgH)TqV=V zGoT^45)+AJVn%a?AYv&o)MxtgO05R-O)6mw{rcG;`9Ft=$D%!$6RR4a>vwaT*cZX2d0Y(zF~hb zIH)!cikKb67HqlLX~#0rsKb-303{t1S}EfJ8u(Bh2C5k1eF!u`sXAYjoyh@$F z#>~fEDc7BEJ#jTk&$yKfFbF-4O-n2L(Ju>r7O@(r?lAoKE(oNg`jH1I@{%|jTcx}RmXNo6y9=* z%A5(}OsJHr>qR7%X2b9Ja&w~~w}U|U_W1##p&z%@X%=iB*S%UU`LF^bz&G~%{w4zT zcdbxAcNwF0za-afkHFIN`J3lknKkh@RWC96KBve(0Qe)^|3-}z9iG|x2idO+He>60 zbvQ0UP)mYLHT9#a2eaQdyc8&5WJmd&GW$j2s};|7@%l|DaM#TU%C5{mesL}KZ3WJf zTdDjf(mGG?RXjByfb$U#2+}qZ;}Aq=sd*Wo=!GG|7?&wL5KTs??!MrBe{{NU51C8& z1yW+qaRSv{N!e|j&JAG0Aw783JuQ7=Q*9Ru#>9Xz{v+y-;h1_UEOTL8{0TBW+&7QQ z$4!Hq%;{78(GQ7AHJ*WcZvMjml$3i%6PVDalS>)8IfJR5t?8PupiPwPLbB@-ldJ{4 zc)d;RIb2*6bBVxyjg>^U!%Q@5`}8%KaY*wfZqRjKR{EVriS>c+Ys_|q zaonf>^3c77Q<>;{Q^E>9mg*dngXm=!<>q7mj|(+kpr&c)igVh9u^D=Hl{IY<>`1+( zwo9qJnU|UU>r%3IFIEYeQLt!C0^LlDfeQ}U_&qtnoqT(>+7u%R#Ehc%$I#$y!Km zuX*Qh`|CRrCsYjSj%`j8PrAPn+Kp;&@sxoz;KZ!iIdtFE0AZgAA5|vBMu0Z}lBx`o z9dWuSl^b-TKIonfEECy1i+5>MC3?GVXfvg83OxEh0xS8gzLgaKhHgKapa42ftw{gz z^R>E9<1GUSu*UWD^Pu6z$HlLJ13w>$Qox~U3O*_G+@}v)t3@w{g%G~>d{e)3E<{4K z;?fi81$>mLouH-jdh?205|!|?!MMBFZwBGUzpNOa2`w2?NiFQUH#yRzo1aFkFrufE zoy&bs03Cv7>GGvAp$yx;GcnlxfRSyf(zK?~3b`g@v)Fkc-3C&g(lkf%w6vi^-JhpI zu;{wC4sPra%4XriFU1RcG}XaV1A`O?L{?IZij9gB?5QNpu z1EgmD#1O!ECL`3wfWJf;S+&hJz$6JGG2Cz}R4h8R!a~o1u)QMCpmADumnClt>V;eT z94_B-zyqbF4T#r7MMJ>EVgs8g^07NTaxY#9!-yV!%;QeT?WSWZEDx)>?@|4v8W)B= zjT?XfZWEATi#WR&gvvc}o8Z!N9G=CTHMjae^$&Jgk|;-U!}lwk^R5Pvy(9LnI$uuB z5txx?L?N|DpOXu0i0Zz>?uTcE*eVo-QiR=q@4A-kUQDXLJ?eu_4xi6Lo~v)4a8>uI z(H1@g)HJV=oW3%71$TvTtki(!qQTfx_K*Br@6p4+ynHU#NtsM}`O8^v9{i2*gIM-% zZQ*wNA5WvWv>a0HFdP0F<wvBK!>&xn6)%H?a64jI_fgfaJr zlqYiZ`v~>xNIy?o@VNTTbZSJChh=6HP|Q0h?+x~;^ehhV!$VDN_iz%^W&!{JLg1&H zQ!OHG6^ad`{1Pc{Qx$r_(4VC?QW%St34*AStac$a>W}kN%NID>^pFT_07r^Io_nPA zs6s85y^VA>!A(E01XI;X@|%aATngwf6wAR)LogU~%e{FP%lnr^TE|z`YF}Kq*CiTE2rlMMv~iuB1e>u|5lw8!b}p$wjAEx1#=rTakDg(D>4_GmJ?%JS_!l(j z*z79u5@`Z#tzQafz&@peXaPDFV;0|7W(tgCy7x<3B+kyuO-C}-d|CusBAuw%{XhN{ zgCJFsAW>xBjLj!7D{%AZ&}~hsO%~~GDF_q}pUp0ON`jkGmO6CcWjZWhG-+)&(dt8V zDib>F?MRe}rRt&bYtWraItj?qw>YQ%-UPaY2q#S7+r4ZblZ6_^e?V~V1~jv?FxEX& z9b_xXU12AWMY>94u3zQQ!0^}+_4;1r%y$5mS|+Q&iB^oWUVUuE4=9smOUu8Aj^{#& zTQK(^{3IWk94gC|76TKxAV_#+u;qu&I1mWBfl!zQ#po*lgsiie?^D|%Bw3PP%gbEm z5dW;V$4yhwi@~mGH&UzokM(e9>dV5I;#tv{B>G&K3i;;}#NCjgg~;h3KHT3|*f)D7 zBlKPq!dE>ff<*@Ud36}$M3yS|ItURZuBtlDJEEyBH=j^t3vdo6$L0T-sK*}Gc9Lwig$~V+LgSj!Wp4sx(5hQ|a zqbd(WaDuJyIfREk92_@V2PEQD%o9!U4yWXY-(O1)osCwCK3Q*}vz`!{?%5#gXC-M; z@_I_!mH4}%-mdiMzE%wcTPOv?PBwys3mXr(h(kWYB^n`kF~6sz2$d02Mqt>VQ9qJ5j|~P|c59YSdrVe^vb}Bq+pOIOt2rQuWnztW4L| z%;vs_s3mXyS##uO9&O*$(-RrgjvW3CtSGd+ZnpG(>1-=Y6{|~b(uIAji@~dHrpkOL zsc%bcC2g|IVU}+s)L7Ow0SCrTAkMz_dRNR%vk|)k(j-N!kK<;bmmCOYu_rqO&5Q$# zYv3<0=7>p<9UG#BoHS(gX;Wn}J&m>xwx|qymtbjiC#wur#&jz|aTqu%Q}9~f{T+~Q zqRi}nvKiFAHVEBpY)Y?G+0+MyA!HlOM=O+!}1sP&Lv z6Ox4^Egk8~*CtIAViz?L6X?tvqK|tQmw_@O%yD?=}RU`HPUI1IOQsX9lx= zl-*}qN}pwwA2VcX`5e+n-+W4;Z9#&~Chcs!HF&bye7wqX{%~bZWL~69qj=&q0JrwO zIN8jJk`{X7aZO$n)SW_e$-14{1-z16Q1XUUYbTm%Q=%;?4?W-JUxfj0cX%Q!1XXkw_>Tgw-P`JGuF2WU8}D z`B&bmWFL0>joxkY2xoEsbZf02e-sHn1PG5J^T8kms5RAU;{24)DET-7iM5f@*JbdH zf?gcBg9n)A@~zGq{)Fjn+rPM7PP-{KuKC<)_B%IprtF`TM?xuSpivIg;u&6S7QHjMJ<(orZvhqI?v)5XfNW3EN8f2U>W!+&TFJu_hu+bq z$h;x@(4u=RN~L15#2zDS$5-)}N=_FLVj&AM9}bwqE8eKS!dyeJ^*vj>h{@Dz45Qs{l~F5% zhxl9{JwRqUDRns}ChEvfgQS(4b3Yd-L5Z|@ZKM_+HZqK*!9|u7!i*k^n$z@n;*Eu2 z*%Q`F&t^OxjZ-ulV#Vy0g#0OefvpBh1ng$VdG<<0(ZCz~e9cE`3J3m-6qnVoV)nnI z(y18K{%UYL@}lNc!$!8+>G#QYBVymj8W2gLRD!DdpON3RQAC4VDlYuQ^P7SZtOtGG zc4eHhY~9(5x2jNp|;2sBo9+&1d`$V-_?@G!+<;;l})u;t1PxQ!PEp)a4C@jP*sp6ZfS(JrIs@*oA`Uqr6XsMGS zdN&F7?XZi4@NydYvTs7uYIc?kLFw7rI%t*oz<)n%XiD~KT z)m%1p4p%a~C`|ZHPOo2g8nHO2HqGC$&W6h#x4>7$?0vfcg3}u+t4x|7R~JX{>kEsY+Ju+zs!}Vxn)8Lc`7`0t2(KD!Hz2 zhUrTyou8L^K4d5awE3+*cQwMoKu3!bc6Og;=zJBJt-ezeT-F9k`-I-CQ769^S%lJ^ z5Vog$fSW~%QUd_06FKUs0JIPX5MZ-$a{YT{UD#ThH35z_v%wdULhids$q;ZquwV>( zl;n|Berz_^EOKdfKWV}Jg+8=vYKIX)%DJ-IqJ;}fX7~EXKM`ymhsLgV{!JENsG+W# zPG>GJPwzLZGwHcg=dgq!169HEseClchtz9Xzq-)XHUiDTC>t?uVU}nAeaGz8k*Wl`!qopzHCU9%O4iNST5G%&+dK>z)23mM=QPe)~E5Fg-DFRHBdgXJuyyb&I&IUA-H4Fw|^m{3!T+S zZj}RZSYA0@=3Y~3l+2(#3$6A11*$vV0bD@U9YmE~J&XVLVu~t1%8pF=;bxyz9RViQ zWVo7xv%6cGgK4KEAkQ(p@vL`P z<^dxzJ&W%M)_RgVx{Z@4?R6RH9mCJG!6cEbAM(2*183*8zbdM~@ zvc~OgnH8D|M%UMCV*gZ#l3HRF^DpN86|Hj7Yyn?S=?uy6BC3tYpspRA|GvYj+HTg` z3|?f~U1K$)L$irtWe~|nfGXk+6>#{IJC`OL=1hoc=Lcj5fa{Op{Anv|k8dI=9r0Q# zV|8SCdcGA$%ym?Y_QSeb-O2K)L|^efBPV;KPiL)|q4TdmRU-yEYe%R7A*Kbpdt=gDZ)RTX; zd&hKHC>JpK*bB78QJ)%jerN`s!De*NwF6DPj{oYC-18lh4+q;H) z%sw!#!JTm6hSg*5VpMl8h-IfT{-kZ%df21j9bV$I4qALdC~D6BjafDJz7S{p8miJs z5HqS#)gO6m`xjKynLF%QVeGepdhfGFGVB3E7CDYh$LnLmRAV59Q&F<-U*lGTV81Jd zr3;a@>P8w#+2sw}_6{!ZP3HmYCOkxcNwxHA{Hqi)Iu|{T5NfY7Wq;3ogT`9i><9Ib zqIGMkyg%CRcu3msg{EV-M=qy%n}Qu#gBo`y5&#!==c(A>borozHSh&UAzRDfjEes- z+0w`#Z7tGc?r1iaQ)+YP;f&^XlvRiE|0tCqVU;jxA>1`=_dK9tuo?pHW#fml1X!1S zzkF|u$J&50#(T^-y&cIWNUkLhVRC!=G1o}wa~GO*XA`)_4+ni@y;{jSo!@HDQ~wfWz4^^L3i3(V^U|!gj@1HBILt)b-e^N*2Gn zIgO{f>Lu{YOQU}hEY=&6tFB@bdwj<~^wlo?)_0|qnfG|gvVPTB`WWXB&s8~@aIF(# zN??ke(i)f9o2zyA*vF^t zq^uY-9E^Ny*OVmTuwpT3191~qw7`R-KuWIp?8wNUGSD!!OK|EL-*WktBQzc}$j(6l+ zJFV*y`1ImofB<2*Um-m1rsr7x9=#Mx{Ftm!>#C-`J!%HfHyYW%`Z;cj{{iKy93o&xGWuYGa*c7^__SmtlLl`(9AiJF51R+&TvAl z-e)tQkje%XVz^(bjJ$|UvT+E&y%}%hS#=O`nA_M-mcR}Rs_UA~fez}1EKpLEuEHRr zem9A_S~<8PyCz=j{`hDCETslS=K${YVa%*ku9 zoy}BeG)t^0L{f!fUqD4`mGYe2*u>mtAtm+ZLb=3`b$HD1)kBN`iT}P|;_1HzIKQ(% zvj>ru&vy(7CZkzYi_TPR{X07V@1(pKU$$*8&U%DUFwpRDMx;;p zd>2L7^~5g2&(k4j+WrcFK4Cv=$cS@S0D;qL4;c5RTVObigv05~=K|d1x)XvI@qwwLXxGpsr$kpo=4tzvku`OEC zGxgOO`un3z^(T}jQTQ~Wy*5=l8300_%`LVkA9A6Ut1ctand)trejJ)ke;hK~l@$J! zN)pj!6NyAYi_p*yGivWoPJ6*9pmsf@HgB&Wilwt3-#vn`b@Wrld+}?%;a+;Yly0N@ z64*7UP_x|*OV#J8H=E%Lw|wczYrBjSx~bBhAF@LTW*bwhsFU)T7RAGD@;E~w+!&L4 z5WqE1sZHgaSAMC~Bdf|g#AsDwxmo2bJN{_JBt(%7ka{W~fEhaFSGM626q3zYWL5WN zQ@dz4)`X|lw%c_-GiUEeOc?J61FydUtD=P$|1rlr$T3{1* zKPn63MD`y;&=Xq~23aAY{t8_aWJXWOvbvZ!1)(CVU3MpW)2z4-bV$fCcBYB2Z z8v8LB22HZ=|7|>=wY4ScEDE{DWMaTV#bkbl>xO~%#LV`N(<~g#@_!;i&+$Z9nUS7U z864-E9m`*fVW7kVGE6Z@%=_k7K${d^yU)94xn9Q|V*eAJ)gKb;#)CZT4 zHena*Ehof2+P7NsepXNRJ#)KH{?;^Mukz+1T3IsW6}kjy5?yQ~l!YIBK`p*Oni zfgJY&eu!xkj+e(8@axa-pKtM;_&|Z2IFW?%sG(0|!e^Se4E!gkq<;=>NOSp$ul6bR z4LGYP*IMP(-+2Z1j<`yWtUzU-i8`sGK-c~6ac7zGDme?b*5iJBzL`IbnSbyLwY-#kbbveFn(MUIY2f?@dU53V|P z5UOV3CR%OQT*^P^{d>3BKJZOX8K;4|m)AO1tSEL;)zE-TMY1hRoK>jWKtW*M4}}$J zl+lO5d?X{43C2g?e%n9mhj$K`+Ioa&2E?2UP~Zy;`~1MEXWovtsYy za;JS~=wbO%W2e~ujAlvEN;%{;4vFcFVn&4=)kzVe@2f?9``fnt5_8MO6qgR~#X2aV z`5*@T_!q*2&1QuZ83&NovstbVMuRSqr~wdmID2)1&ELX6&p~YRLhfJa&Ma5?PWz08 zxrcjBYOWP%#tKLiYSrvm65@2prDzA2r+-W-crU!ZLB&{H+Zm*WKh z`Mk!pz`WDP%Dsk+N`?YTbjZ4|-sb*2#zeA-IJ^}eZ{)v4ls+7QHQ=iePI$1VWTh4m z9>z9odr}4RLv=JTrYHl^0a;1*We_4_enCGvvMB_=1X;udH<+$*?e%v>@fCa8?t;zI zwim^|YX(2wA<3g3VHIE92_%>j$2oDgli6^hl4cn7HyaK3262^#43yjr{qkENdY*uB zxp++zSk%3~u`VkAnmvXT5$<5P%l0l2W%#zYuERdBmybtF9aK1e!RwSl2o7?h2o#Qm zjLL*G2xsBJVr0b?y4X(f=crCL=meVDk~RPIunbNt*9+`pcwzUxfFgz|yO!1QvkbLx-t96dB=qWEZ9R z{U|R$_kkJ=fPSHFm~W1-Cnk|mBK;ds80~ghBbQ#YafQ}9_>oRx>{RS=(0^ufwP9ae zp_It|`X(dKuGrD`jH}p-hcLYkGEG!?{#d*7e6DcBvv^lRmCN7swg*gmQVk3FGHph) z`Z4VC=gOtt_ae@2#3t=KVbLDkU%{O+ThB)CAiCBg@9yyyGOEo@=@!!LHkQLBCfKC! z>j(~&W-3K(4%eChVxkO6P!)&%-JYX1JdVM^c#r8r>0|4k$E@(9P*;{Z+df)ZEK?Ew zcdV>M$$S1+xRfSX92lZ0nYR}gEhD5OBE#=B3`l- z!}S-^)mvm+j6$U_U1c5+5ZX%xNyv~m!LwtBi**E9K(kP0`+1X6do<`yqMgr!V^Wtt zbq+nCv-9{3X91n02dzE@LUQyiai?r&iQ{fQA-LVj=0GSOMEo##D>u%jKPbEdko=B(Vo4PSQnF!HzRVxwFH6U6op43A{El5SF6K#8xUe?5&xUJoRidppoo+Ko8( zV3eV*EK^xBS{w^7e4evsgiV1ttybj1lUw_F=k;GJh8sVPmY6Vjc;Ln{Weh$#s+;7NSMjirs{9WSU$=m%KjSVBeRb)0! z3lF-~uiDnIxO2SjIR6_j(E1Dv$EjH@aFUk2$qIRUOp|>OeBT3 z1#W=6X1VZhrJ5#vV2z9-y2trQ%13tUahl0SpIOt*ut-gje&1}(nF-Jut6I4}+}Hf# z3r6p;+lyur7 znv^vjd$dBK|4i(mn>$vI5R^|MPDUb>o5GTRB9sM+Qr3r_-sJDn#doFH*;i)o^?*Q* zVW#r%=;P{+mrb=<#9KiGF&w4H94#PreT2Uv25r#6Pd`QW1$@OpoayA~uYrCLq z+ovKGr^>kR;F34)VEFFLTN7u)zfdH>n`LQX#>5Cn>iK#b+YUdsL($dvW4ESzHB1+~ zdNFD}wW%IbgSUI(LoGDiZ`rgG2C+Oh4&QwPpg%&>b@q^4VJs`m-5 zxC+qjZYQh?dGr>yV>p1!-%$IlcIc6aUKAJ&3=QONR%d+i3Ou!6EAhozYefPWBeKg( ziB4uSG!(H+fvx3@U64{aO_j@I!eKY6<2sCc>k+Xki5fkBQPg-lSxgt6MuGbZ+q!hK zWAjY26j16}BFa@`qo;6E(X?1To2TW({0BzTUS8EAKimbKP`}z%krw{j-_u8Z#B}`~ zMvW)xHO^Q&7>UC3d!4vOjm9y-uI57KL?+I{HbazHFnXoV)BBUJ*QEN}=cS;%=9N&7 zET$?caE$28d!_#eyC-sIFR_&Nz1F?83?^UYDxrYko{N}Y8fQdfUx?0%t&CA*+0e%0G<%=0VvISu- z=Um0;>N{~tWN^Y=!|1kHw`y)+mD4nH;fHQPI4}4l?x*ZOF}Ef}yT*K9+DW;-6c~^p zLS;7x(sT|*lUt$Fzah6>_Kps75o0lI#c!JokcEu!lq4Z86grJRKAo`w)?2I~*Fgisw^F%zq({O&`}CuY-no*P>v{)X>xUwkR-3 zG5Dka*yspv6-AhSN*o@T^TB{Do?l-xXbTN(^2;M_z`9CLEsT{@Yo%CLY;5wxgOKq2 zW*HfpVb?e_rbkBsTs@Gy66hGq+Ap21yM%K*d82^nnGE2@s)7D7n-3t)U9{k20#je!|f~=fX{*=kL*CB(LlQnXih8J?c+vWCMw+7kx zy*n$G|9sRO2+CB1e)tdIZ14H{y9u@w_Bm{1wFC30d7W? zSmRZH8VOeccu8NQPpX{7^kYu4ibthv4(zfQ6A5#pSo@dqT~9dUzh!=08N--HnN}6nR(6SRED@By8h5%gu+k>1VFw1&ffAZFi`tQQTU0Jy{1lXp zV})DT{v;o-3JKsZ{Zj!sRI2eiG3-y;a!(Ihfn@0_al6V=)@WssJ%W}9(wZ8L&~`*t zU>Sj{{L#B`lzf|M2WKfXP(3=}Njq!*h}~+K6}&HsX4zS))k$BnNxFL?SY(UOQn%1BJv_gvu8iC>4;)_mHw}`q8)%+w*=M_tnlpq4`dvNF%bw;K>&O`_T7^P{dU5knQm4~oj3O3YBc zk|Pq~ZOI7-M{u6S#6C-eKbqMwrJeAz7hAgJZMbyV44x9U@kKD)?n=sjIa@HQx>E;` z9kpyqDS!rCcACHaHqGV1A%peThqc$s6j@M`?hwnH!}g$#JyUnvT*Z+D|5X;b+?A+uXc4)$IgJIYKCieLFb#5?cqw=&u~PygDfpG>X+Qjdeq95#jv^-LPOGT zb5YGSk)n6lt|V1o-?6j4A%D&h;`;2ntx!Te8pxZKk9Pwd4uX+(XSX>7WO&`Th!aX7 z>?XJfd^q6w0{|3}OD(kwk*X7JeUsaa=pN+XJLdvye9F@~ZzUts* zt-^H2e9|P=oi?mfLmyZnUV*4Wj+x|d8ZWT%Okz_8Uft<%1(8TE{C;isJb{NURcd>H z(?W{*V~>^ZggsRemtu^l2~O5^3U89zw`+`mmbWN>1UE~ZgyP{bxCYQMV(-{zz(z`m z7Sph-#d23;&H*BG6O?|G1T4jbDvpnY6HT_n!c|T%xtcHw0-JR+-w;N1zbF-6r zK&{vm%i!l{iPK~oTog*}(!T}oaM^w5jg2@t(cUD{m>IQ#|1JB<(b#*?SP~C2a9(Eu zY`}7k{>TAG6xr@0HfLtBt`%HQ9wv$}n|jwNv+0 zEa#`8sYz{@7f=1TpG)y3YIrp``}h}BE`A;ZkRE$xZin`Q3kLBQIB%0#>^c5Q;hbkn zUgOf-_k&$h&4UYmBEB@Nk*uK`Z^3J(IzRq?-Q<0l@x3PQC5F4&fCn;wL^zDQCsJ^DXM0&`)32C8fpcz6xUKV_P8 z*IH~ote$I5#ip!IzW+S(Ls|ibI=#I0)4wXhuZ?9q9Wh17OFp%^(Tt0Bj@^Q+bQ;{( zcLO2z(AnVcoL*b7#YL59T}5xhL(P$=V;}z*X^~%_hdBn9xFt%aL$vLe=oFmtuUlH% zbJXk6g-K#l)V((Qn2RkEGn;EX6W2vry|+zSchCnPUolM301AD;l?SS@@@8Huv`#Q4 zKZWD8F?ReF8e?#yx}y13VQw7xC|a)mW4A*M%Uza#p14u|Vm?I-*7?5SU*YBi)?ZD* zg-KgzAW{f2mMkMI+y7u3p7}grn61EBQk@K5w~ywHwwx?L@0)S}DiNv_ff4#PS66a@ zBJtf%Yy=HwPpUR*1Sd{F+KyRX1*x^>o|E}Cv&U_dfC@rnJ})^Dr3If-s3qN7&ZJf* z0kDRe`=$636`Voe+RLV7iU)Aw4kGuM7=5DY$DNvmC7N*cq?B~WMoyEA^x=(D2$JVI zb)J~0J9HR;x%emtD>VL5J7`YrbWr+AkNB`J*iCS#-xAIPBT%Ej+D2s_BUfvk-!pP} zIlNOMW*5QQIcfcgFHTJuR~D>KUZa?Qn4%pDg1eoGe!~NYK2BtAa2suWOSAZ)Wx{ax zx9dZ35YQL%l3M)pbR~i=uSMb+*ZJMIrUtz)avvj8%CwOXV!3D*A`Yh~YQFls9c18R z@1a)lJiROsFsh>U7L=#rsK9lS7ZQlN>sQqaCELJme<&&ek!BfWz-)QyjsNYmDkV|j z0~n~kjPHUD5k->J9!4IJNYGHa=af|rC7Q>KEkW6*gq2t7I)G#M2j4QTr(ngnc7EQ3 zgFZu+EP+vr`A>RwyvIY2{fjXyh!Hs6fy`gONAAIM{;%oH@YX!V6_6yJ7B2(OhZKae ziw|MO2DFYJ7?Xy6rWx0Al=nqhb^BH|$J5=Z|8Vx!t>4uABr*Va@?~<6=0*BbeHPmKYQOK zdXjIZ?OP_RY%&P3(I7Q&nGj;NQ7`hrm^*_t{CKyCkbR?r>cuRQ(@#;z=RtOI;KF^9 zd5ER?3%b@azWtnS$I*mc=0~?S*}8&NvD4BXr)oj>r=#sag@Cg2R-pB7&GrGic~ymdRJ z;Mt+5sR!T#SqiD4eklXUM!W~86y!RFv-UvC%GwVR87rB^(c?(84zGqa#HZ=u9djBV zD?Mn4*!@b$25`E9!gJKiin>(O4c)}c~2~aenk9<5nGJLQ%YvyZAK6@C-e=y z?|9=5yeUbw7hwt6J=E>vdC3Ck3y)A-$1T}gvNlPU zKAb?}C%d)P)XXJU*@dZp9xMrgcKtpJKOM_|`t_09qT8c&4)bDs!m#k`9)t^3(%irT zI)tw+O^Yf3*f7w!wN#_<%UxIQ^`ks~MFMIt7w?sye6YMq(qUIJ`*RJ1o@VqbP!~z! z>f+?jFQ+&d?b%&?A{GBKncjG;<3B9#Gm=}-NnnB3uUKlxUL8QO?MZ50K?Aj_|De@_ z)=l=9qWo`IXFLj!F4Jp-qv7AQK;to?Z1iDWY2Z)d_cUq+$*Uu7M7Wk zdW;1`sw*OF&ZYk5Q^8CR3o7+;Lt+fNw8(cJ)q4U7e$MG!?!baihIaZ}%U$H;X&3(0 zOfE*BDO2TE?Q_j+dQ?OOhDhP@L&s5-obo)V+%)(&RJDkqDB*m`u{-rnpn41~nQYgR zoPiJP#-ou9Zaq7@zLRk3TzQwN=B;&x{0Kj8|wpcB#xlhTI}8?(y<6^YU= z1S)y0$NaIy9+%PBsGk?MJeD^-;YrlOgk&`wZw308LF(+(^B=I=f?*LFpLM6>=W+n# zqQjP9iPx6=445x14ap_toFg+&7)7GFfq*(3iCCqYlRrdbgul+v zJnjz&)h{a!=I`5|=%m#V$(({re6t^m!WEdbA7F2akI^n@{9QrW%^Sv&u<2qtB$$2GxS(Zc_-!J@vdEig$hNIwjdizQj7UR=?M&9y-d5irT6 z8J_+Y$#*S<3x?8GAgzG*Xuxbmert>An*cdL#=k1;c0v5z@OPk#R4DSFT7})S9n|6GccJCBB3Woxk^q2f*~= zzZ19Elx&EnTfh0I(B6h5x{YC7aAG=46H={|&@$g?Dr1I53Cd*Pld9Y1vVQYCBg&*sQ3|CBNitfV-5K#%1Vu%@;!_BN3OD=Lb1-<0}$NsXWG7W z{mpJ+|NVA~?J|vuQF$A>$;@X>i4y#U_yGZ7RhI!5L7clle$(LS@HP1wDjsd$dC_Fj zfGu!wlt?!PLoQma;j$ZF^B|b+$Pk(rre(xToN^ZocpiZl?}k=X3)&L&X#p3H*xFzn zvb_0;#Rwy|jmxiC>~pgeLs%iSGR|Prb$+6noja}um)5wpG)I)#^dYb+$(!Y|tbKkS>i1XqNd`EX7PTW{;X0rU(sr z$hY(w_g>H*FqMI8%e+!l^lUU(D#!{Xuz_YMu19-l=19LZ@~9?p!n++$92xBXEZxc@ zal{|1n8Q-dyZdqccvzVL))!`!D-pd6lB&xuBf%Df@n_tqv$pfdvWPxz_y#T~)TT1W zW7S%WfqeG&;`X<+`ZRWj?h4YdIdcjI>1(adz8OnV++fQexRKzm_G1>1?8(*LAK1k~ z+Q@$;BFNb|MqtK}0k7dGfY zuQ!6VH87)Kz`h=mK|F}pFb=LR{b{O$N+&bv7*#3(NDf;!DNG%EC!0Uy#1(sJQ?ucq zJjn&#)CQy-U5&kN+n^DgaI7?f3Z+CwHXsxvcc#L4U^;r-Fp|NoyB#3K@}f;P2C|nc zrtuLHB~z+{aE3ZXNu#(~PxYyURPQuW`+`lHQow*}pF*YtO)9GBbI*8f=)C7`X+3%zDmM^ zJ&^xJ=G%o&K#Wb@gaA>HuWT%l?+A3<*T5IK&#R^Dx~~HJ`^`BP!CLcbirY@+pv!?o zedg<@jTsHFb$D3fBfwnWzyu`ZFEi&DYTWq<3<_m2hmV=+>RK9_i}Uq-ptbGO4P3G7 z)%o!%yoycjHf~4PT6s$rml3ZnmyX=l9hY~YNG(3bGOnc};u>t$kV&!o5d5wSln!5h zvU&sMI>PV|8HMZFn2=x?`9*|yOf(_IC!e*bxf~h{MGi0wi(0t!0BOug7EoJw)?h+_ ztlop2BzDQ2Nt(Yzxa1Phm~#|}z~K|f>4wPHlG*=Lw-4`4Bc_^wyPnN_l2y2Nzy)wj$V1M%BE zoy5cqPYl@7bQyB>^tz{sJoC-GPKXm+^CP+-xqFG{Y?jzZ1%A&MJLteZfUfV^7`x6X zvDPZ-eJ_2(WY>Gffy~D7M;!wT6)_s=fb)8Cg{~B|fx`=8tLR$GnxCyM%qZt}&n-}% zqr74=@iJO2hkHJI5J&Hg8KDmXY=Erc?1iB&3`pS}J={z}cE{%j!W1ox<|V28(f}~f zCMIsP@lJ@|J`}OX@*C{A2UISc?yG99&FSO&iQrEo(cQ7G_BlT&K=(Ffk3=%pL|9KK zMPcVdxKj3LhgIm@TZ)~OhRsU4!%xSMpr9)$m0TWmzWWeh^-%f9^E!HPK>xYbHP#z_sv62j0A0?HrGt=w$KpZp_{)e+ z7CEHQyrW<1n@I>wg#ah_cJd5@J8|*1bu5=itrAi?e}qWQ%2C9%9cG;*RHxR;`-)uL z3>FR?NcOgmQX6tkUEXV8 z+rkWMCrW~49_wt(RM73&u>P^p#xC4>=n$op^Qx_WrCh17cS3N7jZ9emM!*T<-=UpD z{^f(O4Pw=GDWb;Jdpq^d9TgqIoWsQ1r%CRh%!19HTh*)JI6FxBumCEY#jMqi0@){8 zhJJmK#$AfOv2YlNoK`w`#k}Oz#;0R4K2-(4D2}TmkTcH84GxXXc^pPiF?o6ucjSk{ zD2s*v&Rf;)@~z7VEJLeYs7(u)Q;IJ|GDJR?_Dju(9FZVF^4M5KjcPob^7z36jfiDnZSa<5u^*1={Z{A=D8CzA~E zr&Jdd@9WWA?ryLG8&JcSpCkm-LaGcY9mbM|GR<} z5B1d5#}gG|fd3{-BRn%=>vVS3`dHDN%J|2E)Mp--pDI4MAvBIbJwC?#Zq#S#JMmN` zVH=_}vs=5ubuVc@DB)Eo-LlSoQMS3;_e9{x8Cj7WVH9s{W*3>AS^pa-9N(*ttq%$O zi-TTIV!C4B0O;m-7in8)u?S_OT?ARqJlm4z%af_djFh-XYg2V)nTJy{k( z(D1brQ`Qolgn9wT?lgA-SreQZ{x3zBA2CU!@ zM}%VarSnOZ>1vRR>Xhd#F=MLcBxPPvj}xcDmV3%&!+O}KwrFe zLAl;=@PjE;pB{Pe8{hjn=bv|&Gm;<@dIhry3Bz`B^30?TD2Nmbw%&l7CF9(J@m?-1`asRcW8bs{iXZp1m;u&#-1%MJJS?G*?w!G&$`kU#CiTm zE#m1cp2=qYPVL7m*Y`M22b~I zs0als<>F7?2JS)?Bx!WByY3baK7w8Id{p(|=dlpozDo!6SSXJJGT$SW!V2$-mo)%6 z>)FRI0%`@x&qIXHt@Vx8X0SFeUg2|MnOY3!Md!ZzvGJ__1KO8)_s&rYD(91+XwNjHY6-r0+2gR7$YbdZUG zSy`SVLD#c@qpJ3s9*tRiH{Gb%tyV|BD3UU<58TDF^3D#puB9C3_dkW9vY#fs=&Vrf z@Adei6Y>L;J}a;sXAFx)H_}5E@}E576sYsn6h-1a9@|2v+An3BV}w59($%oKlUOB| zyC89Ay1An1vdfjBhD0g*pa?E2V}V#LdIm){h#$pUCv8c1csHsbi<-~*0$qRk;Hs})MX!= zr8JBCh=jt{#JM~wVX)^~b-v_-vnG>r24B$30Yt^PEf_Mou$rNpXYTHH9|-u2Rv1?a zA#5q~dhIP{aI)EO&ldi`LC$}m3Pium$?OT<)vER3yk}-~(|BvudBF+}%}N1ji7$K= z;JIl=KiOfy-uvd@&5s)q4>6?X258L7(DYO{4YT|}@7!9S6mOT;U{jE{C z#_~Tap<)%QirST8qz^w99#C6xo=9z>%N*!i@m`Og?fGIC-w-4~#Aw}2|IEa)@?nj% zFph#=Ic*~gNt$y28mW$DqqAY}XK#pgF#so@$zq87p*L@nwvlB_!EAxP7g(hH-z44= zf&3B0RT2QO^xCBl!Y@L;tEahlL43F4fYtnb3kW6Y>{h}1J8OXT`L?c{s9mh@V2f(T z2qIAOr=iTnt@s55ubn@?==N&w<_vW>aeb{_Sh01QiFK;GACNNgQ~h!irCk!Yb@_UH z4+jroFySi!nv0POc*01y`hNW{AAk=45_)RL$e{j4IYErNjwr!!)`k4JgzQuVzMQ}> zvl32Mbn)$M8}mm1Y%jPh<6?>$9QJ)Xm-@4XdIxC?ohb06MNbN}42rMzYZty8N@a^T z74^b@+5RUJq7?a=lO!faRloNXqwDd^QD&}aO%%SDS=%+CwA9|3&D;+ehPKg9{XWA` zzmFbI*%kro;|@K(Ny>crUPZAZ!st9Y(q9kKYBg6S#4gizweckltPJOGK6*pUa9$XZ z(#7rr@zU~Q$9oIO9>d-#7L!B2+R)>^1>!)a@`j5v%&E90+j8o62ct8Ka}dCw&3l)3 zWFmhYa+di*aEPQ|ZE1eESLqmJAG=-Bd?F?stwr(94LH=$QB=b_PkFVu`k<+SGXJ{mc6XwIKCuLKacH*U z*54g_OIZYrGD#oTZT8t#XWtR!gx`gvxR4N4Y8YrEU>513e~#QoU_V5;MuW#kMoJ0Z zRdZ#oLDjL=zV{m~PeZx4`bAs=tR;=|fc;u%6L~0hfWGUPfH%&hA-68(=6r!CB1I2w znujnMql9TGOkx)!R_Wk=5R3`h8qfYU5x5L)IW`kXI}%QXoB7im1^}?SSI-ML9T;xf z^+MD0L55m;k`o8o2u}26cN%(Nu^|I~H9Ajsmh>|L#8?urYu~+?JcTJ%rPOALtJ`+V zKzC#Q>txP~1bVYlw8++=5bmS>u))Rht@9)<9(#(AZP`8h%W2-^QV3cR zpuvfH$myl{wh$cSK0^Ibbt}#f7x_PWh0CNSYJ7x^pCYxz2yK{VTDQy~wNGQ=?WxQ? zK27&Ff@Xtd^jCeB)K@FY#6BEt%&_lClCQTv3b7|DqBO~J+mx(Kl1HZ#x}l2t&)3uR z;Rm}d620@-`7+J;VkZH?rVAS7JxWisuq9;mSjDMUh)FoV$%F4tf$r|C`KK-g3Q%-d zS7z?!54A?q$frx<+9|{L&cg_n@blhAj^nylz-_s&cK@2 zxz|6#B(JJ=3ovCJHhu!7!I_`sWeIO>T7^@9IT9!GTnf%L)| zNf>F9VH;A@x^CDen7-THXm>Euy3ggh@57%y#+X$I+Vk=f+=@aZh@&^`#777u$mQ1P zpv;#wp~8|>KyMkv*Pb0S{3RFmz!q4V+#Ejr01PMl@f z*_TLA6V<&g<+(K4M(_*?w#WH)5?t`{n4%!by^8;R363hzlFH=Bm0f-8CQ&1ztFt zQP9ZyjDfa6sBXf?7HltQ{A0DAhw*wpLZZua*b=$E8t02w~K{hgJhgF<%o}B^>w^03A70I z@DN>Tt9wXsJ+}C9OsM-Os0k&3;c&=K`K|*3(mGNKol31SCc(L zvV!kdrF_{!^=&}LXac1P8_T9ak*P;kf4MT%CJ@!N$F0B<2+vt^WU8h=Uq+n$9ZLk4(QVQ*vw2x+JU|+0qQ4 zF%S2ipEx>kA(>@#WBU~*uA2}{RYMlZX9O`D!FT5Ta^3|I#Sib;Jy49WJ4@QByjREg zj}Ii>DHps}zl^PvUHb2>*^930>!yH5l1gd<#$*Z;2XRdxMggXRirj3-^otAUd$@q- zWIaqsJ>d0_o8fYQvs)SBZ2(TtR9Q-K*ZS7WNXdcWbKBJyvdj*nyn=0N->pt=0xLy< zNT^qv$bVD9V_M9o!=`)-2@v1&J3Z2!pws3WP>}=(K)@0ahuX0kNJ05e_IA4DFwS59 zU|e|Xo;KUD73fhsytI7VIOW(81)G#<8f9NTI;Ag*6SI-n=4eA1+%h7(yk}0O+~#LL z8Nz0n;yQvlQHu?-4itO1@x_tc%ii&A9f0E5kD2wJ16n<*DfM>A<_W_)G8lPb`%J2Z5s0rG?iMF-E@yXo^Z{iMOc&{A#3P{fFvem z19iX(0EG#`)=vO!vTGFmqU3ikj+Z0GYs-#{|3RJkX)H+~HysvBq@pz-lt!E)-C zh-8Z6kU`%w?)|x)xShZ^Rpx7KZ5!s%);R%s@jiuqM}Gprgb7U`@Z?De6;gXvSEUPi4lmM_ELX*cUH(jwxg8u67TWRoY4%d8i+136 z&;@JgfUR@Lhce<~dd;i1qJ)=1246|4@)m2)gl~5R3`AMu9J&#LOQQA#BhCPvs#LgT zH`nNjioXSHb*1unukB_z_D|qD~nK(X5Y|Q5Q%QUz`dI8!GX}rp{?T7<|@yi7}k`r;QgIti+jR z*XFDO^~xc-u3tVIdhRlh4dJeFiwAm#VnjNk^k8e9w8;bNck~O3?v7=mgL*Y_{zz+% zfYz)tb9kWWgVnjl^ce5?tI<~l4PYU(AiwHeqWe|Ol(Uj0s`z6k$EbzJ8v&;ItHudrJ9=(X~ll@!sC; zaeBN~WHtMSKqc$)g!FW-v?xsKE>|0onZ=wbGql?R(7#)7A&r}`=VL!HP5>%{2d{|N z&LP=M6ki%ByTsus)ph%Y%{y+N)ih7DsZ)5h&}!T3o1I3adJQZNuX?Ycn@L(w!7Y+ zzhV-9zP8pOzIV!DAyyDtlQ}PE+R<@-5wv1zMtNiiEg}O5S>s##vCN|skV!|Rf!xv~ zs9G4Ba0gA}4%fHy{}(bGn;}!p8MzliUhbKiR|k8lUBF$hYE|>wO6K+pnX6ro@UVav z%9ZtejAP!4EHxbP(!|={f!{+Y7i651w}5QCKA%P{>50gL`|kezvjUUK3(e6Otr7~4 z0nq(RI#ZLqBE8L+*-d@XJY<3@XK%y$`u6s-RRYK{Q;+3J>z6Pt?h3O2pvmZV_B!T1 zpqpRd8AVR^09Tzi3)SAB6?jrgY=9iWh6@uQ0vPnQVLKJ7nBipnKFHv(Vxd#A z%a$XF%s?mzGR@R{i)bdsym%HzWP{(E-FSTdSrm|hUWiOG>xFfKb^Gd?qm`kwj0Oo> zAp&CP4(6N)(HnhX98;b<1yYS&awdv^?8axQ@4Bxd6s4 z{nsObrEP%T`0XMg@PT+9n>h!{SZy$0ITMxewf}G^sWXGJxM$i9)7OAhdPZ_UL|_s- zi3#ryUMOERN0iF@PpJ(-Dw#c=O6+N-&U8dW?x35OM>2P$d8bw}^U}ia6QaEZt)e)F z*!y=&H*)wLpdQT-;)i%(u|F#Fl?lVtUEni;;Ez}sklATgBd`r@p3H~^CP~bFLN

  • P*B~s(!=fEb*ggiAHb@`y5<)z-~{#S@CU6OSo97FnR zs;VJdLio*e4ieRt#_!9_vLzrDpC!$+ zw7Jd1kz8iRonZyaE{3l%+Y@XtS7E%%X#_c z=Z7^nofCjXg;Y8p6$-h@wpQ5SvjJ$(hp>rYEyO&^{#99y)q+Ky?n*XUVep~TA%{A) z5S!MQ{R9&!!Q`ypi^N3`%BUG56BAAaT`i6nY10f|ElLG>cS>+lXsQ8Kx70f6L&pS>{%2VkZgVQ@Z}eqs-s(@@LBG8fU}GT zkBrk>23JAMU_X=ceRVbYUb3O9^B%e9=K)*Jn)6A zubhSAQ%MnL77|+ljWwPzAJY!sWua?!pl}Q5W}vN%mcXLuzHa@?36{WcrlXfCpauOe zMltM33ssL3kPz!qY*mw@4h_y=ylL;`fl74NrQee0Axt0K+@CaA%?!2q$^_=YX%~6BE zxAmDh6OqArbhOfoJBqGkXb#R+*&rwv7n$4%caA4s8n>^f$7Sv_T$Lxnr)l}fEtw{Z z{A(A%X@PeUhut>2LgwGr6i>>1YF4C^0FHty0*vGULEb1(dX`3xwuoa+thfy)zugby z=<-u$Ly|;L`uQ$J0G6)SBCp77eWyv{6bUzj;6B1mKvpQto;!fWdA7|XG&lJ0aN{uu zw=%k=r|eGRvn9q1loL%ef9OJq>EP|1a;~K|VgFO@l=7Yk6@}Re(T+>WQ`;~^7@L}%;6JN)6k9Dm-QhSea>((#bF z<)ELa3hRqq$mYVm-GDWr&BblX;9MaUu72}=Nd*nK@>#Qb>m{@6WBxlR5nM2NTEt>hjIQt$;bss^B})ST%&Cx^@B zDNFk{G;afuIJtXE=&a2jSB}IYC;69mKC=#NNy;QNfyH5lMm81wayGyd+%f}}nB0(* z^y?z%Vq!EA&%!qwk@{D6Rrt>m=H9V_IDMaJhph8w@lUhy1?L3k%e_i7j6+qqS!&%()98!na(2(2_P3>;2`+7y*<;p z;&Jc$ALs}nN1LXWrMs^JE3ERv=w^AB*&j$f+7dj;68r1ekLR`~BeE_->ZK8-7Vo2y zu@g|E-RIt`aFpyCjt)`)&Y~EJcdW!BTff(!*5~2s#Uqb*{7_fjMU#mGzmexr?I~3@ zlOlj#7pMCMg3FW`pn)SS)lGz-h9b08N{Fkeq)w~J-#SzDtWb0}gpaj9C;cjfDzxL> zdmKOQ+lzT-NeE}VR%F*`!Lr^`W*mj4zANcP6)5hfXRTO*fe%_XFaMOhkH}N+!sscB zqtX(nPqlx-a>&N&??WX_gKwLj5Ym-!xBzRU-*cwrjH*Q zPoN+R*oLecgrN=g z{hZhsx0Q$oMnb^bTVAHMSd5_dJoiVqKfrJVAR?6go;WHkVVw#sNJg}3I6w=bdFR_8 ze~oFhk2mE)k-5zXBGobn(wkWuyV(=F%NE_XKlt_&UQ?U2o5d4V;xT&cp|y<;@r+9P zBq#ebZ&44NxiW2N;RLlGvx7bj5Jqw8qa#JUUrwj$*$ z%mrOXz&9VLR=YuRp5DY81X^c2e!lqym%hqBYsZ$KnJn4GOO7wi4D9b4ReLligDQE( zmEj3gBmOyyYvwmyhUGdQgtwP7Zs|Q> zJu61W50mCp5W#^hQ@cD^d$$6uEkMmI=3){sGcVDf@73W!uMY>F#SVl%{sf;4uJ)7s z@ppa-@*Qq~g13EK>g9r8%k3qL;8JDeE9zBc!z1 z-9&xEgnKTp;zM06y)P;)+gX-wD6j8?SFb{71<1G#C+}7Un}ea5^HlEw5_5-!CzVk~ zY8T6|E_L>Pv)|`9+bxYj9+=%xp0=#|k>K&D0CWt+a&DFk8P$S4Epp!#0btwK{_@wp z_jiiBxMFjv=x9OBB0Nx;k()IM?p!{H=L4(rSYB})%9d{5P)ui2;gzuE_z$84Sl$5ew%2rrqol7*IJ%rJ`F$tI zo~xDycNCJ+c=2IUmrsoGc6YWaY*$x!^C8*sf;VL#Q0sy>22(Pr3wpL;}?ZQW32rVa?_D~)Y2o(#v zLXP-MH2?BDFBr}Kays2;f!lfPn&Iolin}6;!PuHiC`4iN9&?(tI$cjryUAABN(_{U zyUzftXNSbt?X4#)&0yij67s^25KL-bA#b8&4N{H?|BfvugW~;ud=M&?QbYno!2Y{BkoUu{!(@_lC;jmj@7F*p`gSheEL4qNL5V!15Q zE%QSV2VWYs(tkQRRBi2#pn|33@f)E@$?raOo2#ZB6^W6@=FFn2%d6HOA3vMVJGDol{sv^HP?5m*Cm z7kTmWMtZ&cf`K#gl)x3T0w0<^?by0K%Z%ZPCEIKKB(h%T7h_K6BVrCgHVa?$o_5r3 zAR<&62`N^1GViODMYyrnlmcRJbTk-)vxLjE5{Q7UKgB_i(3ju|+Yj_P?=5zy*)4LX zR_C@@K#69`ZNE8xw=aX0kgEjv2lgKdk~10e;B2vjg0P!OhnaPWq)mP#{eVa$1}7=u z$@`g~&n=~RHwJ`Zy*D+~pISAaO7Q+NbI3LRBicxlj86b6`M9=xyzN=`BE8SH&299Yp~bQ?(_3A>?wqaL!DZcl=BCUL?&FNe zH>NB|c9s3+P1q%_-MCTmxvmskY`nn(WMX9R$zVGDUr&W_6RbmIgu*-R@%@<)>NMHZ%&2cKzG`zB2^N2~!i$>tWZYTP1R2+X?;c z`{qr%*z-*{3A}GSBnqi5`_@)u@I+V3$B;Q}fv5^R9kAO}7G|JDInqoBl75U9y-iUW zKgk$TVv=Zt*An*EYF=g$41S^-PDdb2Pbwt4ky;darBm`P5@)XFlt`WvtRD5iGc!DpFtb`ip03fwh++z1xGP}Y64AX3+G^rZ9gYtAuAI5unL!X=l#7|!U9wat0jrWz=U(RVH4(-;q;fz*aK}KfQ`@>;~}kg zf@aDH`NdCLJzi{}3wD}kan`|tkY)c>Q&1oz35G7#7W{xU4yd%}h7lN75(s}};I4K) z4s=dr%Yd$4jy|QL1mID$kmL^JYY^urj2v30mDR&1Mkr{qO@@Ig*R_#um_pqU7FkN* ztUxn?r${iMU%KtG0n3$2XHvn_2Ly&WA*)47)$ITTm_~)Cx7k3ZL1I0PUw;ebJLQ%r zE>dK8#p3W(YkmOP`4q~-hWbIQ;UhPF1kQ4{(O0DH=Hr`5y=R0%?}60G=!RsefPh2v zN2R_bv0zM`hySJs=~Kb+bi-=yu_fUm8NB%J5-FhduN?t6>u@QIShZ1p?+_ zPOk!+VOIfXiN#gS<>?;m!invL^96Od1`D>u@6C(FDQPxwL>4;i31%}3(7O&E%ANz7 z;jRU0!;NaF*iiJhhsP{757f{@ zt-2Y+qwjWYZ;{f@LMItx7G%8|pquGUQeQI6R7y1_n%FSP>(lXuLIV1Oo20PE0|jxP z)hR>5>=bylnST_iiuS@n_~Cz(1G);gus;V|I82~3R}4NcLCyPpT30JvBvGTg1!;fs zQ5>;H3KY#X65LHt3uOs3R<>9X?yR@rWrNT171USCJ;<1j`UYzTUujk5SRX0Xo=oF~ z2utC?nmVf;iFMZ(ugIBp?`1#OiY;p7uD#vL5PybH!fXF!!Xms^QfG+FQ3anvuu zDR;MqD=}t5?px{dy@jPvhd)^BpA?c)f)pzau7YUvJP}DG3@y5y(tVYua3!zS-(SF{V#9 zLWHyLO|ls#FcD<;#t>C|;a&G@!QVd$=-pvRuuR_Fv8|)rcF0)!QH9Kh!*vy=Jq-5K zE!>?s9dz<#JzFn5kb(8|vbu%? zF$x7lT4!o>gW^(*ixd=4+v5^&!DqK2t5F_l-{<{f9U2vk_p&*hApn&jILU9NUB|N8cz{Jtc_L}<;! zVPx{YxrvN`Df!enC>H|YW!e>-q-j=$+oQ<2jW(;r=eZsj1g{C*7C0y}yO>2YUiO9s zQ7+SQT^q}!r8CUA@le6@YbITUze8wGpY771|CX*aZ-hYnGq)*V#deTrO&Q!-DUOOo zH{p~5jFZsHKB1^F_LP&Su`xRyF#O6rI*~dZr?%_50pRh$g?T5<0ecPEFnTm zU}=5Z?i}l`Iq{nkAc{@wfGI)o0bzglD2JNjVAgoP%O52$YtpTlXf;;*FK#Lcgejk$_JK>-M^G1C!|55s(Fg z=8m+Y$XsAMeTj)gj}6x-hHMsDC@0_$zbKhD*TR{#j>AXc%hi69Z4FHPZVoP8gTK_TCL% z&-xeVPK1Nn+BXR0fBZo+)GYd+hfePnQZ;ICVzhy&>s0FRQ`WfVsnvO1&$Q)#I|aON zcPBCbUyInj+^+oOakH%FvBAXu@s1+Zk+7fE6E!3qM&`6rN>T+G?w>15ua1&_V$^{% z;AL;ke5P`$5$tCVKiN4k$;VXj{~vEX=UODaXY_xOLwZk*+TF8@9E;B}-*uimn#_w_ zYDEHcwUKka?E|uCC=&*pMCQ&1ta^vh+di7gCK4c8F!lCddHRqHtugKrj&HZ^B%IQ1 zHVtKPDwMA)=ri4?3Fy@CbzUBas@Ot(biOsb4m<{IS^syE--ab8D40|06;72pPi zQT1dBq^g7yYOP&W7zgHl=@CSZUp>1D*7|TUpuqdZ6lDP6I)mDhwjQ(WR{w)Pvm`o? z@HkfriFCZO)Oa6PPnVSna!6$$DF@BNTzJoozmlsjziq8*w8#}xHz!KKNvo^48_Vi#|SzkpQw=c-*t%hp@9BGx^^3irPA{E z+E7qJ^T$GA=4dj9(GDyoUl$H2w~ZONy@F3-Oz!#w@c zie8Fj8YICvO|q14H;>FEkpj4)zf)!5;MATD#h5{4TPW3f2a^q4UD%T{kzxj9s7B#8 z?x@8hr9l}qpwTY#jI;`-?tqm%vT$vCvqKAbI|Q*n%%8oo#X2`EWIwh%$VX20oK*Kf z&~Z$|pMLN`>*Rh}PQ1x`B@0J7OT;<&zhXKjVpCU_w84olbKG1M99}4ev~e6xonA)D z@{4TKA5C47I_D+omcr98TZ%O}-w`4u(GA53#w{1oYe8UQ2i%4Yv_qOYWkh8)IZ|9B zYVs$MU-^Vr2*rl8F|#)w_$%Vz^*%N{&M1{EI1$^ijnCJz_tPk}XvD8y(1^N|@HeJs zV2TvR6g91?`(Y{ru`bX2Pcwjmqck=0KEbvIvB~Fj^doJemGbXSsght(8NU*#_hq0g zaQbA?$-8ls2#b7igDM{O^(5Jyk6_5i&H~VT_GgR%?-00SVlg3)Jl_?URyjJu8;-Qr zft&0p3`S(t6HvYF{1=NeBE4pa!AHp6C*!N^)v6J`(#zE30fYemq+b=&i8|h)yL}7l z%i_>b24yOndvk~qQtXp?*E2BjC>=aHte6lRZv<`%+Hg)$1|r5W0Okf^vW`irvXPm6 zxw6#3{!0$rhV8k(fQYDhpiO;$CxbXfdFILOp(&u544;lbFLqcfxtlVpWhjm zcDQ|vv3y%C43}IUFA(P?lt`y;+E3NPy@reI5s4U`5(h}UzNxQI3B4tq62=-FTj{x1 z(8vF-wXi-A29XDM_fWRA_eyN%V8vitRMF(Cr%wtwnHCS+CWFNw2?OJW%fro z;Z#f9CfW1hUDIyHhOO(iNa(QIryDI%}!^@{z~EE>HmqCP8}H&!D!n;KL{uUmUGo zwJZXN!%6|-qk1M9cA1MT)U@KL0`nqjfeAcp<9QL9R{%_H$FYb(gU_uvs|LbKMXB1V ziUhEXg_@TQ?glGQ-)V5kwxtbal%Wg`V+&8B%){Evwd4s*1fB-6H&5`7@S2nv8vIQm zvRp{*rQE+Z*G0Xcm2Cyv-N$a>-LlXpAggYT_DzVcT}u6fsot9S+HKf@gC%hV*?xj+ zk8fN(I}ZLfm1$r+1M`(?7yi7%HEPbW5J%Dp+wJtR00)5|lJ*kQ?;}Ldz|n#ZwXNXW zIp&Qe0!@lFf1odtn07eFLTsvatsS}?VrW$W$akM9mk|BW_rt7<5s!P7g{mp*?a zho`pp$@-XjATMfac*mIA*JUs&zb=60QIsA%KE6Ti1Lmh&9)tzrn}6Z7$1J{1meyYN z`~!N)okDKe60whe?n7xXc2pB3kWe0}`yOBp;9y}lOv9448xiO_W zx=(2JGDz53*TLDG;P+AEpezvZXMg647Nr>I0Vae)=uRkm0OmXuuG^_j=T+r9;%I;L zJUfHZRXCCXn|3pvFX0OE8w;G~hy}noW_Ht={7-U+PX2v6fZFN%&H(!{y~c7Uf|2a? zz`_cNaaSW`w;l6yC5&;db6wUwo6gA4gAGZ8x(Z8FlO^mG`!_WJ+8T8+Wyf5H2fer@ zR-tT{|2;SiT784O|Fat4KF1eS73lRQyU%M)`^iXU-vR*=C5lovDhZzW$afLyW*iR< zSO+^uYms=n6vak^QDm1@(0G_um%nd{uNjd+&W~U|obbTPK2|hQvR*XBiY(m_)~8B+ z0oZSddAXoihWR?jzT~73^PTeqksy}uFiKq>TBGG(7c5nE zrE7GI&gmEd1gwU3*@#C!pxaS2mw8Y@?7#Pw;mj++>^EPTez)tZfc<7UOs}}#6qkSS zuZ&__VWuMFw6@ANMr{aWcv}P5r512;*^L5q_?D>9Tu~0|^nUqglyOB;G9q3eFjD`0 zA-!D+e4)tS>bun~w=WW^M1Z2f5i@0Rum|G_AP(~dKpm+V2 zci#@t@mc6w$xt5217q6pQIO=L_Brz>K_M{a5Ak__Z~xSIN_6r8ccw6+C1w)ZwGY%} zU|+w5$>p6*exIsX$cG*Xm(Z79f^_2o1RXu5=buaTyC;*(KF>(T_o2yo6m>QIjO?Ch z=~UJEVDkC$Jl&AJSA~o9a4jOq>3{0;8M9*J5<24T@11AZXiPL!9uc*Q*dSZL zL>de+%6Ab3}-_XaBsS_-&}QG zDi|;VN}~#1Ykq4NqDy6!w&8-PbQIBimoIUUU~3 zfx_!es2ju`Q=bxyP?LT1br0#*FTlVo#&xTQyk84gJ0H#xpmVpXUUe{&t~%x0js0BA zyScGz6EFf;OQEzC&VIF=ihPl0vE#Oqy4JQcd!pJgi*}l9=fRwRSl>1oxWsUt$e6=w z&cF5AijtL>0LbsSLr6YlEhA^nZP{H@e^mK5GdHMvrS`-cT)x=9Kcc=oaPD;LP6u0g zb0>sx1JU+x*8Ianxf_)=m-bS0gICZMM0)(KVCwA69vs2XK~Lh#S13%ZlPtQ0tfRY@ zWiTqN<@?6XdxbsU6=b~g#O6M~<>24?PqVQ7HIJ}jar{CWAD2IL$62NdE9|NF*<~319u))prn)PS! z87-TF0E9nkeSwZf4`IBAZ$QkTMXma0^_3Kl@C_N?YHNLk#0GLEpY~p{oKbRfCWZ_S zvVO7&^;|)9w_nRuptPxwYRC)jK$B8{G}O~u;K{@$VMQgZg}ay^TJBE9ta+Se@2C-^ zQMgjY1?XRq+9~|oV^^{N+dwLBk`C*fW(FCDo z&|frjHwv>oBNKmb_>_`5x^FYQw_sABa$b{u_zxKq>(5oKvVZ zkwYzZKx@1)Fd)@3hXwB)jD&1oCwP=#G^+c_7|-Nuun${t^U)26oZ7Q%qX5ZmiI0MX zXSZbT5F?EuQ?nwkfVYZSV^P}e4N3Ef)0&62k-BnVTSaedxg-V8Pm z!?bc+z_X~Zy~j#|KCQilD3dW0ZUncHB1|_Qn^PCQ0H@p#ra1(xW4PL;rddQXT#s1F zaP$;5iRxaOWk!U&?CM~aJ>%Tww z!$WSHD*J(sat7?@Y9g@fWMK_jlO;qDK!whwT%mSa+mC%-lwa&yqHLuI$V7$8r5U|P z{)*^R;j-7YGRgINugfAB=% zfNnsdSkxkAN^3k$K0j@)&>{6*0-34rQIHRhTz+`r@w?tL{Q^d}LIwf@^h!*vMp--I z@Q7<4R?*jG%?vtMuD1p9YN+Fm~}F7zmPbVT6F%}Rfn#P>cm4l zPOVoW?*n>J>@2V(ri8?*>#bs6m?fG)I!IQ!r)6UTR@K@}7aPgtTpE8v-2mw=(xLjD z2!cNWtYIPXt^f!-qDs1RFxU9yA>J;@1szFnVHrJYP2;S5tx5{k1gVnZOr9K@9bCN= z`^V@Poss_**mVB7%Lalc?wxHHF7?iMZyV9CqlPKyv%tu8ES$}aGm1K?fKOhd)5TO> z8&La>H;}5=bvqL*738ti69EJR)~`3OD>Ey&nqwL)erKK}+T?r_$2~*K<_0or#V)DC zF%3ZcgfWKXfNOJmHMxfrI)*I}KsgAj1uMp{Cg^-h4oaq20g?vpBts9Mjh-R%DuQ`yR@K@VL zEC)2=da7ZoG}JzeWO3$bBFM5pTVcZtahuRIBb&MzuelTHx)sof(mzGgSmgaYLlBqf zl?A^fNEFNpZPuprV~?b`9Y}Jx5I|F$)_rzUtIc-32@23armK}OZ~#mm*SPksziCqt zAdk9;yyT_WP&V}MkMQUeRi-;o_va$o3_Gv7(vmX5(7diXpP`3#27OSHF?t$K@ zgn^TKbx_H|9KTkt>KD^yeqw4+ag&V8GyY=*q30%5mFZuntO`}-Ss~OLp0vCk4vHbs zH&R3ez;Jj^ZxDnVHp^W@?M0}uRRR)ztq0}>XmUM^%FXk|Gwm2=Ri7(rvMI{c0FJldEp?*>P~4?7(HfIr~5Dn?*Yl! z4*WBH=Lx_VAwW7sbU5@sf@E8RanKNZ>@Bu!UV>QewAQ#@+_)- z#O*mot+>r*@;A={LD^ba4C4x{w}_>rf0O+fLlP2fxzBA}6c|)kv^32llaMATEgbju z$-KnW4&2#^=!+%8Evx^H#d$Gig^&vfCRBZYS7RY2mEJ|@W;9<6WhA%l-jl&l3h79H z3D`QtcasiKJ z+e|yHy*&J@^W#3y^L$fB^QJdy%i)E8xVI8bu=I>EBMBpANG$K%-ls`fO%*IU?|kBG z*;@AQODv*FMl)iL3XorL^}&hWRm)*_XXb5Pdz#bul2KPf`3ibDWtTR>B*k0RgNjqk za0VUjp0&aa@p9!39Yn5{3`cvZ?aAAWaSe){XK6EHcz`~b&_bZ3zsq4M3jCfkHO!*n zk&HHfGdHv{PM`hr@yf6$YG^nLUf6J%>i^rY&lj_CR2ENHH>vnDz+2F4IRWEDC;mh5 z6D|61JDe4xGfd@I|J&;=HZ>f}15JkSJUUf%cS51NQu!BVg?%R#<{I+8oh3#%t;QPI zg*_yj2!-%Mri`D0)QJ7bUQC&;g#iG*z1z4NM-mRo#r>Ks|NSu!kz^>a14&f2iS8Df zL6o0M!%(;vq;=|wS!RLIw7@gv0xflbxAN&gd#d&Zp74^^lye1BiDygKB01083xHJz z+!L4pkb3q)FEWwmJ5PEj8Icms^-5$SL3Gj>7Z7iejY$8|#8_@;brZECyfqV-7m3%T zB#j6%lx(t!adpEl89@4yceO#&@3nZZCc%One6TclD!tS-=Tpy8lj-Lgg3o;SkAT%Q3gM*i83Uq4v z?5F24OkIDw*UQ=+nY`_Rg*BNyTf&}2vL2_)GS5U@Ia^tAcbUe!w*eI!LP&Jdq!i0H zPFJh@lOaJhS%Wh%ol3mt05OP7-5MoqWdGvHCp@NZgh#9}G9!{CPz_jRw8BN6Fwi5- z7qJ#{_8>0xz3IL^U6qSYyQI!1?v`!l36xN{9H44v?#5fl*L#Z_plZ2`mQv-@r>|;c zaea``ITkztPrA$3ba4YxjC|PI*B8TPnp@4H3FW7eahn4LlEOa&gYzct$Yv1VdjqQ* zlxRT)2bt(ZXc&$(4pVzkxI-YY-cNk>p1F{&F~~UO*CF*3Z#YhMPMeqnY;UVk z7H<3}fzth05s@5BPMn_4C!bXClpYuz(nuo3!1Lg=Aw0tzla0KH=Z1Jr%zv7oIL1ph zECb0XH3qZSw*5fvxUh>|-37HER186ehbFP9!lCqK1(3_X;MFZ)NV}l;A*kRO_|43X2Ws?9Kg6W zTIt0@AiXN|nzV#c&1shCIIrL4yA52lvrkmT^{0SR zRX!+;9$*SIrNm`r1L(17%21K|W6*mD|1tzCK~;PyYJuk!u+rBYb*1!ZG%`mG-_sS= z=Jn?xWVwp71FyP{&)F{wTABVbcxs=c>2wQ<_d59u+6KNm>ueS+R zN;dUILmMko==21aS4)iiyk+hWZZ?_(wF*Jw5s0U=uu3-_6tFR5RF6h@JpXq9sfptC z0{iRrldy#=7otbgV+IR)1WdW05G@Ik{18C9rsi7#OYQu0G)O_M?9WE!`CY6(p)b^D zh#&?@&f1v6qS`AQ^@nd{ZRssCZ?3u>^M6@uuGv=A%+-h?c$E_-C@jVX62j1%7hTS> z26dj0l3ODUHmHjxbzu%KrgUl@t2JvvKfj(e)mdR(=Ha^jk-Zx&{+!DtF#r*S;k5;w zAYT$dcFS?pZ2mG&Ur46abmKfgRl?s_}tq3 zw&spDAMkhUjf=Q^eux^Io-3lHnUt#^yL`S@-i*p*oCaJ7h|fmeF1l#ipB0D%EY(Fy zRjq(AE_(P`u8B6E>xOr8nVRm|i`md(dDe?7YtRc5MXDP0Na%_x!re|v3a_B4o%J;3 z=XkZs*;`k*t+OnG(4z_@YoGF!*nr4PGA(4E-$W@PDsSMJISZ+vv*Ii5Y!}+5Bq+16 z9K-9JrX2c#Dl5w;y96i=M<9^P%^yfHZvR-}0lc#^D#?4{hW4}nyM@}$Zi}6*Z@Q3+ zJMQ;mOFX~f1Z7&nv#q2s|8U_waENm;{9!cknmDxh1fyCQTHk;oWhl|FSCUK z1;6wlO_Co)g^g+SW^MHpDAD-%(U31;tgo~3C$@$zTKnO13y>bnSM8{%0&s;#vKkMq ziBsJ`-6Qu&JOZB!FX3VfLQs6Q%$a-JMdvDEJH2Tr%E0MtV6NLng>}gh%@J}8j(uD` z%KI;A!%&R)tfnj49AhQyKQ0&#qvNrg2}1H;o#|faS2quolbgKyOOoK#3Z7-ypW=

    3Ko1uoSx3me|@M#k@+V|iwFCpm9B zfI;-q`WjtJROFB!MzpLu;FSJ~jlch-lK(Ijo5$Ouu za%P?xs(!n8*tc?-pvm&HO;4$OfRS687@bqIkQ=PUu4jivJ>}4;P`Efi=)ZOD>VLZxAsZ^$p z9aY9l8@HauY{>?qapsOL{$I$3(=@18GWG|~imGRdkrJ|J(vz&1*wuWwG;E)Cuz=_Q z_i1{JEWquK!DO$A-&JePNHR~c5=gN1)eEIPuHT^f(MM>xOz;L5r7t@)4h5bQ@ym+k{@xYi6 z$ehQ5xXD^n0votb$AKYiEQ9tIQl->Qen8KI$nMC(>ph%Gso2iNo(X*lsWJAoi^iU_ zRQt-$JZk2<3E8EOLEeO0n5iycHN!AWc?H9o`=9M+=ZAu_2_2XO_OY7!Ayx~*$`lLg zqO|d&j1@$1j{o@Yq;17HNg!PEDK|>!f0dUTCMo;x(}A$Qv~9df(_58n9}DKgHpPbI z2-3jS!Xk&IF9fwMQ_MIKNA{7#-`vdRhepFrH0M1oZdNw5Z08<(9^%s{2Mb|kNN)g3 zSY%pc4gCD?!iJEnOhWn8rvloUg0R|IQu1zuYD(y*kGV}8heOMGm6Ytbx3k7QYRaXWUHQ%`o)GyLAXrP!Bb2>mmiSnxAhD#36FJZXpL5oKxI!jNdu_fj;MR4lhjjq?Ekl0xqUFZ@{*gqa zVTyIw$pgo2*w|_z2wYo4z11Va)IDhGb4l8}u25k-w_c%NoFc1uqZt$=X|jfIPF5%D z3yX-`FoVgDb4bOyA+RVkx`sW<8p*Vq96wskp*Cva9A&sCgS2+LVr*EIx?&c4u4^7* z^&>jxL1+IUb_p$eRXx&PE{;-_#OtKJrMc`M9)Ms=Q14MKNkZwknz59%lYxOBz*iPs zJl5ak#*Gk0Ymy%_K)lQCV5VTPkTptJPQA?PD7{q*cy^0f#K>nq!3T$}zkpzWuMtI5 z1>i8Gl^49CJwZUp31^|ohGbyc7|kE4mJZ>BMDkDU^hT4SU@ z-W@%fo{WXAwISE1N!z}Td>cb(tp(jbTP4Rl*zKJg-_kqytifE6vLYZM=o{u0W}%%p{9 zhe>cZZ=BMO0Trj$cCwxPT>sz|=<`S6Q@3P+^GgvUTHcd%pR0s&I2O7lrZtyzJyd-d zzMBJ8c_@vFh*LEly~zH&mv9biPWde$2jiE)$@D%IvWt|x@^M4J%8}bi5oAp@aWe`h z!`3siYj4lIU(V1Z!SVRUr>s>KT01YD7#@Mq(v|LIOdCOxs&9P6?B7uIKLOrzmF>JI zf#=6!ABTY^ZHOaKUBfM{VRcr5xOb?qc~m3x;dy4qOP&Q?qsI90M$DG+Mp*%0Jq`_} z@OQ`YDkDNiI(3NClibsf0LrY1_7I#KFOkJup2ObWdGERcD}nDH=FEhKF08qfd_!8r>0)+ z9{viPibIz-5dfGHhSki3@SC~>lt@~+LiY6y`-F#@A|W%OapSi`RGDWnCMdR!&2~gn zp=*Bw#6O0}vD?WH9gwP_w(5(Gy4@5IDve@B@wu&18AcCH9||n^ilj%^a;jHsFmJ=M zD)pe?_qYuq(`SvK#IUCyB2*mNt#0chC}C_@Ygbqd0IgvnbB>9qt(Z&VyGttvt{$MY z_MaBVLX-Usg%cQCaDjtvM@m-&-|gx{56m_Rd*+vT}QtLf_U{r_amYu73-{5MRJV(lNKg zulUC@06veyO{&tBi>baN*4Gv#6Hkqc2L-FG?`kPa>8MUZdC(LI;yqfSqLQgqJ=*$o zmE!`g3=&6|weGNoLTN{P7vw?DZXHi7YSmfopAD;~;K>;>~}?PutIQ zU_eSS?pA&@9D2l`kysx1z)PNe8o!(IQrs>RyNpK0Ep6#E9Giu4fs$P%mdGYfrVw`# z0DKxIK&U@)pOH|7)*8^yZ7V^bN9o0*5pb%(y;?08nUzB!gh+@=_ncqeosNi%d zh2pa<*Y;c)7-B`>Yv7sN)|kJ3465c&)j6HNf#yK2@e*6KVs@OyL6aZ2ukq~e4BmdU zBd|%*q_KdW$hoa|ZI3s)bdKWtr%U-me74vSBVfZWvsG z!D9h{y25oYn7ao$7TYgC$81K_q7@DU9=S;=F3f^>896=L)ZI}#;(5F8I~Uy7)U85# zwE*vFH6OoP(Ohd#l|_B`o=R82uK4!D!cnleT)k*O5D3(A=9sAKK44sMCRYRW>&E98 zWRwzDd0rTo+-=7+=FgkS-_f|_$EdrVN@>`sOeP+MdsTDWc4h^;t1^Ude$=gAL=k)s ztDUhlwLkF%4+ET?9>0b?vZ}p*cRTFYO3!9!oKG07HfHrS+c|`y}x4%zA-l-BeP2N=A*bS6V zz+2JRw@#;TiTtTKyzmtz2W*x3f5lK4L1Uzc>$!;$23iUh@oLGw7a>v%W9}@!IKaWHq!f&? z!4z#g95+ECN!&+iyx?{6Eo0_JD+%KTm$8x_KnTQr`iVo|fcxBzS&;26-glM!uqIYQ zCZV5tEE5;4^rJkkIyAm^xGN zi1wYi0Ah8W#|O7#+d-iK!v(uK$pm z{vlSj7|9wxy4t!;)X+wIyH>}nk{&$U?&@6_!FHaB<4F1dhVk!3mhTF6ZB9nc@U4!D zN%bc9E#)71M>-2=%9~)qn6r4;>?(f@rKN-eJslAbUqutdaNktiPC7gt20v*L=|gua zXF&$~C?RzM@G_+lH?xq0j_f_KLHx`Wn>33(x`J@-AZmVWtIR4V^u|A}u{2LO7z?aN zM)VMW91bCB#IU4R$bWlnj(9R6;f#~hh%PC~jLS@UoStBFahYGaM@d%#OY3QjC_jb6 zB$^zlk?pU+)C2i@T}Tov#@Xp&&V=?Oo)EoU1@+F7IT8omWuR_gv*TW;jb-d3O&FV#fa~2kOLz_O5Wx&^T9kTfAcbSCl?lH_&uT3 zL?%`6UNXOYQQR|LLK^*&sGgCR$rm%(!Z0PtuWZXWd=jF`OWG&9oG^&?#tmGp?oUG} zMQHd!7ErKBaCShG#A(w4E<16M$?0*{6vqWHCul4l&ipf`+)ESYTsF}lj2PEd^JyX| z7f~?b^3AMnI-NpNpa8K>G7g`}=}*NQvVuxOPu&t+@eoSJRG2+%asv4~kwR{+v>Z~* zzLR?6gsV|FOI5K;toQsZ1k8-U*>Qr(d$EWX)URQ?rLxu$9Dil|HL1;>Y+F31BY6wF znz=1haP*Qpo`74sBR%rcCg8R8#H%n=d5QN-Yhp_Teh5A*DPTsEJ9{<)_smaUpfexF zYxIH?w7M47n69#OKMQkWXDd7Uyt$6fd#N2Z@1oRCY2}C|$*`i(_wbPK{k=rWJ!jY< z4Y9avN#`6c$6yLu3-aOQA6VzokRyADABybzsI4vm=h;P_95brP;uIq(|v`doyHk#nYwZr zX&XByp6BLxN5-}{nS%y~DqO9QPGy?ISk+Ime(A_a#kscH=d!bpapr8O;dPS#+?#nB zfWq*5&ASw9g*)@J0!zUeX7gyaquD!%yj4^_g7nlGQiCgal*9oHd|%66xVr>F8xmuX zbOfI@lPNrvTN*1kGi-A0#$RZXQc*v&M$#536wT%}XJBG=dFNYts60>k7erIV_k$wp z)B&^!>D9kz&O7@s(43jO#-3%G{atN1ge3NZ=#9_c&XEo6)1#9do%od4nAlZIBr zt+)8XblENHVp$T>g$ZMRz2d^rnEg$Z{KEKm!9Lj`KZZKF%u9;)>ol%Lp}8?Q(P%y8 z#^L`pWhw#<25&Kl*8p<*jC_mnf41Izs*TEL$=;%Svag_U3_^&wWgOI{2JCbSpUp_A zH#-hWb;I_X5M^|BV3WN&FDg7A|>w-$MKd3T%u zR~d*_K%|2iOr5JDKK2L~Y1!u#p*euo6uY4OU{7vCzcF;X_x3X(q)+JQs|h z?IWmgmT}aPDP%sj@zdhflw;-U@Xpi#LZ&t%;Z(9ZL#*!$VB4)!z#R}66 z+0hrW>YhvNx2pumehp)_yg!{UNQh@a>LRN8<@L`z8$-hW_VP6*17nm=uG_3@587&o&nc-)4b)ne~&m13Z z57Jik|F;0Hl5LEFAIS+s0@F$XvW0PKA>|BYEZo1@IEmiCw9TdK?`mGb5x`g=oNVbX zaJW?7m7MN-NP*m3Bwy#n1FwxQoXSSs9q%cxU&Tx=LJro>9TgW@H8n7Wg{3QINDXZ| z#IifrfvxbiI;e|)PeOy-ru@u}K(wiLOqC%xPY+`VqJh5KGu#eiL#M`lcCAsN~8+H+GBfg>53HJXOYkRzEE7XcOL%APAv| z(F2Y3Fjl~c01~&fU-Z~&hN{?WY5fXSK~)pscS*tMuemM2YYhnW4+qSf-{jup=T`<5 zoHNLT^NOJjb8NRXS(th_#s+`W9se>;n=qq%@ckyzWAw8PL1f@l%mw~cbJ#cTm6BUIM4K?-2q4?6#44`cER-9sU|T>>R+4ayZaliNjRzQV z8tsMu!*S42AL$mJJlNqz@>Wu9fXHSrO^g=z+FenbtuDFLw`fRl!btEpIHo!8v#3e# z3T$AM#L1);sPZ47)pAiKOMXi4Va8U;tdRRVrl!Y+ah4K)(roxg68d}kZncHKM&7-B zT|BBmFROu&DzunPXm6CA?!T3U)vxr_8Na-wl`?GbJPCQx&)d5NPApUkmsB_851z-{ zI?~%V5btyV0k_kw)9I&c+JXg;aHNRxicaL*V6zPyM|XmAkHp~!}No#PF`ZXII~ z*CLE&2*m~{%KErGIw^vuUxuie{@Fab-e3;f7G)v-VVQM=gF}^}J5HYsy#_@NWi03u z8o`aAG#mFAunX;cRJv0|ZGlgX`Bs#8{VNt<(7_P2GC-JLf-WA>>1)hlzATJXXShhI2hdU-oXIz0{Ik<6`h-e=SEuBNu`#o?B`I^{I->DK=)qv&ho@ITOl@R2>?PR&T zozb-VifHD0Ey?fz22mS0O31|tO-?_H@`UNphb}1;c9JvA6wA)T{wcA$MNFKFOpwcW zG|hFek^?lF1mMJDIH7c6No*4b_xU!96O@>TF=jHvDz12oyWqS>a&Va}CeKbpv0$}p z5F8#VW(ohFtHk&uR|(9XP&Ll5XAUQ7Li;TQ6NN^RYF9)=y7Yibok1Xc)!^ZYx6QUJ z#F80J%BmQ*BsNs7y-rZzKBg(jRz1!JlOhN0r;8)R-jo|PKQq2YG!uc4NgZ=qZTOyXHx&K-nrZzm@;E8jYvZ3a0DCZJ6b=z-{lP6~{$og;wc$_`1w z25N=ft(?L4g@jL!PL^e6^ZoS|76!1=Ujjr9R%zW)I=_Rm0L}zgVCB8|rA+AyDN+|c z1hQzz?K`Uz(pm_2F>SA3n>mTk0up0izNUU82I!o}wD6tm{R@OS=oN9o4E8%-D~1@I zO>aCD78j}qJGHlObi~<`Az!=h;00>0J~qmk@_lT~3O}4dj*1p8C6|~FA>RD%siDQM zKfpB{Od2JM6@lIrG8EKqw_Pw`1+jLM3q4O9IJ^ki$+bla02flDyq@fMf*6Bmacg@B zv7$ngga_ai=CI28Nm{BgiL+6QKAo9Ld&AtTxiFhZ^8~!@i@j_S#T`C-ShMWISK9qh z%wzkPku`FsP1syEi!&&2u;(X~^8f{BkW!yoMvO&2{yFY7e-8eSW!|y^ z1UYGYIe*f@F=Fgsyv}FMn0bm!ekvu4a!b+paSbYr1^m9DtP|M9Ahh|d`ZR=PA^$1W$~ zJwE`XCb-Yc64t=MAm|{7vs-AYA;uo?0rcb_@0tR9)%&->IR6zmA_d;4CAUpmHYZ2C_cW6k z+lA$d*{@j5iOJJJ@G84eKHw4n{S(kti{pfp#B^Y{ME21{IGly8-P%(X~^n#Zvx^=rAhIf`(A8v=M&0u4f{^QM4^SXT^#; z<}U^q(m6}jQg{^9O-LW^KX=XnE?81ln^^XF+&bWF$Mf~(G482h7EJ1Vd&1w_1Rw~| zqQMt3aFK%vO9S(pB$1W3IG0!E7DP_M<9E81+vg;)%=Wo2jV14r(YQWDDB&J-G@&?N zk4%nX-qHHr1>tQExZ)^V@Tm0|9WG!xc&XQg&yDcRZFi6%?fawG`-!&|cR(C&n8R_; zGYR!b%`{<@2}PU}>Vx}kb+Vz>><4i6SS+PSNDipN@13qR!bKhZif*Ey5ZA6*f>9o1 z6IOMq0QUqZfhyxP-!D$USv3lauF?44=v{{--GG_z<*lq-%kEna!N-MeXciF)8utD8}Y4+bP zAK5Vv{xH0{N#{)7TSI+tuYYq)ENyVzv9V?G=-7bSqmp(_{8?9EloS6q>1U`ereG=| za0030uO3!$Ot?n8BfO<6TP=H>W7?0i$9%uV@d&TYZn^$HLGO}?a>n@N&s>>sz}h+F zX?AQRVqA)?TT|L|QeEa$d(P%)LFSQNc*rq2e%QrqNbG*6ogTdXNOC@Q*vU>pus<;t zV>WlNI{NL#_z1)1EiHf()8FZ@~Yw8c9FNU1@`3+kwCJxL6k}_N z3tv#rJVg@u`C$|&AS2_A+|AtD_&$sy63RS;&wH(x@hU8fBHJi(IXuUJZ&~@xjfl}K z%7^iKbme93j-!7i!)js`tR@>~i!jOTfK{E>X*Jw@y2H3l-AhuRdfU#r^?}1+CE(t-_q>lm4heq+_&Ex3 zlo%&B%|vJ~@eH$TLIXl=IkIelDc_db{ERKfEDdaWC4NOjfzcXN9g^!-vppji-tBeu zD;8+j;n{Yvzg}R(Rg7goR8rvy7&WS0;s-w%-T`i2=vP4^!VFQY7~>cKsc@0mK>rVD zyOYAKHD@v>K_LD0I~93Z6SBJf9h`Wv-s~6+6~8sgl-O1COhJYV_@Nn1C;NNgoMKO4 zQyO5_qa3>8Il>xUlMK$}jE$CRV;0f%DGJ}!9%2A9+JY56<>G9Li2ku(^wx%h`?}q` z^g+hQRBKB<^JQu)9mH*D;5ZbRW-{xj6V_8H26!8{f z(~SRFXyi^9#XD9{dFJ|+6l`Pa>8lTP zyFOv(I**&~c76!ab%AgttPCo5<1gRNP28eIzvf_Qig^Ls=^1sP*$=qS6d_V>(JORr z#vxRrlrTV`c_sc)eY53D_LmH9`BYaRS^Zf!j51`5Nf!90tbyq2k$+1GKva(n-dUHe z((MbQA3SwX5J#ET0+OWO3AWo+_OXoa7)UH1x)l!Ac!xM?Tf5@;NJLDnq`naBmM<24 z%?FxbJ|4uKO)GKb8Sn*e)m!k=e=p62?(HF-h zmI*}tYJb5F;KFGzmKfbKW5MolLpX}jv}DVJeV`Ay^!P~UaJ=JyA7X;HV`Q-V{92>o zLJIaZ{F=|}ek$sztO-6JRn2QWxiUSCr^VS4aS+x90Q`}lgFGHyT+IZ0WvGfN6JJq- ztzU;=QCM$5I+d&ZQ~O>TAaY0%p4%BU*`x;0w0t;Z26Q!!Y|c_OM*KSevJv@_AfpM- zhb}G8qjx^Iyae6x2vH)`C^ipl7C;FzgCkSK^#Bx6=p)TXG&t|LbHP=dBcA;U4I)&N zZT8_Bv#_*T@CScAU+S|{Uou$Bs)b5vL`#9aF(Kh}m6&^?EP-)%d7K{tmfxBZJ*CrU zE#0W=E~m^e5wYz6?by8uxu^;x-9Drmp}Jm+Y6k12M3mWVlN>;m`4oeFd(RO7b%diK zuy4K7SQeo$E2(Uuloltu`h3y}1&wJxJvs`sZtAw7w|>RFxmt2FYIA^&E1H%@erxYt zBq)HM@srN>moRes7$N6xT(IaW>APfvHmhMr(mz?p@VO;FZ%k6MG^`vOVd1Es@S*ZO z9;vDLrdqms@JL}j*<0rNKWTLR+Fs!xBV{{VxbV?VVGZERToa?XNn?m}7o6@A@%ScB zS7A1P1mg8}F=a*T&#ylJ@7&i*4RcBMP1muYMX`!w&ovRn$}yHUDbCmG6Bppy1+g3H zAZ|+oz`ux6lsP)z4tkqYSg;A-LArfXToNR}RbbuJ=fK>#vH2AKI!RtOs?+23BsT31 zw1`9!(jSS-WRl$>O;U5Kg2*5BWT71=H0?aZS3o|%hkgwum_XVzTAZZ`NhsnAOera$ z<3`0CXzlYh$1UM2W+W=g7>PTu)*)%#6PT$aWHI{iF14V8Vl9W?NW7^1;sx4{HL#sP z;XOzgY*)uBe5{jqklOHuX$o@k5}*@K z1fN*KHOGI%(35XR@?(i4qE1(i+OjtPuJ#mxf%id2!#(2P;*O;ib|=hS?VVQQzSIx~fg3VE-{Clh$w12M~9Bmuc=a#chvJ(*& zu*iMjL(Wb4VS29z;ezk;dM*5HhQU0DE{TYg;)OrOybcQ6+beIf0?wAggb+feao!-qgRutSmR1bA_E0Bq=C<`A6&DRjr# z2mw`~x6&7ghS{D!PLS5^3Z2RL2SUBD_Ct*^NnX)5I&fI6mB|huDk=<+lLG{FXFZK* z>)0k~*ged-1)x#}HmST^P5LtdE`nB!H)4GiTwWEmIoIGE&Cw<9x&xEDawbk6{arQIp%KiJOp`LY z7bCcw)(J~_Bq9tP`!oG!itaVxUTH!A+(WvD2CFunH19H~ro0~XtKMbK8^meTV6bPP zNXh@WxZW<2vOeje!>LCgQXK_gx3>Z-kKpY9`}|691Jtswkl_#VR5LGa*AlBM-6new z2>9rkocdDJga+M3;m{XPo|xR$R{UgY7^k$1!ec6q=_Od0B$tx25+}LdKa25~ML)!4 zYVY1uCLn#}$4%8!;gsLf&9Hr(F&-zEjbA9XHtOLJ4&zXQc>bcr z#?8f<;|SV>k5JW_gR5PLBm6L_yjKd?(3J(9#c7tEMXk2^V+(@Qla2O1oa@xU5xgK%PaJs3vennd{1#l0}m&@OaU_JmQg_=HM z@^*{vN810KX8TYKJ@8>OLuKv@LN>LnP7yzJp;33|Q?c2Y(?e~ch4te2B-tqm+b5e> zU|W-x>%Bim1BpIYiU)a~HA9`FuIy@QEhpA0 z6pO)hXGANw54=+B7g!`+UJQIkQBN!jV$UMzg~C|HQKfI=WhQT}@UQd2wc2+@xO8EZ`(urjA~wEHqWVjvBl`cJj{hbGO=noC ze^NYJ(n3;0Ht`W|``1AkBvQ0uJ=#+1=Mm2{L*=4UVI5C~HCnh{-Bl}D#qazS&HkjW z;W~F24u<^qV3Ar8{%M#QTu+d1mi7+Yi|Xm3;ti)TB{4MP@F;*|a8+=)V?8^c^@9t@ zwY15kD&dO<4njjX&o6~L^ljKAA;5y(11N~5^X~qJV2k9B6EOaM@@J(fQp4!_zcwwx zD6=)-tZ(CT`n_e5z+0}r=P!_D|+xxaQQr$|!)4)(;L zO`~l;ACgJ(D3{2uJNFL~ zw(p`rETp!vo6xUL7p~7V_12d9Pe~@rRa9m*`eWlt&gakoQb?#mkgO2Dc5T8<-m$HT2)G#srNG z09?WznEdn#1G)OSaQImOZx3}O=w24N?wpqh+J6?+EVUlDn3!d?_#oscye05u2QsaW zBUkh4we~;T|1k>KQq;R1-Sd60$0A4|t&0%I9w?x>d_FFF*VTlx@IY-c`=S0xLxFyk zcf#xH_67DqTpk_x9$w%1S67~D=%^TG%|Ydg!RE&Z{+@e`@zm4;X&pr%ZMRyL0_({~ z=|xPK3t|oaC~j^6=|LC`cBNsDG5G0;h!Aa};K%>fc; z?eB(md89H(V0pTp0sHA&qf?=$?y?|FJxE#-TWDa-tgb~_oplm?&bai=X)h^NfH>JV zB^d=F2e$U|bSw_SSmk^FbTi0IsawvpvYk{$dwx8oy*bWvi5*0_j4>{Z_#S^3W{6Ud zOrC3a%o=AYj*~B+`uhm(ddvAX=c)b~uG^r0804J!8LAADMWVEZn?YCI5el<1gn%D) zBe^|4XZSl7HM+=Ua^5rC2r=7#C;|9Ig8poFC6b(t{CW8`t|N;1F!$#!GN1ijF>!5s z+~dS?E4f{n7Jh<7!Q(Ol57C56A<=^|&XtLK4mcabHBCusR`AbI@4PxCFAOIHYX@gI zhTQu_=0srYgpdmb+1?rx-K-%^W1_4>38Z^oTwNTnNzny;_1p!WWnr(Jv>r zjfGjd9|TXXW>L^+mT~YPnqX`&$V$f2duq536My#2DpvmZ)v{YVb)o%3L6jZ00+Mm^ z(Pr2~m{jv@^^m2M=A0%qiRL!7cRB(k9lAd->_VShWo}YebrJNn!%LUB4(JBSEhwyu zXQqQC(d59tMC`OWf*)jkEIQ6oVJK^}SpN`U070t8OMJJ&H?qLYIuLfih{y@8fbJEq zc1b_)DEMH12?Rz&MIXMm<~9*axMM9Ywmb~y2z3crbkWhBZKn}x<`SE=M|bIrTjTB6 z?YvD}H+kCcjF$E1sSQ;UqJ~I=ygal;(k>TN`z;oIyj6r5Ow?dcFF1;hi}U|o(Q&Wt z*kx`hioKgL%1-*5s;+p2xTnz;27;uo*2t?J8=VJ?HjATdr9e-_74XUgjUtjvPaWy$ zWJxh}^H?TcTZGP>u~Sy-V%Z~7Kw)<7pf~PdV&!SKlN<8voK1RDXSJFoDZwRn!n}{>2K!fH-iU1}QJ^%)ECU6T5V-Ug zZ>g~j@qtt4e^#JA7tDEk@+M{=xpuULbBE_`p-Q4oD1>@dTX&C(LKFrz9@&`OcHSEj zIxpTv-NoX`T01}YODw3;E?3Sp=>^@(tEx#2DI-bbml(W90<#@vzFaFnbBR~)!o}J} zqG7*nr#uU=->RFoKuc2yR|U+VLBC}7OZI0V=6aTWW~!5ohuOcI{e>H0wrC5D?^A^F zlOu@8h$|z$&zRoB7Qq=L4pIfDJ2BK5Djp0C~OR!J#@(mWGjvoEw*OVK!on^-1(vZL^H zjuvm7MJAH%K=xdQi*`2zp#_D(7c~@ED!If@3xDUCPC6es)$#KJW^@G%K#id&4R%$R ztMdXRmQFw00v~tTyatmUOV1qZjd>efi3VI3oig+3T&dq7ACM9T-p@bXLi1KB!Xd-c zQ)7Pyezi;?@b9lk4@~Xo^r?b)M*zv{elJRdY(o-jsG37bYdD$=Hk)b2V|fy)*DhvV zt?3@X&rwk9iE;MgS6LQf$go9uVawzf{ytrUv_ z?IzdZyc?CMBT^ymtZ}677Xr$VI5!_4+jHhSj?*<`M)fx?i+(p`=36j3pGojKRanGHj46R{kCN?lPwD>+ zo4LeZ0sn$jfq@8f+ew%)SzbpGTLJupRV7xR@J0x-auDUvn>zA~lpE4eB}}IPferkpYXX@*M$_zRnc>)e+K~(KBQi0twCB z)#e~h<0+M{`e_-`h1Wyccuv!-!76)+emA_Z`DO4#?==}j`~jEOw=F?EWK(dC4EQ&8 zk|S8@X9%0YgXlR|LyoVq>}_rzGCP#04s@2Z!^x0z^3`L5fCXDE)w!e}dg~f$vizSw z%TP%syw>`jUHWM&^xd@9VSz*qr9mK=gHY#>xE`v!O8|m9z|$Pnq65`nKmhsw=!iW% zv|^_%$M=-9IxShZwZD)K0X98%u?2vHlHAKFxU14u_amf0R>;IVNf~2E#EKBqcC7P1 z{mGsXFUA1A;ll)hVZ@C7qn5bQQ4!Ha=!}ZmK9bQ#(3E$LpeG1V$&75`k%!=>HWS6J zN$eeU{m4bq1SInSKm`xLU%&2}AKVJBiLESwBxABaRTz>Jbc}y?A!Z4Ua7iFT9}4A6 ziB!-LPy~bfCGYQr4c}Oib(;R{(P9(-0 z$o2({Y2Z6ssTVE@_0yLWh>DgM6%>QKAGIDxR6}%*&6+Dq*XL<`V@S18{9wlZz@hY2 z?PxA7-z9-;@AaFUswI-5{yFWy)<6u^HdWI2Ia@mkWt)hdzkz=8D{CGLg|s&40T?+H zk<(Im*o7#LqqtV{D$`l%C~#xJ8Z_zxG1;t?P6%|m+=Bql19mb*4COpxx_c1DI>4%5 zQDU2nF9XY_ToIv88rUe75Y#hN7AtbghPR%%zvcL|?-294hq$?+uYaQs1c%!qE@I}z z-`q$ZdZl(fuKyI`C$O5uyy5KoYQeZ$G^0MWH(_;`We&W{zI$F7k4d_FqiPq`h=1~* zfvA7xKM}fV(}?i0NoWl4TtZNRcE&DcqDno|woeS%5tfq+PtdO~96hk!tV7Ma(UWYv z0(-zd$QJ6r`(4%)IXA;;=BN(If3HUfMdzm8LkJwPzb5LMFc*goo!WE?RdLO?Gsc@M zZ+oo7odJYDGfG=NeMHZ&7uPwV%6oaXx4~M!+U^C`h9(_!4n*(|2hwI!yN0mnPVf=( zRvkn!9rcbC|7Plb-%cFfkgr*_kIQQts$0rhB2Htl2(r!!zqdXii}>e@+YxkP7QB}uOjocAeb(Tl=m`o zcDlzvk{Y0CI=vE1YGq_5`u@4bG$TjGLU-n*mj2zg37=Be)U7R;37(fujSvdgO+6;m zyR>?RB~HvEA}K7203&x0gYd`zF(nz(hqj%$^VrlEPf4@ zdqU4?EV3kD^z=3e|8TeMtfVd+(M!=vaI9FI$W_nSYHG>IabCqfV6znZv8d8ny!6fa z<1JXrTzk15-R!E7Eb&k@2VC&XPvWGa9ODpPnxu1E8S2>?G4n-x@>9Ee_J#453s!)( zhD6^TN-U5gf`~k@5bD$X>UBkmux?}bVDxRZv)+5Jn-m9V}r zfPlQc?K+Y1kkQ8HFkNMXHwFK0`;S+~2%!e|^dt*uzbmfmrfYq5sz`=#2Q4+0b)zpc z!yYGVYz?`?t!7ro!Qn)P*1SL#I7L)BI&C38!Qc6l4m9n`vBzmoN43&==mOk+r%RSb z0O54?F4F+;KL(*C*t4d|L-}dc7a7>U8p@XVRvTO zdhEW|9$A}PBdwnYFGUz7if6QFqmBsGA*`%#jFLk(df!|M;i|U95%f_X9v_7w0}%Bu z^W0YZ_-r5)3|*JYx|;iCaT}S)zZu2X=4GCM_IG2yFq~{TuJP8faQ;3>KJ6Tf@sFSe zKe{U)-8Cv}vfzJx)sr-b+;z11X#An>!`28NUU4qw{83GVhz#QZ93X{Y`@eYwd_pPd z1I;+Oc|f<(i)g@iIjFW+W(oIARJ3MwgT4w=;lN)!W+XG2vVOr!!1g<0oH6yVPZOHu z!~h~>i<%+pA@GAEt@A%-t-Ee+Xd|*M%$!#PWKGhALE-Ff5JPK9RZSxb#o^3$k!|St zt&O?46lRn4n8C`?yZt#RPWxOSQrVjrnSX<3i}wWW!v-b1GeEoC>3U^i-ldEhLFXoP zu4R-AGcWhult)63EVKB$Ppn_GP-zU~cTQ_NvMUVal-f7Cl5BDx=~s(xx!Z4N%MTWD z>ElTUMpAZ>CN)M)V${7C znp-;OS{3`>h3!Q2MTo|N#8dx0tPA4ir^tFtkr}A7GHPZZh@g!jU!Omv2Auw?T%e=P zo?3l%|ADS|Ht9`81h{xR7gSQJ@UC3GT9q|tEyVzYQw-ivTYQs;pCI&C{`P(mMJV07 zFE)rum-!JQt}uX#T~($<&MSpI#xuj=HkzHoc7q!E&p#Jr0nJ@=z*5YR3=J^KW_?TI z$x<}j3YW^hMmK3k&jX=w6csz=c=9J=nmt1V=epVL%n6CT$M4MKE@RkQ057_Uu!VS)~Q^W)~pp*GILtq)ipee-N%RX&5Oh>uIqwxf2!6S)nIoC+|>qDo>^-N|UenXv_Qf#3=oDV?e>Okf@>+EF4Ir&*i&Mv# zzxwKNs5{+LjHJ`GULT2nWG2nxW6-|^z-B`_DM-uQ>b2txZP}kQ6XfGnd^_i}C^Krk zK_fmTd7EWicw)aA(_yREF2VCJrXnhbtUsNQ>CJ)WbKDoYT$`LH5MSIc7sTC$G0Z2& z*V|fXUiGt~_yJT>D0_X!>bpG8$^1$vnXV@VTKnZ9kW^q)HwEZQ_-HdXfElT+=H zP#p;Nj3HFfIB(;*g#y!s+Te!S95z8wyVkk$a3O`HAr|DcJh}%~+P8FZCzX+gWlF^v zzita~wR!iIe{D_627Fn6uxKz1=uyhVQQK?va*<>d*K6(jPL1x2!Ehtk zOMQ$v56mnikzJAv*2_~f(FpBLf5d=0RR?e^oS;^}>rMi5vL9E*oXpmvn5MiDxc3hP z8q^^1JigqhhWYs+;b$78-&r?*I;dRnD)0~?&b?nH!*yygthJ&tM@+qIh# zV`hcL%Jq+o0?4qrJ9_13$UKIBChZuQY$J_x!L{IX7eu3rn5ar16k7NF1Hgc87c2h`{Ezbw@;ypby)DYV zAp0heuo2Rm4m7e%WF0-adn6WmPK<6<$d3H@EfW>fve$_qg4ipqKOMz@eF_ct#ef8C zKa7*(iaDn-5o)^a&lUe+Yu)~?kO=*w3L(sJ8psTO4eGvP9 zKgOh!aa+W+-*Oz_-Jiwfrt8VdPDG!^mGPG}ND*1NbC)ZhO63Z&y?Dc=2tF4@AhP!V zcBFZ`{@13kWDPV$hyh0dKfQ<01^i9JuJ59H;Q~y?O_3*3WNkJiBc8p`_qDr&gQT4* zSiHnG0k`ZH0cOZC3-RV(yhHqzv<|KjVCf6bs5u-j9i!%t@bjdPZT<;*SWHAbT-x%Q zADcgzY7NevXH_VbmLMIUikKO?7uyc_Ce`|Emy!4Gt~Ru zRi}$$!|j4^-MEft-B-(Vr>%7J{E#_1mI2m#r1I{^>8?eFLTnT$RWqA}NPI8al+5*q z?GXium6rFSmEHx4qIs~7kjZij;hHq%5Q~p6krW%2e580R?!~w7QlcyVg#=73+BRs# zDEf_QMF~#t>JztO3U$_TNQPn-68gq}_s)U5#9ek#=K;4#_Dq)b;8jQBV?^*O8J1{M zBG%ShsCht^v&|gI)0ux^0?AF=L$+z%*`I%m!k`INKV(Fp(nW;;5EUP)O31{g>cE6E z#1ZNK9;3d)+oAvw(>L?2$}6Mc?H!-|iqwZoyUhrsQR44y=|cV};vT>yeO@0ky%f;nw{$~xO2;F3-;qzI)wO*I4S@OlFMVY__eY z<3QKu84LD?&vs>|R>F@29KX%ppfUqaLp3V_SHm!!geEQkg4S!!Dz~cLS3oL*!Ym8g zAvOQxnX9-M8G0Q=30B>Oz(Q@f6rDz(yBV4AGkJqGv+)N(FCBIZ7=!Hlr8nID_ssgZ z8f7_)%ecEW)g7e1{p8fH7977GB(cl%x94lF=`(OSG$o6|J>%>l`7lzWo1DMT))cR{ z-}pR;GQFX8w4!PryOsDRlFkk5$Gp~ zt1Mx$2>UPV?y`K0vy!RF0$I^%rxr&{>(T4ItSXe(%-bW20dA>lDIQOl9&4N<4nMMw zkmmC; z#+O#u65Z)LVoX3gFpQdzRr+?!px6tG9vDwgl*)DH0|tj;dm=qCxyaF?v~$Ssg$}9Q z=u$19;J{JOBoBBSK{NoFI#7+apaR0vq;n_>@c(VtkB8jU&|P$|@x(9FzF@S*WZ-NZ zQMf@g;qCU3-I8Uf#8O)oIo5L8A?6b4t^2Vi7T@sc!a>-+&h)()C&2%qeuDjC#f_M} zb(0+&yi&C$(k#v`bPn>e*yoH}Qw622d%I^aEJ7EwNYgS@w!xELPQNai(`m`VXGm+F zg^?f(+3Si+U!e#ZAl=-&D73YzQzN@8LWN8pW(Um#x=?&w(;X`1J(P}~pHoJ`GvWhw zq?={m5jxy3Cn}hNJo4fNHSKY_?HZrA5rCiqo0km*j(gp$jFM$YEL0bZ#3{->+mN_E zs5cs@Rd0dOt8}D&Vaez%S#YydEBjEFvc#Zk2bhmmo$}+-e7-cX5+y)gugXW{*dNKi z7!6V;J{kiJ-HKeYULq-}ftf=R_KQ-$u(MC) z?fd9%5w|mbc=Exln@C>#lwnuB;UX0ZR<^`EPFqI%detQ>P>X-HW)b6kOu(!Ebj%o2?ir5n!kRU0yk)m}{i-QQdXK6Ju5%qOw6k07EQH zC+M>#lTz9D(u{Xf?%=Srj|3jCM8ZA)!i%E5s_wU$@{?N=Ty-Vz4)k&_B;xMc$GRf7 zeVXQQ4T)j^(6SVdMlWVxq&F$R7-;jIdm!ySOHi6#@Ho4X3#sbsEEy6x9gw@78*23k z)F&@FZ0BK2KT_4%=aHF6r%LD~UEp~aYq*aD8u(D79ZE6b1T#msP6#W+NL8vQ4D3`X z)Z6lS{#MDIVT)Z5lRaoe`A9PM?BY#Ds}Yr0sQ&_*qj~z7va&yF>>4fXLF3&O6jpMo z7`Y?gYK(N0Wn=J+yjEX>H%q~pGR}*sd^82hI>o~DYeRmIwqRb`hvczqCiZm5bnM=B z{8{ej92rZ@;Rn>MNOYJj3YQ)y9GrYTHwDiHEXy!@f5kqe-GL^M``C-5Gz~AT;N?Km zY47p6;Y9*|p61Q5mnkCm0b~`8(-#pY%q5Pxe1D+*$y7U?*7inDu_S0*IHl4&{i2tj z3_3fkwBc^2Z(dC4V?BlKyM%WDK9}?dNDc zhT;~AoC7c}CI%}!VOh5DkVBL0b7rzbG)l+JMfO`dBjH3^M+Ho(x}ZG5T*u^iuoQW| z5DL?LACNxvzAJUjRopQob$Z2@^Ofcpu<`(CUfZ5K1aZ`{L#^uKYk@=(QgS{0Gi@gt z7@aSU&)qx?D2;E~*lI%$V*y6Q{2WU5Pro2X2)}h1mo^Bb$x0H9bUgWkQE$Xq2UoGF z^%+LaC<%OC(9iqJ5p27#)T`o_f?lg!SuawH+^Z1e|B(YC;U6UfvhIABDR1kXAnWQX z(z#@oV4N+@@3C?c>}9Oo=8qc+{o;eu3*`}c6>;*HZBQZb+|KvsoZLl=+*$Ue62SiK z<>6SPo6;{v(dDD7Azmn5c>069iS2!&zZ#>S@ z$_)S^UjXZq+0%r-li)XJ)4@9D8vFe$T^@$jy?{{3Ccf`mO~e3|zp_JEGSktqx7UXn z;Qu^CLOP(9#nN5VD01f0?#cfFO~SuyfEviX>W26=M{fN62c+%&aqR`vAyiPnI;p-i zxYu_nrw3ID{WWkIyo=QNf`P>H;UQY{7xVF|UH5e1P^u4eqtE6t!3i@-6!G;nzY;(=kX^#|xDEUr=-_dZf&*UCY_L$p-T^tbPLX-YD!09WV_r1J_^(A*A zz)-K_EUEda7W&XrO-{~K+*Z}F0FA0ukL5nRDs?9}Sh`alOVL?K&xP9$b^1qI{H@+4 z0aP1J@$GA1;lT@eW-`!t{m_LT21F-M8!0w}USeTS8dZ%uX04mK%S-BkhWjd? z$#R%30EuC=hRyY-9Cf9T2pqne#UsvHz^P7Owc&^}QrygjfqH4va}T*$^q zVg?|hEa#WJbS*&f_NY+Fd~JfVm06=yJYZl9dBk*bOO~rzG|xn z*_M)<`J>8KAL6#MU=yAT?Gzt8}&5{l?4opG=ao$!E0_8O=N8;ZR1g$-N-F2?G2vO@74lsE^~^ z!)QX>b`t^!gEWBO>R8&+_c`gIPsx@kVvTSx-@J#0W8}c4Q;bdq#=Iu$;1e< zE5s&CbRLVr>(_v>@v&_7a10%}<2%75Jk4sqwMS3@vL9R@M!{JroRP$7Yu`sp{Pwqr z<8M(eNrzo5mYCau(STPpb(0IK;D|n$dAE)OfG=&LiNQIMJ&*z!yY$-h|N6?WolkEd zQC|c%^>raI>R?#I$`g6VvJ(q^bg}U%#cSHfN8QZy4aasxmp?TvTLzY=%g+bV#SU!^ z#*zC7QCmaC7CUn$AK&z1VQ2Rq2eawi6}P5FQKU`JW31edDDPn@%2cOZ3i1XOsmAE} zr0&3u=q~LJb1f9Dubjb6=xHa#1h5&3D6ql%y+ufsk< zNGZ&e2d8Ns>X^E6@jJB~$81Kx2ro&*X8j!NY+i&}edIg>e$rB~KXmd@bs5u5#Q)P?%Lhyv{RB&CbB5M*vV};=m7a+eYuC{^#dbmKFJEBvW`>qpUF6$OE zl_l%u{@wO#;~C6hf+aWI`<#p7-Bxw?@nb*Y!?i@@_k>?aF1h*w39wO0R_oX{Y!z>m zs`$cFjR?f@r;Ic+q`q28&qQ`7(2)5RQ^F(p8RdV^wf`TvGUT(UZN`g49xzD(CI41o(3% zKecAdY!_aQvb{2FfNjllXdEMEp5%lz zgEmChv|2}G`p%tG-6XOXFJnh8u;Da7;ItFfJCc%oBef+jr=^q*{y3XL^U?@8MlgpF z-@$b)3x_zeR!&LcMwi#)*yp5Vmo%&C%;rU%h};o*Vq5)`m1t~G_G|j5CHScoF$Xj) zPAGGowsAB!p`Uu=`x4Tv%ICJ%qq=e;-#u>Vi}LR|^SN0RlW6s?2&SA@oZi`{dhqhb zumj&3rI?dyIsVHxufAf(z%WX=&$XJBJM_c}U~z}XA#2o?Jv=YG7HHd@r(pTpkN&$9 z8(O>5*PP2F)B}(?>_KW${7_!hcFdbdo8Q?U|G`RNBj$xCe}fuiMHs2@`A%M+w4@?X zOw$3ARex4)#?(>BcJS(;78g@E@2RYK9k1Ci1wAh(WdHRQab{xZ55x=Tx6=QhReJ$~ zvcApWh%Q4qak9WGLZKW? zG$`s@mVQ)WkR1wa76m%&IuC{UzaXgaYSM~Rv4rw3pZ&ak;b=M9 zngkltxnGoB50Wx$dR%tEE`&h8-Vbtx1ReN=bR57CPkUZdtmWiqhEt3$u};7!Vv6}8 zgF@)8fd$p7=~@TUeyP0vekY;n^V^p``UQkkQp&^7LAAdHu{o7}|74VVzCK`_)v2qU zA%541>Hl`wwJS;k3#UW}FR>`SO%bz3UEI+15gW@f=%-tnBa1(Q%@wHfYa1$*%J?1z z@1a~3&ut?pW)uOZM8C_5Umn<6)tL>bcyVeXtu6%67Gh?YlRP~Fo6}bDo~0B4FhlS- zA=BV51g?{^p;ZfBE?wBFRJ2Q70bObx!o3uNdE)J>3J`0;*Bc5Ll2cLmss z@Z1@!qdzx^#*6PuqJmAVg*_dhV#30Bwcx2aDYrd_0v?r$Y9jX!0DAV6EF|RKfvM4{ z6@SPh(8jpFnd(YqLZXLcF&_Ie-Y{OeE#}Fq_qdbTAj)y*Tb3pMNqvAMZ?`_Yx+-Bw zefYjD-Dp+SX24`th(Ie-Bb zEUqT)$kzLp##41{U3#(7+qdYzxF&onG8N}?C^pn>N55fP{t!mVk3@@u@cqE+CgvU_|T5I{nI)UZSaj?%NFrP*AHYhdW|Y3>I)cs&NInM~OrT zr3pa-A=$To6SyB^fl?`YG^?C)y*{(;cI%#=#pj>2l{dirk=<~nR!j~vPTh7@^9s7U zovO*yEqnGC#9nK%4;Qj zfC>l?72YdoHdE&Znw1X42#~BHh|8N;*vj4E%_gYv?-SVG_Oaw;y$QefO4T+OIj&+A z(~|1~*_5$`K%(4o4K(I368+s_zHVdzP)5q#=L44P6PDD8JsTbw@LD%5S`2~%O+ZX6 z>F~fH`MAJlLBPx{;?++3+mfR3wuHyxmrY@Oz$ulB#n0`V)mVGwlt>LD^FJnnl8YUN zmV-0KG$Lp>5h2RHY^8tJ&I`?(UHY!%y{I^x)+6eUCUoK^Ak&JjzX zvk)q+jlj4XZp)aPK&~rH2RdP5WI4|~)%9cnLvX{iRU#2G*;s(ZL0e{0-ddh*_{E); zALJs}JOfHF`P;!}n}bS@8X>0{k#&FCCHh-U2ac5O_lt~GN@Aqj^=oaLf3JAx$7hZXk1c~UO-`S|?YG}l|D zkKlWpRI3Kxz2(UFiTmnX>V^Eme0=3vIn{WNe|KzRL?{~+9CR9{d^}r_c36n9}a=K9a_R0VSDTgGsk}O=J zZpgB~p3@|4|E29=E7{zF@q-NtTo3Gax#SS8 zTy8`9lWp;o-kg&wAjiETyJXOkr|r+CPb6@=)ll#eKtMv>oBEf4i^DQj6}! z6Rwk3U$sl_HYhG+vQMq3e;Of2aQ-#53mSD_aHW@%0dK z?6FM~+o*SR;oWLj7qeoS=>&=nT6W%v!z3nz{K3?57aAAiI}p&mmZ$R zeU6bty%~M^SL7^#ZcuXc^e@`J``Y*OER7yd*#r;eu5y`o)|t~BF1E4i@a)%8FcHnV zD2@FaF#GLmAX;05g#{RSPr+OuIKro+aor&o*EPJt;(IlPn3gGw9?8EQ&l>YTf>m6Y zfnRev3{0)={i5(6gac~5IJ?4V7?866h2*gdkbkhcIR$$u^v+|Vi7W}wa!-Jh>_Atw zp%hZBdK5FbuFm&!*@`pQsb)x@A0wLWk%^7Txhp_F?7yE3MMLZR90!>@1Te!pv=Bv7 zOhpKc(%{1#1eV!1!@Wn2+YtatRIP$iq^jl9D;5EeOT(P?Y%g{eKU_SOSr25DPx zW5fJGt^rN(=z|xkU*@b>TI=lQRjH;Te3Jn}aYhNfKaw9y0yap9(b)~cP^3I(7pjx9Jth}0KP4>Jj0qn0cRswDUM2DC4i;tpw z6pAKUu#)`4Ll)U&@#Hs!ZjP_6n`HEq`4Sro`69RfqQEhH_fs>ocj*ZctY5YvQLCS* zc_F$$7+Up%o9gI6iX-ZcJfF%f=dto+y;vf7Os9MaoV!9j(fF#D(6FHv7yQr9oU9N> zi8<%iHCOvmhU79pICDr6z0luI zOhijgY~BtZb?j_QEWTM5(ur)!I1G*p8fEZD&K-s-m+NjWPy+^Q1)rU$<>WtL&z;YPhQlWd?)ePK# z!Tx98Gmaw!aE4+4p+@*8y$t*BI;+XKY`^XJZm zas7l!?Ou@?R2$XO3eFK6axA3gs1`PnNDjO=19K{w^&=>2Y_q_8l9vN;FOpKcK8+i=$11&m5yLr> z*UX^v=H7d=W%^oBA2o#8D_fBIZJ;rZf0)(n-^8l?3EvU&^iogMQzVt+5_l$zpfX(a zrqZr#$>v}oMVY27QJH=3u&SW06~ETric>xg%nMs~v?wp9KF<#Y`g8sMjSu@uq_^oY zAEF6;_Y@ZMam6TPfWtVHxey)4#v+k&z&@@`?dG)NowklcT^F59FCd4tkFY84Kqs@5 z+ma(nw2G$19g-?GhKWSBrquH>HivDgV8nS_Op_gqEL(3=M`gG0V2&70lRrd(`k|*L z7sOGRY}mIMWG$h%YI8PKTa{ziUs&XQqILl24`SGiE-~Td)aW-fH(9+i~7BN`sdD%A)=*s&#BR5enAFTQ@&8EB!}sVNVszU0E!_qD|!w>US22eQ+J@{ zO9br%+!MFnT=u3j{EJ9Jm{iD@jm>NR-A<|?{^B5|(jhDGeY)SL1KE{E#6L*RyS%vxwWBfn-^Pk5vRBVCQS?&4}-% z9GO*Jwp{+MRMUm60f)D1sLTjpFPrqn;^>~PG1A!?D42wh;f2x5i`IaUP@3;Xr^589 z3922Hv7>Eu*+C*7WdqxSA(CQ=r0ut4-2CV?&A`Ul5~LGe0Vj1e(3FFGto~)CSaIxz zX(j8fDcyTCSS_=J*wPimmeDJjhhA};o2I$9RE?Z{j)3{0+oIF*Q2Fl!!LW#%N2EM( zhKec!i4!@3TRHzz-(z}r1CV7jb#RLENr}sctJ-ZBo}=DM^ z=;f5TA~>AMPbsUX}M7B^M!HiX;3dQ}4s1?{oBl-ELW$vz%5jA*3xcBSX0G{mEBG}BeP)%;FV5|?< zY101P@<9#SiMtzwO92fRpod2N^FuPakLBf=h)4o*F*YzM{AtG2#!$2yZDBEi)ykC~ zpoSc^y2~`(ApP8&R@&~0(q|eCR4PG(mxUDgaMR@XM+R=p0g1RFX$?~WI#&r?$wNfn zR|g9OI|v~G7QGO~JE>_=LocPwDx;+7qvo>c@=U!%(HlngEbR?Y$BJ=3o*ims;i3C8 zOhqbsiK;g_8S-jSHGtYrpLT$(I7CfktZsefYawmXU&AG3G8{4hx`z<~tw=U>+Y*(; zGUPFU68O2!N%H^>SN8=w1gYu1&HQ&ER*V)Kt!!QFz@WnKfo15uZ<#r`FD=0s9<~Li zW)`;PgS#qQ2oJ$bM*9oI)Xd?u)+^El?IpUBNBVY07S8uH7SbsltbV^HxICU+0e9G|+ zfUh^tCNBvpr`@Al!DHlKWz*w~B6kLn8r38O?waTgz!8QBCrX;q^9%m(M2gUQuOU;$s55ro=6jhhIA5au^DKqm{ZT54e;S%tF?bay5X`i&Fxh9!+ zE^k1QQGg!uzPAy$oKPpULk$!9-w5zfHS9s#&i; zQOyP0#)Eo~c&d~=(!XowgZ%|0SI;r&F2tF~0;_7r56;2?Nf|EO6P8m$^~P-Zqm+WP ztlZQDs3kNI*uaJAE_kW*eYX21ytJ_wy|MlUD#SrE!!}KeIgB?x$%u`Vr^wwPe-*U> zbE{u;ILNviC+W-GkVS~s;bg%Nv09FVr91k1JX66 zq=q#*HrR>claq;^#XM0kqMa@!ctinAn+QA|T#;z@=eh%@uGAs(X zcq^aIG^Km$25c6U{2-+1@=U2&J)PfE`_M{m5VQ^Hi7RlP!+Y2jpDQr2dH6TfbkKd& zGEKv@6GP7ujJBdZO^uOqnhp|G2$A81q35;t%?(RsnnhiPvH&rDVJAp1b*rOcM;b;X z+T&DvJBF^K=p1uH={mTW?rmhJx)2X_!R|G-dfGN~Z>x)(lqUp=W?v^(SA)M7_{mzN z%hnZfdllJ~(~R$eHm5MqWXQ<0;L+{*Muel_E9J|M>U3z)WO9vDWEFRE{q>ylZ4*|5 z70x7t=O*HOO+Z^2ynoRg_J6MY$#3}>*sCEKmbuc-h_Ie7;i-+0gh<8}zH`~fMUIPq z)R5x(v;C)H$*7hM0OLqzBETmae0B&sCrW10A9_hoxhR`kJ0)IZVy^SePMmI>@7I20 zUR1&VrHUVrGnGH(9e(t$$4Vh7Z z{MS5yuf+(yzF{~>BAO8MjWAI87>N`Mk#VSaFALe|w{Q znD^4029NrcwNm!AEEj#VHBvwCdZ^0r)7yqds0A-VTe2ERxm0$Fed?pfo)4mL0YiQ` z++B_rjs0}bC@mDkc~l8j&z+UHGBr00UMkD8uF#tGdB!#nX03N?6CFV5g7%g;w` zvx8APF#y|2VYy)atD>hKy!Y=Eyod|99}?x ztiA#RaW=v0OH5r$-M4v!4$%h=PtT$Jh15{S9{?gUm76jv6w48 zWBOme`O^-Iw0`JO@_7BB^qkVMYLcYbH+s8qmJb3!n_sg`fh(D1t(FqpP%U6U?&_p- zu`pCb9Ax4Dcf!0_l_T4!|50&z5_1$HJAEMz*#gpSB7h<pM`^L+3O&7a+5j)HblBBOnI$6sFFn8AEkYS}3+4-wQt`Vm zx;6RMIAjQDd~~Db(p>3VizX?}-4Z)jX5ik4x)E;6gSy!zkjkN9NOVwOb&iXS5577N zr@ZekoO=`Glj{(LeU&d7NGy@ob@lkEifwo7<&WMErl3_?)iERBi32Va_8 z4yl?KF~5XbZX~@*c=`KV(QTS>z$sYDt?LDaB-0w{GxahRnEp6un5+NmJ6u4+h!tlr z5Z6yf&k>S8CR1=zJlFCxncw2+nrW2s?TI6PgFyT?-tgY$u>{rHl!z&)g<$!nC$(6K zFo$Om9U8WTdMpc>pyrx;WV5#v;=-v9tzofW3T7$EhG@=qruBZZ;P0jBX{U9i%M7@p z!-@d;gLe2D?|Au$`>O6xZvg_HB8oFgmv!nT5eb%r?;M}tj69({EAotMkI53Eu*~Z9 z3pvmVbMbP6sQpDvxiZCu1B}Pekaj^Lo6&sfyTvy@LQi$PPJdFv`r|`_OvzP0grmlo z;@003N~esc{DWA)DOTuQ_mb^Qd$MRE#(|C833Fh>MAg%a=5^=oN3kank3gg#pQJpM z4Ci@Ri#+OS*aqk!OWp{t?~!(mS;&8ulRmY9|JmJq0+wbDd;AADzQ2X^wuBe7p8cA4 zKc-vmG|cWGOZH=Y-+g+l2)SFYpk>%HYpHHR?ck-wz2d#*$CXhD>@8LoP)yN2$^QFE z&76H#48TsPglF7?gy;W~B+h@t+AbUo2${PS&2H3`oMVab|0$XzfLa^5$`>XsoATaj z(t;C8Vz`nmRgoyDurd>5u2qCSGB~{&xe=&vXom@1E6m>4q@(G4a-l2ZEf=An{}cIs zr?>3|+E{lLvihVW=H>^zvmTHTyyfdhEj8{m2z6oe@4seZ8 zQSEjQtyJgH2E7m_l&C$%xAULHFti(>5TI5WQsLJf>}^eL3~DCI_Mn2?%zU zVmHeqgo5JI3-n-%c?)$qE0i$kBLDu?^)9g$QQxG;Mv4ogUj${DA~r^rbK_XvR`j{S0FEvFQCcTZzkU8#0u z-K#h-WpVneFlvi~vGl;YtLVE0&ZW2W2bJ_Pj7AX3yK{Zzwam3#?i~8=7?(sk(Pld4 z;BOX;|FUAS3HW_^dC7g-&_2VxvCmend8Ezh4&WlnoT}e zx4Zm@L%&sN@D5f>lXP@WJymVI`u5TwA zn}3^SEIzBF4vf(E*--o+6RVZyQkp#5j2f_3c)s_OAce=O86ojs_i~BBB#|x!eOOYp z6%U|&xJbxP&@Elw2jiFc$sA}CoG2rb^6H%ZyaXWZiv(w)K6JOPqJ$lNtTS_5F|;Hn zB7=k&9;KVLhA@D>{`g)9>mYm{XgTi$tp!d!9gmpzDCs$BZcQeUeT0s`$r8|P{hhn~ zx)nj0{)2oVQ~Az-pI3?V`5C6Atj=^>uR-8KkB`b;)7lrVmAI>rpY~Ako0QXS-hY4o zv|@Xi2v!d~TtTuD{af_1Ur(Hv@@@H1UWZh)bq*QPw7bZ=qnJhC-~C#2mf2P@WN{ZN z@Q$3F-ueEvRjuxVM}7QH@i}pSV4GSIao``%BZ{!`Q)C=j7jz!Of==HfQ@R^Cdmuw! zFTtszYd(O{nbJ6*!G$sPOe70GPcaujLjI`}W7t2^94WFONyacj1jSc;d7Kk*I3evr56%f8DoNsp4t7=GI zUOv9@lwg(m^7+9{U3$q{Wo%>;xNG8-Y%0nQuI8t4nv14@Xf$cN=;>O%AH^i_7x79h@hA1zvt5rKkUE&;?0840y$H|l z<+~XVP{)(v9M^s8JOv05G;1;`d}oOtGtK4-_1Cad!BGH_gi(tWE#H6nm9&MPMdFf$ z``N^xFQc4NN7bYE6{2-GO-(=*g1U|m2lSr_VJ`z2t&Q3azj@tGttpb=y+sQy zkr1m1;l2g3X;|4IQe&N^5<8p7?#cVeke%ZAi-VzCL&>p&Q_Jx zl#c)w`XT(IqnQ?Gu?WA#SQ`e}t%4r9m4PYTQ48IQA|&(oY0FN?chtmJ@Di6w@RB{9 zQriTJIs7!!jIq|Ow*~nNc-Md2UYf+{$>P$&@Ap_cr_9S<_Tr0zQK!yXhzhwn0YSUWB%v2VS#7tb%*)EIp zVl}`GJfp=^V53S z9^CVDgybclq)L|atZZ9euSXlr#0a>kxteaFLaX47PutsMbENJI0pF+G)O|5@1*9 zH=f>m4Y>Fmp>f|7^pWDYDk{%xA%N%8W}nmB@eHMK=*47);KND(Jsv_sZ*;WFlSbkd`;W5tLymZjE+sUkykpQVS zYmOj^?60aKnE5MF_ig}m@f;Ht07sPVC$4&`zz#Rvn!d#yl#=J2HthWTiCL1}Rc_MD z=%8W)cSe-w%9!aXfJuN?F=geoM6&tg;WrWie<@*!fevIbxy8< z3C%7Y4zz8K38SjD^-~cKxV-cb9{p^JQA)sip|2hQ{V@&OfEUd`@pM3pw?>M}#K#7c z#SnaD%!=*0&gsYC?nk>(cqM^_*Wb=loR596Dwk#})=kRquB9k|RXzpbtBs_~CTWqK za3Bey>8K|`eLtvR=Id-QQmE*g6jQG3Gc>f2CK^4&Pen|RtisBS8;)vn_*M2v9Uycr zDndX&v_{+uFhS5(L#)xp6}5($9o?;)C1p`$i%52+ep`UT@1FU8qwm-b&}_|?rgJ<_ zP81vB2wDd4vdT=%4&3$js6SY z@^Y%X87YX8U$5LQ`X!=fzk~|`+HhIy;WESOT7}}R0&1OhE5qWKq%z`GQ%-8CUF}-+ zf?&99xj>!}jt>BZ_y~-0}TSHHEj7E|7Bd?}ECh4(iKFoS8Ucqy>2f0R zC(iz>;}=bI@*z{s-xHO*+WO~6#qc{bjGNc-Sz06qkeZ0dDN{>f&y!|{w;uu09-|wASEK3>pfX5 zR`G@4x(w(L5g}p%eCqW#=Q3&PJ0>8ZWeiY z#0+Kod@MyHhozVp7K3|WLA_gqO7n!%f1PD zlOCmH`@hxZG$;`@7^CKeV<=+|-21?-&M(u;6AdB@bkm;OfzB|Vn*J|KW)y46!BfRv z;yO@kI6dz@ja2R1xD_gyu6hjmsgabAu(zEAHFFNgdowqjBUN)|RB19nEfvX=! z7}%$%-fQinNmMjH@K{M`U-;F;*N%yxJ(Om8^2EY_Vnh;GL2Wdv$NVrVq60Vjm55W7! z6F(&~vkcva&lKz<$tVM)TV9YE(MXEzo?^-LBe2ma~I zh$pTlbIVr6*ezF+sOE+C-V10vNfg`h`PK`~6(S$HxIh(FOH))zN&2r@H*h}~31Mn5 zkVt5@JU*?wc$c6_dq%Ilaa55d&%y={gHx>F*#3Za=IPBE(lkgArChqCRP#3u1ZeZ+ z)n^(j((p8Q24vgzJ@mBA&uHQUfm5*U_Z%ILB*iEr(F^?Q%QpAoIt1M60%RgHO8 zhZrB0XnV(K$Cf|5Eg1DUN3?TL?b}YeBlfRV41x+ZlEXdVFQ`&@fix1U2gZeGZ&>4q z2WT^bd#fNb#cPuRPH38T$dD)rvzLKPfMJq}jkAK<&nX3yAf=*q;V=3D)W+ZO(X5Z2 zZfR^Zx%7a{qpQ!RS-FpzkHq`a58~8F6>35i+3U}I+l;~bgfhL_EK5U>aLcUos+yOp zKkC+_=Q+|E(r}6%WNE`|I3HXxh={G_pvFL$#cC@I0VD+@a;=7QQ@UOAheh;DgnfMahmNsAeJEgK`&~H8u9vtitmI%HNtL4eKnfir3I!~jgvw^CcZpBJ2BzE zllxUzfPO1q^pl%_5toWrg*@jpWOYGM#`xX*^wEDSRLQKz>8?NHtsQVU2lC9=P_eS| zII|yMn@ot2^Sl2+5Z9aO@!OYWF-+=Q&G+-d3GoXbq!w8V@Hdo!QBppJT)Dn4Ipx1(bj>iMVj zj5I*Y;)-$yFmh57&u6;~u+s~}+0L7pZOd)+UGC^Fpf*3q3%v=~CCh0pK_Z>q7(;V& zK4{pFaNvM|aS52S5f?EA>7=WU?tc*_Z!=zMG6tV#L#* zbe++SW)dgJh}PfDd=;o!GI?EL#rqt=sYJpx^Wj)d*C1e2Wc^5wC^j3cdf!XkIC6pS z%sbNZR}jKoLGsxFa3R-|wZPPS4gPO{;@*@OD;$W4{Y=Xv7l>l5Sl4g0Npi%*= z?^2#S&S!nli@tWM{DNfXo905mR*GChLBe9Vha2S~Nv_qc+VAZ?l8&?mm|oY__xg&K zOr=o`AO^KPGjk3MECo-AH9c0RQC|HV!v5CaKjOg`S^XgqHXMO@-s5w!aq4#ms zcUASlLOS*^uK}EM0>cDwx{7RT;Qng_Ar&U@t=fZpB1@2SKokZ=#w;c1G{hLz3i__O*fW}_X zJ5fkS_n=&_H9^B@+F9&sI#yn(JecE#LpPo3hAbjPQBG;GM2t<8Ls@aKx}Nv}!bLCs zu1V10>qFR3c&q6%MSI%!ZM9W$wA!mIB0}FMe9Tn7N1DO$A?!8li`Mdm5^QTl>(IT6@| zr1?J9!}#Ai-EXU`>{_M+y*imwmsrDmo78E3>?zdG)0x%j9Run{g9XY8gKJ2Tp?U(S^V}<9IV9+sS$?{ z*T9HTI$)*OdGU9hngt!OB2@MPFuZfGZ5Ci!xvitXfIu@J_9N$46Q2Lu%`ZuCH*Q-O zfC8f2P7(L@pWwN_%ihl0GB{?p8%Lb7glB1ZObL7K}~PjfMhJ^C<)T+pmo?!6@@iO`XiCi_z+a* z2j%D{v-WqeUL`OL+UR49#VPdrwWb+QexJY`VkQSoGe+?j!nSY1npP3UnOgv(cn1FT zL~LfE=VrgE_ew)8I^xK-GE4@)mlfq!I+9Z<|4g4pOh13?wjdlSf^x$2q!kCGeKSEE znxJKP&q5H|k-d<3E}aXlhu1_lFZNh@UkuglTpV54_A}gt6<$qtGoi!&hlU`;Wm!^& zZXpzLul4to442!^%yrdf(^P0w-B8)es=avhk8NyRec%n$g8zZU)&pf(F7bCl%^}As znZ-tCR`s0yAJ(qe3Yms^2aBH60s`nLyhC?@1TPcylslDHRJ{!_L{7{GYN{43~BRSg*9B`oq zXIzxHyF%4H&Z|{ss*%pSh5DX6`D92hN?~N2$;$sxbxDPQ>^Jm^GurnoeNe%xh-sOA zkTD`jGgn+pV~l7$;$=`V%ecVgh)@aH+^q>mS8|LaEmIX1lC}x`)~@5)`W{*7T9h4& zShTjkHhBxz&pQ3`z~=p#nWb>!j84;kVxKq>IUm_@tXPpW?RM)akXI-)3*k4g?nhKJ z`lT6V?+bsA;u#AI&;XR%RLJn1b09ZpdT&4H{t>Anp|Q^JscRfqN20;k zcd9+?Y*Mz`|03ybfIuw7E&ydlaS^KI<4>%ybeiWqdKxPjt(fQZ;c%VgL#_}MflAz# zOue+n(m6MII-uN{qVKh&du0&?%p!&B%5C4kk0t&^7kf|EBgK;hjcXb_R8!2+P)0P^ zO#!biDO0d&`(}xp^Y&%Ph=TPpl~@k?O|7^?j7Ug*^?pN#2vWKpp`DxiqB~@!Ar~WX z;B;&^Es^F8Z7GD=w|+X@S;;ECSBru(bOfCq5;&f z#@f)0J)I76FC7AWpwcn-p4zkU{IG?p9Ij%2A_%s>8iz&LLx><(Ly^=*YW2!}>ET$W z;mOxy|B&4M1MT9}TiDVt__(BVsXD^>>AuQfFr75a^GRxB=wzP z*nt(n-=j-~W?a9sNf^g7d{&M36=w+E7+hoJ-UCFvVFvQp7zuln2)#>%Ag&w}X8=J! ziVd7_uZ$XZ(RZ}`#It@Bad0s7vu8x|R9naGH$rMX9VmVZDr~T5uD`C*2a%w4D)Q6O z1}9O$dlIrq_)~Jq96$_`-wCPQ{(L94J?ACIxl$8FJD9fuMpBRev(d^4g5-E3eb%+E#*rHY8@vX#R8sR$F zK`t?PM6MjGMn7w-e;x)^>7KN|8dtzp zq~cJK2$%1FQx$NkX~@p(fY3Z`k7KT>E`0#NB(yG^yd%w&<-cIlu>SqCi`7dsr=&{( zCwrOt9j7iMJNp(yEK2_~8DY)k`90d&TtQP2zKH&%9dJSU=X&t4@v zOF0tf@)-OVy4wA!ucgj6dXR87yvmu;m#HNVmnB7d{>hNl9}^gkA*%_Tuun3h;<6)7 zOg|s6SGUrP7+bX8cy0>JyMXy&v6K=%$9YS9t1Ept`H#bf5H_H3!j|4)${eGF6v&$&Pv}2dnRA}`9@`Gn z9QdzFMPE*&K(LWgPdD|lwxf^O2r9;|DyT3COrTxfXXyPrd|!DTrt{)ckH+r|8daT5 zY+4|Tl&S0yU#30e&sdXE%51c)O=wDD$4q`HG;g<4&}<}D*UqquX$Miwx80{PMh}=q z#!`bz0IE4PP>Otip!GjT!)4|vKo}Q6OH~|O=W3&jZmTSU1hz18I|ead9o*(j4MCP} zB_^;ncK2i3z2VK1Rp*L_&7$jr1B_#6Nx!t8)Uu8Zq3Z`Rx5%SyD)QTCFYV#3#dWy1 z%dz6iT3e1=2$FX!jEH+76&c%$I~MLsP5fT%C(}?9<}6=;L|B>$G(CyonCdDpn+rc_ z+eraV3)GR&R>L zh>XV6sp-otYE-Ab_18AVF3mT(J#Xx<MuU^Z~)GwV^~v* z=C7TE28ZH`s>dMo8)OXO=Q=M?7;|{Yv)Y_zZ{66LEk2j9vUbC}lphUVaNAt=Q1aPO zpSc_fxK|E6RivX6E(-&`lmU9P(r+Wd+XI?uMOm~`Gn8jWDz&@qdVRa|EIFV?7)WA`3+`8yScuR|-vP-5 zpp!`@fvTjLA;H$Q%|D2TLNcej`|8Gjq29R8$iC1Sx1NoiYr7m*);&UH0{|O*m{3;J z+Y=V??GOjoUFo)gs-SX7H-g$qNb1|Nu`sC-kv!{bNVs3F4ts#*v*(Fr?E-m{9z`qz!Uc4#; zcR&ayj-xNQqpPFT_-)yU%6-R$jJ1T}0#a~KOS$SE8Vzt5IbK%DZOJB@JVP}Si1Mp% z<%M^v(kg@2pXMu;+8Y^8Us=fH-a01d*JyUW_Xtg{^AW%Ke@w(u^G^h_0BwDOGy%nhe3nw~Ijz!Spxq`yl-^utF#b>AU`CXuqj(Vni*DndtjLqJuNs1hy;Ukf zF#m7$)T;BPV)7b)^goT2yHxr!VM|GU#Xu_amp>kTxRet&x~%tiP$I!^PQm)>2LZz< zvnEQJqFV~Vo@o_&J> z!N2s58rHRD*br$q9GFUjM08$6rYi`%5ZuHcnD7I7>sTUuuO>$%IU2`f`LXA_P&wlynV)ECad6QZBx;v+NwMPLP~q z$4iHzSc_r{aMm_;=OE>6m=w7}lN@ee%00dvaT!4kb`oD8F&FUKYpG-jv7Oq45L@t~ zz*cyGstS*!<%8$ofRCaJ>bQ!NhBVfu$P>~>Cz<}Ck~M^7XaV!T?M)xz<<4s<@=JZK z${bVym~1m6be`H9p|trOm_L{&f#<$GwaKfwpa=6?w-gIv+K5ZVs@I{oa~T$)CsG^7}yb_*}wd!^(eLfx0n{1_*uvl_4@0 zTDihY*7-Uhx(nq6-bG7n>kF_|6OH7f{ZWqmW;n>w<0X9{7q)LYTAi?al#aby-j+~+IESuUm}VY)*^u>M<=7&adq5gHi*yQj}H)3M^X-nKmP+t0x6{Up455;-38y@a!9Iv9&ZHg*A^u_lyOD@nAV z4d2c_d}pt2X^jg&IjS2y2>POP;FbzwC;Iu^@vOkMDK8OKbM}U*Utd0M2AqHZ0ukGV&kqp&X1WerNIhuRVr-P2O3C)I{^8tB%<@zzZzT+p@uZ{+ha^ zEW#S-yR<)oCFZ8;v9A%&C5h?aElcb`Q{A=sEA2PId_`<=@^!pO)+bZsY^BE2Ia($H zpqaXhpZL}|g0`-O3y6QO+t7be(5nqt>1{D5$w-m({!jLp

    Wnocyov5}cGp1(~65 zHm>LS+qIo;nsex@be3dN-GHP?V{W*`vq?lNV|al#FFwECp=f;srQvUQ_~p(w5L3@L z-T5jgg`Nd*`8?Q2(1=Z4{2^0rMN!olzeGHU#9_!{_EnzW$`Z!+Ibpx2i3DF1&nZi^BEhN!hq5L#REz?K3Hfx z%;#%h&TMPb)|)@d48`Un!ZY~g3+D6)k7)>G{LZoNy8H1E!?tT+=&eI&t{y*lXc`KR zA9<&XYc=6?!4rcKHzr2;Yc19ev$c)k1TF=_x2AGP!7|JLoy51?D|dVt!%##wfbxiQKgH=P7rqr?^GEc-F-9zS=^g>>G!-BjI%{tNXUvM^H~on@0ts zNhmy_ulnlqx6bZwLvy~~6t{}@^_7GR+bPH#fUoP-x=6tIb<(%#r+3-)368+Up-{ap zs&S$)mrb5CKUP1wj3sq)f|2pJ8aR$2Dp6E@)p1_tHSXBpOeT`mzQ~#~hBZ%X`H_a^ zs*d60Y}1Q@swjrFD%ZGuR0T?OT#zv?l_2HX5t9SeQnuAr1J6bMww^_mgG5j zZBfE_wGdPOE^V75!6I}DvJ)PX32P87C-cAvzhk7G$qo5F4Qym;MiQR@pE9>$IwYUH zvzR|O=!9_z*6IZo7UfFxp#hojwl|*jTf`xt+PWq0v2Jjh)po_@T!ul)rm@`B6rJlW z&s=KF?)o zNDAv@^uv&fYi|PRCQh)Jq#h~R;EgaZIXYU@0)=D~uZJg%DqMa8b4ZIq5G!P(s?N-K za?m9)R3**jd*1^*@v$hozY5|k4?=c8yo?Lu8I-*r2zn8m2lWsff0-}Ro@+_RK2Fu| z>-RfCY7Pq$3xRGMHpsQ7U>@**St(DkZv1dxBiLT!S33*#b&HJ5g9ye{MI1>G)725&Ztc>6F0EK zEW_so*rE9}8%w5COIeWI{SAcREb!;Tk?7V&j?1L2SSKFjj?DcV>?|~8*R5R7*NAw_?rk9O^~!&w$RKn+mmUq@F5N99;He_p&bCkZp-Hub1^Y)^}?T zN)8Re=Nd>-VWO|4wk3JXVcG!T*tY#XK8NE49=4MwJVFxM>cPF|j0z>jgVhfpz2tT0zuz>~oOt1R#kkBi`#s)6h(5IKx!(V6s2cB7Soa>}*@#(2m6iW)^|!%( zDkhVy+$(V5e1T>n%m+eK=5(VopM?>aMP*@3^2}uiU6z$GT>tczb18n)JVXEJX z@=N-lMuPN#I((d3ieLn_bj%YRGy>$?x5_;H8WF9giP9cljr6rH>)>bN&S6pKQ|a-D zR-?DGscZgm8P@5p(ZGw&aSmE}P?N4lsRjN9$;cLW%_ z#_)Kg^fc2ceiq_X!J{2c8|+WcT7Dx$_os;>T^3|&HK40hl3yi)|Xt_O+ zv)Vy~pZ14k6{`WMf0~0=5q`rHM400xX+A!Ep-oOqB>2rYpeL}Hv@}RO80sPczXLmJ zT91+g0aFPcWIk6>%ry|?CI12Ce~`_-!mmfKb3!v*tU11I5%50Wl+RyrINfxGJ_HPV z@yB;Dc?!ASmYIQRZ;Bd3`BJAt2F*R;r|OA4(|n85(8HPHt~nBDhA4=J&qG9&B@V$q zv8~9tB8ShF0Jq(DVlQ5*`8@AG1}Q)%z_;EB@w-$Q$V;?9bM6H6`AIfRxKts*?v2^M ze>x6f3ri>6t=G{P{<#xU&VV_J))w{}8d9t(mb8fgPAJE{I_iG#mwJ5pg^TygEMDZ4J`n6t{%<9DV}Hz+MTOt^h1uw z?z-0ooV}qv-!6ihjM0rBH7dBV9!Du{8g0wh0a;h0sP$~A?zQx-Sq&5kfC|BnV6H)t zFMf_RMw}rzDBWcK#vFoBe|TXp^8ZM4ib?KFd_zi_7vFI=Gfi*(#gV9Crf2X@JIqC4 zE+rR%Y^HuB9`Q@z?EK?ulKGPcF^WR2W!Lf-nfShklGjdMa4;r>{E-TfRk_7@+)sp8 ze-iGmo1D8^udAgaQix&M%1sR*DwnF1e%$G~!c zbU}z@$6X{ETOOF^HTy~CJ5qJY3VuNFxM1@=jdFHjfx>;{i~D*V!9k-5D(R#-uoUCt zF(P2(bJQa*DLfK`|I^Ys_>`g2Hg%8mRVvzFh;CM_McN_&VYdBd=@6)(!i)2aQ5C+g zoi#f>yL~c?(57D@0k08=L8tmTDqUuMrrZavG$C&xUuNzXlQcFwzvAG2BXj2ui+zvf z#luZ)Vl341WCBuTso$j}p05K_IH9-Lb0hz4oNyDz4Mlgpl{*^b@x#|y?Kdl@lEA?F zU|Wi^5HY{N$$+${1zOaoDq8k_8KI`Juw#a5T_e1mLsD~l;h+VS^XwJjauH6#N@9N{ z`56w*241GskeH6t(CN|Y(t-4hP3I}XhVwbJqnEm`l3_YypZe>q?O%<0kkj2 zaAoPHk16E`Z641c_e6#IKoN#GO{zLDRnN?dfm_;h4~iMVq5PM4ktbtt%yq^T_vYKh zA3FOqd#B}5xmgGkPc25fZ3 z0!SDQt)z&OopSB4A0PotK+c>uGE-i$5?@`f0H@d4i4yWRGaHCD>tSZ4$Iz?rEpS}+;zDE-Vnl?pb)X9Dzlgj)7QjM1qe-CGOx6>yg6wDsCgs&1 zv6SHb+|sRY*#tHM@BPEl5Og+K3k{XQovZ1-|8?||-y8ctzw-5RF}=OjArA@Mz@(qe zCL}F}oQO-CaC%AYKxl1weL^D3M~lTR4}=uMH~dZGMuP&!o3hk|xo$+vP_&X32O2Rf&Se3L*eDpr(cKQO$-F&mpO&EI z53y5p+F3FZmOlC|88%AvUr^ID1DheDue%EcJF@%ik_XV4B+QD?k^GPUE|)+M?{2lF$KAg2oG)a_>d=DWubG$ z{_87DBn@_5{`;nUK$ofZpJ-NjmomO?8NFF?fs$QiZ4Dx`O><0(_-{z5vO+u+1qI0c zR5bzM`g9gO@V-oh9sQcX_arv{|Ko*Y^y!Q$3M$mAt3$n zC;b2ZQf=iFd)e%!nm|X}q|%rJ6Nu_c)FXHo3?jV?1!?GT;8f9wD~b%*duajh>jKD{K#s!3{u33zX>_5ZE4FTnEM zW*>MFcOC;&SEwEIB5ItrJ>WcAT$a zr4BR4E3uJ2l?hR?IwSEt;hp?XvB*(Sdp10s0EAOJ#QgzK`dT3I*WNa6=##eAJJ7`r0|n#YQ0%n&T;TzDi=Pln;&H z3ihdBFJ6065GDldgfA@hOYML)qfovZp}%Ea7+$-$)V}yn{1*w24pNq#QoRA(cHcvN z*bVQNOnth;FkB`S0kl4y182?t64Gf%51MN)dwl;qpz-msr4|jxKJL{*YHb}eY|2|Y z=r>YeuuF3RIU})*^BqnOgp&h|^EKuo@>wNN-Z)IMR_PlvEh&BQ_?F^ay3tapBT&$@ zT{Ri;_icv(kSycWJ4;3QlQs6v>uFfg-MJ-aFtZw@q(i>#Eh1`_{T$x;Yd!@$;ifEA zfa^qJ0ssy39E<-$;-%Fn)Bpx;2a4aG0W`2)7Bm6DL1&Tx(5`sZ~WsGRea$c_<5Eo zUpHv0%go3&uVbk=i}G5x)1P|<<`q-%^d3DQBP~Ln5`jrp>pFj7+|a5+eN}$a?^=O5 z`6ZFbI}*dkTI?$|ZtqTo0VeYDu_x4E5sw)qN3)0@&LC}wG#mi*h#ePePlaaL{im_a zleeI9qx5(uMa|)atQH>-pgkBDNK5S>Q^NK3blo}C0#RF)r7Kj{$_(f%Q*+|1^w@{d zBMY+a!*8L~OJ{Pj;|+hlsqz=byYZBck}`DfdF!Ke*EoVrwLPqG{z#|S3|4`)jtWn` z)$M;_kJWJUqX91PfK7S+4e}GeD+*I?ZlkjQReHblUiITMbNQ|zjd)DH*wz8R)y~7V z2Tp>QXi0tH?pCy21EP|r?X4GD1;)D2_|U_951E84*`lme#!$eCy?T)K$e#mg3$$BU z!BFFBlnmQjDYu>P2H#}NTdhVVPWmqn^_P?7rtNup8l5(0w`h9DuOt*N8+0lVKCbFr zS&{X>0^=4fyKk8{by3)2l2NDJ0N&UBxeF(Mdt0?#nuJ9j+)@IZ@zo%XHaqAuBQw%7 z$eFqI<%qzKhpD6`JB85|z88z8vN3+&q+5m|&y>q~S^J$Vg<(p-P8c&z%MMXP7|B%IOCxWIVl=Wp<(qFT!pa}q+1fx4cKliW ziEwG!vZ$t=8c^Bay$Zbd+W=9sZubT<&623CIvo}C{aIn|J#z8X`$n+K7`@gI@EByD z+n#t+oJd6ajjYST)3(>&r_G&$=;&RG{_aaq4ddpn?lF=bX&In*5Gt+RZ@GHjSHd|N z+2b*}sm8VfR@ufl1}Kuv&N~44*#CvC9yf zTtU=$7hIpok6Q$R86mXIKa#Oq?fAA+?FN?d!$=X^Q!1P$W*!!0N}Mx0Ib*99fVazd z(t9#y5?D73+~VF*fO75o4?QRDp_9V@kvgkXyN91|QJ5`I~gh!+Q z0gwaR9NH42pA=eO61+~@ib9B1c(@)f9fgJI;1Y^LEukjm(CQPW8Rbwug68ySVlwm8 zSv;ZK;Q!)rZ90Mtf8s*>RU}+Z{^z1CLn=KI63dW(1$yGiATe~r_xYJLfkmOkz%Q$j zyNWFea9AxS;T{X!`~XEPeX@ATNt=v-48z)`8#0&R;*d;?*p@vbJ}7o>gmP3N*26iZ zEBaziMJ)JUp5ZkQeC2PZ!$Q5uZkIxNRYDL2BJ5X6)g#skoZK@BXpGyax>XB6JkGn@ z_E&iYM?4Rk0+v~-Z8Xx6U(KEZGv*g?^U}JBL<6NABIh*Til&e5v741%OTQe z`VYKqyItet7EC45H!i-`NVbw&`A(2g>rl*{iWj@evR~U)XzH$$mNJzro*j9BKd z@)qV1lrO}qzWPl8bk&EwLHQJ&N`(dE2vw9nnpoF2idb!ALirGM_~XGbn&}N*-jL0# z5)MNt)`-8?6P54$T_rt-2I5#0_vQd5QJ zsBe360`3hz?9R|8;v|Yof5FYW5aS58RqoT@2Tx0gkA<_H(#>bsik$Jwqvnvzsf$8* z{rJR(aNgYC+DE3MzkXQ{`U;X4;=v5JX|V5n8nk(J3Tx7LY5|9bie`G1p2k97CvmU+ z4QDq%nhJ*d6u+2h8!Et=y`Jm#KSd?kr_2V4>^kSfWikardO*wHnGoSfZ$}*^Ev$Dz zc-Aq6ZS8J|#SQV^y#mSKk=E`>m&;4VHhQZsANNOhQmwa$5z935NBal@FN9vG2ZNr2H{VJ1uHQroPEY2?6A* z%Z_T|g-x||ro@n<%&kEJG{!p+_2w4DJIhf8&kUeIHOH$c>kMnvr@LIg@kdPgBxUG_PpJR{~9S&*CVLP*$Y4fWW$P z%eon}nBKzi3bVlt*wgkkSfX2$iGsrcsu9r)(c2Z4xhVI?X~s@Nv$~n}t;q1(Oa6F> zS2jjj)Qf4XIbOi-bmU8bs?2(>7Ha0E2cn|3p>sKWIM3R$O zZXKi^I(VUo{5r40VO)h6d#`P9$tnRLQ2mVr3)r6W)xz&!CpEQ&5AI|deAui%5$Dxf z&VNp?Da)Wu;1~)fDmRG>E&<{k&QiWNdhmwu{i!Cdh5zRPvxD?1?vFs&xh@$X3>7q^ zQti3bNIpAbn#t;`ZEyK#VAR3;&CTB6Nw&2Q>j>?;V_cqsY=ECPn5lQCW%?@{IG4us zah!iY=!nY2SbkvXxb2pNMOsYzFC)q86aUGYX!M|Ez$%Yu965CwSAZR|QZ)beeoW}I zkj279f6%Rt?$pE}`nHJ5Tp(nZ>!D7K0B~BTiRav_Cpr8@Ry|_ee z&PuW>M-*&B(stz0MS4oT@VqL(tarqs0xm{%7t-mvoitFa$R59HMdcu+(hNQRq;lNi zm>A?wLaOoId%~rqZs`p&9-V@UC&yC{7&}~j4)qc=WMdm#9er;m$cyC5;P9JAPtB>1 zCtJt30)Dw>U?wZ7-rE&QuvBFV*hev@{%%Ka^_dyHa1N1BuniI-f6}rdzixzZb1M7&2*#O-iryL%uvpNT#Qi0Kf_3o( zHJp=LcQ>vK{Aun3FAAZnGqMC8fVta`7GZ0!N1SPx`uQ0DSTX}@4?S!Dqs2e7B;(2K zbH&J5D-$a=o^&N~CGzH}$dCrq8xPv+LcykD=}<>gu!)3h!BXZrOQCB+_@Vrf@q8ab z?l9RUxyNkFu>Rb8Jphz0O(Q{ZVWirW`%_3?nto{gdfe!so%wa1vDY}Wai<7m!uMju z8kaV8gqGYC+h(NyEwS%$9sq&feqwQQWiI{m%)cts_hDvKqbm`rU(vHJA8e+|o6EoCKqSefhPoqiWSKG3P*J42~SYM2?9H~2|#8pf5z!|1HRJxbUmZrOla^(kH|cyinW*o8&U2Hp#F!7tkB>$rxWSTck~1s#O#XF(&nS;7>VC6! z<7eX=N5h%Y9^#k+x4T*dKGg7WzwR(~vlyjB=hz@pvwSC)iKWI26az7tLMuH&pz-hR zhn4ze^wPXqg?>dVzS_EIuxp;*X^m`tFb(#IK7;UF@VHPV;B;TKK;;E>L)R)n=j2n zY%bc=(*`h?eBUS=`XNq7yl|HsuaKey><=RUI8Tt0J^x@kz-tvcr^otAQr>7`3eSxI zl^e=*z<5(4+0h6qgx7qd=jH{ zI@Y^fll>;^sp<6UncsIJL*)VzNW4}ZyiatAio2ars7k(B!>B}b5Gyb4p0ycW4;dGb z=-v58N<4^y*zb197HyCAB>V9Q@Hp)=>LeOkUZ#G{?)>z2TQAV<&#bReP19PZ}Uns-K_Kq1D z^jjyh=+xaR2XwYm>(bwM0-^U)xxOL57@lyaH++6OY+4EErCA*Vv-&i&bXC?k3|;Oq zPDM)vcUf=1sw8UI!=#H_1$IN->{2(ZkL3vV>x*szp0v396Y+uo-PE3jlCu+tCB?K` zSIhqoqXnn}N6ykjl*OY}2L>cY>r|v^Q9O5AX-EqK`3Ijs;ng4!@~N!2fJA}LsVd{E zcvhSKZBQu9B7V_Nh;g$v_x!>k-*%rjb5?{OKg%lz=ED$|hhL&2CSvrC26V6J7Z4+9 z>48CeeV4H4N`Km6i1e`xvTyb26^Tp|A#YfRe(aGh)-z!aVXg?fI8`CJN+rPDRGS31 zGavRG&8d}vYir9{+^+p7g%@LT$qq{KhB!aZ+aseC;`VSbLm?8aSM8XXS~Rm>5fm3ffx;@Gu<| z38~3nAh%sde8zdOC$cecH>Z32r98&a?H^o|T6pNM>lZPC`|GCDg(W&+diPNymfpP@ zlV?@&bK%b}%hoCw&%5x@T~lOC+)k%)+>gt%O)Ptwdg;-3CO~TWgwEDj&V|jIXWOb7 zM7R`K2%4)_J0$08EV^HiXw|Fz4xtRjisQb=p9=$tMW)ORc!6BwSep&QgBC?`|XUiA`Qk zO(WIsd^3~2f$V7>ht>K`NSF#Tx`2(R&eg!8ZgkW)S$?i2VhGpN7oVPPdHurD=r<^I z{Oh*A9CP9nlnPF|)LGx4YEmaY)8favKZ^UTKs*V~{mY^~q2~YJM>uyqd;(e*wxHIU|1oJv9jgmj-?>@?B?|hzKN8$mD$}H(8mFxxJAcyxQojcr! zmVLhvp6jKslV-3`Jg`9ph53z$s)<#CmNqQPD&95g52$>va>?USX2P(Zg%*j-nxh-l zn^HOx5sa1jdP%5~q?yEGB7osnWgV8huD5OyZVgatPQOR!%V3Qrt26;v;N{`2t+iDG z_1l{*Qm*)$x0M?ZuZj(Od?W#WljZ{lrpIrYTrE^`@%nMQg^)(%*@Q@xuj=%XIMIaIj=@DW-;h?vdZ&m%nw>-4xQ|s0y zMg4kc!b@(k%UDd-y^+aXkx7uPVi&12^Ml3re7mDu$abX>nn1V-yiKP^`R4`*XftE} z9A);Bb8#@OiDd}dXa3O8>ocf3sox*9QO%cVUfd4@#q=ADWuf(ElVjk5=zE`#@(=FH zYxl3$jav#eB?Nz0Hp~sAu3Ko8HBBm+%?X9(cH7Hv=iDCmTk}K9(>yf|q12x)MyVp+J*+;ivsE?YJ0(LruKKJfDZya-3NPeRsmpt3Y`?fm6BC_P9b4Dp?BP~)@} z9(h&~O)x)^a%MxM{rv~@W##NQa!%RKH|S!5wy%zbPv3?gWavfl;p!F9X@_Odt(GosTa@pj*Yl14fMb(HNtENNG_BLZSsVjrv z^_On&+`nByzU%=M6=nU=QW0!?nn{VghDU;5prau7cO%}x>G4IaNVUQf@O~m{!__h| z#w1ax8=nG&NBg$60yutNj(@)w?0DPAq<4ck#x}LU0nULcp$$HU(!+YY%=CZdpB3ht z{ukBipvGDCamuPZrZ+i<@lH_xgC(A1Y%P1oHWRoytcOv<&KWB_M&399v`?5+HY-ujLCq|B`D9YG41;yT5&U#6MFlwE! zb%Zf*8(c+XNmEV%IQ(gb6RbPshG;E56ofM7>u5vg+I)l{7aC>}b81VxKJN_DrOuJJ zmKb*O??k*tTW;;V5_IAFv;jilYL&bwI#82Z3zlE&}Ub#6lVTx^;&ScWqlQpPaG#z#=?n>|^n{u1L z5T$Og#;}>J;;1CELIf&^7UDi~ATh&euKkArvH^6A^~62pQijk(7`vzS#kuJl zJHQcIWxSojOSR_`MA|wc^}t7zIKk;&rOj~7<`3#aWTnk*rA}h)6g5pkoa$NXGNexSC?JZlhyD)*7~o>S2C?zfP%#+J+J{ScI(X!=exnW&_DKfDku8K z67;UWCIA@31nODw1~nbG`iW(ApOKCV1?*CC-Lt7+?zt6B?g8JQBnQSE;1iXR#ubxb zRd`qLEPo(Xn2<24ShyuX1WA@Cg!_=>UblZ4DBcaiFy#Y^L%&E5vf+9F1LSVJ?gk6B8qQtUFqKa2P%L^_mQO>TGMiNHG-zSpX()qDA#*d-w z`;TFuz>a`S6^A0_AckB{FkdIt(f(wqy0{^d7y7pU$7E9D(=kZ#wex1a{&NQn zu%ys|bc(HvuE--I7trnIp~S63IcoT8Hn4gwWr&uAxCa6k!jY1_+P(T-=Nr~_WKmm! z9HWYF4?VQ_9e2IEopi!ltRJajg~^3=wP5z#CRMez;7~H&3rX3^)uy_F>A~EA;h{^2 zCFIxa(I48NUV<|4JfJJ2=n8N1VdK01v`8SEDqYTljo+IB<m?aznpa7{t{ z^{HCd4RzL9I`zuf$rYvuu=4k6%DrlP?M<#DwN$Jac5mbI6*y|rdy&&LYNll);U@B62c_|=H=gdb}XW@Z%58~KI88acf+f7ZEYv=hS5u?t5sRz>4 zusrgxT^v|rcc^_ptrC|TXOMZI1kr@7)1eLL?D4NfnwBomN&uemlqzf-6KDMf)N5>X zaG-;$Ne!^+PQ$q;E>BIzkLSH4-U@M`V<3BB+qi+yW`aCv^fOp5lF*EN2^Yz|c?R8e z02m8${Aa#C6e0XNUwf~mcddY)iY*CtJlracn9}Il!VEG_WQEb94y)!Fex?RCy=A=9EQAO-_R6PpCtGy^=xI|ORQCN zM!(?!&WJ8{fa>MocE%n=VfTNJ8p5|c)d@E$dC$T9d$qvA;jDB02VcUD8 z0^vHiO#!ZM!cV2PhZWoZY3e5g9!nEn@oTZ>coc5}gnU81F3DIiG{rQTyWkW4MTnVU zLqsQf((P46#XboroHHVaB-b^=oQbjr{E_Zq2$2{|g6gr@93ZTipYk>H{cJ+m;-o7{ z>csDXk-L4{ze0XHCV$kZTG5~H1C|9e_zJN!f#XcC-}OOwoy?o`ai0stPB{QVXg+qd zJUo}gZ;Ef`HlR1buNz6kVh#~DazSj6soU+1l zI`s7R^n=y|ywA<6Se&m1+3C|~KhN=$gVIp2^g!-|X5$QkX(M{I>Gb7bC^d>+qgkBU zA!ey}hv~Fi&KPLxRu3i6Pf4QGHn*yKAcPZC^zF2Tm)k`-48Rm&4vUyuKNny>Wt%)Q zL6vg>*ppPflg6;mZ59Ciby_H|%i%;StHN|0o-wV^Nz(CjV4N1}e;8&)traVr% zfBzBY%fAmx!zL(oY2p@*pUz80dk9E5 zg4D@{OFvR*_WskL=p`bi{(&6>nl(&{LlNUyo{8rym%&E%xJq=FAydAzwJCiks3-Q! zSzN$;WKvLaWWga91MrncdO0PTi6;~F&Ojj_D--j1Uj zzL_q{CaFc5%9wYYg<&KgME_D?wMQHwp0?h^cSeZ2z|4_~^!C5z^t(R(UZkt`FGI^W zE#vKvPxyAZFIT$dR7W%9!vmhrydY*;Hd>J=V+i~(`c4s}<}792T6n}B*uO7MX(rob z$P(oX!ARcO@O7!&`ryCnjx~t4L3m(-#Lm5MG?uwUFH^+5TQu9#hDEF?4iUXC^^Gr9 zsAmu{C~3J*5f?!zKw-3s+jrQDFEyGGuoIv7JB?4(RMeoZ8%U5*>iCC(FSb^?TjhCF zr!^uMAyEWWrm^uy#}m6ZpL>M6^s;ZQE7syqFbjfFHMkLHGmts0aCIzDK*TakdN67P z&HeLdQst&p1Jgd5h{T8r_Kv-#beobC`7;YU`PeUeo%qPs;Za>_y7g3o3)#A0?25^R*tg1*8xdd&RnOv2{2`!}KhmVKrjP*_P2NvP1LEcC zDh`(+OUTbu8xJ@{k!>DkK;Gef=lww%OgcJ`roP)^Me$_EGT3&gO)bxk0P8rsnVomE z#IEf4G5lfWs-Zyvjy(-rcKMstG8(1SUb6Ynxa8IgzsDjE-wT-_>K#-HFyj#q`UgQ& zH(k8ONX0Ccu;zghrH2SSlM6blTBF`5-CT;ua8V@Pf;qWdmvH=KGk1crM_t5lME`)U z&ZBulr(aKPg|)y5m2@ZrSHoo};ttNhv+Qvz=Pf_9u`zdtGYG{vAOQ=C_p?$;J?b|? z>JgC)TASJ#pp(E=REj=al3cd!5_e#UtI0X;2dC)y&o6%L##k_S0n>gj>0E0&zS=@X;`o7fP6DvN;Awk6Pl5!AR3g{W zHlY*{R3i1M>O4okdsn3}&Tc25Ts-wao2pnEwsthFDbwsds4-LLcPjY%Vh#!10SRq7;~`g##eEQIvci7k-^xQXY_jYCGdP6x_c$06p#) zLztKVVZeNh0EQ_s)7_x*Vj65~r~BW-mo_@mc+Zi}p+BzZL36_0Gfj}_{M9n#X#Rd3 z{hJQ*>nzvn1a?w+}B3wl#`&q5_>yU`eBJ zsQC@KNo2}%2+tlbcU7UkJ;sT&XJNQ>n$|XFPfELaVS`Zzx)1qHJN5FO&?wOsp8+=k zBO**&Hf52F!Xnky5O!q(nWNV{6hSf2-gPLlI)-;$f;+)=V#)vpGT@#ZzoTpY-_HE@ z+uMtvR!#dia>MK?AF8#D3`2A+O+%&C7?pz#;L<0_48%|-2GlRZ3vrmmkZt*+Dm%qj zM~&izcQs)OXj->81t2xrpe(%PU;l?CU%U;YIs-XWf>k)W-|Pb#23C*V01gJwj#88I z;z?bOlV#_Hb`yJ|_YusUGkR?WsvLbmHGcuXeZd>W4tp(?Lmkl!A{j%sa2*gconqCn zbyyhzE3?`flSZ%G+~zbZ_QU(@*hNz;?{dP<3Gb(LsNdJ?d_*d%77yDsiag5R?_6+Q zOIjO+c(*NE{axQ%?Z+!Z;YdcZVsxG+kmy+z?BYkAdWgl7XjBr6Nb;}w)^W%{>#vr5 z{wtdWRa2r$;SODy&!EuB170uAmrgqLrT}DHOYKw@)ec%!0U;E#@+gJj0@MC07Ze^j zE4yA+Ll;k9UyhH_#a-4U2|z%y>}hL9C=1+;`)=|}Dws;I&Mv)Dg|_Y!)`Gq7?I9Qq z-$bJB?3ElUF&4NWFPF6MMNMuYp8lDx`D+}9hh2p{Ks0wq+(C$!);3YZPtYp%67;5bIx-rR?i?{f&Egym ze6T-sAT~qD_(xR<@3|?l8~}|`PFlWt!=l~$F#6AL+cK-XS>Dtl(A|*1<6WUmxJ%@5 z*p#tc)WNn7a~P`e#O1L2e0=B(o^{AUl;e{o+3YK$mag304xYP?F-GS+M^&ns>x{6= zPsGkd#Dm-ARG_@MU*YDQtGSbGYRB2u!HN(TyD=>dDgGr1)G%M6!U|90TZIz)qM?Ex z!YfhkAHmsr=J|+;+O3iqwNeoF-Ni^@3&o+C#_|W&h#7T|Y6de!rBNVC>o9&N2pnyX z{DM$6{Ulsf`2l7O5rYx8P=I?psJg>$Ula;kaN#?fE* zs4euSHHqU1_weE~mAS!5`8;xXa4^LRzIIP+86Bz3B}%oT8JxS#8|$I#g*lRcKb;3y z5SHk~rKVo4 z*Dt!STS16g5hj>`Y*>i@^S(yxYsJ7(xISMV9$=sCj&4+Tnq2E-)jIa7?68_XPohr< zd@!zn0uKpT8wnHu;sCa>^(PSyx6)XGuAF2Ox-?t@7~)!sc7c2i<2nFKiNP;Zp_8|k zoAANM7GvW@Lq(+BoBUXV?TJ7E=jJ5!Qx9v&<+Wmb7fLslV$>czFQsSX<`m^9N2qJt z!Jr(kk9C0ZS&zpl=JSsSRmzF`0j7%DFU^=_4uQAJcZZDuA)T_}Oq0xW?KFnOKRAO>DFS()%b1I( z$cEZ0{$DR&5KgoI3#AYma!Gno!MTk!(*V>Ku|Z$h4w6d!I)VL^#|9B3WrgSii=`2@ zCA=@UWM1?()2aM$eB!%u9T|$jrQUmxV~)~`In;P9#zrH418u)90vLd|C}CF5duY*1 zgU!A_rWxQW#xyPf4(jU~F-inD+w$UhTBAUKAl7r+k3~SnPMYLr4r=OWoxorRQ0gW| z6(@%jnF-_1MyDK32*o?xWWDc-k2!4D9;0+cO&QVR>PkRA*I&1FuVM&RHrabo(x-y2EmEEC1uLEbh5CW^Xa)p@HvB zi(`cA+}0hewB6V8Q*!7lnrR?J;e+H`T@Lb9=f^-8UJGF$mx?gh9RaA_AxY}0bkD>y zUIwW3Du!Lyd+AYy1gH7yF27hCLRy6N?Rw*qPYl;+yzXoRF@6AgosT;(|2loo0Lv;tnzFy?F*65n{3$3c7`fUNW0d86v)Cb}>- zO{#1;e4-S*Fw_|~g{As{5{Ox31%h8Sq|=8uXwgg$n$8|Jabo!j!y(r8P^UVq6s5!R zJ*OAg83}Z*FfxyZc_~$0#81iZ-?!&wkQ1l)*orm~6ynv_A>J4=Zjl{m>Hm_vzxgp| z%3E^+Yru`Fm^y7;TCYSusbl|Q_l94bxhI7oC`YYk8$eoIMuF~b+7rA8M!D!xHp5DJ zoE#(IV0LC}*ApgM^>zl~-24vxcyNo0ZJD;$O{c7KKJOQ97%~ooB>Z?VNwq&>*9bL# z4=T42mdUZq^TlEyI@Im`0egQ$reMFADM5EW-I^u#FGXu^I>fZwRWcveQ3b@Fok2#* zFeoDD$^u1fxXQ_a4$$#1me(L0Kgd$ztR~>GkCU|oK9J#e(A5|r?V@zvH$?NU$yq=q z2g`zeL){uB4ohS};DwtqyRy{s#)4spv)c;wXVrO~C+_}J7hK@7-L|{5i8U@v zIjP_#0-A^8v+0qdF{?v7^^p@776Iu%lMlo{hK-NoN$bdWArrrG zJ=l;{SG$hbZ6LEtvZC3>qUyfwQhP148uD^FCLq(yUncTJavf#f_)`gmTX$_`V?;lc z3#vhP6ixHK^LgVEXtU;=`J9=Oz)eUL@m|wRRj_VQE_t znFOQXJ0Nfkpjo9`RtJq71MTspYIbzDXEOJxc@I(0Vxk0 z(hnLgZ>8;5{b^8AKES}JkPGgd0jJ4P%KvNX?+dcBcz6o);_1RTZ(Ni5{+n!~0g376oSljQl|e$8c5Va-zfSFw34`OO*gITq_})m-U-@=|%- z|3xuizN_0u_<0VAws@4zEG)b&NN-}_ya%MKe}%`4P=h7;aI0V-qS7`!xxp|9o-O=aE~&wUp=qeKK{+Lo}sFIpD#^l>k;k4t%*xaM8r zdJlh;u;Bgr#qEK+hxkrDC8s~|#T`$BQ3Gkgz`K}g#*R%V@(6{*p=A`Elx$$%7zv3g zg>nOg{O?XWGYL44YYTx+9#7-dei~xs*g@<-&8z(u*1)_g2)!xe&z0X(Y)N_O#>jS^$3(O+y#v%51>AQ@cPf0 zx%-3d1f4%WtS2lLw3En>+;3G>zcMgn&{*DoU2we&f`IG$(NB;03Y^agE{y~F7bL3Y z(W}=|Ut8cAZf+n7&0j-|SImSH&#nB`S>k9iSU32*CnjL0A!8w;N!?RtzC>+(Mc^Z+ z&{w`ZfSe2-n49I!UmdiWQ|MxJbYMo#1vn+1>mK>uh z&^N0D-zNRwSpN=<#^L6yH~nHWdL=fz`4UY0jh4x^N^J~8_o%Tr^EuiudU zQQL)$M~sx=j^amkBb`aJjQer8ct_-1h+NpfV!COfB~k8l&|!iB;o8nuMgkQ|%Q8rE z}#4(n4P2s zdiG0s)H#s&;ul;6n+TKF3iglX{txgj%!(LH=je&06L`ZYi^!UyHVPn55dAjmnudQpY|Z`s2i*AqIMJlT}B80xIB16tv1|MalQ&k*X(hrmm|WJ;uUmt3{F(8 zi78&WsIAmJL-0Y&b{rIxVazg}KLK@gM<_()>Ox=TO0zZc_&qS}*LZSE%E`gal@xx- zkm~D$AGhHm;Jq>HI9HIH0&Nwrs3Penf6YLfjx)R*U)j_k2Z;-a`E-{bVrIVH?Wdep zF)abf(bH$IP&|w@9J7wKXKfW$@9$UM*c^i+2Oz$un?ze|R<59@l0AkMmOgcQF#tjI z0Z?b!-qewtzJY5$3A2q;+&r5H_f2boqaq#_TZ*z8rbSnVgj1Z@7>IUJO-ii z+2Bd9t&m#m-UME3;#@7W#xWjlvcE0Kw?Kmh4o_didlyc1M8}t5N|)Ti#QYRG@zWRg z)xz#ZhK$rLAT3~DiQLN)0X_P?n#%k%sUk15Jjq+X{Xp8`D(6C2F8ZK)QM} z_F2&|zu@Z*K|Q7KRvfkn%9F+`PmS5guT|q?0=PB?-LTe02} zVw+VoBv}{BAkH~~fDab+bQSPRe55CVM>p~B{JsE8>}CU$rF|%~GP21|T(Ts!Tgo%!8$C-3YTfGBe;~x|IInpil37?V2==bK8Ft#T{u_my`eP`Wpz+SM- z)%G0T6Fm$bUZ}Y}z1|Fjl0D#feU{&6jV#{;tF|qyfEm-Oh=dLnvWv=>K{K~&-r*7| zl%=&|d@T^)=Top#2IMxm#W5rBkfgF9q6pz!v!?)p-pRFfn1Sh6=!hsaZGUBmt|-|- zA-Jx`&fD0(%*Ltt2(_KKrZfIRv@s83a;UL6?>3Ng7pGdV!3`JVg}72pc}Yj>r<_S% zZq9#f2<0BV7XzI!$+l?l-d+ZC&*-lt`|vDDG*kmfw7^pVuz=o$#Avoqd^vqF(Hn+r zu$Hw|K$&qB(HX^4=z}FTBMbFtq@|fLdPCxwexHzWHu1fpdklUiP3%adI7>(j#3=W_ z-+3zsXzrj%x~*;zj!!yOB~X$kwf3)lsa@+09w)kY~9rVVklgF=fb$ zZl$Ph7W?jmOIf%(V;Nye;i`EL4_j*sOZ2(h$k)8nV}kwIMILPIrR9Wp8(fEx0TcCW1OeZM5Ci$9R(X%PXFK?)CAhR#bOM z<=-MHttBLBVElQz!})n-%MFWTVo&3W0+x@%8TQ%`^eWNVb(ZT|=j!}h=UOnzW`_%f zP9kPW&d;PeOeP?54pH9~ZiHkMD5KNs^C=&m&g_yDgmD}vQH9o|u_;#kA#T<_VU!g? zl;Rp+6i(?JcX9SN0>~g2E^M7q$6Uyk_)#58hJ&DojI3SQ9+m6tRzCm9G*^v>Can$& zQ0M6Si#}dJ;~v^6-$|qSetO34N<-^s!_3lxapwD2()x9rx8^IUDm*5iBoojEv}>Ba zVVAQHznG9=`gIrjnC#yWFJSOB@%u%E{2pyO{(5Ch62%HCW&Rl zqs*lGU--|*hiTQ4a?FkQk~esHz-TS*d7M#~8d*GZ)3qO|uuWkoC?e?}Rip7(-f}%a z>G69h4brgLR7J=3D9S}qS{x$D1XOfj2T!N-`kWHYV7{qJ4db9@#-zuYJ3~0sZ49D7 zf2VCW7EjwIQFKf6jk>5PdEOq z5<lfr81B+;kkj1!b;|Dzdr0 zb=Y}Rx!$s<&uOg7pvnC~Kg&3%Ak{Cru9G}E$}6J4H^7 z#I||pm;0$VF1sc5!-0AjSmc!F{6@7wA@{16U-Yjp?;bih%7&1?tCS zV<5kNrF~|iCzY8)An=4%?GW0tJ?LDgS$&p=p}_qrkY#^ihTYqUVQ2PZYIy=}vKcq` z6D+d9hkbjs(}Q;rTDkM=eXuWXdORp9awOk^*DSX6a+d;qmZ5B8mf&WhL$Jo6(IwyB zm^yd4+CV%l_`TGKBloq`h`!nN=kMnN9)_4*Z&@N?IZihyr*sIY3{YnS@b|O0HvHlj z8f8Nl7a54$+x26ghTtzv9sG)5@8%5cHvcCC(<7wXppuLHee^>;mnehqo#g9eYQJ(Q z6F!sjQDv<@l$P@tVe(Cn&}5v1@qiwg1(_l&<53+bpdE2?;e2tIRrmxUsNW8GIF7K4 z#<4qDQ<>4O>;2*Ms1UFiq=&kK1TK1Wm3%|eSo3Qsn#j7+J2 zvq#hQb%?#diYkzA>yghlAR#w^^ufodOAbVK{?5fSB+ty~rVC9&co~&pIBTKa5(!;! zCEB7*#Z-((lb%2oHGBT_$%2+%D-zMzd(-1?>#ovam!gW1A?eQu*1tG=!xqkETz%rRh-S(^OSOm3^ur&jq=Svz&OD9GM({^94>$bvzBxbrgO^s z-C)`qA|jNCtU)G7C0Q)Z=D7t^z1aTAOt9R!^e}9-Y@_GBu4TxFj#FrDJXeLhLWUNOqg1=Y*E8w1h}DxFXk#Xt-8~iptE>C2NCP3w{i%e^{m}|Ce7Q-8%P37F!|A3?6QE zl#DP2#wP`cu%8^-U<%I;SMKN?IQ|(|sswXwp)h)VoZsYsiATfwJD$ni=9fJTtm}F% z_8!Gm`+cWg98H-fb9Zy(sR`Rg`V_Ohb-zXo+C`k}pBfWD)fDs-*#+k_=BSp#CdWhi zS<>D-S^RFG*}p)#pMQT_Vb9t#;1$2y4nx6x{+q^`$42uq+^&Y(1rX*fXg(}U&NBLK z=dUp9>q@?aLrO_f_9SX!ifc_uV7Yte-rW;E+o+iH3)rrpU?^4Td+c(J$`wDNX-$Et zaZ;x+yXy433xP}SI`P0ux}uc{h%TTm$*985e0!*n?9kE=R;;eHl}P92t@01td`Aq0 zTuDMLX#P)jd?vi&M$v5tv(f|80hTMbh;|;wr{o zIKiP8LCI>NKjY&g8&70C`!D6&!x&8jB2!}Of3w30Z^Gg=WhQOE34`PqgwMe1*THsQ z2pMukD=YGw+N$#2NTno9E< zh*U(m=~`7-Ob?kec1Z_LgR73Ps2C90rjYxGFdQo2FH?Z%Iog0PY|HxLAO5xt+5il= zvss4Dtu>l*{=MT0^cVqBT@$0IypnurL~3U-t+535$q(7~p~Dh>PIzJp+qoMSWofd! zT}XgKIl`~URoS0iu)fN~7TR7^!=}W=_~gSiF~rHp(gaz23ZV2C>EFT%sJcck5kqzW zkA+(af;PBAYp|WfnfZ(+RkIb>L@c`5Z@(wnYTtcdNxSG*@7%Yn_C3zkBPXD;(m}P_ zFyL9uSSETXMVl*>AVUu@aX6+ z`Ytky#HKk+j1KB!p( zOw)$c$W5bK?A2nZ56rtK5p)4UjOb*6C8db{D_sDGA(ZNsxZEDqFJY$Zb`<*t&7E2E z#1^yx(N=_5kAfr+vYtc#NX{g6w9F0txP|;AmzbU7ZICj7#X_E3rCmM>6;5qNgb5f$ zWgF0nwGaUm6AuD+4mg>|IFd^$(Oz5A3v_bd(9Y!h*eUoRKi#BI90EaVxvMrtQ|c?C$Epet`)Tddg;PkjGy5=?}LhW z+?@BR49RYs5jbmj-2QdoHX=5bj3e51B-_Ppsd?QSeG{tzNyy{Y?jT^xLPp35{Oo$g7WM^Owfn@UcW!Lb7HM#59oSbPau7fg zI(|R{sKUPp3-5O$cfxuB1^8SBSc+5m3YovVY?!S1V4H~iZaf&3@F6zV+$?{GFj|0U z*Q(W6BD}p7SI;NZopm9v}3^D;uogo)#^B0l+z5g?<%-IHt!bI(^9420Im z<6NuO?bAI;kP_g-o^-vXF&LNf25heC3JZ9(y5cs%j@_{|=;HD1%ek~*`A!1}N+B3z z81;rZ{n+;+nxX+lpPX;FST>iuJ3~R1-Lvqtvj+c$s)L9scu2uvfOUg4A9wvv8 zv~pnxJDE`Ir&|X7G8rF4VEmvvY3ld~2}#4j|LVDyGJq>by)22?X!%rkkJZGGw(9j5 z*^Yrgnd%BxL1Bt6y|L z(7jr;Nf6yTdgMA=RtPqgZ_XE}_f1?96kr>S;0O$C|2wzQ>D&Sa|6v6q8l2tpv^3C6 zx-DG`iStvR-!&$;V zH`$d_06#XOoFCH0B}!%Ti!~JgH6V84fPuKL4Q1NxxB+h0SmZn^n&{~5F{m^AVA-Do zYH@0Yy6KtCvm~fDq)Dxu9es3QqAR1%wK+~rD+-B{+HUy9_* zGfFKBJ>>DQ+px6|eMK&4yDdFD3#c=_UHs#qab4NLA@Q7@?58IMbk$G|F~K6Jl+UYckO6` zHsiVDsZi!9A4z~UJk(g-m_v6f=2};K`K0)i(sp-Ee$F|6qc=R62znkQRl_0qJc59C z<=U_?LtOMpyZVUQ(R|MA;IHLmwavqs;g*J@s@xv6ifP zow^xZ>`ELD6eFn6h8q*VSZ^W zK_a3e>}16u7a5=Xv`N3k?*_NJ1ybp7ffwk-_PBC$zIwAH&_0pHZB|!%HFasA3|`G- znMJBh>s)40H1#H475DgIlh?ACYyagG3Vs1YSU8+-WcA&987w+AWOa%BwV6&V>yZ%u zWv!J0$$UN_#o~5OPXg?-&QT4w#uVf5#Y;I|x)D~AdFwh=j@WK1!qc{tSvbk|L_kFk zo7~~oz%!@9Y*%h7!$U!l3tn*6+NWyxB4@}7#J*xEAx$LAMyD%C5PAINv1xn2iwvoI zP9Nq}&}!KIc1C#?^dAaKxJgD*+>xfZp87atlZzwk{;}iKo(>7Lsbohm8sjw#IpjIvM~O5bk8dAj z%_6L_I@jD`>EwWxIUI$A?a(jXfyE7VWm%nJe5$S6xW9~f;-}!7D z{L5{XsD-GlU(JGorx=ZRO%-QldI}M5nWMSiS0z?WsocSPYfIt z0RP)I=gT$sYwuxB^s!3=Ne(VjOe>%w1SIMK5*6yT$l63iZRukhWRc44@s-kYsu%Tn zU@=!%u)|e4y|+k#V*1c<6%x{-$m|!ljTQx)TTRP}=(}BC25)NuR#i;GsUk*$EA7Sh z9~xnW?P}f$leC8mp>m5AT>De8oUPZ?rEAC$T`k9s?o1f8?i3&#$(x{g#r?@WMpiV2 z##_iJq`{F5dqI$7G8eKLYm*ZX`;j9^l;m&3o&q9jUPr8DfGO;u_!e(74`$>r0Nrr> zC2NO*%vZv%Z4UVismROPo*LK_#a1nfY8@(U?tVoZrtKhEmZTPOJ4Xj<+I#_3))kma zXPpnd(@P0-*!8=52d9;K`NvZc{e>EiBwPxPau+%Ru9XtLOsH5I z`3w^a3G7j_sg<4BR`#28b9u^qT-2b4Y(4=Uo`pY#TAkPDFDLt`(1B9ifeM}dFm!^h zke{Kr{I|qAo+gdGTu^+VDL9Iua)3i0zpdH1Giry|>k;#06)54f6#2Dp*ON1TTeD#O zIxuOu4)a#wKK&1atPobm_xFPdE|^Y=maK#$?zvnIfyV!z2@>n28!lR?dv3s=xMSte zm|wa-D}Qy`mL?N7U#Y)HTDzgm3pCKE5&lf7IS}FIm5_ zQ;r^%4$8GNZ2K$?yB@7$P(ZjrvW=U5MM5XVenDnE=@TRX_Rf^DtOnQ0Vfcs&U@MoM zue=2;u7Wy*!1!%H;fNjWK1A}D+uiW?K2(aFk3Q4&_f?qwX3*l{e_0mRZY$;Kgx3i^ zntEHJyyNvjy!S~d5sG!8lvCf<^Y{)iJ-mldk5#!04SR6I(@?B}x(7&?c=`Z^KxdLR z!4rOv=+Jz0oe|{p-yp+|hDT1-f*6!}H!g)n39s*oc$lZNIMdZ;S$v$frP782pu%Ue ziVqACUFlAE(yfdCaxROK@5?_l;Fg&o=C>*2-c3fsiG^*ms7u>8?A!4aCLrzQ?^=Nk4L z?+K24ejj(%!wzCt0r#S)3U%~X#tM7tAe7R`)^9aijpYQ)CKD40Od5pOe>jPQ>Ix9! z+9H(CSkr_o!l;;SqUGh_eySSn7S9RwjmVt|)_cUGjT8ha9W2_KH4r1m-b=#zy)%Dy zl2;GNxwP>&u^!C>cgb<9_^ctQV3u8mfAe5Eghu9kHR+9+wU&L2SypF`Ld!dFOls52{wO@zu=Z8)h4t!g)k4+)V$1BN!Uw&)+<4v%q&x77vj z(7_*B9|lm#JcChz>JZ*HCVJFO7i>Jl5S-(&A$pldGrmu(6mpvep1I)F)JWD&H+ahR!BxlRT$@#kpVjW|`F~>?8K90cG4QAS%OauvLTmMDD{fAAuYD z7XS0jWn8!@=cN^XM<0&@?vr^&@fxnA@Ynz_u|k@TS_{s*VD;XrQmED6SoRvE^%79nRY2L>Jk4Gg%msuF2<2(`A@s7pMF)iIDD!^iFqR{r)yB#2-2rc|`2EqP*Uq6GTkJBjp8g1%!t+Y5P(sf~ZuiV7F889XP7#M3 zXja1V)SAHl85R*dUy>Le?Hd=S6Fypw^L|2UGQ)JA@kL(NDPQ~XF3DKPA$M?P`w?G4 zCZ0o|0x^zGCyv`yn|!W{h3EQ{Q!A(sGJvkkPhlo(izn?;U2m#jGPLFZ9=&X!F-vS< zs5Rypu~*Pry*9NmEdY6r(k+>pb+JPASIYbQ*j}zoZ1s?ji@h#{V(j9&6Cl6A-R~_i6tG$Q$Cz zqV#w#35bkAvS8W?^yYo_v*~@h_tIWiv95-M3qp5R9X|PiYWpRWbS(Ar2uCr&F;(;ckfpE(>A{zsDCBiK80xKn(rx?qj~+L<@wnAfq2|)dXn>U z6H_G2USIkpghE}0#W=X~^@L4aC@)UQOZHn0*q1V=5w$ANdwk$>at!8h!7nd}#A#uV zZz-FeW56s=&=x`*wbP@}lp|TgZgC|56)zf@=6dEzkF+rBI)9>{8Xzc8;AQggwmM{4Iy#N{6dZw9L4M06A zeQN~Im?@9qpU?-y>5P6-Q3`S4`c_Kv8o9XyvD6mmb18zil_PAwV}kYd zS;sCWR>d%`GX0=JjkomWq8s=@Qltn4?Z>v-jgX@LlIRJT7t>SNA@Z^M-+>ktjw*emvf=r?+ll(; z3M0QKdjqR#wUnx4UQf*31+TA075XJfhBUzn6o8j)$?=tr84n`~d>J?Q69yB!*~t&~ zUuAG@EPa%hC@J|hOQnS9ATG;o^(N=tK%N!m8YL}3Juiu2L{u2fml-m>BPcM`I=Ydo?5R+M&3v1dU6eF9S5t|&N0-oV~GgkzR3^-jeg^_K(d|iPAC-XIm z7+Cvh_-amS)@4w)_4Je%_RQ3U zSv*7@R!n~9;FIS_3$TwXaEh#?&c?VJOr1`<+Y_}MPpq1u6eNbn{e)n_QZVmm*!c7p z#n{8D5_(7=+=}mD8Z>&@YacSBpFa7I%>vb6$9E$zBi}{_z3@}qv1Xce?F*dA*h;!#+v>Y=d=psmdbq-1Lg=R0LzXy7w2v(S1+jcDe<}&ldek8mP_#l14d!Yc%epm77(J4 zVl;GDU_+6NC!leO3*rhAC}a0*gy-S^yw*dw`Awbg`BUPPsv* z+kyswz^SZ?z6_V^>|0hLpA0WaY$Y>dw_Q#r+9rz}L*Yh9xAO$h@j*ty=>mi8R#%kP zT_Nh`A2HHs>U=}?`2W1tP=35WS?m?CG@owA&Z%3VH&Le&SvlK6{bD%Yuj8nZ1~fvD z@Yr-U7f20ycF~2X&+s54@jxxNdH1qu;_g!wY-Y-g%i)!$N6WV&80mSv(f1#raOG%! zVFXo0GlCFjTGX)V2eAUx_UdhmB}gO*kxO3z=ToGEz4g|Pj(xcHshW5?69kCL0S1FP z6#X&!?_IEa#G4bT&;!HVzv&k>el%-$Ti!)~R2IS0hSdrn8|eO zh0_6AGhLDTQ-H3gBLo0(5yu>D3`t4f9tTe$(0jF)12BS}WT1Ki41fGrb^}kl)lox@iiDG&MsU@oF-HH-+>}UdzVV_ws?*5l z-!8VUjCk?^;eKz=Fc@w)OMGI2_1wVxD`xR}o!MmPf8}w+CE7Yj6T1oG0BE)W0y%_X z1xi2wCnLD#=WaB5M$z2E4n2LPKW zP2GgZJgevQD9OZ0N6Hf7VG<#bi0%K)dd)VBPl8AEV?M?t+EpT8fVxSc9b5`JTok?_ z*`*-%%huwEUQdfHgP^}txQ!S?@5WIr=OX;^sJh8t_ugDleVOSb&dTb zma)>~S_tf}ZvEATi=^D&miRbq`Z?&`#LeV$S_6J5`wXCH zgybjZcw4+M%fzlK?lWEpFvNXM7{BWyC@QV<6AaGM^hsTwDCE0n|3?;>@tOo|Oo5#8 zNO;llF7Aj^srQJU9qCrmJR)@p<@|8Ai=!@4h~3P{bx274;?chWIeYPlgX%u$0AEr9z?dR7pMZBWP3=y z&hE{E{<4gzHHfv;i(=vZ%0zg&=cflMCA}H2_EJcJV~`?$*wqulF>oQVzlHqnUy4T^ z@p|Ru_0P}JRdjp}HNwhNGq2^=aU^17=T;y9c zT>T-7Z;EKC5vcqW)^!Y!A_v)af3p~e-81`P*#X)7SeMXz2(x4NjrV+SMZl* zyNH2(vYk3xPwXBH>G0+yFvHZhOErle2hvL&7Mb9${SyNhDlZRCtw!^=ZISA){(-LH z@UdiH0~%Z_hCI|f{hvVvta`V6N->){Y7Vf^%Y<#G+MMft$_;KyCM!V)bBwQs>kB%w z@2s@#QEY9(L0P{^QEjH*|JMJE_%4DfkoV%}>}Pu^0`Gz!XdTA);He2l!H;jz?^{m4 z*7ry+&^=++6NJ$Iy5OT|eo0${Br`pVL8n81)^76lcD|59Exn(-pHEb8U#>M8&L8O(>*^hsw)G^W1L|Y&o}fjNK<`8yPs-6W^F$27hI>7%d;Ic^ zrWVv^y9EEeJq8^Z!F~($KFEn_ml8dZ6De*tz`gJ!xVf`W{%$3e3dX{ug@|V>W+8u$ zT#aTCmAvgv&_d@0!$sLcKUE$i8J%6290!KS0gK%sRBubp_B|1OTWXG$*3{U)to*F_ z-q-CZWjJ~}A$(-UK=X(_@RIsDjc>oP7dl;UmPglq;(AT_D-L&>GACc35U1dlq(7~| zsru>nz4N?%Q+an#Yic&fDQRvy-kW7t$@5t(EIc{pbs-RS>ZgESclj9E^<40HTJ5YU zIPxKO|NfAukOs?Rg{JTn(m0gy%VgBJ&#t zQKf)`UGMbA!4YFQ5MrB$ZSuk2Y0t)av4}W<+1?3_T?i{iwWCbIT0Vz9^d~gEyMBO^ zabVZV3ejVmctLMgvT(09a-7P$By&fyp?Y~MP`d8IZ+TcM^?x7A{dvWu2h9j1pRK=f|r$3`q% zI?|;?2>%h)r||r`s$P;a=oS1O3L*#nQ{O*kjliM|rJ}~)l*dN*dc|1!dA=+fK}nKr z(Sdtx;t|P#dAuQ88AzpCm8V(+Z|>Z|TqwmZsky_MVqem!@S$X(5`+d4o45R(;+xr+ zCn?uqRDL50z`O#&7uc%9R5O3jx2OKi(b4Yms7xY4;jm?? zkMBR&l$~C$A5P_P9G34jwQpCjf(QJ`n!I3*H%UH9s2sF(kK8A^A_R{OA`a+ zI@`3RuVD(--tQWj*BV54uRa2mxG1%htO|u%)~mYtGtRvbT{pUUYXq)<<&phrY`2Lf zW&z447P@#%JE>*HnG5Ic=DKhpvU*vN++e2pWF_R>Qfp2wD)0-~tz)~F9DF*<{TQ<2 z>knB${O-efWe(g0Cje%o|0}PF4%>w6HI#y_B)P**sTybqa2T=KVahyH1hcNN>k6P#7ON-vZ1*!2xCV20iKAaI8vK=fr&elG>n zKVn>FxggWKY@B+#af4@~>Si$s{3(rjK3(MbJI39-q{(R#{Qi<|D7<6+E<8})OdsYf z1d`_@wtN|n0+;BR3Ep2JEpBmVrL?8OB0BS|(ce`_n9p4jlAnzU*a62fHBUk1v93xH+)fJ=*$ z9b?Gj-^1Z=$0^SDok?clT))q%>U$aKU{PC^62Q?p`7onV4QkfQi-aDlRDM7M zsM2zN9BcZ?RT}%Ta@q~9%OfSnnyAEN2GJG=Qa{5~Rzn?uQ@jK6$Xlbe%lWcQaFvwU z)Zb(Ll>sZbN+)iSAz;;q=E;|S(d{Fr7>;6@xP^1Agmt(0j=UpxXKu^o0=)Bs62u%#h-c=|wXACvf{H#L4e|P!`w=CP*z3B^BN5o)%Vw&|e-D_N)%OLUqP|w|Z(R?OHnyJZ7X#|eCSm{;@kY?TN3TA}7+$O_ty8@;!h5hjvIvVA znpIF6wt|~um3+hBMDyC|6u1V|8bb=nJV?Rd@a8KO$`7R@;ivUA@PUuN1H6S`B|_|P zn8ySr=oyX%|5G&R(#K{*8*ncVUQGB(1X@RbAQ`L$?K5eOI?dh#z=3$XjRu(f3+}bj zWRx$JRpi8(3%^~X?X0;qDbOdncy+Pxxy+dZH4u4Ay;#zp$uRd}Oe%^s6ZHl0av->t z0PR-9`KAN>}qK$b&8Du0OY^gsUC{(>!EyT#=p~9A#R< zO&vn3AbP;lC#@TsBZfO8GWP{q568*jP78O=uX(Slk4%&G!JM&enoo^y&dl?%aPVJ2 zm6kF)V4+ik*Un>e&^x8CWa@?tx*d1W{EaiZhF-L>$F8zlLLenSDaeRo%IN)K0KP&< zl!3lzn}K8q1mLP^OJAeXU)bf2zi`k@0N#Vwc+}dWM=8i7jIBw1OZYrKbV_ySLlKuW z@)Ww-4Ga`K-+8j-N;{S$GK|lccSb|RsNlI`rY3NDeg}2>EdkLoG3HqG1&U(Kk|e6n zG2^Ch)YRL2Fxdav%>^5~ryj$~IFHyKchk~!sr1`uMp}FY`=JGcTaWP;2Y7k&>BNkB zv=`DL@CL5Q*FL@yTY6ZH*A8`Xf>v&bw+w(gLg51=fX|!2MzB$=H$V_T)emF^PC-b# z=U8qolhaC}n=ZS(%~T+8a&^k_jJBoe9oezI*U6vUwtK&`(01%VO>5==pg_#$j9yt7 zh$3L_;4xgW(d_^x`T$uPww)JMQzeltwM`A*y!BfTa&kiT8H*5`+b^R@TIEL(0~WeK z-}>Ba%|tG8tb;EPmB6GM&3voRH{Wxn<%AYTaq2Ig(w**9VYb-rq#fR0`Px}#wUw@S zY?AzNP)PAh}6njhK^7mgb%A*BFuGi*0T!UPlx=7VVoAsCsGse2GuH{YSWi zft0vocIqo4*&xMd<{$P*zx3PA`y+H|85`Eku1DVe21|v@U+t)K`*fx21zb5vbsxz| zCxY{pxqe-xBcHHJE6Gc8Aa^&Wyj*HBJgIH3s={^(y`uhq-yZ8PV&Id&G? zFsHpZjP$4Dc0f|jbRXg0Xv+hoAX3RX$oO&NdU$dL9uy;r9s-Hk;CDQndxgAc~_i<;^Q(Rp#?R`$7+5$71nO}&;Z9VFU#wXYIT zlGZjI=PR^XcBSjzFE-DQz=%OtLSX)iuNyCvN`_N|Oi#=J#0WEau%jF~3q|mHAFns8 z*Gn!9PcV@Wj7FBoy0wfJ{u^k1lHcmdG zEQqW{s5+Spr)nhdEPC|2zw@Ig$-VQejQpO_^lb3t=5X7DI8)2i+-)K<@;6t$JaGz~#OD=Q&q88D0Yr#}&t`&?64_7{vw(@w8!f=-rb2_HHq zVt4zAtab(qknZcvE;dv4)G!;E0)~^O!O2V%EsSI?Pm0$(j z99kJER`xD&!zGt6udA}IgHO)lIB`_`fa6hAxQH)Q_lQ&+SE)ZUob!8N7-d}k*=h|h z({f>xyvoEEVjJ(&>!Yg!6_~{d;jubZ+d?f0W`qbL2tuY6*Xjpz1U#bxofofbASLXK zRIFCYxy(6AwJtU5HlU~<38JQ~icv)C&n66yMA{O!SrrQ(%j$Hy!<+lqZ*R4z78`b{z?j zfX-MsKI;GF#o9-JLiUjcA>mNpfq{DJ`z7%|nbxcvCr2_y4#-h<#U@JdSxujD1ZEIT|bg3G_{d+b8KJsW8oa`#J5s&RWZC|0K(k z126dTQcaDZW0$gMbgN)|+nibV37EQ!!5Fod+|Q;|GmTP~<``J^_(X^Hbi9?4CvgNK zt&u{;1lK9+Dvv=1Mhu`bUH8V`1KN*c04f4;D7mE%mNrvs^Q|Vn&h+*ed1?5BIw8?5 z=Of^Wm(}tcII~|M7lZ-RaiMz)CpZiMENo3IM%ztBm5zMi!>(}j~c+TK%Pn>3# zrb-E`Ak9g>*DrW}+5lTP1vnld<=da-peZW06XNHyVXX?e#khC6Qv3;5=(rXju!8G8 zhZcY`R>T%#qPX?7wiripIdUTU-b4mzH-frEg7%c`sD&KxcgjoVM_ z6U==|@i&)!cjt12nbiQ7*e6wpW>9Y2#PPJqTdHaf_FrR3VKbga@*Fxrty1)p3;uo? z0jcH=osG>xMoSr543MUB-<56`@r1Bs7F|dO>$Xy|(Ap0J@V_i&i@xytJvOa`Jo9HA zt`RT%i;n8Xx!x}U)q@JNS$rZFITa7D=b$(02@~k*SBn$nU<^XHb#cA>9Z>l%Z6RCT za<68wA3FmQP)BkH1nGDiM2nkoCI-dXHx+<6OT0c-0tEut8{P(HC{*LRMLLx7YqjzRyN0&7rozT-YOiWJ7%rraY+zrD{_?d z%`OAodqaPF-FvJ&)eDL9EkEnU09b39cnl%*Xx@_IosoY%pMS?mqe`jf2K+t%9slF- z@LhZcqWBeha$u$la;Un(jakPufib3?SF6R;!){+S%>w4L*m~xco|!mOh2C1dShLBv4TlB)wRijq9VmK?kaf?%1CL29(jBl`4yo z^~5Z06C+|iI#^}t>$Rzwe6y|*8pR>@@1%;@CAMq+?7Ae|EhPdnx6r#E)@>`?Krafgs z>2f9ykys@3&h*m;1)zXRx2XpMk$u#6o@5YkkO}3NrW2vww0TE-4r7(Sh6kW1#Q>18 z9xoNemD{W>u!pYpg5)7_9bfwWO%lEY3fP zBiJygtNQa`FJZpL1ai%Q=RKrLB(t>!Uey01@p-=KPijUsTt@v19tEu=Yw`0u99IOa z+!D9M{PEYSC%zc&WsqvJRL8lYZP(7(=H1)>CwWjU0BTBHd=h#+?iE>ChXrAPYP5=) z_GI-#tMXXQt-(V6MysPLs-W;U8nraakpB4{kEmNLmkZ~$g3fc7kS-zo<0vi?%*k+P z8rW!EHR!mfZosR*1D)KWWT3A1o+HjbJ?ZL!^3PxT=&>7UI5b{#pJxv@I^l=SqhjG_ zRxF4m5jQq%h#I+@UB;<#x2zS($RBaGu*~PNxyY8%Fi=fVQB(Ash4rL#m{DHMuGM9* zaeVWKmCAYWD@2$dpR!)PS}}eu=vHGqfcuTN>|41pn;ZkP6gYk12bK_=S(J5gk2(!r zZ1gIuZ404k7P2x}@_zB;8J{?5$z^2c=4Ib_Dj9;>AoclrY+#qRac%)L-lTR=k7h47 z7)>{+Q6igRQ(mWHKKovcyKMce{3iKxq2ATB>%WB6U!>1w@|fSjB@QkF|x`=)kO4dLHKV)+JW_VLFCZbD)YDv!+fJON(X&}R6Ozq2A>oAy zfg^3s|Gw%~Z4{1J$GiB2P`FDE&pX<>|G8l#b(fRUHA3)au!lSRETbP)rl1J*;QNeN zFMdmQbx4oX2RMNnYW;#n&^(*X{U4jiS95UkRCFKFDk*#$f0?s}3IIu`DDSqF#xI4_ zeYKb!gdYe0c}zIt#7`91%buVNzK6m7nH$lHmk$z-3*gLIOhvX^p3gfrX zBnC#`eM;@j$!uyE%N{+V{QC0$9OnRnrceIKNYDT9xc%`|m?yg+R#81I&l1KR?0}ZAp9oX((mW4l|s>B9Mh1gKq+mL4wGCpoGUDVf<2*x7njf zYcGS2!m7Rck>bw(RyhhexAhp1;@oLfLN99syW@xv%tMNh1mrC+0q=^pXttd_l8Hd~ zfKzP}34%$va;6APBCKd(J5a7=)TQ?r5-Y~ir%lxTYCZrzYp#cWF_a8=Mg+pSMQ;W? ze)c;t0DmM~(3IndIhpVjWy={a`Vc8otOcPc4()5m0Ib3yVP(1`$8 zYX+!n8H_rRSSPK?4u4OU61vsADMNW@e=1r;)gPKW$j0-T5<-j&u~z9wC1~vVT6-IE zMtUC=f7pJra&s90-1#R_hDq~g&7}HB>(0h85U1w&HWyk5Bo0Up>v!!x{~SeS)Vw({ z?k2Xio^YYp#T6F?Ccc-ZJv>+nI8reGmu@;Wz{toT;h!h!h9@FjJ{<^H*5zGm=Y4LS zIeNUgeIoltU!>dvcThUa6+%!u?v#MDi3~)fdg=P}1~&@LOJtgKLy=#hg9PnoXxGZ- zW6!^KQZjAdp=^RA03iI-tpfdd1cX4J;lP4<~>%?IniI8?{wg>W)t z%&VvG7g+H@O`v4stdb*;(V4U`d66ZF4k@uc7d6~F(#kINf{QJiv6%Bsc)lxO$N;FZ zLxPOQ5M^Piq`^AkYIH9$Nl1=jB1k&*5|g$^d9mxENb5}>Uba3MJA)~a*5fFTkT@kL z@CW&YGakWo3=BTFly8@*-nXa(g>+roZ3AB*QRD_M$3K)=#oL5kY$$q2BjV+zK;g$r zu&O1Qp5hgMnwSuyGn1c;rnh`VpkGNVw(76;vjd0R}pgtfRoPN-3ZFu;^JgTyVj;Ips~*gnU#vl(|kj zwMVf-I%X5=_5o(tu z)t*C#(_=FP)mT}Jt`Hl=mqX?n@-CKW?}~^sI&CbnfUv1t1`8*#T$Vf)v?QNNUI`&? zT}c;}_lM>|^|OPzOR4B3BX?uFfqkd>b{(z;)fy--NL75t1J2@I^Kg(`d)s&)rK=xl;{V~8>Jx@yrv>v;|}le zU61+xy7)$Y?h5b|9b<2rb%=og7>~NEuBjJdC86P*5}`UAzyQSUr|S|#W3+XYtEO`S z=s1Py4v9d)5Y!)VVaO+qM+&%(=8|=r9+yettE}dAN5x0>_dqnf#|?bkpJT=n0JtPj z)4KlE@E8r_^i}iNAhE8T^Z`+G{3Nri5t*xERKPgEMM6;-qyXw32qRA4muj>AW%1Q8OiPc14Q>FOsGO# zT?LIGYyseS`Ma?U&5dwF!eEnM@XOIK2Mg5)6e=l=Ps_G_)MoRx*_llmq!k59-CiPe zur#54MO>o)cMuxvX_{2Y=!U{qda-C;LifW(Naaopc8TqlB5ybuktpMK^H9K|$O-MW?VD#d!t;N|}cR%&VuSSFDjGGG=R z-2`efLGCY=wlcZro;0n6S7z8=7`oQ^=8*h(%R?nD%) z8px0xj&v0DRt6)5lNwyo^<6O=EP4LTQsWoZ;y#6Pk*lQ3qY@mjlQ>BrOxoeF_0!Qy zHj?bdrW5->!-DN@@D|nn(gm=p2$|-cb!*j_*@KVJB2T!hML)q$@PA3z6}#m3Vp0_} zF`VfA;tBI^i-lQKi|v+nLn&%f9G~za_(C!yKu^d-9tu;rgY{jJC{A6^i*7*1IYPz% zCFOW)Xqa(Wxu=|`9p6GYuw4A<>CvH^f9-YkYA_!y%v{5UtuW< znJlO2L2qI8tpDY}7t(XJI!h3nQJ2!*>erzppKl;WP8Mboz!nj`Xy1F19Qqb?e_yc` zO0mnqyB}Izv1~IMO7Q5TP4!^AlgoIeAN)un%`QzI|!{5w>5a_IlS9WVCms_JnPkFK2Y15e0e5bGrQT!wiUwE z92`8}O=Duow&@3KRyGN@gBGI!%GP~}h2{a+{50*@7YeaRV)fb>?9+W^Qb~+-0dlTZ zu8FmxB+S&8wxh6C!rr`XBQz_A-1XXn7$1o`nToURgTmZXC}5Cae+oSe zc_-R`gnacE)kHbnZ?vo86r@xQ zS^vw@cf5lU_6Tx=1hl=E?E7^{*w3lPv*c&?B0=ry*5k6XeTgCo!`8)0FDqXcupK_W zm?3vUN5FTIHYbfXTvmgiFLN5bxiu@oa?ywk2MxT0^hG7~6^cD1b1f$0Y#?ju74yCT3iA=`Pm$*|rSgPqQL$ZLEwK=_ zH){BfmRk0x>h6$eFs3vnbLRtkf0^kENEZ-> zs7lc@>~>Z-nQOo7Jo}?S1dpMK3W!B)WX36+x;N)42$J8*?#OMePKtFO3%n}U>3zC; z4qqilWpPjhefHlsg^#}VBi*(dDR>@~_;Ic0tf`BeH6o4RSR^fq(QK(Vkoz0}aNBN$ zj?mN*I+T!{HqQX8sReDz`*MKc3z`6xdF-g6WuRsRH(N3W~t2M>_c{G&{*y25fU<7oYUw<<2w$q6KY&YDvtelvsv z=8!^6xMio8;SBibx%Qmc>e~2!IYfTh649d>U~}L!63AlZ&_;iA2RiKW7NMU&H5yC$ z(6Mi1W42pCN$(*$4lfF{QnC5*oMwk1;X(HaGM zk+UDK*-DehCqB81+u87_2NR8&2a&-9AC9@tOPXoGgAZkFOI5B~b(w=uPDtp{5=*~5 z8kkvbPkU|&$q(zHF4^$SA-o<00xZ#gwzgH`}4NoJ{ zmSN^i-W@|%TBcrzRSJN;Dhyu}my zJkCF8B93$7_rJy1@X!T&E(XMriVZePRWZ)XTrFitFnCN+db6Qs5rIYV*=mvQx*m_l zlG)!^_PNXMwPZ75I#7BIb{2&o3%s2^&3NR6Oa}Xr^2HUB@iwOEQ@@6APP>u5BgcGQ zN`lz>Dgng<=ziU z#PDefMk{PhKnWQkLP7}m>DeWZ6f=n*R9i40-P#6@CirV2BtOfF?^3`Btc$bjGudN} zK!6{`SGMJ&QMIo>8Wis%OBz5O6_<%cw*&t8>@rja$D1Q(B3J#zsI#{~!MQ#Rr!QXz`OA}u7y^9Yt9};(Y z4!9y=Gq5-8B|0I3xzvBagO1B_eQ6T#StE#|*DyEjwb7>{DawL7fdC?aKjOfFlL>*3 zQGwS5uk_^Sb&{b1Zo`)c>O?t`;l6hyvr!c1R-7@VOZ8{Ye>HY}tA(H1!Rtb@Y53;b z5PCEm?5!z_wbNyH%1}U`{FqqQ@Of`oFuPJoS`YI7WJ~hY{NoY*qQpm)J5L6-vGxRA zeo=qN<~|bv67BJ>C>5H<>kq34AFB(`Kgm{mNc}0NUo%gU(|QB&Iy%dbp2r#nx0Y_< zFY$PU2$JtT-lk;f=3emsSMOC}I)AG97=*Axm!75HaSZC#W&}z7X z9F7Wb!+d+Hvb!ikh4tASIk5bHa{Syc(a*)r z%2H7GM^$sPeYd)w157v!q7!0_AHP*I9w@b{8-nrx8pPba>7vYZmZpR)ei=f29oJVSdKOMIZr3?wP9U?hvs zCgZ5R=@189^UU{$`w9zwqn6R45cAcNb@ME+@_^C-;+%+wsQyc;dT=y*Bi~2zhe;td z#JN2_SeE2SV@KA96yXa;GN>QZGG1;+4{ne`OqPVjI#QPYSBJ^CIxNz@pV+;{depHO z#c_6PG{v=uNQJ$@H$raN+|AreWM*>tmtO^%Zy5FE68TY^ROZUOz|FHEr!;cz_cu}jCQcD_qKw2*6E5?PEud5$7i|QbZSF6n!5(?tnK!?z zJM3T5;umYy4I|<_y_b^_KvD=dauZifK>N!im#BM$_T%wj7AopfO zjPvWw$uIKQ$o8wOp$)5_PIrkrcGdw<;SUc#OS`OQn<~JI$_sNa=-~)HYx+cIb`0tT zscM1u%iL}HO4QsdK=uBo%S_punj-KXViv|q$VtA4fFe=_C3O*2%}@z%wr)fa)6yP~ z5~UdD#wateGM2X**56%;=4$NXGYq~w^Eg&^v}AxL{=HvI1U>`Nry;jvl`4-BZV1@SN2UG6u0#)jelz3f|b~}9~55+9_{?!G3 zmw5uKS;bVjMzwrV=XhDj9^lG~l`(f}t(BaB9G9y9`z>iI=+|;Ho^oUbBl>Bg$!*c% zJD)51=~YoI$uS>xO*d_Dw!AY1kaH$$xLv<#YBsQiS81}W2qh#M04OA~?Hj3A^q23z!t3R+TJs=) zQ6N{8QAf!FxX61>l4;-cAdb+So?4Mj!qR_?b)>|54`Q%daEKSsGl<=;kXsdV+oNE6 z4t{8$se=I{eK|l*n1>6h??Zd4A)U9Ck^zhSWNZr8WwVqhIF`fD=8Om50J^ED7~-NO zqtT=IVZr|t^p4a%Cc2pbRehdeio1Krm&>baSKQDX0`y3@7i~R7ME*2IIOImtn65^Y zZ_ovT@R3?n%a(##+U{XgG%G{exEK$OEai7EFCe6NBacpVvnkhDgYUQiw@&th-t{0d zHJ1?4ynZ=}Q0VhL@(9Ll*{S*P;|n1<6OPJgo6VSqy{s{K!8Lhv&jXpYnL7bo?kD z8PtsZ&PUnWb;wK4w%Md|aiX^*S-?evmeT;BALm^~fY9u^l|^c^y;uz!=C!v7&xBzu zrr>bq@xuSr1q+S<;DB(IO_uJGGVd}<`Cle^!-KHik=DHJoRY7&@$Zofh4?+}w*^A!1)>rW2H1?weqd9GNaGYKgZSpne4nNTB!Dn{0?U|Ez$DXQJoi$7_r`Fq=L$TRvjdjvQ$FIt zBv+%W8&8@*h5$>Fy~wT^*voC(u9Ai$Q|U0mX9y0L;-VX2-? z?rRsXqn@47lQisY>@JB*wyLG`oGbN7a}&dB@(>W%*boQ#As5UDvy@?xf@l6jU+1em z0o^-xoxx6xyq%`eu*P5Obi&~Gk&se|7TC(QF*w~wOv=pndx^6lm%sZNyvXTwCh%PJ z78YiodDDPEd11N&QW(FDwEdwz`_4Qc^olwW=5d|A%R5g;X)jb27zHkGibX`|IbPvs zwza%3)m8@JNzqL>X%qAink$G14x|lLB~W+$u}DAz`}D=e$J_q;A4nlUH6;`qtfKMPw*2q>byEo=e!a0>4UyHrmDkDE+lJPXLEz`2To z+FVI^BNyetMt=9ScJ8fy=(q>X=;^2==Q>kSY@6mVRN!8;Nc;Ej(B_V<#3o{2OxE2? zoIJ7_dDS+R^hQwJC~Mf0oC@ARbKzF^#Z+ykdN0WfmZYN_H~d+CcrVV(74nPn^D|ep zFEU{_a)=6MBwyNWsVeznt46rGr zKnAG18V22Pn-Jx(Tu5Oa5)k?Oz5MR~SujO%xS${_5fM3Zd0hB=fPYhYgp({%Pg&)FiUh_1TW|Dkj)E0=6iU+e$p9=d@F`RHtlFb^Vx~wZ2U*u zc5z5NFl0g6D87RRLJeAE>v?()#y4q~j>CSho9oLZ*OUA(uA&wux|}t&Ty7q-*al2` z=aJwJtJqZVZ}ZHbn&juv#Y=RlIp73vf$74Pr$bj(j6B|E8efjh8njwgCHD2ITP#r4MauROm}#mlB8{Ub5TdT=$1h|PRS$6sJ&c`)e_Az z$P-FaVems@Ho;d%aU<$rysBpwxU!FbJl9j8wcl=Su7!kmXFfu(2{DAq6QEoa@q4~a zkr!?Grwq8*jH>M|+(f{qG;*zx?LfVycqU)b3UKr*x?_nnjQLyU?llqi7|D^|tjP;y zwXDHs_7GrEz$}i?IR!_pjtW_3JInWhJa(hYCb6_;na!63Ow1(#Msvs0{w#}^RQ5a+ z$jI025qN5SaGhAq6v?!1p00s0z4EZ3W7y1#SMtAlNh_Tcf@B+M8dCPDrFkFWIqgdtqU zGBVA8P#|#=flxfy^gmDM8JXNBDb;)2sbbVOaq)zf zuSFy*`+&ivka)IYLzDyu@Y0-O5XeHYQW2|_GI}2FH&}aKik2DmK4&}MXnn^-bhmLr z#iBq*%Gjuri5b=y7Xd}jdbhFspu<|U`c(fUuNGnz9!b*NQ--j1n^iffvYX7abJ`;l zHls)F>%q>SwKq`4=~CeT>f||i_ssdcdhjBXQm((x1@)JzHcx@uF^MTpAoaff9PpQX z?G@P&N4-!r95i0f)3y4>fX)fU1`Z! zhMU=m<-yz7r*c>dfxezgF-P|Bb=QgSn5K8NMW3U=cC;jpl7TBk9!ml?;8de;6Ta#V zFhsvuG$|!-A%Bx*U+^y^Q2sx= zR7^csjs@prrEiuyrs2^?X=AGtMzfxFmJpJYeL}`g0wY7mT1V38aL}FLGXBT}v_U9E zJIzjNjdaq_iVDDnzMbUY7sb=&B(K65~cK6#jqLp;ijo+a*F$LB+uvUNSwJzs; z&$b?!nT$A=?MR1K|LK(AV@3^&j_3dSQmpnHR{ig->LZW&jR>D@R?XcZWM*h^7fgYR}nXAl5vuPST|rZcUU zgJr*T&gA89NDKjbr?R6Ou2TRzA-%~8v5kzryB=faRcLNg@!4&M0%S0v8nqE&y$ic> z;Au`w7+ip8Y5!=?LNDRHSCBYb)*`63G-&U zvB;cp!D=$4>NZYuL`Hnb-CN8&(GJ@3Q3K+u_0f!~nH7hh)?cQPmLwfn2(S+_tc0kL zF4aA5M!^Jp-V4A5KdTCnphrGk6i&kMa=IFEi6Ij7oa&2bz>+awLfOR0iBo=AW}-Fq z{qoN6S3D{E*W@B22GjJ!E!ZaHZm~FEL?+-Ba5R zh1}v)YJH_6Lzd&bWGgYLpKluou@?HWFPBZUQ~3MpP>)oR37_2#ti z!fw{;IObNaL~glMiYk=aAPmB3NC}NeE`f#-&%^@j^k9jO;QJL^m198SK=nNnZrt*# z7P8PemaZTjUxwL#KGHBWR9$OEo%USZwLad=Z7(mL?v4_s(s`8G5!4M3Xd*K5s$6#5 zN7YQJtoVsY%`Ch*IXvU;Cqt7UewdvtflOxQvQgu&%5iUo{b8~!-Y># zi}fL5y3^Uoff}ykrDPX3r3$@-(M$ocyR+n9xf{l>)D%wK^>G*2C2nW<#X+%T_@hb9 zvh;a7h;fI{(PSCr*m)iU)j(uNJFEPXRRt7b_#yW%Lme0>`)ezD%r~>)hs|I21oVBV ze&;^mI|~mH9@u%X#)yl5{Hp06^#@2e70{Dd!i^(W-6?Y7AXV7lyWvA9UpE3lq`#u6 zMo<8>Y;(d@SAYaE_ZL58i2TVEzv0`B;fWGZ#zI#PACIBRM4wv4w9%t-;Dno1%q``Z zSdUM#>uiSM^8sum;s4>OT_a*#OK3rwFWZUZ22Nd`S)FsGSOR7v=d0Qlz+;Hn7|K1_ zXvz1z&n=5#z-sKnvxc!vPqZd^VjGNs8Ck3;nY}bj<7th7XVqI@7Cs{&0(PixRm4gy zedLjJfpo`Dz-L7Hq-){ti4(Xp0RG>rK&zS&(#T^$ioG7>YtVJYe|vi?n7Q_esj-&H zB9*wu6kRu0U6~)jV1_&L^BQN`sbWibhSF1oR1ArYQR&R^++%yg+wZK8JV;~9qE zCa5*9)F9TK_0Z~`zn5!M5Zh?7#=3g3700%JgJ+}x5`AJ53{3SV_nbYx9R1fW0w^XrmViZVDcZ(!iw7B4e} zGl2ejocGx77mqyU;kDf4TNhD={(QTbWz4BuOWda=LUxKaPDvw4ijQVDMC6Hs+JmMt zTXoLPkqp)=m*1P4rtX43AMdJfVC6(nsxN9KZ`?{3DokFU0nSx^5rn0I7zGm_IIV4i z2Sl+*ME@M7ATuZT1`VfD15;Ckk0K=^Vteo8Z7Vfjo`XITPa^{vj`umTm3jsK$ z8tJ^V427=SPf*CXzlj=(_lT0mSxRf}%Ht@U7^jQ2Ns-B7lP%sY{jSDL5R#3D3>=>7 znuVRAB6$hvl3Kll@T!w1mLy*A3io0-g(`eK^uy0I#>J3?HXfW~OZh4H&4B+@+0v@R z_~S{S#+UFR`rWx7=m%tk1@m-1mL1cq(fVGMY;!n&ov2YAAZ^~2Hfm?|hDFzAby8Ur zY0pCZ`N;dn^{@TCUq8a$e^Q#xA-YFmX9BT%xJwC8fE}`Ta2Z~&b;YV(Gz1q?ee>7Ex(1GEu0Rf`% zPuT>PG0dW>hD#5W_$U6+dkI%g|D0A;F1vFa|ueV$Kn>=lSbvu;juDs ziY*uFq6&XfhV17Iq2WN5ieV3}Qqx1f#d~Br;>&e%qE^ofHrakABV<312YP!Vk`4a? zAQp)j2g;|T4hvGLOel8+C5E+0Nnpn4Sy{sdMz5+GGlMul5??=_e+<1#fTpcsAyPYd z3pY-8FZo#Cb9O(;IJl90>-JcoRbVplw8#3!k5SwW(~JhQ3FZ6eLmXBV;RGcI3m>aO z4mM+eq_EDsx47>|kxXhXW4Q%pq#K=9gx@DZGq-XSU56iV%ZaRpJOuE7)`)ZRPd|ov zxKjcPun&sIJYR>k|0@We>CUGJ*@>m7gNw~`Hg-mc(~;?nh}JA@o=NOoph%4VInMFx z183kwa9rit474mlRUvpE;Km=nl$_Yt1#DQM!`uWEBhDML`(!u}ziQ?^5f1-9nQI9a zT$Ss)5e!u9Dm{GKO?;Vv9-G>2YEtp!1o%B0bUV<(3|eFkcq=I|veR_}W;^^mKz@OB zC4x7`YiaJh^To5K3YY3dMQ(HpK~k1#Dp1-NYmgl+T5>)av1Tb-gt}sHil=W6#Dai! z*lH|vEt?nDDDnkhLO_OUJpk)EqhUq$4vf*d{Q&6Ei<+Py}DXNBT>7(aH zj}N0@^1)n+Xus$b5oW$xbtV`W2ITfj;WZ*DXYQBI&QZyy(`hXR!HlW6T0mj;{dl1L zse=)q&xe*(nCcuM@F1Vgd>hmi)-=z29H8W;*W4R5XN~Ok)lvlCn;$~P$Ykfh-Z==L z#%V*b+zv6A?bzpP2p)qODSJuCK}$qUC|y28DqYpmaFpykRNiUf+_s9!Sl;LX*5B8g z-2kS+{>GZT_qi2@bJA&!qi`c(oGwz6e-Yo;z-p7IIuPc|Lg<4#Eqc#EP^cBvV&*_C z1Z&f+0MB>CC~ac=k-H2xB84sr4>9*Xk+VdxzilW6@3~w-6<9zU`>z6$K*QN%F>~pe z@eoYAzR0En5nEinS{T1X+$r*7sFgwq_=#HNPBvj)!ix z>+KWiILh}B@@Z?qxnmZ%h9WH?_VpqJRHTg1eQC@#v=HdB*EMj#uF#<1e6LVxTAlh| z(YXY^c5&#ormKvEW*Qifk=)RUD}fbdc_y?3y=f^=-PH(T+#VmaM^rr48NHW&oGJPM zvA#7ZQ)u$V_TgO_EUU-LM=`gS$eEJ=vE;FS#|yhiIHmTK8oZNDKJdK4Nl_r2JS~*a zYreI?%z4z;_Ql=q zw&Nviy>G0*-iWo|+fZBWOO>R+t(K8B0qx^P5~rs~#jm<^uhYHkVJGT#D zq#YTc$1y`S9Q!w}lmZZ3-R4VMPf*NKsl1o zuz#W(j|~LmH!dz>e9J}jWvNjlsH8zL`#u5ZD5h+- z5n#NH{(=D#khZ#0k7_a`^qjg=NRo3u06m!=(~1rO))(B!(!mHElXA z|CXob;?H~x{!!(oKuFI%7w-l$U3Y+ICabWDA{$d4Fh@8GkO_9Xd9I+K1mrEeM@8`G z0YjVVFmt(!)9Lk_g`gz;SFn$$_Nht20|JIa9q@yBD3o zw=Kv;aJZ4dy^Q8$zZAhn{881zoqFW;j@qwwAh=|Htz{e}LjO^u8Y+wDY!FQV7GKaN z^+7bjRDw(A;~a z-~PJTHC}8g-Le|hB@hvah1R3famuQ$0nCT#8s0pw{YtwnR6v5@m-|bx!pyzNJ@j>x zPI13Z$M3nrci3ii>-q6~!?B3CwfaXS8cj6Hq<|blp9auD z`{69mov$Fsm!6sjXCsb3e`$-0Z?3ct$)+#=HecX~gYXFfeL5U}?ennrA1`1^Xsu=MF@hS>zbGtyA&5K zIn-Q&BXv7I0R0`3bUzqQXL<8-HbMB=ZOUtc+oI&UQ5TXY&u7PPPrX*9K770_zZR!0 zpHrm2+Hw-s)qfe&fhR)?O!N-xY`k=^aRp#6wR$5NJPJ0RH}E%&dC_|yr5);k1G3PN`L-o7I;J-YjE;~XI#*(E(Mp4|00N!&aF)}RjV)v~Ov^_f9{u4JkyqFxb zeY-^}bI4?PCcZIV$InKrsRKk_SG~)&gstvc&qQ$Z-?v%}4Lj{VyCHV8xEHd8u79$= z7;by@Q$T92CqUk1HLpXB^7|VIeSF+NP)-dr%BShm9uR)j{pxu$DmFk?U8$kTI(%qP zdbEXbodaR_HbG&ccC&054n2Qa1#>SzCXb1c?}slI zOF%VAq>!4yxg%zKF;pvYkGyk6ymuGdLP=)j+N89B`G~5!_4a_~QKV9Nfx;h@S1rM2 zqJEa;Hntxck?bhHXOj}zNu^P*Xp9Iws-6b9D0EOK%(hP4X0#C3)I9CJ`;#AF`PRT1 za4=XF2(%;8T*$|BM_g!?{gfMDcmt?ARX&il+6B3VHDw8-vZk1}T>8$Q9k;}jo$@vc z#!G&$6O>lBJvwB|0}Od=6)WyT<&10p4+Smf42OBvD*A3n_{K*11*Ik!%#rllF8|7- z$*7Sj(=B;6rSD=QPkU#<=6Nu~PLM$LmeD=FI6g_alLA;hu8&7D&@dKCInnm(QzMtK z)baOV{%{^eVel;Ui#OSsb#a)KHZ@NJVB!)ZU;e|W=2cMc^`xdTN`m2zN0ucAR!;?@ zy;(>N{Le=``gD6z!<7RXgQM+4GwMiw7Z(0JzF05 z_7GkcrA?#v3?Y25Njgs&@C+RVY*CvS%UWmg+@FoIV>HVzXsCY^1RkAM;d+ce=g(m&0mPN~BQ7*oayB$cyb35<) z?G3o8eeZI_m+*J3OSLlr=Wy%Gx6p!!C``GBYp(hfLSaVuaIbpB4+%pInPd&FN8QX; z@M)Tot)0?CX7Bvhrx3VFZ0Iz-F#8O-hd1}vLdhASjLWZ999y~>R)N5J_ z(P!9d)*L7~7oFNV;xn*T5;aSKsDNnuJ;tZzg2TC`v3k5Inu<1VC$vb3n{IHo zfg@C>-I>4@k{GER40o_Z5=n+ET|K@DeT* zAR!MEEje&S2L~^ePIBBcB+^uoZXCt`af0omEI1Z!w&Vnpy|=SZ8Phuadv)8sd~eEL z)#`>Wf-jcgRL`5hC>t3HtqHXxW8jrw@B-XE$E{jWG~hB8UC$7-0*3y z7o2l2!Yp)|54!4x=kcw;E*7MDtnL6y`qMiI4+T)MLXQop$K{r2)DNxrL_Hvr>^ z+tNthv&Wz-Y8PQO4FnXc0`O0ozz$Y?kL~}wG>RP@)m~v}_#FVE;0JW=(a5)dX6hSG z6!C)nrE8qih*Q;;m0@5@*>Y#+Cw~yBzCD0H?3nr_NgzEP(ramguj92KGcxmvhniI^ zsTo?Nlu0B$zdQm;c$TOiuD^>;3Ec*X`++Q6)QsznH(<<6Sz7ywr-*N5+oYZ$=jNgw^sePP%aWPGt;{mit}*t-Bm)ypT$}%?Wnx%SF1n17yVSVyh_~iX=BK zJ1R0M&TgVRyyF=>C;+v7LDN7jEqEre!S~@r} zeCOON=79XFMSyd=#ItMxnj3}v^0L>5RbZbOCb<-sGG<4rBVwfLh!&m(*2GPM$^dix zE9oXyEI(;|#tA$gT;?7xKxv+dYD^u=9Ifd_wTFdI5*9*raH?3}Jiq75Ue0>~hq;29 z)sTpuR+%3c3q5Pq3*3*-ksWbmzmLA(qF=OmkEs=Kt_Wd~aE@Bk`0p`~Gh>+JCs~z| zP99UD)%snmP_RZzFtrE)7fWLO)(gcZ;sRLowhD&b#5bE=6E&FpUm1kK2(lR5hoIIx z%kD*8j)z$U{QcX6|9(fW%yhnOh;(_IMDXiz@@uN4rezz=;450hpJensO~ry3Za@0S zSwcFZ*cu&7&Jz>MVQKb6IX~2cF1>KZF-yOiy+~ z%`?cF69;LbrPO_61(kp+&exzu9LA{u-JM>mbm)#+g$L^#?fq^X;Xcs+k5&!!#sj?o z0N@DqD|{@y*!Te#3^&P%QEh-Q{gC2~0GI|w7mxIJM_Wfv3vFDJT6>XIWj+5`)jF^4 z6XAO**MaVkiHsDKCRLca66F3pl`~N>(M+>Y06}yWe*e-L)WdGS^e}!VJ0fc@}_#v_gFwDQBk&Gc3x&%70{8(O%oXd{-dIxDU)Q zl&0WYWPV()kwAtdD(1c`c6WJ5aHlU6t%}zN&W?4v0l7dBg9^HctGB)Me>>(9+`wzN zZthc8PRmwHUKh6ssch0DWFW%MVklQ-(xb;8lp_dLXp~nS8>vxM&0H^ITGMx3Sn;(8bCz9F!#^-RL zu7CTLx4d{vlk!VYRH|D_#T=N*(|NJAH#5=1kD~Xw)f(3?ym}8Q48EaN|9M6nF1i?T zbl3oh__as%nfd1?TE6>l$hJEZmAS?bhCU{#%f-*XM1>84hCuTSgOXzO3_N>)?&xrMu4VQ#QnY&u<1jOXVPnoOx9o1QX|K9 zdQ>hx)!F(n#vfos*dSWH5j2C2R?elB2q{~~<4PiYsiq#0Oy8K|5bVlNhpFV5z-9^+`d7r7mA&hYFYv;Kt-Ng zbo_xtGvT}dYIU~J=Sskhx)ARry9N#|CzSB@Twxr|E{kvOVb6NsI0mMIafts%PVCVjn?Wvg5KOt0cr zCYu31RXI2smXd~4+qtWsCO{BKcC7H#XZX0qEJ6Y68Ob&{o$1kbGC*LZ5jGbT=Te4v zA)CW=B5XT;6rt_6WL)~D<3+0UYdCcu6v{huuy)rN2M|-=EOU)0Lem+PI2S(BU+(XY z&V}MfB5dD6K8o_pJ}miy^=OZhpJWHl;MY4p-MhW*vj-p4P9p3!8WeA&HF;g*-@1^pBXl{KyuA6}7DAJs7EO-G{XJ83uub3 z*zs~d2P1_4_yoh?MB+!o>a9^7Mkiw;VsWv%mECSj#<6Qug#yI67@i(b#xP|@u&qq* zt>^gHq38g8w{us(Sir$Ln?@WEKx9#&M}~mN|3~zr5SGkfBM&c3k*_~If+b)#>fb{{ zS$*~Ztkvo5>aOQbVb{DF_K0>%I8`FII?%OP)+j~hLk5LGGLu1f)#MJgDR z;lUsGjxVWr?&f#sSBK%t z1>DTl)~t+G_UQ;wn;;cYO$$Hw!%FKgPc@tF*cUfqE!e0#RxPrN+h5_RA|pQOzLsFc zZ#caV)VYp7C?eE@MO6rm6|udEol1(^+m{$yncbCc`@Xs;z}cTR(6Lc*+@)Q_Fr_$x z)_1gFs)lNhF{r(ltX_17Gc>mmEc7P%h5y#+FKGAq;PN@Tx9#FsTYdNj*Tv`t9#%m ztP*uxDD<7&+3X!Xp@grMFzZaYvAH!tes7sc{k@oGIu0jxrwO?#xtuHq@a_@ll1DgO ziqgBKI7a8RgEpt9OSPy!Uy48?Smm>k{g%UiCc%U?(f>U0M_4h>e}VtIFMbB; z^7Atf;+Wtx(BaRt?vVXqqnQ!lR=jkOY`n41O$tzY>IW$c|Rqel+Q*=KOT z$8NIhbr|7SrRebjb6g}yUu<$sbUgIFy6P1P6Bhi@GpAsA7%kYQ=J94pnQK$m!wSx0#RTZ~hck2Wz|BPtZO+ziXpvhw83!N~ z0u#+Rme66Qet!ghd^oxHywD=`DfqAT{ua}x#^h{gMwfOWHaSe(dXBMQWO}|HLD{bi? z)#be1$iH9P_lJ$TM&D`D@mNORazYI3DKNc~%ILxN0C7E-FUb;{7Eoz84&ct$5N75* zUvp%H5*IwfC&0Yq4^XFVyO5qKU(vSgg3(!bR{*0|hG44Yy_E3e0E=k_1H-JDmDOOu zi~MikaI1~|6XQ9X>#nq%&Gk-;{sd7hAD)oLrT1tR4;LA56(=Eg6N5cGo$8| zZK(^|33(|J;K5gm0ycw@I~1nXe#^4>p=CGTmq1`$mOdA)D3#GKpMUVwE0?`&8*uYA z%pti(r5n3&+iF6XuW$^Nwwk$pb7-~8happlB#wq~z_Et;8xm%ak~sFbvT09!=3|4( zsp|+qS&0ih_7YVK!7!YacE3ihs-bT}YO>q3W3r2#VsuW9*B0 zy=((--p~a|S_igJ23{ds-hrXZEg6VS9395r*_r2sa{k3Bh_%9W^b6Rt2lekMV|O2@ zpAOcMjnThui&8;-lb~XquLl%BdMl#m%6sB~sR!Q$dPShT!X{QkvvS{3HWR;_cN_^b zv>^7{hoy&(n4*#G6a{EeqzSKVQDvz_RK$YkKetamW2fi>e0P$Tkc?E$N|-S%SVN{X zLAi`Ws*PI0h8Lj@NM6p68ezA>g7lR_NC-j!nTnaX;?PYCfOR=*lo~OCg%0G~(Vlmn zR}Yj@;;t_l#P!hMFqCSobZI~+6}nfXV^>|}2Kt@NQC>y}lG~c|1w~}V(D=LCOF7bH zy35T4OY0JF2q6UeMgjXg=q|$n^TMVC=pA#5!dqCCyFSts*trtU_U~}FPYg0WkS+D= z;!?`G;i8kGb&O{2t|EWNh`6xtfL9~aatOM&B}6S8_{&LwL9paFFthc1_v!ALtmXW{ zM;(pf0m5V9}@+T*+4S!%z)e zUIaG;yBHb=YtQ;Kduq2+Nn^PULeezML@Y$`<$prNDR3YC@kJBUR;la>^FWr8`I|YQ zM?y^Sb2Addv&TPXjM`8r^ukKm5J#W@(*wT14>#iOvjgTAVTdRFf-dpHbC^8iLz=0p z$+%SM<^~P+WZb`Jw$&mJJsneRp?XdbMOCJJ=hWMn>AaI=<>rtZX2$)i+Vg#^-B@m# zsFd(%3Eo?dM}#n8$ZO(uh~Ds!Y=tuhwLq1OBCk#lZg3#xLZv%>Ab~&?2+EdJe2pQ$ zlx$!bru-$+Mc|bYMtiBQrBY@RF+gaLnAoFG0;Xo!D547AuRo&PjH>x20v!gjtg^d{?8`P zKZ#6;oO+^p#~Sj@>P$T{#6Byj~ z$;7j7LRi?O|7!xXc0V0~@coNKse`n) zSWqw^7hb@VlHK{*EJg4xsZaaPUnR0!^ZV^eNYhLwk$ zYw)iv-S{-T^&EQeASO>%p3q_S0JyDsIJ$n97~{3|Es*+w_L4h59h>`&LmlfZb;Q3t zjQ4*3$^h&ZHT>w*UoQ5INu>^NZ57CDggbJD#t2dC&69!Cm|^!dz*I6mj4Jm1G+KI) zM}}1=Zqeet#NitUt<0E2^`gUNpB~~*1({UQORnn-LS~29%Zi8JC9u%iRvjX}Oq9#n z+6mz=3orfNf(M;(s7azMdz53O)uUEfn3s$aw_Ez*qhJhvUgJ1TZN{*n7?7O z#RA^7nR*9CjV)}lV1(i+wk#+_j}0O=bbhBZ9WJ`fjF@U`0vB?(Lh^juVxq zS~rNP>}qTmL~tuV2%I*|7|OoD9{Ry25d__X+^&{}cOMsT%(LC_T4{=DtWo$%yIyGm zt+2~o!pahIp?GXlk3+*~PeoxBVTQJ|I;O7r<1e#f@JlbiCp-!_!R!FaiR_fPeh(`ndaVV&OI4JyBS}H4= zr}y#o%Nr~HaWjQq91@F%k(4V47w6!G)D3NTxbCE`iyOzVDR^XJ8!2vUrG8Fz_fd@y z1WVMgEtvG;VWGwb5(M%q@09AOE)B2F7razD4abr>N`w@YI$?Ud_uW)I%M2$k5OPE7 zaHWI>zjR4s>-&R9)Dh%}PAH+hNr-*c*my?fT)nZR(>GyvoBtWlmm>#KkoB(=TTP%E zJ!UZg!#?K-B1Qn%53;Wiw9hy*`qsW{r#S$_Q?+>y(*N3v9KTj8nt%^`%v!q{v zIQR46f^JF^z`t+|px&>ls(QV^80okr_WW-ZU+v8=v7gS|5=e^Z?CgHhLo880d3AfV z);IS8msmYy)18(yJ&cd}{*t}-!p3ThA?N0wDGPnvwQmkkvysAZR>C0S@U(n&YQ;pa zpPklRP%H~Rk$fwoMH4QdWDpQyj}==0NL?}Leya#tZD*41ek8K{hBzQ-q!@oyZdmAS^UIJ#J_=0Jqh*k;PiefFk_$FOjOCD6R2()O{isms zm!0>e+nV0%Vs+voQygRmQYF*w{^5)6P;mX zeZ--k<>WRnYZ*^7nlY!EWg;oSvlJc1bf#W<$vFbzX&_lN0VM=)o^)cOXEBPVI zNpjVb{Hiw=hH&8uq)walnC(IWJ!dp#z4*j}LU)fHVxkFXcVcme)!{Q<9GM%Bln{$AVK8WTt_%XZkkUFAEe)>dFuMoBF z{rHE@x3!DryTN5N6*R&WVoU@^!I$b>k%~5jf2oxQxOAqYOsKegW3$^DNKih@>!^yM z{`LzolmI$x{iR7Z%CohMvXkQ!6UtUJ}c{^G^!LVaqWSs89F~M8Nk7C=B!3eF(Vfc5^!a`MAscejl04B2+a5D)v z@~-dTl=Q!h=0c>or=IT*7=)MqY-}0hU-!P2k}Y z#=G(UbCqbkKq?o18yhJ)0KCzn5;=+bkH4e%iRqWjE+X=V{ zl#(nYXAwzC_4#+)i-hbe_>A02WHIN?PsWiL@+5RG&g@(r0L51*9#@w0P$nRDy-}7m zjj)x<6%w~b(W6j|jW4$Ri6TV-;~?<-&900`HVBc;E-R^v{ddvBA_Nb(YY z>Oo8$_WNGf&S%dM4!}Ub7)CHD;C{GKs@jD=FlRzBU4j$VR(8R*cC*qBjRzFYtgeWw zfw0~9`H)~X9S_SoR9V65nZpmF>T&-YRl;}n`pnehL>|k*le#n1%!2DMi~hqbp!;*y zUVSK!dWGoSmiAg4lMfvGnuk9Bjl|M(@xvtKSx*j!f&5g z8cCo?`1xt*ba3PBHoT%pA9N|NM0Fo8sl1Wkns`aGp@WJoGy_>BF>@qQD_Sk3me=xM zB8jDa$NDzk+UVs(p++icMlDUycx_Cg(SG(c4pbLx9I{jq^$|+*jFXd0TZYihYyCs+ ziYQ7>F^)6`qZ{yT$;j1rLm|Hx*Ym5f5D|ka0MoMiZEz8Xs~z-fl`@1tY*)(so?vpU z5k2LS1c6psFwr0cyHz0vSSwGYUG{HtB(3LgKzvu>WpLmIpKM@9KZEp;3$sWmn88}> zB6+$wS2`GQiwBq~@e$Gq)pO)kbR~R@0j=nPyQ)uBao-W7mDW2i2=` zRn-ZLDDX+;OS2)S#)?ivHQ$C)34FOZ{mi;M*n;wo3_C74yP@Uq<}YiMjDz?@Y8fn~ z7RnBq5(AvLrjnUb%2$KP9p+e|$@%+D@v7FptXE%4O`33u^-J3_fiakWxuO6zxC}<7*wyew z56ns4{F^K~H}+v4w8*|)lcwxszG!tEG-y`!=ZfC3%|v_-&rSyb3OKTgBEWBsVJ7wu z!?e`FG#>FG`HLx206f0=fae?vPEIKhD~9-)ta-KBo*`^yhh1ajg zSL){fqBbBudLGHqXMrxo$v`GYmXGa_lNkOmg6YZ@26A2*#`;=Sz9}nb->&`mv}6j5 zhL@f^ojKU@c&^!zF&4h+-$&YvE-AjiXuPBoQ0`z1P+M}vFJf3Uq-fybGVFI58VWLM z3SM((iziu_7sPv)EkL|4j~xQ64~fWt8b=~drzZ509M8t!MJO@#Ac@64o}j}~-kpfM z7!7;{A2VOX&?3*=Fjl82q8R(WlfQrjbhP2<1`qec1Yfl+pZ(?M-F`x**T!J+l+@s) zo(CBWQDNhsthlr4>2zl>J1bhTD0@d#Hu13hQF5W4`U=m$>1T;o4Oi-V4>YIaHFhyg zFBEJ)V}{tLZ}~U;=p8qL3xu6r$@@q*gQzJub?IrTL$&2ZohKRXc^yi|)l%++KWj3F zA-9b9XvK;$1U7{ay>eDzx^zNP<^QE1JSy#WinsqvYERKz5>@ zb0{cPRuLOmT$(j}FA*~pFV*?0cxJt4Qd&(HYc4?^^hoGMtF$5wLnjsFt`3izzO)p= z3)xuKoe1pGMY=x;T{8l~_CnMPpylTp_VJHz+kxB#oyf*W08>D$zp1QpqB0ftHg^=j zg6_o&=}e-yJjDb^oRbfF1wvr-!HlkkxiV3wC;cgrs~7iE=zO~v9GS87AgveNdf`~K zfU1s0(v<=MrPoOipfhdziRalodoS*rm6#@<*t4+1s4GzX&fccj^F#D#H~leHQxLPu zgz>!j;Z}$!rvEi7C`gqeImR6Y8ISU#$>@@ow}TA7fMs?kj$H?K)K6%rFS@Y$EhJ=k zOgB%F7#kPOh^hS;4DPT zlTtd8!%_5A-QiRVC9~HBYZr=#E9Hb}oj=VnmrKvN0G;^UApogE8fuy4Y?FI!eiGJ; zrX7#_U4pgdv9=g2?$~9yLq75q_fpV504M6YRy^#htapLa$*I!gLi#IliV!sn3c_a2oaa> zB;4kAlX8?92xO+t`rKy9`MsZQUY9x_sM5J^)X(VDs-J2#3qH-|Qu%x4;W2p;Sf2OQ znshL(qeJ7MIXp&Y9tVAuV;Z)L!_~)Az4W59tPvTHQ&4_}e^KYV-5VQ8UWr9vzvcjl zBUclou65mePRQy3O3D-v1iKA`$0TSZ-5;9@-<*6tcrDzWo=tb*4t(nGZ zYyeqWvpQ2332~&mYHqN^W_{VFzLa_=o9qMo&D=JEtTpF`aDPxk7xuUSoTY-nOS1gv zrW};Mg3F5G1TpiD3=#RQ1}epsic3Fe8&Z;Yj~jER;X~e>PdY_T0Y|CLYQ)1cxTn+j zIhrzJxgWrX>7~$^!|pKZkb7fIfo_VN^^MZeF?e&KeXEn9kli?P1niZ1BVH8Dh+oEe z@gx0_Y6`@8o*EdLbl@TVRs2?|8`M+Np?VX(B;+8UCo0W?q3t~BY6>Fpsc!B!CI~dr zbp!ub%&gl{ewqIE_z=L%cW^_(bW*s+K)kg-A?$7&eFw9u8D5Cx*Z9w5zP*~ipwh(Q z=?2b#>)b7xD|vOwD2zjg{C%@7R%$8S(RKp3yY-)MWFc4pgjy)&nOk+{B+`}r@hv9V z#edS=gj<5G_ON5%SnMt>=KJ|JdkD-hmed_`++??C31b9d0I(12- zBh08OCz6`j@9v;(2Ay90B2V9Orys8UPS-0~F5(-X`NrDA`5Qs$C#rcL2Zd2VcJwSez?K#_1A))6_tyDR4Bc-79Pr*Rp8wEs*XTNojGg1Y!+p z;L>OB=a3)wjfuOTu}y1DUIUHyrSpa`#3_)G;$Uqo{}2?Q0um7_UGXD52mk##{c}|$ zp9gW(^rYc;-gdL`f4QT_))1-f1#sMy2sf)3`d7iwhEg6 zjHNhLJ`3(l9mrKZtg>&0FoGhBSITM-=*EQH6A;8E>({RuuxCu08E%|eiu97My-N`@hnteK1Cw2Oj*F0eK0+mKjKRKWe zne_b#$KuHKb_yF+1xqhh+#v?RTvb~138uM&&9idI1K^e9o3R~)LBeGfcL}LRY7%sb zbJsw!gkTi{!Cax_W9L@(bZUNJ;5TojGl?3=YJCFuk`Sa3L1}7CZ!@@1S@A=beJaE$ zW_u#P5@M1e=DrKdt%67c+}04x!fCKM^^rpW6BFr5)w$MB?qz+mVyB3Fv3Ygrb_Ws< zNpE^+JPf+dAp;zm0s!pA&qVKVZt3pAZ5%VOqiq8;XLh6g2M{ODAMVTx`x8s_x;s}x z;ts9GYX@XV1cJ*W_vbX(s5VcYCp{IT+P+WUI!~`2=WJNoCe)CU`K11ey?^S18|wCDg;`z^UcnEhPWTiJkRQDkyMs=_6Jz6 z39m*Eza}ebsG1&|;qvf*06**LO<7H63$eGt1LIa5^r6IXEGR2w_1=GF+S+)Gi;y3( zwBkfYeZ?s^wd!vycoL&zIzhgNCKnl(&Mh}(V%b}GO&WO;Uw>02TfCi>ZIIxj%uIzd zBlYBeXodT3>yNYr*njIC0(GDf$KBJND<|V{JD+5k)iz|FB(n_2g75s zUt8!Mo5MAIK!f_YP@XRtm03|z0NTeNhag}PzU=ZQYQ{nlFt*Q}fL8orQ^3g)#39DQ>Tg6!ai36#`nF&?T1j65 z8>#ti=D$e%E4#=gjhxmF7R~kU1nKt&JID+^j>6JuGC1PV0p;Bqu`MsTz;ypVqEaCG z6HLS%5FoA>+qEj~wXe}PT9ejeT&Hq9CrIZ~LIQRc(2=cS{Dkw<9!&By$J;Ml22>06n{024D^ou-6=>{{6X>jWLFP=?v1KtT&~ zfUV7af%r71d*GPTy!5rti@pIfb2P%Mk_~71d=(Aq1X&;hfRi-I1Hf%qizJr=avQfg zfJWZ`(xKBE2t>D0I~C_Ibp__FJ_T^o4D+S3hlK~e>5!~_43|w2aaZ#+(y}Djqs=%W zdw_KxmX-L1$$YGHoZ5gHuJ$IW9^fz9PKUcoq{hyQ zPl@Q^SoK>b%2_^FMs}hZh>ABjMZu;Tu2UKi%o_`l6|J0+#yZpI;GEj+e?fzKzdqzE zwH&Po3J1bTV$q&*j}`pu!S7u5lvZ>xoa-FAe-rnRAwX;rG8XOwJ>lYDe*!m*-AetiRPi-JDA zgOam+eK%I~4f5~x0RAr*yV0(YLQ*M!cnTa-^6KyjN zYy=O;B?UHDz)G%{+%P|jd=cC~KuWKDm~Ma{24M!oRG&QQjL{>cC%tTncRphdXc5Wm zfb4bx=4F1f>(Eql$e=U1FUc*h*`F66;2!OG#i1tRb>z7?G=lBskC4n|GjD4<_oj4x zCR#NQQ&P4$d>MtAWm_6!&ic5RfPE2-igX4dOy%{SJO+oEXp_tl1Pdb^sGL53#&Q%P zza=PjMWg;V?GeB1l=C3+YZ~l4f!||e0-#71A^%LEJ>!S75>d(rW(>~CK%OV(tEWU_T! ztuJOam}Iq@!5YneF>UsnyxNK~m?&%>pd6n(eYXzT@*Z;N3#Z;;+zc4Tp1qm>J?MaNx8xS7}HANYg!+OpX$ss;5-7oJZ3vfEDnV49f6u; z(6uWQ;{j)i_@Jsn^XRGk0g^Dx*Ng1{c})*Hw36W-V#SqXLutiCV=-wq-i?Dv0^ENJ z2I^j`bg5pWE=|JPg~62x$L#7Q4PVyve0A}@R#=Lz6`H-C^NKqUt|Bj?by{p(6d%xB z1xTsnOl_26+u(>}{ArOh=F7Mut-Y+Jy?&1b%vet||5{lgEvEy7NF0k<&<}+&(LfG0 zTfk7u(YSiF0*^<{NSg9>*D}x8uec?EZETaxFUc$^F54Ol;-tTPM+v%PR}NI!PEpvq zc`QwaIg1{Al6%Clu^BWl3=4G{=7wN{Xc5WqUJaL0=BQ)~j6tp1CBmES=h+-Knr)+p z`}jOi=TAVglGojr{nGk>&*Re|oc5ROWt&WoITe`uL7Vbxu&p?a_?^hqo|!`d z_~g{0C7Y*ZO;}d4X1Xv`N46FupNo$fvixnwkxIt0Lf1XaZq2NfhFU0Y2m?Tol}>dY z#96&#_F>N)xma4ruz&rL;LTwZ42p>??XewOgjzxoeHa!NHtkz~2XTHRKOa}nEqj}| zN3Kod50CDcX}C*%VjxYG_+-vRe}q-0Q)69G1Y>NR-!#Va#J!MtZyYjQdhhE#cfkhf z3vWHAx8TaHWiVtHTr&TKvt35u!8ug)I11{ADuR^l6cXK!SE)>oZ{KB166IP4yif|2k3tr-4!3ip3t1qY-33|5=! z8|NlM;(^K6K;?9sPh}qSV+==X66Y3W445P-u{gKGB+--+>$d>ds+Tc&-Os^dI; zqId@PsNdm`w!x*%GSxEKpCPHvO&e7cY5w_+kFN3NgD6vM_p9hOB^4sMLfgC&YxCDo z|J?Z11F=R*^lc-hNGJBQ+(R_40Y%vrD8yfAdakWp+fqtv9_1$k-Pr=;Sj!ThuW6S@RJ3U1h|Bivzxx6=VWN32rKbl09Ul$8l>kK7CQ*^N_Aq-tHQb8l8J~F zvVjZ)eg}Qd`ZW+Le}Mw{Rn%d201m0>IIMBZ)Rd>oj-BHV|H#;ma5GN_o?2>{>WuLj zNuh9q_MBcsTnZP^p<6OfIOk=U+`R)~`03k-caK`Is|9l5$A)-M)&TFct5dwB;!@VD zLgw08*F~Ar`m<=<0@+$?N@#RK64juN?A^h?16)vjKAOuPRyQMN23A#LLw7ul5BFBX zeB1W8$}(UOS;_*zXP;DPy#`X+5cekBZ$y<&hp@L2O2B4JhjKLb0=VzmE&^GKVS2-!73WbhGA1>g-F!3~^M!)xE}| zQA82056l4evCf2NsdOd-=Gp4DZ{xH&EEdI9-x0W-Bm7`V4vx=~@wxi0>XI`hT0{&c zdryB=$SmgM2vYPp5f9?4qFhI%FuCWCRPhw-X4K{?vzMv;qI&@|YBphB-}v#A&PE@7 zAs2KF8sx6M+1wY=ke+(;4m1-m)1hYjv+^8Bm*?}I!;<@PnZ&65kbs?o`g_h;o=$mc z@z2Z4PZvhL;r!Nj%GeDwYyyGpXg{Hg`3={wS5JV!um};EMD_t-v74Y8Q*xwNYihcOz7SzFfZ<0|8!LhyC;V3i_PrDA%dqinl0f?M6i)mdF5MJB#{`Ghm*6 z`EzM1pa?SB;Tz$$H(6_u4&KyUbhKLNQ-*0@cfwEYoHSWgaD_r1A2Ea)6}i36*K9>^ zTd)>5XSg3gVn9YX)p1fsiL1Zi*$B`!MpOvTqLuuhL_0sNy|#rJww>)j9wGG$t+^f6 zuYU#1a)EORzB)2uj8FPRr&Ec$WP6BJ&2SYv4(o!&ck?-E4NP4p{Ku?WiUM6_>PckY zOiLK2%yeBQR-W8w%nas^Rg(K1jUTdaP6l z?QRYT`p!5n0Q+pmSNCq;6|jOxPuX{366J=ofZtA=q?vl2HBZ$`Bq(OZTlz@Y%?ene zRPoR?#0-bz>P8KZ4?&Wpdaj{tsCNBiE65C&FJg%Tcjfl`V~Wp~JVZF?r9Bg{VFT3y z@OC?&G)Qbsl)Xa8{Q*X}%43oLiEE5F16olM9|gQpO_z-x#Y|6H&Yk9S1*QTvleC~Z zX{MPsR7=ZJLg9#>>Ka(cP0Smk8Wd@cT(rL6Ko^~7X=SQ!&p4l=3GP`Vcru5Q>r_F7 zij*0^fna5Sj?!~TAk3CxVY0x;2Ytma&`}4kCZ0F$AP8WnRH|no(9Z*ir)?tIC&BKr zMf6jd3!f=3-#XNBNILD8K(z5Apg<4`(p5U2>nM%NSe!OEL%H3B_6bPp-?Rx1YxfN( z(cr}rJsP*y-;WOeJ~MJ(=cfk>0&X6OFq0Fm$)lM+wKBL5W;37&;Cyoz>2FeeDU7wD zv0mKGXk+5~n`_C+mC0gxyQTF39ekhf22l(PZPHFTG4Ep@k$7v>;!nYq9JzI~bm)6D ze?qczP2Vy3#RL86--{SHx_)G?MWlB)(_38?Do;CAp}sx@>g6)+kn$#iFb7ILeM*te zV)+?Y+Uj(J&HbM|6=CawOv^x160^#;V%voduut#OP(F8DNm)6GQ^WTC%f;5nw~Aij z$0H&uHt7^9_qJR1pCk31N`|7s-tgpdw@zrXgd|>Nj79%rb!N(f>?&d1jQ%GEtHPSQ zmm8-Nb-_{>>ShkVj=z2r-I2rdfDXL1ffiQ9KPq6j#xI86E$_Y-D%yv7PUJ>hxpg^5 zsW0q!F|H_~6Rub{W&xUO0n@hRHhx3Pb~;U^kK1v@x%~( zS56Oq`jp=KT*vrDgvd#mT!NMH=9WKsHr!dBB@u{Nn*b2(;AVV-)8^!vYpCy#?~GsE zeZuC(*Z{2#Igjrj+j>;bON`tp{&Vvq*Oqh_!Et({pGzdTbKH|8{2tIxrWN8NhazeZ_CRj9s&)+_ZJVz44{%!mH)jT2{718( zg;l-E!s{vnr9{;Pr#$ldL8uIy-Cop(dW&9 z8p6KwoYvU((~qhP=65e1gVTy<(>0T>W|;by;Dj>lM$T^nKAOrOytAM7`wTcDw_A2} zB}i-5yMNXQgQi3gi<4`rNDv)GwF>n^!g&Da{_q-6202FBkA0`^57zkR!?j99qba!F z%|NHPzkAN2wT4@8XohkRD!KF8fX42dE1EpHmkVaIb)&wFnlG(%8IMNWC-2K_F@nmV z2qSp9lScSoz|nHIR}jT2qMq`bJ(4C`1jR-H>TPl%f^pP)3X_Lqhdck*=X={+D|LlHYKGO~7q zUU5~3ss#+hr#x%3cM3JNO@Z_xn6@;0QfK%k-CfG=kG^j z!W#tp@1&KYmT08IVqs*yncpVB=@8R)s+?B`E!UXyzle0M z+oO*#Od;T51Y85@=g_CVd0k9yuHz|84I=n_WYP$Q4vZ3g5_8muBE_9n(iLJCtskI< zm7TOfRIX_I?Vz&51mP(k3(Ild6wovXhO=pX!i%XVwKWKUG`9Eukk8B$UPe#2+rO(& z+$WPGdT-k{w|t@dW3a|`5v#IhH?<#d5IskaVwg6r$HUE?4tFHStNr%Ea@jjo-LGN# zD@1phG4Ya7aI|K={`^pfzUkvS1BU|wO~)9WK&sy@3-YjI@}rce>wlpeCL?>jIsQ#m^~o9PGeNy_8gs3hJOBSi2A`m-4%4G^lL zN%gN<>wSo5%9N)$vt|kQHV#KL6FZ#*Oq|ZO-omZ zi7#K*Ji6mfSMO3w5j39qK^qx38ZJdSPiUF7{AA{f36HUG#Lq-HK&J5p){o(UaRo3( zdV>RaZLQxS=A*fzb)jKhm4=3AMMl5-*bgv8wqhm~lMIGm9?CI?j=Tfy;(kkmkINDR z^SM>a2gqnh{Y(?M8A~E6e0S&Ma!FNmEWyki)x?9|i-`T1>DLB34I)~KEql~Vqjd}- zR%cce9=+{u!@n$5`9ZEK83xIAju&N4JS~*sFck@XvOCKxTaqO;hdG(NdGndDAh&ig7>~r*z1Htx&@Y#6Z5f zQ!JrBI;6pgg#*ywe6WOmTR|lNTH{+c3&Il+{bdbXjOa~>2VR$JzXbfAwA}PM08<16Vqrm% zB|8>3Z@~{cQMr+9FwCn+nHSrHO1jcoRq=AI z>P0!!RTEyK5wcC2mdC?*?_8f^+>A_uUb<(CYv6Xw>(FB=LoYQh?pFW10n|=@dWJ*D zG6E`>+$Ic+jL)|EA94N$J=RJ=H{E1QpWf|v*pwm%<-BOYsKTqJiLMnq<}FukUBn4M z-sIIC8-HN*Yaq9}5bYCC0;I?>ZqZyB+0H@&@)4q4ubm zLyU zNrzJgax^S|0b0t8-0K^kP4URK8K-P+^Y^iq_r!_8Fgi9M+{m4IQ9Xz5ckIvp@p*{P z*UElNE7zE$D|j)R!ctH6X@|Di&^irIR(0?8V|tFQxUq02Kew@!0MuebZr2NF>!C?T ztkVhtXwCVD`6M!B@>2DX4%;d7G}2IU@&l+Rd%MYPeTKs#qZ2p&qAx!-W))3}4* z3aczlE$=^*mp3#Iuxa9LOeLAq2lhiS@+lIGU>jaPfFnjd391M`R zkcw~2E#cVAd5L2Ryd**j*&=4HI=i=l#jvFnH|&*RXm;@!sbXu-SdzDA$oI%xztcI& z0Lu2r%IWCbWlsdL@va4wH3D&vOB8QpPY|>Jlle>{@0OGQo-}`KQnP^`UMF`HXj#x# zs3R!_r2I6O*MXsRRg0J}!&vh)W>IDOE`i@j%C}jTZs;cSn@zYbK?4%O9i&+94v{^w ziZQjIbPaMI!ylg9^r=B!)n!&8x@w~fmDV}2VjVN*mhpnf{~jj&=mCJv$-**%k>`?3 zqU=dm%#UMOKlhVVt{AjP<+@Sxyms8C1F8^OREv>zn5^IWkOE5Uc=2-O5VW9`r#DZ4 zEnL61d|NIVKGIX&eD{*1<{WQUeR~_ZaIE5kma?xm^x zP`?F}9I&K?_6$7|1d}f3QK>r!Z640WzCaE>H$bnOYV^vnyB`@xiYlwOtEFo^LdEna zMdEKU=2~+c+*EGNi+@NUiIEU5?s}19D0W>2i23kdJQ}x+(uQBNUau-;&kWa7l~^w& z539q;U+tZ@Q2o@{PMphg-6a;Y0Lm423AkHa=)wjHQ{;U8{`XwSMhDt;k}Us-72Lk|8pW1VVw1fPwzF?=fPD0)3V& z1|zFk!MGuG5=K`(f$wE6YNzqll`QWrj{hghRq!@MgF?*EVAyoJ-1}S*fk6#$NzQ1>-5G0cfoT9+*KFHbpnw;=fBVxgWmJMvq09s)1hBtrAhgAinHg^>dzqVj_1m zn!KTYRN5kQ-+@9g!*^N7VSk1M$V&?wOY$bij_LcwE;?ZjOMcxAgF3DL8yqwGs=voQpvSF)s^0 z!XPhnPEDWWFg3KLHCXM3#tGB{zxAAS4psX-do~uP3V@u|Lke}x@>#kKn_hny7I&3N zCpNbl5^N=C)0s3)wb?GPqD8jm{nuY4;35Pzm$U)W_~Z_XE;B0t&sfEw_e zbKVae7{kl+C^Z&Y!TWYxx*xB&-On>%TlnQyDsX5XTfkUYbPf46?KfIjff+=>xiu9w z0(TrZ6Rd_UfuBa_)QMFsgW+mgO#c2>N4kwp&@K>d3AZvNjrSc>8%OY z?3Fz&+@&!Ka#Pp9L)F0}I=#^J^hfGPL80M^c9i^|Iw884qn~g#A;L`+i4wZAP1044 zfpyR8QJ7S?!}ZI)W*1C!MHY}{FOK}HigxL9c`CA7Ngo}6mYE8GM?j<{p|<+w(($RJ zyYZRvNvwR6)o2ga5pGUEf1S>3XT?fcOpP56nJjCH(YgitWX1=lrwI(y#!V|%c6SIC zI!}XNn7KnlpRD>7ktPa{UOARG4u?=*U~5VmB5r_Q6yr{o!j9UfxUQRWL4*70ysCe~ z2R>hMgNbF$MhH{rh>f)KYc zTcXlpFtSmpdv~X1x&Fcgnk1%(0?{cEI9B;owtUq+DMGR(!*UG(bM%16L;{>@pLf09 zq7ZlH(2ECgRAh7erg7bKDghFVzQwp4ifG&C7n*kNR*kcDKR!_Ubx?L~tzRA*To7dJ91$LUrr3c%5Z3%V4 zxxRVAc7kW!34%=3HbfPC7x(;=%eUXMF;D9CWq*663SAXBtqB0aQdFU!2S&I?`ufiz z5$16{I(RV?Z;Q#N}p`$7eO_buzRctXv;VslO+(HeNSXhs8k+vWj#y9(mZ04`AvwFRumA>7lsG2O_4lTa6P~^{n!beYP(Kud z(tI)~@)KJ_^8=viYN(^aCULP>pXhKx8xnckF8@+9<1j+*Z9fvO>Os7;Bg#)JD@9<; z91(2?Sq;w>@mL06O2bm);2R!htD<6`>4bIn*n$q4ozzX!-pEAPdzYzMis<}oWmeX- zZ_XoDOm8N=`xVo`bHF2!q3{owUSv+YlN`#z*s5)kzj?`)q8tHV!7$*8>P9i;}QNBGx14 zsMi8xOGQ0K&r?lAO5hk=Y&fD_YJ8!$X*88{7s4glj;{`M^NjeZ&St9Po59#UIV>= z&md~=0Jd}z=KAJ@!6J*kUt%xCqRh8P#g()`HM%_OSJ3Adq> zd*e|a^WhUAf_nVZA|+%R^C@7>W8cV?Hhpf0!KkQRQh|a|-ar!Qf#$tBZ)wydmB!f1 zrS3;W(cxFQgcQ)ugQ&lQX5Ghw$rIEHl2!EqWj8P1_MbUkNHa{4-ZAS1pr|0|j&9oj zDH2f|RYE(6GfQXAieGf8?}U#)JluKzMJf07QO1m)q$+Nn5E8&GVz zpnZRoP%ZtavOdMt3aCZ_F13f?-1T7ijOs9%L5r|TKdZ!9-fsxN>${+4(w3<~k!nk8B(N0l}Mb^JlPwZTfSqLrF$#X%h_k~5D4;fg0EhD$8U4*W$mg?uA%s^28P3;+hdCD5LeC!xLo$rwL4k5-$s_7fL?(eaikCsDgngoa#8L8xwrk=K2B|@;+1$0C`KB#235$I zZT{@v4D#YEy^Y?9;XFbjpk|+ExZH;^HKk%nj1F>iQPk=16k>hHU0b<&)PGe|P|kaS zx(yVocm@5mlnJyWK%Sm_REpFw=u^z~m+4 zyE`vQQL%Tg9oDe_Vzr)}4y4zZpVC9%=rG{Rh+ir@m$?1=s42nE9JQS4#xvA=SEJ4k z!2=GxS<@-BxE1f_P!V}mF9t6J4+F2-hNV`|aX7fL(rUt_FElOJ3DCA5 z+63s<04byHgbSm_VKA;l$|;boMFOjsIUNLmJHAmIo@ggd=v_!UB&AQ(Aif?V@g#Zl zeNim|{jl1ZMk!b;zsxPkh90#=ceP#;BxeL?CQXqp>OS5FNFK_Pybj7{tRqQ9gA&~t z%8|O+qZBdai2()j@cbF%t%CzII|3ApoN$F$@)|_$ zi;E+o%A@m5y3?!-_KHl-tg>YbhXuWvePiVtxf0*@VwfQfnj>JndJo=S6*Yv(iP znyH@7gu5?S7GIPoPX%vGY#CoKt9V^+FC(-DqTxR3@62o&%s8$dR$Z=h5@f(!Q1}vL z@6_FzBX@I>1LDAFGxLWf-qbqd>op27L7*%)GCK0WPVaHAg)W zV}Txq^z_ZkP_p2u=|_~5|KXcSYtY~AOs^oXGg2hE_U=b%k6dfnSweBxiS3*pDLaGS ze(M9t2Cx!?0+zC485iZp=Up-YPu!t;Sm$f_aiy6Ff8c}5_o$fdWu#i@wIsGh6yY-d z|6`lWoIMBKzT#90BAUwc15{q_8zqVYJpOF7-Vgiyrd)^pt?~*^ls2ctK4d-~`*9HW9 zsj9G+(O6R1BMEd?gwK@o`CA&)jT*{!_AnumQXO@Z!M%|{zn@(^bqfC>R+Ieq=XXf7 z$MIE`zF@Y@UV-}+>el&GdSby`lMM2>)%W>afmC8H0z@}dOs;_dkA6te6~(?6cbAoOD*z)|-Rj=N&ul24PEo-0RAwP{2 z{U-1BFC3VkcKrWWmPiNGIv*Sn#~3f%{j~$}aa>SpVkb``8Vh+f&%vLT^K!5IrJzh! z*GBZkQazet&SrEDTXgxm*tLVH4q`u5*9X;IXq_tIHaO;%qpA6u6e%iYOr%9UmC5#O zOh%Cxe1|VwG-3N1n@DN-ZEodT{tu?QeZI%)pAJzb1T@JiYa&kKQ^P)NSC2D(BN@BX$|l<2TX*Ply~m@2WhBu7z|k z{h#>6;uPnJ4^)GcDe=i zL=S%Sqktv=%#3@K=Zr87FIJr%xZyz>shI2VNTo*EsyfmT)o;N0J6YVWyI1NG5zPX1 ze*Wq#Bw_v@!PA=9RrY7IoZpQ4dv4n>08zHz~d|;DnQy)X$|h-TVND9wOQraH%RSr z{&&9^V@X4qOUd_K87ZIh=mZ94_QryirW(n7B9jC=mnGGA=1Zpd1(=0W^i^guBw+i) znYCfRinke=7{rs+bYKj~9wh7vi%)1EF0muA{t z|0%k50X13h8}jufpZ28Yk^C%f+6#pRBD7BD0JBV16caLg)AG6c;o@^E?@9(Dz{+kK zM$hkbOz4qLUQt9JYWJ;_S?4*r=$Un9Q-EPIp{cbP9lj=VE?mtt|NR@#DiT`T(k@@v z8h^GPLB6Ax+mTuUy_3w&QtOz(2P|j7|)g<*y>&3AIm~nbC z-8Ybdj+j(WMEmA~3|ZV-!hElb&YeL@bSA*`chPlle8Y8cZ&6(ATSyXDH1H@+{eh?* zkMA3QH&d<|6R`3B68_ex@Q>kGM()YU#1h@$bS49I7VCdwGz{xZ&j~A8uEkw5XWb?p z1?IO9ne&BDT57M zQ@=e%OvBv@ObU;dxdtTTd$7x+guRqRK0c`9FV4V;5v@7-5N|Gtn4^?$0A$w;O-z;x z8Dqw6t(V+OrFM2sR~V~j0tOSMOgh(&D`JTWk7*-SrXl@i9S5kbNH09zJnocM; z6K)sCTKPWkS}bH6m8Q<}`rSHeZgY+_`D)+*y_&75H`b71B-#qz;tH{=gTt0~23!zs z2eo~}u_E1F?|z}Z44{PuXikd66#VS(6WUYn-Qx-HP-^bS&jZ)`Z!c(iezBa$>&*2# z{;v#U@#)NNJ1?MYtS?pNjQDT8ryY)h$l-5E z)9em2R=uOKp4?apoHxp`z<-yV1|pHgbbXn!T8MTz4{MV3x5Xy-r?$7)+_q(RXsL;o z=%1-`>b{dDHV{DdtT02Ns;pvePsg_yT=G!N?J<2rJ=8(^Zu&C`VDo7Q)Z1ZJ`kuzt zS+R;fc^;On30*!LfIiX&g?&sC8cB;4qFgYQXc*0`9^URV99j-CLr_ux()m<(wDHNI zWu82%JRGi8YM#7K)G8LfZ;wXi#KsF2hnk@hqlHiIjPmYC`b7|~tmoOg9K5(YB3mCq zOR7)XK668h{*bRa!Ueh#(0?~zQJu^ndxCCfo2AYT|AZ>u1J~ z2Ne4%t=RQMTx=N)(zbg7Qq!bcS{cf&+P2(>I1;$$n3OJ;`XeegJmK4s9{3v}_^W=g zaonj&9io7n_Gki^WzlZ7xabbIH%rV;SJ3C#pzav{9F_RMI~r0PfwYV~IY_jvv3kPJ zK5jgcOXskAJBcy+kGx5QRGg3CueGOURf}w}2nVE1&J3J_>pncEq|2ZOyo)RoA|KcV zFB|+;wUMpu7Ic}_!lvu(VX{Jw+!-hs;0eh3Vx*=fb%OjPnsN?tfKl;2NmX*hG+F$ll4f^zky{@ahLW(MnFf z8Ne=e_)*t60fy-r6LD}>cU%|2GOvnZ~1iPg{1B#(qoD1yu19Iy&y1w$+U7QoMS&*Q?IA))zL!Oo8= zww|v_8_ZL^<(N+mP7r>?U~mQj3-g% zJGRkvsG81LZr1T#-I_}px8{R@C(r$}oZ~vxfj~qzD&wM!8?<0E$i`~pkEd|`i098@xa6hj;7KRQ=w| z%zl#aRmZr&BtfVSQuuuO)6IZ5fAb9ka`{6%KMGQ7I~M{e*WZ>3#co68tDp76R-<-f z8A^_!$JTXAc%VU>5FAiE^zR|`bv0mXVRVTP(|J^^DD{4$s#+XQ__&Bt-N3)ZL$)?| zMh#DMj6Fi-!jQ=H=$cAf$9rgy_9FQ|2jfG6#t*9>wKBkZmo9inCmP?)*hYeswTaR& z)-Fp%`jRA;3wFt*ceg%Rxf&q9f&vK#N#my?C|HlsIdB-PokZcmYi`Ht(4b4j#j>xB z77?sCL02cNkAy+{iO@eL_FyuxtSq(b|3Ta`;m~u~e}XaBs}Trau|j$K<+Qzhr=oS zj!px!6TnEKiEvZH#|q&>NgOuYMyitzyLGudt}MPA#jQH)>W9xs@5sxFe3KtsZ+wpM z@imQbnf?E7z1^J7M7O3rw>N3@e1bNGrp2(P{jIiADz{q&))X!OIZ4HzdjO8XfOd;s)IZlqL zXYv5|ubwQ?<)~hj=EkE*?U=bZO4$)GJvul802&u$VZ2W8LctrDk+Vck<=55TTu{~X z3B=G)%`xJxsx?oaj$zVBP$+LEX1#gGgPl$_OJ?QL&~ctm(DExcl#?FRIPC|a*=oaF zb&kTbbY0S+dZ0RoYb(%T&J~z&H8)K}k_lHn1S;C)om<368nT59`?Jg?Ak4jc<{&Cg z82aq&YO=;SkJK`$;2%pNaVN2{IN&G6MG|`$L8p@(-vZb35I2Y*ZGpj^2M@^1r+a@@ ze|%sIC?h6A{CTU!Cd6)HJb^UIf@~uaCvn0UQ=ks}k6PcAxx;>On@S2T0y%GBL*B}SwTtVuF$o<%_7~r7Ix&E5|)`+G-eDL*PB%a<8w3= zVwLvZnLvr6)Dgx-X+qAwl%;jXa>N`R069R$zuwzF6Bl2}&?NArszwo3s(fvMzATd` z$wiCKK|xgp%YFY!OpQnKMzWH;bVMC!bVyn3dP>DmJjg@wTKlY?Wno3Ff0^H=`li~m zb;MW;TX(tLnYX5+mBbEXL`e7`ZFnl&=OF@z0_Nms2nY*hq9_g08^azUb5L^NlA}Qb z=B3F^cQgw(Lz_R-$yGIatnOxUtW76H^Jv$`OK?q2s6W zjf;cwv`i*K8q?HGCLN}&^{F4uUL#WB>@1J=(^(VUp!hcf_n5%%nF;)~0&y#{fD8uFpxn33PC?tdyCDGR&K zOz)=09Q@1-MTg=DoD7Vb0^upClAbuXT+Hk^P|&ZFqGIj~zPXF|GW=t$uy6)1h~s*5 zdTD0F%_M|ermo2Ev6#IA!gY`5LB_1*k3%fg{!*MwB({|FQZ?2+a|hvXQHV(`wTL*l z@vNOXK#{oJo`Bnido%m7d3|*DD^fRH=0&>HG?F3}^%B0BUfLTd^M^q|`Sgz>Pw8$+ zfDe|9k!48=9NsZIg_E^;qbWFiM$Yf4^yVu)H{9$6(iv_}j36M9tVfO$fRB!!UHu4# z*a(FEJ08vl_+OF`ls=Br1+d|jsey)pw-Rihgm**#fzo^&Fxzk)5PW}5e__?TH%kY$ zaVfjH(U9*>-v46$y6H#`6u?6@tUg`gHEhUP%m^)Z|BVAUYcF7W*%V$wD{G(gPH>Ng z>NK`b+aNsmhK;ga#AH^nfN)ovszwXZB`J*}d)q$}YkmeqK^wQG(h`ZK=28ibP#UvyrJh-?jSe)XQ7BeSKQu$gXs#UeEcu(zVa&46@;*V7*g! zYFr-}?=?{-?kbvw3C-J!oa}H=9L$HsZaH1{S~PotjNjXrbc+)W7rCM8#@CcvLol2w zJo*t3y;&K{rFd86XQ|t5O`1IK#4g_KiuHA=@U3!)^4v$uLWX_hhJlP8y`yz^I~2AUD%xthfW` zn1rx=sL3-;D>N=eLeMt$)^-+aHsDj8lKI2}speV}Q@!WQ zE)tS|^JTR-Ymln}k^L5gNWT|=_w+VROMm?aJ7Q!o~(c-^h<2!;Vfo2*ErLXqwStg7gc7`9sq z{}`=Fvn<+?AnMpbB)5$9)cw1Q8_qh#kI=$<%IdXG=EF#%PJ!PP#p2mEUI)GuQG3}+ zrNZZOzf(a*#tB+dXv^8C0Ecl$( zJ=1Cx+r}{_%}xak^Oc_A*7V-QJ`*s%Y%CzRVPX`cBpoIod||CLO+9qbSN~egt7V0D z&fzd1&D6Yb=0o7%uj!*0#hemd82RmAsqCYP50R_BneaX+dm94a@5$IgvQB5O;vT{3 zunxB&be|$H(sqO^{i*JGQBJ36*chsF>T(A7x_7vTG@(CcLTdPqh;~6v7Q3DR<+3nA1tE-2NS`oy61@L z_q+(2$}OKN0^8ZGc?z4zXUquh{hhUeh&#WEYhw8+&}0vx}rwP;ASdq zdd9nXw|5!mGCxQFBSF3R@`%-}BD*MTTg}&-irzyCrk^6-gpO!qmQJ{6h%J-WiOf;J zk$=r)Z76>p@K^X^42#tfw0m9S16#vd&RrQg>A}RxUOA8~6mm`L(2J05fFyL`)&co6 z8OX7+opYuE^yz+k>_jgwjaCi8ma~1D&Z-arR8F$k=`}c%W#VtatIb`1s`10+UF+?K z$1y}-fS9yuOAiDg2F-;_A(ZfuIy>y-9os~0;dyM40JgY~FxYeNPOYo5I7bBql%oG$ zrDx)w*F9W?<*ySLX>h9LuBAi2bxMXmXd59c4>a>^wHfNWrKC6TpBF+7)~m!Sp=FE!-VOD*EZ!o8x^B8JCbrK^_YUr$dUh)urlKG09mPI9hT$;jkD{fzOdnM%OaXf zJ=RNe2QHT5`xH7k(572n>#0extglA;TBERGvRDl+#a|2qBa(>SezzzVTF4QGWhQQu zT;w%zXjltK8CcvKI*1ye-S<0@A7=_+C;2$+#Sz{xSjb{AnOL~Z3za86=*Z|N-Q@pH zQ9Op&ajVQ{af=Ri)jo|+mgFqRYLaJvscNMc3qyHlXZa174^`6!^By9fjDJyXuSIWLD}8kUnGz6f}qbN zBtl5|i8r3buAFyFIeFDCa-u+lXnC%A3OJRC!xXQsoDiX&;xH6TnFhD(`G-7q399)C z*S>VC`zHrY$3JDH@_A@aN96VCmn4BvV2<``vYSiaXnuWVFu4FBL=uf;sW;Tf_g=9Usc@*!`?5tZ(RSw__5v<%)C&fBKq+Bri zz|{-h$-sHld)%Wwg zC>7PpG_lVZK{7GmZY#>mLehWC?0hF%fPHCNn?<;M-6_$v_f{wOwGI3Yf?9YSAOR=W zVc)N`xIbip>eaABDKORDZgq*54952L7S>$B6tBe9mFTfM{GQCmX`^HoK{Zme6Bq$Z zkSo>>8!HG>^zp8JR)rH?Crpjt&81j;SgW8c8un}aC%ML{*Y--ABY~s_CI!+mrHz@y zVVCld2$$&o{w=})AL>VCBH=6q8L}ycsHCbAA}_NS{z~!39JFdxrUp#{EU#oF3WcIa z8zDtKupy6)?)>VmyK{$T%17>Ui!_Y*ZfLb~VBVsw2lGyh8ka*b6twr2Mvp&L`-6dz zr~xo7*}3E#&72{e%=aG?dFm2l}77aTta zXvRr$)jRk%U_H+iPL2fU3r#e~ES-KAnBm>6?Y@}bj2T${B#JzVK}aw^7p0|VS)zeVZDqY(vI+4YKue^i*2gPJDyt*r_EKL#$1VmBYg8t%1S1}SF5dFt- z#5{}F9lDYQsy&64o$_YHsvxhj-L;D4Br;-6{@G?J>B~uq=VDV~$BIT@%t_EHpsC_2 z!Q$bOP^A>+l+iK<5fJ}&Q}z^6*^BlUQC_io_B;ajL!Cu_H2{i`elOU{NC^v(?b(0L zWpR+y;;NjiO`iz+#D{0TLfz&05a5>~TpO2#NS6Yn8C#Da4Ej(#XcUJ~ z>==bu_F8Y4Tq~swf)C7I-f6+Sot5>G$kYNg%xI=9&^&HITP{?jZQ~S)-Q4Q!2f4-> zy_#xe_w`!aM%Y|@BM5p*lHFM8hk@6eDWQt-ZuzmjddfyH-|=1WAB|%(x*Pazvq;kG ziWDeJmZ6;{|1W5|)el9nlDqOph21KD&4d-Ut4sQPxtHG{6zJ*MIM!+bn@=CNo#&@7 zSFASn700G#NggRKAz&2*2DHzXN4Em`%vuneRio?-sOqGxSH=ZI2sq<)?O8jSPJQw{ z65UP?uC}=K8i{E(4xu`BZy5~Vz*HSB!>fdEJ)?MBTl?xxCNuFKpH`p^bg+!nBwd<* zrr!1;gJtUf`S9SM!i`1J*oB@QI+XchJ_)3=Sf;LEer?6czRd~QFK-P7 zE02(i&+RyRiT}(Sp_SF(xb}SsJbi2N2AyPxM~3!IRr}w^8N3*52CWj_iPj@+=Dz*A zuKf>!q6mP$5UME=Ik>cTw>TZ`jBk1=-)?WPi74@ zmQ?rR`|~>*;4aF!0i&yL4apPDZuI1*2-^?FHq#z0@rw*8_Re(E%$h)xtSKy`#r0GP zY|4eYEc5ne?evM30M`nF!r{Z(ca|DJR`0K@I7D881sv3M%dC=H0Nd+J_j~s-Iz(bx zra;7Kg?@18t^DwAAp~%9OFy>l z2bg5sy3Wl39n0EU8oI5)`Waq*#2X`I&B{=75>A^6w2E=Yi}9C4AM zRQ7i=y^)SH(+DPQ-zrJ!)iLTyAo2z_=wDBw+*e#s0e+^F+PxnAZF-;#iDk4m39O~d zW*6S)B4s~mP55uiki}pUTLvA2L6!bS5b7*8O?b{W+THDWcgnw^%Fiy`EL5ut1+F<7 zST;&^Qpv@fMt#<^-QSs2vnRR?24Zme$7M4RkhZu-|L)GiD1hFernW+_TWBqHZU$I> ze7pAT)@y*~iM1MsMioYp_iJHa$_<_OA`@j@P`kC>4~~}V_-_47rkvi-Is0_w{AHW^ z1K8vW^uv&Lhr{r6RIu3Y#*g17`kHen&l3b9vRp5#Oy5k^+*MU^p?}ATe@%rKETW&R z^d}awFCY;`iqE)|8d6o8?YS;oSrqre6uep2z=i;kOcjk2P{vY+v*C(ior4JDju3tbCC5i7~*F z2f&SI0EI6PjmuFB*!Gcx{I8e*i^|tMz%WOY^q31UtqXqkeT|}|b|Oyy*(m7&U@Wu? z5P*NI5cP4_qAq(5L#WsX&cC?9QPH7@E z2+Z>XgLK^=;7=!Whad2B;){u~_>khA!eQPiv;gT>Wx%;N_#YQ0TK0QlTzq8*tNLa> zIeBrM>Fs7xCWU&#-f!`mB^{Qvrz5~I5g8~K{fMSKxAF!Apl!iN*4zxpeky83i8TKN z){*SB#;7@r2u)WH8Zc&9sdvr2m;aIQ@)e;*_nsXkHhP*nowWC%h9rmADa0Cf~7&b274{_){HW z5>ola6$wFHZop{anS4%4TDzZOQX2Z&K{EMXpVm)2gaMv8YrNOD^#s;~_qj+B?-QS? zdxIb0gIgQKsdpNd+NDig@%+?vv+rf-ze8o?#qj?(51d<>AkH8L$lIAWuT6c1IR~zh zq-DJpE)Dd`pV;5R!!>65ANpXzAKkysnLeBToN=pjPh*D1rY|Grcv8i_xf>CwGq}ki z?L{UAL8=SFZjwLk-bz%Vc}V9LRDXSosan~Gb~$W;@xj#3OnvV1uGJk$S@9zc#m7nE zgI~k@t)nop&YoiW8LW%>4V*Uv&56Rsyz@0V`T0S@NlC8B3_!fKo2*x|%*9LQ5dAi-PB1l*`??bjaErCw>+|OMYwEKq-M>;lN$xXmTt_}Zzx#(G0E_Iny-hK*`Cy3m*XfDIpi|+{R-DqN>FUdTNaC{eC{(H3^ z+2J@&XfNJH1#PD4H=yx&O2$uEqVNJ8`>9vJD6*gUflZ_zCSo9g0<;c4cUJjOaHEAz zqY^lUx;N_9XDVmxrVZ;+c7zYqM|6j!ff7<@HIedHMzs*j*aVHXqIQF`uv8WO#jlr7 z-9jSIVvFX|FIISf;0PQeA_iKb{5ve?Htp;_-kj(xHO#Pw+>WmR^H8?tR zsU*D8R_ic2ty$9_15sJ$S$2e*q{2?pDPz4u zemTm%Dd_GzK7z-)hXn(IdtlN7J`ODqa85lpcaH)>1^~!MKK!(=5>B#+>d{ojVSt%c zfgv`IzjY&rL7*!x7N#jNr01~G7-PT9xKwdT{-#Gj5`2jeS(gXL&w?rVdz~=aVajmdaSR_0(7m*be0Hl0Cn)N3BT%(<%u9hq ze_F}VCQ&4|1*$)6h8Gd;TgJXl2++X>BXE}JG{rVN`ii_0ge!Wtqz{<=RJ`|yu$G-; zR@Fv{Eb<7Pj~YB75b?Q4Z@w*~yS0&yq2mA5h^KMQ!Be8!0xv-oL%P;3#kK7^j`IY2&krkSdl2qpD(TZ?8{7cwX z=qMkRpo|FI!Wpr~&v5P;!JGqlGp>WrdB33o34wDvp9Y~hG6as(eDJQ6$CJ0rcHt#b z_HzXSyQ`p=j^JPF&u>qQsBc}#QD_(*?S#8@`c@DZ5S2G!C%|tMH(r(wF^!vyWxx~k zUygHAD}0Z;>(@BuN=KzKVt&jWIcZff;iLa_^Zp-tWeFF}L!?Ik{3!vu*YhsvBs@kbZb{j zLT-cK#S)1?3l2ZQReI-3g9uGu&N@!-LbdGh07MWAuG8w1V!b~bi4kN3<$3htneSuy za^uA*n04VsXagdSi@LW;zi=IJyF!A{_Ha`uUBXRB`Jso3`hzHwhGbT(#=@n_RaUOu zgPzS$l?_@_DlZlxWTVEAY}d(3$^6*?<%TDCQ$a<8{wt!3MybRoku8-eV%FuzM}R6yEd%k|j&GjZ zdCZ7)j2)=N-k(r)Ax-ka2ODsQK)SF@jS|Jrx!Xy#gQTisHWSSc1KOq1Xg=|HJr<2g zb?V^2Q`l=&=@&i&v=RL}Di5G}z2cfJg7Y%0sy7&STvVbNMf+?y0}>ljB|AfQ zw=A_PbE;X*y=I;FL6I^yh7v5z>89xG9CgvJEA@R>(-PkuWt-dBHpI-m1n0NL6n_(? zDwdAOg@nbx&;wNDY`4WwI#p8GE$^fTf+C|O8P7(91UxijPGH{9ry`N%gP;oIkt7(R z0b50JZx(Cbr53r+g)BU%AgziAfQvs3yD4b{S(G8rCaX^B>XTiazT~2N>Q#~AV-4od zati(TCO1j7rEwz!-NB@4^6@}cDmHJFUqNT=e1n~yz*OP(O$uqGX zoE8!W6Kz#gFDWtLb#*<{@AuYNfFK>gL?}2k&#u=)B2JDzw=SP59_|uJhzkO2roF1< zHW^pxbNG4Lx=+adQeL>7a)ZakK9!-AVSg7KB%4x0hA8z%$Bg#l+z^m(>_HQ^Mm!n? zxc10L;9ub>n;n=2IB0Y?iU4u4-0d*VpQcSlzEMN`X4nNreveqj-yTvKBdvEBHnUrB z0BlyW90SA5SpDVbKvQb}RDe%LYs}R6CW~o(e}>yp?=ArdZuC_;i%4aMKFKSjInzXz zy`F#zjT1`55fCV{-Ad*UJLzi>SWAcGy8-a)10O;aV%mM2?>h41|X+W zQq&{yTx4o^Np_eYE+7gwcUF^hH}7*8#>o(4id7)jKxO3c1kGOF+%|dx4PFj0rG$-7 zL3*fFP;)kK_ytj<>QlhV=br$=BR+x^&jL>$g*_!7J8t*09*B0Jk9fq^&0=pGJ0CFM>ibhCk!xgVVV0WDqikBXM%)R0ld7bjh5?1)zEyOsv2)`H;Y2_- zi8S|~t2J+LlRbEBDV0!!)j!f^@$PapZ>_e0wG>Uk^Sc1L5ft;C1+dH9JgA?r+OZze zXn@UbqVjVfw6JLRa@7bg^((+a#AF|*+esOI zGLp36rbJ*uRFq{b?2~y10>Ji3Sw)M11p>}zlUkdTLc`4UV!!T#^B`9X)!RE`J|BTG zT`+%3YMuYOOXI<@FI%dDPM53YhT{IIM1=Ee|BT%KBFk})6L&Nc;R&Mz9{}uDMSb!_ zhrTcrVQUBtYj+J(iZGI6=f{t9S(eA~11YmErg0G1?Ge;PqIHDXE)hP(vxxCT z8ahlN_sS<=b1bLGwOXi8bj)xid8q-NAWg8k>r)yZ_PR8i;ciN5=_k3>*&rgNfPvt^ zdvFO-agJZ8J?%1g#~YlD198Mq?FONl#XG=Fhr7rN>#oD&(vDa3@k!0=0ch6i3}-MQ zLGFj%pw*^ITC?|xse$npjv(k36VQuSG|CUbGlt;aMD2~us9w*D#=G_(lIhv5znu3y zTlSkW(cNTRpliuC&6-sNLhk>E?GLfS>;y_FaVG6#-J5B#^Nr*!CGce$RrHlq}+TMuCJew0O;4&lAUHkfMe`>6ql3 zHeXxj@@1z6eJc^I7%vs{o6+CMXa1s$V^|YjYp?dO{DTeC+ZZ(lPfzVC@@$8@e|=5x z*<3kW*8=DATtA!|?jbG>c?2e!Do{zUnRS9Vgy;-|9r17<->hQr}5j*+yv-EFM?ae3B+}aUe)1#wG zN>yCEWh%v7_cB9sk#T8AS~axDs*7?9W#c{K8zzDwombK4D0(sQ0dM4#8{+A(&|c#L^wMh{G119>wpmEo}Z@%Cip^x#zglL8L;DDL!Ym zZ(nWlW2BgFcqsG289o7_>gde8BmPZMet3Yv)YTl5v4eDct8ThexIICmpuRj^CJ;Jt zSRTIh7`xQ000T*hWt!lkkx@YBz*j{=Q9}Lq0r)jz(IY$H*k1th1ePduK^P(d@Xh=V zqxBUAerkje5`yV)0oV+4vjC|4n{j9LAbuEo5OCwZ1%ufRWNy`1;eO#=#T=L5y~ZI1 zyZU%4E%B;-n~vR{G9a}(!;{;;9yN(m5Jo)a*5c^~YlV?ntR(~wFFkp(HM4$5cGY`o z`4NPL&)%~|%oou%-9y^3-mnLLd{Hhx``Ae+%Rxn#Qm7+N$TSfdoOyyu7o-RfUbk9k zwY!5>I&nZd|E3syJlu=lHQ(@fP+ns)&sY*vq<;gHYCqh@AMz zFE)E#C86t7Qjx3w*!1Q# z4ggqrP=p&ky4&XTPE#K>(GkMsoq3kqni*fi@0qZohzXc%~BubJ7u3Q#MLdq?V9^@x!@QHI!o*ZQ>Z{D6s2qG+3As zn^x;JWZgUOe9<<9ee}C?ajt)FBXLjb%M`{nlXm|Vf%=fWQjAJ0EMPy8E$X|>{Lh$>Fw>jxjz4y6 zsy%L{b$Xq~KRC?snqo&2SethLQ?ml1y5_y^iKEfRO@H6<0r&e+1rqg4t!gOSu^bGV zvK%(KbcUY=*qZrZAX{>Q2jp9F2Wuxxwchsq#eGeNWut59CyO-_~aNvPiYAN-|{8J$2r6WLYmxNsl_Bf6R1Q~ zp=n*Jm(sJOkze}-h3MEgi5YGSs4@3c_=9fnK=f7vdG-3gJwux(k^}3^3V2DL^F)XO z#s_O>HR+EI3l^|h$XM-1mA_7L&UJq|rK#`qxgZ-FxVVD(3{y{NgYl;$F$bjc5qw(x zr_?x>QMZMFxhW1?B6yaNkgYgnZSRhif)Hlkq=ag~c4w7_LTbzXSjk zTOBC!?|Ol~Et{lD|AlxXy`|@Gpe(rQI2&nsW8BNEhQOfY^nPx0zae;f5Y&FeegM7L zquC+%cbPMJW` z^+}HL1!s;-0dCI1+vx=#$A4Sy!FXU$y})MxTsh)46V_mjQUZ7-+4g&p`hljfXrZ-T ziN@L)+{<(zmIgbk`%eJY{tby_00E!Zoa$}t2yi3Ul8cutx^(U_+7rXem~VRg7|)v_ zUY;3Ql%0Z_c^4xwOW0q=E(`VRmE6BmGDi5$gy+@8<=eN76R_IgjHreozT3iF;w3sc z#3O3yqOsN&=ux;<8#%m))Kx~#ENTnnA9lFJr|VBWMH;chMs>O8RTdUdod;kkgal!y zk`Ze3+N)f_$I~f{ zL<_RnNV1@}bo1rvgR4aB5fVNM48JNtt$1jI0YyLt#RKF_&t3AAhb6}solZ;#gnf{x zAss)^^Q1JX?63^n-?r#E@=BJ-Vsh5R^HX@HWzbU8CSq0@Y%onh*|ADi4k$L;uE69* zXihBl!mbLxeOa_d3VP{Jin>3koAslU_jqj*L58=hGGnU+8(JdE5}?0!8U^NL6!iSO zx2-(XOwM5R7O;IQ;#tC-^wLI6%Z9u{!L%)`)RU*(8sEf=1~*NhN22({9ko=K8%U>I z#=kIwdRO{HuLnA&F%;+O>U}n8b9$$OazJw;&fTEb!HsR`3H;e<_p#(>CAShwb7{Q4HbZ8p0p(IgP7*4 z^d=VL4XhHd$~z&&Q@P?xFSRX%z!~>NYN-+*zXgeIO`a{{1FsWKKsOmYf@W849iIbrOuWyP+1K*U4XBnh9 zTnchx-_XcPvDZB6XTz?wuiY<9#h}q;0{+1bBL`70Z?F^1Dc(ioV`$)1GACTfMEkn7 z2;|4{L*XQe;59FCkDe5x?BJ62g)UD3foV%6nYngaxce+4ksm%TX6yr&Shb*;Q0%EzZ$ zSQCpK(CD@CtzA7FSY0at|A#dm5{|)sJfyVljI7UB_;Gu!PY->D=2^S;QV<++{|XKx z+XML&b9t56)!b_0WlgXtXF&KsR2!?MK-560MwEn`?xIo-w}OD6<(>A>C1PC<@NxHc z6%8P##M3xyXQ)ixUTC3ai4!IUF4}B?s(Y3^Tbs;Jd&#Yb@)cKQX*U`qK-CndT=kE^ z;a2!xUr6eB`T^%wDn>=vY|CU3&^0jrFS?c#{9=vk&&!HVh2eVbBN>~r=J}yF`x8*` z@3M$+1sguc!s?qN>~`~JttMU5kCF&&?FEycc3U*?vwon=%d;qexvV+bMUnAGozBo{ zH9-NKP8fW%nUYv_XX8!O8`eOTcR8%jz5;gH=l7Xowe2=EWkVr#+cY1R)nobJ=~t^h zZbYz|IqASfo3*R98*4)4kD~>xg$SuGvu}Bh4NQ|A{Dvbmc?}uY6)ECCw`O|fPaIvg zHDAB;zG$V$9tv04AyefVI%~NgwQP2jZvqgzWACi6z|L(^sFViOk|b;Fdrwch>9SjK z$8>;{Tzk1kF4K5s$hu?aaMplg=l==G?h*XL?(B4PCA+N*ZfgbQ`J-5UYlFEXNU+tqk{=&3!`BHQ zb07d`FWqOvz6KexjEP(@{_Nh=2?SvnFxbF?FwZ7ua!Na=N+=o;RATP18T`I2i(Y(M zQ)Z>=6aO!c&&%Q7vSKH9sF<)_A|KL7vffUBy3xrvqX&035aWKWwTZ4Ao*?5|E57N# z*c$T!u%lKMsSm-6v)Sg331vcow2yLPe=y}61-*L2Sj72ECzj;H^I2w{`B5mqr@oEZ z8d-y+J|yC;hnaybPiAwI z2xh{`jKgQZ-T#9tKRJWL4hDalx}mEfgEdvbWGx;2 zL#I?6X=EBDX-679ZrHQMC;*P^%we&>8s;9(epS*?22@WLH5Z|I?r%r}op;DuEZ!fl z_lYv>4LW~h+=c^g)wzIY`nRKPyo1Pr>+lrzBh>V@TO^0bAXh8m>BpkWc{Gu*d0!!e zhKf>pu@Z;vY@gZ(A_-_jB8vbkAh#eVTCRnM5ClhU-169aoG;@Bg7YJfn%z?=a=bDp zu}@92lW~EX+_<6oF_yGLo7_DlX|ySx26q}i&o#gb8sE~h`y@$ZCi}V{j%2Am&M=Rm z+Fs966G89eW6P)MQJDPf3tW>9(gx zj8oUr#Mz!}qe~_#lf`V@7b7P3-rWGvn#c$StH+LrAcxYu|KXg(3a3>lLve2w6=re9MHUuqaP=S5T2oH!t^hP^@ zVjhwfVcc%87kOO3{ug3<*DeZgSYPkoc{BsqH+uK^#^(9#iobXxXTU@jW69hO8Cf6H zU!Kk0u;Y6vl346)PEjkI6yc9jiS^wmw49Fa)-+M`j@jw;Hb{t=fI@1&~9p0hi zgtHZfVRKGvW`Cw0m63Qe@ytmkA-7&61mUm@*w}6af1p*?GEAd1hzAh<%G4iB>m_(}ISaN^6RNH&duAUt68Vle4 zFucdy9?(*?+#bpP!7&%ENFZ4#ild%I)AUoN8JO=Ox3;wstMMdPZ<){3*ef!7E%M zw!}lw3fDc+7u_ecf;Q{^tqr!!=4CH%qeth>IMdK?Badr%CCJlPBKT(Nu)lhDLz?o@ z&^|&@eUZMLTV!K!CE8Y~YMn+S$dUD^l2v>a-H2!c;F8~V#U=)KVAul?nSA41#S6le zC1ha!*+^`MTAEU|KY*B2zdw(w)UdBb79m_SMt7+j&cYNic2|-RXeoP#ECXOY>6d73 zu@MDdofU$4$Hwq;;Io zLr$J0xkf*C=L>m$yHfGk3pJ9_kz9z2E6c!)L{pdup|H`l)J(3#Sc2Gxvs~o-uP|CX z9MOpx9IYB{c6a#h7|R4us2~?2Unld;j9tjvu&z#ySk^LhhM_rxf%?TdAq>x(N=u@+ zbab0dLe7q92E^5mkhvbNN`9iloIo ziGP>!RwlS0n>iZUOi*!6iKa?(odqK3nDSZ`qc?=GoykU-g)SqII+Iv28?VEZ-~R)B zwto;nz1KIrZJABu=Tg4x$=D~8cI>Rga*G16{tv`Vda@0i?p1xXS)dt{u+Jq5ZjuROH$1y~*0OBH%tg7LV9lF zubBs4M2zmk6W{(b`x`_BAo5%XxN6Rm#$#*1eB5t-$tF(Z?x$3uel!VG>3sd6=fIjj z#TrU$+&hz6Ur@vco$w%qPpR~eQRrgX+MPLsH3qdotr9$4=cq+4VgVPKwU4u z{Y?`4eZNBUg@Fyl?tGl)8YT8_)8nMifb?gM@4maxc_uk0TQ6NDEFho~>JOp5oV9mqGNm%x5qQ&l(cm;s)yA!1i_)A1I0Gu3 zsg9-<>x$Dt4}mAOakf&QU*CL3S`himSU^s)e(Sc^4jc1(%`uw<*!Mt;H zx79x#RU~S+C9LfL8&sPyvSb#u4vz~rps@J5LAlq*7&S;WM1WH;81=o|U)$5;a z=`se)Z_UP3!zeRydL3hfacY-~)*B1}cD@m>`Sw+eOhEy#VrE(sa;r z72+xj_`?T=d+B)?M&LCUrCAg%AWNw^^o{0POV{{F{@hBg1PyiE@CLyzk0HU<<7;F% zZm@ufL0~jyh9{quig_h_JI#p2aXnCAGp@)hD)*8^xG_uJ~j zb4$;5k}_Q-cDT3NYJ&pcIavBn_w`3HI#!gNK3?YMO%%@)SD5hl`ha86Z_C3HP9qx21 z94If!@_HE)%MpK2rc&-{CLPPNnEeV(vGcnz=D^Py3S5}+yav+IS}oU=-f-XqS#rp! ziT^ADDrc@)L7psFFmm(%y@U`QX1Z4b5QSHI00)3hx@qn73fq(EY0=%)Oo;A&%=Icx z-NApu=5_7P-Wv>B!p*0pTOa`-Bc62LBU0j9tMy`&P@w@@SWK{Ft%oxs93NM>`IssQ zK;K8Gvm3KRI|koao&XTYa#KP#ie!T`v(y|{@Q;h!W(lf}t}5~h@4KPArPE{#eCQB^=(7EFK^*8vAgPAK z(E!kgVo@#`-K<$(sPlLZJ3J`!k_s>>^_A23f%DzxQ0TRCiF+*sZO_3YpL!*~=;goB zUJ#*UZg@9U1jnQ%f-B@7R_q7yvEc+=kHeq!>;wZNxIiax6%qx7o1W%VJ(M2hqO?N#2Sg}jN=@bAxK*GOjr^Qr>U6l^o ze(4OOLUVx0PFc=-?#iHnUDvCb8WX`aO9G#(uGvT@3Kjl-ubR5yR z<=vVD7p9X>sU*K_dNhmhEADiep%KKOt;xDIts8Ea&?6IFR7>It?w)8n8qNK>D(oW3 zQ&L$)rkK6h`r0J~15T$7M!?Sn6lM-#2GS~2ww)RZwA-;1L74d`)BfvAhfr#E(yKg! zC$2qdbjp$`@6Grez%doqI_PBjsxk4`HJ~S)_N}%=r_6BmPY}X(1P&lTE`W;_A>9mn z(=cf#1{890e0+f(ClQTT%7!pY(QXFPQi}P0UkrSh)?#dPxgwr$Bbp^tdA*0;J}MkO zLLsc%n6+lP;dEcV+ za0gxHTeoo-Lw!nOUpRbmg{@RIhF=14BfoVaZ$S?mTtL5S=ntGG^JeJa_IE|*T}ax* zg1`XzzE)6Qa?wd~%gKWTkZpcUOS5y|uY!pA;(zEF?;1ydkS5&`;CyQ6=y2GgAB8In zyH)240#ljNN*dD;_x0~!ZafR)lHG|xO43~mc_%!A5NRO^zRHv5W7IsZD>?th=LVga z{@1(9PqDZBL>sV{fF%5axtX@Zg29$%E&1Cn%|wf>EQ#fSwXqeeN$k|eJLYezYe&yA zUs*A$VuqZMkI1KP>@-}&M+>>rl)Wf+0$z9@ z5|^Yk9xBcc0h>zCHfD7b;YTV$=u18=xKGj{dmQIvxQ-eE0aU5DT7v+KaHQZt@5W0^ zeJZ5vE{EHeeEOjF&fjB#T~$~OH_{>Bl2Y;_q1b@h#`=#0hkfiR9w6EM@;CMvqRkn$ zN;_NDTjxqi<4W-Bw<$MJ{^WPjx_D#qI35^iY;3#ifxYq#e0(8DTqpPMCy$s=Zw^2N zBo4YVjARH>nmsL=3TlIja15?>_F;OisymJ<{f|r~T1~t50E}pW`=Wo#x&!`v%f1zr zeRP3cQG6w~9=~o*TWFj?;ZwmMP4j4C{5O~#9aNR8MIduEhWle(14CKc+=uuS#gehj%PAQRm zqSmaqG7XJRQ>Q}#3E+XqEoiOBr*V#x#pgd(3Y=?ajCJQjA3P49bYG?oU-gYV$7jn8ja#c8$pLE%P&j z8h$G82Ux!S^bdMVYlW|agu<(i@+LY?ebNMeTFE%JskzyOV_?g#0E7&3D;u={Ey&Y+ z2G-Q<#_8i|zb27vQf|>gkt*0E?A%+=U3gyJ8>D*Pj)b^7Kv$`59!4yxr+?yBN=?$I z4oufLvC+(49@90WL`p}hj$BS=aS+wouv#cw1NX}wHWxA zfz3sy=y=`24&{(WP@h$fQT_0~pBGU*&7Ex!I=VABR(A)d-kRxMCCm_zKMb=2omcg@ ztr1Y#+2{guMYVE0>*Cb8Hwavwu2|?Uo82tto3;Dk%$0sw>5T0o)ro&d`+Q+B z{{9?(f;Arq2_N(wGQ}TiCy_e$tcrK={I=ZCESB8&jYD*Oa57m_m^L~XP#B6xF1o*W zLvyTXhE~`{D*B;wW9h|tz4oU$rWA3MimRc-O7cTH4bweEU%~CV_UNS{3dO1#sY)5qA6Ti z|DL7u+=JXUy)6aOC-284g9;ox=yvCwe8I|y$Z04%0GF=<@=JbZpBg`^KAs?C+ZqE- z(_1bud`TW^^uxefy+4_S6&IxuzFLJY3Zwl94Y1)jpafsJ`Kd?fVJ33y8KJBpqsWx9 zx#Ca$^?|wszo019RxvDn2Y(uwr$0U3AE7x9P4I z;ufj6WJNS=ZVU z_nrKwa~a849Bc`=RQwr>*B*>`JqQo`cYIicg#|BBdYDX}-Q zfO_Hrs2{&<0-zt)$sNNvFQf)uA6GGmSjup>=7=kaP*H@ABzG=aouBpo5;{ z+R4^yx!aqN!TTJzK6_!TAKn$X2saR6n?Ra-DwQYLT-j&!SPN$89!(;-fc)vJx+T=k z{Fk7V9Rt6J^_3=(xhM#6+~$8!Btd9nVSwedIYA9yen?b?s9=ba+ttaM@gL@n=YjU3 zCO*J#E9X^Tz?sTVAFXfbObncdFzsbUbiPhP5^AB`Yqx?4h z70}HP;Oag?;~0itt_Vi?=}BEU$Su*NUTQu2TxwI4ErKx2)xh}pZwlP72mp_AWX4~4 z!5}tqvOXWZJBkb>{FA#^L$*%|l9n;qCs(hpzxYypfjs!dhuKg>&*;io#K4lmP&etS^x4zSx?KqKdS7!VN6~PNLML~0 z(r?YVP5;6^ZIIh6MCP+kvR_hhQ%}bb2Y_2!d_Vk9BU}8`%x0#@B%8w;63nYs5XZW8z6RALSk?G!Kw1Dq(v)ykEaCg+D0? zAw6Z%K3fU+ItqF8&D|t||sV`8mx=!w6ST6RG zt4PVJZ*Q*ooJ>0~J6Q1$m>5sPR?L&*<@qc65 zWup^9@5}4OP3apxDXT~wM{)!j1s(x{+JFotu)=~8CZlkFEd|CdEqj!y+~JyK(tXVV z@Xxl>V5|gBeRkV?=t<9+g=U&?{6(#cheY|xAt+s_yu8#50GE7wOM_U(>yy4rpgVEQ zcq+-Yca}(w9js?bh)MwIZRAH>cz!NyV85U!kOl9R%pFA9nsO*n(H-C%5oLaVG)Z!y zlcBrKjG=8>yS9}aKLw?D2u&{rI#c{wMIC94jc-i>`*e#ZliIpFD=Yi7M29lhQq2=V z0OH0$yE{$}oO_NoK06I}$tEFW-p4%($SLc~nr_eie9r#R*qCH^dO{nW+AFNz!>w@B2U{s^&H<|)^_jPad z5dqi0I)Yl65aE=I6bJ05$Gs%Ot6}?XT`Za_R=%}}P!r_+fr%m^QESj%A(d+BPCE8hLU zw^iYrL*K&HMpRL0U~2119!DO)kiE5snniqdq|Q*_^Ei zE(NT1)OB6M6k_9!aJh9k7>2I(aUmq9(7W0{0@6VZyVdMID;O$iJs>kkgvVBSD%qq6 zZHIOGfk#eqbIXATI?pE5QzUmq58YrroM(}RaXM|y9~a8Y;K$?EA%oW(M`QyEq!?e; zS=xe@v?R2!O)NTmlO{<8Rs`_VS#VBn?Y27bzf+B*=hgah+#2cic4lKn&5r*ZMX+Z!+8r0Az( zmN}~Oc*#>&!)t4|G&)Yt&n`!MV3JH3EMKRYWfJHV_)qlRBCp0hUW-*~155P)25`8D z_t#M@ZONa4nntzH!y9QXxhHIyFSkl{E$LK|O=4t_>ZGXK4jAU_#&6c<)i0y2cF5eE zW?QJ^1$UnqHkPXsWatff=ZYF3H99I8FMw{z7lsB z$)KmB{90WauG1H`Cjs!YJP<9i8d6MP`~U3h1wR8u^1d&>hqtFIca92uG@OR6$Hm(^g@_#Naz|6WquYT$eUrfU+O)Rs6+nF_+h6f|1MPlgE67o*yqcK7BY~%AsBeWc93~_K70Llp>A1*UdY# zUH4Ed>FKvH5EP0^lKys6mX(t++M~=!@Om>HEK3255WsUviC;oV)vqk1_s>6r!TJh? z6=BMxR{q^;HDED3_OCSrtrOQ*fx6n6WlHvI7m;wLtsx@2I8&KnG-UVhgs2;n==)K0 z@;mx0w(aCm*#!r6c)E+J)TVdau2x`K@6pQfu##L-zJ5Et=9e5^Xij-yS77 zMTG)vHF#Rf&Tk}(y!wZ~BHFFO_5J4MK0uv4!>0FES~q`Os8B#Jx)D(3S zHS1!WE%CZuC~^1=`Dl@?SVIJzXH*@Tp`F5xy+yo8#h2OuM)_t3v>ny-8w(Ls$)Utb z{*Sfq5kKS*wqCX%a5tiOXO}JT&e8RAqi#?45$x8eKN1?RU;V)ANcU|X{nJD72=*=^ z(EL&Ep^47M3>DZ{Um}x4Z4Iwy*aQh9f{`PxNKRScltK~ZXeR!l)C+L zx2n>_yicpgBi>xhq@qSseO~8lQx9)h$!`)}2J%-<`D_qcF3S}yTGXg{b$tRKmTV?w zD|X-&$R06tDb`8vAt6-~bL~Lda6!ZR~Ghz2{ew^L{COrN4M5M;Y}jsyuZ#^2H48X5m~tf+FJXc;6XZ_W1d9NwWt2g!@omP- z(bceKVY#@rR5O%Ew~RiDgPzY0842*&-4{IbT=0pdb+z?2eN;Z__X3usy=vd)E6T)+ zG*Z;`6cNWo!@ILmWbxO!cSWYNDWxfyu20KV97h=&mY`mlAtI>L)V#uy%;$qorU8jro&;llID5$ zp|}u3a{Gnidq3|xoiowJh3LlH&(@kZBGLXnK=8|vl~&zq^+1~u3d@mGTUyo4A$#N* zEW_<=K-=+PW1={LwG# zJLNiqq?o-hJ@eGq0Dcafz<&+cwqPAE73 zJ`}ROe7yuI$fzqRS%JVh^IRx#-Zg}m0R=j?^#jg>m6_$UbSH{PC0CVV=B|gN__v*P z3Lv@E@2Mw)LQL7`3nU53zL4HtyB8gxf)8!E4so>~J*9v*aG4gY^&+#0(ciyOBaDeN@ky8bX6 z0zZahadlwVS>=3~Gn?LVh1230n1dP7D{d>X8W6lXsgIMoSeVIF4RBEFZL76uOg>6Y zr1nhV`%j&1$K!0%moPxiRt@kVmWNKoeGXG>YN17~nho~f($@KZP!rdXd19Msn{BJ z^E#RVwKE`5bkTXiN$MLGA66gpuLsFj@`c0snmP!<3B5cOU<$cCfv7(W6OUDO5N@YR zBSwsfxcN8}WEs7SLBE?kGDHmzM+|>w)42062Cxq_?T;zm_8Z zpMX{n`OFY}9>a26lA9)6fswB%5~TJPRv|Vg3Je(VB%?Q`GykhANLv^tJqIP!{R>#^ zd>}z2g-6{9ER))2L*@z!sz42N$7s0bn_)BN4vW9Q-vNv{^$t1%r@>krK13d?Rivmw zZA_Dr&8!NHcO$%6kQ-SDoL~^ReZFQBQF_Hr#>{4KihZ$E(lJS4%q~uvMX)XU51INV zp$^D=n*QdM^$m>I4kpUqq3Wpd^h_;j01~hwggWB3wGVDL01iDzOaU|HK;MJ64ku_m z1eNFdUzS`~^JtN~3JoT$Q#Un2??FscbUj9dOFDGtXE!-ObeqH)&EdeWJ?af3szdyz z1xSVqj_sP69Biu4;wfu?Q~_YbifSJMSU8C`dpPNCv)({1wD0HvP;xEwadNG%%_mXy@8IlsF>YbQ(i!v-bDGoKl+MDWAl$5qbbDhe-smQs$6G zhUMk97qHfNFczQk3UN=WlaAZkvrX94Pv6kSX&l~Eq7s}Twv&ekb7e5{f8?Leu14y4 zM?|`~MYCs|XVfk1`95G!J&noNt6&GOvFk6l?zlb``Y!pgzbKbuaAx$2po=DKT?_Cl zWlPz{0nr$^Ud5lF<^)d;FRKY7fgI>cdPvYlQchIQ7Vo%$M+@5cL?@&&1dyl&;BbgD zc4YkME&%Ozn?lhWT0R!>06COU7l$Qg`1!ItM0hBC{oQ3W)P~61KVQuR+-WRvL)Lyb zO9KlT*eF~WW_Gc+r^zjAR@bQgx8y%gy^6{xodE)ze2*BeIZgZ`Z?Bq_XB&rgLF1+9KQX8w zR;o>$2h$6iNVnJhSL#lEzeKFvJn=)rg)A{lTT>`?aUS0zXE51{ZBcWj2f}gN!KmE6 zVSoB91`y4O>*P+lWh@6X2?(l(WS{1BKZ z_;$!+60Mx0sP`iQs9+BZ{KGz2eptSb{5uWWGIzS(m!^Q^1CJD=K$>?oxrzTaQDJPj z>-u*AoS4Cwqswl@hcKUEiwO7-K9J$2qBI`N1d_IYEoFPLQ4U1mgFJhm5h$P16Kz3m zC_YJUXe()Fva}T6Y54Ca9{ZmU8bnC@R36{GMROFB=TsMAgw;EajLTsr8)hQK6jqfE z@aCM2!N^{bS2iYGOwytjoh^h_k^_p$E~{^Y>CE`>u)bJyc^Ent8MaxGcK^{$?{1C; z=-+wsqsKW3AERAU2o+{)Yn?fNd$?Y&d&QL19tk%|cNeh@p*JZkw+P_xf{hd1_IF#N z?k}TqVj;R0O}p7t_TMkh1wU1;3Oz_i2qN)7omMSc0+52-<;0$Ejv~kQD&>QRSx38M z%y~y8RZj+8@n)|3Nvu}v109%J(r|L`T9qP0G6bvQ1qP2Zi6dyE_Fpc zOi}3Ay3TFCB(yeG%{#gcFAKvA_*8Z5LeEr_<1HxFcxmW zmE8-!bXW+RGZ;UQz4W8&B#7AiiVaXA*WpusQ!w%2%K*Y&uyIb}S!+}Ez^nzhVb!gl zwTYBa&3CjS?EfgvLEfI#dn4yH4XYbFO673Hj>)}m=A;vE&Oyx>-dl*5p+7rhoG79? z2XXL*d;8I&mkv{M?c13^4Z{h|hTJY-Rc}OP7#CW3iE$T9W%5S`W@*QdEGJ)oS=o`^ zv(lo_2H3I$7jZ1hr{~u>xTuZrt0S@T^$j=qCZ?#0wdOqxJnbb>k`tS>(YKj2l{dc; zJI#>mRTh#N4->S$qebnr%`KtT7j~+;qX&2c5<&vfb<@v#uo0T}u_-raQ*SxR{!VX= z$juZ%LC+cY|6$3c2&vV^zV{AjFCJhqA4=;GNG-qvY{PsD^TLbI8}3zVp_Jl(A{ooS za^i^m@-jzDX^yhPE(YzEwa_)}$uCC_L$L>>oJw^qiFso;vl6!&iB2j>3iv?cbh4n> z9&=_1@D4X^@fB$v5o9?(#lOjaRxz`PGl$I~z3j6K6~HObqd!``KG zl4(8#6^R%Lw~#LxSR`+&myNVn>>NS^bfW~Svr-8lc%YE}CP@Sow+fz+8RCS$$+BA+ zx_F*=^x?eg-LS2zrnCy zPXU>(=th$n3-@Po+I`DmGWk1abC>mB5U)WJpYPE{9!soEn0Z&2!foKoAkNDcjmq9Z zK-&S@9|x7nnav0oQv@DbUIe5Qfniz z5Y~8rEG#{qRT3O`M8srB!|1rAS*_Vzsft>xy!6Va@%Zole(od$M(=R9rCv6SDjx_> z#nCFkjUh)TJkxA6SkYoylJMS}N8rAL`Hox-mvv&t8e3d!e(bBZ=+|!yPf)*8c z*jR`5M9B%Fe?tslNCXTbQz6pKOQHTjeT@sOi^!Q#IsViHe7tlA(@A<|l+DQv!#=E@ zo@S%M2FjGvzefo%Q}ncKo332ZGaf#;zi~EL5F7n{U+UTqu&8OEMJ(oKlopbnuZP72 zIRFySTZJ85hFI67)-tN6jqYok!CTeIM)NgISI9_t@`97=32}{_ItQzbf;NyGnwp>9 z{Dj^ko4ZbCtcvy*DmzF&>kIYQj=D`*8<}T{u zcO85>h2Dv}Oa?I3+FftU5RN-l+~7%2xh^w(L~%d>GbD}+u+xRz);cSpA3ACtX2s^r zYk_tJJKCg=``i_Ep~MCpM2UL(R-2w&XR?Q+${4&sNS}`WZ9&s!%;+^AKj-?b$MgvM zmoY79fP)^D0`|LmDF?^+5fvJi5FgS>Gq8kN1d=X{yG#-}%E147`g|%K)RabB(^U1s zR%b4?>O>jkOP~gOP>Kh6H%A=ZG^SWQNn9X-QN)Lhmyd4xu|{!&1LZ3LFq z+y-tj7tfV{30KSh@a#%Tt@$0nv121({*&O*e}dxAy#h@YXkiKP?Fqco?uZN73lWL6 zB?O1an1o+kBkhjnKF5Ma+dkq?jg0F%2NzMt+X&)@If2NDf(U=@JL=CD?66A6EEj#* zlRf5~EN5$L5Vo;B22diU9~;&*u{q2;E^Hun0Lbbpr$Imt?`@GX|JOULSC&+ZSQ4Ct zB3_-b5+>sC(?==TWxu`03OnufP2Qi))+wbgjDIGkpcGlrThq8PZmq5 zDZ>|ld%L7ivRWB<$u}cOk;j7+Z4b!Cl%-}NF_4Woo+VK|&T`6T05WGjoI>Xr+=Wr{`+FPRk#20`WI zyyXEW_y9O?%+cjpIRo)~P`YBWw~g4i(8o5M`(#54rqo??6|!ktu&QaekZJa;8lH@& zls-5!+|UDyp6bK5=5oy@DzLVzotUu70h|A6ZC6U-L!eTZ$_0W#BiU3WLvB|m2tkGs_yLGolp?6?SsD2mgaT* zOfK93M75hvd8C^j>p3U7Bc+)8@gTE8E$u&yS-_;AEJ5wkz3wR$9VZF+%P zjgS?45#W$d%$)R^&U|^Esk}Bt?RxGoU1Nj;*@Bzy9pk3P7cQ-OiGZ(0y8C$hw6Xtn zt)LSkP7}A*Ng&l;taH63g-+3X#+G^$Umhe}j2#^{sq{Ghvud+8ZLt!Yum8k|EB8ia zTL~Vp-&Mt$jvf`)-~))AP3!&qoc#e;aUOoMS!buQ(`Skg)TUkKMPICp&KFKJevxHO z`aV^>IZ?rnBbbtpj8^1~HPMzG9KcfkrR>`Z4tY*7GM`(ANhBdkc|lWaEs&OYYa@j@ zim5@e58~?DFl6hsTLjEfAJu`&qp6Y+NGJ}s(L*clhfnRZS4Fu(^zZ>vRA!}J1 zvH>djYjS`Xx3!Y$tVp`B)+(`PovezbV#zwW7)XkwQ$@M6dsGnIpHLZAR}y#=CN{Pd zaf$16wG+^IlL)fubdF%{$o{lZgMeZ7==}%bQ2weBu|Z~cmO!^`d{K5jC1vkB_!cfL z3m~@%fHzWCZzV{470jG;!afvgJ-pVl5=@JLq&CNp@^Av!-EzHy6ECF^MK?7^)3 zO9#<%tw<)Q*U8JGfM{HTtK1t04pFXB00C_E!}j8hBw{8~Q^Vba47c0VMJ=bk zEgloP6yz=%><7%_%H6-`&YRDd2%@T{&dD}Z80>8bsTk81P>I8~NoH~Pp<)(%J*DEF=x=cmN;hTkvi*Y08{$qa4%Gs0 z_@Lf}^ojl<#`{$ai)dyFHW)oMR8Z5IHMOAa+CUC0Fc@NGHq}2L>*MY|( z$BC?gVLOg3SpnJ6-As-Ri$K1k%^2nCy6iWZ|0y;`4@kIifH()^S57Zlqln9(M;R5N z)Ikky{LF49;4^DRx9#&yz5Q#iA@tRQ#+dL^$+voOZTr1fFcF-9qAW3jjCl{W$f7p= zaz3S~5jf*Mmd3oG*EOMlq?`?&tLz`(9bj6%Z-iL1+(Y6cb4lq~W+U0Evr5Zc$8UHM zZV@3tvs*!rMDCt9azs-Q0VB6f-*$?wfu_uCp(%m4Wo7K$N>(qbroH=F^fI*jJ~l0< zaxFpOv6$~Nb>v%0WdkWreXK6n&iIOCYyU4ZE-j80d@Nv~86(n@NWD7tfeqyXCL|y; z4}5F=@Xy+1qBRmJJQ6y3bs2!8T+%PO!<8FY5(vQP>?}#YAw*Pliw@i;d^uXedDnfu zV99m9N;D#YNN&Gkz2tP}HkKJYf-bfuZ-EbYj|On<#v!#wXxtXV>5DNOnt^)ls*oOp zwU#a>1Lsh$Jaa(e>T1sTPgnntI?MpDtV3OA00jB`Y)b=dl$Oe4CkDy4FNeY+u z>s{u&dh9W0)I2+a1wEtmhA<_4e{|Bs>=SMcUgu^cz3f&)o3|nRoFE_*SyI5+G+@gA$?mdzjeR3qWBY#T*&mH$+6Uh=r zXgwq^?^Ln9F*=nXs5murS1q8>kFWY@gh1LPxbrtEapL+53mg!x6zhrXzW9O+!O}++ zXdpLnc^i1+7Twr>kP-F1%$J{qN&?bu)Ij8UbeUVOPp%(5`Y`Yeu`V!}$pk3@! z1|$_^L^}-NQ#+L-&2LaW=~(vp zJl%H{$*t89yirFCzf5WNgFl@dBaMx@#Xij+mbc{$d2P(m<V#Et# zT_`-!#My>+{!+-vBvk=08Qo5S5nnqE01xqUU^eBio1l4Nf_jW1t4$%S*T3Kw#xhOf zk>n9IF9es|;Tl8`P;0wk{2DKoA9%_Q9VJ)CN6FeI7Er&)#77^-wRNVjH0q%}LO*v}6OsG%0d1O_x6$E+~$lT0^993ISx?QExgO4uo<tCec_*` z7rSiy0bmhFld5v5;jc(SI_V(JJE0qNb zTPhOO-8S&6d;nPqe>m@aKK1jVfW>cGRT3dTrTUWeht=VAC~bBjr%ToKA;(McCP93t zv|>(Q`ncDD;TpbL`ETjp8Is?ZgNgNcJVmB^T+{J2t)TF|K{q}s>x|EkbBTpLp`?V| z{CDz4!*aQLG1p`@LHpR`FexqXTp?wHdjX<_}3Sue>RB0RXM`_X>}-9O+==K~7Olxc9k;V&M4 z*syYt_LR_;sc=09{Ub9S)+i8knCU;gs-(hsEmf}|!#5#*cvLQ|1bxyv`U(c7Oo)`% zR-)i#Rx7*^+gv9f)nODuE-u?ZI)lhS`|B>b;DA#LK|!=cDVv=Cy|>xYx+y zxkTlac5G&N>2(m*CECa|&Uyc@7RWFr(gJr1wvoj8gS=`U&+##n*iWy*gD)n7*kJu4 zWgaQJNG~qy@zob}T={>7+7^M*yi9OR)gae;t1I~)8@@4z80+y>k?t=3vRf*=+fqXG z%ClneHZ+tM|6ZO2NqBT7o~o(WP_sq$TEo}75r3*ccZBMbVrN>`Mg&Tfx9=>XOaBNX z6sK@ejW7O>9=j-pe&m4hQzd>0_HkA+XOx}JdkB&S^#72AMsgC(_36#r6&W26Lun{q6 z*>^bp?O{g!*vsNr(#vuqX(yfAHfNuvD3qT7w)HBMYbB24_^pIpo`A%`7oj)N{4nex zqV8pS$d?DVCHB}Pr+`pHdMravqO<|@qpDdlnXLJr$o8gwDyS&=q)~xYuCKVs5uz{4 zybkM>Ye|6=&s^poNW#uNMu(OH?LsgD=)yIgPq&V#E2sOAy$X8tI`BFLF@5!YK}?Qo zW5mLr+}G7hC$PLgtJq)QH^0>blwzG>oFou6QfXGTL`qk`O+0pJZTi0UySd(GA94g1 zWP${2;=P*6;5NKev+FLZ8y2+NMcFx@uwIRLVM>>%m9K?%LP{5bEWrQ|0EyG1BPv*U(GM*8(aQ8Yx z9XoN%BS^Z}Rmk$xh=j;@-~MCD->gle4(q+Q(OYxCLpur62*BAmNrL;S*bXMxURz}>wz!US^6r`&&jstU^N?)WSusU!`=SW@ z*BiEO_^4AZ+E;zUv)KTvy)mjDtnb@Q3bs-rj57E4fcYhxMnm?2Eb=Xxf9bFcA4k+N z*G8KbC1H6b;?CVdZi{ml{Tod`*nN30-ol|BwC4_%27a7Si(ZB=#Bu%bfcu+liSxuu51W{Qqs?X!UeK?)AUL_tNzziY^IND2r;UI@X>C-8e*^DSz+$x z_;EIz#^Z~G9IjVP;#z2l;rCVIvffCU`9Dxy!F6LM%!Hu$FcgD~Vxrsnmq+cX>-UAJ zZ^rvZ3|D_$2DdkRJ}Qfe90Fo}AuLUETav%Ch(~$FOjI@TJc)`THtW%jYWFjOD?!TfU>RlWJT`*d}f$uB* ztGGE#%(%xQMc{O#eP_iTG9&u0!}tYG(Hct-@4zCuES$@s6@^S~`^|o)F4-j1BCh-e z-V~atyFcL&L!TI$jfScK-Ei`YJ{}M23Ca&an556=?w?C(&ceF3?zDHHY|l z<Pd65TlRreu+Cb7zMni_5Zm{j0v)g1=Y zlrO(~sn#2c>3m_VH0FDWPRz|X&_&S*Qw6Vq?McD@7ru*8`QywCo&<4z&7)E9P8~!%YZQ-r86p_}Tbh15zceSv*E}}FKUhz+bRML( z_l(*nX3w^y3QIyUv4H22y|)w3y*D*2(?xce%InZwUPOeb-xZDcnj@<*wZccF z0?;ZN`-u@3T*g+UO?`lKd-L9mkn${LiAt^oJ*uXU*FSL4X(obd`4)aJecn{Xh>M@c zDzU2Dt~ZN_g5p#zfDT>@UKIbU3-b>(4<&Pj6DS$^k2wlo2PnU20(KLzkUS;1_NJkx z@%Aa~>(C>Wd4P0H#dMHqUL{h=^Ef+(jFo92puondipu}w;$SIe<9VYNeQt(5{)Q#l zu>r^mT^Q|}Eh-WHg13iPG9AM`|1?UiR-Z}6HGe{}NrVA{SdS#tVY)6FTZs5TM68@M zBwvQq3Pdix!>jQO${^-eM}-D^#j4oqK1)el5eH&Tl#m3S>HX{_uAwWS4hgWToXXw7 zSKu6s|6$oAL7O|iL9TC1`Hyn)4`!1E(?}csn_X8+IT=si~t2IvTlxuNu%Rue#_r5~)4#TFF@5Wz= ziM1a6PEOaal;G9F<5gqqTzibh<|g}jS^SRyL7^rf=lv+i?S}71U7^o{PhdTsBV!L| zVp70KtE7L&D^l$~g3BX<7Mq36ZweVEM z{7Z%r@g63hi(^cis6av#mNN&xBaeR6?1&l_%$H`up%<*F-Jydp2-u0}D0Qe09mhAl) z+#DidqXK8O`-?WOX_&O0CnG$|h)$68jXE0`q8sh=H!!yPdZ}hEim%P$J;?VAE`Unm z2~at~CIH)1IF#JJIubACS2o8Ai*HuXVC8wh%Ct7|+L{V}Ve%^4zI)o@T-LD_dF)Qc zl`~1cf+mJO$6pB=NeGtWHrlvk={KVB=FDs7bAO8ID-G%(MSk2z?`r*8SlHSz&Es#E zy+~icSlT!@EgTe~ApEa&KMmTw>PzI8{ZGeUC5|$hlES#Bu^c{8n1FoLJ;ZCK$zTa| zKtcLT=sORH*m6>OK1clP^lPM1p(V-_`MillJ?=R{RtW9`9b!xPa8$aU#af17fDu81$z4gT zaD2?EhagNrW^RL8%%Xu$EQ91(KG%zVfXYSv%l}Yp|8Jj9(1|N|YzN&8iF>FF2#$%7 z2-;AS73jdNt3_l07bp0Miv5jsW-XLwk(C}pOZESb2g4C}?%ZMG`&%V%J#?U9#;gh5 zS6%_AGP^2R?Z)%GKfwBnv{2ux67hDzGU|d<{Yy!Z6WxkZIiW?A^r% z`o>2;27jnHT>0IH;$u}7ZyKTi>>pxJzqNy(UKSr2HI6`FaI4^#>wP4?g0OS7qCa<$ zajgvtVu>c;Bf7|^GRu~Bh;8^cF8OJfRJn3kV)YnNV%IU9o%o!-3B)}!I#&QNN*&0L zPvV#>!knH+nTtMOlGO(1;Gp74Cd%bFq-=B{PrOeoWd%G&gS2rkkbeq47j6e3(l6xY zq`N5+mC5<98P##QzP5YRLo*rH!pJp9RPiiF9ul=VONSB4-{^$3`M93G6 zYS`{>VDrdR1{;p(eTi)eu9xL8$oOpo=gd>AwjiEV1_bZ=$WhBzERy$H8Nqb}0T&@q z!w2h#=YpA(wobD z^M5yR!m9INI6#GmZRLJdWw!dYf9Sy_pZ_mhb+!WjfHq0ZF8t^_0jT%rrbaRWoov2MYd%n zZ|^!{=68tP%C_`Qy&EUZqrq{oHfqRX4*I2=Ar7WhKGG>)-e`8UCk zTWI_E_qIo>43AbN(;-$r^h%=l5Bb|AStIJ%h`BPhl-a&9wRUIMZ`zQwgP zZO>WlQ8naD@~>Y;*O+Cskx-V`=zh~%I}h-7av(fa^>BZ1Bsn zT%y_y?b-uX6Y^@#+T8k-iY-28HZ+U~FPe#Ud?;UJo4=};-pRe+zGL1_mn8Skkg%f@ zc))U2qf0v27B@o1|@$Y0BJU%h!{5w|a1q znG&eCdj-_-vlFkq%T6?N=`jp)l-@0VRF{~(S#rJDLY|l}&5OX1;!cFRQfUm2`465s z+Ovoo3oVcnYGj8P<4G64U<<3sL0$U*qSc$9$jHP_dnJ_zVWG+8~5~0?sMBTm z!uJr`-vIfG06}KL{?l^m>h&Y(#3XNCD7Avw^Jh3nDL)%2y%LipHFuAOODE4Z53?_| zQx=f+Y!agAc7QS;`p?H!AE_;&oZ8X>(yrHO-pb}Hi(D3bcNx07R?5%IOuP$UIq#$O zyJ~S1VI$KD_~j3%He8UQToH%;ZO_)#rPHCb?(??+>R@s-Tz(_IF59|ijMKp=vIc|l zSlp%=YXY~yH0sk(6ha^GuQhy@TN|(Cpi>THlvIBAYVhkgeS6Zg!j#g@z{LS_mk-D~ z3a}bUfdp(+y{U9bh7E05;X0Ykcy9gsPG8{P~=(9H73ZyS7eks zuIB@ezOd&a}R4v{wKlc(uK{5-v#X*t1uh}dWB#)GV1 zgDgCo{*WJwk@#Zx|B9hAjOP#Ve=3){OY3O^c`QVn3@FxX=v?sJs(R!xBteguyF=Rk zK{}GHg8uYdpi!ukJi*lPVFInRD#7MO+6c#W3q-#18lOCF#58X@g?D)=PeH^1iE_7zWE?N)eNK+UW;}o;liGeu);g7AdNL?KORt*b7m*?H7(Dd zqAPktsOR`$5w&x0)jQl*`*>bBm9g~Es^sQiiPv&<7V=O`!L!AEqWbY}N$>(tvVgRB zQwSPU{NL`k(y?44G?oTvq{c;J-mCo@k|WTKneq+CJCZi#Nj5&wQec8cfY=}jetDGM zTJNg91dD=Nz#bB;dAk*(J9%6;6*#6{6|?QA@s;p#nkGNAH@$;ka`oITUQLH=4<1BB zV?RZE_4l*eCEz6hhv%RV|?;O7?Y-sIwFf<-Um~LGOe>QUQ$F-d_QbXa} z{)|#QwOzX>C;tOxFI*sTl(o9+2(UfN7yojA!?6zmeK6oq$7p*22Lb_Y3Sqnp%*JiO zL{Oa437q}wR3O!ti`KunqR(SY_>X?1Y+4hb$o*Q*u;bO}Af>m0UXKoEE{eJW*H8Bw zWFp*mbS|T0Z;*QBr5U`rwRTQ5$n12$N{D$!Ve|CC=|PdZnvznTr26>VDisJ-TU-`F z{7k)Y7oPElKH6uFsf1!P-dK(+T$uTxUI27$@5XSQLwSMs57jU;K{&(?6DJF zH#2n_W4IKSO*g!kKr^NphVTD_pM1FP+dp*kz!e|?QdcPo&>Iv-u`;#;;OLqs)L0ld zB>I{=R(pC$7l&;4!N1iX|5YI`h*Q8uQ?>YUyC;xW5;?Rf6n?XQW07}H%n^0gIzF94 z?@u1gv~(4nB!MoHqQ1VZ53W+FS3ZDM$3yKjPYn^U%lI1l)q9}>nJMG?!TJ)$G=~8l zs&L%LszdKM+})mzi4dspbTAX$5}sl>|B)sm6v^wa ztS+j!8N$7%{9zFEHV+H6HCgkP`d!_m`bj7KB$@S+NG_)NtCHGDk($g;KL=`@2d`Yf z$UU<7*bk!JNhTcO*vE*jBdhY^Lh_-x+6I+Hk+WZnQ$jiB$<~({_3MPr>S$%Bcv@s9 z1$M|!_@*UEhfY_leMq1~h!IY6RBbq%m8F7#`p{lS^Oe|;4MUVTp$z`+L)nu0* z3`|hUx*uj32sDOn;Yvd?GV?L+;> zp~Z^g$9$?#3e5RSgV)Y@`8TOVrR4o#5Fh)sI%i??$+dMLm++E6u>FU;;AzEAd->7Q%;HxwWV!a+rCJ~B{}QlY(dlbDh+(m4c1 zlUh*4QJf|z`|kvmVRW*IZ4ZYB;CSNnKxqUaad&akzs>L>W!-tXouJx32qkY06;o3Lcju3 zN2n!`OYI*p5fe(V%1d~W-id5qtEoEm+z<71eanJfeb@AxC$)`abL4A?Wa{qrnYuGv z-m;!kFdQM;(JF{-_MhG{Q@#|ddZ6X`Y9Rd=I>b1%!fq(@s+Di^`8i<@dP&6e299yl zcWdt@(rzeg>l^Y_obIycZti<6(~YmXiqLDWwk0|Z3id)6WpXHeI#%Jbc7H4H6mY~$ z>}G+XXoZP*1pV{{-`wJSiG%ugmf=HUz41V!{E zB-h#bbi=?X*-8eDyUBUvrJ9wj2dm?8!Tz=NXZ6XBK}TT44{Wf{E*B~3IA~@~LO44h z=yzO~`C2-~k_Ixk2N9w(|K=W|8VzBsr^`VmTJQ`Lx;OS=C~eKVyrtNp*@Dy@kQTMT z*5u^Y4Wl%6Q#sVpD|LSLx`wa&z2J!byph6^&Y@9&<%Jax(z4>KK7-A9;)XY$<>}NG;oi_65%-#7sz0> zrE6r5u7IKnO8WC0->?!>h*Z*@hmLuC)=3tlvlRT)p-V@**3eG8#)~d@dVU-0 z&JJC|4B@9tIcc?`xvNy`wec9`$i33j4eQFtX@;%&4z{Xpoixcm@(m-&C zhCJ{d$xeYxa+HoBI|9;=`-ma4-XWBc|1qNGsC`m~8e`}>NW{dpA9ncwv&-x5;ubE@ z`MQDv{9h&;kNtm*}49BNi*pxA4UNEK@mhjV8#aS1-732;AQb^5POQ*ef z|F%>mIj6)Z$0e#9aHkte=+E)J39D=%g&oqVPHz?o5T1E6n!qzBTkc*k3~aPsoVe=j zFHW`#g78*Q0LGnE3=SWn38()27=2e$XasGv=7=tF6*Q<}Jju_=x4ru;0ZN5pHK^g< zlrsHsep)4etpIy*Bkuyux6Frh2b5Bs!RODe{%>>6e2`HGjdGo{L>cVv{-F4dV|QYp z-Wk8tukDVFKt)X^;8aM-l-WUe9>6s0)bQD7lA4dx9^P};bxjNt@hm5#TFGVliIc*; zWIer<3XLf3j{6lp%?6;)|L_<`Jp|Fz)706QL#Y1THpi9C^U#-@u)ipvkB7rTHod(Z&ih3=7s=RyFQ!Ew>a+)z1 zy+c!6>S5xDf)1)kQw{E@TYZr>j!ND-L{n&gyU1_qVjGrCDc3TXyTIv_wyr!b-@4-}lEgzTAqp`{*g=UzmCXopK<&9SjE@TDQh^FjRO($L*#BFH8ujjo=8 zEXwfQX68?|t_lB` z3QaTnybIT>yp;$#pEfaD`U(4tOeAsVWZ^OOKE4YnEeeq%zkWI<>XsRsyum>?T<*a7 z7NUu)At@kp8gj1WGolmV`n-;+K#|SS=j=gjjp$!5mw})X$>JE1a?lg|v}Pe{8X|W4 z_l}Q6Ze-ku<^~su^=>(NA-MuRC%XPAeK9m$KijDUlnpgWJE*jv{3ys5isH;Yqe~mh zq{wLlpitIaG6X@l#Jl`!k=9%Frat7a7scrc7wj~}Kbc+z;V$@DYi96?GZm*^tb6cKJWQ#0;wS`&(L_yQu#8+to7S#`>M7J-CNcn0@$hFAj;^-_uVgVZ{ zjz6Pz!Yn3ml!zdJL1as50HQPgo!7OQPT?%!1TZA9ZqUuJYD}ZUvhHiu$28 z5KYM-VMyz#ESQ(yNsr|;c@RnS81jEU8&h(>#|j<1Q(nXHF~HfiW|T&sWUkPe;P)Nj za8Gxxf4R3$Yve3{K1q|GIHd{8JvCgMAu4^gBfGIL@r@7bdsReRoRys`jxW>6Hu;+!bv{)JAZHc8n z%L@G~6`U{Ez_o{@Hm8|c*{1ugc_-E~P^oS$DU8g}V6mXfYq6TxTx%xbu5({FYK2La zhAZ(Y2x3DzOlTIWqn#Pky(`?mM#s0W-JycHhfOnQ8ZpA$?>|%Ki>24dGoLQx+awcQ zP_^3<;PrB}fJ2^ETWaTeXD!;#rW)F36NWU{SiEXDGs->Ac8Rr=xITrx)vzIwVTMq! zR)am<-d3IP=9~Q`F4ie!xb@(G8zIiTWVU0Jy8U?`%@&60)J-fjPRs{bP_qy#0Mnx^ zaZ5fRMXsEy@b&O|JNx^1T}Y7%y7|rpK0bJNp4q;#+$rMz2eXxfzq!EN1r25rwlnP} z8bf%pA@A2m*G(=ADr4V@Q5}a19fsz$k#Au29JFYgVBMLrZ@i6z5e<{oQws3H=e-Bm zVOppwn+`VQjbv9@?x>@`V!2n$&v`|V6AV&N(1!saLbQvJs5nApFl9q~_-5zODCOs~ z{%RRUWENdi52aKju%S_vXCj0O=+6O2mfPVoY2&5C`3>{(-~eyntQH>VG1Y{47>A{M zHzIZ}a_-SxL#PhusdDujHWd{i3lDY*POoEJa-3ib_I!pyFHcD;&#S-NJ;NOTK4LN! z?f?~GN$lGo(b^dQHrj~@sfxu}5!V8I(`vJMQ0@ntQuNuX#%SpU;q$HURXK^;81+&JML6eep^VzoX&rz{|$7wkzNF-a&D^~&ejYr$KVo^^Ua7E#Uh}>l{KvdCwfo; z57s25nT=etC}gudK{5Yp^$F+^Pv+K&&fV{Eknd;5rwZ)mBE!}s>Wys|pmb#!9J5xL zwUJP~$*yuhg(Zk*_AO9#U|DHg&SyHRXW`mOa}KMNtk! zxi8sC`SJ1#wlp9L)->S!1hHIXwD8&c?o#ukFMGM9L5K1AF_l0(kyCfKf zx*-7SM(IZf5L*>}p7{*i8j+4E(@08>Raq&LB_lCim_IG z;MbOgIcR`C7LF6>AsMLtu**yt`}Sz{B{xW(+e9>>coQl|*>u6Br%h2CQ5_$Kii~=Enu{?aEi!aq^gJwV6;AJ9&SFF$jaz1{ z$p6xy8%3j0!!bMsDzYojMB#K2RKZH!w83pG*I81dG1LciP6ZYfR+_$H;rpUQkf5L; z`w#!^l|rrJn3-#68w`l69KT?MI1jIx3T*fsqpp(Jw=S1&3pr1ur)_ryu@kX84A?U= zHR7MFFdH|$*ayqsU+6ui!bu`!xxWW1`}Bu?E{2kl=$WY5_QNFt*QnOaHPb%-0c{XN zcQ^)3Ugdb9B;OP<>kD77TTEZno=fA7Db@TU$10zOez?L;N-j;Ka{D8r(LkP z!~kx?gEy;qJ7*(yJfZ#<5T7Q_u1}e46b%|K1$;y|h3g-vpg7g+wi_laRnP%s24bBh z#0ka7H^&aOkCLfE)pHD4=R?5krk*OH3G2?z1UIs!t4K1diiZh7Z9u^moh2K#MI!S5 zXfa>+*hs_cY{xiuGLjcSrj}z25vy)OYjSqL#c@PthM9=)a%{%T!n6TU!v0Lsm=_oN)Wp*KVU z33!5!8jc;g+^vgv?1;CnvIy4w>Qhmlc+U}bbnPZzbeBDc7d*3Nw_?detvX;`m-X!z zKP8VjF{-j5-_RkU3H4$Vb^tsFlQg)}{dnoqGL9_zN{Y3z-Tsdb#N*S4!f;kWKThiR zJe^I=L__g2MqFD5GMHTDOg}rrWqd%Dsg^OW0qo=oPCBJ@JAY;%bDeii^&BQM+l7F1 zGcWU~j2eMRqYO`JB`q?3+VK|FSgxjSFr>a^BOVZ9Me97GgkbS~f}-=$G+EYkcSYkc z$H_DW6w8W!upv%zhxh} zr0gsO67W4UtN+G52I4hKkcdE8#5dMFLBwBG6#pHjm~FWiHgXd{k_)W$DuW3KIQsnt z48~=L?uVH#wOEa-0OT{)MG3521yzbYk6c2>jkR*|e$}OzjDL&Hwu7cZ&OFS&kc}t9 z$%h(p?^m)uTo@GsS#pcA%C=-a1)=820BfhQc+mz{N{{^n&0D$ z@@_nXtqtBaV*#~%xhmM><$~0d1cp&DgCFLTDnGq!ZFT>L&kxKFtHq+}elXON1)%$` z_w*85bqMxPD18qrQVuH>CMM3HYO81OOFS3sn>WTVLRdBs`d6M>R8gPk8q=Z<1vU#) z!Pz}wLze$I)ZUSMa&T=Y)lE6>w>fMLGcOadbp8OQh6n<`1G~cj3iDl-Rljie_-A1? zD}j*L-aWEPmhWIg&kKb2ltt(8L|FY|F6IXn)r-pfck zmNIsZre7pwFILftYT^q0_jUMHddlkwx|wuJLI-IA;>jB2yYJiMK7Ov@TGQ863h)|< ztT<2rSz0yG|3l*N_L8)a3}F-iX-b0SK3$p&^JvynknyFx!i137;=0!X^Ck7(botO~ zZnG;zu%i*j^w2eT!p}HhyD_u17l$MYK6zx?5r<}CTn;&y6e}J%{Pz~QkUY@U?P1IQ zb30eZ%a-RRni|?GOEX%QbMU69UWZI7+~oi@zHnNRKa`w2kQk6hQ5&=j6|0gttf`

    je zd=r2uEA!4}MR{Isg*Dc4=I8?pa>7HAFL|Hy6Tw!<>7wz1-_w_~gu#P2k4xY{LTc(5 zwQ4<-d_nodT3I>MBZwp$~V&Xt8Q^ zSiO_=^LUfj;psU3je3mRA>2s*k9;}m_CZqJ#{tILP{}daP5()teGYK=K}BJd_#y=r zyJFBdKS+?dAi5AU82nwiKVc9k1uPGr?n!E<<>1s*)t@;yKc%JT9x3Sf0VP%jr0CS? z)*(iMEy5MhRf(ITDPe$%NFn7k^`zI>{*y++Z0IEV?V4>#h&11H);e$>z$u^IjZ_cC ztl%MA4%;{_^2c$c%mS$f*6+uJ^tOH14Z=mbLAq{|GUPs0Di;U>2vg9AW3KFzLf1m5 zy8)1vImjz);8{3IP%x)snk_5_t3V7i{_R->3bwJ&kf6zIZ5$nZq2SX6aZDB0XAlEZ z6Ee(Gqxi%ombcBF$)<`jo2TGH&Ae#-vkceRY&l&?wJ$?{7%#gk=3we`q_`wtkXY0b zbA=6jfRL}2IV!Ydn5DATVfmx1rZK4SpA!}dl~n%)p)T22nnOL|gW2(HHqam57+&a` zi1I7nG&O)VGfmluP95&}_S^0X&XX(%G)dZ1+4?w{y#9)KdM3~Rnft2}>{C@>Ho>FR zIl*m*7!~TNy_igpV|F&%Womcb@sm*SD?)Cz+|qWt1rC}Hz~RA;Xdu^T&-*-}e306H zRlBb)A`A!1u{sj-!vR*BhW*Wz_qQ+eQ1cYV`q$*13I>zUb>SwL6GU;7X{KuOQc1c& z(tUD&r1CVmp|GoHj4$GcNX0-x{_wg(Kex9S?|geckMp0QAjK;d3trjKIla$4li6$! zeMfhMVf&cL2?r+6ap{Dt$7qeTRB;V43G z5XBhONasbturC4Q17`Hi+$We(YU2)HzEuwW*NPH_SDWU$BJSeIDGx29ig(Nc2wxvG zGS51q#@731)1Dw-(y3iMg&~2AK1S{kS{$Ln(f`9(ZAyy?hW9SB-BUa4t!?38NaR-V zN+mhmLjt8$@#G8#{OUO59hv{0O_47&DW%oBrZ8O;=u2f1MrJgO<-2FKf^`sMTS+O2pY!iE{Vaf7GDmkF{@3)PXC0`= zVSWw!*_f_xJKu$!!?>Va%dK6dHA2-F*fT7RN|_d^ypsq7u!Z;&I$fdEcyp;uhhe!#mI@LIEc(3qHCe=o+JSB2DsxD3Bd*`!SF~Fvaw5ccB zP=anqUPo79mY!lj)XR@L$ohA1qkm>}e2_jfE&Q$-Q6emE9TBgA&)i5^Spc$YUBdrW zy7qT_>IoYHE8*0M>pt|tUtUN4h7y^D*H5o%yr;C8|w!kt}t83eRII|8D3C zntci37fko33z~TRYHAI06v$jzii|)Ks1&@551f#|Z^D0Fiaq6f2yo0|>!5Y#5tO#% za#p)ge4#Gt%D6AfdY{8N1&J`jxnQnb38#y%_w-$VMsI~dwZOn7=IqXn678^h*i**N zTu9K+$C`;gI?7@rfjOoAQ;(`DU_X42kfer$dQHqU+~>XBANExb($uK@BqB+p&a+yt zx%T`f)w3mP)~nEyz8Z;Sy*mFS1<&J1NZp+8B8%CNnxJmxe8@n z3}*iS&m*bD7WhF}su|5)2edeK>-$Y69~I{AXL6A4t@IDO72HqC#x5S_u;ZEKcq*1e z6CW1Bk~-%`|8&iT+$jVuP^fE0rMch-0qV4}`Z{VF8BVJD4gUmlov?h4Q+C6b(85>4NQKUN#&cxgruxfbt}`kw-45x%S(64V1+`13OCTFTnI zYe?sJaS1V3GN)%0zXocM+IU%cF*_j!GoE7W}uKXZYKipL-;l zuKm=Ey68VFZpA;5C_FVjSs`9P(^A!aRvUJEfpv@J>q4aqohueRn2Ke|^S|`vRfD}z z(@Y#h<=in63vksB53pn}>7=d&Aw)>GoJ%cgKiSfHVRWjHpyw8_wvkOV>E0m{)N|=2 zf>LNuq4Q0~VB8yWe?OKF@%6#iw+-e>9FOzJ8^vM@w-U#{{Au74e!tBUgCzt#I_z?6 zoQgihO33&w;k^ajzO9um9!b@VWO$vy+q4@!Mg$Fatn?Y{*RR{X!_jH%1QJ1aL83Mx zgVL*X7?JOA-D9braJ zC;V2X3?`o#ia<`Sq$+cRi2$@KkvF8>KvH(8jXa0Dt2|80JBC!3mk%%8Ox-tD_Rwu~ zJl;<`sfx0pY)PPGu&1ykqn+_Mx?{zzy}IyWw(w?MBn4o_I{6;;mB8$0$ZQ zI#*A-ro+2YETcNjrdB+gc>Zj{*%ddRuie7^*RoXTUh(QQ0lg>(G$#?}RK?*<9FdJ%Io}HaRoY#`gD6I2t-!x6m1E&EaUm}b-B!%2tB2qDL3Cb8AGcRz5I>U zp>88!hN$0WUdBf9FHT_2a*etE3wKevO^$RoT6kw6sG8l(xrz)+vcl+<#!R#x(ycUzqde2t zF*DG`h82fLG`%Ij7Gj}Ap|7Z%mHeHw+@}37RvmX8tURW#-diQj{D9WjHoB|lGNR5% ziMNilq*-nZRw9`sn6$FYWT%B~v*-TF=Wkt0xRVIPBXY%% zgaU=#lab9pZ=~+dXWIe?HX0>(10hU9>4e$hd`y%!KqJ&-R;enRcwt!VQ=L^0Jsb`n zZ>n)(=pfu0Ls(quwl1mLtY4DL&zf(Ymxqjg%?cm!z3=PU=IB$x+bk{r>HJsY7wTrp zrBX^keO8>4INO`vb1*sq^D#P4;dCEwLPYcqGQk2S!8WK-UrU4q|2*%q)1fO9;jRmtx~qbXrk0-(gb+bw`mVVU@^hQW6Tbu3R4TR&Y#Wb-D|^K~ z?Z-kT2BqNw#WwwG%|DNU*9*@zlBF{Jg;@meed2UgP>Ned9s5~8DFUgAks^mz`a~$@ z?AbeqkHeTOjO|^-;%!%^T5h^=7ZRSm+dn3sq}l4)tyzOh3a*mnw_n2nDKr&V6CN`=3ODjd4`% zmpJ`++Y{LIKdK8Q-0udIm3v^3VY({^D9YGkC_ey&)6dMjyNk!{%& zbPgMaA6D~Byy!xO$4S%Gx>OEAe2UbaeV`wEsk4Kn`^!{&g#eYGuK#rQ{mTYYn6!go zg#QPeEm&iuUujh56eCCAIWjSV$Qyw0x$k@nO9_h zLY4MDTr<3lwuB}Qk0|H+&pTMOi<7ZVt$D1pi7M${g>&g2;lt05R<<3R0(@Chkzo=Kkj^nZ1A1Vm7^+X=b2L_q!pFs*qDu{^k_*iSeDpO&@5g>t{bg=-LRDTpaVzW?48H~~c}hj#t-r>RfSJr$t$&rJTb`5EsAxYr z&7j-PJ`#Bn`KU1>=hK{kIf%e6@!V!`k-784hWyuSz_cx%r}-^qNftp+aUrd}T;Z%MGU@&7;Ykdl)^vN1?P>k1=~!LsO>lG}hg&R13kmxS;r z8s3UBC9vkCpfVU-_J{CwZ(3otimQ31S(TbS_ewEN>aa3x7TRtFLNwRwK!A#HHXhp!z7~Y#X9Olt&&_3Ej@FBLJEfK+Pf_Bnq9c9sR(M$vH zR5vhK&xC&?Mj%QZV3vQ`7Y}0{&wD7OxCISr(aiD^4I=9C5beLK$@iyN=VE!vPCU|R zL{1r?pVR1?2GY^vQq8!DW0?)V*8+6v%l%wk(=FLIxg2_`qMYfo7$DZ7$`ECW05FfyPmac)iTmqFKJDfPekH1E1b1f2TlR2#T)z zn!%g!FJIOM^I&`3DVmtiRypXF)0L>+1!HZ<*G&Q>Mww>O%hc^wq})xxL=#pxuI%%9 zHCJ$!L-5A!BRyT&S6_=m5<#-R6R2|xm_@-Fhe_Y_8$HawJEyq2d)U>(b6$tX?toLq z)TnkO(Sfli?@!C}Dfn9@S+$$FbZn@K6EjToRUW&+)ETAPpmZHlCQn5VW5U#$9&b1xLP(zU^ zTe|*C5Q{8lYQQ8Z9?53U``WBUx~G>^!XkS2XLPO`hK|KiOW=fOHm=iT zH~0H|5s4yzcU}4_7F=q%g#>g}r42J}vzm&#e>#@2(<2Nrca9Zn9vMGK8YpW{z9U;e zwPsZhY*BTFHSr$rg#s%KGeIqz-kYuhH;$UD^OCLyP0qKPdU#bfDIeuGHmC2t>YiXO zc@;WTzc$W!gdhg9nIvR`xtFyjzG8AwN!T7ZD4PDMTdoBX(K&l%xyR^kob^N@TZqSv zc%JZze`G7V6e1^R@&Xfq%o?VIQ-=nJBlRGHfcxPlT5W=@$IY5cX?i4REw!sGlT)4zqQ_=CDXCuV&eK+8Jk~+%YwKR*Dg|y`( zKNA<^vSV^agnJU}4SG+PMCU)t6k;64z0^;Grxv9(Nk?bicno&7cD)qNfuhdm&zdt- zkgZ-HGTCFp)V#%f23IY95IOl==1z*kQx||%V|w4@@X4|bwSiz-tviG(p))A^l~WWC zVGc##-$=sUL>c>$_o!ySGjM;*;qV|VJFj%=mgplgldS!_kCJ#gPBT5F#`F!q(Ub&1@$(@e>y)RUL5_@Ps=ay|_*#$S2ou0zdo zD-U!V>b=KSAL0|W8fbpTFT0_jaD`0Hsyo*nO3>f}pdr{xwqMLw8WVn~8}UQH*S*lk zGUn&@t=w=!)J6BY8Zk~<>+2_(&^fH}r2XdfV^w&Dk&+dV`_pQuaL5(j*+gz>CqDhYZ zMsmtt>zl@p@kbO6fES)i=ejfv^3&B*aj_WF$AvBf!jpqihT<2%d9?`ns$vTq{U)G5 z?HJB_Kp|`r*oQZ|I9EX(LR#WWA?r3pem1YasJI2IeGR|%?`=SwyVj`Dv$;9G8TI+c zcVeNwNk{~Nm@gci)DpT(&={A&f;cjX2CnEO$q#dZv?nEZ+gd%b$=r24=7M*)8{f}n z2+N?X36kL<^&njDB!oF5!dno!cZk~kuJHCR5p5gA4& zW;l#Ert*K9lXOdR5h+l=JHHz@hH0lv_Rki1k}W_ock~@s8Bg9xratm2ZPBU#ejE8e zR2WGbua-cLpz5_V5ngg|i?J1eOW^|%YBfuaB8gAneup@QZ$z>0rv7BN=cb-K1+`x~ z;YDOhUvdjPi7(TZD^t0>V~!x^0t1p<~}ub>PcKW{=)1{6iIjO zl*Mpr=F(EtFoT8xi)(5s{VMf)2a4(Zu@|HVO^0veM&=VfK@%`w2j5`NF@lo{C~-go z)40Xvq7!$OyGo>3M?8;ydmX?h3c-VJASlFj!=QiLK6dDd&+#4j71Mq&fyv{MsKew| z4>8DngTb%J5OM7yhT0f!3n=~wX?-2T5my$P^&bD2Z?F)tiE`tpbZJb1l-dr%HBqZB z4Cb9xuoTCzI73l6ciVRi#b7BV2d4HGRA`z#rxO-+_;7Rl37s()6;=71R`}Ry@S6f~ z@K%i_8n+UqXjDTNDW4GXml?d9t%^B5JC@@)V*bawc0LOPNR%i%WI$PFw{F|gQRTmfbaHlXPJJ}eTrdoXz=pMbPPGpkA;rSqcNt=|A{HT;1o;NYsHBcf-O7sM-{u=i+u#wa01% zA*3SqwUw6yQhio~55i3+yf3>QYPwz zS$P6tIH{hq;6kVleB!WmthH~3V@kA&vfBLUFC9$X5-5})C7D}TzE_1U5oQKQUvj|K zAoq*b20k675E7qfZO41X(APohX|f1w0MMDvouSfg?U8m_jPY|lgUlzRr38Fe-j>oo zd{5m;-9+a2WQAUfcbJ-~@&CL*88>S&X+*Js()$%7sSCBo26IH&pi^9GdkL`4)n{Gr zubtI^0H93xWo>D}N>1h&D9r_H0Qwp>Y%GllQP{~QI7=KTBVAyiAnM$vY$Adrj;ME5 zOXQ2x2KSg&*+l^ztBp99E>J^aIeJF3W5h~s3a=} z1;SsIUhK$hOsnXWN@^=T4Z;nTUeF#CqHWd=r>g92QNDs@1T7_Lk5h?a;DsO-iBd+| zE^vDV1L@LvPcEvr|8kHPa*+POfc_EBKg%#J}X4Wh};R-*UK%Qi$8Nm71BMt$tpr( zc~Yz=?>R+%-vrFpTd(x)8NC2Uvi~hvQS}yLnd?nckN~S7$SlC z8uvGxC2K8}ckB5skjxa*w9@to=W_MT>(NdKxE^+W#n|D+;@La(#Q9|j74x-4J>z7J zoVUJ7C6ceBz5q}Qzj&flq$FB!QJVeF)TLNoZ)4aAG}W_UZk0?ctpAYO!q5=&2<|B$ zi4dJWFnxQRAT>)PgX;@)0?|K2C%siJ_j4n;60G8{mnyH|6rB49-ODt^c^zva8J@{X zVco(8S1J9(kXD(WY5x!(gagCaK9^&YB|6AFch7EBJZWMZ`K3)Gg_`}Bbv9;Zb6=sd zD|_WdNzuq233=rc57pM{c2|o{zlKl?JXTFyoV(JiRcu)}on)PVxmn7!{R{41OkGF` z7&dm|fI%xyKH=gn_>6o=meYfKXt8~!aE6cEh=*^0Iw2DTzyOhzA1tNa6{bhV8hN;1 z=YhPd%EKJcEZy5PS||~*D*{WHz8C<4m>fvw>Y||CO)#}odjr!?-CepcN@etlB#5iv zpDfS);j>v(QFLLy-N$+D2oXK|*&fygr%TH!jAGvuFvbNxuI$l0oTid88K6Va18;PE zjta^!-~kP!a6*#fI_!{#*8+1GVb#PmX};~1t7^^FX35j8VK2xzUx$Fh=z)3y09qWS zv)z3{wtB5(Yf{mk3z6aj{V#6Agmnuc&~E+3bu*P`sEC2Sk0>p9G-g3FDylbX1YPrmGL9uoCZabhNw)Sob%S__5##W;e?139HsHPYmmU?s}5-5*|5LX*Dl(K8U9#j)-RsEGjM z6-NDop$P*~$xIufjN*4C)o^WrQkm{q=!4O{k^oKZTZBC) z3M0@w^J5StiwPQD_f@2;61paD?(lUd1-(RLHhWq6*W}v_Yb5pPFXfS=7*=E48cVsx ze7*0I?z{>iJ8qXljA|otTdpqYc+YtuyepLPL64&a)~qfMm3M29;T0DCa~g(dA%`z3 zN;l$@yzi_&S^5;&LNipsu4CqM@f8f9i$z0mU7o>jA>~krT=vjU=_6cbE)_(h-J{?7 z?sHDS#Fc*~OR{G>69_S%b}P2oA?gS2F3Ct>`h)gQU^XVCDOuIzvh@Dvcs;~K8U--f zAS*3cvbple@#l8_8}uuA$a72CXJ~`TC z+5)OyER6=Sh$Xm`q@`S6TJyZ4p5&&aD}}<^267%DYqn293kby>v3oE-x6N}teg^{} z0IAJ(!!6k;KgMa^kSvwI2B}Me&s#4qs>-@#Yux0LR95cuQ8zW;HyRePTpt?``7J`o zK*`tv!4f5)16cgV{z0n`3NtIiL3md6I(&4_nnc_S*G>ih%~{Dah7)B4ihiK-gumH1c`yjQ#3iM@l&?T{1X@c3CpxzUX|-xSH{TyV`VKPb5H3rZ5lG#FbQ8epMqlEs9JI=1 zrkj<4VW}9zQwUG_&wT5T0m%Uy`%)x4aHt9Z<0kI)BfIcrB~bfZWS{ z62ZfdX5i;v3kJJIO$l`MKjUc7!#wC%I+oEWa7vxv(U?^Y@(*ys@o}xW8vP| zOYvaIWMdy~^9!9nl8{^0o*F>|n@t_L_+N8!f2N35kS&3snkb~Ac|HPBbJ>z^&yJR={&;;X%P*;8uE=YEj&P|Lv^y<>yYnKI+@+cE^ZP-(wPn$T$=f|}{ z?xF}NLST4X93$zOH8>4!NDMEyJZs{t}HM%E7sJIsyM{7n*&Kn>9 zwy+&vG0KaC*iwH-&XT7Ed=CdfK8$0Fzf9(7NCY$8zZ2(|$0hT*#h@$63QzWKtH6)r^nLebasw_M z4ADoS8}px6Q~#$GL_T4`d2u%16g}S)j&Uy$FT`|PjFIaZp)zI*nG9?%J01gvB=PA7 zzf52rnv$X9hvnbG8oAReW?$?yz(uYyz(^^QjTV67ocd6e8wHs{Mn+@*$Bg`2*98M! zvmr4O4|B{e0Ci1_)(>&}{YU>N!*UvE0WnBUku7?RY2JWD%_pVJ0!+{?9gx}@M!&L0 z@}OZIo;y%<%NE%mmmHh_Ntn9M{63%RS{WP^8pEWE!I8dP@kbNO1^oU@-ivO&b`4wi ze*Ncc&8%-~oyr~KKP7>Hl1+bt*@C%`jA6)f8na}XuuW;(j@1-O2{*3THTWYSLYNGM zT*j(oocu;*^x>V@<@;wwauY?kgx=!2$;>Kh=YKBfGfW1GFVswEg|?P` z0(QXW=+pR)wBH02^#fXB#)0~Q!BP@P$KTvYK{E)bN24x1=G^D9HS)7q9=U0QNsTjF z=cb+0Z>5wG!Hj6^u^LbV6Cc;wNW4xX!We?Z5M>miR3Qi;FzB&R zN2Gv^Xk!fuw&|7ne8@9{SHs?sQXOmBiY^k;hW0($X&hTA_hp$#7s6!N zTDlqQN0NAO!mvU1j8dA&j|$K-$RwECRR+1ZW7dVG?%7vkQ#Mzo8IGQvdWKEkUwX^HoUjz#*bINo>;Io7VeehR;;qNnYw_nvrI3w<@k$**Aj)YuRHcIJuD zOOQnoOHn!;!Y5N-=@(K->RjH2>W_2Hmx_Vibq32P*83ZEP+*a7rKz~;vzh8bSk1Wk zC|uv{L*v2>3^0Sf`vRa+yTl3-t^V7)uX5W1OZ^)D^b8gEH!z(F(|?oYk1_OkI>$dH z_%@OnhEWnF|7*&vM?VLYmWX&A0uJjoW+wJa2Fv2nY>h_3YG<6}sAxN1L^j!?tI$KX zr48G+buL*cbaeH`3m)vbubGnW=QJtQVJ5RG5o1QJSVVTnB_pi3NUcg9uDVl@sw3x{ ztTnOJ<3i%{@!goSO(mF^+Vii+lU!IostL)Q%?JtE9FMA-*YgSDBnC7XVPP)Tq0ssX zmq2~VQ{eo|g-$`oX*?BEy4l+je(S_NN?yh}9QgH`AeMfgm#091rCZL$j!vhX(t?QQ z#Xm32OlcXzT-cCO?~mi1T`^Ecb7Pu2mnehKLg<(;RK1Fdz=HFJHE+UOnldJN z3e50WgV<1NrVN-G@VCKKjp5tZrDe*<--34Ry2~_^Hv_@ds!TN;dH^jz(!c-TSzxIa-_enpGTVCaa;9+qv8<%RIV+L>L)rl&2w zya9C{qH`wBZ3(JBRnC4YM~7mMG>)#iRzD!^aPa_KdB_`!XUhs~Z6v9oadzOZxQ(9#v=?ikn1~f9 zOnanq3O-f`)2E>_fA8?=FIkH^z1}Q4YNC@~GlZA$rr0zpo(imy!X$s?qIxQ7iy#dI z2i#EB%^!~U$*2{{{SbkzaJ|5U_m_JU<0(4_fw?Z!^;(a##>(wZReL^Nhj#Ra{)+$*|7fdJHO zd=kV3+BJ#~1rY3i0ITfKAKdi~gvWh*$mj3rtB9at{VV!%xBSw-qCmQY%&n=S-3(MI zC!m(Wh7L>^*dkpBg?>s1cthkS&~d9wJ0I|p8$K3r`3U0UGrt;rSrhP0x^S(bU}I}#?UN&x>rOdqxmw}Z zeZE15g>+-GuJv|>hr;NE5X7~=LEp&j?6x3ynEQB@y~wjL_^pekgFf*-$~vpE#pw>X z_pzdgb@kM)L!AU9$g*?0%1I|b#IISQJF$*nRc)A>a9s7vn?XPFEN=z{hqK?BsWZHb zTaquQaV{bH8ghe{_+x>V;p@Xkni^qcZtW_90z7XR9%(|98;8u}?laWY(KAa%L7LO9 zapPO`|3eJ&n+P_HXm=*y8&S6)-0RC9oyR&l;C;rB=>AU2uiEb8NrkY_EO@Vu3p(%O zwIypeQmziE7?0E=I$an+WmIx1{zU`6&V!95<6FN_5Vl<63;cvgX#VC93+=gi7+2x; zYX=tk6s*?G36PCg!}T^_K8(hqu6`7}+_ZdX@d`VD+>XM*;Gls{5z*nQNkVp=^h|L+ zA6a{eimIW(VvG5rI?F!5t?~;0xyQiWZ57;6IQ zzpCpLmc)y4CZE{dM}l~S;efU2+l{8t$Q83${7Z}r+yDbk)#;w4{;=FIt)a}lnOFH# z>qfZb)RbV+2w&(x-As-k)IO>x@Ab+Wi4+wWr9)+2DsxBcUui#NY@i4*Rx#8qOMvsVUC7KWhS@+laWe<(YHGzv@mdGI6m z3kbv8m*1m{nbCjiq7m1n5(57SC~lq#AAdq^|4$r{urS<>)5|lp!?2PKl!($-2U3BOFUHT4Z4rTWmPwJ(CKvdB z(#`U>K9tFi?N{b!u<-2M->K($d)(Hq{N0wdw}TCExERZqJd?E9e4z_ix)tY`5x=i^ zyj!b=yc;66{auuajT6O?Xoy?2D~Lq?7|{se$Upf9*8NgRc7a>G|T64)1!HS1H_$oM>?HnqmV`9O?E5QKK(clA~&y z#~3sm>Q%gB52oXgdBEWmEGq4%l4jQ-laH9{iIFl(etTs&A072PqKhG;Da*yA1VDCcQ>`{*=} zMd0bY|4Nycbxu(I_5E6+anj+un}uV#^myEM0FC|mk}bp>OfE*^SyMUrfF7N|TL))t zGDuO7sKmDY@p+Nb!eE0$oB8(q6FNh*A&Om97Uahpg_u&y@@UYwy|+KuqCa~t!0X& z{^hvU&5oDicOrIKKoAOc#dmV@oXx|75|cXrD{<*>@l6)@XhLD>%3>##cU6>!GB zXKV-u!lPuHEHw}F8`JdNE}UeFgj*;^>|zf+E@HcGLy9MXcY7tBm#Se*b-z;~b zO1#vw!#LMnxUdSIdJBRoaBP(tL0S$vbW1hR`G($_kgSW6W%?#y8HVEJ)2C(kMje2Z zL6@c|ZFbXZ&_Otp-K~?7!ldXq7;_tCfNT?vo_zPZO@xBop7{VxOi{ElLLak_u*fxj&N1O_0c2$UkO_nn~A^V(< z`avVDcjn6o6P?!t*G9oFln}DsFpM~R))Q`5?-k627fY&7=2T9E*)D87*Uftk_6 zcEJ@s1wzx_tD$}0pg5r)IAOZhOj8as`u<gl8=2 zMXD{}F{ua?K&g@~>rPthL&S$#6C`W9E7~re(A$fSb)D+(T+KS#_-xkT_$fP=RaRYr zn3|^%wQwhIkgerLS1xKT;lEC>qDR3(`{jl|sbXQF&dWke#6VjW?MAr2sNB(pYJ_;l0f_pyk%fSjyF8KjfYS~%Q$V|Nn=af99+U|V2N1u7+Ru6c0^N+V?oLfW)JpU`!-sJeG2__YzF&5QUSHvJSE@6qfPqd2|AyHy_zM z0N(UQKQ0mYY^@#17(FJ{_hO8I?7Cr$)0}YAAPaZPW)6`u3?F@|p~sG67k)ZAKGv7A zS{fd%^!w_2Q_)c0BL|O|2kQ^Q!LCT*_dF++9<#Ccva&{R#wRc9IF#E#NzRA+`9-Xf z;Q?20e61iaQy`oAq3u|pL}_Ao(P1F)k@_(1WqAu$MM+EOo!SaI-g*bR=168ex(=1i z43gJ^2)~wFIoA*JbV6PAe_D-FUxGDLS3k+IY2f;9L8k;ZS>OxT-5Q{M>*n*Cpiy~I zCzmBMflIC~|HGxDS3-yL-1|j|Z`?e_NgvGz80^&Hw<;2V=dKZ$IMyVfh2n*XNqE-x zK>8uv_=;1_qpT7L`8$lSOO<&n*m3#WGyf9EI58x zorQY6i0OK(fp?wEs_XDCEg0*togPIG8Ys^dJwVde9}kngMltKhGmx}aT;6|6YD#39 z=qQF%3)RR;qX^g&{=GkrFxjM~MBn$JSKb*IJQ}MHJKN>9r#6qUf@=ThoR#+`R9I<- zR`Uq2aTCHoIw40$9J@~iw}>E9^~&-rJgOFb0(Foytpt> z;=%3uDA#ysOEP3NQm2y)jwWHKBs(^=fO=bYW|k8e*Ot(bHJnIupoaU_x;-cfKs^{C zkRQ?@?ERB|n7DX4tL+SbQoT3N)WCMqN6)p{@*uav+pr8AV^6Gzj-pOhi&O5hJU1d# z5HKX4NCm;{)9Wp-(Yyt0k~{JL%_lva#;D5v&xdsBc@jd(0Co(cO5WOr3Vi0$U@7%a zqv9;~Y47}40WV;+SkqMjTEaU&QH~Z9p*-1kUoyV6&aKGQDjQ>;u4e_@5>!)h&p_~x z0(a(kqW$rgCcB@Ay#lYA2ZTT%hk6hq{^kfUb2d%x742`U4UwA_s&X)gc$*k=TRW36 z2Rc5j*i0Bd8vH~hnD|DA9J9p>>1bZ5EA?YUK=HIKU$uRyaC&EM=i4ilY)`eyd^wk z;7(VUIjSU3v*MUC$-6!0im~Oh8TF$7%=C1V;4#nGjRGzl&nI&woT<^+`e>uW%5WOXzq7pDf@lMTvA2hdXdSl-21}K*>oUsab zkGU3(uAiV4=3?w^OXws00oasQ{*ONk$5pW(-$H3uzNi#s6fZyR-(NSS>UEO0Row^F zb_*>6pHL3*$DW)oNDhUMsMyW%%Vo#`zx)3vq_6ruXa3OttviLNeFwfpM!N;t>vD=d z^}Z+~hnnte>GbSx*VAbO-Edb-g|_;w^A{5iU!qG>%J2Nz(ocne z5llj%^@a!tL95^<kX3UMS#^aLv3SCGxDP-G|wt5);%b_{fQUQ1|aSJ;?)~j^_CrZ14jo%?HioN~ zfjezq4T{u#|C8@N(;Y&y4+B}$;xwWC!BYFAViaStq&R&BS5vJR(%HLuvJQhu4;H0D z#v?LxOD#ZxRnC(@CcFgr)&opkb#nVMpQknWf)?^cwdq#r`E}?XFDejQvKnc^#wY)b zWKmOP4OQOj{GBae%85ol_(B?E8GWV>+~d&$)wD-23;jyDoleQ-R$TCVLo0UV;G7HF zGZm8vpMShdt*nZzAyozZwce#_FJIsy5-{2NpV6)dpLr@bjjpRXA!tOPxZdx}Zb3$8 z4xzjQLf!==1H%5M+HT!4i!AJ{eSomCi|x!%aa28^Ho-0QkL5ML(a30nB|dy<;o8^1 zu91(JbDhRl)f-*Q0f*qHaLe5o1O%S8PS2oGTDM_CdlOq-GdiHljy1?#?Xo_dUr#vj z0a&!6*7wIe=4kfX1B9;HC%|9R1o(qn)GfG_-^vJRJ}-W>vXdo#i|*Mvrzmd*iE+ZQ z;%2CEWy9$|1ALR0T$iZyWFppDOYNzosrk2Jm>ZplE{qKHiSx(UCa+oSBm{N8w}VRU zBgpa1)CWH|71ZYWJ6O3UkOvO`W+YGWrbJS8B|)FeLy7#?qi=$6<)s;(ZrJ?3kJXwv zo_ka`*1*khmepq9G^-U>B+>bbG6Z@Lh+ncuy23d(2zSf-t!Khlo_$esRBdqna3X_yj z#5l|=`QdcmvTK9?0ATo57Vw7hyx@JY$Xr*W)%i!0evXX@vW{{$J6{z>m8%`F{EOoF zeVP2|R`=>hbBP~5Y84tTeil6ST;FC@F>EoC@B&SxY0F6e6fbQusxSysjMY%HYPB$M z)GB|8yFcVH9-zmcD@4yS&~P#g(jL$&S1QanW((iMHzp%iz&?cNs@XT8sR;tDhyE+GA*n)}o!1xm?&7yc zbpmKG*~JbXPiK*|FzNPAq@iY+;YZ-K)GZ}7dP&GXbcL+2#C5lJlG1F8X>iVXy|s(i z|Bi0WMtUjCc8MQ+(OQfWTe&c)zG7C?f40~#mf^I%L=@GA#*R&Nb`6zUO?#yJa{XJ< zJ`&CH+e~)hW5=awkGa4VUep9}x^5`M+Wi);8eiIy1zoTYO+Uv3A4*l2{{`QcCEEIv zM9B`{FzpW_{eV%oW;tXOZ3%~}=wgsfDV|}Hh_NeDGOK;MU1Cn&c(Y9}U6Sxib@EU8 z|E&9rl7SG>rxChBw6J0NVj`a@i401j*IwufRmz$A&4R&QVTomYD!<~58UF9;M$Gqe z8NJ@IeWuhdxvnoNWG|4wlHS9HVNx?9s#-+_Pr?lO+ghX1ZI3!FBis+oM&$JZDkLFh z4wOBsx8UmmfKA+XMD7SBattKC9M~8K(dawXgQ@Fw8b8NTTQ6 zX@*4=Ep5ie&429z^P&yPu1SOc$5&!kO89h=5tMf|YhyJUf)mA=H7(3_Rpi~#=$cy= zU=D)DuL@y690p6z;(khfdv}uk`n~rK$}n{KdsCdg_{R#{1t&fmHGT5VC1Xk}`&k!A zF7_2x?4yIM*XF=zn^nyiENhzZz62RebDNUGF9vaQE9>-~tN~;d-R4p|WOP=AE!>qe zZc&X*CPid3Va8T;hdYrnTc}U4gD9D8pF+tVa#K=+4RXT>{Wt;~xzCUy4GkzoecQx0=ryK~t0-PHzTZ4HdL`;B0 z&*~`v0tEx?r6Uh+3KHM8X^|YG+g1&EPUOX%W#f>GQUHQg0I9l|UoOpBz#^w&=WGa0 zty;3~_e?q3UGRd1Le+7>V?pooDcZ@_v*&;}$9yz2K55+yUu=9&+`fp%$(_NY{cuM` zKmb?H))9TS&0@` zV%9G_uo0tCigEwp_WX5_)CZThe*sQQ(RBAG`jt-UsTQ|RPqvy0>wnYLDc_6gAa2wP+jrpxp z*Gjhs{`e+c8R7*GV3+G{*LCf9XZwnGsSY@#XwAAP3OTS~P+c;-pzDT)9S|2gb6KEp zSF5Z|V9Zeo&DKScW^Vn1`&>W|$8e|&Y|955r~uV9xs}EQ04Y19+tzG*KtTpWD?e8N zq?%m}+^D+^RR%wnAG2FLyC*V6)yReE=c$+n89bOZ)` z76*Qx3eS$+)d@moxz;wPh}A9w37kMWzsSo}P1>0)9a=@=<%l_VXhW>-7Sgxh+FA)O zllpe!{TJPr(wU8FqpjfyTT zd)8pc#f8uZyp3i~=>fu!U;a#Bg00RzDvB(|1>V|W_)C?AX?7!bk~J5c7v3T}WmTfQ zHxxQfS$l&vMQ}_kem{|1eOPc4ZRiy4k-Zd{Dw($G6FbGJW7@c|p}_L>{4Ks(%+NdQ zd^goxX1@L)ssF9v`h2g#w>z2^rva^H$)B)~@k4YyE2%xbXECds4Q#u0Z>?KeEZ>f z$e1zD{uv^BvV8?8slEOxio8AKuuYu=KEmZM!1y9XY6JVaYfqWUhgy9Z!LYbPRebqp zLv`KUuP;8z|J9+-c)|%wII5LSao`cTZp`mNo4WEi>WiT|AAFHtip?iZUPYm~mn63}0k{rAv@d2$yvOwY85$FgO~8#~ zqBr{1gG5yG4OSgbrWF)7B99a&t4c4Nwi7!hJWLZ2T|XO=TQ|88V=az(1viyMZ@-wA zF%SYG=bt<-L1b#`!TfsIlKa}LC>C%oGfmL*OS2v`{X%&(-4@Oj{X#@2%XPeGXE9_5 zO|>-h7vN%d&dH06jPmlkycg%h@}3c`a>;0PtC8J#A!0yct9XXC{p{>n*H?(J<*dG) zZ`E1-23~9RcBrxyrg@KHhKCl7nC){YJ`Mkpz@>wLg|x@_dt#`Cgn3$ZaZ@2)1b{ix zr*K@*LqvK?3u908seE+9l+4YNoOLu6u@3ndgw)svH+x;p%gTvTRay0|MAf4?$zry` zOc*Vyz^~mB)~Tu=)(#r^e;?-BYdzdV?5xLlq91pw_XzMJHKbxAP&G`mem-pwedR+U z_adq6Yd&Ns#!y?k;!6xgbtCslS3$2#)c=GNFBoY30gc97)#*xbs&+7l?rCkfTHuu*3QU)C{U95G|P#2fn`G-!OpM_ReATU`tn|pK1It$ z#fkDOGpM@F&38hG1&!VVfafz=`F_7O)ls>xj%yRfJ&4-y3m;m^qgZx!i^u(s3|;r0 zqf1WAX*_x>=h|EV%Bd)tqRGSxwx(v#vq(dk4B;iWB3-Q)t4jTv=V)|2sAc0QXBP^P z4TTbs7=)wGxtlH^S4@}B3CV%NzE$^;0j}t#$s%9liT6`C`4A`G(t5#JjInWi9mYs5UJV|*ROX_777sj?)&>Z#mXAS6J}bdEy8Cpb zLuXrIX$6(To3k<+s538-rf}@RhVF{o@LitjVO8{ZSk;20q1i0KasZN0|02*hirri! zuxrn%F{V@T$(nkp$^58=wx0NQ1mU2zMhlgu@|#xDzsb9ZK4^D6}4H*Qf zF!X@sVwInNy^m~C!i+$l^pF%;;$J3D{&CAEl|5EO>lfo*mN#g=UzFrfLkIZEzoS0iKttOXg; z&&A5aO^=*13POP_O4_KNoSQG3Z_R6QPF9%Ex9I7wOB1>wY1NW5L`Y}?=WEl zr(#&DX~jo1o{GV6M{e}kLfD8|APT763u^>mCN0EQv!&{E+9yTd{xmny0-YNW4st=! zI#0H9>c_mC0Qdyd^d(bVlR6w;u^a*8$1J>BV;}|BO1RREOWcbSKfKS0n63dM#Y#Z! zI|_#g?W?``s(%>hsJXLM5;`UAa%JkyC5J*96n0s{=OPH_lv+86g~S*9Z%_-lGjL&+ zX1JM|v++(3SR!;uS(+|?BYUPYG`;5iDNWTR)W*&Nj=*;(XR11|H9ZOvl}na|Ngyo4^B>ucN|3(dQDle zA%L3<`KXl*+=4Gx?wL~p^#9ZzR*6eLOb>Is+S2WT$Y?){gmD@hX6Y8oN@Lv zQLnqB2pgK@72xB5jiNgF4f$50R#5`orNLtdEB_Z12v`tV@P`l+z7}J5b%>|uXbF#2 zF^(PINUoRgRP<3qJ)D*P^$QPyPb^i*#o7sV8?W~>DrMyN6Fc=eL?=*~Z zE<94*;l~<_-Rz5mEC4J&zK%t2$Lx%rilt3Wu2wb@j85CGQ&Jju@-kq=4k||Ss&VDoC;H#3 zX!q#2o;qvG3#Pl|2$l5@YyEiT|LO@lejj5`@e>8Ym#0L=;djRaIF*>H7>zU~ z-PO=?M-Cqf>mR-$v4nNBoU1JI=>NY{&K%xRFkSd@bFPW`B*XU2Fd+QGm>hoWqvYZn zf%fIRd|(VV?sjYcgz*NrEUM%Gp(;Z-j0e|3Bd_g! zUd{A{6svpQjXC-+?9kAhwTJb;5~<~Fp_aCcN6Y8(OsrucR?8@74Ag2DGf>U3F?wU% z^4Q|bC8dLwfai>`n(=oLXDwQ|(n%)GMKF}9N7~sqNS^riP??v4GUE|CYoRi#HTGTO zBLbMWqmZ#OOi(w}NO)tlN?wLe)SfI&$T43$>P;g;^HT04T$a zAR9XU8`GAXBC=UR!3d>*e~?|txt-IKhQ>4xP+IpS6$fu>$~;Ylh11#nc7d;Xvg>po ztJZEjS@Sr-w?PDUG6|0KfKw-0keo7=jEcs znXooz1JfxIF^#)jQR+p2PhI7=WUij~Lk&BcJxxqHq9zZgRqm;B)4v+QxhZFaX}Qk= zXo7EZl%Dq^m0tzT9g@eFl8aIMX}poJ2O`a_C>LpFFt*4Nk1ABITfi$bDGa)xk(|41 z(9<_zu+B9yTk#>O!S;+bhs_f-nnt37)$XEdX5MstoXE<1Wtk(bW98>}Xsq_ANd49M zLo3L_^BOy$lPD$F$F?B*{!Q>D5xptW&Nte?oXHIC%o1=()HjC$T*;^6^`JK)f}9|< z-BeNm9F*&LR0u~)m%nk#j0D%Z)iuX_Tj%Fog*}HHSJ;m-t`})?jor56?;lu{J3c9T z)cKY_TNv95!A3Y4n91SzY0@b!u|S6rUi#bZ%mxT#DCO7tLOmz@5Sd<;J!i)7zhEi* zgUdflCyW76C%)afWB%d0Mm6NGA4s->n&sj2KU)({G zDN}HOr00dARae#p2q|Qhb;F+0WJdn^^4qWxC%$NmE-_P2DTFuMaz<{QTeB1Ko~>o> zdT=c$Y6w_t0sOl$do?q!Z+&R1=5O?UXS52DBlO$~_c6AdHSmMuXJQ#f!lS9r6?f1) zKhMafbr4Zd>$H6u;_`c=eU6YiK;j0keQYQ!2zY3q7q=Hrbi?AE^9n`;_P20jZEl<< zV486skpBxzhyqra`TSb)3bQ`V8#PfGAH$oDp~NVA#HhEHqb)u17^+eV>?rN=QLhw++XNWh3&VfRBYKh9_vCuypaJ^O?@oB=Rx=a@0JY0AH!v zOU~75stI|qoq@Zk(U2PO*)zh=(=rV{bd}o1el@%U`BQ`ny-cjK^2UvEBOXf6y$>1y zabjxEyC>$CT>0M&etaoFHMXXj5*d%LE98V8-V~fp75>7sCy9Hz_FQY6! z{v7*)p>8pSQx)MNIy=BDfE|~S_I9-gciIVzA0MkFf2|kPg^cAfNdpXPG<2DVo=~;R z4{T-Ilx)Irq!)PNiz3N?9Z>Rg@Bij^$$kdevJBz*?+uu%XrK38T(Rg1rEMRLyCa3Y z5aFXyA6B#)y|{OK8<1h{=r|v^Npl`%g4dUau1E@KZy;_IWxK;|iZ_|J7b|a8ptHom zD<9231!zaret&uwelz(ChY6@{!8NL&L>Yc93?|v>Tgl>>#ReF$6|SHIgD4u8nD4+G z{B;0a6yIr`0#ULqDiSjLL~{S#v4B=TDbNc1f9$YWr$v^ULMP5dP&em`fOsgVz5T~Y zIrjf$@s@j5+Q?GFQ;TMbuXO=!rGAP4R!1OzH)5xjabbg4DdC8}#ix2VZ1U|D&x+v_ zH&-wO)3O1iBTUj91Xh9{I{3*55%j^N0bB?v%8Xhzrdxee<=jUSBuWUqSPlEOcSi%g zC*wU{GbwaumO_mD+~S%ny&(mK5R=4_Jg`0nfdlLi!Gad75^zJI>FG%zXDkQZMCIb` z{G?0k#ZctCK>=8>xr?nRy(A6o^8RWe+7SH`%JJU+%p>5U>74;|lQTh&0L#!IP(ewU z*#7d`?J$d}3pdQ#6NexwyE2^qcjk(}_M{ZTm3H}d(?Ulfs&SBGn4+Cgm2`8b8wp!= zsE#zk8kw%+BI^$!gm1|GV}V3DnGv=~k>uOqZEYVo!S5HV|C`@d3uer_y&cB>$*9$< zgv5sZ!#BOv6el+U_v<3qtM2xHNSbE*l0XuYr-Sr@bh7Dj!fjW)tT#w_KbY2k_m-BM zXqoIPJQ{m=$CE6`ExXRR%$J+;5vVMeU%Bk9U%G8 z5s05Cr~NO8YV%^v6vcS#wYumAfD8t49R}Z@TA+zCn6P}Lnd@HFAgxZr8dog&)_${C z11Pjk;^KU=gyY zi6@iPk1aA6fW+=B1sxECImnbrjmAPM^vhaROxdYjdRuPGNK_!N$?5J#(A#&KTbxMK zsHl6OuXh*s)`w%JfD^IGSki++yO>G6*b(sQZ0bczq*K&zJ&ugDQ&Tybr~W^Va2-8U z=eW?pK{f5dbm8PR4q>97t3oF#(Cw|1GR5&S&;IgtQO~IwFT%2B?H+{iE_Sy@;tTuw zd@@;}IQ{0+L4@>uAy$h{9TwM@@aPK_2#rx&Swd?j%6+A)3I^nR7q86^d}oJVEu0z1 z%w@c+0{lhC>tb~4X^a|N_8~!#r(v4Z_mGWztMJQK^{zGi=@}@uDPi7gnSaIcMx5faYrcIi8T*Y&=b;(Z-Rj(1`>{UOD&)q5l(+A#eGjJC$U!hwm=t z;fFz9E@}c)AfrQLA6BIsqp&DMD(5?1>{1zO`j8R`j8;G<>v%I;_*)IALxrxt1 zHHm@4kr0;jOiBl@@@X9{y`;3z4oE-gyegovcEM~E-VDCRRy}&a5hGoKPic^Lk|swv7@KaI`2?$oLI44qKw*)~mZO z&f-|k4e>yKu_ZQ9@Iez-pRsh?rljc1=x9*4+Pe1*)>mZOmqD3*T?L$ea0a<3cY@Tq zEV{4GhbGb&kFj-K;rS9uwmze&h(7Tw_wu1y(|iRrH%7$`Xx@z?jphH;vNPLB)Np0D zT9JS$h!BpLzBMuv?vOlXvp6ioS~1k#69z!pw8`Q$!^}%5al{59Dr`CX+$N zbA04qk4&5v&a;vuCd&6`Q31aygJHmMry0g<@24hyq(8Mi>PJTLA_FE4%SAvg9#m(M zPgIT>cNod!6z6kxgELVjYjBje7u*iX*$0M-iHfm9@x>(*Z`XEfe?MQD%_if~aqyYa1ij>lo@)4Umh>rB z^6Yaoucw^G92HK9WDIeC#%lZ*8QXLt+S)#p3jmym9L|z7LY?KtdGbry3y~M?Tl$Rq z?zxHRd^=lWJ~yAN1oBNLJ}o9}%F?SU(-*l7ltCz) zcw>jhV8X*20-w-H=ZiZS_`E4J)(@?1+MGS&caC3)CKlxU>7-{!NQ~st&7_WnhqvwS zkyO8tD7swhM?eQjWCy`vr+UZqlNeQaGC#6RR$n>H6%2Z?8`Z?YmS;hBWUe+OjM0iw z5Zi)?TK~%m@2+Zx6JQ>TWD@D10!|Pt(i?hQiR+$N}n zWQdYKiZaE{PYoDI9>e-IzGEY#lNE-XIQH04!=3Ku9y3`7x;4mZC>y~ykxdTAiYX}d ziA^ocUPFrXOJ;ItpqAJLJuRX{_uwcc3<01B1q2tH%vUx?#0WtHOGGp(t~al9W#nr` zbrLo^D2u10?jv>Bm|m-+sCSq~)BN$gO|~uQs6$6EIx%m}0my)PELgYOxok@P`GC=Ub_M^2&#Hy*7Sc2j6BtXFi7Pdq& z!6Os!+SNjcr)|^Wc7R=B0lm4{Ueg8UV%fOtiK?-fiW#k$s1oh)?sQtiMGmaMbJyU` z@U^!?^tj^U`}d90d?mGpZcQVwf!If6 zBFNjXVT(qZZ>lp4Lmw^-G4BcAjN|Jy<=Y$H4J-ML8V%WZ;Vi?jJHJVTWPEM$A|U-$T#5@;P;dLf60+{)U(!ulb&qg4!U_wgMYD<%t}9e{ zjcimt{}8FT(UP$oRRKdQBVz)J&~>Y{ECCp3<@2*wHBW$OWxKB!#izs0DooJm??In|_f#V=#a-+DFL zTWv+leG0S|p5s6LA~^LCEQvAXQ?dlT*uRb&4(&UqZs1nYeXi*Yx>KuP?MRhWx*BbgVNqMO z)<4A0qhoTTd+aJDC=4>z%eNlKx-zQ+xh}#dnjS?@pn{g*I7-?&JCG2b!ot|6-Omei zYIE-;g_SW<_LexIx?wtDhb|BrGa%SdU~uH;q*9d_sDeK0dD>BR2`ADey>|ARVF0wd zlG~5yyGO)L8+yP^N`G}dF1V8J+-b~&_7O&NjmyJN)@3*Dn?-nj8%opH*E3EvP42%u zLA&YYsuJaiSln~8EsftBQFz$G@OT`wk@wDc*b@t(i3LT7d*X$A&qIR6hjl91T2g02 z;4m5&0bbd2TOeaQC!5_yi%IUvcyscic6GCoC6XHGpWg_41FW?>Ac%uZo4?^IH!FVmOC}~&<6){80~nud3U-0 z>gI_WT-8*-qbt-tA_)N2h?j)`1<5XT@xQLGktMOaX zrCD68+%BP-YKrJA+J3~|d*Dkl`?q45p1PUfdqD7K1iozZy5s&m`BA_;O+C(5>r8Ufk=;~Q$j^~SY8b?+gNedjTMCKHOA+d zQV%3EP-HBY05@@%U>w0`u0b45f{j0erLRFAUQme?HZb^k(_lgL6 zx-^$P`s^PG(69CFe~ZVP1)qHhy^JO{9E$1Ozu{)XibCAs^DkINkR%D?sI~`k7GcPNRPAM`uvxt2n#IN~ z%~me7tjD6Lpj9q)oX>N1((1Nj1GVGeD`+p&VbOMR*)?3uf*|-MjyJdGoX%=4j{UwJ zgTb-E>dpeQiczU95@t^Ua1RJOnD4hfqMKhzL@;7I(vsbDzEoK;YSHi=(K$z=aXJky zio+4oFds!wUPoa9|1%i#RCMFss8@X`9=5i$M9s2^%TlAgt|W2QbM$NA4aJnid{$ z+-nXU?TcAVbIEyW$Mh9$W!q->f*p>y8J{nnnPUL$!ZfR%(5;>bM@0AlOF*>0UL5%f zwI@DxalT;--A&c`I0VTo@3_Fcg{!&rTVBX4Y0zj2-1p3h*&E#0A!cbJ#M9{MzvK{O zp7&@U%!}ob`wE}_PLHpL;yc(;dp^xSFMibowAZE#uIpW*3jwc9f=@b|Ad1O=(yDTf z)`>(!eff{~`9UPl)K=Pp1j9HNH>mo63Lu%|8sH;$k;xtX*ZGb9IAi;6yI=kP!=rJ< zxA~p9q!UNwh@)(xdCIsRf1)MZK=VC0b6*Y9{&y=lwZ{*Lf(y&UboU|7o&q*sNcLw! z5j>}+itPvHuQj*MqHT zf20Ug$_6n3uKWF*dD_-=ThUp_&-4M)yjtjEX=K-~27R>wzYl&9##1 zU)K_u)N;3!4pc+D<`;)#yiYWA{6_2n7+Z8cC2GW4XP1;!qL@;E5lziCqrauWIz+De0u-KEvg;8>tf_7|%pbiQ!+fhS@;?fsOFn<4`ItZmkrigPPhr7PMF+XulV2v4GeH^e%# zriy-Rs>?BAiBW|?MuI^S!LpplpVAFoYWw_Ae4MQ+V5uZF7a&4O=4bE@x$SdPV!j>}%dW zu3m%d-~W&3fYuYioRPGO7~0xhPAJPAfE0zUO>4GPPZRt`duRAqFk9spKlF)7dET5cJRf)=e%N@06Nlo3@Xv5^_ zxHst)Pk;DX-(Ij6bU?*wd@k3Lh;g{o10UplTGR8}nO#+3ED7CLHUxXFU~+bt6dV;! z5cBamm_2-PrR{n_m@6>CcvCco78iniGAYkwe0fT^xjao1jDZ@((KgiaWfZNqiLKJT zHKo(gmJ(GtOeHx~K`ya|;3~{iakRvoT^z_JByg>Vy?iM{N0iCq8WTt)tnJAkqN6gR zpD|%Ok}z^rV~a?&+b|20m^?7Sg~3tne}SInm54qh)y_a91{cDdc?pf;Hr@H0lCpZe z2p*<7pH_YN%gy}xaeK(%-zbC{0{;n>q3>Ht7Zro|PgTV{QUlwsuJ-`me33gR-;)g) zv%aihaf%Bp3v#C4e>6oHFbW9{$+Hs01ow){S9&3Ps4mlR`rDm$pMgNGQmu~xCY+r> z|K9ZL2E285P*>XIU`1tXMPb$8QR(BLze@_P2<>m<=v`TJo>rok)l-u~AT>$46cb&_ z2I`hODfMs(r!)b~VWxMfw&MMMGlH2ty*Y?8Hv$!Z$hGM@Oc;g8#Mqy1NLmS!X+kit za)oXj;^eX zGEtN+F3^iZgH;Vpm2Yi2|F+u{n$BZe*^>O5u2rHL-GP_2i%W9nYpm+#pPXop?jFt| z+>JcpY!gxzdTy)+)wBD^TE?OfkFwe@exYErOQ$;Io~@hUg~Sh58eD)=Gj(Ol9ocOE zge&;nfTq8YOl%ooeBY%Zj+|5VFK+em{N6Jxh2j@ZCkdk@@>b@-bQw|PGPULJ(>k5h zRPH&FpEIqOu2V(Ih5d{ZfIgob(Z4h5P4?~EjVG&dQag6No26(wVzHBj%0f{_V}zB8 z-Hn~FoDIchH-lo4{Njd{bCDjcK$== zq$G*`3@SyR4ci})*>M&fY?Kq~+t#tWia80dN76%b%dwcBa<6fO~Luqzw> z?z7*T?^ZM93mTmjonEV29Ge<)OP#OAh-Dx@DDD;70zCNMwghF^ zR|uc8Xc6&B_lE^|vJz(=EKZ?NWT_NZ_mqUU=ptPggtm|sU|#Sje?U($(-0NE+;3L+ zDj=PC^81LgRDX1g+82sbavDIYcsh;sOZCdcU_9TF(B>0v?cU;@M555#2Ic$ZgX2b1 zWw@F42(}Q9>X-!dRts4gMa4yG-;s(plEZxFf!nc)(!tT+&&i2W6!QDMRp<&8B09L9 z)l($F$kWYDjfuU2DSd#wx;V4?)(h{Q%kEH}Bw$*^|v-Gj6xk%`=m67UJts~_R zH^oI1o{kq5SLd>ASTX@d#=A(x0b{}dN|Fv?6~2BjqzY-%jL2I??chZ5Xoiae|J{f5 zP89y{{G$TYX7^v3(K-;lpm3X*!5D&qRbmQ0OQTFyoyw$VMml&(;P+9sF8a$RU)?D<<6E!RdsJu|$r(Yl z=JwEe=2NtREvyZNh}W0dJfMmCv+wT(%|(vuNG!Y_ z3AOK&m3wQ3?i#$GiDWiV`ZcS2y435G#{WKEYSwSYpMR10DWF1d)X~oSDJk10J9d#= z3dFc}?blN+ZYL#@`%&bfB{)?w(8T4|V`u(6T;zRsXGGg6JV}lE$y2G>lY&@GRxX?b z-2~j8U9Soomtc(!f!6f=xq+U9OP}rU8m+<+*%GPwlCvSG?33k&@=}^n3t|3CKH->23QtO1jeC6x*u>Sz*q5nvbe_xd1P<_KJt1t}qKK13G;jB)C87<^Z5f1fo zFx4l3;?QkVjIqqwP4>*XM(c9`Hc%jM23yw6^i$dEUNxI&G}4mvS+khzRIG^FzMc7K zhxX~XHAF$f;4``y)C56ekm3ALU$k05J^L~)GaHwbC%tlS2oU%7IHcbhw^=no?2MFk zT%#|tn(C|ZEDfW=;<|cQXs=WeyHw5{YgRFVC=C^`S)ynJu;o)wCMT&IyKtz3xG(Bn z%RpA3C9AftUHODN4dLi zt3v-C|7;jL-F19DF~vJ~PUD-l`6rclQKNb9%hNHQrMLZrhrNw{hSHq5)4h=boglhH zp$m$vGt+;r4z2I7t#zO~P%4@XQMXh62c#pX_MU{vyA^N%+JmNDwW+XsFlD z<7lJ#BT{Lpg)xxAsMtKZZ!pRgl|d3YQTf-sN5DS{(X*3O&17{wWElp=*KC%d{8mKR zB8%f^05A}QoD+pM% z|7nd4@AGuE(67%|avalO1HlsK^StDU!||cp<`mB;FMU%}eGHlZN=05WWbxh9PZ3s{ zG@~Z>a+;1;$XRO;^&7NErf4Y3X4L@Mf9Ly8fd^efjcHt=6!cx^Cc2-Ws3q+74MfS* zYz?6VHZACe_x~mu>~*mZa}>iLWTK)=eY=WQ#~!Xt&)XWJLMi=uLb(?`7x}pU0kju! zlib3xV0R}eG9N&PGe?&^T-`7`P1>C*itDrO6P#EZzgmeb1uVnddcjbArDmy;np=%2 zuClh!hF6&amGd770YDGp?R}?MJdtRj->CYn`~y1OX{7A>2<@PKTy#h5RrcaNf9OrM zT=Xj{ji@OB!r>n9Xt23+MZX8Izqd9xecVoe?icAx5=7w=%}T{QUNsxnqrGsssSL8- zD#{U~q+xX@USPX^iY|vmKE!|A9>Kg|EDlWvlr7V9U4y;)b2Y{ItO>f4%CNPC#yG?p zv`q$l6=(6~s(vJM*WJBzP)V?(+L=0uDANJvd=L@1)-0Z_5<&g@Yg8d3FgUUc|G=<{ zgKSYpynd$F5SI@GK-19if=Y6YlJS34;2goaDP=v{czeBL`tUvEFuQrgaY!J-Fz7xz zv9@C{zLS0iD~~s%oafr_{kGmKPj8XMcstY6j(}OzbG%vrQK%)7R{eNwYFV}N#5&s_ zHyWpoMLjdqA_uM42$s8nt!ldp3hLh|K@Ud}?gA3+XNeq`0S6u?$o>qI ztzk#eN+;Ah1o+Hm<#X;M@WN5SC^(@ujgy5aQZz;6xk1^Z_y{O3J&GmL5Jq%=r^ah< zN7&!}E%Fr-Ogi5HCsu8I(0prPX4?KnWpe10z2S)2Mpo`sFqLXCj-evUp zAoIaGIR3l~_L47GEM^8Bz;-v_m`1h0|3%v&zP{YxVuEUZCr~nT*D5RtPVQ|}$|!X3 zbf3{;BCDuGERG>$maBQ+=~YXtTRHFZYi%XC%(nhx640n z?RLGbI13uq1GBzr^pBhfQo`*=^gV-<&<>0VX;K#c%xVj2`V#tM8{bctJ*w5qtK8k1 z7UcgUy1Res@Zx;=D^J<*r5#&H^a%*2I50{;k<6g#!iSWL*p*~W=8Fw~?Sa-^4BWBV zm*s#8o3Q@>bsaQ+i&`oWljoE;fNY1+ZWGfSB}EzBIvQ=)!Yc6m4j++ByJsBqx)Nwp zpBu)y##T35NR72IF}K_&RlmRkuaTPrY~gEaOxzYzE^m;f_%+=r+FK>V0p{QY1DWaG zfkc;J;lEV2DJjxeBw|mfhw*}-V-D4$L%mrMsv&lLN<_d)zv5oU}Sik^xVH8-9ODqf8z40$Nsf-5Yx z%@xg-7uQ*fOOKHL9K^rW;we6XmrUc&uGa3m`YXe4x943&Y&3%T2mh0lpLUl~)c{Bq z3~o9p^I>*cd|v7`V# zX|*nHigP$)qK2~fz8@;s7SCytm4_d>j0XC}W8RQu7cV*OCQnhPW94QZzGb+6kg}0& z zAI5Vz7-AjB|Hx)$=eILdC8!eYFd>qMSsS4`d; zB4aF$!Il6fix&sA0WD>Es8n6OlmIyGN%7Xs6I2L?y#PC}{@bhxsuTMsc7L5U4mm?5 z_P=ZPEl|yq@l5|KnJ=hKezkj{zY9?W1L5#A38F;{bn!c z(wgieuHKuL?nIJR6Slb_d@}dxxx2`y7EQL=aHJgGzim6_7O9a_V|}2p zG-`Nuk{aDBK~sr0k(+&tWTM8OCgbs`oMct3!E~GSYLeNdsa6&sxOM}{J~DOw$dp^1!S}5zvMrJ20Jm- z8C-bnJo|1nK{9bCD|y!?3JrLJNJxwx*o&>9eU`BgovfYVbad~4pGSRm9fDGn%qgEH z?j*QSkzc3Cz-jO>wx(UG1?j_|5$-Q^!}hXgw)NK^kI5PmuY?_=>cpJ=%;nAiYJKqq z9C=1Y)r=KMhgG?nIy8>9i+|w)X#QE@$O0BV^T+yq_}nAO<&?Q^A)NK4FmAr%-en?X zD>gy{vqby)F6pG2W!ESX#7-GJ*&!%&I$UHw5w@%N=-jt>N=;2TSZKAt?+-x)t4L%c zoVkVaJwp$!(1!a3@Pze6B;XL~dtoT?2&23UZz-$qW@`~U|7H-ryYHWAC@or|B>6C| zxXa$VBEm8oVwrhOroO63zID%p7styD^*Sjsz4RrA5nAAX^PfQ~@m9th~HwfuY(488N& zJ40*6`~ilpyz-fkkx?WZh1}&fg%X?gXJIYtJlcbSncOccRJ6cy4i+l4jOc`%`;6kr zPxheBI2nlvKMCCJS}Nl!>cE6<@h}u1B7MGJ3!8It-(3Qp;e&4OM~j385!B9ps$_M> zkm>|H60-m_qtev}?U8A|WySM8AEbu0$} zINHHP$70XFy;}&@-<1+q`q5K9U-pP!B`dG|2n3#fF=^AFtI7kex&e%V#NKhElBg%fVu}I#uRm8zA6paj zkX20r;Q?=8(PmQxtS0Z6#c1CWw2sh+;cfK67~6ux$7@%t=<0A|vlYcHr+)`Vf!_0s zi@#Is!GI1q2%JHD#jWGy#~a~Uhw5#Q<4@j620!iBpK;VYAcG@1{q-llei%6dm02}7 zavj@?x!-`9xIL8`RGG&2^?{O+k{{%9ja%G_Y8fZOzQN6t%nkTj?T?tyc{4}8@{>hn#S zGQ@BmvbVu$I-s?2baM)L2vZ4X&ix0Foc_w5Q&zIJa0B%%P`s&~PeqgRIcCBJ>-b?ax$Hy@o1~U;*f~ z2nO5*xml`|l?8p;QL|Yp8kv{%F951T7Fp1vihC^WC%z*ZgpG3#i;MdSA*oRu;P9h~~;^ zx{@m+T1oTIlZ30<4YKB&;h^PUZUm2uN!G2{D9tX9&63-*-9p<#rLh+E)Eh7?Q^0ei z$6k*SlIXiOTNUz^i@^6{@mcevJ~{^;H*}~aG}uDa#y~4qaUOCl<*L@N>uz`10M-I! z%Sgaix_?#y?Rfryyl?<$JP{hS3Xq|;gxZlv^j;)e1*83vgSRINR)8fpuI}m&DRSp1 z=AID5zrq-ql?5p6sNS_fq%X4Z)l`{X2~Y<`nc6z*!~A!**SCwrwHI7iC43eXK0Ka% z@DtO%-e`pDOkUe!!mgb7JGv;L4xsx4YJ3(BEj{9z5zbQ*WtNW#Sc3TQg z@fa9gz!SliykYqwy)k#8A2_4~D-(kys#)>#3wb2{evFWc>64mhFQ#k11hXrrFrw%~ z&&V^p<&ZXOLU}-4u*(n~RJdE>gx!J2{?`Y$=ODGRUD&Sq5enAo9;B=OWw=nW{5%=08Xm^c^qe zsqEC6`-#guy4sN<23x@z%0=-<%wt$OlBAXIE3R$O>(QYfT0CK+tf>eiOO%_4Ww{QK zV#VHNr=ljmfL>;-R*mZ3cdY+ye9#$@bm|`A*VOc$6Kd#_SAG>#O$-qhIorc`;9>%} z&5SWXS5QXhSp>?Aw1P(Tk>@z z5KAhpjo5FsKuXqFUC;umSH0pbSCDZ!dWVL$l2n7aAE!u}H#T;l=2oq%ykBax6&LcK z$pp+TxgQor$VajwN!n4c(;>#kSJy~5gGwD^*$ zc7{?6si>aRb=6N#{^|D%0|Y^Lj!?V*h?$hhD7CfRSdhET0Kz6aF&4VpH zLoEwnj;PN5j&ey9NtWHRCWV^UVl=ZwvjrgX`onwbQ-KOB%MUPc4U@5M)k!N1W<=x3 zgJ&W;I1)5w0~XOT9&qP--O)A17#}6Jy@r<)0_}f}D7$H3^;K}`%&Y__HBEfcLQX*) zcXE(qWxDe2t?h4@JvtUmKZSxEQC_Ir4P&QP48yf%*DS*Uv@9E}{Ta~iapo~Bx84g~ zQH>Z&mx`Yb3qoYK^_v8=OAc`a;-6@y2k{moj1_lw)Je;vYEI3lvz)dDAGzp7b4NtuX5q0=Zf^6>}rXd z*iHb%n-%Spe#xEnT+K55Reg>amrAb>0*}$BE%QJ{QbPsax)Y10Kd9?6(R4>$$8>3)?yMGJso9FfM_i-o2$|s~ zjb_+3Gs|;2Zx%u7CIatXi5Bj*fUzddxcojrS#QWur_539@}*{5wf>*(8)~6QfOH}y zHEbl+*g({hZs7fGP<^!dNnkThT5mvmM8Z*Va3q9K9?a>t*?iN06qgnrw(nuSWRs~F zx7Hpq*l#2AnZ`|7r%(JLP5d;6633B=cKQ(FtVGRg+%p`Ld9FnttFRM9g}Vj6P5C^f zCi!{W=&BaoJNNei#uxZ*%2ECwY~}E+c9sGv2dPEBj)@fX$&}5v(t0bEN3_N#ZX`e;Eh@_8fGZtd8-`#tv?>Q#RSBd0FM^8f&_#}+1V%iTnYUn1% zeqDnn*tqh1yH8lGn<>$jF<2npU0DM$xrFqqZl`!0U(V%xG z&smJcuq;&mF8#OJA)l@=yIuv4FF-Li{i_&Q`rm!vS+Nrl^HH_OqoXa?rq*A`4s@R~-=rzL`m=!9U7uz2 zV`mrdxzyxtHPuL0+p<2lwrB&>atYP^pai~>CQ0`PY+bokn3H0W5i4&ljH7b6-U*weuDr~XGDz^-+5wM+Oow(uz@lbI#0BQ#*z zAyqq6OHTV!C)CKkG#&+I&T3{HJ2iBDj5xFoatQ|{C=nODTI!D$udBnjjf=)iIy81u zxBXd>ojNb}t9PnfnvO)cnT-(ays?*e~$hjePlL`LJ3-__&{Gz`juL2}O#;nwq*K-m;A(1s51? zmuVk3L0XAhwM?%gTq>kJ4JQh)jiB7fMrIrd19O-M%R*o)4y)RlIj;iizJ_$&-z zwlusqmq%g`8hHD$iKfafsK+=ca#w-?gA$NUy*fM9krtF|T4MthS2mgo8^n4CD-`By z*HGTQ9vkc6M{rb2j)mK8>1h!U{jn75$`~{V_CEttADGI3 z7RACku%H2-ZmV5Rr8q$6qO#~LGL&0%c-c+s?MqJzx8S{-A*~t<*CS(ZK|1+%^*RvP zqO6*7n|5=)N_3Ldqq{5jUE3SCTR9s6jpb&TbHDwnAdZ;e$#!O^X>3UtAWFYiCXc7( zEQ(hE(c5;QcLYY*5wM|Mvu@_LFvjkl~#Sa98c2@9|~>YZJ9r9^e8iFJvcnuCXJhX$7f2sY$o&aid}mU(SV6 zT%y|h(gKmcv1Y`e=jVj&*ruQg;x}QJjASdD+ZnfGHv{cnLk?bvTG{e6Fa`+X>1@XA zd#;Ps=FM`|3Pm8^7B0Hd>*qV>361oAcD+qP5%~m??0!npJh!F%Aj9i~+&)E!mq3}z zBi&a1U>SVq62Kga|0U?&ljvg*^aUDfogk*{%OBI9(_yAnf<%zs{qzzhzgo($-o(Dr z;YGb=0Eqdj_PTG8;U|zGJm!u}*QG%OpN{bFk1oYFD037d^O*rZdEo9vi-KOwjU|B% z7gaSPsT!}~x^{2LTCo#9vL+MWsSgHHG&%U4V2O(-3^|fT%GmS@9|XXL@3pmsc`M%z zz~9n*l>${WdlT=zuzWdtAM2b!3TDqv5lbR5oO>Ec%;2{WUsGv{r z-PXgDC31rzyjV55xN1CylD<83{4WPf;HgKfGo$o&%_oT<$P0`+l}ogMZevMhrOs2q z%Q0zI`iXj#4(LC9*1qF2j7vEwaynu*w-CBQklXl6QeE+KNy-Yu%hNhrzuZV9l$=|U zjAOko8Tzm?x#x}g+lf~0@<{CVGZ*xG{JC2__B|~X%UE7afUo#08)?+Ig@DhEV+a!)t*LLD#d!@&nIu-ouCLZO z0YulvzwE8&oheJ2e}%T7!jtm`CRDoEbhn1FIIFM0P8nk!ec8&!AK&+<;U`2>`klW} zpBY#Q8%JnaJD4{sU@0|=`;q_EDWW;nNk=C2>SIoGk*tNB4YmjkfLgvmT`+9^FSLw5 zF~Dq*3(18zI1knr_IWsT;-R6`c5##|Ds#4#MMa}wbSv|q?-0t951>@$y8THJpJ^jY zx9l9OhbtKh5z~oVMf!02%hS}F5}o6l%%rwOp#WV{Puk9&pe^h~QkS#SxY`s+)7URi z0yd0U%#tgO+)Rt#teu8!IW6ct3~iPCid%&wfK#M?zr$uIr_}b4a$16`7kH zkuqudLD0eK&zoF5hf$9E-H44N#w%*Ux+d$wFEU#*78^K`6%w1f2y z#%VKc7DYJ1jpZUrek$SYBh0z!h?=8rJ6nyMCVS5as>~PdovRi`wAjnY@w4T*_i%$N z<%R$0zX5jQwN4MCi1UauWSjUPhseAPE+h{2(-9%GuyPT72aNXMO!7Zqz7KDdu28-^ zY`}E8J9m)XKcwNEF=DmXn_{>8v_9;0^Mw(lMhnaOqS9s^?+@5z$xyTZnL5xTQdwXj z=xh1+qyWF|`^Tl^o<;pEShm)kpwM|yPmayF@tfo?({hLu3a^!CCQnV!)j*I zGg|%Mjd+p7=YU$cemql|OyVtfEg}3~KW=H&X5Ip@1Mw7$tL(9pKsQ)h^DZZ4%poc1 zfPXNGQmt#U`na$T+rIHo!M;3(G%DjPLyzO~_)uDF{mnU)JlQ@5JiIQ_%r3?WoMHXI znpi(66>~qFhv?Mg2BjkT45r}cKO*W`?xn1Y4oIg4<0{%Jjy7s-G?!E+VdZI$3}S(} zbnRrYLkQ|`P7wsL(BEGb7KlXx+V|un~{xQ^xOW9aK z(nY6Hjwh^(7DUr5U72>NJX^(Ob4?3!k$cUZ%-dhau7NA4qijNH{NL3%!w!9rEo}gA zoVlbRgaJ;AR53SXCwf{>+vmjqnyU$mnC#u|3-$s?s3BSey2t?f)#&B?!TucBU^4TUFSWUUn6}MUqfzg`H zz_m-ppm#0Xn9VBr+g*k|V}}7gJ4`R}mx%6w2 zUHm{i#9Pf`MDxa=_(67j;OE0{M~i(w}xB_@9=hxYXnsV73$ zr7UM*25XK9-umEpCtn6(I-@oAuh67n;)%mQoa@k82gq~ImrB{cf{1l#C>0ogv!>96 zQaY8K=y4`wS_95Qi>tUT_Nlo_s8Y$wZgo?q*jZVv6#w*CFVPdSsbU0l)U*m$Hm z7a$|N7CKXd!^F@|UeUb-!~TW`#iV|qL4v|aRI!mcCI~R=p43mVy&}r@wL^=WfjD>8 z*A!s(4AfDj)F={BdX(8X<yih3P9~Lo;B}yd4p{(}LVMV;H?|epiGr;`h=|$PadcNkW~~8w)>OQ&_%6 zD3y_~=ou3J!QU7g_9f*y?FV&krum5j3jOeNS^}!a%fIUmhNP-}{yK5k*7r<=IbD+v zAWz5qd(&Gn8-hn66t1$B&TC}>3F32jX+vw^DI*w1Z$|n7?l>- zNzErZ$0oY9mi|Q&_L!};zQpBM?Sxk5l~1l#RC0-3j+a)hPp;I`oQsvRr4iJy;`5&P z7S-*>g(68`8W@q308pQB57T`omk6o)MIkgmD80~CTiz*klpYsllFxKvFeK>H=TmMD zY&Wx$pUa1oYa(vsgU(R?XotTvSoNXkZb;FBxw(Hm^S-(QBhD$+rkys}pKibacMt!~ zcPufwCoo814^VSSRJhjac+8K=n7??M@P-_5r4>}*t(D&20!w5%*~ODlKr7P7${i32 zfI9xg$ICb9e|G&to%s%UPkSa=PN!p$*{1}%b@{!j9XECC=F~FDkYGKJXKyl}b1rGS zNcKR@9a;dr^HX&UwftfnilXu=nHXeAUNR}cnDc`>!aT}phJgm<&QyXHoYv*o9-^?x z%R($dpQBM9*y$#zpM-&T=jR^V(wJ5j$6EIGf+I%FWA}V_(`SD3f^z2C{X?ehr{@>V z_@FTTO`IQy$;k5aq#$*X_kD!2#YO#adun(EkCZh^-Ply|y=Wi?qpGA>TfA=nxgMzx z2!lj~--fV|B}hM82OxRn@g}Ha5V*XeI6@~|Se@ym_m2Fup`DwtwP4~cm4O906tTJ8 z?kDxMh2Kj!GNY-gdnyKcE4m^&s8)Mw&-_zvzpeLr87T?Y&|o>^XqlF<6~o1~Is?f= zIW*J(cVDUz_K!>asuovX5#dOM%u!*X7cGi~RsAFd?I*G%1W zDQS)lV2|tDs|F~4hC#7%L(kpYjt$ZBe~QP(@6=TnonMpmk2@4?F`8I=oA1(K9u~Lpk%%qo360&Q3YL1Z_&F@1Jr$9K%AS9?qX-`oc0;lci828ju<6U)R z%Q7OXwH2XQuL8-6c1yEUBnS66z2~M9TI2+rwX`ejxf}A|PWA(Ik(r;UgSgf@TnTO! z*(KjGYDT#_mC>>adIqcJT*dbF@c}3r0ZP=|&xH@S--&X7-a`=Dr`oCaPn2sI+|x>% z)EZE_PFM`lD}=T@L9MqO`ekzjqfSlS)dT?l5fah(a-AH3LZsduT*w`o8f|3xmp7THF~+m=|bF z;SKqF9kTe^)#vj*>Z@i24CH~}&bEZ(Wy|90``H3h`3pWG&$<&fJ6?}dn-ik0ub|kZ z4WN2au0HVplc68B*z-4`;1`r|#iFfL((8%FA`Vty;fG?s6~ufyb%zhQ0c&VN-g)o? zaPiR7ys%-ZBIPeMN=Ftj#JESVHCc9wu6<@pI1){jk;F#)C)=RbSA&f*q%-C4n-C1p z2Tae``EcWyb@L)!y08xcd|U!MRkT8-Nl=?b#f~dtb#VZRZ&uD(no-+UkpxWL!>OS= z0JJ0m=#KZ0i&`LPv9ocCL;jRo1oKEIYInF9$Du9#-*_6Ll}u2Neaqz&#>vR`mGR^& z5u#G%Jls9J^#3X>mpjHgCysUt4}SA0Z;yH0CCReK@ZbM~MIwtbEACNW$__!m1~l^4 zqe%Ww$>5I+`I)KY{p9bGa2)IdAb2J4p}Xd{M4v0Lb-Iq7Yiru0zO?e2chOZm)f!7B zx9AUY8T@(P2p0@11JL&%P}|#NGU&8>4MCmn1^1haHoJyL=e2G7jGUEy5&u+`#M_rf z0Fxs3i@zZ90RP|Q7uqfSi8{=1`=AhTC4e}i7(UIqoG3~Ka4=i#6wV;Bcs`)y15{5> zWmb!+nS6Tj?~&ZH{Kzp|uEkjy<8dD>{i^QHr8~p(^;Fqot|Lc^YDvLoxMV&2bUA)t z2lA=H93r)v6;if{afb^<_+h!4r-qksI_v5VOQVGI^;f41_pO}#jHGq z2VCNVb>QQ&w%}&VGRtd}@8E*kfZyN2YIzquP7?2+o6&SpOW~B~nU_u{K z`QHVG3$yu@Q#>?=UUlL@GfxwJ@2pd*`by-Fst$GTu0qL2XrIUt6#TE)<56WdNI;pJ z2NDZ^9A>kjP+7jD`%q{Edl*nY{2_4afK5)j(I^f_dQwInI52szzdv7z%} zW;VIYyExrxH`^|0E}m|gz|v{A_n}y2{Oxdan%i_fqgSRm#lQ8jXup6 zA!=6d8B+nXeh{o)5eqwT`vo1x3lb{VIO2CmnE3%n!0H#gN7 zTi$X?mAuK^IGA(k+y~?}vRbctRUaLGujG_3)U!4qoAdB%k_z+~@TifPEhASbFW9W3 z?^!FhV26Pnmgk0KQb?}8N z+_S|Vc|~EfAf1fF+@Qa+uLO`b@>tvMhhBzv4$ zA~)!cWCzmm2RoJY4WX!Y;I7p0SS6PG{5BoRpB^b)qmD(pUFiE^XOK)mwHcMbGeBtq z!Vw{~n9}l^F5vHPl#4lRS2i7?{k`OUO+5ts8GrZke!Xy zTpr!j#nH{cG7c_J&Tqf&I2)H7r-<}ELl81=Tu3#y`IivibzQ;FWDs)ZWG{S;HFG%J zN+GHeut0P_j=!B*V~LF}cc^P>VsQ>Mo#q=#$uq%2;G8vG{84}C&IvYUGL_o+tju)s z{5Pm|IzTIx6LV-rCbv5bS%x{!yL=v9RY1H3mIL>M5C+fQTpe;yq?$R+=9QS^#MIJ> zN<0<1aXHOb2QfXzRC~K+je4Yy8P0pic}@?dMcFub;B#kYu`DSRK3Wb*2co82hHl8=5Z4afD@0ZnD3*ko}VD6 zpotht(K4U=&(@Bq1KCte)R981Mfp{;o4&TsjaS3|KXbsevaST^nPysdz;kBcZ{)__+9jm4t$AKpm2ZoAn!KdHT;l<0JeXuK_us^}!h*!*h zSeaRH``{ZG+sSU~_6sKl-K~b7m^MP;VJg#=cqK@a1=0p4ClSzJk2XS<3nv*z^GA>T zX>BpDVZn<}Em>q@V~J%_XsKHC15`JR0cqrfp~&NRxV_KA5dzjZd6$k@yM0FxT#nl! z7YoL!AfDy#QGONGWukj+#ZIOlx<#b;)czoSpNzfL<-acrlZhp1) z)oy4%UfI@i?lc{q0}qhaHE592z|IVzfB zFE~(d-0Y6ujfgeE=&P+&9E&nqLg>V#MeiO#8M=Fcqi1qGg!C|>$A`arSYMbo0fD~j z7>9d4Y0*Wp6TO1(YDx8qR;1_cs$pdZe3FSwpy1y#g)MPypj35O*Z)A(c1b~u@=MH6c&5=mbt^6u?3cK;=?c4R{qd(!%IGtmF@n&B7i} zeGp?94zdH9!QKy2xK4+_+DmE|+6bClDFqfk`hmh{Qe9sqs1Od8ys(%PGrz{=Jloyx z1RXmkAV_Li>7U%HU2ZPBcB9(D5;@o;2mc7PPBj1G$U4CR0!v4i_oM(Nk#}Rv%x8*= z?q{bZ2&fp*JcPsi#j}K~7o>8$wucWYiR4ao{Xgg-k&=0vRN^NV5i7}J6AQY5k`MJ_ zNWVi=_6w#!_=`^EL1Ux#`?D7l(4MOq8QxwHxON%&tyF}1e{ra&AFUg3n-T;Cc%M)2 zK_20y6U|}H7|^r1w|wA?yjwn3v5gK2_Py&-tqX}=wCnpm<~SH`-`*bY=ogHSoPZ3z zLORMa(SH<8r`q^_k~U8`4SR?8ZD9`>2QdeNM8_@%etCA5BBUs8{6RJuf7GE%B(>Y3N0AoJP z3qg6c?bX8#%>w|r*hZEL`6+N zJE}~x;KJ2MAAVjrr3Kco;RCiqe$e0?@wWRXw;wLNnv)ZNBne=iWJmGK(7D&n8y1~@ zR}?kh9>{gcF(C{z1~xA+0Dr~N-K(`qr>(lEV=yYBA4^7wMsmMBk)tT!jc0r9P6!`D zW_4w+=Gp075NWE*JvqQtwH1}8+71V z?Q;Q82cSMCIO2VhJWy%P0vc)Ip|ouZKe)+hIy?KKcv~3VE<;Y4{Sp@EmIYc&5veHT z1haG$@Z&vZ#epp?aon#Hlc&e#-$lPYm&!{jg=eOW|5AAg&nl6(yxz8jhO$%lBdr?ZqpokPAGqBjp-qpR1ABc23cwMKj<+5&2t(6KS030{)vr{3-5Ob-bT^`T+az`NgvMpEID@f z7G+z;EIDhX>i4VTPI6PMVfZS8nzJkS)$QZA0l@mybvg8Y;b!JWI{rgb@DR%=uS$Or%YFOIUzE5q#SfdGT>Fw$1hWZ?}ma+3CM(^ zplb}alrH@1LMTMI&5X8UFQnh#cJb%w=XGAe^R4@&)_(JgGZ@t^pMEHVZ+TyRH4ESi zCo-QHO=aLaa!&;PRxy@8QK=2}2F@)m0Gt7JAEFp-#`l9Bl(4IU^Omc`TTb#)ufyFq zj1D)H$6-D0?#I^V8CVve2tC1_+eQ^u=4+8kK!rCO-gFxe)`a`Q765L+*q)C)2cIP~ z7p`pqh40j8bnY@Z#tO)1w|ha%C}SAj*KPLFKuP0DKE2nAk->OM4L7L|NUTqo@@ZEM z$EC@~eGWIA?VzD0a}5fl6#TNFu?W4WpZ|&1zJ}9no8j4voW-#`i<*@GA@Cz$$es4l zc2!L8CNa)lS)`-Rj6Yq(+cN7Kp21$3 zCtV06vmJ$_xy|DW^2i%;I|VUXU#IIirb`K_};#x z+{u~~`HmKC0O)7?#IMOu1X{Dm-+<%$%IJt=T;1$rB{E$02||yria$fIw_DuTKot+a zvys7wIGUXz+hWL;mf#3VPaBEckd46y$JxO16rx0ar$SbzhADaTA8D8b}R zwdnv<-N?V#ye)Zue{!?zp%gn>M2jGsi=7F>)RH;ot!{k(G6$0>kz^>aJprN2ZHyKf z7(2cFKYr~DTZ-N_M_Rn6{+k3Pi>%!hbllk+zqA0S^(W;F1vY;o?A)ubC62wN zKtBpcdBwD4rwtAI+_m7>Y4`}yw*F?b`}R{q7A;c=h1bUVPfy0HDAQ4nJS3{HGPg^P zN?KGlVKLO-H{7}RzI3#`M=9nxPZR4@7`NkkFj_L3IJi;v1sG!%$@1hCg2@E+c8_`VoK z3b|}e&ayK<_r>m@7I-k&gOL6-gt*Y#c_cRPRO}M+o#Jg9gz;Ir@4x>7bR*j5svZ>j z^SO^n`aRUn@z(QpJEDUwel_R_lhTnleW`?*AeXV@zzXZarPzE3av!BFj8*rA0Y(om z9AF}%#~&&wl^zX)M6>avHctid{;chUh640~#nj@CC~>t7NGQ2xe&oQjS4n=wZ<^pF zf(#~{Y{D*T*c3vDMIZ?o#**}*fwG$Z$FiRy>9k=R9md}VhIcBC-)K5{Un}qSob(j0 zCLe;<58SK-r)#Su_5mL>UDxTTeCQ%Bf!V_2i|nF4dIRvCn!k|IV~BzSw_Kd7DJ|{5 zNXvkGh=la~!*={gnBd1SC4#|fNFm(eiq?geWK_JT|_*n&NUCaUn z=0@;1%EQD5oaEfw;E9jQte!O+Q-M^a0VXm0+~2UrXzwDBH!Iw+QrViHf)#1hV+C}g z!Y#p{_#VHfZbbABn_e3)Ew+4>$+e)KjJb`ISX`=D__RJ5Or@AJY8;%kvt|#UrH_B1 zs;}c~>Z+;RWoSzpaWH?{U3uo%4Tkp|A@j&X`fM{Ejb12rIn#t4qvie29!c#kbuElo z=#t@8_n$ng6#N%5IgJfI!hb|*UgXcKLM@@(M9HhGkmu6~n@sXaLqbfWk-P%x>m_i! zX~PHBqRsYj`@pV{ylM~g_Q%ax{Ij7O5rHjP19hZEO5{HQ+E`vbUQBZQ^X2cRIa(%5 z*Qef7Mu4-xZXN#of=*9xWdJs{i|~m+qd8u+7qhZlSD5Hb@sxPk$xnDaJ4*)xr4y)O zoa$#dK!qrHk3&m>1VGkLlpC#cuBV8eJ_WL^KJSivYbRX8CG)W8kc=g58ai?D=r;s6 zV!L%;-XVCIl84fVU+_Y?>DAusFe6>kJ02gQ0PhuC+G!t-yiS~XFBn2~P}F$s!%>1J zmwqaw!WFxkn|@6QW+i+PphP^4bo!~wK(v}h1!6Xl{5IQ>7gC|>8%~R&iANJefjGp+ zNyCEApZ?CNCqlKyRsoRV=188Iv%lXHPp0##*!r4$Pa#AjKnw6}mg-ow36XL~EZ<0g zv17!hCJ~mXIp6glA)Alte#g4-QB6^r31cPITecYiJ!nZRrN}XApJBhnAXW<7vAn%0ri)oX-~Y-JISK;qKmD zr^r^KqV?8O;8~fOnm(N9=%6e?_vgyPOMH~cd~u(esxk~)n-NN&SN>t~QHbEVLjtMQt71=;&4}s4^qA6?rHT*Z)#%?;O{@yopX#jfQ0Jii7RGO3Gj{p22M>c{S3EI?O}Ae{Arh0Q!}MEMA^6$(j*31TkY?BL^>5 z(comdwyv+LL(aDXdxXbpDZA`7SE0e>N|8wb zT@DAltaF~W)$8LE`ePR8ZSPP>IWf8@*d8LK20!mI5u z5{b(!uToi3;=lVZAhf*q2AkfX7a3t&JU6qS49eJ=?HST>M-s4%hUCsS7u+Gq(dl1y z{*}~FT90&dqQ3doCR7p_M-zQMbblf_E^3adCi`tMldG{epw^qJ9i2Joa}qr2jo_K> zQ^GOvEaV{pW|qoXybo$eXv#&w=B_tt;k9aGML)jD(18KX%uqpUW5*-6mL=^)x% z#&7z`|KUJ~s@3jn-P^bohz5f_clXi6SQruJafHrTJl8!33fX4@@ocu0yZ^-^7IUUg z#A}o%mR!K;y~bV(Ho3Hv&iam-Kf}^XEsvNh6xsX>GFhN^cm&O@JRc=O6|)Tgbv|#R zl$YZZ{eljZ0lVpXY!H>6OxtT-gKP+)c~hHw8iYbqP)NQ^D_xit}X&#L=+V0RA7W&yHg9eilw}3`eKq>ViK;B79NMrD|5;*tVkbCZXoD3=O*p=EeN~9~ zLsEXC}kIoXoTVP|Zf5UNM&j)~Qg zcb>4IKJR_5prXUK>~lo}?P(VqDhEeY?GOMRM9t$eDTE%6++P`QZv(8TN1@7Z9!C&Ta8N94(H8N>#-vKByprlqLM z6c;VH#!-;{5~(X+?e{Jx)Q)anZQHu`-&#$*08IAhf0OioXeZE@Gs7z4f;TD&rK9dH$+2gNJRe1JhJTqT^P?W$bNx-qBe=UhhgCUcqAAsbL;|lWa6V0Z?np{} z*_=!3+PsPBMBe*H7oTgOe|nCw5JyWxfZLFojR=0^d4*enrsg^A6h>CV=ml&@y1J4; zX3u>cq0&0U)}S(b%oeih2XlkFv*Io6Z2ULoOg&Ueh*1mk9app^4D`;>Lg^qA%#@`) z17-{Le{*H88;;&Bb%cWq3zlbB6U!gM8YE6^{uB_K)xSU3geUFB9r$aiA$4uLo$RDs zaFFY!BJTR0x1@#UL4?0=TtQK}drX;nG}>fr;m!xWMo}R_$$3UGRMQ53ew@Q5fv%md zB`OPk>#sjH17{`WU`t~^lcJOREC|`vg#=#6FR`n8s)d6Y9eg=`?N%SHj`SXTfdgDK z6d0Ug-Vb?6QbDB#Eu8IwqF?n^n_;0N5Mk?cVXL7!+vkk}(c7>q^;A!FfQ|5}a)KAP zA)eX|MKn?mZB5-eRyKxuSR1BKR_L;r%)(Z(sug>*94~Be-Bzu8tr= zux*n`Le_0yH$xpCE}K}H)yI@WQVGe-IT2TspB9QZ*}@doH8m=8Q5q-hAwgs`w?yUX zxY~RaOoaRdf!XE?tQ;bUF0yNs3mSzZd~g&-37LpcRrtOxQDHUsESIfsCP}u0{e27| zr=Avz4c!AQcW^UzLsO0MW{xy0v|qCbSAE8|dox}E1Yy-l?)LNNDo577CEtUmkuCTz_M`hfH)*-%Syz2>gtK&&zWmx9F3N3SBej(udH|l}$ig zS4s(afPU?O0Z}x*W5!YXAF$d9$-8$E8!@bvXLueuyAlVRq)BJCP|~P);k>o0F>yu} zTgBj)B^2?I#F7#Ki4m_Z)2g;gvEpdjJ#U$Wj>Btpj#z%R-*#F?z+QX=jfp%|e zm^&(x64kUUWssT{n0x09di!YJ%9azZ%ghZOFloq8q0pB(Poe@g+NikbH}f#M7>wtS zx!-vqZnf~ptnz7C272ClPgT;N+b7=x`VsCq%SKBK*+0WSjFJELpwff-E zV_6DD(emOJS?j1{0~61kwK3m&Dua?0TV{{%>O+H|-rjGz)m*Y8{7a?S12k5OpRtpp z_lqV;x-$H1!hBKLpzHzI`Y2KA^LxPRnMj>J4@1@LUWFY5<3EuGSAzv_^RVwIs(aDn zyz~>Yqegj_9-Fn*opTMK%%>Cq#__rnIhZl#x(@Svh=8p!VUwoz_($7Ran+9E8eE?t+SjyFJTVG^bxh+{*U>yo6eI8=6cUU^J%FJ*L55>F6Lp3np?mzB z3h%Q85k$T6uW7l8yYRJi4V?;Emgte?TB|7|#LwUyEp&k8iTqv{ z&MVM?9j6V|=8iyo3)9Jq*lx7V)qz!5O@yG=j^~^@Qb|_h;Y*uM1tf-3JebEc!;}je zihY{7t3!zd!R}J(5&WSll@)vEHhginvu7w@)G1@jZ4z1A!Alz#ii_UtsqkVe*xla$ z$r2366`GQ$Dnw!Eip2kjBKEy(3ak@K!fOJcv4i;V;huay{G%hMWyVQ`vvu=|Jyjtz zoDR*Gvm(C7Y&W^#_piZfh1TIABm=^I-tZ@6elzWX-A*l;&L_Az;H-%K9q#LhIir444+ z!jrSNTK&Uwy0;8mnW!nZ*TNFce=uKC*qWR+bs=(ZsfHp>xF2 zuqz6}_ij0~D^2QQW&Fd|*ObzrmK+t>|3W!s%?zqdsJcA30*`GOXsuw1zO?f8dsrY< zacF2W86|OkcYo_W3wE0sMn3_>ja7w8cu_#R+G#3)-1BM}GLN56G*8MvB<#~y0F;=o zMob1`^^_Rq)(1Nq`0;LaqPi*%>rlC{`?r*nMUq$u=%0=|@~44wLaWi7=#=sriQiS6 zN%P>#*~bK{A9v(k^fF>kjJqj+n!q<&d{9}mjc-UBSu7HV*a23W#2(&z=LbSsRy zgW2Z98!_xJG9Kx{RerkY!nr(Praz)_{tlc&M@9bef~%IWZ4URaZTL)<6YWknpeUW< zFT>`zl;^ZJUvjQM)|ID`=E(V4FRD;OH1d;6Xvxvg5`Xk(OQE;MEyce4$wiTyG){j) zDrcb*wJrRtF|U-ldxEcyk?8ml4$4k`Ls}^bt6T`HLDr`2g!;^gz*?yJyh{SORaOzp9AeFFyXw4#zuQ$Ot(6vB*9`2QgU`qj zn(v$ai-U_AfA|l>i@=IWJ_W;iYN$0dyw*kASEp=|M5g+>1=X0Tu+-1$A#Uz{A))aJ z>t8`zC9Iq^s=6yZc}1PC&=VhC2@!6uSre6t8yT-Gijb$W2XA-7)U;KiaE8ZO#C?55 zd3Cb`!=mKb8~J9L%p4K^WGcSvCz0taCTOYkk5>iU@F>esSqt~fpYfctqP2ETkldH! zqmd`9vSP}tlr>4FT#br|821-?5=fJS2Q7Yc*_6HcUVu;}JH@mmbZgCqtCpjH(z=(3 zMrlww>96E&s4$fHUhtoa8|ldCy~2ryxd8yczD zD*cLG0@O3oVT=ZtGGg@%lu7=WI7p1&kdlFW9pn3;@EzQ&Y|{`_P5=g!8;aF;n)0e% zHk7p^d?;J^3=;9_*?&ZwTHC2PWP9)ls;QrFD^mgQYI)|=zpR#a*S&`oGtP#TGZT~Z z10r)24#f-t z1(uT)2&9*?j?0j1Po0rN(Yz3T2zhJ_CHZC!74_B{q9p*K}Zl?zs^$z1QXyLnhti$JA~?K}`93Ka8^TKR4GSzL2N(w;)<~N9tFHk%|8b8x(F; z6U+G24Wo?mBeLfF&A{&B;!|>d4$MW0tt2x^azFXyZFn-GCFyFQPFhC68VHk>PIkA$ zv0nWrosmvqLq-a$|Gzhd0No}(FhF-<`8r*``%>N#D;Wk`oxODRha|WH z86!v#nMjIEGae4SDHeS$ve*D%*lo+Uzj)as0dn9h9IZwp3{mfqB#OS!w{*RYj&?67f8C%IL@FNF^tWN)dRBApB_t4v>P$Q{|`%pi&o8-I4DvSl>)8F7AGli=JP2r?SZ2oiFmw z|2tnD5^;KW&HXedVvm$^FNCGpe(4~}-bPLwc#vf|So!d;Jc=BG#X^T*rsJX*Q?x`@ zLvGRTQDQ(~18v$&YVIrv8(&zbpXYg_BI3|nG9X7UTt#{&@Cm?k$k3ImYr57*yT1oU zhb1RvrhwWu%ks-=27sX$4IklQmdILiSUKI$G=(X-MW$?!7yoVm6@O2P#NM z8-~^r!Zol%^7pbkWPVFet4f^&#k8&i-QV^H5Y5RLn?o`uK?Bnsotbp3o!5^T+>dis z0WBYe1-8U8y=fLdgkLV=PWLIpF1HAtVivYk=uPB|Lm?OBk>yJVhd_PaGsj-^4_C=E_qqQZ*(M!xU`8ES- zHyq&CmSf?Mq->(E{wZs6t%aRu=!g%6;v`~AOmbs`W}(CyO|Cs_<9)mTT??&OX;#x` zd?-J^#fGqeY<+zVSGW?0;V%f5ccEbJF(b!VydVA^*ACuz6Yd63EdR>p=dQG8_6gPt zs+SvB(DQ2ySOdKZ*nAl9+$@%OP`W3$yc9sE25zkxV>Y-SdcbrAaQX7avO?IrkC6?c z@AIW_NdFw3hP=d3|8DJDwt9Yl5V^7kmj^_qza8+0pcjQIdnt^$e z!I}OdZcr}@vA-p36UM~9V#jc&y4QJg^-&ED>HI_|h?u+<#HuKy7sLKvKg7O^J0v|q z;0RObU7>JGfRh(h?jV+j9?doon&m>NHmH(74RZ8?QFYbz`@Y{-mx|Lqfl9iz>iH)2 zLxn@f9Tv#Nw+aYEe6{{+j*bp0(My6@I7`f34c)g|MJ!3z*h^yM-Y`lmT>kJ>!+IaG zRS9@MLcpdndYb($%pg(GSYoVumVL-fTGWcCVk1We(lJ0UzNv`rHJLa?3rARfQe;2A+~r8t|P4{7Kow!ix>sP1yL7i*P;!g z2{aOJSzTk8ssuH8s^l&s@z3C;#k&{$B)2Lj+qjbGV6fa^nj=8Co|Mr(6n|WL?nZyPS1!Yx6k$3T}{9GKeR?%#G-F1I2f)cn;Z3T;=5Q^5on5E%d;8D zhS7PxvHQYwxlkR8|3&jLk;}J(J@nzJbsb%@lvr!nAq3Jv4W=0F8Y_thO*nOD;ALz zw*gD`sngjM=J^V5SD~|alRL{Jb50W1wbr%9k@i2`P(oNYw{wonHwp}|>{0uWLRgo7 zaIolr`#$A_s7p)&Kl;38)lcI{CPfMlzV?b{UrO#R)yivR-%gL`xAE~+`&g8eS2#*p z0?ATfCN&wO;6q?MLi!3>{q1looSdUO{a}6BEKv5kBv)ojuh8Xke>ORimseJ)rhpb5 zwQJKc64qZH|9vhnVTD$A^kG%(-f84CG!Q=7Mh*xZyW(oM?}%sy1_ z`P@~>#(7c&;n7z^ydyQq=7%z$Gcf4BhZxA)9FX{%yH7UV2cZ*7q^J{Cp^b829L0k{ z&{Rv(XhDxORC}P35lw5@8I3J_MKQRe+Z}h@`oXdz@*lQL*DF17wU%#kLOSw_x-00c z1DLNa=*2Y)*S;KN`)sSj{1Axop4J!9&Zm$57}OiJl>(FJ< zWV#a%2sZfiUY7o&zcMI!%t46v-p%r2Kdwk}RLVgSjy$gSv4QX!SlD=;%A;I7`0fKp zKLc3)dwVOLh{D5fHX?R$bE8XV1+^y-P3A3)tJ9BIQ`J1_`X*|g8**SMqpjmQSxZ_# zn7s1;pl-A@%1feL3>CE)6^}Pgx%&ZZ-0d2msKKT=d{}ynd?xMv)qlp73Q-Yc52ijw zPQZoh^)<5k7_Di6X)<5aUNq@?!36i(?s7Nvi|V#}C`;5I2bC+GGW7g$AX4FX)=OXz zC%t?i=4o7$UV6w-R-~G*`hF!C+u1Q3EcmJQwFF=YHC+4)tmfom@tjRSNaYZg*74Ly zO?28#em>$!s`9;s*>~RxN`i@*=&;u$&m3{(&Lu1al&@F2iM~$d(TrzbFawo6GfIN} zhO7yrKL_^&o%tEIn4bO312EMEB!OD8Hh*kPCTNLj)p)Ya>Xi4mPqK_dJJ&&8v6{49gi&WjA zX4n*K`&{Iq^#T(v=IS+EHOHf1%2S-7!jnqQE@n8rTXUb_l!Kx-%cP}QA_S38SU>;8 za&@tw2fX|T?yNyb1O%6p6~%`|>}t)z19O9IAYe8;3VTIzZeke-N4)AWUoO-;acGW5 z`aDs)IettH4-Q$3<(Hn2{OhwStdA(48msiC!N>tC_XqSP)OK~Y|7WZ*J?|=R6xjo1 zMiPy~*q6T(bH+4iV<}$sPlwYq0%*}Qb%z3OVv=vb@_6=6^@jMXf(D_=K5>%R9ht7W zZiXr%$XGl|M%RiU2aJmbU&9kn9z!6+uJop=6^orZC+GwF7Gi(4qfV!LU3RhAV8up1 z1|HPRdXrE|>S8t~la_w#W#w?l>Wf{?tAb}Z&$G|Kk&3*rmuJ3)xvMp5=`npDNxidP zk5>y%26#vDf9S*1@GA{$z&tSm$gO>r%O{(Ro$b?9m&XK82_OZFbeTs8M>Co6>4k}e zw7*||@wEq3CO4SK&MoK4=z(_@`$zMwNycj2a*xVU?BxwxJScHGxN5goeoC|PqE)Zg z$k`Z-X7KfIx-I?2)@A31qXETUQzS3gV+yLSV2y(}rufBO!{zmGN<{`W_l@hzv_BAR z4_H|jMHe}uL@ci~&T^&I*T`=4#Z~LO>TeYECh?AF`czSGF5>rTprX#bD-pt{QAzw` z9d#gC;2#&7EcgWw&(w|dq&_ACg51g@H6BF5D(WYTWeYf(V~h)ffTv8lFLJ#kggO)W z?YoIK!86`{rsgroATAl``c;GTiP}*TgqITHl+i*l6p+PIE|e?tq5bhK=|5JU;ni3& zdXRu-?i7eF+Wv{78;~lVDp1db)|IcuWQXGaj~A8|MqKFHAX`g8E-+n_K#!2XaSE=UsT7`W)iqs@=~WkNFekNdOzbKR7?#@ zh1GXfv=AyMN0KumCwBC9n(8>G*@2KKz!A3dou=rQ`Pl0AhIDhCE&Nh*=r4;28$HeN z>v8~Ni`ckYh)|Px$}G^BJod_MFtUGXj4nuB$RG6vZDbDK8W(U!iH@Dlup_g?;lL7r zTXQcn9pnG!8XGO168Qink`sk{sbWC z>79R{aM1nGW0K=LFiKxNDs`sG&&0-=({V_@R1|AVhlnNuO3fkHLiz>L!N2hXx2@yuZJ`zF})Id0ROUqevy4sFy6zjNsF#8`?U^p@Jbdl1HLI(CGZ z!aFa&7~7*`POK#^+i~eyzbv)9pMyeQPYH_souAlOI9BM{QxMKhEwE!TVwFTbd6-pS ztx>3I%f3PsAMp53)?@2eP4hHe&Jxa*d4oJltu8Ay17l7{rOt}0LI>spKp71~1@o)+ zG@yGDB-JlzMMI~#2Y zibp;_>GwGwPX<4y_`5@}r*mpPcM*!2zLjj<_=)5f=896A&m5iD6;mPP;M6H*2PZ#%IX&Zgl`J2l27T zY$t<^Sbbu@bYlU-nfpk#ATiW`4ZPt>LBPzag5C`3^@*d{AYx);h4LSok*H`+Jlrq^ z0F_|FvK5uJ_dgw%I9fdqQTpb!`~E=CJ<@kgoA9!MJuu^i#*t+!WH^QXxV4uS`QSfbU#SPLX6^XdhQnDq(dGqCmdGF-%wls#%BE=n;;44mm&bohWHkM zm9lohh(Wnlg=3`+KyGesi1VsJkOLG^tZY4(@y|wM0Z20N=B!fCzVcfnKZCM_>eL6c zMMaC>bpWQ>RDm~KWL(xk(dj?jhQUSCIt?o$w#USaciHV4y%O~GHIaF7fedg*uFcu= z+{ynB(sxSL>iIgA`q2JIUk2E(ZZTi-xtDoQix#TGKU!+M+e4v1?nEF3Kq`{hl zAn{!Q9gl<5%u4<-@P@OjXPsO|v3f7H&Bbsq6b3GS$K7!&0ZK!H);#OPz0p}w+a-?v z3^b}M#f8HLaxmUSOBO;C-4`B=;fNZ{9`rw`+Y2rmsSB#r@Vg*7l|lVkYr2i*^AwvI zRG5_1{xv#vp}m@yr6d=v59pxEQG43FoC6f&xumOP+1~*PK(Z?xM!-=x>5?{foZTWI zzi3duWy|oo5!MGt`F@3;PKi8!LcAIZ)OQ*WeY5ZDYo*m&>$H+zBAI}4Dig|O8WQ{> zn%k?6IvP&ir#UY%*>HFYQz%_dhOP+aj)jLyw736*j{?l~BU&Nqae;U+^>6M#@vzbE z=&zPOPFsD|AP4099rU_>g#;&dB|>z3PK`YY?^pgsU{3!E%}Q&Dsv6vwN<-;t%CPIi zi6OLFEv6-un~zRcL$JJmiCqxWylu&c>(O9_(~#!*Yr0{^kFx0SiA817+Jk-vi(Tvh z;RB0mWIs)8HMKvoAZzcU?Pngnt!~R&Z;+1yCntP8resZQ!TG$$YMbFtGsh6A8D&>p zQ+csg+q>U~eK#h$=g1Ql^(tG<`7tY*jcs^{r7-LY|2*cBO?^-o)-uHf0kC~4(Gr&5 z$dCDIR4&<7#8>Z`x#9y;1Z@c6=rm%2Y|9k-(4AUY)rJv$hRfR?M=oB$pT!I0@0=1( zea5yQJ1EtBL&hP*EE99Za(H0nVxp)5W9~(sdQ_=FcjjB?sRK<+Ws6`!t>I-apwDw&Z>b; zadoft)e*~I5DrNE0fd&Cq*b3|G>4^$b-@xUvUf&n{;$fhHY+poq$|@K$P_~~%+CK3 zpb%5HIQQnZ%6Bh^+l#+*4U1J~>xaSkdu9&64`!cAtS{4FJ%Ee}aaUaVJ>-8<7N+YY z`9V4!TG`D7Gp3NQ}gVM*2AWWiq>o!lV-% zpH1xleDk5s;10c$()#fO-Z@1Z-%{LZ;*}4MT}>$W538~|2jd)w6<`ZwxoGShHZbm) zrLiWjP4^;dwkhfezuCOp^&&IA?LD^YyTwoM+2h*(m1LI5cf84GG^QkPUb~_;$yq6fN`5qKC(!Ofdaet5?C;VDk=`&L4}(S2i6QCu_FA zr_&?6mWr~G9Gt3LdplM4xlm?62Th!R1n$iJCyo#}lLduYQO1Le3;N%BU+wyF*h&ZbO{C?4+d8um{$^yQCK1Tr;z07jg~ zD&_TEW;n;C({%JG`|T=Rn9hHz!;at3r7RQdSu`&(Bgw?eklL^?A^*;F$NaB2F^`Hu z*4T0>9S$-v6lv85+gJ56-Wi9S{ZU|&yut9_DM;{#E9jz@lVQwz+Kfqj z6y}nQS_V0}w9nfu)Z~%i@nzosd;@ex10?#ZjB`3JrJtg?05T^!Ju<7p5@7{%6Sx79 zs#sML6Wz~A72LM-v)Qn+(D(RFG556y28g$^W7<(MJmoDN_FqC;hg*SZmqDEv>U>8t8x{5J6)6a$67@|+j`Tb zgy@>=735&`8wE$MreDS9!22ty1k1!eglH_y&2D7XQBcS(lq_-GIsIosrIWj!7i)o@ z1;G>h%~N9rY}`Ph!Gf z1?EeK;HP>;Wd|{RfpLi4Rgd3AQBhGY5aJK^ySBRZ_XSu%ZZa=6xfENrmU2Wf3sKTA zZRnxx40=Q-`U-yw;r*!mRsGkqVuY}+-d7v_Ajz~?DQzuD2C`D(a!Y}mh}AiN&b1Q4@Ep^%2`)bPKB!;nbLD*htd_DB zp3B4j^zl%^^v-}`GFT_46|f{tR%m-Y(<*1{MUwYt`91^tW?%4ASOl`IuE^r9ladNNvst&pNF*N#XznAzr-sBk=)fY`+qPC3np0#BU{dphReY#0h z^)^AVaVGGcKJl4_U^c9Mj1?tj9fuKJ9g6qaOSa%8W1<=kII;B^UDw=0ac-x*6=3NU zB502@T+@7)xE|RSs{>U;9D(s#P9sx7pqj>KpoE@EBvny)Q$5~6PpdwC-Lqqm5mM>5 zJM)rT>Bm%Z_`v`V9+~?2NqX+6-u6qjk?&yVwGc}nE2390J5=e%9A#7{VE?VwWNMhY zomxD~X~l@eB8UA)tAkysV|DuWlwZNE^%jk<37_b>oto(f6{O#}wV3QTQ{UZwuf}2b z{DQu6anp-KagegUoSUYeYd>kQxn2eRoR8Bh3gkpi^Eg2gb>*;L#^Q9Q%c9VXBRz{o;(lFw~XUL3P}>&Y`@~ zflr9(v@8#jHUt5EIH`rzAig2JI%qM%xK)hBxF~NkFCrmInZ8u_;MBG12^jUyl%>jN zT!5K;uz~nqSQb+cwblVg+EoVBY0$;U7U@bsR?y;E22y?q!+9@0g_<>6#H zWlAxCrA_~jj3&|_Ol zxqA94&<{}g4@xzlX|e>l(#Z(6=IbpbQ^teNXtmUNH2yy8^k|i7n`o6n6gUp^mjP}> z7=ZPd1K?NYE*-Dfq&!-ZY9Ad>A*)xgWM5H!3z55}7E_1S3Ifu4Rp4y+YNCOwXi+l6 z?ZWfqSCdksKmtPX__CkDRmS269Skca$tDFichNf~)Cb=)Ay$qAfEkiHug7;=KK?yr zsmM%!GV^)8m`wL1E|yYW%vqx({dQ1nXg^^5js34xpq7ogUD7!JDEGFI`3$L6Q#T&E zZd2%5WUi*_AS3xk_nWI`o>zeKT;-rD^+nXhw0wwpWKgJKxDo(H;_oxCg!wJ$Wk~TK z8NW8Y7+Frr)X(wu`LV~UM|@#8&6@?4qlS@`xCYBEaVry%vICW##0hUs`UZe%fixo{ z@dAePhzDWZs{I8OyCl|f7PX00GH^k4i__H1+q1OQI34kW0+BI)vXWB&XS4XYSWw-` zHVDxAXtVnUDiV+q0$Vt2vIj&IIB*uabcqWue_cD4#_^XyBF(@ppWPjMtDqA%$*uPh z|1VfWUw<8+aQyU}!OKqyC^A!ev%rl>26fe`!@0Qt^3m_-~k-LjeHDy~>Q zZuzdl@O<;cYCK0Rz_EEJ?GKPdNsgx_aba2U3RZCKy zFvFbF#;pC9_&JRUA#=o~Hzl5n58N*)rV+tw{>3*`*%RSc$2%kjG$`3g*qjE;Pm z$CHgZNTgOl!@|seY)V{-z$feB$3~-n8`iRBgK(bZIryA%ceKc#3F}WPljT*9EGI5z zOv@nRnG@aew0YWf0F4`mTvAncCWj!)o&wbs^?mb-48U+wOw{>gzcIDgEvI>S`Cp zAeQ9Qr*CWaxl>!#7hMPyC`GQO_up=e7d}chq_z4m4T6ooD;boAE9VpvNUbT2x8FpL zi|#JeV6}$+_bn_H12$n|$E9{NxDU&IsdJtmxDvS<+`Wj##qlEREU#hMp^6}9Zcit3 zt@FlmD0x|L&@gRO14Mb=)hilE8P^B^HRiMREw0Q*Reig^XKnpu~1TlI#F5JyMOpaA1bhuA5 zTuT4qB!@AcL6Kb;#FaB7x%_N;9)`S$7g!@-(gd>V539Codh-EiCG{aDwN|K3-w|Gj z^7VtGb)MMi`CMVIIU}0yL{T>j=O13w-@#wK`P7<7{+T${1b%s+p?K_HXqcxJDbi1f z8sB)Ab5$~hL5^$jIoQJE0gG8w28O5P0gn9nR$f*o(7dvouB#(tz8 z?ahK3myR6vfR?KDZ0ll76b~@B3x!Tm%=;U0s8cV{OMyt(Ag-sc9MDr>XOIgH3BkV0 zSt)Wwte)){LLSX=+1r}6<%eV`jW!HoL53y}UQ;lbFLHrhh&+=jN#e(nZ&iIWu5k+1 za|+wXMzn1|MPFsO@^UOuk$&tcQlRGwTP#7E@p@ofwO)J3sfJ4+x}l=g8w5|8?2zDZ zm+&P4ynXPev2C+^>|E{s2B~kCQAjl)yDSfq=uXJnXM5}+$9>)>qLxQWqSc?99UH_M zHJkP&ieBxmZT@3Z606DpHcr05k8%!z=^q?l4F?3H z(GWjZyvVMilE?83S>m6{27C8x@~$+{Dh$E(F!zW%e-d`hPztd*ofC=xIY7q0n&rm{ zu0Ck-O!QasD5XIV7k_JUBz$9QRfYFVQdgO1CBqHddG(~;y~4GM;JuZF+0%h{ePV%W zwt=01qe z$PI^IQ=@UTaL_%e82y8dScW7k{#iaUx#iAvWe zRJ%0nW+*%s$KZT_EHa9B?bx(Cnd&;`#EAFrDZi8G{|m=2s2f|1BiQ8D8uF`#<6XW= z6J+O&B-x5Q*yQCC{TA16!Vas6?Zk&aCJ<4EVzKJOb{4ahB*jW8B1DoDuG~l=zX`$Yx-sv^-5ZQxGO)h?nIs)N zn`iQ97UTN>Z(TF$O|3?D^6MY>6D&wVnhJ zdy@vm1i^@Lh*#Y>>rR*Hm~W(z=z4&c3O78o0A4}_RvRTvGW%f&(##3?hSPCpvG*< zS0vc~42N({4~i^fc>Q%Aq88%y^gP`$@kV+oXjjS7?Ig?5r~->kI#qbcV90klrK`&+ zFFpiFM4Ard3xyfvKg2I&wrCN;t_8{s$Mlh#oWWy_+g@T%PIXhbHCGn#tfI%O%6g%P z*|9`QSsAEsJf+_Ww01E3NI@tu`!EA;f6he{f8{z(xd{S0JbE9{0=2NBXmvB+Q)8tK zYPe066DH(U$-Bu8jEE*V&4XZFrV;5R`uvl|b&qf9=EH71x~406Tw@_Y%__`4{8o5H z(4RRXxh3!pZ_!tx-*9m1*pIQ(6l*p5>CHZ|Uug-{6MoSFoC5h`BDCSOrA3y397J0b zNe+MHGc*V4kG@_Xrlpdk1`5@psH=Bz5v>oQyGChQYu(mjCVc*Crrx3_I)U{yw!S0J zediPumkd(q)fe}k{X+ZjN!LhTWriNI6d6n|`HMjl^#CC4LAkx}kf|T2)f{sSLNuwv!AYo1lQZ;v(BH7&LG{)1 zS(v9o^bnXB1zG}`Al+sSoH1yZrWjYGm(q^U=F0(``K;xyBF>$Q;zzNjs9Y1bhP6ly z1?5TMkzjQMEu{-t?#?LpN7I>B?7Z}P;yFg)m*8<1b>4(kp`hmwK5G=Gn6(?Rax1X3 zG-jV!@5JOEmdgz{RzohpIJrLQ(O^42%p(y$D@S}&4&9tfB?!ke>g1u8;=%o)p*7@fDwFpN5uq4JaRu4s#9 zdAyX#ZxBTbo?(~<xy>EKQuY$X_@#W}W|^4yAM)oc%{S~|!4f~09o5cs%ijc0FBnKjJZCdj=H>n~ zY8!nxDuzs_eL{1m&xnd=!A5gfCI(>rg01`iaRtQIh&O4{nwwF8fj^gV&9j_B*iDtm zB>CgbNId#*kTc?0#T*x!%*y>s;~&+l2rN&=nL>B2Zbx;y2>cRFD}S0X6ICzd+oYsx z<>w1eZ>IDsuGbFGit4G`?p=#ryVzQDZLWR49 zxw+V&f+j?aYQ7l$E8rTz=3Hw=zUHeuAu@-(b<}edWrN1(@F~EpjXcR04MW3##jfMUf9_s9NUf1Z8w|oUi)<$C1amYx*+P@#oQ(T(iafi_<~hd@LM6tBF?}32qbCH;up2 z;w$3RrkcePyFscTumUfbvz&_d-|bCGW9x(n@0P)H=TYoy-7qOq=w3s7M4ixsALb2W zKp#QzdTfrrK`y&Q&$7CVKUuIKsbv%xj4QmGf*B=xRAIB4y_A@dO_*1J`Yu|CKt1?_ z31_2!vuBYzeRC=92hQ*_Uf*i$^rsgaU#;nR=1sGAMTw)i*aR;o{Jm=mdj*pi#@_-ayH{#uG-V zbhoI~$du`Ge_o9W(1?-S^EQ~kOi%}|=ouzatULyqeHAF2^7T6rJXGA@+fZs)59S0g1}6>v6e^f3H_0gz*7i|s)+ZG^5QS`7<5rlmkuD)Dnsi*Z3mUm57)M^1ou zSRK!}yuY~D6~KjwW~^?)WGi6m(CtZQ_aGo=s~F4Ac*K?7%MlwOdd!iRrguld`iNS< zk9ObuUhu=J-ao60)?s+L{q7E=THL5eNxJz{%Csz_Ve#IXO=gwl&@(Tl8mV*vd`>Sl zItTIW9U9)2sjj{kXsm1h`M`APH8WG;ay@Z(^AXI29+~(6KO#(2Wv^UtvB^w+vZ?<) zta0o4Z8Q)HvTkaGZ6#NA)J2X}g-z?3LKS59A%g$bJ9w(sU)rvp5VLy5HLylioivFP>VtLll>1AGxnb8HL}`Ki#$!U@}7*ZvcO8CayE%G&=A!{LN?R);Qi{5|!n zCaC1YcV#xS?j_TtBw`OM#>p++)(&xn_ucN-rfrVxaoI=>$7P%EToQWCK@oNZ@n`E$ zv@YUTGZW`SN>n>u7=Ca5Li(~jq1UF_?$pXus&Q_h$&u_!x~^ymiq)RENn{;lKx1@` zkQl@pd4c{(TdZ5YP-e>XWXW|Z4=Jl|#PjhU&U)^6|^q+#b5N!B#Si zGV_54rGcq6J393a=f_=%_nHkrt63S8wf1~zKP4Qm*nS2PK(T7rEhsjksJsw zQ5OmhUu*0FN8^f=P$J>d|6~YR8(7dLre~oZDnHe{wGu;SCwsnb^z1iL1)Su}Q0?KX z&?-O_YwU?pI2z{%-3f~JJf?HIxgu0IuZ%1;E^7&1*DfWG*{~s?B>lOSXroo$J;5W!1&l0#=!tJ7el2HQ(fbSw#7l#(D0EwBGLH`S!HbP zm3A&0h-n`Yx>bR2`0YiVZ8-o9HTA+u{Kf0l=`9;d@p%D)R*jD9pm9vU0OcO>aI{=i z#&@`ISBWA--S+WU|1QKe8ZUsr`%sXF_O=OcIC@4K6jxwa+{ny|r|LhTe2_SvVtn_e zoFb4IX0N$Q0ljPF>PQy%ySMy^EaP2|I$!qZ#fPZ+?>nCS5-}nM$4XJ*zMvMR!zrLy z_b_tT6PYEwwRz27H3ocR5U26Cn>p9pfLG%*YS4l_(=sX_|nOG?pVW9PL1~m&czh)C@w^J@M#FmM}JFsAx7*= zraSk#p+N7A4-hSb-s~q53=0O+qz*%jZF&Wz%3JEsvRNJ}2yjL&a zPsM2Wbla8vJlmR_bJxgv?|xF#!jKmez@Dosl&4@7vD!>M1WseKu^t+TVwL&b zT2OS3*<@lyZi@-z?k;f4Ac6^R0p4*qD{8d-smE@SN-K(>>}ys!)TM^BcJKZ2&cbHw zVR%Uj1}JxGL)s11SJOKVH8ux-MHPdxYpF@kd=x!QDKEO8(%#7yD5Ojcb-KQ`I@Fs3 z0S|zE&+J=x(AWU9e!*A@ao2ik;tnRD!?DHR0t{ZeDhhzBe#Ju2Va>D32GZ?(VyKHx zK|%cPQ&_hXDIsje!w%#{0S7+`4_dWPui)@XjG zQZU7)X2;Bv7=p|S|8@msVc&kpt4w?ijOYATEn|f*rHcjxrXNp3rw$ffG<2mFcZ5!s zjgoLol*gG7K>L5PQ6Ei3CDtU+%M-GbjEZnJ9MRN9_4w^Q#3J*e^x*GsBpDhx3kHVd zO631(&|8mRthf&iVzv<(s;`p1yyJ6LLuWat}2{%-Naa1`EWl z3|DIVCPR@KfBFhjjcTFDF1Mf8)!-w{V-72oJfSd`vp%IJJtOaN!={ zrf16)hu1~bs;UK*Y#yqJ#R^{AfX768@0^U!HkY<86T zQFOqvYx1CkwI2#U?30slSQLJNClT6Aoyz3yo0KiDV%DoTQs4W>Xt)v4=J(}x;7&!b z0(Lr>?1?$;*dXr7QrQ_b){lS}WhaG$9Neh0g~BDb5yTD|v0|kmP;zgs?Ij!+p=+J| zaA_=4!?UKD;DX~@$6`5EJB&>ppu+dYjqG%;#7;*9_bKs@bJ%qwC=-{@wdNpS4PK%M z*`>UFQC_Sekg$n4f_gcg2cX&W||zTLeTO3+>kH)P-TJzCe5P zFk^}9D;?F=HO3cTaIiIE0(^`dH_(RUFR}LkhSd+Had`JxNb_z2oMi9!BnsRoA(8(;w}eFR$;*}9D%l5$Y~BSvK#qX zMZejP0VJ{x#{~{qBE)v({$zoW17ngwi51a3&3*kYVLpyQ#o?nQFIDHgbN1aQ{9ym$Z0nqTt+xb8Hmp1rpn{LTo$Ebn@Ro6 zL@cWJ!>>3K8`qv%ZB&MSzg+M;!E7W>7@NVl0&RoEym6u+r{g zyQ4|8D}o4}|J@|B$$ri+&*7r8pgtO91!URw|2rD7jWxrr^OQz*+^U-sjfxv=_738a z29mk4_2Iq1#f{cRpm?^{J3F90NTPN6r${;_zfyb{>bXiTBw+-cR1PI%Y0x27AF!MoR!+7k5#Q6qPM)MA^O{%1$v|6H^m|I&+v!H|2UQ+J%Si;@AFs6{$yP2i&CHpPFwZD=}xKnrXXJqaatfYY@wvRW&?w|eYhovVv z)Hd{=nVIJ{c;94J&Pgm!!*XeBqv=@}hIm~G;4XxvHxk)5y>xjLYGXWnGBWGe_F@|W z$^ja?gY>$r3=|u2P39MCnKdr7eU)hIDT-K@x7PO-6^6C(ksV1EOe=>C`_)gL7oLU- zt_oE305LpgwLaN(;&vQy^V2Fz`CzvvEaa;NDb_Tr*A-ZXuwB=Dptak5$hg;(2PhQX7YUcV_cLZA@MSY=2@COyTF zF4e^oh+rwWdQCpvcoI)ZhBBYHP|iiL<*t9xN(Q%l40S;1&tY>1)d3r7`^mO-5PeFG z4@{gL30^&Lb)S-{B5wK`m@Oq3AE6m_vIS-&8J9DJ7}CzmW`szN7&eLZ!+x8D?@$r? z9w~iQ&(3_w`pTl$;79_OmlJR~a+*5EEJ-U1en^@6vc(%;Ht3!*`;7m{DK~n;UR-dX z_rE5@2$aYWL5{hGobi7O%@9Q{hw%yRn0jQDC_%T9Y*o&>@db6tFwd((#;R|TCHT}p zsI|{Pq=eMk_VQCKUG>>3deo8=ZbK!H`nm7uiMw}WjxP*Dp?t#?s~b4iylv=fTd}Ox zw|ln2R8aO?!>1<$*T;)PTi$lZ?csH$@~7Zm#E3Jg@95H*W&3gcO&^$OE& zte`clP)O}Fj@Bw5G)7ltGz5t9hXk`1_M?j@4}IK(eKEKAI&-c0AwvK*s`=)D)vz|KIoyLBw-f~UXq7xj39 z&~zM*?q9ugXDlFBF|P<>ItzGe^E@H?(l-wb`d-EG45BZIbji~`5Fhqw>nc=h2)KW~ zd7F>vcU~a4HQOS9d0VIW21+Ej4p%-QcuU}Vn-!dqp>vWihEsXewnha{^o~I6_HpI_;jjS( z*LMav7wftoJ_|oenEF(PjP@{CdOo3efr^&>w(!&|Q3e9O=6rAXoJEws z7rjP#UP{u#(q`tI19?HkePhkWcaDcl1BMv}+W@uhT=%;?mbf@m>vhfkKbn(dXwvDt z@Pa^M;3H$(1$vlHJq)(+rhUU*Ty;e%fV5!}muvW`aF(|{lVYb<`jKeKwJU|?1hwB< zDY|qQdFjVa+bM9jGz$eDjv7)BH*%NGmW>gYucd4~6^C9MO~xOO%=8_++-f+%0H7Yg z!kq>yB-d$ZDpqMxZz`cJrgj88%fldHMl z5!eE9-^5_1n82WZ`KGr8198&VX*J*m-5gO6ZtyPCr@WugrOdAQt+;>cojGjj8V`ng zOoMd3Cq38if>Ap;Cs3Yb-Y!9LygYD3>~UaOycku`fhJHbfnrcqrB+y+e)Z~13@vpg z6^%oVJIM$%k;2nrCG0dYt77wV$L0JtHbYeOLr#JnhdcqK&TcZZ_m~SulI6-IBtfiS zVf6AjG->b{B)i+}PZ@^|?B7Ned*^K&m+2GaPwxkV{5h3P(JGRnW#iTl;@Z4D1oeV# z88GyTA`C$=`Xh+q1CpD;rOhsmcO{E+qo-we{gbb=l|}gz_u9UrEi)TlYIMbin*WGg zhKmqb7~vBTQTun^BNx73)j zmdjl7>(tF7^G!m;uUSYl)LN^7pyfMFmM`u~;9LL%x$ zHI47Sr6WbcdcU1<&~;9}80)tp(GDXlt4%+m=f3!p$9-sti^~3+-C!jRjcwJV)6@IGPB{0o|MGd{<`~Y z-*@Wy7+9$$@Zv

    AUud4BoV|ZFk}#$|EV6$RCEFohH*ahY?q$W_QP8OUoJpMZ?~o z8HXPqgaev4gG5l_c6QoKQ!5rqy2a0yR%UXl%!!8lZNrEmDI2Cbr=$sxbHs2%^3XN= zekXf%+#r1K1c8=ow)l>z04Muy?&Ni-=d^dAubP?^gB6Z>RVar=r$9x>$wflK&ofVS zO#9FH&A&-o1q~&om=ex{0BPPR0`ep4@*kWU!69*J)tt6%Uf?r11GwJfJ?z+48qRgF zJ8kst!qd;y(J0HLlNo!C#5*wO@mH4fmW5~HawhsM{&M3}O(@xj1^#h#%X?Tg)?tg{ zZ-#ny>$xS{eSS|X^vR59{SC`k>#>#%gBSn$_j5?_MkEftxQeZUGEiZA^g7=rqlCzZ z1{OOxKyWgFL>*{w7N>r&Yfq?goU7~^E!`cleA9n{Kijnmb>J`}t?a3`{j^ZF;R;d# z_vDmh>VRJujo`l$4CwKpquG)5DMGGLi<|eae$9E8bSr<6on|OBMEsF@C;ZddoLYmp`$LHWdfMfj zs*s7yxP$W3yq#aKQ+E~;kUu9D=D;eO00xab_pi12scNj4&-iN2i>C!x;bn!t7HMr% zT7;svHI(PqM6BO)bOWq45WK=|c7tF*KCsNkTHwcap2{5W_&oBrP;-*4))a>vn6MG? zfZyViQ40(el*6vLh0rj@xh>AUIfW?Mi`lUgw6>y$1oisF=~joz)y7G-9V zJ>;@rf_mr}ku1hDJ1x)nE#53HMgF`0JHQF}d;41blm%KnSt^B^PUDIup$M{Tx_QP} z&dXu1X~d)fb7X?l8!9j%BFVp2Mg3x-sl1LLz*@epmhhA#Xk)m2ZxVT}A^7oBqgTq? zcCOcansotlyOm04%-Zv`2Jg$7^|Rvb4(1O;FZmk;1!0_YV&J<~f~fQ4;qZ>KCq5#S zUwX}tvZ;D7JwbPlK6GuGs8YoRc=Y>opSu>T3}-yqNmRVcKD0#ZF>(%a2W6&-EK;3w zqUQ~s$ppmgJ~}Z+t9IGOt;4qyTG8Mskf>e}a?qIpS)oh${e}r*<(WsRlq^eLTV3vg z_`1)BK~;62V5Bzc6OR#)-<8@(6zMs`$q_IGu&~c}PXkA|OIC-_T3m-|>0$-V5eam~ zx1{AnAo)J)rSL8W@xuiJz3KSyK8n$+m{=Z-$8}K5jD9_gK1B&CdDi&YGbV4yTpP=v zJ|lmu7vDUgGm{CzRLLMvZqVBkzthO^uraDNW}Xm`)!fxhHOOL`=46Q-$)A&@s?9NlsJK3@POnLV& z;as@j(KN^z@eb`ua4ajm%M-m5T^O529$P(THgmfCwo8ChwJHurjr}v0y8uy7;gF42 z^kHVRvARQ4J-otY1vGNiL_Y3KH~gdfr>j4+rRaAJhM?Gq^LeEIcX5(I5RGD*`IO@Y zq9dkVW?e-F0oWWl{sdO~|J^3p5HP{d`CY)j)+%tb-(ZEilUpWxvg|WjO)N9}qyoxq zVkwtt0%L{=O^iM8!$oOBiHCtEFx3!=MME$}8~N4rjWvDVE3JUHB)^`%0Z@fW^DIKU z#UU3uQQEdCmuaIwe`J4~ZQwK>v-8}P^>U`>;V)yZIJ9_LQf>+#Sz>EEd++3oLC6JH zyDUgTQ9MLrXt}Oz5^^~PRE9NGb0jPi+@^^mAfZZcWVXoVi3ZlVVxR_6bF<#x1i^!N?K8e0FS4O( zXq-4S$@D$GH8$-Ah9>6-W!E4w#6Pzg1zze!#bKt8a3#ax>IplhO6V=4CQMbcP zJKCHEtAM>K(Z#5w0jc359PiILtf~c$fbAi_fRQ;1#>0dZ3S9hu24fr_vfg70FG2Uv$(3%cK^zKj!nZg)2qlk$FEFKue6by>(#FaH2=@&QgIpE+$hgak4TTkar8ZB_fAek7wqbq4KM(tq(^8-&wH@TE^2;0n1#ATkKAW zw3Kw51W%#;dTz&b`iFLpc?)zrgHhzX7uLMdN~JdsnLEfc!=tBwaV|=mPag;H+U#Fv zEdukUhkB9Q-x3Aq!|2}9875ugH#H0i`5ySxo}F%gvb)E(C)Zt?Kj^s!5qhqd<{tvp z$hwzNl$Yt#whR5_^!pA)0RamGa`Kcw{mgz=)!Ar}32T8}=t-O!To}j_c(qw-(xO$c zT~_&9aA|u7@OR1!#5(e8WhGjSw{xDNpW(eb3l=wT9eRxKM`N2j>||U^7b@mtWr;CK z^v?V+cv+N1my648zlL+O2hZq{^f2HnkD*q?>H0aPwhZZOj1%+<$7(g^;l-WWlTLWJ z`pROgmuJA4)~IH4%02s+KiFJS%oV+cuKf36FSKgRdLaCk6-a1Dp@fZ+v{}gah3*On zUKsR$JU~I(yr(OFFRcSAqCM2K4mFkz1@wAFL=5cPZ||px{(rQQnvy&$>d`J6Q(^JI zTk!A?37FV|QYk4d<-b-HahEH#EJ*(7CMY1fmc@0pKRJc_Lz3Y~lmc$J@Z94BtYlcA z1BTCpcW1zCU(mQI-k`NI2uKb0)H1R=6bDJHTr>^BE_mHQsJY< zQ8CDNKat!}acLJn8NhNqN)xILs%N@0sh0(S+#N2hv7WTgm5tgjD}sTINR{5}b|&Qx z1ag{f(@Cgmn@iL9!Wx8E;t}5k?Js)d#-TPPCAMp$#xC#9MSKkfvG2l5*;baHlkY7j z=K^ON-mH49Ko-~F7yCfctxVZ0-aQx&eg~Li7~yVtv(?H+tP~EW_3R`IIbCEcOz`r< z{aAg**1U`#8CcjJPw9PHkofXrVm>62c9p*{D6^6N@Mu_H z`O};dhG+~|ipXzKSrJt;zsdRnKmg2vV-~p8aReQ|5Q86zM<9o&)pJPR;CdHLJT{Eg z!!1o6CZydee;58S-EjkE4#?>NKo5^2E#<~(gB$&BfCW1*0h^YPP8c@rqqt6m{U7Cg zu%f!-fEx|A5v(zCn(^DGIus!>E6??5ZNBN8-2IZ0vTfSEg3!E;Lc9MP!3yOHq)0Ms zDn@ztM+}59;goS#99j?(OM!_!#MAyxT2gGCFzVLICt!9^;(^m{;ayL{Pms;{WC5i4 zzO4m~z})#S_I!aiF7AMlzVOn`<-@#x3NyAfCx!Y7R!SX^v=gp3JAfAr3zpdje^xrW z+Vy#yu#Z*dH~BS zC1qtVDtGL>NQM4A;&3Cz@iD-;gEGZ+L%ubUJ~f7-VkNFOk?CvVphUlsKEb<{mOzudd^cGKYRI zCefDrXS1I;jLZ6_fJod)j6#mm@>kX> zG;@1D@1)?T7BR`F%2@uT;KG8Cf=~;hw`r;ljKtJ zC;Jc4i{0Pp#1>MTES0ItrQA`#PbycVb#{K6(XGTz=3SB-c$geg=4J)(qcTbL=rE^? zT2YOgrD~_#MY{yX@V|KD=;~mggI0`G5HLyqOf%=c{GN?#qOTHsuRH3ZQI#w2y0;c> zG0wW3_}MIJUgD`7CVFLBy1E*5_BsGXs01_5*hAs{x*Fw@rLqDJEAlO!ySbZJ`yoeG zN!hG2@tA(bX%h*7R;hk4A?lJ@%k@x)Ju!{-59|Dgvc1*@xbei){Pb~MfO*TZ5bX)4GbjKSH3my;<%{rgU@ z1F?bLM%`6ckwhILu37}k?P}9v^|f3&Y860kC50?TV@U2vsBb$>C29W9;ye{^w{2Gm z)YXLm+@X1pvNSeNXBT2)EiyEAKc`i#^V)T`PjIR$D|P{1KKB@T?+heqs@hdXFgi4H zzzp!u>J;4TiRV^K>seA2aYrrd^x;-`yMg^S2WT#gxa@{rv-K&O`jP%pf0`*L^%DXBIxdoG1LBTkB;y%Y5|o6s-q;Va zRMIcofHIXOxX7C(lYe@()0nk~C#<=ye zfXWPs<@0@L95iIgOO3LpWO^h&n|VMufKQwh&}q`RbtB;&LGPY^UkMTm$+7U7vP^-V zQ(H?72<3jJO#?44^_Fx|q{WJ37i1C^))H*79CY4<4bi~06tpu&?ub6tr&8qqOg=+44 z_6o`KDO!)LQThoOx9p89WQKG?Ti$s$zaVR{P(^kBCfiIZY?-8&4CL1U2}!&Y zNZUmRaVPXS9ODy{NR86!gHVNSLwd{=4~FR^%X|eJ$g}y zfNVJ~2{RJ2pilX%>PDq>!Ct1Uqj)rM`Wpi1EUA(iXc-8a?Xxc_d>O<;h-u|h?5lmH z%vFQwoic8>LoW{V7)*l^O%P4bTa)j@aWSD2W5P|%BJiAa&jqh*-YJIMrxTLGbjMC=WkM}B$-TP zerJLV^>c;bOE)3JDS*C#NaRcrYnA(qlDt1wjqT_nh_0O|HDU6(^jXr(6`+zO6(gC^ zTTa8aO(!5T<8OhP(pSXdMjgW4clHw*e3LeR-O1FIXspbp8cOg3VBN8^b|ZEF5nhB7 zEH}?@Sw`gTy*zDAs*`9%T_JZWnxx&1_8PHQs{M$|1dR8}%TZG9H%C z47=IsgNZl7KJKBtGluxm&Rm2KFNc1;#r|ljBv^-^t|WhgF^o7@Cdfp)O%VnO4NbtG zm#+G%sVR=y7Bp7Q8T31jYYZv!@%rTgn8;q9mXbrFX(CL7#|9}^uI_10^!RRh{9*S}VK{ZA zjmetAdp}9fPl__Vg&F!*=$i?cQ7bZ;MXm=$`ro>SX%& z*ot-lL+VM*@=6E;H(dyj8>i@2P!?a3!V>>l9M^LtJo8WCmh}x1ipiw7;}f(Sd{n5` zRuKjPK;@^@2PP$|bn0#buQ~O{r~kV)d24IX^NbEX6P9A+Kol=ayNf!k$7XGJ>n#(0 z;`XSm8d-Kdy&5Qvub(=C*Nvl?aL#c>nI56&~& zHg2oFZvCimgSjuIIr2pJy!!6qvB^?!CiY^Pk{hlmJKi?cB1kF^I*rPtu9#XE@dQ1h z=uT8B=7u0JaP3HrgQ7ngJXp4?s)cD7RxrXVmQp|BrkdV!AWYv6bHv(EmXMhk?*-+B zOGv0AO$E^kV}HCgK33EVQ2-^}t8?Zw@aw*>>e{|zQuG>SCU~NX^VsRW_1y`# zPj<*+8B|o}AC~Q}c`Y&+6=_~^9oeF+|7$rmJrId+7M zAIuxCZlmkDlyZfYVKW(;++;}$q4TYdU^Z#unlf@1WDZXoj>}!fLLq%M*kqkqHY7Jo zI1;}Kub)~bQd|T1rij0_e;Pe-YRBEM?qbn19+&<+yw9#LGs5(728#OcKNH;v7x8|V zbfM}iZMG5&s%325H5_1b$v%iaXS13~jQ?D9Tkg!`CGS~*O;ZmZJAXb{&&z&GS)4pB znu2UKZU0cU&`xz4-B=As$Wkf8L4Vfu8Zc(N6}XJ%k+kX5m4~pmeI%? z;rJYgheyt6MGfYERF#9eGWvh%9_u=d1An;V1><(WKqF6tH12k&HsO$9PBT4zS5wt- zl@b#x72IL{>Vi$}DwMaIl;^?6r(t8GhZgy^%Zk`IST9UeOHMQ*owsUk&;fIQ+OZ&FyU+%S z)b88*4xfO9s(}` z1K`nfwjNJ(m_4Vq=&1<4$AmZXT?@ai9K9tm2Fj(QeK{vpp((Ac@QDKwe?P`%R2h|i zivv&7``6dEf^Jm@ zI@oK%EbGt!03wWx!Wy@e{=Gr`t7z7b{g`eHnxr(0A~OXZixA4H98l4Q@p3E7kae71 z{|lT6t&pDA&>sY1@8RHWc)c<)N70*4NuwpCQ|Lr>>(YDL*f!Jl!C<9?w@txpGXv@q z=!~8(mD(_=5bvNp$uv}wiMYj^=)lqAeQ5HabJE2dN{}LQ%J)Lak6jWYM#tqtqoWVK(SMl%=Ev>W3*}E<#WENi zu=HeH#8?s4R~B`qreg}jy+mx*Did4=?=#VxWN(J>fUI35y3|LzuQ=lvO=M4826Ei2 zjr)U6_X$|x;R%9`KpF81upd>4ff2CU!Cd(yCmOiw;ia;Rti)vO^lDV+R&_Bqm&r{^ z(1)GNKfd&f2kW35*U7=I?aHgpO6mVa3|60L4608>)W7%L^k_Y?dCqP$VgV#ne9PYTOl;zok&zm zgVN7EQ-EjM=4a+R?Py4ca-V~`FT)^WsK3BeuaE{dI(!uvF&@V4YPC-L9b+ZfHc|8F8lPTY+90I05Oy5?W2uA%#^F#8d z5Sb2()PSZm3DQ*R!MWpD>q6YYT^Fph$V{94OKjJ%iiDR$! z3x)woVsT4&%k@oChKud27}~b>r`lbkS$|6x#ocM+&v`AoadHg<-LzGWMkVF_f{n9p z9a5f-E4U(*e`(g1bIzL;>K{&!qr)xzj&1h2)3opR3x`4SmRxOgIw*pfKSoBIHEY+a*hX5?vIB>vtf>c{sgF2tip zkYpz#xWi|cG7;*R1tPb-&b!fvRe#X|%=XB;pSta4>Fme0NB2JOh+y!L^4$IeY?{#% zl{3Lcr!4RqsYu9o7ddh!8EwTKeTqI1aK+cyo1dzBiYTv?0_kS|Sn>UG8r)DH6z&ZOw<2Dv{bAc-3_M`TXp#5nQqN8`u1{BV!tC9%O+8%CIiw=bmgL6T zn+0t7e*U6t+{*zmW%bmw1-y`~P`hJkv=<_u|gN>g91hw-jfh1QI7D@aSWC3WvzbtB~9`m&o$nyYpB=pHp?yHN4ilm=V4u00Oj1;5^f zCQ$IO%+q=-MgO?w56u2MZaYX2yn~eu)rc zr34T8FaS+JvcKxkOmB*}!)ud@ZObTJp-P6OY#|PHO?nn)Ae`g!vzbjs^ zKL|4Apz_KkORYA3POiY;4=kF(%Zs;NELx(uer8eG)sr7$7DrrK?p`o!E#2eiH8>q; zS}T$JzC_Ow$Oi7~ArBVvNaV?_rMWGZ%B*8P74J8$5cPq|M6s8{e0tg~mWJ?wpYrj5 zY=^bl7g7^TMBRo`U+lR(<|4Za4a^AaO`)MzI%UFdl4Js!SK!Fq5kPaU{fV>Q&>zXc zhSHo%L=|H`upTKg*M9Y2m2m^HE}t^}ecA}tv@G|}mR5sldMK^x0z*M|Xqo62m1TR( z1LNALFPOw*a?7#IVvYH=szYsK*e~i{x(K5Z8{-z?pwbqSbPn$K{!F6hFKy3xv z;k~Ojb<|5}OTNpo*{DySIgG#-d0|DSKDE zkq`oxkf0;p3*1A|7**N=h3R5dqM!T{STecUbB7x!V(+O(;_2H`iWrTYp$|B8)5&q? z)c@7<*XYPzWBT$B7zMpEijuaEuT843M;Z01Nc~yig|)2H8Ve4{zZ%$+1IH+BA=sj< zzMHT<%?;Q(iBQ^>_v@DL2FuQ6n{L3%-My0%iAFc^GH+(&B`T_|8utx#B)H)2kcF5! zYk`3$F>m(u8bWd{dB4QR0u5^I80z&D#KJJQhk7&1D4;FV{*gKmkm~xtaz{DbuF(NP=UhW3L`6sZ>F;`j}*~Jy@wxiHoDt3mz!-{7ZzLu^ zjXCb7Gt~CyzX(nn`78O9vs8&SaVVZN$)Nb=Pvz>Pj5s5Drl45uCh*^y2)`wQ5lE#8 z>hdSF0BeOh{z3cO^T-*RRq@xQtIDXF6``k{ zmv0cwB!t~)e<)6R4Y#q6@jZu%_p2a(Zh;Xeobbt>MH7|@dpPrd`2j;`@;!b$2iFJhgv3c=FJ4$c{6r<%#L8`%wvQneJrvI!G(OAb;NVp#A{uas-nRoV$18}&=BU zo~0XTuFZ%1vc2=d=Ksyw60R?+(#;T6`7Ng|&#XPW2MNtbe|2wOm{Adf>3&|96L)X? zKXcTCw-W<}yy^3hLseGg(G}m_gOzgF(K|+fx%SNh>6Q)Z{?2*ht|G&Pvn)y2a(ocR zFoxAH3mYD1U_DBKCBZ)QJyO+FMA}u)1NQgnd5gU>bd~Xq$;`cbb5n$++q96e1q~Vw zdV95d6VnNuI`!Co=YebCJb2rEO4PfYIi@DVqPbRQW9>fZT;uzCAyIQ)(gG6n@qbI_ zI!Ch-r3uOzEb#WvT(n*d_D3?K3y4tDK6udx za@p%4io z^7Ug|Qf)F`pGHlP-HPV?X>MFSD{i%zuUmP}N;aK5a`Yoe7%@~yPqWitoJD*@U zJT1A(;&Izs!5v`hl7UOv{_HGmwqTq4JetBMFgvHqCsz@~%p)zuMCxb}#_pOQrU%tk z4jZ3q3*iNT&l}`Z&F93IlLgW1@A8UW`!{O;8Wi+h!_Saks)fhds2Z4|J~RAj@fhmx z043aV>8ivjoPZPi0*^Fmi2h-!+koT~JbIJnu+Pei8JBy~_%Kpg;1qB4RF{aoB?PW- z5rizC@T)syCs*;h&~UO--g<$Q{=XG%j#^)yJqc*Cxd5-BQrIH(}&-E1%Oi2|jtLiBBvy( zQWn%X`6(UQ3crt4kQ=H!f=M&HE(MNiKKmcecP78sy)}742%$(m)WO>XQ6(Htrm3;MvUqTP$@+0 z4q20tZ0wS;x2~_hYZ>=32ydf%JO(%HsxQ0H3&mbx4xagBjE0+c{`C5xWyw1L-Z*69 zBQEjloEO`+{JGK^nkH8UaYlC*F5oKjGGTDI=VPtP`6R3(iDzP_co8^&|CE zhQZ0A!d_RvDiiiTY4WG6!s8lm{D=`N8T#6^;{aJYdFh4t#TQk&w_1kLyi+G^#i&&Z zPEW*|P12R-={i}W+q{px(8D3M3c{lc;MuRx2G)|JLyuI7N9+f~sU4Nhd6}ORMks#- z4Fn+VzrE${eBT@$!Pas6*U-uCO0G-Y22s_C33PqeeJKT(#m_o(Y#21jE7f_z)1d@Z zu?pf5dlT2w=H)o4RHi8^eW1-wVQ`%#tClu4rA26gAMDAE>P7F|gckBJWKEQ+?t7Mo zj>$cz0aZie$Yx!GG@U*=RiBzNh;J&$lvz1Xq%GKNxkB_sPx}|N!7Q2kn4ZBe9j?%& zTpxQ+Ug8lD^P5e8PXz0^tI0iyH&>do^9y*P05gpc@-ix^%pji-97&`c8LI|n3ue*G zNjN?CS#85?NE_lGb{Yt;tMUdY>d?IYl^Th&{Nl~ajwDK1jg?7fC)B6F+!LUmb0FpO zt^EH)920Eud@#SVK`+zukfr#?D!*)Ux}QMoG&@n1_W1=^ggPx7|5ydJ%~lE%cy&%5 zqkfBWS-4Abfq4Wv<@{H__u;tP9*8uPCLaKqbI|#58Q0stYV)2I)ZE54!|%xl+Qjr< z0f#1kOdK3bedQPGGO+ipizr=_B4KH2kGp5HJ&wB<{{?@k!EBBCeq@i?%93*&2=eGX zVD-WNgU-29_VnyL>h7E=_&eo_@reE&AC{&HMAJS)f1Rx)=HlHETcZ_m@mkC3b@RVc zkk=xKgXP4sr4GA2GN{m2aZ-*Zf~!UMygUTlJw?8BFJ|3l88%=}m{CHl!bZ+=HU1pf z=CQZX?|`^rrV%KKt{pckk_69l#es2F+c#HoF`>Ru@jUFOdHvg zO!|fq-QrURXqpXtMInIy8jpC>L_TNOuD${#p$+~eK2iAbnlIJRp>o))0N*`XA>Ad{8Edv0&jk;%puDIlmG8Eh)Qp$9*h!|XVy8>S`WxYiVo_JI|1Q&EwNGt zkRdIrAbC`vF=e#rFoa8KWq2a-HJd7%`?@1L?IM%0eZsZIk;g=SmknEo4;&u$3YT{t zVc7c5%^k{n_KPt}#tGtQ~BKdjR;Oa&Uw9wtJ z8p-Pr2Cfyay-q2FN zueIjkfchtfnS-@4z_1TDBN}Hy(_?C`&-Q>%w>Vz$!eieg%B9H}iTj@%+f)Wtl46Ns zj!+i*9XkQw8?`Ey?WUreGUOMelHL=0Rm-KNAxFozt6yj#KvoPT7|72H7|{=r`Dc@P zLY2D1Wy+KQ>JiA`SL3`$Q#h(YlNdlO!0U04@E!Z;y4rOqD#xYeSbCu*)my3+{c?gi%51^d zp$yipXt#XB=iY_hZLMVL=}*-K!ZhtD8gnyI(CZ z)H{%C;Nm~i`ud+ajAq=iGXPWS_XV^<=WxhOO0p9Po>aG&e2sV{58Q)zhJP*KH4Lj?bwGq4X;td{KtJ`X?=|E=&#s zX@xneU!ftKXA5l5KTZ=l$@3!Q2Dq=yn%*2?j`pebM-$uvF)etGQH!!>G3z;z0*t$0 z*tY~FmS&sK|Daw9`Q`o%(=CF+R&GlsU{9HtU-oGA`?f@>Kb=cCW`jGX{t_XAd6PvZ zoZ8IyD~vx~pB8yUAy5yf>a+eT?ZDL=i3)f6=4a|cSJ?p1VYNgV*L6r@QA(QZoA-Lu z;GDlq5Ei;J6GN}YW&HB(N3PTYc%G;B_=J5^B2s?atm6ZI2wOYeS$P+$l4GWjcB8~8z z4W?1?i>4I@vakSIbmj<|`Z^XE;=XFP#V(GViPr}RD3tD|GhAsj)7?0|J%Sqk3|C4m zaD)YUKu`|BB)ZZ?IN>pWEE;I=p$^=CIBqF$o_psRVO+u?vYzyIr&AUi>BRUn)%h1% zW^x!rMf{;inMW;fxug9|FfxufYO@X)-(ERQ^ZU;A@#&-KvW zmltxm1M9(ua$=nS-)ylVVnUx867kBIK6WtlYGsMvh=W`I+@PYWHTls79zCX{t0<#lP$o5{qjU|t}PgajlH zW^`D$h^Ed9Zo5Pib`I2H(+=KIIGYP?1luMAC9zR=tfN%$aX#|ija>6J$t^u8R_cjZ zjeg?XLk@>Kn-9;KgZ6m->@vttLEPgy11RU6syI7EVdOeSHrIitln#8}e;%EtYq~eSxJfNFTga>?3~V_G+s1IDM{48%l+UPW9&K zya2Ocep#yYxSQ$IB#=D111V|~F?q}Mc4{R9&TxY1L0n3bIGHK70POCDyTTCUa5ax0 z3~+~i46F$kJ(q)fiLY=SIJoORir)!EfBQnjBBdA`^7?IPoZDJvmc%NMcvqXCV6;k% zF1z?VE`fAM);`zAY*;Cdr-7*IwO7k8pe@Y71@uQBcdZB8|XYqxS3Th%qHWgKf$rJhObT=wRh;rZ94 z{&DNlI$%|7$OWhAbeO;?hQ|Uvq4$@cBxH`w4|RVkHVa<+F+`fPn%WpugX8Wtff?00 zO4p-dY;s>ur$%+?%4|Fdl)YY2DS_x& z75V54QP%x7C<0kFIEaqxy>W19Nm@>EI@S0(nBX@V4Ja4W>;==QB>H0{rclJ&M3coQ zt{p!;cU4!SF`{9hYLe2-dx6u2kx>avF-*GB+y4IiAG0>5uxPkrSYbASlr`Pa7iONy|C+ES8wvh`i~7-)>C>AkCspKA z#?*jw_R zor`8x9}8D;Zib%9Tis9W2bQhR(kM6uwaQzuo&AV3_-XJG z7#Gex0jvb|Oc6d1qxK7w0ziHSWWWWaUZ*+~sqY&Lb7oFyx+X_n0yiyze1c@4^?XWNwp{ zh(Khl_{GFG|I*40ZYyXVj_gLC?cE(#uEhcyg%+K9wcOu zh_LKmM%XR!?J9%E8vb2uZ-)S=A1pS9N&GhQ-j(4b@|u9m{RPpU(?b#;^pL(DQxJTm zT*<4paQ{3&OPFEf_|^D~A!nt*KMs{u^lVG`6cfWx{!2W6fg)a;e{+$ z#rTIlYZNbO+Ct0asu%?=9rwYJxM7mD0qcaO>uz9C2WWz)-mJvd*t%n@=*s122?=}q z3_?c_^I?&8DR=zs%Q4|Ea+HBua& zEfiy4o`5BYGW}e@*d>`z5?K5YTL12;RW)W=h2YL~V5Kfa9 ziCSNiDg+cZxEXfuvB7$m`)?AlfT>OqtG7K!}cS}lCYA{)%ddmu7MFBLU zRMe;K4=5Kjem2H9fy|PUW0`fgI3&` zc^tlMgFQCO5XEr3H8Tr|z1YkGxRF3qN(xrrFj@am%m36U-}hqSD%I|u;a9*2?($%7 zgb;=F8 zts(mVStZh~2O~EizxUYSy&4nQA?`4>^|(OSV{Cl@0Xt@52JpztuoFu`fWA?jSju_r~`(P`RPd!2;&bv<)|*V5c-)pK53{ zh{qscE|IN$(P^05gGx(T<##Kq{AW&OvS#nN&&F1oCsJKtO`PsC zef#EP=JN1M8F@I};tk}H%)gUN5YY?SjYUu}VvrceZE^!7B;1@L1Qr`rH9)Jr7G#zS z_Z#rj>YX*1!+G=Y4_*IGj_kyn=6Ds))kUm|8F&HjJ2zZhQw|tjd>-553+TA~)H91a0kuE&tJrTi%QC?FFeh?)bJj$mveO|TY znLS`7qlKS4U_kf7(WYwIQ~_znvH_>!t)4HjVEFt8z3>HO94meT7p;&8OeE4Up^zCGkU&g(hUl3k(V=oIz&Lg|-E zCsDOK{Bi$>S{eIybVgKGNPIe+pZ}49u;ThNqd^3Gs{*Sp%Ds0SGoD=u;8ZnZd*?l} zT+HiK`oARg zW6$<7wgmv@oa|DAVm|yYAn56qpldR~0Ku{xhKe}7OzROlTyhRfgx@YTo;0dZEZE6p z=(pysF~r*){~KQc2myUWy;1T13_W4merC87rilaJNva~uE~~Y4WWOzwU$2qS#<@fL zDjc0pkzA_J_I!Ox01Y^lc&D9-VYt?4s9szsw|5if6-P39cA|Xij2%a$#e!JJdh&%Z zY{j_n@rp41HZ@IbcF{;ch-5gxc1IR6GlQm>(p)#Fl1KD1f{%0#(0zB=#k?Q2So*fA zp9fc?%t+!cM+4NDK%Zi7{8CDw`gz(FKlU&0*9eT_e+!~S3M_Ko@PM9SH0GjYBfmSE zI!cPBKYPgIE^jX%!Q|!tD(_~fpwv>Yamv$^#fR#t0T7`F<#jo5Go9EUehrzFQpGi< z3s01N9G_18_Re3gd4V&$so3`tOk3kT@x}p_!X`4-BlC9!X3@APmld(Nm~?9#C~{1= zw2fhtt4H1nV)JL+T;Jw6VvVA13uDTVN-J3rcB+W{KRCwk4R#X+jyViWlU%3IV_(!s1Zu4fXxx8#-2ug&DF3bIp3ZM>IOf^J1RD08#N}2G6 zM-{QgJAn1ee$B+W9H^avbGdQuJ9t$r{ZtHs_)(7s7L26l8J5jY&qj7nSAHP2L`+?- z!?Qm*9;0BrnbcYSd}}6k6dq8YcsMdSlFp#5JXghkxL|G3r;Hl5rL+E;47wnd9xW9* zssoZcp%m0!D=bxgYb)m17?xw1XKXtap6CuA>Mppdo&`P`d1$FtkkHw>uE); zhzraR%Ztk+#MYgmZmk)es3cp-W=F5wgcttA&zo~vu$4M@`?e*?&u==|3-W?t6{&{T zB5|K1rUH0M2b7mm?KUo4D#7q<<$tkyj>G7IBi^Na8&jWLO+O0}-N7R~-Oc(ztSc64 zR+}p!y&%=>Nm+s0O2ta4id9I_MgDGxsoBRNF1xXZ;IF>?8I5d_EKP176!GQ=d6#EA zl`SqynK`&;@##So;)?Y0X;_N#2qyN{L7VT0ZR*32%=cK}*1RPw;r-cXyPPh$Wc+E+M*}zNJ7^x*A(_|4F7pcv-uaX~kzDQwM4+SOrL&R! zqgh7`^ogcgkP4*b3r|@^*^#UKP<4VdW(Ce#9sG7$Pv9$pkUd_}h|UkaO|;dAeN7el z9|xL*$g`l~f?&Q2d4s2kI(WeERc7w0v>0P(2g~8V<$jzgy|udXqxzv0THSx>VRMfo ztu^f)Qm&YdKHDX6H_P+e7^Ws~)h{DfDAJ&BfmESL6Kx9p-8&@Xq;d(+q#noDg)Qj# zet@}O^^D*gc;~tZX!vPd%&ed4J0J~gv#W{R)~G$5>0e?#t>ZyxoHau$sXFvt#Gy}CMdOE}UJ1|d_f&pctb=1V61*dF4 z?Sv0Ea=V+`w$@orZLbZg1p`6IJv)Yf%KnP=3(p+Pxoj5z%k3$!o4xZf>U?>6D?>kE z+y@Ctb1u`gy;!rvCuEzt(_Q`Y@7T4uB z2;fY|i?v$-L8ck*r_*GvCI~Z%7L~@n>b7$xEQkE?2Rg* zr=xhzIo!8laG0~9O=sLshJ3&)obxn5Gt&{6}l=MEIrM3 zEEwXW@%;;dJ0P)=^>(gtW&;H=IBScKVZ*27-}r$X*u7w=|A@u0s`(&hZQ0C0KWL$l zMpz`>g+|XVw^ZvMa5yOk%zwhjpvZOvB-!Vz0-u0b$+oY|d%k4ZzaO;>cQeH4N|(Lq zy87<6^3p0wG!1kNhe-=Jv=f@rw-AKG=ZtNv8!6wbI|9_nKY-7rf%koLl)WCX1$||p zsQQgrx*qA1vd0<|JORH0EGS)3~j|y^^=g1{QDcAg9wa`j5pIPykoS7f&3LUucJlD@6!W=Qmv?Mg;Q%1+w6%~-dc*+E^R z%1>zdKaloPNt0I>A8;;J;Pxqn>Mx#1>aCNIC&&K3fs9&{xxawk%^jbAxrZ{{eB#_v z{%b_Li*QJd&qTUgS zgAdkxOx5(BXHLCpE^FJx=d^rMEJu2fW6L>-4n?`lWIt&Qa_HbK5P0MElMsjI1i@4( zE6dxXY74rwj&{b=&U5MbZ!$N%;C8N)OB?{D|Eb2<%XEQBbXSmNYWwPtYc(0ElkLpq z^eQDKIx9Z_e?`>xcxI1c5NND4`+69D-yZ`aq}QjuKCeBt%{*my{a3GVBF}E5rtwIW z$#0TNUAdN z$VZ-FBn+ML&b-bG!M$=BUqfa*b4% zkoIAH|GnKS{o413U$4kjz?6Tm@Sf!Uz2t7*VN-;-aXK#?piQjPvrwXZ;%WRb@K2`5 z)hmLp3CS#>#idOkL@e<8*$1`*w*sj1{HI-Sjci0H_9!cxN&hZ|-yYl_=Hf#zDC8Ti zxDq-SO;bKH+Q!s;U-I&RY0*taq_9u%kZ}sj5G6ziS`%w!x3n`@tRZevehR?tQbA8{6r6TF#ZO1OBPCw z-I1f3APd9;fHS*hiGxqy;}TxET!{YE;=CYrQ6E}1Oh5G#{Fmu@a1eGa<4~giyDBR( za|~&v7=5FpeZJ~oa(=bUcYjOYd8e?3DA%#WRpWIskK0JJGWco`11klig}~O?h>Z&~ zPf@qE5Mf3T(?eL;*G%y-y?msG#16b*f3~S1V9_Ulp!`LNEaMUJ)I%%(yKBlU)-S z3uM4^x9Fr`VET)#ijS>5+%tSOZlz!+7zZqt0fNW~PRhdnGyDe%wcmsDqmVuxN+d-+ zAFZ=rSV`Sch#t)Zz+LmoBS!K`~;4nCxDaZmJEI;^3iF!fd|hPGjjE^qO5$c|xo z!S28`z|IujKRwf_I;c9)?&`BwzM`p6cOT**k4`ZIoTqxvJ2Vpqjmb2sMJ_=;1=T4r_;R;*Ltlxj3PC zTG`l_z^7GJB#tPz{U!peMd#KjeQ{vtPWWwfLnx_*qhhh{(Nuuql6N@v%52jVZ_gAO z`nd+1&c6kVcYzwz`Z-AobU{i0GX=0-N7JC}nu4|;7V1m<9QqPG<7m0q+&yP)@`l_n zJPi0P3_ChS1C9|l?H8>i;ojm&!(SUxxJaXDRP%1t0dbri)Zv^s}Baa*>7`N zNfk(~u7-m4$aV>y@QRu0JNTb!*divYpYupShR2?(<|7EY;k|R!!YLEKKbsdlDH4WA zozakv@!1*Q=13}=<-iYbnq}8ZuPH^FDRp}V>Y3?p2=;CW@!)QmN^JTFsV2n}RJj{^ zWHaiev7#QMPz?9=NH|g_JiT<9I*qXfaW{$gU8@uogKg$_@aS=}H)Ou78ArJ$4#rwh z1P7QdCB}y%cd$>QSKHUV*NbE5ohjgiR`BzxnnenAgn2S zgm#mJguC}QzFFC!b{ZZw6sVBPMhY_H*1&f$giv<6n0N;hIsrQw;LM>pI&wsTUnHj?G4hX=7Esf-qf zogNRMm;>?<5R*=y&YZx!pdm9w#9CfTrk78!STbsMz;~!_zkSjaz8;f1qcYyqhdKj{ zssSzAI5JVpWP6V-(9Q5FGAa`L5xvqFud!G>V{GZ;ffO=UlF+^fuzEvt4-CrXva6FF zDG~gEJwRTEnayuUp-^T(v$IhQwe0PXOr2AH9;kh>6z$UB2JzFskH$CTozu|+b(%I8 zM`yo#rbW`e(N@|L*l)R0GQaI8N*m1Jkx6 zIZfX291Q$!LfVuBF!{P2t`YVO(bpK$mHF&iH45QR+y-UN5>%zpcxS2tJQL=RD_K@m zAYEcArvOy*6@+#y#?FFR!8D~UQvn|~R2AhoL>4L<2_?ys3taePoAjnOM90dy=d!w0 zF0^8LW0Zh=V;2wjHiDTb>xX;Q>FBp%kr|8d@+ta!YcnclusBa?6*{(xw0_NN`^-#M z{_>EzrH&G8p-Xw@t-<~I4n2vJaI22I1PE(z09+MO3M;H6b^R6hy0)oOMKBo9np!-` zrC%&$c_YYE^OX#rzc;?0C^TBk8e1NLQWshLPK@ZM|9BnS0i!PT_CJTB4R zD%HWO&st*2lqC@38xPvbfjoE93N5TiQr9x?Bo2Ma&@Kvmo>-=R^!(fLn`p4pA}g`C zjT5m%yM}uYeUcWmNneC0Q~82ldJR|_Ercjkg|6|ta3HjLm$R~Uz<(yXtP1pwm}>2L zx2EuBfMs%a{!X$Z*NoRz(USHB%Fni7#47VA7{^DHMR2d!_l|T!1NtEWBPbLYR8K9-IBFO*dlb6iseduL zYWbQ9G9H+N6dGXJ8jtddB_Vs`0Cca-B23@n6sNpo?B+U%eyH`>R`s}sbA?+#(o`<6 z5mr$RZDZL54}?#h4k1kiZC3& z1p6|3)qC}b_G71%=ZNqgNN*C5k=>AlO8Xt-+!yv#R}9Aig$TCJLZ~-#o2+-#S1q8P z+;-j*P%r-VTX2oq%v4*2@8mG)bZm2~;;(&X{&I#>RQ8P=v}h%$(aAZLhoj|}9y7Kv z^mZlHEjwG1`+DZpCDzwk+42(_eNX0-SOScXgHzmf#xG5aHoF&>?5tRRb%QgwetP-@ zF9D?~*92+PH$%y>Zbz{WBQb^rNGyvyk`H!o-mW~ z)d<*l7f<3Yj0g2NY!DZXFRxfoyXZvrWIn-}{lqc)U4$wQix*3D4@XHkVz@R~;wC&^vim0dIhNBq@Ed0Y5k?le( z5@sp`yoU2EU%154PD!OojGK?2p4+F>5Y3rPi9SZ$6F~`n+|_X7Pvw~@dsS%-r(s0M zf}L^G07oQfjVE_CUQM7byxQhMH-k!7X1_!(f|blPS?TSfv)8wGV^1Y6cmnM$0uAU+DF5uEEZ1{2K8oQbmX|S1*n%CZb)+eaTrQ02A_iS5W6n9rmZN+#Ors z4^ZV}OWPS-|JAL(9{SU_+tX!@X!Tj@aY{D_o9KlMF7Ql%ED?q3gDzZh&@|s8{}e5j zND_&Cgin6q{`VAHY8=&B)EWXssGAee8;gtMw{Ofvc2wx^qbRRd;5RgDab+3l2u&%G z#HCs=tO?evJc|2!-YE!@qB){LtfisJzA>W&-gLm$wYtXE<*(90EQv1p&nr(zza&Mz z!msO5Rpl4az8Dteb1vVCoV*=H%E+hvU2P58hpUt^G|YaA74YrT2m6eD(EF+yB4jDd zk_rM+)7{0nB3Iw$TpOaI~uG1@f??g&vKw_XlNH+A0A~fFXg!MIR7` z3$*uU1=$U<?f$*p$}gyv?@r1%UC_ecmR zo*d)#WBbA_*wwMG^EX)~;?3YR#0@$!ptDLpXVEAHoGdFiNq^&G0q4>mAMwh1>lb+Z z=tdFl7OdpCFXWnsdvS?3>NM#N%^Hj+q%bkhV^WPm+$z1daPhIa7<8@d`v$-B`o+9s zNc2sT=292c21*vgV*!SbSDu)zLbM&w-+yE29S!LG!?Je;uCdd03_14TigaYZ6m>78?Vn+yOgRz{5&WDO| z0P^cyz3IP04XxR#by$h0x!}jSCTgobmNJCtOD%ZbWCf;U2Q6V_!=kBdq-AC+FJnV>5*1 zRtM5((rt>?Ra}bSk)pH0(??vBuofYmtQHq~qE{siLMB_GSD|>ytgc-hHL3zDY}jue zQu>&l%Yev^Z#!d4Sct3GcGXO^neOh2)ql#9KfI{|Z_0LAo(MGbF6JIh4KN)ES@`-Y zILUKLYBG<#o__vV5&YY!Q&{usQ$M&#{{3EPewteuNpCbk_l`#yx0}+hScnP~#Yw%+ z1xx=eiz7MMf|6?TVNI{&bopIp4t|)ef{&}8ErM?Nb22$?%U2QiqCQG+`$+bsaYqwN zn@AM(h2|ioJh+ZN(p+AXwa*N(3^?aaj(!3l?x58j!Gd1v=UYy8$12_NN$dz4Gg?ydh#ER;6C+7io6@UGW~*ol zN$37-6eNHX=k?OtIKIi~z4|PtqfjfUiJwaFvsb45I%Uo2uQF{ES)A|qnC2=ZR`1Y4 ze4pTWC>GM+PL(%%p9>URl9Vj@>fCJcIZU_Vi0cn6)}@*&?TR$d0JiM$k*=m6^*FSV zh4$f=T~z^VT(xvfLl?Zn)Eh*daKp>j?6l%t4lQev8ireiaG^8$VNK}B-y#&?U^89U z&O)UentZL9&0=n~H2>%+3~Zj66N;~7`~mD*%lx*N<<&}mo=as}=j20N-hknU4#05} z52mHf_its#`g!o1f3c)qBiQ9VwYZ=`gAaatrmXbHn0SuhOz7m35}m$Iw;nbXd4HT# zE~2tV|9J1zIKe8}lEs@)QM(-Iv^zxL=Ris_knJalBl0x)!oy%}aNne-;=(`_tbEBJ=UX1P_Q1FkooQFL;j4{FLcsWWDHm5&mNX0)gK&> zJB>+KzPQ~H1gw5`7oOT1(XiYlw-u00g*mUv(dHprs+MbL;%B!fTv9A@5|S#9k4w$QRTubK85nJS zxF-rRMw8XJI7`88@KznMME-k+$o;I+?ylomQhfSw=zH0>qqACtxx*oKABV#Kefrfl zILkj)?3x~p*I!?7=hUFVyXa!xmC5n}gsLDJI(o}Og%e@~$At?J=&2H}@UEt)r!gw! zH*5tf6~8`f8WAyZ1Hp8}#oc-8ZM@mZ_qy+QJMTmEZ(;)i$D&!+bY%@pY_!+&XEJyl$CWK~-d+R+^K$g1Q%Rh>rF=5jrf?-IO-jb^`ccEXJ!A)Rjl zQgr*2e*ZfO4$M8{kj(5?;D?sz(Z7R+ybei@LOa%lge* zm=8qrHnJoe##YRoEB(6&!*?EO3x@x{0N@=lIsgj?-4pmXG1ntNMz)~cQV6-3E|ydJ z{TeS0f3l6Y70M~1lun=z=pRe|`-I0Ly-Q_zXl9LzGcuI|(6JR))h}=^=Z<$^+qh+= zN^Z9u=2Ebo-V%3Rz1GqEQ0bV<>#*+R>61%gM3bBVJSw**YiJs#i+O0B{58n=g*{x* z(9KLtLligbkTRwcq2Kbg0J_K;LG-F$4Ci z4bqEJ*TGjEjA#4dXg*F)9KvM*YsskpeZF9y+yVZXYa<5N$JgH3w&eh2M1?_nBl4$a zm11RTl=Sw=kw(b?hcauzT`g+^@KVy_$r}4*=hGgW);g_b>{1`ii0CMme%MKM>@q_@ zx2G9G>}tFbIsQGi>?lGBOSwjylMBIL!7k#m4KI@ry_|o$_7ENZCN;uV#*T2{ z{+$EN&E8AA&_70P9gC9&aM--<&JK34|Jz4b>LfSMl$ z8(ESGw)_Da^$LHK?5q^iZu8`%KL+#7^dHrMyS^b~@r2P|+vkOf5UGm7X#icE54SN4JomvAVi=Sq?YXfVnmmuCrz>g*P?^(aE zu8V5AQIJ=oj9<6<2dv%vZL9-g9WI?;YW^iLVOX(yvJ8*``U{uE<|4I02q@RapPLI4OztH`QRoB<5v zTeqF$@?wT78(S0lgoj(CQa($LL^Z4)`I{NCGpoU-YQeTtUo6 zqRHfra%GGQJ<{?X}uOFkx%G7`sv= zz#vk`rSbW1(=7LdIhyLcX=G!16((5 zGqn19B9-eU64z8V$8THWN#LQ#bk74_*>)P1@X&DzLw|?{1@q#u(Vo}|_MZJK0 zSINe;whYy~RM^)OsdxvG7vI6e7JmYnDJX>p?Q~rBpC3FCS8?&F^tPQa@m+Jc%9A{j zBX(#Hhc~9^8w2s5qMS8ZAc)0m=u!M_16zGQ`k`q@I=i8M*JeL)e?IL0&&Bxg+sPoyE)t@%7j|tiICFnKwsuE{} zFlJ}N5wYTIDdLf>p0Y-qXV8rGYJN$p_EP_$S&y?K=Dc^dvdxRg{HY9(mm5W_^dT5ZGb}s0mkccSZNbOj zLcNOPZakj>+@W@ z=oCk9(m7p%`{L`4T{I;q>{b6JuZznE=?nas3S(I+i*#5zKt3W`B6dRqDsEJlSnTkh z2|%c5GMcE-x#i1#IkW4iPc=5e4Qq$x@q@@WQNeUzxZ@ zc+n43@gQcRhwa&zJKX^JQB_HwZ1gkHR5b_;T`9-5D1MBxX8+omU$~nZ;O@5S#)|{t z$7{}+U!*?mC#ht%(W8f&D{5{zH&sOEEb-_Pz@C^-H6h?(y)m>YgDM*$67;hPhVmAM~)34Me3zr>MN z_Yr^Yg=dMLPtE;fM;sGJ(5}#WCwHBD3&B$BI;_}}u15i`>C1q%LLMFHU{a_oA#Dlo zsGPtxqzp}0BCYCjdSe5S^Nal`n5m5yHPW&oR7HqSa2H#~=6-DlglGq1jV@9FqqT#} z_Kr|DIj7oF6Z}+RIx-DM!JuaFA;UGbY7s?$I;so(fXmiQ#DlSlSx|UVY|y!P#3};w zP$T=~P1hbk`zT#t@Ji3@3KF@=X(M8Y4@|$*c(zOPv(M>#q) z39?vkl-5f|`Aj03xV+5Qu7AH>Y-f6Cg%UHN!1w9??Drw9sZPP~AMy^`>&{rtD8s@8 znTnO+4Q#us9m2Yy_vOprCJMuXEsNK@1D8VHTUgV$J?*>PgYW9JTuo)4D^}>~ccl=E zg|fK4k53{;7G77f;zli8`0)DvnB^Cf{lpwR!4i)tc)h0w|2fbgoLrS~2+vlB2oAK` ztWLE&cb%TQ-6(fwHoXq>TyYDhUY~wApmjpe-0qo`{zK~WAlAF&i;)w$+swx%3>3po zHsr~2Qt@?QroN!S_`6@UX!;s=_X{)cENmLwj;5Fl<+@P6$mGk-p*0rOuJ$3v zumY&m_$>HH|GAF51Y97#;aLgHd9G`NbG#X#n*M&^?L9!oASp9Xn-vt=rNjs#?J)|Z=W~;rS+(n04paJ(+w&uLeqpc~PJk zR&+kM1t7=<}F|fjI!Yl7r4DNImrL4MH;i-9L971 zrvPW@;a^eIcbN&FSiV5r=>KM&yE-ac!FQUhrpNco}rz7U(`nzqvBU+rD)CLB|#dMhU2XT zIX=Vnn#?$}zK}Rq7=um7WpPzg`^`$_oY(cXn|JkGtlwmgP^|)szRmmlU%|5&8tFjYy@2>%{XC zT^EE0;L_95ux&Sp^oNWavgP01x4QgyZE^qNwOi=(k_;}slajt>bo$x8G07TcPp$`y z&3X&W|H`n^Vc=Gw+z3t;3OIMIq>C7Ag}~cS9hyeS@oYYN1d@enfNh%EtXva#C>&pA*YWvzkiNn;}UqY#-I%>t=A5_^y zJ~u|};$qdTXu6)Y)^;5OKO2K;MSSYWP2Rs%DHUmhB&lv~h@<`-ylc`Mv?NcyP@_>+ zru##L6R^z4S&N^4iWr(Pzx`ewL6la=9^zyL#o^@}5y+Z=Ckt7_|8z@xT(B4RPEk2x zq}?$>8dhKzHOP;tDeS*eS8+0$w{3r7J`1>mK?#=E0wb;GvcYQv5+=t;>KaF>JtEaq zPkm==nu2RZxa8${rJ%+3)ma+6T1uF!);<-T)!#M^Dh&4AKd|MAD1Fuo!a!se|=nU(COyIE7fK+td z!B&D&_pt?+Q<%#*M!jTXV+@#9#s$e7S~Iy%QefF(#~l56?Fs)q#Kx2C^t4Ojza&c) zj+ApeR%a9O1B3X+Xm z(K`)UzK>PCa-#lNyttn4VM|*u$d$i77B`t1?_(CM)YED&bE=jM=ehOiKn6>f&efr& zNQ?~~8f+%*^mk$zF#w|bo#_gz14Q+H=CTSirn4;BdkOP9_9ZhlR@czye^z_j;n%=& ziYMP$vbW0Y@io(B-S^+X9mxnAF+kL?bJgG_IJlaOkC2n{9LeQ%$){brXV=h^O667FXM$-bv&wO1-~T~74<9N=+hDht+Vc; zzIi^9DuJ9evCTI&89JH+dJ+DN$St;y z8P()81$MFI()UR!{Tu=D>20dKo<4ZCt-e1}K{kXi%qG>9On(?OpADbvFOa%O0TD# z_kPV?xV!7LDeQ9c7WCf6b<}*P)a(mw>k+Je2xUUBbA^;Y?j2Xvsk}$Lt?K0x7lz`5 zmV}29c3Ict%(v)Uq;+qzm1-d0%;oo&l-){pVm#q!6uxdNbZkLOPCQUOIG6t{a|RR- znS%9f?JwD=eGQLw21oc>K&~UQQRT(8^obq|pm(34HLSeCvKhA5pm7LmZGVKu-7!r- z!}xXiaG{l|?G*}GY|KDWm2G*<67FT5>O3LbQm{2!_?hK9%%TAF{3yP(e}9~ep(pnn z(0QTh|F~x?4q*DA#{vM)Y&%#B+u?4=U%aY+_G!tC>#vgJRNO-%8%G(P&a5o&h~RAA z(IEWkD(;Owm8xWE4y>tpIS@J)kqtw^K$KqvCOa0IZpN9c@yZ;o+H>o8>v9`>Hq=R z_MWG7?Sq-@=oRFTEnobuZ$CUvI}9(9HW>*MlXgG5P)01DD7znwwYv6 z_)9PLbD7BHRgJL6y-$-U?oe#Cb>8~_BJY#5l`{ShQcy2*eERbkC;mxQ8;oT+f_yTe zH3yvg&Jjf3fV^t~>q$K7f%L#@5qI})b!I5o98f;>otD7Guy&$^Vgrih*MzWc9uM^R z^E{>nU?~2ECJ5ic{9`jjqmgLQkv>RtME)8}5U-A$eX04bSs25?Cortk8YJ%!@R#zz zd5pKje-3{8*9qK}AI>G_Xbinq>eg$#9Ny*P+*{#p)03cvnZ32oH`y4vJ!HOTqJ zsnF(ysCw<%p2_Qsk_sc?xOWTUeFL|GXZ~I8u?H1rZcc?(kqCkkIM^@<0@@~9x3eVO z2MqpDOaVRY|o=+omQe!HLL|G`qn0K<+`W}Ik#T?E`w&cFsX8_am%bqePg`t zYDExRuaDWUsXxT>#ge8a`gszvg5yvB zk~B<_47m|;>J5zM2heXaGY@Vrq(BpS3Oq&^(J+ANmHmn$$j{}$LagxsAmVO=T0spXGw#3@?rrs)9s17GPNYhux?L<*Q((HRrO-7nvm$MQ%^P#2-gov(L`$^wIv@LxcXZIlmp}76E9c{o$ zW_di(X`|bYZ#iBIFviX%gBMJ4kA3>f-j7KN>97|FTtR|rQ8P|^hY&C5R$MgKuQNKI0(8;uNEteYqUfEmT{8&w@91v)7KXH zr365P0|VU$ALO2aWb@MQ@VHxGKm7$HoeKU+^8payT)7Zq^~t(RLMK-sJtns%Dm#MB zdtGLo>K^$4=~lo>3V?mG9z@%96YjjgN`M_E{5Ps!?sW+)`SP#y}#N$ z!bDNv4pg;rkW_-h@L9d}ORo^2ke^V_hiV1u#%Yb)KHn;~qzvXfHntB#0zvl;YTdbh zjs_MRYS|PV956TGae^f#Y6AAgqSbDJg9c7BMur(Fg%dKVFAoH%B^)z5HXjyCSX8f~ zj%dqBw*ucoMf?=r^Ezv7vckj8Jd}P_)Ad$I8_z77>iblx070~bn_)iAWzS@XhAx4s zZm!RzI~W?K-v~0c`G;QwxGdyG@`V4;YLV&71th2Kj<2!-!`Nw1&0dV8rm%wyonM%e{&2T!Hu|bE zs6GmbBSH>L>?6dg`h)`_YN%|I4#!PHNa@!^wMR@AaWLfP>D_kTU>|{RM0x3TuM#{h z#m>^eDf*RjO%e&fXp=y~NMo^qylYW%NF?Yp908opBBa0xd8y$KqzpAn0jH&EIR}B* zC@~Nh;-4vmO??q_BHTZ`pzmZFR_iu4h0f1*iRJdkavmDbptP|b!?fV>fZ$Mx`^7Uo zg*w=Wn#8dopAI(o*8lxBW%6ngdJi!@WxO)#d!gQSr*7_ zxP?=407dHG!GOLdJvi;5Zw&>mM~`@Urq7hf)EhyVSuR^Ak*}028TXlnIE5({XX!|F z7>4o`VUTv2NGgGW2N*9+P|)W26SB|`)iFIbj-el2ep%UwL%rZ=8U}+bu(W>?lmG}0 zAv5_7Q5bWd!kv(X#LVOh9}AhK$gzuIcj_8;ee!L$wv@Q#E;Lukt}*2I*#UccJO5pZ zoFBf_0jEPP@!lxdUa@H%UsrM-h1zJ4uOu!5CzB~*v)J_KB`&y=eqOHJ_5T8DYHynx z3n0!Ap_Ql1fX+81<0HuhZ-)7e=XeTd9285l@fU0h4rR$UA@3?#!W~s={ zCzGZ&ECP$HXmNf0Nb%Z5L~efi0P?!d;G`G-X#le~rxGmoU%`Wf5R2se;1(5;SH*P2 zG_9|Ov+bqn6E~x=EW^+8SVdDaBVKyt@zT5vpGVGd&OX^{sJf)BPHOkxA5!Y-d5Q4M z-4Nr5a$bfpXuYg_n ztksVdDS#*7cu9HCD(N{CEKKK-N#HCe7~Z2$@qCKqx|QWs85noVj>pK=6v< z?&`AY_5JR>gkYAlR)rDNq)5-=bgx#uWFN)Jd0h&8*YDe0ba3mKg!c9)2V|Nz8p`5! zR)CQ9GGp-G=9iP&2u6;t2ZMRU__aDF&S1B?0nkb~_S5G0F(gqFlz@gw(?`eD#N^4s zAvfme3 z<4&&$JHdPY=L%t(k0m+IUEw7UQ^lx34qMxM2+%@=10X6l)7zT+7tQrW%(eNvIG4N5 zj2bN~aG0c4OBK899K;`Yqih7_fV{`)G)Ubzu+4zhkq%aVVsm!!07t9h-SI~&XJeGP zqXXOsJov6?zh=F>^ueSsW#31f6^TU1-&4z^xm3|$suVVOn~}Ia?3jGi+UfnzP({8d+O&pxZ~tve{v+Ij-_Jin6<0{(d;nFxvjrQ z^z(nuW|X;lYGpvyeM;Xz`_~(P$Y9O}6r*;54CG}@&{p^hX+Za!)h6^cSs|3e15m`L z19nKXIU~a8=1iWoIB*e<{piS%-@6)e39_i#Lw31+u6325?Yrj;_#6=>^u|2TwvCx7 zvqz1aZT76@GU04Y>V&nVPJ0V19rBx4aGy+%IFwIC8UOwl4glD_wP9R93L=a8a zl<mJiKtsh8IxBkEULki#3{ExCS4%jGvGW6evgZ$?9x@RS#`)M?Sp z5t_gT$R1fguP*RY4|6Q-P4$6+mtX7!=r7mu|6K{XiZ5E#2eZ^eY1s-!w{4t|afgr;t84dg z^tYJLo8RD;%~?Q6+I|J@tTG~@#Z!V+>LwLPWEZ)P6mqd+0li6RQ;502^y4o1j4OU& zJ6@NUH`U734Esa`U>-Xp8u(j$(I&8gO%FSMG>g2874$UbRXrr(Yf3oF%=x3E8ZA69 zIS#?sfC(x47>~sxi#S@ZN$R*EF{Ble^*n|8g}k|SY3=lTJ%iF_%ZwI7d$S##aK$?h zm6lVbrVT6sh~!CQkM>WttSGXPu8?!5SHjXol|07MH*0^_45Zll94i?oc0kqN?ef9X zl2c5Jhp^GH2`6Mlpuc*{HX@buEpbbr7hOqIJ<{>7Ws&SU6`P(L`N1iuCo58ah?CVn zLZehzbErglv*hG!VshMu1GSQ7H7M{xM-6eG-Dj3T?syN6%MVf5pKQ<#SH76>zK_hq$6}t9 zn@<=tJo)<-Sea_%WSu17#d6Ec!b%rpV2KjTsOAV#fbvTS{Qg(DZ~LC|r)#E*t}5)o z!Sf#^r|q1SBF$13&DH&q#`pF06x%C`IWZvJ{;N=?D+yCD77Z9%;Xxo#@861$JZ6+z z7KPeyp3ZISE>S=8!mdX(Fobn$#BBCOpl5Ng*8Gb=|zb+0e;L$*CHH)#}piLJ%dctjC1iH z2IO2`cgwM&z$!qGJxjX`4ZZaGy5`|*o~o-a3y*8x6F)WVCL%d4@ z&0O5De541QWPX=M48JoYJyF`UZPP+dQay{jlRtK(ez^t-mM=7tI~?$qlEiMq+H(W< zqru@TgWAj)hEg+(hh3g`(g820N$J&%>)_wTiAjsBKMk9lV_SJvG^FL4mK#UG6Z!6A zub^xOJ)HaC7k7+?iVZu0#63yR%7J6YMT#Y8&lzP@>$AwD*5NRk@#kmtC(5NW|x+J)|(e zeuw!}hbtPv9wixaTtRB|FmPQ0o0^^mKIf?EynS4mudIK*q$?!(CVL9}8O^`@U^#rB zc9(?gZ>%(wb&!d{;x&qo=`5OI9|Z^eDM|@2pYNWA?^tN3riL=xnA@I5%iJWC^7rv~ zY!iun@`COZd;A0Pu3(=F%fI4cwO!K@E;xDQT;Mxp$v@vju#D!`P@c3zLe37*7`TqP z&Fn7(GPL1l2n=w4CGE4T3ew`H$;NdtGy8hXHp^;x5vU{ak&p+;2*hCV8*5=0;h};_ z31;-&p}7=!k_1gW5wgie8ZaTk=;Xe1?b?lxJOg7e0AtK{oY7c44tj9JO+{X;TUHoL z`v64)Y_ix=Tu8By2X>vE`yElgxHt;$W&_%nMiIe2a+fSzN`8`UZQ9@Hv|$TnZEs52 zvFOqsMmf`bBg*MY;1H`s^|}H(1}-c2|6Jy6l-u+Rke3kA8Qzex3{o&OAB{*ptX;&} zcO+-pK&QbjC4z~wy=r}xP&EUTd<-HD_Q^xjZ`#^SD+7s#KWS`T*)VFX1*)xqjlxqY zD&|H;>C0QwF;Av8!0{F4^T7!gN4TX5!G<1{tJfp$Jp)AFaDtdO!pw#!)kHJC1Ckw$ zKGJ`WT3hnTzZLv^SWYC;sD;*z(*fI<`&M@nRl;H`_i5k~4T_jp28j%S3^T`W>)T!Y zIH|k#3!_K+eLLpsfPcVo=wp2aAP$X?n)vRlbSETK3Qc@Hg&Guro;jtbDvo_p-G7WA zqI^I|=qyN}$WMgaooV(mDK6(25)X!?;bWvxMoau6kPLl3u+`}>U2_AJO9!a+r16<8 zm5XlFqULfJ_ZiJNp`+3S<=@TcB+=?`JYdQYy^!kYE!T#lGBeop7?^kkAqE<9_vz02 zuNyRK1K#rE>LV`Nmp~9~9z;mFbNJLCjo_mpQ{cUHPSA+1(xXrJ&67PD0Y>f=XR%Bm z>pFF)$dIh~Qv}Cqd3;}nL^_L-)E2d7Tji#pU{j3??~tE|502qj|H2z(Css0-DE-;n ziQ>T%&4JtaKtkM{Du9NWZXZ!2=Oc0=;Oz*)>ggQz_MwwwW7Y#aq;Pfd@kh$r!B`Fu zHCH}XQ=ZlCuKPW3qnHQiLCn6i-lNE^K8ptW7(L%=Iz~Imj@ngV>q-#ja2AK$5 zAtAud`dZq|p4;B%vgptkd6&2s$TRLu{4oEBFU9^AWrB~dN#_3qd3y|~F)#T&w4-B; zNT&Zq$dy!xBf6vJ0^ebX{Fsp&-`|l2iR~men(p&=EgBDbUoVE1irDAwzdXnOe?8Kv` zuCYK5cFIB)_s)@`|AIqk>HtmDQ}Vt6O{(SB{#q4s3F8G-niS*2V1m+EuTMJGEAIC^=0o5n zTc5VmWF!(k5@=ior4+lSsm!~e&C&pm4raWe`-_;155OhHDz4+SOuxDFOfBWE#4&b5 zQ+ogQ7#dzf2D0Jw(L+%Mlq#p87>yKr#!~2ZKhxXFsN5M=|EJmoiG=RF`@*~~ynF2F` zQPt#vdcxCE)o@QDg&DP-q(`~m%w88u3kE!r+W{R5TX6Gk47DwNyMb{-9I21!Rt_Ui zrH;yLJG1_$;*uzpDKZ z^}ouOyKJNMU{iY*f%o&7&w)2?oFOaGT1C9L2QgrEHR3o=)&sIaiFhEOzb8MuBvgM# z0hI}XA#etFPq>wpkCJ`}2S|;98QBpG^ZGd2TI^0!bbEi2GQ|gAHs32OBwl^ND3Ytb zjQv|LGIl^tKSUSu8&~lkr)-p;+!rF9XFF=i?iVDT5FhiwK}u z?n`^cTnfKo6(ipJ7WPYcSl|~8Z;9?J{P^!LKRd`@-gvCN!8ksKgH+Q*DgMu-UVN+9}=T0TwjWX0aLNPTxQ;qrONE{6zru38r@u5y>s zw_MP$(P)(5<`#4z6AY)jNU;`&Tkh%DL!m-Ku3`<~9>5B==FmhRg!$5(DP^^fWfS2C zG_H!>rW~oT-1Mn}rD^-^iHv`ZlndT$vWJA>c|FO+p(0-~dxZGeWs2%WB=xjG344Ap z&BLVHvSg9>eQ0gNrL)u~>5-8%hM9QX9r+4!!`By83etH2!CQBZb^rg(cW-RE{HqDD z-X@<#aTU9OnI9=fn5WsM&|SJSR7w=$XX-<})U;kcw1s(6xyO(*)+ZgQ)oC`w(yZnvTwGi zZEO3rW_`hir8_#RRE$S0tRS_ina5)3-jyw7o2S-*$Fj>&f)4{@6j(ycq=UT7QToZY z{D?~^;KW`lxn)-mWcUOM(u&;xuEv&VZ_SLDc7n|FiSm6K4dWf!KnFY5-Hfn0WJFGW zP5*jGJkR4P#RmQWz)}fg#rYK|Ak+z@y3T*t^1RuOc{Tt5BXnOIqB;{P3jcKpOMe|k z&=^9f9=^8@5da`ALRe(xgCNZtOs9kq3R%t!IEJ5pvCg|Z8>@oo@FX1&vs!gTSx1To zzfy^sx%}fo6g^Scjkvh;(1!F#LFmf4aDbTj3n90;T$iGrAg*$uE{$-39_5(u4EYG_ zd1_)qLm1SUn~TwB3cM@c3J!9huJTo<3_$H6FVTZ5jo$NDf^MaW-Hgl$UM2bw51Oj{OuhX(3Ni`E(Q zgLMZcLLG8;L7UfL*Ikie#7X?Z#_QbM*d>L3O9R9W(UMGw(*iWH>($ zmz+1Yz=Y?e?_hhr%Z+4qsfewF%d;_5V5E;OL;bE1A_0N{o3v&bPIrCE^&glDas~LK zHetC(CiMDA>Z>^p6m%`9$t68mmhfVq%f8K?lY<98DqH(3wONW2+NM2EWex} zc)y0{=>d;~L5l`7%HD7N)o3JK0W1*ii?geH!y#zomQC--S6>$|gE`G~#=I`%-&?1a z+P_q>wiWLL+=cg8cU#WC8sXUVoQ}cxEhul-p{j&`BUAEqDg1$bREh5^VGykMY|-UM z*~NX<*7d=XmB`IXO!t&fQoC1<`-Jby>Ny3Bmwpvi+p_&g$|tu+O3y6ZPnCEoEqwS2RrAGG@FEj)q$Q;8%h`d&TvcaAEkBUFD-bdVqWt$ z+r6zIz*crL8^iiK$IlXcL!kr)Q{#U}$HHSL zPA*2fsW$7RlrKTk9>>56HoHd`qPFKi5$weUAy*@xt#fG^tqX5v2I5`-Q)+QxZTtyo z{(^GS#~N@*DTDaA%Ql^glYjBq)uPV`(h>LxZ3T5~{K$!L@63QXX9X3em4tbWfTI(W z_VlvGOJ)c_xsfl@(r;4#JCobkEcjUzjT$ghgA2h%LX-44Mnj2i z&`sN}jT#Pwyem$mN_w*lt}std6R0dO$=0Qp8*9PMhmG#^@re*mSq*y6!uIqxR%pXn zUSPZD@zFAtdRJA<3F3EbIMyIpf9kNPKtGSS7`rzBPf!s=OShfBnR1p51 zJMD@9SzMcU)Smgx@WQydzc#x}TWYXT8A=J0*JbmJCea6B6+YPN{Hm7Lz+u8_fye3z zWkEG<4CTg8zdBGQi+>=h{O(wyI?xZaYl}0}47S)KOr0}Z7St~mIuc@Wjj@KuE@@7G*tzOiPOLjdimks~{LzMq7?H)tG{4n{WW=DRqWkKXNgY#7hQR4xx)$OTG zlLdL&ndgv-OEE$$YlH;|Tab!8O%xa;AG}ujIvH?o)$1}a|5bT%2TeisqReQ4(4)i* zHK%*2wED*^Ayb1eNB;ftf^ufFkqCPS5xXOQYekTVD|QaSO&b+kjv^-RtbgqT6eC~g zH7#iuek@@8s_|HL^{5XC8MFrahWItM>v$&(EqQj`5T`jZZsh5N5!N!L)`!D$ z0NEB!As((E33*|`pK{Z}m-YM3MI->Z84kC6Aj+Pu)#}pnMDrOZ1rk`|j3?Wegv1eb zXR*nV{du`kf0!1#en34#$|2C2t{h5Il|DrT4>UctgOkW5+9=(q~76Wr&@3&_FKj?IU#`yM^lt%Y%i6x z-Za};qxB#p%v~*&N|WMJS~hxXq2vr-mT2|TQzt|mmMDt&8(fcRyql5Q|5H!-bN0&t=0i^3hHB2hO_0*V zMle52mD3WoCi9i2L6`g*CvS$52W8{{CzC_jL+hlFav-FLg1$E}HqhcJ#tW+|rdPMv zE(ZAQrEH|T#0Y6?Oi;xCUJ~lEw{CZAsR!R&XpxUWs zym*j6{%#v>{_Ef0g_587WsFGf{%FWZ9Xe3u*|(&0yzI_SrtlafIp<+-SFY0O&NlKWB|psOFO{n}D2|KeTj~jcGb6><7l&qA#);lB3w5C`gm| z6RwmtJ(axvZMQi1qQ5#BK8Ji1$`>VSd|`JSbtHWI#ccHJO{D@qV6N@|Q@ZNS(YrC* zxnbk1%G6AA%ip%k8WAQ9kuI}yl3bweo393T%z%H&`k)vnUZ4m~l)5SxZENb4saHFllnY1N~k%P*GthNzBnZ$EMzS+ze0M zXwAL%+{okyV9p0RnILt?NX-VS!Nk40Sq!cK#a?WbOuKFEeqhh=JIq-QgpjTOL^L%7 zsn`W(=4%W>#lCJ&mhCcIwcD*D$&@N3xZMoMfdRX}x*XNCMBXucQM6?)f~fvqzo)aV zpQEHJKO?Y>2J7&nnGgzuHo0!vz*=v|WI`_pm;#r>V?Z~OE{Qx%1kb%!W>kID-NDfA zL>+v$tI>URvgo($ckxtP$ktVGK;JFv3Z;jKv*L-cVP?@W^l9_;RTYr6^DDK@%BT`C zS#J5B`m=p&5@NWGn_V}jx^wDilORdSoWDP}3rj>8_$@&zrz|1Fsq}aj?N#Y-l;2c^ zQCik_M)II@CrookTF+sTIWPU?oT3`vw`ri%r=F|FpzKZYKt%{~kUZMdj_hf1b%&~t zcOlQ9YAz|jUM|y&V}2MHr5w1qc5J*=uGgBpotCv>-T-`{vrr#-o|2|gxkw>AoC${Z-r<}09uGTa^os^4aSQ$NjX^2fAIRSo24!&F4ME`fVEvC#T5OM5tZtVr#( zNq;Mz64}+V*`Oek@F^-z?s~cR+~zR-D0;KMmoSu9`~VATn#O+*QY?wKeq(xw7!BP< zzq4+F2x~)V7_P8hcVL4^|G9|cw_y^R@Jn-n90KO{Qlt18895!w-14#xWWbQQJ;Fdv zb&)wgQF>`8s%jWDWtH_eTILX+$yFZZJKd*TBUm%@yDmiRQGQVw;tKR5%4jP>$srPOIPX^_*mGzIQa#nMAYA5( z;d#k7SiF4i;1o|uF=LkB7_$_o1x78@FVFgJx+_Bp%Y)F#tbp7A8)aE9Sm3L{eoYHG zS|ZMv^+Tz^o{L_|1GdnYi_X51e%DcKgM3mce5$p?@)K{Zu1u?O*74n$;28QPomYAh z?Tmc<*6th~2Mguf*(cZpL{eEUGp*KRLsQWi0ZE;~nMfPk{FF91hU0e?E$?_hPO6$h z2cpfgml1Rpt@IQor8a||Yi7Bm6qiZY67Yg+V|NmjI$OVw#klOv zkDR|;gmSJZJcRY^p!b&>{n$gIhG*{}sTILovXgi$XQcB0{A%oI>M;aR(RX;pl5U(=>A?kr8@)+oTU4E1^@x2mu*Qq01hC4 z;nLODN9SieMj5d;g29THH8Mg~HR5_myuW5;q0}`70_xTrp#jNGZAWhUjIElW2=Y-~ z;z@S%`4@#>ad(R4|MR%URU~{RNT(j_QtHnS_)T}gZ@cLUoH9#^+3eFh6_b7sq&s{$ zOz1cw{KQnP59o;88z{f({G{wrt)3Bv)a@9BI{(wI;=&Cr$(*Ma1WMTp|Er8`px> zyZ~H4qrXp+sFIXqiaP^N&o;HAtKmWHk)lhm=H$}!qoG}(%2SNnO08YP4fjU!rIA*H zm=>|}JX(?o;#Q<1wHfpYtt6_PDU1Es(4$UY*dqw79j$mawlQq6NIw;!KGyijLUge7 z{0byGZciojtk|^MpE8^|+47%Q)zD3ImIf{nkJM@bn74H@RwDI}A{_(~T6RGGxzS*# z*PUW@yMoHgm3YELL3aWTvk{vKKwi500^#2<6^2SjR%`iw38_=>)Xd7dro)$O;u-k8 z`oimzXZ?B*%D*GoWW!O$C$L@l5zFwD_s`6|iM?X^zRuTOdrMhx6XT#FLA5 z()k<#rW2B+I&{SiqjjDN&uimmQ%q~-_tBBO!Ke3CZ<^@(_BN-E-jSAjC_=k?Ms#_A zB*q~4+Oowa`q4-tdh^Ter+N`5)et7o70S-ud;?RKZ965?xRc>R7a!rPh~#df2zSbZL<*#oN&Jg8!ENglTq?`CS0g4Z zC+W=E_M8=}?)nglP2JGw&fQY#=Rmm%C?LS9U!bX7J-|N-81Z4D7I<)%(H? z5K23S-ToPxkbyySU_gX^(C`!S6-yfh&NOFR_(ofPu z?Xu8Q5J8!BpkvuY4whjnbt3spTcAuNpiQ;v2(smXDV|>bMzk!8UlgD*n9G&iIB3}G ziQcTF&*HFt!NBJEDqtC8DD#Wfu@KZ3VAa4OYqsu9s|F2p|NeZB%WFInvAshAu6YvKKoe_Zu0(Q2RpitVPNbIS@` z;o3JLThf<+gpmkS!vwO`qa88ZiiEyG1dV<+`?bVv?X^Vd$sKFUz*CtRPZ4lmec!dzu+(i<=I5nY! zdL$a}5ygJ|D*flI7}lI61Y*@LUs!1p-U}o_L_T|rio8OA5^4uCgCUEh$-X;K>-5Sq z?=LM(q3@%G(QNY{(w2ZoD%Ef<>{?jn_159vJ|%LH`gyxcj-M*RcgqW_7%4ImDbw?9V$xUwwNb=Exp_*XkR9*<9kvp>u~<<}wpel{=`j>MoU<(MdBU<_YEDS`q#hYbn8ppz==XhtfqeLlnNYWSqb&UZWUZag`%v^DqOW)GzcCxPx3{W=^K}NeY)iSxqJXN| zn;bRUux32fKN|)!0Qs$QBq|s@5_0s39b|}{Gp$uqtG7X=89Si7hyBI>&BI<+EnejV zBnU!EKhKQvw8s}cntP_PB!+SuX9O(v;mADUEK*8dp8*2R=BCQ~3+I<~+@t2Xf(iiw z-x4Sd4S~jMw%=y0TCZPa?tGY3L3mh#HF|*xI6TOvoar{0QO35sFu`XCkvM^irGaJ4 z_fUUB2#*MXl|6k~C68TDNMNg&dWmzX8%iiCWyFqV^)xT|g4#ljU_Nk(c zs5AXNeJ0=jZW34^OJ03##ZbQ^D+=wzG->S_8#5j$8a|qKByL(xAE8iR%&A#Y^f?Tt zfO3`whnQgh#shsi&gys-rPnLH);s1B?N9HBQ!l)GthUHiHDci#D$x}>bLfsPNt&_&aEM2P26{Rv>FwJ{*%yfEKH3rUr~5xgSUFZK zH(328B;H6sjP5M^rWvaq-{@K1r0-I7_^9YR;P8#d%>_mVPwl@p@a=-hT9z<4%Vq$6zny9sez`@9PM!grHkRA z)@&<(N5X&bIImCqRsz5zhFD11=GoN^Gm*?TEf?KxK(v!R&@-m zRDY}*M#;o}8%S^`QqQ|hpq3tAJ|uh~^tphR;Q!hdQXVc?US_P3gnGb=I*$~3J33th zx0IU`sPzZ(3^&wZ(VOf`eR=bTPLt+V9BK-Z?nx#egS)lm-qoT!gy!*i)y>Pc{<_e0 zEcn*vdGQD7W)3lE-1{$wS=%v&kEv2Sgddhz+z1N`X&}b}Utl3ZVj@k%ZvTB9Rd_hR z5D2;Ig@B1GXC-gi?PT4a+EMJYX|2k4smHq}pSWDq;J;dghatrB42|KOdLD=e{yt>z z*N?zI{3qd3=lf%GN^`2JO>Oi<$V`t>O30+Wz1(EAx-ix9$hO`>|DBwFf-+NKl&B-k&R| zEj{(NbBGq{Fy_Q~^V7}-A`HU38{(a08$QF%DsN3<$YP4~Wl1nB271@g)cA5$l@riIMr9D^`JnpdFA z-y<~A`d&WbIHW)*`RF*3t15hyh+0*G8g)5qOUIAy$R3jBm<2GwLN)*ai_q4im_Oah zG}w@NS<@I}tU)r`uQs{p)%jVsV{cTwX5ZjfC3l*pR1%XkE0geMv8aZD$I#;sXlyq&*5wQKjX7BYdT{43MQ3zZnO@i#OqhdNFG zx31urG`n)j67ZrohyVpD$ltJ?gYzSJIwU;_;bUANAIahYNJuD2(D=+mIeCA|E;$-{ z;a1-gW&B9+HjR#mk`?|$DzOIwMFEz_$x-~q>oo6#8*vnSJI!hdi=#=A3DyEE)Yx`q ze8GQdH6{VKtULT`)#V06KkTNzkO2*r^3W@FZk#+1ym%Sf^^e$qCD0(?WYIeyKE2;mPeYA%Xu+xgB{jTZ z+P*24Wn^#%D}W+7$BjdRcT5t*RB%j7e?MX4?i3^sJKqOED^iMVS0%*v4AJ98ZoT34 zn3e@+hH_^h&l+Xi#lNd%77JCygGV4n1Md~NJJheV7MWXYAB3Bt@-=Nx>Yot+X}4I$ z+l#MP*=I4=NwlHVn@vMfsU~zO-CVZMpIW!E$)Z6Hj(iw1{LzX3l`|@RO_mqUZLmRo z1`q%%*s%c8&G8wJ%PbXOb4el#fnECkvSi4U*cj=WKC|)iax-<1 zqbf@_(>3kg+X&)#-XGJQa;LD=l#$b>>onkCDkd(BpilGCGgH4rZX zz;3>>Nh~)hbu>;!+V0bi>zagy0zff~UY*$P6H7$(jHCdun)%!+uHG}kOKzkp#1hr? zoR>yHkO%G%WaAjh%-O_A7d&;d>*>JID@}FE_c5iq#)~Q z&4AOobydlYG=c(Kl4ow!uT>Lel~*My=5~bkhUJEx3ZdJAIUnmt-|McHLZ_sP2)pyN zJ0pVM_?dJER&pQk?kxNdnnD_Luf0fJuNWa%t->v$`t>Tvv?!ItydRwcg$P=@~@9*>1l zU(bbC0HWrp96?mu3L87l>vp}*IMUJgEBy~Adh13)aRkvTgp;UB^0G<|6a=yu(9#sH z?QtjF6u6@dbOiGUb=mr6c$lURce@3D7g)TVC*Jl(6ev`oicXvG!!;S|*0*ZdI1=p9 znUujDN?Da?k3tyN6E6Ze&|}iyVAE3dtyOhe-j|2x?VeD|3FzUz{0qK9lyaM;04%SO zxO$3N`ektpbSq3v@^%+4Sx?+hXiBL)d>Hor{@rf7gwOdz%uyvCo$H|qf%}sOnU#-u zDOulTqdI&e$snG>b0f%W)wWdsEMj9XqV#`j`W34&#}e!$ ziV{160cWxX9L3s2^=oK2A7F1*Gqs1Hkvb64D|;Y%aaUwDB{EqI;8P##6o0Q--ezgx z!jRoc6BGg9km>uu54ZrS5zd`oimC}VT}aW~{pci4$Eo9RL^5FXnC>x-h~SXfiyqXv z2~O8M?g~ra1SCMunA73KMUHPvJIz_j!#aWSSUxmOHwzlyE=ZE1Ko#ywUj}gRoy$XWaPM|n<#Biwh6a=AYJ^skI?&C#l%o57O|c_&xsx!ElmSkAOuJQ(xc z?6H!kW9HxB@5`<}miB{anQ98J^Audu=yMY_Eqqeca=r9b?zaN2!vgX0d1rP70AGyl z9FwZSyNjYG=g)QrewOUHeL)x20g>oBpQq_e#qPSy8!@!`!4c8d&m@@0$nluRYinsx z9`p1C%IHf+JVp@4tR1WR*`}l!Uu_y)EhhHveX`)Hsg&y>fHm3)HXjWyyW8LCWI!Hi zjtL1%D6@?eKAtw8!->~=r=tADY&^HL=6DXu0U3mFtb`GnQ7HCi$@27&*+uiX{g{~o z(o90XAzfyij+EjcCu$!__7oTV`O!Rw!_IMVNM&=%7Gh{3$OR963+?BZ=Mn*#K`J&m zNtV(HS}mj$MNj=pG`-^W$7E_OGbt(puz7{+(fGq7@H@RHAh3#>84l`0-DYDi#hs+x z6beC98EbY>@sXf`Cozj*rhIjc=^VRt1D3tO3t~cyl3U*SaAg$0e0L=ryQQo=(cSBK zF5uxzPDY!vU8ui30#};W6JNqjUUerq=MylJ3F8^6N<5*{)8*dRGEJWU$|Bt5gsIyT z6qqU&$yo-vGvKurlD;;($TDR-@ip5>=-CifAu6*F;qlwC@z+Kw671}k=w6&^gCA69 zCy&oy6T9pQ%e|_=ABFO+o2C<5==M)0kDldUd!lZ!)1 zE5<+zKQ%5q1f0%j1^2t(y(Y?Gq`zT>g%9wt9MS7=xKQnAFM_!>QrddWT4|a@StBpl z)qbN6fe<;lNoK{6i;5z;U0jnNN%tkq4WMB&XR&+PgOs4e_@?3g57? zuN;LEol@M6`y+5mknJs#?loTg^L&)r<>k&`l23+VFs+Es2JTr_ys{ca5#cRC1LEoQ z0?vv-&Z{|C;$BY9k78vVcHBWa6RAngaAHTE)|4P1RV(sq3bk}dqk@|1tX50tg`!E^ z%2H5+pZi8Al&KTTcsU%G;AD=Od9{1oY+?S#MxHNN200bMcZl@L-yq9e2Y05Fi&pfE z^8}q}(mx5H+iZ{7hAuNjTg*|f2}nTchBuG0sO)Q%y=l_B|NktMwg5?PZf_t{Wps6L zAX8;@b#Nd=VRT_2C^arJE;A_r0000000000000000000000000000000000000000 z006u)mjC=u0005LrwL$P001BW00#gy0Zg@C$25X-@QPTO{5!7h^+`UwUPO?q2QuVr z)=1&pKR-Qnem)AfCzv0+Mc%sT?WFt{yTJ^jV!8bJuWdCfR{EqDJeHZBZib&MLFu%- zi_70$DTJ*l_WqTTe&s61ZDrb;G2Eg!t$%8z$N?Zjn8x$v%@;=BHC2CKQA(l;9|}>( zX|RXlB9N^4lQC&3YFWH{&|JrBYK*tmr>8i%bGj3n(+&a!o>yv|{|=QAwDsLBGmhlh zEq5t12OXjMpu!A;LJC51Vgq+*n+XyGgUD=DgrJCS>gF5pn>7y8iUu$>TVo`Z5Ec7$ zcOf_Ir&jnZ9cRJ*`xa_Nd!53RcP>Zeg~*v?>en6l2Tfk^S79T@04(BBMN4VEcK`&o z9jt3H`!0=1sPMCwS;g`;J3h7K#n5P2Vox+;m~)pVTg$~s1n|kKX_tod?|EWM?AIe= zf=Ee%al>g;Ibqtxw%`1iQ$TJ^(oPe=eVN%9cV|Xif^O@|#u7r)NE`NxsenRG5)Ygm z;PE@96{9o&`;nG~J@nFkgN{S+@zblN2zFQg?+DzN{PJf`YHnI(d$$RNwZtqK6$tk& z-syHB>K*_6z<7!mlRr=3*Ev;VyT)TJ&91^xKr;mMOdgR+7?VBtd0xOf`H+k7#klUS z?>h2;$jduT1P!@DPD)@X8CKh8y3O4fveOw^b1Q0A3ifOEhJJ!CZ*!hiRcZQZTUoIX zKfev=oz=CiTsI`iR%yT!U(n9w^<=lP>3`GvRRnviqCexsVW1baPh^b@DQy-JL-mr- zfg`331~)cJe8)ruro&_y0iJ~|;GWli7=R5=3g=P2InN_CjOnatCj2~oY49bQT;g0uPQ*MA5r)j0rIK|y~W1| zA5Us{gkpRQH-Z!tq+Mhr*vtA?Z}TGjVXjlWshiS;5I%bBm5rmEA~J+bD8}vLAs(fN zI{Wd-$w9SFIU+B4B>XQAj{M9nQb($|e>#>gfVOd>e#y0*SQZ;;e2N*fm(K+50~eyg zRW~O9v53c_uy40)T`NWgQ*FOgglY7s*j+Z4f05kkTO*`^T`omeRx#f61gmrZOd}rp zwe`M@-3G`m)|Ebbd@&S&4TSds5B(54iXckj<}TvjP1=!gFZY7bAib~fxYIz#J_MaX z#nM~42(n6 z`cM~zK)Da$%xUUX>(sPtFt3P6?q<247Q&9xohm!^iwvV1Q1>jf zJPAM{nq)xE8XCoOVY7D_^y&$X6}z?WuUfydAgG<{u{wK&%eNoHD3+q-XX0!ty!ZMy zL|dViPOP32R%lBy+`Ps|vD?BqR>KfC$U^J0h@3{Oqbw|Q%3GwW03b0t(Xk_k49<*+ zlukMWv3~hDlpSK{DNQ7x?}MXQspsfUxqP(@zK>8Qgn{)Mc8e9$GK1-0l~MYBgu4}xB zKYm1TrRZkp^0vUyvH=nG;txe1u<074VHZeh_$=*a=nMMRh^PvPwnnWqIEHQc<7IfB5o1cKCt6ZwEi&2 z+l&3uM4tUyUYt;42>`zu7f$D#eW|Gi{zq#_^~fXmn5;sJJq?x{lGv#4NTP}ND`p%iqFT3`CT4$!StBP{Paz} zCM01`RUnC6hd~Ru|4_iuSbj%DQaRRTeWuPEFTpZIQ93Od>dD=mPwurt#EI@Lby`eF zM40Ef%dD6?BPnjt_TYY$cH0N3M}&#l^Sp8`*_E!?Y{aOo!Vtf16yz52;7Jn}#5=*L zX?jlcWoCJP_beO9fY&HRy&zWgT6D#SDMx{qRsbJT5m>Rgw(ydV<5y z)x%*GYg6OFr?^nvJj-mf>d{tE<~`I#TG^S+4ZPgM?OrA9ol@VrOat$RuIm)KBVM>| zr5NVlw?D{ORP~Ji4bES3rub7l#X6H-%2*4={i4r5Q7)UpPuB}McQnk-4cj#PRpsFu ziXTMBekseBC*SwD|B{QHf&7!@G#9BcgOnG&dz|1pyLu6#MzvJQ^;8i;TMHy8D306Gnq%YQo9d!j1kaZ1_JE9BC+4V08a&$`xW z)t;N>4nK<3)EjWJbc3|98Uf9^DTtpHJ4ENqoAsgU<}=EoXwxNh&a5TH#xzX{a@79I zAHQuCIY`b@29IXMSbVgrVk}jei8s@317Tt`IJrME_$uv+Ae^LjU*o@Q`IjhQS1Nl` zusAyVs3kRsva%ec)1B8I*lKKNEikX}ufMO8muZ24BBeSW45o`yt9!dM%j~x1U0l?7V*~mP?4&Fh!r>)|cngv_^$NQS zhzJZ#c@yv~W%y!;5Av(Y!xwTUjcKwUX7l{jRR?fKsqu<-ggph3A2nWbtIt&-E3xz# z$zA5dCfCBvc zdBJI4Ajb9Ht9B#%FnK=W!W&TUC`Iqi8QpVaqVAC|V?qHU3|@ct(^DC(W>!Qv+Z;yN zZI1C?O1+9*Ww!xkYYxSb2}b0AkUgz$a`G&qMc~*;q!$Ja;KgUx;-l)89g`!-13(stZy6 z*O!FsHj&b@_Bd-F0O*HM#X6{>!(gQt zxtYr3po_;ERJ!ogY3+M8ph@}zWwav-Q7UFyz$z}Rz1dUaUs*cjuZ4e0*z|!%ZcKe2 zDdZe{ieA3{F5)H&s`io7i2Ky%BOl6Z(h5KWDBm(?r7xCv%@V(jS%bYI$2{&4a50D} z@Fb?16Mt0N;mU6qwo|D>Kjb);h{C!BAo7A#>fv$~%k`3qtJ?1kpzJt2BJJKe#fh|3& z1QPN1#E9xl-Jdi zR7MMVy=}%xm_Csws)P)tPq zo|w0rA9pzj+r|XxcPaEXlsHmrd(?ay+b8VVr#A22HS0<_9L@Q2{)yMyw|(t@M)V&| zU>V<{PFh7<%g7clsM>L>GVFvLQ^J9JkpQ!5nG5Q*k=GT*M2z=94049*?>0B|tVSKv znE~{t-b)Snw$$m0E&9*@0FlQjyOAKI(>a%+3y82V6(BHg!ljmo;S;ErQrB4&%s*)^ zY}f&o>p|Z^7XgBp5#}WOP~+FoI9uAvZ{gS6q5)Avh!e^A6nM1WJNzhJ^3)j~@`<4f z`e@v_lDnUWKfTKPgpPiU$Y+GLi4$1~OaZqvV}5mxiLJr(?O*lQS`ng4TszIrrp z)J>=4J6<;Zy8ep#SppYteA^u0ST{(F+{9Og?L$A>LSW~Pg>2P2lGRA$Z&_INS<6M` zVXHo-K3PQV1~F*r#>tXXA`Fm?Kq9%vacICm3A|pT)2oMJ@68LayWv+m*6{EHtdWQ z$~aDTT}o1->1AV$D5KiP(lNwzr-^nl_t@nkICNR}iE9y4j7BuUMOZDKSR*OH^DXRHj%v0 zBN2`)0&ER9h-`zr8@jlLfAYL(Fqd}Vpo72F2$NH4!SIQ5B&fwl%Ag!BtPWH~IfAGr zp3zjP;}Awj3s&)$CZv$msnqiVnCDCabVpOm%x{%Kcycb_2wB%Rw>F^>qdHt?RZQ??ZJrT+FBwkXr&51U8(#LwFa7dL4}(e~n? zUPTde;@pE%0EJOw`ZcGdo}mCW0SbWBy12q!17STgk97w_zLe^LRXqTZmXW@XUgs$N z!oX>)k)>%H1vDG86ogNiqka+kU=n9{5|kiv6fZ8aeFxHG zK>T5PQ=y-eQFkw-brXmYJ-JO!0IFtFeNnefu*@FNUK@3SRvz9-K!BH4fqDcKIp|Gq z`8*dRioB(n#A=^F|g4MQRqIY{EGe4{tm%sR>Oh-jS9ZQ!B9wWc@LP4h&aT%t-48Gvls*k?9vZ z3>Xc$Bya-E(XqjtBqTaOudMT-6>KJ2c=8O&qD<5s(jooixQjv#%g+!BXG=vfsblaR zn>3if3j{){k&gNuJ(LCO7kD(~T{{!#&wjIucuJrG;XTxY6gk|Te^cOii?BL4(emLM zfyWSajV=b5nh2ywh50Gc7DIR+l9b=@Nkx0G->;DFCWJ$%7`l5}alN0if>u^>6Ma2Z7JX6^6%`OewulM}{+vccl*~Sg&V#X$gp#YE$Xdu6PuGOZ zY$8HHzr%LbWG|vJvm`C*&g{dP$yA*StHbNR%43jA1%+&qGJLY3l?QS>7!R41rb(?g z_&aCoJ=Y2rG~#`v<>m5_>pd}MPRz8zbcUu2Q6a_CfQ?nEiUmrw$lHc@BCLz>DP1eR z-VD=W*6VR*UGVC}hz3FqIM>aTs=wFww9DQ|C^Z&51zhl6Z)K`f6bD#A>~_o*wcPDI z?@C5m&}ftQKRH01$15dpv~=4?A|*}aW69&~`fJ;RveH_pSU;CLZheJqI~{Z>Eu zMoykB^;vr@K^Z7P*k#7GNXY)2LrbU@-TAf7YDfGs_oB=KK9B5;RXNQzOYtzo>l27( zq_>?4o972m+d`J?t{lzrJz8KP%fnC8bLR(xsDrj( z(r-5!UTtT3*%qN&ya4%|!DA(TUB`5{nA%$t@lSVA*F`X`@2scX-31U6sm9P~%U+nS zl~S`T-QMgSe5_QQX-46TPlK{jvV*^oqsi2K3xCX(cRZ_*mSNyL*ub3G$Lc2C5FYwG zWr|CgB-v&<{>t^(Gv@PtLmgF(pLx^kk{#b4Qvk~OB3W<60*U+V1`jm>3ddKR6dwPOHsJ- zH6y3g5rx5(E@--x;#v?k0pt#i@-+p4-z&$+Q z7cG9sYwCqZYn~1h?mFqo2tB!eRU;}qjaiUyHNd}xnKWl7nZ( z9h-YQ-pP6p+)A+?E0^&-z_CvNYWTy&f&Xqyd;3h%4OwE-s`1DfmMX zZF)a041wi-gEm%TD@Y61rl;62x)=YV*PV13N!r)Y}k#VvWkR;43pcqpQR9~j(U1X>iL35E>Bk_&vGBt z@j5NwdrW#0@#VyYO?pXIV#26o-m8f@@^M(DMZ(26Q-z?rE`6=7%oFUIL)4*8^}xgTbaJ*DHMzyw4J({*&f?rywgkIqtT>qVPb!0;kJ}} zG8*0O-c!~M#6^=9}+sGUrmZF;Nptb*|nr}QBxqB0FD|v?wIKv%E0f7@8j>%|dPYmX z^@9-~eF(P9_ zceUNyFA5qZ3R6^bz%B8<=;x>ljG$w=oWGc_kI-+0g&4P%sOPum(0OjTA8NyejvjDr zyKPeaj3myZDGJJdOVXh3#$laxV^|!aKFb(vOR)|T(i1(HQgA-%kDC%{2s(x@5iJ|m zEN-A%%%?F9)9pOgL6c))ybkKJ>-V^LI62YyENDj(aoOAC1WZFbJjpVKJ9G1|tPGtTbvTPIU^zmiTd^%&j#{gTzGm2P37D z5fmi=%@7fx4sh?{)U@j;I|3|=;yB6xH6vqu4zq;5y!b?p zhZUd~B(RJ$0@mlkG1NzVZc>f_4-yY*JofPy2fGHGsrEe%_qQ6s`OL(cC>BJP zYEt>x)&kH3g*=A*b|N&)qIz&Bj_$E_u{RsVxtTBKjJzoJoCouw^y8I72NmLUDxCw8 zmo?MCMMLVB0JQ9|`fAtjm?MCmY-KoA_zhim==WMs@sr53?33XuMRM2!7uq`)2(2m= zt`L^mlEp^ryMI^2F)K+-^y?u_;#oght(;=M3yH9ry)C;y8XrwQDkB_05Qzw_IIOMr zDcD7po<1kgG6M3Vga!lZ3=NoPjS{vLiWgc=+h`jMwJ)`^^rn*GV+@C<57m|qr?cSd zURAfD)ADEv>D~2u9aPtOT;qClJxqwo4%zN6nwPHI;6eIU6l^duP1P>jEr9@wvkC~I zyLU=f&e)4*YYrWySda6r?-)!P81xBwZ@|eB0JFQP8AR_ZMH#ODWC)(w&nF^+N~VGu z1`RXTde(>2iICDtEaYC?wf8U~`O6sNNz9#ppBAY~2D=PUnLiCXiU^kmkYPQP+`QtE zXal$gI5?PMB%Fp%l?k?5Cl0&WfwH})3>9-vlVI;;LnAJhP6M^D$ei}k*x=j1@%Gwk z`sMhYWNgmgN&M}^ebn6fbTlE854>IsUve>-G*S zM@9Z{svGwx_m^OJ1^vAFkH55eZpc0CnK3CEw(qE^jbndP?i`3++XQsyPuoK{%HknQ z#YWGGlpa~1$ofvzNt)=nDUT|4pMNqr-j!e>-};C-y*U7_J!hJGSNUH2`My{Rggr$z z)>t3z`AH{&2W{S~eF%hJ#N_*}`bJ-@E9U^hKX`4R!W@Wgl$iQwB0LO*pN#(I;n7Qm z@(23%_6M77=J7?Ug|F_;y=lG<(w?|!ap$pWWRb2QANX}+qeSxmr?hPe zkdBX$6A+8lDZm7}8Qo+f+@JM78Jyx2WAAIgQ>7QAsju>!{s0{MM`3V55~sw?hC8G( z4^#NT=f=+a6oO02uSpfu%!`%E9e?l=S|`Lpr#W<(akgO)GsqW~LkKbz^Ld%foSQ_Q z3fUL|cU!La7ah_{p6vydyEif;_^wS<3Y?>Ds3cD}a;1&QV!OofPftjd#iAbQE-;T( zy7_ZdPa{q9Ug^Mi&w*K`wN6PfJu`e7lQQg~NIhG!ZMSUv;Y*U`{@tbP*!X~9W?4_k zhROSAl#d$>`^m{~+LaK72)OSAsn=k_&m5O%^{Px=g4#e$6I^ge_!ab+O3_UWg+15V zEA`PG19(!&qnkyG9&mAr3;)lwCB=I4lf)+jO-k;2=Xo_tU@2%ekQvSiTigCic*{V5 ze5y{(mzMwEewV2kUAR;%2qx%8i3B6W*^&o{|3PgAs&7ghn|g1XOBixCRmDK~Mi?Gh zl&>7!UbM(O9m|?L2cQ27quRzq50sgy&<+M(%9~P28xBt?Es6TIv7=V z9rVopWQ-<*YuQwByYM(0M+Pfg>rAtz7rN!6V09CB`I9N76Z_(@OmqI&3BXm!l8=xc zrKV*T@jO^i!!{X2mF4Y@Q{fWvCcb;YBljrke7TlqS|@AEa-`?o>ERg$62;6F-Boo1tyUOMSYuQ?99dSQG%Kjg(e%jd7G}kllCWm!L)qm8K2gj>#WK6FOb9a>c)J_>@iMoga&)v7~Dr z16a}$I_Z#r2n}`{zyLLS0a!0jaU!QiQnA*zRh>$x?FLh~L~~}V$ik{Cb$-|+XE5Fg z`K#WElSYT_CKC_}wb~7?!eXd`-(9W!Sh6aEeU{L5nXq9j)TbXyt73ydcZkU(7@(UwWat4AW3Sy?AG%N1MI@JX!%K4nhZyynUhk z_U@Kq1|v3`L{XRh)aq4XY+Yw|wGjgP3Omb~=d|*#V|J$yw)Xm9vH5CI%?aP6z9T!z6*@$=*Mkz;|w$;De}M#D^Y@z6W<0KYp|We-xc|7c8`AU)L+zkp2x zS>SdFjsO!8v{b-jht&^Dg z%g8-&e8z@|&Xgl&Z=UtxA8DCbvtcEzR{};t&tIy}+Y3 z6DlSCLO)Xx2GK;=I(CVQ_ApYohE{Sp?fvNcT!Jti!;{i*7aBss`Q|Oio}Wc326x;p zUo@glM7JFFC*=HA{+{mi?N0?r61|pa1xGY*dNYhpP1)nlw_+jah2oK$GNc7qx>Uw( z*n_2RSd~*DT}jX~)6XoV2hXY*LC2or<-EHH!Q*sZT!MfiI3^a0IpDD2XK*y(paIQc zcUQyfvl0KofRZ;20TcHepqUj1U~7uy^A@hDK@k2psuHirPZ!NmaG{NgP2f!VZ2p&I zB=9qwoiRDZ0U0Yd^x78nNSZx>x#Pc?$Xf^?w2sdlZU4S%3P|dZ-uhD$pb^!%ke!M{ zg@9z?7Yd6U7891MMrFhSseH8W<#MQCi2r2ut_a_hr^KYty0{R_IEzezgOA04u3>Ym z5)wNFYC7`QKlw~T=}l}zh8eAUDcT;N@^bECSh=|STIy;rjt=u zso@?y5WrRqsR>)cJlErK%;%3M4xNNc$>kz~8OQfVvf$Fe=GKD-nD`i%)|PL)9#@Hj z@z=;l1_+%+PERkUuLpd$CPqk*y*hx)Ff^rH4AnBfl3ML5oPCMS)Rresq}lDSWB$@- zB50Q;r*RRe%x<(rt|qTRS-aD-O)!N_`zTY_Ja-S&f3qnHu;l7T0FPUdVPa3b=u@%2 zOWhpXh9;W!3Vx?Tyfv*$JdPzFY8)ap}be{UbK#X!R zg(+9%_?s25I1~%n;$=q{?SsDFKw%m(qsU*+c07^IbOqe0%lKhO3|}JI7jX*9m=i(+ z@xLF`lGU^#)uyvpaCpKuUMgxs3-dWZ>uI&*A(k!J#OtfI#&%Ka`FMXJxOOQ4liVm?#6>7L(g+g0^!kWJ7a+kQd(=$OE9y$@p zEqx${Mwrr!Al@unFB1ckSVqkI9^F)K4x1(46(P{T$8&Pb-l?dB25iaJgelW@`T5WaO`I&S6EU57W0*Hxtu(hRF zT+L2B2j|N(+HM?-_6~`eKa5FW8ngB}7GjfUMhTRdvKgaJP@Sh5?dI^p(E@}{bCM9Z`YiT7_M%n>ono-F{-;W06 zk{P8m@jJ)piA#=3@NpVrQW*WjQ@g>Otw`FgT3m~MsI|ek#q}6DXQ^-$PDAIsQGEbQ zK(xODCSfB5-xiQdd8MC}f1B<`Pz#stwUm~;ZvxL)efK;fK73I(ZfND6#*=$Ri&XD<~0YEQVRf=NiRb>VeH$VIGK7sx8V!b?2()pj$8Az3YI)vYabX! zc8GVVW0@VLK=S*#g=C3t&9zfs}uz#pLdI-5ovJZIE?W)*QZ~azj}7v%Jy3 zL6(o>Ru~QxvTF}}B(brj5AfzHuufppVk7QsipfN8+s6zqM{$+1&p(Wdrps|P(L$Ju zF=sJ%x<9=1Ks54$n_4=Xuc*oYRbOHWO(AjMp&(RJy@X5RttgAs)soNef^O||V<_h% z;JJ?!UL8Q}Jj$_hG`DHUN;|nb--U@M4#|(tb?|`h?MQ`~regJv8}tjb^{B=(*9kd> zVf}(NwmXjL)AB`gydyiJa*$0VXND#i=6F++niKHtr#G`I+wG+Hx#BL5ia0ooXe9so zR9Eh)X0_*O+Eqmr>hPLE6o7qIPS<#LFIRSf%NQQlgG3M75@A5(mR#kC+ztGZ}u$mq|~kNK?s0imt=iqx-XU4GJ0p zI+&7oK@^U+`T#tar9pI;ZMLzD8VM`sC*I3%W^`R~9n#V7#=QMCgXZU1K|fPs+L11i zF{8)C_Ovf73LGyEN%eG&OdJ_EKdMG{1_;Fs2~zexUDU8%hbwPY2Zxs!TY}+vz>s zpIV~$X#~OwD($M`!<3;sMcwOVe*4tfLxE@N!K}_i-11=9cR3N zkDBYCyf9}5eW;`No`JzhlWEA#tWYfu7!|)1_8aut9VEcJlFt;#GH3#hmbmgk&Rk(x zul0%q5fg<6G*N;8lNSu<0<^*X? z571h2c&U*FjrPEO_sJ>NS2%)dqVPbIt8s0*prQopTt_3T9Hr z+yw~O4fsiK8MzQAp&4DG=G$*WsiH5;d~Ru6xC(-P^@PXvT?x0m7P~9a^U4sy`=I7} ziaJKVGf^%xcvXC?{gO|*NY>;_UMyI8yb>mYtebo3HRET_R(sIHr!WpP+{n^uYhuK&~>z4{p9Z2OFqa@*X<6k^iUin zA24!r`QJ%(5TQm$GvO*oO8ybec#5Vi46#XLbA@W6;6u@K7(>YWle(CD(AW`zRZOnQ zdi+>@l%L$}kx@1slBLM1oTNY5PgJXIi5Z-UJzdp_ut*3EVT?xo`R)g{&D)gJ8o!%{cO zq>=ZVVc;pseFW7loKDDyqi2bk^u;*)fv5Byr+&FnR_eW$c7@(SKQ{5IBCvgaEKM?ZpoU0pdE-(FG~(P7;R7H!eUb&3Qw5gP$hXN+@)t+=C9fpi^6F@BWK9L1kb8rb~2}Xd% z4g%1R5ABM>`%?Ag^7c4~@r+IL_3{!^lM?F}g&vvRlOD%XxQ? z2?hG`V~dP`PtFh9PWik(ob61vw&VRcgyC+)EO#ALN7SJ+)Q24-%?w-71V|i#a!+=Q z($CekjUHnArD_`thtZP*G8(C0jKcU(4DLdIcIYT}QKwFwr>4UjwkH$BEM(U*u=cOn zwmerNH;Ggb$w2MQLG$qB6d(-e@!->$?Me|m-PeP9B~_45)5Uy`H}C+Pic9!W%zFQj zit3eY+E6gjRy%Ov@ApIEPtk)xVX|r!NME;;wh@UOFwR4EY zq%epG5zy%XFQT6%?;d%-xby(291exjZ$r>#+d?)@B2Q^3oP! zzefk_yOJU}#k6F%W^lq_1;Q&0cqV_Mf0np9%m$zUcGj$bf#wc!?U5S#?Q5`~pU%~L z__p?Qd)&-CTrI7K!+s^;5_?vaDa(x9U*Y0@$r01`VRoho7UDh zUoVb`5?h&T6SHH?l-0#l z)B6uvR8v_k&cQ{VF;K`;gmauJq0@wa5}*#LOwPF|yue~3>Oj9slh?Ej7r zdRQ>sJK$xb%YSb(1?fVdnWJ%o41W|QFuI(H^8T!ErnQM2vGka_=uD5a^`IP?x6Ipn zV+~^m3e#)I&`}la4gyJY+;?|c|%{m5)kGDYraJ{j7>&HFn@^* zb%d1mW%9e=97-3m;QU`nLr6Pgz_#F|mi&;U_`$BJ)alkw-G5!vtPf26{GQ}&>r3GSUM_qd~C1Ew!JgxF8$5z?-QK}c$I?ysu47@b%Cc^8T4ys@rXu_X!r7{~cTZ+2*fXhR-dUUa#aEP;m9owx1Chw1Q?F$xJ+eD~q|GY-ch;;=ABI+rFPgs<0x0xTF2>EDxAKxb?um0+B3gE?8HNA(n*%IBXP{(FjMB zjb3H?mX$z`fCSl<=t;qdA>=~Ro4nD$>XlL$oX2)rdeL~{i8pX4aTn`s@f=mwL*ie_DUVc(W75Xw|Gr`HKBt)B$D-sjQ>(wF zd$DO865#tQIO(9-K+{~Ub_@`)w+L44PwdE^wSaJNqD^UFcPcT55%apmZ5Ue(`TVzd zYd7ZAmnvc{mKgRwR@qR`R2HHOubw}AIO%hucLBYut4$n_L*EN}(Qv`zPqP=hBWi=l zgP*eHRY0{fn$Gq70=MYuIz9yz%%_x={T+c^h|~R~+P!(Q2F7o+SqL`iGGDaeg%FAV zvqFD^Mt7$3kBF!aQ42jfSrk&te7x3I93lgtiw#zBWesw50dP8a^Zrs+*?tbBvbp*& ziH#^k5~0=Pv}Jlj`&&Qx>}^Q{YvaeJ+p9E56u=lx7+n#s#*gv09k?wO3XXv8#+~FZbRm!1a`I!3gAOo1xshAj$$$s??Q$ zSLPWPR|#;@5A6iiKpc}LK`yKrPXHyo0k~wkie%su21Nc%7teNqzwv6GW7@fTkNw5p zsKAX~m{x5Bros^nPDhm=(V@=W0y4r)77Z|GdY@=HJDzo25d11e@mqA-l(7x0ovn64 z(?YW3yrHNaKblwhhY-}wQ5+UGB{EgXJ$&ZS5>KM`320#|7H0jw^LjfoGV7PX_=0}Y zwky}tUlH2prw!cPMC?780fLZfsNnj_OE*vob%-QDy+%F`>6ji#AbGQvAKxJ0`J{1EQ-e63dv)HCyke^!W%i zD>V^5tp1e1?p=;e>txg{4q>+0hG_u5JWP@5bye=f(aM7l8e-7X7PNWnXb~RVEFDoJ> zf&?-WcNy*ZZ;50-iqxx%*^D;PrT&;bD|V^|I-pmHwC(Gx3VeCzr%^4<2UCI) zMu$DsDP%v4{y%Po1zn#E;6K;{N7bP|RZPe`rJ|_8N3f&=T&Lzwa8hSZo;(-ZNscGh zX`ZhV5q^0CjX~23;*u&O*F0N+0@pqUAqTqXK5U+;h2{OxtN3NVlCKrv?zf3O^cEz+|#;Rd19 z8qOse-{n2?`w|dGtznHHi3O+pT_?vQXQH*DV}EGrm6u^syrQJYqZcy(xr?m`$gOHY z2kpT^)>F#Qpg+^H+-H&w(uyQw3O;LDH{@^6b5aO>>E&SHBbq#h5l_F%E=IVP-kN?$%wZ1Gw5dmI#H&K{rq zj%XMK5%j%W9gFQUm@9Q7C4a0u3&fH2I!Os#0I4V~T0S19`l%Q4>x0@MvSeQr0a9BM zoW{ko9`BkzIG{fD%Fl-Z%BmH)*Q=UK<=?5m$v`pKEpikQUDhY}iXkm34f@MA>iN@k zGNp}|jAJaNs#DjOq$n$*G+y%&_c(M35;H6Q%XA(x&F#Wc@OqlHudjRRd&QHz>cqH5 zi%CHBjT)2`C#siC5StvIE0vgM2wNTrx|hs<#JC!&U10*$=KcD>5$I@lbA+2c|9!J; zHP$J#Uh8{C6RG}1zI)0Z6Hfl+62ajkvSD<9r||Zzob4;(Dt9#zQw*eH7d7b#QD%e$ z_*YBI(0@bfmyn7~{5WDuI3?q>=h25}k=N%VQd4MozFzD@%UIWQas52=?Xqkfa!xJQ zM@8I^kyJF3sW)HO!6RYN>H%$6b@tg78|DMWUd9J#G6Lm~YkR8d2hSxU6@cX^STqMN z)PSjVao8rwjHm#@%atS8_Dq|>di&!twQ0Qy50w)2q@G&+3D0$@Lf$I?R1C1^fw1YR;%)j@OBcV=j&SHgSz6EjC4(%{Y3 zagKHG%ST$`oJk~thn~z(A{eS+mcUBPrPY%^kF%`}ucbMa?6GdW2S{QA85op+D;)1X znM^_&W$ykAoAxr+5!8Pj-bEkBM{7&isH9ZoL`pD1BVv<%kp+Y_ij@+9)+G8(UN^2= zs=>FxuU9A0f!&8UQSyGjR6U*W^qw&rVFvRv6Y2{aLa6x+ zIojMUV;95Z0D)8BbOhXN&DK3}$$3-Ji)6Gd6>qmg1&5?K2u^19(q0|-T2O%f~*E{ z)@q;6lV1*O;*wZPbh=riy5&}BjI88zio%hnBq3s=6!M1M;b_SmKqu^NS{m#?wO>0A z9W3A*)VO%a>Qo|O)bw1IH{O*6x-=HM|}9c8S&GI~8(o4r4;i09xKrWs#i!D+@57yWQR zirtV>%5YH(eL!&X4g#AzAVH1+W$x(dz72;?R`C10&y%HsmTMsx=F5F^uhA{+F9SZ_z4Z8_6@f%CC~ zTgo3+u|!qH1?%MJK>gDQt7h6hnkML-HgXPIc02hJUt8O&f5MqI~Cq=C#X&1*lfJp|cxNLPPhENpnRGT&SE)Cwp7j>MeX!1}US@e}vV z!0=oC?V&7fx){_+&6?-O>xeR^5}-3%|5#w$ z5NE1LDsFbbI?Ly!%VPDSn~bwqDd3pg68IYABbwJX)04iiXsO=t$IAnbZUp5;-X7RP zeL#B8sjl^+Wzq~PA9wcd{A^8h>+j4!2EwpGF;FM84ZrCPyV#!ajVj_b&$rE43LwC~ zy@t&(340RjwOUJQ{=Z#!R_TIG@fP0D2X9A~mY`8qnAt}1@xFs~hOHa?0Gh=CzR?BQuQY zS3rztxL0kBwy6<&5e5L>`>L6`YnwvP%5JehsWmC(;$ zyYyFs{UuXXCVh|S{2X#{tOM!g{K$#V`$n{H?ZTTsCXIm9f0Sp1$C9RJ!Z5!4yq69g z=_Rd$=AdM|;7UD7~RjaNQy>Tt4I9Ud7?#iP3u z#tMgL&5VN3pCDmBnI@yp$288~m$4g!Me*tZXW}ic|9^OG+^ufj>*bF`n}TI?+%nDs zv|WAIDdhV74&iTO%Wm4k1H9k2)kk`9PExGL?vqcy!~dr)F+rqMgOrSG5rDlckJ6Wg zH|bl9LO576Pd3lYKDC~^6Dw2!#q|wAm)^LwPf`7h%vF$Vc(&G5%WI5wiI$=QK1eJnLk8*+*;={Fk4NM-KGn2Q&HUkAD~x-jk6 z3Z~j!B$p=vX{s2uP5S+!(r{-;*d(wat6oY!^QAyiO>^`@384JbiDd*G# zbrIMOW0su0Ngz*fIs!lSz?=A!PCm(YJ_vUCBPE5|rs2lInvah#{PKFL8&a>h5m)!~ z-}D{k{Dv=jcV>~!Tnc5vuH9BjHi--|st(O8N<68nLwz7(3W5up(ys@4BE1{DSpx}P z(}YKZS$%<11`1Oa{P7~@nh*2Hs44~nne}ZqWCgl-qri zPTP;(3`9##^OMCP_qf*^GY<_PYzMnRFe(;KoiSpLaV-Z0m*u<8Jz2GJ#5}nsp>EI9 z7fhbhZ5@)L@{Wvkj`)C}9U;V`F9gljl<w*ug=!`(SiaoXflixBGLH{l5*w+z zm*Z4d@o-c!mp3014&Db9VD=%MK}_Tlz9GM>_ekF@gZ zjb$?tKA}3uli|AW+s+(MXOz0l!XUG=q;hHsLBhcs<9Oo zHS@dro4#OkVjwGbFG(rtgZ1o7@@ay#!d_`qSC7@+Z)={qcCpx|Gvpajk3kS~HffR-M+CjHdYHog%+p-Y(4N)VU_c(MOiX^XxdTMY$D%jsX*WQ`56KmNl(hdPca@^>Zv z5t!eNKL#%MoS2|_0b*+76je81``ZFlk)l}TB~K3VD*kiIY>zO7dQt$ES;3y&WV^s-u*<)CP0L_btwEG$4h-BZ;^iwuZGLZfq$=%R zKfR?5IkKVO;EHncJo9^n5WlhJ3R6IYm(x?6i4Zubvm53R5~#&~EO!(`xv8d&$o#DJ zfdEC%s$AG7iv`GB-p3qL%*G?bJugUioQ3sUwFuK@;~iNovsWRP0^86HS-Q7J+rn3U z(41@nsm&~o$peq(4|3iI0TXY|YseS57aA-LqE?c5Uk(hn{L;K9kzs!Pxa)Ey86@1V zm&dt5JC9k|Ad!Y%`R)kGb$SxTI;FuL7f=hDP2GKwVtzvz+U;zyF#ulny@xeknY8syxet1sWj8(Yo{9Wx zqV#$5h7FXxU%=Tt;#bE?YI~Eh9Ap1js~Ev$hr-zHvM}P`^rCadY+`vcx!fd=f_8FV zGR1Uc_k|31g}M zuE;7C@$h$OH1IMrf5s~1krjkTXtZbBTpT#1%%4AC%}EZq7ZN-yO=Ve38PHIx4jbAo zYfOn3l4r0dNo$*zge`teEgZ2rhg6zFeFBkKq2szI?20fZ*A?C7({ z?)O}y$Mt@T??NOrFA;(26DnsDy(zYYt4o4bf6L&x_xv%8O-;NObGBo7B;t6jpXNK)gCRejf-GU-~AfAGHQO z>YA2|CRl?la7^Z@pm)^8`aK9rD7lBp^SewMDk~5@TpJ!uoFX(A%Si@+q6m{*I0j;p z?DdmQYN(N>-?awT1t%3gQt`d2^3TcOp?6}`T}QQl_rnslhUi%I1>p(BiWE3U*0tmz zMsOB1x5*Ko(^k8{g05?_v1w85yn29Q5~d=uf8Fa}i)mckvE*xp?|fJ3MZs)6 zO6nq=zBKRdChr*ZuHt+nmg7> z6Xn(Xj*r;%_cdktMD&lfgGf*+qL{PKo3R4%X8ZX;8>mi3YSH#(4BQ7x4UmM&A|MW{ zl+S>*LD$IK845-WN~fb2%~r1@w%$sQLOTNE$*|9XfV0Q#;`YBP$DY+S3)eYIUFbQp6527(^Mi5o=_qB-@NLGGK@b*Dqe6){2g0T{tr9+J>F zh&I0y2v7IRc1@_+HdDR7P60m8MvMRd|LAxC00{q7z}1uk00E6uyc%5q03ZMWCYFXB z_woU20(F#+r@njWItj{y7tvB=!kEFPJS|s8zAe6#y^Gv$C6}*I@zPs`QsLBmJxp~? zrym=0?dt)>aW8ORv?XsIqs7Sa8@+1Y+^Z9_TPML``C$ejJtHr{w_mK!-p)h;%p7IU zQ6*5Eu54d8?WYE&=>4u3NJTJI6~=>+BG-DQ9n! zrrTdeqU&fenQgr#5>2~ju^Gn)Z@yy(miv!qzwOlIY?A{S_Gq~dYj_E436MnbD$f7x zE|1ZHpCK*!9H@f7)08SMvX>|bI`Ze+u(W%ucf|`x1>~4%X{{F}@bL>(6FE#R9A41z$gfVEnN^%XB?j*T&?Esi(V39NNz!Y5^ndp z7V5a9cS)+<>GVhTEP_o$1yxA#$A9@9ZWIH0hudfa8z_UYTNx|WJ+1f0e*B7I@+d-C z++@wa^~#&gSy&aZWN~r=Qz8dXiGo|+u^q%k5_e02DX=To`+k51tP+XYuMvatb?G-H zzg@*%0%+!!hLF*zJQUv)jC^5cm!Y6^C(M?N_Kf$%H-p6V4C8~3g>@&A0kK=_-{x6uP#D2& z@YM{3rZ5&7w($2e-C$&B7=1_MEPLYzvEuhk&%&NJiug4--zSQ3p3I%E&6nzxvuM89 zptVqVy5;`~D)Z|j?TyFyMk*i9?$-_f>ko~-hYOq8WBi!>Coe<8-`YAs80o>h*g|!L z6i-!1_rA@OeY3xPG3Bf=PM0Nfkh+FBzLZsO6H%<_88Pe48I5^KF^jrM?B^b@XPryS zwlD-D4=^6ursLdVA9^wsVg5Ox-xyl3x z2dvm_ne_CEP1Uj{2w`khzdb2`aHO=w9=90aZ@QKkiw?wPW#pxE`r z=^>U^Z&!$sh)<3uN3uz9NKhjUroJGVtf_Lmt#ox-ZOAa2!7oHT`030L%Y}i;B;C1P zaZB{H-1AWRylk82Mlv zfBc>U7Leurr!rRzw$Ut!i6Y zsPV?8d<>kY?@9g3;F`;mV0y1SN2lg@Sut%Q%y!9)GW#XnyMSzs^zB1VY3+%kn7JLrfC@jgDucubXsTZbX*h?IJoR{#+2{korm>_aQzOfQf! zzgV)?ryO&PrATm`fpQ;gR`;LwUK)+OaJtM<60^z;ZBXWcyJm6ISW^PIVb)}a z0sMyqXErt7r^S3s9VM3xM4f9L{;Nb)4o03tA z9w-C8^_a(`hxY6xlH=G|$?BUIlxiEho|;knx7^*-FB#Ad10UQ#juD3$_>j;h-J|$h zN=iaYA>mnr<>&1D10)TO!1~8idY9%^YKZpc2j+uY(qwx!5d5*uK_|z%piC2(ewaPD zSSU(8R4I^H#6fX^F2~}*-bkNxp}`fDVp+|z1=HJ^tkYT zQcI?(3g=K_k5{?u86Kd!AVe{+fp3U`U)+Uz_Hh7RyougJhe);8ImZfTv(Mx(2y>tM z>zC8bYp82;;H`0g1{dc?kw4v42gZIDRPS@-hsSkeJbi}!gh=TEi>dDs)v8u8fyC&S zgU5$P%q5o0^Yc)KDfMCAy^`j6vQ}-cRSXcIK{u5LNh0SD>5FwPHdfG`aI6jmmq-_Fex+^k(pNTqu3gY zGCS0+UgkYXrUiW66V28FaXTP-CBj{L1_U_C$ZjiWl`}1NGK7iG!kd4_AbNxc`asCk zqRF6apWl}QzNb6I{EBAXk-`S0e*R4=zz)=1xjRpm#WQD4(p$_Du44Eo<4>m^zoty}PAMej2zsK|CP}5!bbCsdoL{3Z>9Hc%XVW}kQ6`Uz57c%X` z5AoHa?SfeqELUDW=m~m~_8yk02=X6(tQWOwwZm4pBend9Yse0g>q}MW_AQc(V6Z#i zg43*Xt7|ELn!7!-WgB~kxZLRmFycXsRDhri&qFG=eE3VQGtGX^JxRBGCD!j7Khc(8 z)_jf%iK<2(OBT+LMY7cChais^05m@$MK)bd6H9^D3kO3*&VdnITee^!B2n2N zGeZX2D_d}Z5&tfKa?sD$DH+b-@6)x5mh^S|$5}_CmRu0{9IZ8UKog{d zDb{kG^i`xqY6XcZJAXaJkXwFkfjAd=rnR}yx&pHoohpa#izcIKwu!0%*B)yw1K@0q z87Sm7?VTBH`#?iU{*T-OIR(k!SDbmKlZA#GAOl?GiO)eytx`mF;P(d30)5>YD)oMg zpr~mx-MDj*-xaA5-ReWZ-$5%@UHcxe#|m*Fo>o74p>)h~0nh7pICVGQ7=``w6Ih2- z$xuD9e4nEp7LWQR@Lo<3A+>Ou{%fM6Sg+SlyUL!zmm0FUP~*H>DFm)ewex>MEX4&W+5woz`G0}Xc-h$K zb{$yhTsnSB$AfvVZQQ=z0L=U~#llvMauGpp+cvPg|KuSSV4=17%|$y1t1?_+sXU7^2>;<@ zo5Hrikxib2k*MTlt6)o19U5>3nG*>N#k@DeXclw6Z zO$d4cJx*eeA$sm4z@I8H=A0kOhp^Sc=7`g$SYdLP*aVCSHB|@GZf?jWtd;R{t(r!1 za02n@3*hk_W65aTZ<cy-^%ee09Y_&Zj|P5Q_F zd=)&wK1=YQXOEdeLM!{@h~f$ugh{I<5I~2<+A3#tk)rvD1nl{%Oh|(=?f)+^jt0r9dM-asoG?Z(o?@{xo~@`{%@l1 z-t`hWQudgzB)fD=vkWlHFI31hpN3%~IavY9!^_)plA1U&1nr=iD{c31~)5gY8 z0q=S%GIK7A%tU#ZhRH@6YOZcNztpy#)Z(SX0f12P7dqRocf&5Fh&72N|`fpOd ztTxt~Djl19~>oJf2J9xg3C_4x;?Sse0&_$;gOxYK9{+T8J# zL5XKclsQ0Aom2@|^%C`{<}Ai0JV+uSR5usjsGE=r8GUuB!c5LYoE*u(DYV#-H|h>| zeUvo)KfhkOs1a>|N@)phuV$+!+z}jG6)(A8MGEK^%h1#9^JzV#vDZ(rT*1at(!BPK3xW?gHx(M+n!)wCHF=h4RdKpWGUa0|a zqRo0vObh<4X&~U+-|fuOk-+661ybvkaAL5wBnd6#Fyj=NHv}ankbP3B$tlsqdvu2+ z2gGS*`AM`>wC6rYn6(nBVJZkVU4~?7PozGK&O9-rBY>R`VR|!p?ZUc=+v=O= z%9jV8hOY_|E`)pbr~x0OX@Xo8Mk6796JUDsb}UwKnc;7Rj#kJ_>C`zb841GH6z=0s z+_UlA4YRnxJhr$K+X^A1o3?=j(Nt<9@@Hoch5IdWnGMg%9T=$KHbUL}v4x95k;s!6li#VA> z>{AnkxCIDa`mGT)FnCi{+_}O0!%o;cYWIAd6(;+@LT7gTvyr~g+K^R-1C8t*Cfzg< z61nZ-gXL~@6MaF0GQrs}8p5O5yS7@cdz? zNFh%F=k9m}@ZzpndnfRhVs_l+sT8?agpOV<%PzEAuG3nj@tkdk>NjL=`@yUba;VfyOS7~;^B{C|WR zihf-X$8l9>q`Ge9v3Dl7?V+|uQBh}jmaT0gVAeuRH4D$Xzk?ktv_=_BLmyd@y*@h1 zwj~jDr{oeAwX@%1)g=;LI32T2wU!a4DR!E)g_q=`*7!i!Wo+kl!t#&RGt;)LF?EY8 z?+d+JzuXS4N6(~dkt=B-x}X821_`MLN?2p9l@+cS|30iQNr*faRcm}e#J5jQqD;kr zRv}v|$)+bM)hF>w?mzaO%+E;8DnNrky<+=D2A>QGC52(2u)b}L#7mj_5ezTE!PvwH zHp_O(#$m)k7yTiNm>v)k2D*oNy7?Qx81w93&3 z4M{K+Jp!NeW90_(VFQ8_Pa{RrJl|eBOX)X95lsksak)rnhKl!ZrZVi~9Om0JAL+DkW%pxLnYAj2m)`tYq>q1(gT=-|X%_$qDb%sNk5tjm+QWcG$M3 zuN?`uI0r&m)<72~VeiXegsG~mU~5A)#1KN-hyDl+gaQjK=MA>jIrIyU3TRd8_lBfq zrkSHUW7#zJF*Kz4n6S0^!+3Wt=R^{dU5%0|snhL)EJa09=7u7ZDn1fgE9-*H5h=`< z4ZfBZgYH7@v%r9-SvU_F!l3N#(wmkhMVRtw`x+91(0B0SSi;8>D+vU3v-cT4rji-+ zn@O_(afVh^I90V+uL2A>$GL@6tqi8gK<DTkJkr-zWqsoAqIP7_ZSI9<#aDIqDE>2}8rk?lrfv^ z2-be6ht5d)7~%@8bt#hSL;b6C&Nz!r+^MBW0^RK@w##ikM@yraxr$yM0Xn|2HlS7D z>NG~P27o|_5x038wolxtnJtBEgVl725=hn%crL?ymip|q2*1(U4U7_~96}OxmmnET zu|4i?G7to&F4oir460;M?4U#st^hGBcBF5XI@x^2nXf7&^n;gP3%B4F=cbnf*JNCg zG+;AA7L81oU<~6t|4*oD4Jw?pZAn~N2nM)X7uT1zn3t5=iH~!!_Fg#OAhVKZB}a z1FnGoTC1DI6c3&%O7w*6NhU=#s9{F`N< zmBt^N@Vo}unqcj%@#%e4G!^*vF3n+~CTOsl;|IuepLg8ocwO7!kl+ zRF%^S%^kjQ(@1rQ62Eag44eaXaJ{aVzUp2xVG@CI&>~o#RP6U*b2sn%bemQ1K6ctl zR9MHc@);hNO&WkxrUtC{$WF=N5bf5Y#?w^?Jgn7~qi9f7&mply_CY%KjmJSi@^}o; zpPrfQ(9PC^AY4lYsf?0=xyW4zj*H8D@Of9TV2qae%jJPKFi4nMfv7}5@EqA52>0E9 zr!Sud^xSqfBoN$xkB=lUJ;0KrslO0?y&f=RAjSTMf;MpMee8F2PynB?lxxmBb3zU} z&{S$5ykZOl+0!Stv@Bb3#0H(4EdX#10sTR{*CAdTJ~{H#eIP3{i`-{!UEUmwWk|Sp z(^H-o;9L8sF1!KQg7Iy3eH*46wg*fd+}#Z83K2>7JY})rHwar2)f)H+P9fPbQTNGB zv$?^7c%$!a^{M}4{qWC$-cFptlc&&tl0k**pv9^Zi)fU3 z%X6Ofm+a(3Epb-eE)V1&X?5C;O8wl}GXufUhh`*T8`|Kpa(+s8#21A}B`<1=(+yp5MT_P#Tqd=)|fyefk_A#UfW}!^!|bK)$~K)`;x^6tri7!r(jNoyI`y zEm~;e#ZVS|#?-kS#0kPj>%}2z+Qp2ce=Zqz4)f0Rj5rR!XGu1BrQ`Mh_)CPA`PLIL z10rHXm_Bj2A2#cNV8h|({&deh(FuV z3y!CVyd(vW1XI<6dxIjrZj{yS@k2EHOvFD-TN@91lU}ANs!0^HXjoh$3pIsin)(u?%@A84|9cy||bH!Uhot?|0{K z`{h|?+A0=1xvM>;8Cu`Zat_{eux|8Lt@uuXqWa5HG91<6Rjm)(oao z@z!|Euh4x zA$Ttk3|zX&(t`G(?OU;odLsQVX#+6lHQ|Q#dtb7jCEcreUI(aru8crvL|v^|5ao(+!t8N4gAFW6+`6Ud67! zj8&dA#<$|9jW~NGNcZkhet|c8SQK!Wl+XY(nTof5WN8ip3-5Et&H5(9ki?EpOXm^g z+E?uw<(Ftc0=tTU+YA?TS@tZR7~SutMLX>E=kn1mAazotpy?zS4&`=F8I@#e&p5%A zGIJa|L4rm0ORtMTonIW5E^U*-m#oNUgm&{6Tc9oEmM+mML424pCVytsDZ~wbz4wmg z`UR2>t*ntTroUpZfmB`-wA0*}oM%AzjR!=6`CY{Y9-IN>TY$ocf1cm293il|cz!Ul zmcgsqHZE;KYC)07FnFqu3u5hGB-sDv#GDl&ER7rEvoH)Rut8l&un{H#^*$2HLsfm- zuWscZhBYr4>PxH~v@Wo~Ff#3gpNGeDU(7F?zpC11Y~l)q#D&R7W6(ORX-&nOczdlt z4_^;2e@^78-8mZReDc3WI7chR#u(W-vmVE53W2!+K4zA_+{h8hBD5k_E9K!-&v8uE%sZ*LJE50vtQ>fH_R`F5e^U z=A4;gxZ3)OKEi*KotXuP36!y_GVx=JBKx!tLT6yD=kvw(dd`DMi&NICDSTQ~>*gUx@A3v3;nroY>^ zkwIw1&rWh{q3(tTs1cA2O-M{tQgPU8(E0>}^rgi7#aaaEV#Y3Djl#bqnticNxa~td z8TDkI+4XhsO3!Yun5Ww;ZS}{v{nMnqXYhs#y@1yBA|NaRQndki)0#i_sbUw z?+Ps64JJ=ceriDKnl6wE7?ouIK}NRE#&*ENQE+kFG@gHYq3IFQ>a_2dM19b`W0#W* zL3CaOAXu6B#BEPhDw52WYRo(L_YOwY`Imf^PcbU_QYrVEz3S!Q%N|f?Kj^;Dz+}c8 zyCFSycB@c5HW>+txTF%TPJI>zQ>J(P+49TB((+RttK^xM%I=-90nTfD2+MbVh$95I_cnN^b1+6zIxZNFTZ_i+)yEipxmg;e6a;UNo!&gW-6^Z_pYQ1Oo-pj%)J zSScL-T3UTzfy|zeDiu(?@JJ!2waJ>CYjpuiqM|7TBE$7UswOTU#L#xoW5I-9J?KO} z>j`M`Yexa~gUK11AW9L`XyUQ$jp6e~qUqyPVeG$&`j_Qd?i4^qIw;HfYaXfb}!rFQVr0C3GJ4u^#+yiQ@4nEtOfm> zWuf7Y^m-o6)&n(M?*UBrB9Or7f5^q3IroMv>%}z}#pGvwbFbg^vuTJ2J~nwFy9q|B zx{oPy&LeLoflbx&E#3`!)!s_yK> zBVJVOLM}4NuZ3|PLg)b-?cEd`0sLegbq0IOh8UG#s)w$cTtHn^bLg*+}1b~Kv~#$|DWy2GaX`W8Bd>zuzZ07R%3ctCagXKX+n>ZTL( zHk`&?*jRhmwh?K8piJZlC@Z`|D}3LvVgJ~-SIr9PiUSARzZgNkm6g4s&iK5mYOTaaJG}SqaAmC!QF9L z<{#VTx@Y?~1EAz53En)X_^1)O06FVF9+!SO(4_8 zy_e~Exp|(f>{3)ND6srj0j##d*VQ2Mr0~n2gjR&p1nqDV=eY={1o1@~efo7C9%Tn= zKmIOY=oo7A_;Gw4ZXh=r|>2Mn&b(b6a`GUUWmE zP){qsEv`m|{1mgUEh_!3U?Eg;8rA7HDL%!6Q1K%BvuhKIDJw`~<`!~x zX#`-ereuuJfy8<7oA}Ok5l6!!0X*h0a~T4UPzlO>g-|3dn9kj+Er3n54s4WujZ22oaQYG{Z+ncvb*)gZeYbf}`@{876N#l6oKX~0V z^168b_yqZGm?^g5NH|R+kyu_lC}@BU|m7C3ZqNzinhR}+ahA4D57EhJk#$)J}V<6Ff!4iggV0^Yk+NN<4)M1NKe zV^PK}0z!T=P6fIBA!yzu z+ji3PF@a-b4cSD|wP^5YH zHn)MloHfQJ+Qq?F<(``XuT$%SzAD6uQL)-819*#d@YAiLax!b+H2^O5KBGEeS-_(a zy6r3!V$35|GtPxNrA3{H&t9>IG;gc0GG8W!$O1WNd-{!X@@P&2+DZ@AqgD5@L??7v zCZPTbR}Vt!Wu;*i(FFN)+K38}9T$Q&A{yMzejDNnZpX^?lH4c$VRLNPBx?LV zf#;Yc&tbHY^&1ga1dTzG{G!rx-Nq3e=bpCQ_U|&+(+-z5Skd2jMweHE57U6&PN~;S z$?@S4hb8C|oeHb5_cBMvvd{WKMf6TW^l?K!H%R1njb}j7 z^Bf~D7dq760}lMuLQF$LKHq*t76=~V?vVQd`UX6UW&L&O9AEkea4Za7YK&?1n%h0< zLrlS?eb|oklDd&c?T*@g- z4bdWkQnE^6P#je!S<>N^x5}&X*ROB({e-(;-Vy=KI{tmMc+xoxJtgicJKX%x&WnY6 z4uy7DPBvLlA(_%M3RjX@M+Jjd#~#F3h^8db3?Y-DTKb;s3gA=x;3bA;M z5|LUori6@q?eq?}Bk*?mRhYgNwMHql2U=gT_<|%$T;K@B)Y3b0bG}HT&5u>HsxhBu zs%?&I9T8OceJpomO=54){BEv#MqpEhZw^TAo3S&P6ZLr+TX3;B9cIy>eN-T_E)`_p z&>QdlgT%S^<*B3gT%^*8iSuo&uqbMX!kW9Q1|*-2MHn)pLk)a&d^>aR7RNF>;rmBu zZzT4Pb4^e@IiPXRa8!MD-+U#zNwJ>EVRX98C*)}tk@b~?PJA7DS-tcZGs3w1UMr!!>Eq76RrT5cqKj>D&%yU31HusYqm?urs_+(p; zM+5I4YGLA;U{tG=e739Lp13OPx?X%S_M4uEakmHSTR3zxo?Em&Kf>Ro3#4A>wTv2+ z!3=1lQ=(!(q<++Acjkf?1p>I0TvAuw9ZC0q&%7?fX!c=-n>o8&6Y(JGvUkjFH~WYKV>p z`Cl_y21|$XKhm@uD#dhUiviKXs8Wl&kNv-B3WDReNRplNT#PJ;dCulKa&x%#n>E%X zPpAcKNM$R4c!C?c!i?Wsz=)2V2v6T0W*OoW{BO8tmj&I^TLwTiP)cP@$1l2v9Cv{z z?2QKdx_1r0KG1SEOJ+>`jOS6iiQMmYzNix#$8wLjl*)DTl_J!>NxL?S*2SI-HVi zjrjm?j7p_la;Ss6d;lP*Otgdp;z5DkN>3ai-acf=NYL`;gA&?0q~_U>caQ$$7@T@r zl!rb0EdlUi`p4LWF!l<>F|nOGjloNP*~0!eAciFgO9IuI;5e1-f*UWV9nM7wmwPWv z+>vxyGOPb*XNSGRP~5rSmdaKh#5}hxw0Q!OIt8s4V-#*0WBclFgSia=#-4`#j-(E& zxqQ2j6e><(%8=39`xTs%c`A(3d%R3!$l4f3WFZ{-Km3l7+|$Wr;oTilVCGukbv`h# zw}w~gZuzT(8Wd(`)^WOqhhUr3{DJbe<%a`kHX>#urnBGZF`V+H4d+bN$j1kh+%z4N zMwJ9hP|({k}!EM5 z=_phQlT*P}{xiA=6Ar z`9DNs9-QHn3!~#%2u|LhA#={G#V8$mAr%YSTg6gzT#|9*#P#Ld9(KulRVfQ6-pK z!z_$Qy-%eIHkJMmo^dOHCz>l9{Ox##v(jg@*;RYWDmKw+t`2r&2l^|^?=Ni$2PQhH zJen?LU7WWbpzALKgP?cU&1(hqeoTXGBjM$WKqRFPS&uc=gZV4)`O`YP(s6=4n*e@2 zZ`3Z)R_wKh#n$<8AEMQ&uX?~9kG!@GRJ-|qM)%;YRc$?tgv>U8JAm^PDV4jL{E?;G zz@&rs;NhfGpXKfr0;+{{@mHZEmPn_}SYgen;HMiVabbVYQFXqu4dFwLWvgr!iXCH^ z!5J2YSWlJXx4qf1VVK}QPZXl`wr*0eJNV@$;Kh|WhqY(!tQOI64TlYxT$1hHjWH&b zL;vW<4^>trt?6ZLh-bWXs!Nn0bT1}WBCGdK)b@F~woODya@1I}A?JL*7BPH9Gla3a zpuPS>1|gnjBCIiUz2Whr48u>(i5meuARX={FgT?s<&h4t@^9T=6M<&^F?eJ=0OQ%^ z9M(ClQLq8vCfWRR{e7Z8z3W_Oi0+N1FSm_5#dwu$g5z!I{*GQ($Lw}q8+&_$OJzv5 zhLBq)Rv`_qO3-9yUsr}r=SUh2%{h$%kP&i-Mwm*w;(r|Mw`*uMXRGM9u;%$V5|t7o z!?)+V;4U&#f?@fO`rKvzG+(}wUEZ&ygvR&iqhaIoR0xP^reWqQG~{QO>O5f?(}d3QVpA45Id@$e=C$!t(NjOrlY7fq6O}nf@Z6w?&_T2OD zA>v2)Qm`LhwSm+Vp4VrI)ES_5ufvJ7zjtHXapN~P?Tl!G^_0`azHKen{<0_5Z*Xah zvgddx0_KjTos(|yPBM%E%1PfkW1_Pcm9KNvu*#37;|)^eT34RJ(WQ(d}-^ z6uT8c*)t5hTnIIyU=e#!@;L9BO=!~`a9E1#1fx)0LHfO93FucUJ688R2S6LPP>rHns_Q&Lchis%ILLf6Q0*4eVRQK~64;?h z@Fx#QS$yZd=`UBEueFCEeO>wi&e+CVG@)@Wf=ROtkZlt0q8=w%#LhYd$8TmXOv{4| zB#s-K%t+VwP|_|$pz|t0~4)MX5e@& zg5jX5Ih<3Oky-jxuY_-#6!k}Wm_re49O9`_czh3g$%9C5T)MB!C?U|QpDEM=3a#Dv z2O3|7Zh41}krC+MRL@$H-r!A0+~IrALM|-rVGFacO^VlT>_n>HV>w>v=9cH4iNII? zf~nO$t?W#jdnon#EG6+Fo*bNa`JyOsUYM#Ql5f_S3hxhHU=S(uhuGN3IM2;O3F2Ry z7RSkrT(5Bz2KZ6%dS9mt2BQA~Et33=1F_VW2GkBi_}IiSUar0!99l%}?tx>ckS(AL zpu(mh0=@6JGDEU~P52dSVsH{VngD-sL`qGsy`eJ4oT+f7-z%Zi_;?=^Q4wjj;jVmes=d+61_kHp91OYn0;uk%j36Z*H~o2M;M9b5 zs<*Rv$p~LqE7#inGsf84ENLyCjWQN?S7f0jw5&2KIR}klh=WN=6;LZg{I0$J7)m9) zL$D_sqOlz@@d9y$hxH-OJ?0_L5jaL5`;wm?7g4S*7xpC1Ca+UQ+O7j;`@ykPcE!TI zh>Drlxu53ei>WkRqMNAk9MgRvq!%zpi))%hr|Mp`NOvem>*-XQCz?8x5ymD=-?-_5 zFX128)I>$>{Bak(xld~c#MXOEL6d|-Y)6q+?eCx{)e!9AGH$f)_<^Q(C;54Hme6uh zPS?jA%f+T|`$$ieY9Xytp-iotYx$dLvVQ6WwmA=}d>%7_aJa1q><2qL%&TQx+SVxo zBX$;5;8Z+>x#oq`0d8!&1BEW^bbNu&@4NcbZECI>@b!E4J*MCoo~_23m@=D%7LT8T+g^i2!uNt-Yf@-c%Q$$qItt_I;F8)OCaNkY zw{4VaVb7m+zY`|UtJhq12TvR~!eJ?T_inzYwY)^|4!`e@|LB|>xs?PqTK7#eruDqU zEYz{XJp+WaFF6$IG>~kooq67e8@Cit^f;gl+JBMwS})3l=ed9@UhPe8=zfaQd+R#|A%_N>~^zoJr7@u|>Y3EIp7vY1bB0S&FS> zintGQfVOCv0FTtBK}r_^psT{b(H9;~(%d;S?rsB`daUCe%YpV%D4pH7bQ@*HoMW<* zOb0}X5q$T~K3W_uD;^o%xeeBDb|Fo#nI zp=)U1clNAlM;j^b6b9JZGke8m2}996nxux{Ld~)X12}l4C3ePqy>4vxKr5HAIAt)> z>+Fy2hFRCQ6ZMofqR2k-@w{U)=?<)G-V3t%WWAPkEwV;Cx?$tuk>x(tRo>Qyj2 zL7&LYlJIRWyOqB|$c@Iqe$zlHej0l3nW+CVtJf$r3<6yQXIGPIdPF6g9LHD5-1F)F z4QFB6tpKPJp!56y0V4!XQAn_43%FQ64gPoehM!`eTiP(vDzyD~i8Zu~I+;E~M%l*j z*#Vx=!{33OQa`=rfQ}`T{lMet=-e}b)`TkjD6gNr1f`Qjd)Yp40O+?J>llki6H6bj zMcjCWKJJiAHig2~KvxYgH4`x0})6i@|WIEF*#iL!lMtejfo#}QYQB#+4|{enqu zjD%PYlzk`u7%rPCyHUf`&90+N&0In!+4wsrD zbthdA_0r0R5Zx{a&;42dU>1}2huYOAwSrTB15VD^hVXx8O2Ke_enl6C5!R(7n$%6` z`Y0n1>#Jx5YB%r`o`x36#5_g^69{gAVRX4+9hHltDO=m<8aZS&C^G8!GwaDN!9PeV zD*;S$NoSH4VbLC1e&KX6%5PCxkrV;3VcMcBj|1O}_!H0z3-blr{HZr7sSHGdSU~Qd{a0 z%L|{qw!?YE7M1`)X#GRwRngUjgU9&m`m!AO`{CQ!=bYPt4hTHu_=P+#(S;cDBLqvx zoW9SG3}{!531j}5A!JMh@U}>_gD(_E9;N-tbe#Q;Q~J9#UfR9^!E?ZD*=JFb^#;ww zc`9vILCI^y-Dw0{+|=)GK4Ym)pF5VB@QUvf*zi#Dlm6*Wx3F)^mN_W2w=9PM)w7+A znMMIV%79x^Jz0%2qQZdIOwi5}ZA>e0ibkjkwtAn|LFA{~~uI4|u z3Uar7^hSa2_eL7$y_0g?+S2=mm9W-$Vnm1DDjC9Ms)tXj6J0@m**){#0RdQvlN6{hB0G9@7RF7_ zT|@5-LGu17h|oMa`E&5!4$DnV;8Z9@-O^d`JR_WvixUGRSwc<5BY{KfZmi}kzw{v| zLi_`D-L{DLL{7xe=RnLYPn-lWw*7w^&(e%Lh%(l0;ruTLXJ>Sr9EspLdutwPUeS$J zi#ob2Id#I5dLo#Feuw?!(r!td3buHp|D2J-v zdBnqWCc=+&=4+bbTc+5`6FJ)8ITxBq$1fDegd_Fn8o931g4zRkYfAPuvLjJf{)$%&1Gh2bOaxsQFr)H1-5vI^8 zufnAhoc{5pHP|ra=z9vv5w8m}WF}1Y%bP5Hy8gR|)&NHPg=)0@{lepoOHeC7oUBm0 zehx~W8+KO?BIc>3Sl)4@VJnwWiSoyn3Z)Ea5`ZB(PqJn{?wnN44}IUKZsm2HLwCv+ zh7Be{987FTt)3rZ2vo-0pFZsf97$tT>MoYhZ`Z6dZ&>(hY{((txonF*gVUcCls$%? z=t#H30avioW6$eiT5Dj1Ghl}MEEy%lA0NB(O9p`_I&-n=b^(+c6q^N4IS~^dy|>1+ zNZn2-45~aJ5m{5j0&lo@i8indoqF5&P?|QcR!REA1J{qTq!bo>=9YW&F1(DUWb~re zdAOFlEYL*N@cUlF&FE8u!41g&h7%wH9m!qbkWi|hreDoD2>mF?a>OcOGMuh=bJ?gy z7{bt0q1nK5fRx{M%&>C!oqa3LlGh(+u^+k#O-o;+o-b7~{@0hHRK_hdMrWa=6VuMW zxTblRxPN9^6s?pJ@}CC7v`X$}ZtZx#PDseOiDfO%$Tl0q6c7t^LxDG-(`L23Tn~Ll zA6C&GCJU5x^E*Iu8vP=X?%04bDt+zCt?9+L)`U3&;vP!! z?OZ3?agmMF?bEopSe*H?S)33M!VXJs(zL#>ytYpo{g|;pf{z^9uFE-)-z^f!$BO8f z{&j4=vp&<`i5S}j&X&~bRan}-^derYg;3a~$J%A_C~q@c2x|Bhzajo}A&0o~riSYC zW2`xkiGjvxlbfhZg-gKNKN16?$i0A`%Ggr2OX|X@ZSqlf+%emF=U+&T;;$XZi zZQ=wZDv+F_oR3gSf>Oo=)!BO)`c^alo2(aM5b@)Q@__rZh70{T1W8*MA31A74fyt* z5yG?awn@%gAuwPm%4_2OONg;mGvyj`LsxH^y=!)Qv(QaYyYB6PBp^^<-mg#UATV# zMY|Q~HI$7X*v;HBN8azzkb~UunazJ=@&tDF0PV8?hFkXdC3(_3mB~e~cd;l_n18(K z;!J}ocv`m7>!m znj0I_`4R7At7C23Kw~zrqMw&PR_~ga7-#|qZz&D%F1x!WyZOF7PhY;WE0CsPzOg=P zlTN7-m_aM3c@E<3)0lJWZA>o(Tj96O=E|H1Z&IO5-&v>;i+i5KAOr9E-qmkL2UiOn z3zfoVnyKk{$_ng!S}LY-)cf6ECC|7ePNDF%$o@NxB2%Uyf9+`}1tqsym)EuidZHwJ z?+4l(G=foW3-q#frgBTVXbR9AUWCf`cwfRdbM`RXS%YnR5@reG@bU_qRkhKes zV>YFT4_c;*1sYrr+oCQx8O@qvP}I3QJnyKO&c`9fN?;`9#u3?x+t>7(o(pC4+8>h2@^L!p47#NvZ`7~rs~cF6n~>h1!- ztTBOp>vwkSG%84p3eK6fa_LCV2SI;W?}5zlc04UtP~EDW6bb=c<@lw+N&s?EiDGt$ z3?eY)v@n@)H+M8`Cw3-^f3uA9-Ay-&;ilI(wkFhK$;>5dh)s)d|Ii+U#nzsK|F~bv zb7PZ+#nrqM{;0A(qEwp}&eWhkI>jKZBBFj3ojhSeA5G<$=Mu*96X~T`>A0)*35cFV zM}XtDtJsGd42}DHA`|iYLXG|Y6PPpJ;Tc}{?3&W9ZO&Ncz5GHoWg(p^HXp{l?cI9@ zsdj$Wg6`LLmzP}5ClfBb8C&eul1nC&W`C`sK&3%iR&W%?g8KY}ghQa1j9MFCHWLvs zSl@!%HSf)VP`X>x?GC`^oF}ydag$yhTYM2O4v*eQYQC`U8^2*hr6cXv=T}SdJXB7j zE!2AOak5GIHEG$(>9?Z*3||p1Cl?1hM5Bx1-R$S^3`vt~%V2RLe9Zs8^rsjuqI$x8@ci2App|_qlY*rVROp(BjHWUW$@D^QxeD?5wjj%? z`S>&BP;bXvr>FC`b2yjI^&ttitKdwdnpW^*Ow%b!nQuGUcM-j+`4}`G%F4Oyh{zcs za$8Hm`YmgplX~lxFD{mc6L)7(N2BN;nn^={ZgoRK8tK?KOM<|<8~k4yIDTbex3CUZ zqK{tB-tFKt7&^@XQjcPf$!1-g>FFJ%e;tWlRnn%$q&?#VYWpm;G8mr-do*d}3jE1W z5#307BsVr=P-p)5%Ke%PQi4y{pubDf97CF3_Rk{5Cj`e~^;U&UxPpbv3mv28fELH_a zU0l*(wNCQp9w=5_3?lBB7yvD5kQ!U=^|9IK_b52+jy+dTBps8#ojn|G*MID7>x|2R{mB%FR>QtVy=aZM`t`dV3P7%@#xv(q?1d%o@fslUo7h zRA#_?H@QxP{s941>r>TW`w?pbvo8rat+iQp@ioxZw-)TBku6?}j1Kr@!K`Opcd)Vb zFCBLh^Q8{RdQQBaZRb;4!KIsk?=Mi`R=Xo=qwu8F8PnRuwy`ppdBLZqo3S3?H$(d#^im6n@#V~sUb{! zJpkwl1Ft~-;}Xp%+-{^>j^5_q#gdp78&CiK@7J>sMCjw&1gg|Pk3v1Qy0notYO)O( zserEX!nTd!poM@inc#nc(<3kbPX+psOJwpFU&Ng5L1U^M?a4xPq8!1#db>X{AYTsAxnLEKDEZH8aYDec1H6<)y(@%qV#A<}KRWsDWOEw!%b-yl zb+-r7t-n5JGv{NxA}pCJv^FWsc6pl5l%kZe5F$!d7R&&mjOIMTiU#g@Gy=`N2LfnV z!E9u?(my=sn`D&a{~3_}=rI<1f}TrhO1oS8+TIeuUd)_-N9={iEbs#|O0$7uxe)CL zdZ2Kd5Cc4_I;@p#ZHw~)hd#hbZ)+%|(Z2=}Y_UIGk0I~`Wd2{`#|mdKj%(>JQF<3U zJKqEk;2hh`_J;>$)IhJ<>CI`S0RZ_?8T=X&Sd`q5I3C|PgAs%S7#;@d6fFd+c<5cM z{Z$}Yan8)o%ZG=17l@744)Y*g zV&4$F6qO$mI?L%%M~{I9>1JB6zdIo?R8FR_jv9)DyZz2YgEJ6@;LW&tap~c1_v>9| z`8P!5s_RUP1nzD&SC`wA_>xEP+tC{_o_KKM`L+0r7OW7Tje(r$%bH8WGmwJ4+OjX5 zhg2=14da{~nMl(j7;NztyEW9SwC=7feuyz5;j(}CFxC$D5Fx<^Ya#b2phR%Q9}-PG7w1e*Xa{8OYMyv z)qM97^E;h`T;te>pH}&)YFw=wV{s(#<}pV2`aL~raS;Vlu9ZN%&SwQ}(`rOVM#= z7GT3~8yyG~hh4H$?2O*Afr}#bQ`WSZ{hE_Ih+yy4Q^q5IQg^L6_937?H5Of))5`xj z6l9T;L5qU!+N5sC0;s}9Odfw3!HKMZsx!p}&~1A)m;mce7z~q?1D-5{Bo-TA9bSew z{zU7>cf|iA*b!h0b3#n+s-quScQu?A%)cAAH9llsj&<=k!>@70imr>spJd=jmU1d! z&5Ve!@l?K>$49@jPjCUg{kq{H+h)?hG{Hkb4f5vpG2XLv;~YuTKvVK_8=oT_q9br* zJ%BKyXISLqdsp?U>(Sm)un2KfF`T1-SB*FWykaPh6~KEtHeV0wN&g5r|aX*fJESW#baE1>+$g8N`ndT*QqT;vF;{&<8n zaXbh||61)v_d;mv^QMt*w@}AJk!Oe_>*jg>dHMsG9i94C1~`+}BveNSq>^-QmY!fR)fPr1Lf5nx~$?Qu4T?;9W8V9A3|@* zfOr<)ZEE`#l2HwIq>(>~HX5=X5J_oHzD0>^^-;k3t4`eDim^~D8_mBPsT<#4^mA7M zPUU}lkRLQO{|R)eMra4r*ufD5GG7-b=lO(906d9ck@ujH*$alnWNi4%ck8uQDQirz zLWn|zn&q2-+@ClY{m~b!1SvlkQbvLYR+xFKD0{iCUBS`6K)+ldAL>%UZeMR5!DP zyTkD>K^$Lbp4FU{gFhOCr5o;0X=#MUu>2gj%%jLy%NIRt9o{EkZ+DcUq8usvq(d2E=&9U-6#{4gEUxZGW8R& zs~n?kDS?5G+kex@g;AVc<3NX}cnDe-0W^!1$Qlo13beoO_@_%jlp^R?k&QLmxj_f~=aoSWTs+SkjEhPGxN7qn{K-p0=crp9UYu06% zx+*8`b#Nqf+9k;*`N&3zYGXW0?fTrU;B;RNClsucbRPU2zA0VaV2{OrE4Ybw5ye8o zHHGRz3bSoNPCkO9kH$dco2eUK`@INTGa}mc8FkZcgR1=Lc>{_i(!r-az_YLOa(^7M z8=$O;6+OaiwE=%_8^%V;N+T=%BzYFR@WFB@dOfZ3YzX3*gwc7vAB6ZIUs6-a>`s{z zWP^QmEt!&Uy1~>hrxec+FhwTceFRIBYU5*J;{Al?juUXdAxpVIo{|!Ur zmnLoFk#GPsBSO6XyP<~4Xggr-XAKF&KnrxUxmR<5tQY~7ueANnQd*e;Q8;7bbsgCk zY{CTA^-5I`Meoga0{~h~%+Pmd9ORZf! zRTbqFVdSIun|bkEsy=68i0gkV>j8x+`PLbAFV8Mg(+;x&CzDF#XG&NlQU?fX--%(4ZzKL zRxM)eI|wy~0g+eXa8`Ga&e^+QKtYmQI3fn28|t6p8JRd1E(@p@;HWLv#~-h;&`uu6 zUD)t7EI=xY;GonmDJOTd&mQj3-#XDNi8JoDCsTr6z9Zf1;1?qaB$Fqm<7oO)~5Z9nx=E4btp0Zq2dj7W!54o zw*l(o`q^Y+AvQfH1%A(xbL^g`jpiz6Sbx{XR{>BM*wVcjp*Ppwi z8Uf#XztduRz8ks`^8J{Ul~8RmBsQ%_ctul4>UY~3y5Jp-um?p11k)<%n*{49ZX3{7 z4KrAPmHSR7H(2snR~chcsZz$V_E6*7@lCYevrK!-q$Tuw{|0byZ&-ikB#gd5_=_&g zt42$qOlKTFosz*piJcr;lVvKZ1p9nT+X6g-3b(NhZ=0*ahlbTAoKT5Gy4$khs&env zXdwZn;AI=h!TGaF``Kd=PxP=u5XqH0OKvJc7c_~ci4QiU%Cl2*Xq_()8>?o(F6pgm zY&@gwoaFT{^upkln)-HAW%Q{%+VM0c-lB_bmB4ReXoLd0j0nFGt;r8}6JV-ll~)AC z^TS2a7MIi|x3dU-qHyO0u#Rz7S5Y`g)O53dv8O1sO;oF6u~d*nar0)V;JKpa0{Bitt*15D10E}0ie zrX6_uN@uMSZ%ZChlDt@GFM5TGN>cID>4cae8qt@-^nV)s?WiL0; z;0AL!+uQ(P@M*Qo>X7G2W@vJZ(r{Wm#I1wp%>-Eyfwoz$9`$jak#I;E)uWne^DRzH zv9eH32dw}v4GhaDyr7X-k`(XVW=ozQe?*WBjjA7f+^aN^_A{jq1da%EwD3k-uE9w+ z`^pCBBRxS6A;rMEceu`h`8nDF063?|da2C_r7-KOKqxS$i5+c!(&$ZVsXjG|@1 zKZ5zey0f|H4vU+7BS!P_>J;wfe!9fWa2e!n%V@SII|*|UuBTZo^}?y|F^T!f$jl?S z8+D1^yIFMQXRI=(J#o+_*6tyBU)H9MWUO&;!u$;S_)gsr&@G+4B!3zh2Dx);)Y|~F zg%UR8Io^P9deRn>Qvmzuz-Fq_QSI|GvszT4-Wg6OH9)S`f`dQz`kC>d*|}~b z07pQ$zc1BU@NsrXUaWT&X{qE`9z-YdQ2x+*eY&nWo#q4nC$SK-HVe3XEGECzVAjyIYzFPl^?P3Lu=FJ zFDIBl0qae>F39}}fd{{rdY5%fonkc$GqZD$0GxJ8 zT&R(-5XmGr4-C(WEdgcIjd`EmGp_v;dQ)IUgHQ&-P}d_7`0%yzSV&;nyc?)!Nb5`r zH~tpHQ43L)wTy}vp#MRnxmo{ozw(?l~8o6#xK)Qe6ogy zCz8VG5ZNM|fR0RNXAP0;?h$I6A8Dy5ET#*IUq-CDexK&OgSyp^bpx`^rT`lk9-4N+ zvN+iiw!7XNqhwlt3ArOcv`P6Je%lr5 z6xD8pm53=r;RM?-^;Z#j>%V(A6A`l_)Tk(YfBNF(TsQA6W!rf)9Dj-R&rG$G!ZgX) z*2Pr7vo5Ws6cmC8U_Q}d}08Z6>DYs5Reep8BuKUF6)=Z z^jmQ0g7)A@(7RCrodaokvI$EpGjJ4Lm>y2n?sqznGMvG(V|y0OWWvG^;{hhbZ3t;_ z(aL@NHYqjx6wSbcA>CH^U1S6C2M?vDbbJsvK#~gXsS} z22X?R<*nosPQTaCJkr5?<)9IKeic-#Xp$v-7&3ULu2=Og5*Lwdr|M|8RxWO5MFh+|nC zW3hWaM__lWcq@^RYiidzHs%LtWOBb($r}DI@6Fam##W9rW&}f7=KE$}&YwPsD zrj^Cgg(T$P>jVJ2t~q%%%Ccgfk6}?)0QTeRXk|sjeIou|0f-=C0@Uo?nZrV*G=rg_ zd}w~Vd4WND6=&+Iu2jMt=GAJ*K>7#d)gZHqRQPez4qb1iYS_D8qnCrP;wP={1k}mJ z*-ck%%3<#Zx_mVetdzHE2mIcw7JdCOM>K~G-(DyFaof>;-hZ!=1m3Lh$u${yR6m*5 zHIq{7CthlPCjfKI+o#^9)VO4+r#@fr%IpbYwoRN}Ry<Q-g(FTIhnd=98HXq^`U9+ z?%jdIHSY2Ya^2tvlqN#JUzy0&5q*o#&i$>vRgUuqomk1vXIG}&T;rhR8G}o$C`$M1 z7QOJP!Ie0XIus1DAy{O6H;df-H>*0RUc59$BJ5{gE1RDiw^2J%^GhSLx8S${3vQ%~ z2*}Xx^J299d`Te~A3Rh&DZduHxKbLr;1ib}}(rXiO2 zWOC~M0yW^fyG0N-=dD!>2+d`xt-MwP0Hq8h3@Q_gEGxX^Ux~+IWf^1QYux^mhHwnCQ&WJiyWXeWI460p) z^09uicHR7q$re-M$BMVkKaW)59+CQEWXUU@+%I5mv5^KmyOxIETu1f`a`$T=Ht}dK z?1OBX@n8Qobm=9QgF0(Ahyv|Ps<}D!A;=_(J;C;#W(`gx|-R+E-iDi<+QG zKOKaxohStmUOCLszxXZ@0cuy8`kYBtq{Vl06_xAYcwXE)%DA}%$L8sPb^EfvssqUZ z?$q$rpuaXtr=J!XmFkzqd7s)@j0eJpLhT>;IpOeM`Q=zuIlTW)J~RCC!caOs1A2wf zZ(fggG4~_m54XL3I!N@W0&u$1k9C?!;&LYes=inRDdwUxD6{17u+J9laQ+%HxyG=22H8i9)W zAEDypTH+kY+a!)CkQ4=&;rsqm_yi(hCH}Q185|H4QMZWsI@f(eQNt8BqV7AIw9(Z^ z(p;hHGxN5wUaI;<-hS7Xph+0pn*}2&wMo^*zyqe3b&OL9JN$mg!WZb!fTpRr((loi zCFx>v59*n>(a|>$Su|N^+|_0NcxY_PT*da8EhkS)?!mJ>5Mwlo+`KX#n;u4|$hT3O zrm9VDjlto64opWeCQw$ZsnDIPcLj_V%zEeH`-fa@hxa&=!8*8Jf@_K_qrZwh0H5i- zz(MgLHaus=o$9@UArLIp*Gq|W*mmPM|EaWh4#JET+O9r-5S)(n1*xDFB%ZcZP30Ec8(rI1IHnzefRh>5i*b#EIP(T`dVC{gzbJ3t8^Ly+rA?yx z_;9b#<}jbPp}xh))$T!bLa7Zw+~^55O^7|xZVa!H?pLY|6zamqZt%q}OeY%M?FdgV zl9C>((;t<+>n;zsqvE9Any6VKfrKQiA-i|!HfP2Nv7Ps5(xRzkp+R@H`b+ya^ezWJ z_MX1$p)K?940zh2VnQF5M||))QoE>nj%y8@<6IH$Fj0#kz=o}eO!^aBQzV2_K#W;F?zFoYkfTEL(fd4W}yU}TRsG{s{)V{=PtCRxDBYSvn5$%|Hs8Xs$dpw3w@-&IZJXsYkqB0Z4U&GQfc74g3Xm}=F(fwe>;F~H(mk!rwr0_r&Jv_K1crab z&)L606eeGlz&Ex%2>4!E@X5`END%1WqTh1NlYEy`I5BT7@P`i)7dUbA^-S-Er^o-2 z58xBQ-qL#gFZD4(`J}gAMH^*7j{g!E^gHfZpv-J)ay8QTl6md6kj*sY^YdKRLZ6M+ zy_i?%+fy=R?xU+)2>17C{dG{K@!z<>{_{BI7q}?7fnVgu)hgGXc(iZ%6lh(0dEk7N z8X#P(Kh@=l%45BWB~;L|5#>at6@0GwC@GBK6wqGdWQQYFQUtITS|1KZ{pC=!%(m&wKdSYZOX=5|6Yr;HaWB@)o6osjJW z5^iV@(CS6J+1{;B@6|FY6N@&vy4vc@gssDKf0?y!^tpqIf6;%t;!LK4=@T)?B@kan+i&_)S-6d)F$ z7g+rRm_5KLi?7bSky=dB0+xkqGCWyCks^R2P<(}D{~4)|lq+R?>ykW%$g;)!S9d66 zuhq*;8L{V;9t0D|aAAMVw_o%l%JBN|u9zDhYQTaX6jK&S`Ao1s069oxTf9Vx;kaM6 zq2QFS!+OyzpI}!5DCDg$=2*5 z*Gyj#mO04?4q?~M8!SHC>BUy|4I z5nHSdI%Y% zwppT%zO?TMNKNU<^d-;U7UA`g4`GX~2XxFrSVFo887ttW=t|%s9HF~b zqbt#EH$;&(IV+1v{d+tQJ26*-UB;*sw=w~&Y-IR&BGTfAOkg9ZYBvymgi{e->B}g$ z!~+d_!G~pzl+eBOS-*iKUgKuW&a1KQO0L=ju1xuTcW|+=Z4F;@!3B$XJ<(oM-sN=d zw$jB>6UPNceUWqRXXNPWs?yk0Jz;S$+^rZEEYAF?J@LmSVE`H&j5!eV#XPLPA-zw{ zJEwO)k}0+mWW}72ul5muhq=jHaH!oLnwaQrBYn1%V=}qG!eUG&sKSNsP6cZX8KedE zmzONSp(WG+_RUU4A9_W6^A5+N@i7e~#PNn%W5AJcO?e~ba$)p+T)vN9Wi%e0J+Zv~ z>34OusUS1|(`Es$h=3Vo{UNr__O~UN&bH)c8VE`n&dZ$P^8hB2^l6n;hD{7GoH(%;pp8GQ$q2tO_40ulz?TJD%2oQ z`~2???UtOAv z9yp%F%ZqU=7&2M`mJZeF0@A5Kv^pA=&a2FC!_+Q z3@Z<^deV!*O!9VbimrK$#AM=PDFZEj6U~Ny%BVKUfcRDGSCRkx?aZYg&LBmuZL+*O z3~M3D744c6G__L)>OP)NbC756BU1%%w9DAC8%J`odid+C$|3TEAz&eCgz2{cP9uZW z43D>R{M_c|;Pjd%*ukg0MvRFzNv!b8OtYoX;+?gyX$Y)zRRKy$+k!j|xq-f4X6~k| zS10TtMU$$p$2EUnj9i}tn=t<9$i(Dz3o#CbR@T}L;k5XuDpkjMFUod&_>BhcevrIs zPdA-jmJtq`^V1*F`S{~zju233MnRzfKuSfyuO>?2T0KA4gVw_>LdeZ;;aU|cwpi_q z_zr@mk`yljZ6z=R?2^^Hyo=-D2NM&xWMZ45P+R(ZOMD&gG)%5#bWIAyZ9J| z;A?&%SnE-uc;1t0b4aK!w13#z9uJ|D}>gJe!DtsO{0TvBkVv=UsVp?iz_0_Jo}6JoE;{#CL>no;$x zo@G;Do?DHK6+1;!K*V3I~@}YEqC`2@bF0cx3k-J(* z8YAj>^pAd?!}Vslujf+}H@yjO?PK^62tWpBvm~Y8Q(rJ{njpm|pH{S2xQSZ!=7rYai1#+1>l2b-1xqNpo`<|ep*WTDTF8y7!lQed8pUww)-q!n! z*7F>^XTjMhgdgewOBqN$^W|;6FhYQSz$f7zT3Y$Iqn23}qbX11vwzObg?%A+4Xec{P3}BI0F{g{8Kp#1)u~&awn}uQ)(#XO3ORoKRq85$GsX$HxR0_NU(N za8efmHP)$qyD~AS)?OmOQI^TBgW%a8w6e)9B43C>gilupy#?A3m&y>Vw&suTI3~v4 zkC(V+zVvQ3Gn)e`0fgMCrtoW6i9!^vyc2MF+2i<06eg6;Hji?s%UuS|*TX=Mla4cl zFU*1}M)$$orh zs){i2H~f`;h3yYJfuiZ%sd9D)AW9sbIu$)*iB)}Vqc|E}L#-R(qaP6uK2uU3Nccd- z`gG6TvefQmk>xG#9?{V;iZFMMz$9)jqo<$k6?@Eg2pqCnagm1U=cEY+hl6tUHufZJ z5%DkxBS?bXspbzmX7^qI*Shl0Giz0a9y1pUP2EI7%<DDwgoJJ6GPI63tYUlfO z_~ENA)b!+-^c<_~dUdXMWLK{WytaPOo{*U?j){r>AIma~wD679uuCn6JOG$F1Vdyz zmehcZn3UA1?tkF+LMBCAmE4Ya!WOinkJ@93Y1opU1BUXIYp1P<68=Y`I+*&QP9q{D zMABw$Tk)Rb#AdysYY-}4!%pp$(|YP~xs;5L6$iA!p!rR3KUB|;Z6P8s!Jm`OqPsaI zK`}ZkSS$4z>^(rL*Ox-5Xo|(-d~WA&$WGeCJQxyhIDWB4klyPQ*vFeg{A{~@xDga+ z17-aP;Y~(wOaY+N=yuoV##qSI@Fc>(hUTisKUU$#=Wl_^4|pdw{gav3nbSb*`7A0o zF7;8{NkzIj<7`G^uBw~c&ks86sv{U!imzBLYX>k|9z06nVZylrf-#|lEnr^ePC^#g-%883&dX>uga zS2Dl=ssT5NnPHZVDo|zP&EV6MMwtqb^ic8CT^Dz2AKoz&$C<^+e3^v#=}#VPGGPr$kAwx+3W*#t(edGO~k^; zzcVElPJ*_J%wfDzKqYvgS92BPk=m*dczaVgZy~gj+?xGeho-8>uBV zNso_p1wd?cyr2}gx~|J{6u4iCVVof-J9qo zOk9dP&#J)`DG8hf$4yXGSqjWiUhsHrdZ76 z$VAf)^w6hCaP7>Zf(CILXpcVokE|~B{o{`5F3*IEHeY8z@4 z5oB%bBrz`QWPIBP{?ge_Zs23T1VAYJXhcQJp|j`7`_ALvn=SHZHpcnoM3tX*#<<@x z%ckF%&EOSg=zZXvQXRE!Y5v82tKc)G=X z`k_`0W7gABLm{rS?c8mvNF`%KQ~}paW^bMOq`TNw9lv3NSpbq7)&PUo^XU${f2swJ zHXd>X1BJ{q#%_GS2~pD@35!p$&b}aJ1#=JH>Cz54yhYrM2oT7f2T-SPcMK8$pO2N| zz5HH}#5B6PV+6D>`+Z>mkpE<=$nNkTW8@PsMVG|0Nm<_cd2UrCxs5}mSMmeE1k;0y zgXY@I_)RWt(H^P9i=v^J3)_dfp)#Nr8&cMNn?Z%c4fpiSTiLzWo&|cy!E6-zsD1B7 zoc+sFK%JvPh(`02B=|aI=Gek@CXPRi7W~i(#-hq8K!xjbubp;S-kiy<{`)Tf4ffU3NCQYRFJ|%tcfH zm;e4=J3|_HB;#kqznx>y{UmD8Bbd;lGCuFPXiuT6xrH8z8sMbgbUVwEpmjLoT+Y1d zVWq__B`xQTTraF1V57j+Y&!Y|$u;cg=*-KwCe+d_GQ|xJ$vipN$qaci?>B0M=o7u< zGF@-n!7V20yJSfs{b4Jk8>6Co->wJ5bI{k#mP!_r2<(LrasD?F!X^qh-=3OoG? ze-54I5%`AON6M3mBbX(v<#HFwW596+zkZP{dxcQKsII3zoBAFBNf_koNY}5!Ol z$yf{tGp2JFS8M^H(Jvq0wzuHgvhU~sch$OnK7=D2IHsPzzjtis2mC@7x!+jWjF>z! zxt9q1LjHAcv?Uy-l9;nHJ^Bw`>2MaItW5%90LSZ+X9Tw;7o&g|DbYQn)y@yuX`+oa zJ9>&!&#w`#>3Y@Gw^|a}c}mFAq)#TJT)~|EPE0LIGy!2z52%EB$N*-r7_zM=!OuTO z{gYUm)+${Hc&jeUTBeY7=kzpe&O!~h1u`JjsNt7h5$sS^^L?;+m>Yuj;l61=Z`MS^ z5D6^bUyBvwEl|8a8foYov(F`}y$LiLAi!vJ>o27}8({bF2${82KqR95 zEC4F!lTT|P>*wjh{@hI+PhII-WL?Mq`aAr{V%aDPcc(@%J&@G#PgVA~D?pfx@^ooG zRQJUQ9KT^H^t_Fd*^gWw8<&e*T40LulSYq8FaP`qjm5IVD*Z9-d-}8?!voZN*7#i9 zi(}q3%t9Tuk=uG z;%PP$AU$rBB~q(ib#4aOzNYtntpUUO(})*k>xXU0x8|7@5fqV!x-(usu=2{?{Z~8& zyXr$k%CC1pFt%`Z2OY`Flj4hM2$G&bA=q-xB<4y=iGlR%ZvKb$n$|;NYZ`)Et3&%g zI?CQ;6UmSW2qox_z7S^offZIIo5kW);sR*;-!4_FdM?um$)?p`51-$ zTg?eiYzOroe;^H6CXnDjW9>1h# zh~s1x=;Li@aGZdKhFt8mGp5q+IK|eG90*PM*Df?HjGt7?+K&X(sc%?{D48_k6z!7B zV>-;bLin{ldSr7cI&uRp*v0`$OOk&?M+&8M(3jpGLc$zB!Z+O0LCTC ziDy$5o~g|&*q>4$;30=CxXG`zzGN4E?>s;fI;v$*!>afq(*3?;W`Q5NRw?m361G?1 zaLm>GCXSFwLB+?sw_2}@4Nd@1r30hKQ)cw)(aMqYzS{Ay<(8kj1oDgU*SK`NC?KyX zxEQnVK>CW&aL6i=>9Pw^JSyR_6 zsc|N*Uga}|p)YHWD4XvR0yJ;dD@8FvBFkX~S#?LGOCk8}B{*j$fliH=U4192GgAY2 zK1Q4N;p<^MEir~~S2qEON=tP7yQp(B0u)u=t6wn#JfTk8&C){p(HQpb4M%lb6gTaj zG3qZ9%>?_`jE7d78=8VVZU@KCvCU zIpHUlG|dCal$iaQzLsbThSj85RGoj+TQ+*}z#d@3F0`!lls9lsJQ&zBH}5;zr*upN zPMVG5^=uStK`nz&bx;!dlBXfN5h_YM8^f{al$4Ae9Tw>{piC>4KVpl*{}^%jC!>V$ z^@lg8w%LC83%1y;n%t#fEbg_d+Gjx?6{uh>3k<0?qDNQvUg*(RfDWHQD3^3No9Um3 zR=b8+@pmJkKoQ0hzq`Gxx}?3OP=(B6v^yL&c8Y-C;!qEVYSV*oHeD`zIcaKuLG+E= zm-FT-6HBBGE$XxYaTsy3pkb==F)Ic~MI$lUlq@n@q-2%q$)> zMlNAj52>qQ%TaN;v%>CG1Io!Y$6f1 z$4kkJ3lM1oYBf{T80BjcnyJ_)3UO$c!Pi%q-LCkVZz!0WT4v|W%m@*8XUV=is4Ic- zUE{NByq#{*AKqnra$h+lzuiT(K!Y|7z~sQN+&Xc?OFbOWT0X)Z2t+9)AS)g-xi*sv zPTD9W)F=TQomZK$pb%s1z)&FC-G~*QFIjoHi#|<8q2np!@}aVIF6xS=c`;xMkS%Fvm*MTSMXK~5zPAS* z*u_HKmky$g!tMyfI7defM)P7zYn)mD&k;og)h?kb3!7^7F9&r(4Pe~1b&oNqKacu7 z7fVF+{(vB?UWMalnheM@OOc%y3duYer{ztZDK_QxroN54Tb*I@&=4SSUhh)!EYkx8 zT+gT>4px$OK80k-?N*)sOtUjy4AQi{u!hyx7phTQBFUAN*xT)vKMSRE$6>~l9sUZ` zy4>Yitsz3btJKQ)byUfp^*@l!kkvY2rVkX(pU{P7Rs3Z`Gvz>YfD${r>DKDPCdPA$ z{AfMYQ=ajOGey-qeKUeC*+r5tMNF)*#O}nRR?ZHRDTSkYH85pKYjdPZ0=*O+%#tQI zNg=bDP+RCMxWtC8)CbF!5A3%=BJIl+Y1C1;jINLPf&sItJ+^!><}dGTViEt>`*Ibe z(a-e@or!+apc5u=(YxC>4tnC@W(jJT?l`@P$h;IWvUb`u><0!aiSX3#Z-s+!ZZ9;H z!YIXXt`W}H%NA{_IQE>)8po#mV9ignR&sdZyqGBsT*^EN+|;N!t@lveVqcYw1Qdt6 z2Lb%x^sOv6b(HXmc)x9i;Yt_lmXYAt>sv9KE&c=TBoN#RyAIeg+z{>|6Omk4S*A|p z%~Pr#XX-}VUkSy1FNZ{fXuxFeU6zUK$EMG1=2!h^wN*#X;@h?bD{=p1b8cSic6NJ9 z*R>lN9?<@d%Bo%k-!9|Tq*n^9a2lD)>{MD{NGXF-coCsaiFu*CC2~J;O`FKrO_E_} zx^kgTc|K)0OaMbqyOof=h~VX)PKOQlff5MV#LD{2-MkYxpnc}BQlkfz2+?x`L+fGtujU{ocO;{+ z4B;Za1b%zofw}=z5qZ1&w1N3!E{!iXCiGC$$_~mgP5&k5iM@XA*i7l|56fVKZp_Le zk$~F4SPBj*xHJ{HAJg5Tx!;DKw;AZE5fKPB%$tEKN}Jte!=+ubn6eT!1d|i52s!>Y z|Gg`!Fiu!LcH+`p(5My>Q63njr@nm_m2b|BRfd1A*PdKXG_m!#$O+bT2s3oBw;JQL zf}sJ>A|c){0hG)3O`hxxB(hQ7qjT$h*HIb{w0>QCo3FF-&lX2y`>g+4?l+J9dhFfZ zZTGt9E9n5HZ>gL~Y0DBk6a5Va?Q8tpNtqbiJgu%XymP_lcCQEdF?2ze;%ItfV_^*m z8~}xvYuJipfU%PhvHT#SuHLn+oG2+36Z-m7zB4y~D3Bos6EMuT7LUSD?#2+(gMI zUogh|mu-D2f{}r{Yc(BfTb7t{lt1vDAJtD=8ZW6({VIhE( zYK`w@M&BJbhXWDa&J^lvk|d=@xejc9Qj5^PpAXTSRLyO}?fR6CxIJtnZyVtIwOSxzBCq-GF^9?##dnz=lb)?Dv$-8lY&_L=so*urBJdAa1(N zxM`1^$V^p#8m1mCyik`t2c%{42OE;=qWymKsP2FDD@}v%UIdJVIv;R86;OM)aN-6j z>qX?D-;IXQce~rY_soHtsC0ci-bg|{@wnG8V}O-AOMuxckRD!l*I;jo2{Gw)8pw|XrvjJX?jI&{qB@GY1jN+dG&$(eE$H7ov+H1G zdk6u?1NiVq!(hk7&EhiPedFQNHa!r&1WpYhsu!TSOc|H0Sq}^uraZaE=wzp$H=sl9 z@SATE`gb75&olMTq^yP|1{_sQK?lq%`+QIqm(I~Il`<4*KBI}-ET?>opvJ(pwn|C} zCMpz3wKOeRD+yIzjIRCn42$<81L+4w!5-JJOf)j=hNl)34yb>XL0IGB^hsLdt<)Dj z-fi9TD&D;#j@-e8vM1RqM=Yg=D;RPh*qD+%cSOMaFyR(`1L zDDj7#upJ7?aq~2MrJz`W3=k zufL)E{-n^SA^KaE7G@AOi12T)S(C-%M^`>lPE!$>5lpwP2IlkF3^qc6eX&VjBL9x( z`eRbZR4D27;kXlsO0U#0Ntd{nPJbv1g#}0d2D@@-_MULPTSfwX7NYMxA5oTH5rQ^f`f@(a)q+tQ1?*bl}G zTObPXb`{{P`}~=k)PTec$PMB1NQBEVA}Y|_6QbzI{ym0SJHzKOg6b(m-Cw@J8<1Vz ze+vYCp8xcSY9rwg;FN#lf{Xam4hV-AF@;YqATZ2$GA}bzFXk8;AFO=8TxDf2<_CG` z=f&G{(u$>NUI_Z!vqVEzeu}46b(lF{2}95A>;-3y|a{H8&Y3W^u z)9+oYL>@#`X#o%G^i^EM#k6`+Vfnevce;&arI9j6fOvJg(Jir>-|K0B_pZqjVOE+AM%?`+mb|+B9_2L9+&?*q>n7~-1ItY z=gGDqN9b%jqZpgT;L-alIyV*9c=G>rb%!y}L15sM_;e3&Z@i##zpRulJ`6W+O6+mn z`yWh@&V?174qceN-QHFXC$CzP|2CR7l};&%_sT`(H zH%5%+YO+L>C6;B?-mYM)KJ!}$An384u^^8S;z!BXvF97lQ52U9`h?C=YaS#KZC*;8 zZRO>~Rr2=6?--u_h#ig4dK!ssRp>@H0jmV%36s$mMwVc~I`#Qwg=Kk<2M7XVE8;|< zh?u-ZMT(B3;rva_&$&=(OI+B1yZ8HG2$=McSc&j03!nU))kF%XE$vhx=qjkWfl@W= zWYj8Hv&W5oN}}XuGHGf6D^;1<>wc`0jC+PEV<~Oa5thQ0v7$nunu>Vdb1$Uf4uLza zo~nzA{?4TM%Tj@PgVU&!s!)w!B(#LB0|q(lF-oV9q!zZKnN-j5dt&w<0h~gS5^sOj zaY%yuwWbn^Oc2mH~TD!?0j5IIi8R%{;ShG}6FE;7w`9OK2)? zhuhn2YVUSm8j$VT>tI3NzT&WWHv$SP-IvNYe}^CpebGg4xk*N}Y+mhMj<^cGRBLl6 zd}LuDUN(2Z8Uc<#4H3iua1xU=!)XkfT(`H-G!|ZOUCgDMoUD`lq~uEtmzNkH!B|68 zj|i7llkB3%YTO>#A4)xjJcTj}NWGG`KbzyVbnT`IeQyFMk$UrQriO96k7fD_?a*hJ zqvLo`^;~Y}4FwB}WX~JLOehw4vb5AZQ4;tg52>&vA7Iw*=*Xsfdg@ZbJxa}$Xz6$o zN7{wWs4mps`tg+$z{4BOw*DZ)>KWeqT0}l43}?R1>qVHQGnLx|CHV`ukE zk~v=YASjA#ZKO2Dn#G6W&@Q}pQt zSd{Rh@SC9~2a7_&sIERJDW&at*hRZt<#iZA(q3j}3#idmI5I*CBxjM0$~6>xmrtg$RtK~WZnLtCIz`}S4ovIk^8%E zF@rlu@Mf~S!AdfLGLbTqA9{Xk0Kq;9;{rbH&n#L88r?*6`bm&t0fd!a0|#DmLQh9} za!`ijvS_p>f-{(ouXOOptP9v!J2fMi&*zmMH*W&T8=g-+sR~xbF1)056)9j`04b5n z<#hFY{<3!+s4fE*vDF%BzK@SG&*x$R&FtMb_7%v#Sz)r9i>G>E*m6V)NV31?;q*S| zF}pdbiH}CfPxiUfwaAbP3+-PZh(5V&fi+de$ki8qAq@j9dg|&EE}$(K_>l>9_6U;o z)H70MTzD0Jhl8nLHtCbJvK0F$_XYp}h7w>^VwC;cqasb@QH^X+FYlIoo~V@Xzp=1u zUd%TTN_UWjSr>O7M2Xw#u?u!+^-}iJ1x403{0(Q8rWMzn5Q1Xrpi%Kmn6z3Iu z&|{W;`*m^`;t7xaXaXD#!ksD^gRG&MTweCYVBrQAZ08JT{M!4y_i6b?5*JGszXSgFfBAiWrWD)^ z^~6;Ydsjt_YdEa)ie9A7FbUIQSvPyS-(<3gUJ~PAwzD-LZ&lS3GqPtx$41@(t?koH z#QkRe2NqBGZ|00xQ>g$xl>`O1F%}X$WW=1-K!hE$jL&m9Iq@^Em$DsByh(?=3T=Yt z0?69zgc#mi1+4}XE4-&pAW9pYjmpL|W&5Jk{3>w#OdO>j89T&ECSU(Fh3E7FMLjkJ z9|h2fHA8~`DC=>Rv!qae6U}$^Y>iofN!@kp=zTqPXXws)11QnR|NDHmTrX}n|6`iZ zs-Ny|Mw=ZRKSYBsA_xr0y&d1JY7*b55sw#J84M=N1YuwTr|jNsDPmHb<_k~r;+Vjr z0U0Qo$HK)=u4JyZv=O2HUV2Pu6m8La=9&urV|3h|gYGoB`hx4dCHZKL_QBSKFq&(a zEC7p6DwdQBI~DP|k44vZv}qhX=E9CKY*dS68)1KJ6Ck|JS|Gmt<-ujnfn< zEp+pSc)T_1kE3&g|7AP1^h;;;$wz#!L!*Dn_B}bWhF8CW3rh%GZrKZ*Mx+2EP~hTPn=jC!o)4kHNhpU-SUT&%}^Px84HifF||qHUPZpNM54LqdsO(^jTdO{ zcMqy~>m$~aj4orK10;@1I%e&PifH zBZOc$FvVkg*Yw#tiM0=CS%$(DSv&8!I4-0-&NC?`LLW8sq$(M=v(>LCjQ*w)K^2G; zUgWltRZSc{M}h5Ny5~20?J%*Oli&&T0gy^U%=f}4P?fW=4p&%Tb@blH;hwGET#wMs zE3!97{FL{|+@f#J*0WthB_5tu3M1Q?p_}0}*m)mXS?|m4n5!~~zA;8~Z|cew#6r0Z z+||ruhCDu^gfFm~DrM!Ab8hqXXHCEL0DB3DFbK2t9(CuXlqso?F%{h7I$m;yjQz3J z`odebMgksyQBQ1_jG#YC?=Cr3OUTp-{8J0jZ~=bax3}2TG%Py>Wu9AR^Yg!ta-!H>OBL%QE)tjtgH{;HW^l-~s#BQKO=+fU2)*>c4|_#zMu^jO z$b}s@Nyb5SdEC7eI1hfECUHR}d}7i!8$r6sI7SGjYGLWJ_gUQOZv_D^+P2R_nC^{$ zRv8t77)3@%H{@t7mBdRt*!9sz>oig`%NPXuFsjG+pFdJ^V`Gay=njN$6(;D$@AEhM zpm8iC&C17|QNqDjyvw^!qj4O_YrgE{EQRPyF?9Qn>%xjomFYe?3M4t9f-AN|dByvn z;(2Lyt946nS3AABvibMYQ0_Q2)q4%5kEI}-EW_``K69W{59$1Ixzb2-vx!`7>o^=f zwSkHtC+QNr`$Js4_H9|=cJ4~JrCI;NYW(AxmjuB+VKbxk*zMpf+Ca0E}?9C?6TdO#BXBZ1~@GZglO>FEyF zr(ZPmFdEW{fd!-H(S4rS<%Y{eYfA1vfe)EDnf zLs_5#=|n#Xjp#5GiuF$BUFP=-)*>zRcX14JYud1FfT^A?1&s3*DPKULe_iz^dg5UDG=MRK)qDOP&M=L$&}NmEwB$aX+O=`73)ot{5@&=mG{; zg%_e{b)#|AT+22KvuN;Oiz+zSZGCV#EI(w0+8ay_ssacg3^klXcvwVP%hZ9|0 z3>de>G9)_u9C&pEwUNW=!wnx}BGXPryfd;3Y&VJ}%%G-@7V4?#RyI2X&FIiG)m>ex z3!iZi^7?B~!Ix9MW8%d0uyl*rlRGJy_kGWFi?PtmYVEbRI}9(gFnk>MR0>eOG$do+G|eaG+3wm;kQ z-(}4CvY|UseHi~PrsvDYZ^(p&11wuRpv?`!u05a>tEY9SsG80?tGrLU8A6@X)JogA zY7BjXh_5|C!`i9UMqp5)Ktl|{CudSiC3gJ^6LmaL)!HaXp0Zw-I-+CnSX#axQ++1# zQMWwM_#=@LUO$^0AEhsT$n>zS>SEWA#gr)%@oG53;`m4<1Iuyp4aVIN0R!nPUtI#zG@(EfuCe zmnGj^(xlivH{jcAiqtrY9<^yMJH?x(}VN>$W(*)$b;IH7A&U zq$u0pwlmK?09=c)KtE0 z-K{Vq@3aO+@crdnRLtgUCWf1QidGxdHy;_;@$ie3uak9(_-+>?`|UIS4z z$7XC0zs2krX2lel1{NI>pvs;&B@G>mFzFdx$x0*BZu+)h!g73-%rr}e;ej_ZIr(yp zDz}3S8e}?cC^N8v2s%a;?tkCqGdwQVjAYxVF*TAjZ?=NxQTM^Cc{ zMs$P)Z^ASasuh)X8qkGXc(pj9g7ph^KPSv$*iyI}IPFMWnF%?sDvh)7xba%Aqv)74 zeyg2%OD-~PiTAzDP~HI7y>8PSR4zYEy-vVhK&CV4 zxS=6`?cVAem)vVq)Q)+rN}O|UikGP{FTqoe-xUnN6|%MS>y{x6*kjS_38rM?sJFf3 ziyn!%a}MlmXqjwU>*ih8z|1iLLUOMrP%c`@ zEtVOU*#A~wJJ4vC)mMt`>9)T@;qg92XH0Pa&qolX+}E|gPC5@@UNNx=KBZ*&4x8f{ zLEq2j3jreeqRyZ(xV}caX@ZaY3W}Y2UuXMdDl`EtPt0JLiTM6rb~oz1!Tdv@s1D!U za^#8U-{Q*GegP3?K&9EWx}BtI1`M8e^6AXXx9flr-h~cxY;EA1gopv*dVU3BJ}gpz zSmXn_JHr!7-iI!z*@0P^1|E`eZ^qoabL(r%q^RgZ4JZgE^*l1lL}ebM`(v@qxlzxz zEPF){ZEE3lHGUgch`|XHz5FmJUgP8`!4SeNa@=*GU;zQNfe1(LE2?RdS)*>qZ0w0(S=`;7=H^Q2y=TVNM8G97CBYs9w+w52)!7#DdK_~tK`$aTPs(Dr z_kxsy=f0~IgZgmfNdN{tK(t|XbdqMf`%ASzc6V$_+5HUzr`c4xxWcC7B7yb?X=#VZ zODWZ%)kRJQ1xGq*Up;e~Jj0&POMK-G#-9e#K)G|R`SY=g?b-@^_0GHP*`;@51ydaK zX4k6dK%rsolxvbbr~lytseA)y+hJ-!nalfsJED^IskI8;HWb_{C;S)vh@(%`IG`~+ zX)~w`x4Hv{<~>mODw5dSRNs_@wHW(q$&0yp{Y9BW*4&W{-N1g#c5!lgJegy42yi?9S=5 zR8^Q#;rwYUa~id${ZxxT8ABbV>vP<$%RYa6s-$+(N@yK=q#`i7H&>5r`=EqMA7Crb=X zS7k#z7rs4Vn1tt~4@)kD-*23FK}{hzaWl}>Mtba3BmE4;XQXtC#IQT{Q~mSw=CQV_ zwOt@59(P5F7M0+{-J!;Me9=aUh1xq>NnWBbFgyFa#j~$4GZ@jgL05kd$4#L z=Q%H#ul>mBq6OgxY(ZsDlDo2^?e6}V!b18GPN9q{6_=9}-h9u<5m%jmQ z#0*?b#z_ilocqAN5|s2MV=~5-PBsA7IQnY*AQCkvc50Kj3Yf9qylbJQpFp8d-a+pRQ*M#xIoW9N#qtmWZ&T?+KA5X+7rzM zC`rFN_bfS=g;~St6ki|9`j@}-4~!_jV}M5ht$$Fx4nyv@DCiwY&DPrQAmRY8gIeVR z+`@AasTDGO$BqGumPH_KJR2+4KITG?;;mf!5Wkj#O_F{zLN!=IYp(%h#hnNKhAj=B zM}W&p?J(c(9$zGI)1$1?i$^`tf}DlPID+ndtaO{d-=Mpo?UBScQm}%?^_&h#CInM1 zU&P2f<2kax#VREn2dtPAjYKbE%xz^PqmW%ldoLIqm2;ZAmT>*-ZN1B&+I#ev9Am$O zN=-U15k&lL(GmZHTLV>v8o9n@SufU>Wg+*&QO#y|1-f7LB}3tx%eM@O84r}l7@e8= zmts=Xt`BidHfA%+Yi{o_!2*%P(Mu!g`RPt9qI3C~y$KF8W}pG1_y2+~!#EHOVp}}x zChsKHBo@Huz)8O-Um?PRH?$NL^v5*sgoyHp?)}_)x-~f83T)fK*%4W=u!6{+B=Ws6 zV{*Tt|Dq<)lZvF_Q=NKHga?Uk ztVNhEwZV)jo)zR*iae@n#IDi4j9<|KA5?lj-0_d-Vv!EY<)UVprl)Bl^(Y^tODQ;HVHiI0b=qBiJefh0Q) z0-5Dr>;5wiG%5%RZ)}X0Oa)%5{R|rgMNyaunu9(Rf{dt$g5g?q(ro5nv_uLNw6^2 z>*glZ)UZ8HGy7J?AP6a3qvFWA)NSY={U1u>uu&Ia9)E+{iD|~5kJM$Bm)nQe+zLlL z{2HrEr-lVZO9uFB=@b;s>AB!y#97bkR`Kwf7 zCoX~{EN`QG-|S}ShOC0Ce$%n8HC7PwBH;x?pCrGDi-U&J9onDMly%rDC51{KcIh25 z;@=y}gDj1RzB+Lijn;3E($Fg!kWkF1i3aQJT@~6rxVHe3X{wJ)xu^I_y)&PX#eFoE z7yC+5hBQ+&e%6RL@-$3yI!wQ4fWe-yMKbo;VGK zRVxU&*W+7zH;PdpmBcvCBf&wz{=&3$OKl}POrLmw-)q_zzG?9*(jz0QG28j7hSYbZ zUOBy>^t@m`AHl1;@A+M1ld+8jr+$b6CbE&CIJ3H8R2-d5I_F2yDAYtyS9)-P^*%d< z-Mh(3isPg@z59~~fE`2&Af25Q+~g9?-Rii)uM%GhQ-X<)R|9=!GS&OaWJ6~zgv1l{ zg$6{Zl}HCD)XB=OAVQT{dAVDb=@{lnYB6cUCDqD>DiGk~*$&fcuFX zd1s1kzDu-{eBHb|C3u=HuhYsLCq}u7YvdAPaN*+NqkkckQI%o3HEa^>$27Za==+9~ zhd%p*S`5_Wn|S2=T$>5f8_sy>Bi5`5WO$@GjpCn znkCJ^vHO(}mWcJ*bbn!lbTs+Y9G@C_gJV ziqCj2o-C3A<}PYkhB`)xZY)&bLcPbCcMbNaCRTadxS%L1pnZNLF@xw7kN)iojk97x zc-t|1B|7*{Xa-)H(cCKm2+-IFNZ`~8SbdwSQcx)9A>cx{qd%Rov3fhv}XO!MG&^yRJm#>v?E#p zA`1`(t%nrah>E-Nsr6gHOq{s!rQmN4W9a~-n?>xQ z>LviUdXjdm$lDChMq!|0{ILT-{hwz(YSCnQ6?J27V*Z5P?TXuM2GhYakI3@{$o|#S_;by2Dk`FCoVjCDSeA$BSK28 zi$0U{{3<%zU{xbotIAD?qtA@6l@u(pCwpgc=eFw!Q4?$mz6^QDSHX=UYW5e#4fI+0 zbpxwjM#ua`OY8_J>n3bEOe7~K!iTS2ZGt~&rBS(*=pv*#dZ?qoi(I4-CnbwC1^Vv0 z3S&^vEG*w};1aSJ?l^^i}=82f_XVO8YYfVXmi$V1v^#SdZZ1Ji>(X zcshP>UqU0ucCO3nE`GL#5Ex1o<#A~naIlW_|EHi`935%iJSIA$O_5>+V(c7QX)!It zp=NkH?Ro83zC+Xj7+FwLz3|p9K9$L%8cROosJQ1+PdbI6FM3oK(`2Q8(S6?VB>b^X zwU)j6^DS$z94vO)N10hA^KsnkK~B}rBgE-$XeB}bzR;48ae6_KUVgOxD+;bvSA|F4 zNvLwZc8a;o;BB!3>DqLN<>H_esW&qWApMqOyy!$f)3KWp>b-`)uEU?Bh%G@BuQ-E*35J%Gz&{ieC#Y@-G$cTW#zeVIyftNjhE z2M#b&^y=-PjDzy4Kp+As?C0>2DZ@6tf0~fxamgWL zTcepM_AYy&^0;S-=Up~>!mypD7^#`;Hb;vLKsZq~^zH(8PI6ToFuVr;@=~d zSvg9%@OV3u*~NhDW_YXLaJy6G*xkK#CHK8RoUvqKzrxWDaN4BKzx1`= zJ|j+B^gh%K-3+8ha%hqWDpc_*&h+t1%DF?TWeAa)zoKfMjx7`!+GyrAjM*sEdvlt73nJv%4XGI*A6Kd!Sgx2D1UkETAI$muuPJ_K^lK{e+D zT`4(Oc)kr*cp4kd-{N|GLB$f~V~14;({4&W@~%j>P%oU*iVLmZ(n$&|K!|6Lc==5G z{jyc`OiG7LP^6dm2e!%b;y+T5Cy%D%1L9(l0h{_iPtWHubfGSjLLk^>Q`=-QLLqgi zty+ZOWJ@e6)!cYMHyXDiPa+muU>xYs%O4E^`Cr`S-sj#igl=^OmAmJq#TNS52i>V@ zGZ8Fxo`Tlu0OSgGd&CQ!CTniQjfA-ul3Q5j<45X1hyOaXTJ}1SI)L{x$?q9!cF{5U zE)@y|-?JdD+gCND_WDl{Uz3cp1C@SyNC(Tvrcc#xc_DS=1(7VZ%kcjDr5@0pzwNh+ z7k0cYc@E>ja(M$Gj&sO*EbBh2EP8?(Ai=h`4^Vs8GtFswk8VDahHzAd4|fw>Hv%mD z$0_Kh9&0R%c{Jb=o-JdJ_O4^WQ=-Z%ZX)TenRk1@O*`b2>FzM4NpeQs+?{9=(CnTl zYFD;SIhK8pw>QwPFzoq`D*2z$$yXV>ZSBTHMrdy?H2RId0 zDuAfaKSQz6gOnJA*iiHHwadaySSKz0;WK{|nevC>U0Djret%6B9(=sk&7?E-S@$S& zEvNy7;5%({N?1=#1ViFsN&WyHHSIE{lDoo;9IH4#SEg5vqu86R@D}0iT7e&hqRzcc zH{Mx2YU;w6!tIRyGb1o&llw@@yJJ?d?)$aNccfycbs&&d=XwPU`?DXg+=5cRcQ14^ zgrP!SkJGeRhFIGm+EYFHdwV^~phZ$~1b0)&hQ}OSK4q_*CIuy(s;pNtsYf@l%z0SahO*7PKZ2_`PmXU!L>S?;$_;Jy506xK!9enBEKH zL41oCCS(*+bKDtu;Z)PdpW&MPqoK}U9kObB+w20i=yn#)@TB3@{cbjFD;d@3WO@!i z9OqO3WWoKhq0XZaM>0)XHzr7wZk8D%E*AEY!<)&~@@iT858>Eo0S7XO5hu`z@ z;^Un4U&Y1ohPbaGfszat+KH_PKKR-SR%ST`g+aTQHSlshap=o&j@vgYutO?~K#ll#w+gdEW=H*5 zY~W1FQw0=KagerB^y#B3mcoVQKU(!*+^*~iw3vH*#?gL ztBb&*t+wXdUUv-4C0VZ^Bg^nSmtY*&8w|MggZ|G#l)@7{*ouJbVNrauerw^U4U^Oy z6X+2E^{O;)Y#jK~=h?~2m6Dz+mlej0!lY85B0FpD$*3^( zxO2tWaVVm*-mj$X#>9s_)vA%JxZzb;8X$h-Qtoq32~LZwbQW&uRU1vnYS>;BwvA`K zHeB84M`sqN^5`S>Sry^qUn0%)D?9n|EayIA8DrmQu4@tD1jnyM0qm5|L+XC)&3U{g zoj^^ zYoeYzXMNn=Mr^|#_7SZ)-v0_cfvie{gYLO*ei~O2<4fUg%~x+zhsg<0LW3>R3lGKw zJXpso+x?)cQ^!aiQX1 zpq(#@PHd-pNKDLJwX!I=NZm-E9y#3vjOg80h`;|)TTTHR)zBX0z|w*MK=qoT?exFEk+$47l(WyM69n}U8)fCg^N4a9pqlxgJo9~ky5Y~;!# zsr3;HxL#i!)Ot`WFqT-Y-{J6kV{^=f_9?u-lc`2ubd@LYc;yMRgD~+YKb(6 z>>s`=?xlM$%^6eoe~0yuwiCOJ?Y@X@a;=uu9aZvZ@uE;u5S8nMT&rA5N-JSFA_-k3# zAB7+%nVb3sA=M|Q@i*(B#RRGt8-gH54-nkidBN$Q2Z5n<0@>l>~=Mjxn#{ zs#4CjHLpRQ79BA?GQswa1D3Hy2FWY8EgDtIMW>37qBo80^9QH@6jZaK(uA=To7KvP(rYfK+dKQf%tr-9 z2Z0_0M99P%6fG+HBk;j&X*-B%KF>NC89)>c+TrJyOp{4hI)5|%t%|yMdLO&}eOIv$ z+V*-}`}Z(L&(MCN;VnPlQ@Zfx3Ou!SQ&(*V$d#%Nfi0QJh}ZK_I!B`0wFaHN+Ci9y zjoLjf2^M2<^XHuBXHJcmt-nD_(5Cd%8h^G1;&&f2VBQ1iDanRJ7%w2+V|4w3ij5k1 z#lO*A*p=ysQ)D23bH50*wdPh8f3zRp`+AH-K?;y1ebOg0ytsHB$u^Y3dg$<<7ugDr z<36kvMS+Y9d!on-mx2^U?Lsex*^qXA6i(Hy(Ih-vF0i-V7NX~3%rc?ld`$fRFAO(( zcF5utAlT~r8`gZY)RPX8_-eHQWX?UVf9gqO3zyL)I(itk&18iN+52Wr)NEVy!lSXh zW_5gv##NxEKv)3HnB0UKGn?-kJkrg^SgtfNhvVwUDA^`SKB+@6gW=otK@DWifpN!^ zeq`Gj+~f6hkJEP!cK9iSn~LhUR@=PtY3wz67(gu7cKmAC*CaCqQ?FL$BW(dgz3TQ| z+#*GnerklBQI&+B^%?E{>n1`^y#&FGS^H|o5%I%^4;nm%L3*M#fhwG(Pvh7f0!~}y zzVaI-&^>f*)Aq|J(4TbcxuI0>dYKh0z;Qh}1vb0*uL1E9OPMQ^e)2`*YAF!%d><~uFJP4$lt+e& zguv~XNiAn{BPUa8T>h)Y$aOgC?kr`Fk6lsC=$5~f7S>=0hdTTr@_f@?D`C&^M*qK! zuDRy22-OvzyyT(O;NQl<*bl^x5ghsRQFlJ_yc`18FLA;xLf`mIPY{>#E-;NjM?> zzBO5~G+?tse>rNV;Q5;~Dsawm@i~V}s~pT9t>@Qk5`8i;#Am7I_Ui(i>un|6R1B0Z z;YIqHgDmqzN#Ys)M(!DMEFMTH=nD}}i}Q*oAMjoiX=#;vipUu;OAc`d6x4x8rUhY0 z_vE{W?vwlcZ6fxmp)A4l1=r+BYGsqUWY zd^*||l2|5npT5ldE&Chio1bE!=Ft{jF+> zZZHl;zX&#a>YPMah5EuDP4O48oU)E_K`pn(?>U16TT9Nr$;tRW*DzuMVE;*fjCJB> zfRQPdCxepsxrxL)73x#Mf11L1rrteCpSmh8MOVA+U%dLm7Nxg*E1VC@2B=MBLeu6+ z0^d8ZDP7&X7&dH6GKV{Aw@Ff6$#nh4UBX{f`|T;gENQ(0I)kZ%f4-S$H=!8#m)rngeGs?y z-1J!eaTnlZ_4rrCEG~8?6p?@6!x?~Tr`>HNTMsMVAvn&^gZBo+WFYM7S~d=wZUwlX zM|Qaz@vXGTVeY^C?C%0&x1~oJ+V8hpPoH%v#?0v<__)YhbuABz{5VJe$$P>PeL~U} znP)5ycBedv31{n2L+K=dPray*0WuJsFXCd>zDfoWnXs}cSC&WX0Xco z7C#4vBUh7bohgIapw^>nd#D-jzP!C_xxy~F92|EKXD#ygEms7;-*(lgg+KA|q*qr*bMRU2JRiu) z%{|5-eyYzrA{F;YD*^w2dhi&4d%NL`**qsP^(K1jcXEEi^>JbQiM0y^z`dtZ0V_Ix zw_vzL#Es1WoVYiVzKMSrO_d!8lD6Q<=$pj#3t|=w8h01v)uwF&X+O!GG}n9K>Glsb zNvO(nY?NQlWn5Q_a5LM0(h#mmI3I_>u!~+poCl`V=~{eao`Te#c$mIR0%tu`K;!71 zcr7n%h)4K(a^+1*@mUC-eZ`6Xqdy2N?x|{#pc}=DP>q!^kxQTwRtH^$@{`>o>vQ2qTa?$*9A)>AsKKh zlxojV5qYrT=0L|tc3eRNAi&CaeeH-!W-n;s=&p7WkIkLdS$Q~rEy_NYC`@|}6|Kxe zv!rh$>Qt=P=XHU&bSi%3Qswxfog12S7r(v>O&q#o$wvqOXJj`B6eBXJTSPFRg5rf4 zPyHAiP+G`K?&a!Ri^r^Khc&qf<=U(3G0$Sik{QMj^jJhp&djt>Dw9=Y9>975M6k|z zgo+bjhR{FO7lqk6%f~oKgckxE?Ug*fxA|lb%yiNzfN?NVzuc25`|O=YtDB2jTod(( z#P~{geEhDtDO9=uBqBj8J_#&rRuIE^GGfE-3DaxIiUi1&kyns*4P6>>^O0!2KXr9S zE2T(1Sfa>kS;$oU!Vdni%7kRYFsHR@KHV5D{{Mv2aifmIsje=6dgz?Jl5PW->%)*q zph7IrRbT@|nT4b@$2gPdqNcz?I-Q%GqKyqQ&Qllb{>(t3FPZL=!II-l?*4h?jM7`1 z;_X|leVEyI{PqxXh$?lT>1e+n7I*a!YvO*DNw!LP%+?Ej3Y=fP*~gj5LL8CZRLu;D zH=Ue$FhDb@v%EN4!Dq7OfSL58LMG#T^HX^}%Y7OZeb)s7BO4G8-cK43bv+@^oHDvS zULrI!SV2Bf1I1Os=6Y96Ovx0?$5)L_Dm^8|7nFT3N1D2evgP#RE)kRxj*2@BQJJ_nayAwzY`?3bMG0%qD? z+)Ho8rNj+b`s9L)^R?^tXCk$0DzBby$tPq?;%yJxmfy$Lw^GGgHBd{(Rf^D1*YZJj zk~MJ2(ST%ryLrZ>aBpq#@lpHDDFn`AXAx9wUHVMD6Vo4-iv`Z|csmq}U7Y0Du4M5g zelO>B@i5FjMGG_;cCnh2iMm%$AB22B%;5;%j;d>fQISZ}H{baT`6-LJ@*Vrp%E$iq zEd!eR(-gENVCUtLVs+}VfKte!&&vBYk!jlLZ_i$>F!&(07>wG!nd_qy@kAjFTC(Rk zspUETD2$!lbv@#x!AjrA#uO~%s>|jw8xn3K9 zajaH1jaN&>h0fiwTSyL88Br8o?vPqfT^>Y81Ggm_GOW!<9X6JFg8zc41a0a*!JG&$ zjYP>Ze%Knq3&nUu?Q7dNv&tEf-pfWvWN^AnSTt|_?%ifC28{}lAag-S-7Zs_ny^zI zx!S37jkiI_hEB@p5UGEGlvhR5WBw2#LKppN^@LO*gqTq|1U9orM|=-W%XvsX<&~AA zw5Zq-gkJhng*Qk}`bI;GdnPiz>gbGNtf8L0;!Pc-R#Jp*3vTB}Q_i>}he+|b^Fy8ul{Su+Zojv3X6`_kj`n=-}8=y1#T_@JJo zeA=wp=0tFQOnh1bViK5z__484+$!mWucVsWm&6eG)Q)J=2!DXC>$P`yxXvg8aRh<- z^2qukCzVvO9PQJ-c!Bk9`*6o@81Zmcpqmw@n=acny}gt%_OMe!UZ%v&@5h;e?PSYJ z#Y0XllrymLp=%r{U|YGRH^%_t1IK4QlA%GJ92TCLjJ8Q@i~Jdsrxvu-_|#juC^wdO3wOLkqQjBC^FrI4AY5v3Esvx0mO`(q2kVt6S3B`+lyN5D z@yZ#_k%N}cFG`=AEK+Bxj$rwO`dW3r4pt@MbX)D%?NLfGgg#!ZiZ{NpOQ{K6^Vh`I zYAhR-ymLc#df`vMG5^oAgrl z2aqPukZGFN`P4cD!-|9DrMJ=wDsv&wI!{O-`N-o0}-D z6wC!zEWuM9%Uif)1o0Daribl2J(d19V5boBz+3516fh7$^D@&!rfPA1+*h31Me;&_ zcIww-^n8fYg#p>|LedN1KV7M!ys>GsN|pQOlpuHq=jq%cNlOqDwdNw3%?SKUtnqN* z9q>q@sXAni=AxO+4`Rvb6q9Z>>PT1yhPAil3uh;R(=@uRJEZQOwK#%#Sd{R)1rt|_ zy$dV017D|9(&6(t<_W@|Et8RkAnnbeb)|+wD;BtkY^sy~0sn~GGlwWeT>m{WE3{4l znq9uHW1s4#mf&<|V;hxVrAQ009fMKjMcyOeC=4&ER->LgP4!JZ@v-RsPls=8V&&IYRnNtR!z{0#Xeh)D|-q)no_UL5WO%z7YK5Vp7dG@Mcar%Fm zZNQ*+4XCvH20yrGeophsHvu@!r~z&W*X1y_zHx%Id>BRJPqe8~GfFB$8kVS*Oy%c5 zo2V522Q@sBL#|#Zo-BPF7Z_N?dsS#ApGCy_rUy24q+KUuB|2Qkhaq^xd^yiPpMFV5 zT^W5Y?gGMwxH$=9_hA#9|)}uMaqsA|*Yy z?`cN@-y5oDkUgO0Xzxsrx8sm!w3{|h$`}Wt(t_nS9)=c|PMcGJFYnl^))BWMyMX+W zvDl79xrhx6Fo#!fa9Iofb#znokBGt&a)>tD&)$Ri#1ilEki?9^TL<2F!>l=tJFWqL6wKPB#kHb84*tm z*bNqw5W5d%`%W48MRUbEt6?W1Nm}R>=dGJ7jdT(QQ2Yo!fT8j}swnsy(s2kovG~A~ zKR#>i?6G8Q$?d>`*q`|IvA7dT+ZHnoN4nv69U3mmV%)b$0s&31p3uq_N&t^^i>8zCqiMx8vHidvs1s*Rw5 zTZD-?Jt05-ki1-R#d+XCY?ix8NX+5nwWjKid1q)+jXy3wR<3em_Z4%<&dpu|f(loU ze2B+W$x=W#V+c9z5`=4lMh)%m_?c^5B`?VFZUmRm1G$md%P9n2m9M^R8g7twB?sW*j&BO^nA z(GcsiDUL5)e#{m4GdgXgX~>qXHduEyzV$gN zs&mx2Hi+DWfdKz+Cpe5Gm3t-AcSOlM2Yl>$f$w>fF-B)GTGK*{6}hligI$Oys|c-* z9f0G{n*r7!bf3>iq`X|}=I^XM!FO^L@ zQhVFZ_K91y#P&`PNWw5r%BRcvFe2O@I$h`^;NakpUp&nK+;4{4e5>VSA7Gm5mBl(F z**(Vx2zDDK)SAEiT-|=Pnm#Oo+(dzX2I(Tfk#8E`J*mR~81FDnig3H3KH#+(Ukuu( zO(F6BC1ihy+fb-jQSBtTZFhdiv*buFGu#>JZ%o0so;W~i+tRtuiv3CA(^tp2?(p}4 z&^D^lsB-mc-V;Uj1w)JudxO~GE+hTK>9N`Ic7}4?Trq^UbYL&+M8&j>>pTw!J`&L4 zOS$>Ra`gxoq*cll?@8L~d(D6fNLRuy)Qz2`HtnR(r~$xy2O&2QElFx&9ZXz711z_w z^XUUeul-b$K+Lg$BLBGovDS?Qk`%~@^XKlORcpsk3prCy{$|tga0`gZVr|T2#GJ%c z2#JT3zbX!*@AP76@MU+>T>K*8!=y9J64Qi3ld=`b4YYu*> z(UlpMUbQhiH7EUMh5Vj7DA%x0C|~8Xw8_#OGpE0S?LkzK9h`jJcBnwLI@H5nkFHBh|78Vu)+A}*>5SI)i zKoXmzME?>8l@AFoR7%CmB0?VdZdYmt9wINZP0MwrBur1)4iPJ&cZU;j-cGv=BOhXk zf!t$@HcY0~PlnzC7Xn%0x;vM_$i=4aP__Or{tL7}Iv*$e77KHO%TqJYeS3i*gZ4@V zpJI@K4k_iPCK_cwiSEH9wu~;YLms`2&4lW`V{^~Ek{7}IRJ2k?x@jyMjsoOJGW$5I zo`fhLc=X>!PhJNAdwDcR^~OOT`Y5;{IN8=zPvUxR@!>q3^$NHgRUyk~ml<^Okxt;|2QaJ?vTl<^-#P*{R)qPq@2at&I}k)2^6FGqBhZB1 z9_1E)u6?sa78f`8TLtKP8e0~Bloh{f?9>wTaCS#thUo< z2t;6>aCR%+?#DI#APa66iO#~+;0~4^X-$(sGCQlz@}P!|Fs;53{(qSrS8{vCUwLb0usX|GNVDXMqO(PZuHgk<^|ikT&vi$JS zVTpyCPQGtt+_tRvRNOjiaZ`|!x&1KZ9)T(mHadE(f)7C2Aj}_@FjzIC2sDr;B4>cFc|w<%E{SESvZ52sp5xSLOfoTdJpD~_kdLlPN+?90XY6-!8H!|XYF z7lI#gr8J+D{1aO1xc>aZ!k0FhpD{4`5KssBO9}Q=33r|x3@PWi0y7CsNuD1gxzvw} zjgdya#vXQ3hKQxl2IsDR_xt!9bsU^OebPXv1YFlb0TzJRL~|CZLRDZK0a_oo*#$`A zVgktqvCZ9uI!r@Hv7hQGGthiF1ZXqOHvR0nkmXQ?>KFq@E)wJtTA@nZq!T>!8bw2I zISI)hYydDo=aH2#IJZHXnou0h<1w2h4bK$z@rpeEy!G`b5#per(G9YkRirHm?!EXY zr?wnUqa_UD$B}tne;Meznuz8YCz}KZnhA|Wx!n<_5XEvNSy`ToY(K_CuAKScf3-HV zH2Aj=&{k2Wt|dldlwB(3kas=%vi3tE9GzB5n_<$i@3+QXX^M{b`b9z(4yh%xdfMV! z8RLH|&jLeDAmZpJwWg#W!ZXBIq zl|)I3ER#4}N7;Tx)ufQ#B7x)=m!k?79nPyqtm3}B!c5aR>-5ZyV<~dy4)G5?NPgaf zo0rdX{!}41$U+G$6o^FbpmDS5YvWRGsjOjb9`q$QfdIFX?+26zxMYq|IDPBauCJ=?$Z0?1Tz zTi>shBHq##2&(}|WE+}<%F7CqBMiqu+%OCx8L9Ap_fU01+Ry5y|G@-e%bmrGRNJ8j znb4o9Mm<&`%0Vy^kveJT|QH|Cm8#seJ6)Z(kM9da$sDgaXZb79{w+w}J-FLcU#P^eVs8w3bfaU} z-BAy9P#C@;u-`$@JYlM|vEo|~b6gS#^13+kKGcH8--qo?8f6NugCzPiq%hJ8pp2~? zrb#J2`QsSi4%cU_2fk|D`+J^I;(L>Yi(sX4(PdQN{Mx%0*MU95i?}S^5nRe&>TF`Y z0>&w4Jo(S%Znn^KhbfhCUZz!dK~3MF;@4XE+F+A2yoxxlz~4P2Z~N)fXQdGmGVmA$ zavuWDr-pwL8nDn;n{4w!HY}0MXWCW=B)axWpQ_igvEU*~eDqBhO5i=q41*i5q?_bN z4{2@RuAGwAZz7xCU)ExuKXHw~!FB*>FS|I3(a~`8S;cqP=QD#ZUyT^@CD3^xZ$LyX$ifQ0cLr;DIPGA_E>X^%Rog8JRXVN z4u4I=SU{SeDS=kw-)TCc!5nNf?UE%`JQEzM0htv`WdUGm+bu<6vt(t~XdN?>j+P({ zjAU=Y0NmLjAB^ECIY2Z)zUl}TAOA1ye$orR7c`NoP|eHX<5MZ~5G&mG_ml*qF6y`Cn$JgunoPka~0`}9XBV4m+R zq`aAp+H)c>b(=rOa@uwlC`LvAeJEI;NHMG+i9ze0H>?IdbR3u#%t!mZ zD6ah4px$5*fTM6&`m_f%PbO+ArkYGoLEXdLnpWADA7eX!p+Q;tmLl6My|H?{ZWL!r950)M#62>Jr$8SWvr}| z;3xfs-8gzo5Kk2Uc_Y~XH9*S05=su()AU{z|KJo1%JDL-5sXreQ)V7ncO3e>Et;d7 zP20ZX1PWWzB(e1(FFc+Ql68F&eRKQ~9RYwxy-4Ekh^OsaAa&qst;=m+YO3H3_5FEr z;2f^*=6>lf1LAj^jvK*AJuW#jfcy+ol2!+K+Ek6mC#Y19E^n34sJBNApv?t*Mky8- zxn%I^Zo|$iI%#VznId?6YSMHa2SO7Tv&Y=JUFEt`9t;1-B!(tv+;|O;LUi&do2y#TrwiB zwmwosm=FSntLo4X+Xy@KlB0d9OYN&av#=OjgS%4VdT?~u+!5#YfB-4CA3JAKv%hgN z{4v`-o%SR@`aihM-U-u^6@!K;pPHcid<19$%@=SXRQ=LmT*c*Fd+$xoLuFHjS9u~Z zFEt);4aR?W5K`I1SjDF=;s`QAA6>>i{ijh3Sz6NNaM^Of(1=4FJv&nm?ZtFw(5Wzb zGmDDt;ISHacV8PtAH44YDI7!F^Iut>q;7li#_1+IH)7EOxUv)=D*p z`@~x7P~jkGb09?5k*=#k%Qg1`h>OkRMJ1e#8g6q1s4dV&WS<$+{eR(?k;R=@nN#$b zSoLB%%cgci02|-O)wMuRG&@TyQ>-sz@Friu%8~Ps>lW+L4Rhr1hldt{gPfSUp<&`& zf70KVJE0v%Npm(wuW}3xLDUD=*fV>q{n(!&$+D*9DW=GdOYI2+0$l1wRjy5Xh-bkD z4}oH7`>oW)@OC3GQ63-Y%HW^2O{6a(h;6WC(_MqVvVYo>);yPjbdSpwVrAx_8_(q) z(FWQcm{m&64?sWQwla}#k%ARSYojfR>(+6yWm4E4W@J&A69!wdkX$g{mioeSDJw<| zw=f2hrsEYEv5twXLfog_aw)F7`X+nfo-!xruEb%PKb9$?X#X1`Isj+40v#!f z!^&`N+d}|Gfoch>%08s1KKykgeU7Z|3zoLUxqbg?i>k-kcD~&9P8Hp2zON-NJ2`L8i@|uD2bfeO&H?&&Hii z#$pKsbZhO>B#}n}y7^>bP5=9;(x_)Hm{!04$*bbZ@H;9h%`-0_P$?T2Ws3=LUq-dk z`4F?HOugDoLg;~%y_I)<03rh2_v#1%QSL1sKQ=Y`I?5Rc6ZTSp39st2?f*V^SXxkv zAH+vF-;k)aw+8}!Lu*9Dz(_d!v$oe_mBeW_Dl(&5reJb2(eRiBw1s%|j3<6>USc$L zgJPZ(c@!kWvos`xt0KKyGv!iRlsRzWRA5mv(Q7A2UoNOs@D_2vm~ zIk*CyEUEnGv~QC;tJ)Bg;yDm3E|HZSWcDLZ{6BT+d-#~aw&be1PK^3Uk~v&=*RPA=P2YwA&1p5AJcpxa zJW(<0AsW65>iTBjcEtW{&q!j?NIX@t4l8^<3`~K{*}jO9Fl&K7^5eVSvR^11AOND( z)zsP~+~_E)zr1iZ9Eynu6W{xi5~KPcq&TiCzEao+lhCCYJ1ZEj=fQhseOd8kkA=>s zVe1UQR%d*-)E5mw{Kir6cJUX(CjO#n$vF=t1u_EtjJ=%=N#MZV$1Y!eZ+};t;1}T? z4aB^<;D1j8Ld!9WQD+0e>oB9rK&!SWj@Zg4PChdb*`=ecpH|S1kxY)Bsau6WH22HB zTJc~!;$KR^OkU1Ht{|+YgRfS*b`k;|N@YskyW5tFBy&f6vk`Xh+y)HhL?BwqY>UD6sRc8o zK^13 zl$uPB>gD`zwWDDqM(J?%UImEi={y5~fex( zq@tGxmGZPdU$)9{AAC6FlaN1m-%93pii7NaV<~qC^ZlQOHy82Mm`A_DlLE0^2wjy{ zl-U1n(=d$Z-Z9;lti}L0?eocH{*v83#(NSPob+%aVgVz)UyvxSsAt&fGo0C9V;Hcx z=5D9HrF6pClCX*p5q#TcULb`NzpOmkCHte%Qc8Rgz*+tLg_ARW)mT^4GV_BJZnl;g zIEf&a#p#lC(`xx`aD+Ks=8jE5r2;_?0T0+~=?_lHklP*ir|A;nS#Sc_F-B|x#$tiR z%`IP2u*{mjAbPS_#CcOpADwtYm=NE8(TPXMXf4$}Kz27=7W3hGevDAJPw$oninAuL z@kGe%QQa;goSV=|1?ibW)R|hW(}X_zS&^)CQPugz$!eoVi(-(2b#o}6Pf!R`{+gE- zo-=4xMXrRy{k)Mpg>eyN-Um`+xT=#d)h4pC8G3BY&qo%a(M%k{7E4W9^}=&53=UJ? zz#hKZqFIxhOHB$tdOB&62q9bzLr(T>6>Kn>nf_D~xy9@u4mbY9ir#_|Ys2W-Bjt_3 z5MZXZZ2-`K{!qR@*TA^E2N;DMvM@WwsrNz{sm7HF6SoQbT@vNh`~y~ba{Z#dX+^v2 zbl?D!^dd{sXIxZc8U%dm7G7E6?ZkX-4@V|kNf~2(IBe#M&OIe;TDAD^l9NiPPv}M> z(Y=o147LA?4U4)D^-3GPtsJ`&0o-FE=8BN!;2EK;b;Fgcw{(#f2iH$z^(}Ui{p6R5 zWkwOaGd|VLQk_xQQ_kxNkNQ+2!!+&L-oygw!CgN!sY0A}zu8ZABOnVS-a5n4Lb~{4 zrAusTAy9ogGetbb9!Ju>CVCJN{$?PAt0>Ix?wuO72lHK9Sr>J&(j?*3k&Ii&5^CR1 zphs)h^G*&as(&nlkPyJF@|jBWs<2c?q_XLiA~n7SgW|%O9AjlOS;Vc2u|452kfd4n z;Yg{;p%PD(=F-@B7m86Iu7WXX(G-*zcHccJ9dt^)+# z4(RgQLz!m{_416yPj5iI1KA8sIo|vq418A(xUsV*9i?aOEZC~Nn45nRW(WC=h|+?h z(bY_g#iu=GDmL04(^!-|gmZ;>gL{gatCsruB&A ziO4n_5s4jC-(7d33*>J2LV#=}{|MI>)8@8VTz9sj64>_GU`%x%v>rE~1=v1Mhts<` zOC0fR{q7S-7fkh8p266L&T#kB(R*EN1h=gLOlahYY;tq*U3068yoW86O8GO|U=^6| zEC9E|M(~2=={Kt*Dl%Tf7SWU4+tNa^7gO%iTEgMChqF4Iw`2OG_w2pUz1nTs9n+%E2QdFhEi}UZp6#829ZS>= ztE(s%ozR@044D>4^F7}NV;4syNPzb;gaLcG*m&jMwa##K!n7#J-P{tRm)eB&uN`0) ze=%}_Xxw~qsjh!nSUi#=&j3$>N<46*ZW80m*8f~nU%aa4-{O#6bdx&7v{GA8H&1=~ z%~R1RpoYWjpNV>rmLj-FZOHDYikjh1RG%KNC@>9Hmr@Rkq7}-I)#Vcn2ju&bd57LM z#~$0;AsO;@ZjDYE>z+xk2IfY z?;sw7@VB5Cy0N{64>GdArmjv^B-Cz9X3(lLy-_8f%xm+H%4n)~H-=mjG0e+=qr$Q> z#YNUJ*Y{wEB}F8=TL}h(Da@hCWw{)6vLahVI=Cl)Io2Kg)%ha4ww&@*53!f${C+5C zdA-bGJ{gmkdFpcau7=X$!tKRtDl0@UJ~F27$W~oG1}jKXt#*imSawEGUrlmCIxHvo z-Jwz0D>JK%8_BhSWTGPzSAJbQlB%OS6}GOt%NDp0N_kRIc1A&rI zP4xjpMu?a2tFiqmKu+_pX7QI9$sMzBto>NwDfGWqX6>}3-#dEpWV3gZ4Bc!pOR++O zS^|M}Y5TKD38IE7#?s}KKOW;H^kk%_$;1cwII*u65Zkp`b6;I4MdNwWruInAj!%81 ztiN)1_~wv=p~teM5vN_3*PcABX2k3XqL1=JSIWRMEXYIFR^R1YH;URYzW-aQ5JuYz zID}7ff85wPPLLD|@TqviWT8;2VPYI0&Q<@GpA-}(&>4ad^P4Y>+1XQ^j^32r@g)`o zNrjdpo7}S}!AR6$gS|cI=A}kP;~_1=gDG-!JXpI3wbM(#z6I+{BRMkzKOxn)W*C#H z#Kn=OHd;R5wNC6)0aI{`5E=V3DWGS_Jbl!QR7ss2?V2-K<>%;+<5t@(*>Ge1By<%% z^6Nf-L3GXzD1?SYpaL3@CaA$4a1UYTk<4W0tf}jF{Kn_@ZU00<=aZV7(>H_xy_Eh5 z09^nqNmStv+hi)GN(2GKBX{>4;b2#P1CEyatvUue$bVrN?tEN5;`t44Bn}<|&?F8p z010~ZZ(F7r2@1G#GYpnG5}K`<_m=SU0TvyK5`|noTq{qg9s)}#twEPSm zx3lUa3q;)&Z-NWe)A&QdY>PcUu5+@GdaizW)ippm;>8I z(}j^&k-bzG4g>04Uw!${ht5F$#Oav?vD`Me0lZAGm&zsv059rAHKf*&hNrQ|SD4LG z9qq(LSA6mm{dh6c;D)ZQ%Pe7aJK}U^IY$`Yc`suQVI$P@Vp7Mh7#rLlfExB8HmFhRL5r`+id zt4MVH!X-huud3KQ?SfAmBG#VGg4d=*&0j*PUE^JeoCmNodB7432eYUL+iHlIHGl_c z;f)%9D2!T$?yE=nQLFRTk>=9{6>z$czVUxjXBq)NK`GiiXG=)6Ht-@- zH=OGT33wjU`u_J|`lI?`bLwDjL0b65};qcLH-SMC=4bGve}+lqgzd4u|QZbd*g72nwjUJI3;D zxIjAjKgn!g%3_P7e8rkqh6L_o;#L|&>-%Mdl0yYX?E}-%F$zj9ir~SEQbdc)Yal+n zmj3U3$SE}F^W2cYt=7&8YE$&XEu)_DHdHlLy+)|m4QYO4Fm0jEA4%C!r?Y4_Jg~+B zOG%+CW@Zn1*3Q!9SK4e{?gy>T@P^g=6VjH(^ zW^Z>Ri7*7?;V~c&9mq^G!yiv7%9~O$yY zLGM2JP}fg>s1Up#|3wXMt919Fvc~(wj84YM=kk=IfqR7s{b~S}5V;c&VURD+1?2Qg zjhYLh9HPUt^*n(b2&ULm%_VfZ2ldAJy_r29`%1w+-@iRfBOCNK45*#R0W~^!3&&ZZ z6<-Vynt+b!T}qPCd<>oOMRx_rWzB<7gwdYppOjizvD11lhg&iNqr}raAtSkDq@oM8 z{}j{N4ZCvu9T3rfe(s~b+f_010}dSOw)XJ8EC?UIL=y0i+6U>(`l|3n)DjTd0iey= zw}Drt@mOIF_K~V0dBu%k(M`+d`Z!m^k?--r<5dvQ57aSK+TlN^c$N}Q1V84%FBoTC z_XbrHJHXJdsQp+aSQ9A>r$ zwAi0%a);o)->fVJfhBh$Fo&KP=xX&N`kaSBp5+q-qNz8{WeK2l>)E|9E)eQ5N8)bm z&m?vlws?-}G`#+9DZ1BKeOn~CP9`dEk65N? zULrwCQrhC^)LSikNr`sFqR24WxW?)c{?&%chA?E=K=etc;wWmkPK=G@V{f@rB0KAk z)!}`Xh~idhr3n$h%Nb(%{1d9KXbM0})QTQh4*E9yCNx1i(&W-f4#Lg2G31(u?wD72 z`g!!4D+$tyRykzZ<2DCyLjgI{ePKqgB8_aZVe3s@J}ho>zESXfsM;~A6Ckvbi`$Fyi4rj1s9MG13D8v2c2 zf(*i$0iMrGn93gI1jbuK0H?ghVIkzk>DI^wznP zdn&MAwsr_{N^9Z6fZ7YD4f6(c#Q_IAxIOnC`ClhpR$S2_LlseK19>$dYdtg!m#R2b zC9Ts>s2u>Nsfr3_$_1?aJsDn}?Q`WfKO4!?A1K3nl0-}c&XGWl+M*⁢CB$CIGSC zF++ZWqXF-$Q3EuU>mo|Yezj8}c%i) zR(68OPL{f0|9feCqG0>=J-?a^^0LwuZlmoTw50gkB4~}eO+DCC zA6oMWQV}iZ7Q}vx!$Z)~C$$%+^?h-tqdO<#eF$lRIbmR2mFky7{~W-|X6}JqGu|Aj ze%xX@cp4COrpQM{^~z+yBB}4Izun2^wFsgcEu`y|K`0=q6LZw?`oQ(y&x67_8Z*mt z0-jN)H3)?e0tnR45H;I+yr@q?LRXk;CE6*${#`OoMmbem6lj$qerc-lBb6^Hh`u6? z!|Zlrn&l6M%#?V7W4st7b~JqOFgq;?=%YXo=4wSYmJAXeYLfyzR00cRvUc{JwEhm} z4ex_c$IEE({AqdL=9ILTIyr-S0&pBHr11!8bI>cItVr~L1!Saoo0DRA4VH2UM7U^q z%KZ-wF7${|$ToNmnj!(0yKc_3E=JpC-EF8}8IZ>7)D~fy*)|QDE$oKw|f z2UH8WQ1AK8i@7C(59K#$8uoS0mYX85jy^CiOrVgF-eO+Ff2qPeFQ!Cv{TzlPvMfuT z$Q?F;cq%_G!z3Z@8|7to!a+$JiNGB{FQhTMbY)DOSD+3~sG}u!>}R$&ZD+R@83u~Q z%5N^(NM@cI`GHRC@m}0jb~`{n=Z2n-c3ENqQoFeV<+QYq=8#19du*Bo&A&72@Abl7 zOY)79e{jVM;pi6N;>~-fN+m1kSms*UD33fn?CxzJy;;ycFPg_jJ7G!5g3# zAPDuf0GH{24hty5{1ee{HH!h%-0xK2mj1_3OQ_xdF?9HJkWp!d;RN`hUYCazt7P6n;+3ggAn%rv1SDdO2@X*I*gYsEv8)I>Q5 z^=ET!gq*~aNXWKRrV@F@l?uMBO3mj6M}D0GNbfI0OPlorr+twwYujNS^DQZ#3a1Hg z{pVWw>ubz1OXDG!I*LfmTY&AZUle@52v6L_LJ6SaRr5uqelm^Z5af%etEN7u{3S#l zi5>@|M42@(sS%%uw?C;br{aB-*uaAn7E{(9ffv5ZP#B6+chKfHN(F z{}=bQ8zpk822W|=b{TN`)oTKgpf&jwci<#%1nBF=(RYbm>BN4Af|UPZINy^wGgxXC zLs;B<%BxSe3hu06*GjI2M|oa=>F8@75|fXu&1g4>4jv74i2yBOO(BeV91vE=2~DN1 zT1X+iapgm=rpQDPTT;Z#Myj~B-D(2uC$s|f?^rHn1xY#o@Y*xmOTk61X8$1@hx&TF zOq4`R>BhIVUeTO5(dvKGF$Un>ZAdh7vw=3I-Uf``5URB1D!PPw|5)*(Y?;!R@K}Nb zw*W<4zR>A77lLH=vtA`mv?R7V8ms;S;BuoQ%wx&L@hI{lK>`Gse$aE0FC1C&n>>)} z!&#j~F%)x$R9PPGCe2O@o-wW%rSpqZ_=MAKsrGw-!h1Wy9`fqdrn5HBQ8X;N%U#uu z$fTd6pJFZe6@3iJzw#~D@8A3dFA6=7WX`YQ%aP5}t%h(AlM&6_U{;wcf~}(^4re3# z=3CYZ#!pv$EK@G}2}xb23?dV)V!>SnHGPp&6L@69rxx(;3c;mG&@rFo)%ZyDM<^;z z$Qa6TbsGWA^tgOFbYH+8J&|6PgW{hwa$)#h1G$2+ijaRp?|>YKFBLfMAry;^cSQba zb_-^RtDSlu^X4tqCtta-ikYBTntUe0fY18l0HIm&fpuIL=>lR0ooKdbNK7Y7DbRnn zag&v6#Y>>5uuzMY<1e`hKuTc}e+hTCjq5uX)7kNty%78ru1AdFM%$-LgrdDP$d&X8 z0edIoT+AC$a`V+k#Ti}>9Hv5?PYcK3FZ zBPJDJ1I!~4_AafS%GqTw;_Zdkc~md*lEYmpcsc$ubuz&@X*U%>35TwTbbqeW!X~=O zr74tUD6_du#cfyi(8*{44@ruOYY<^7(=DfgWR%+!epJ0fV2CY%Asdo?!8I>MzWk*T zp)M$Im<-}(jy`M7y;HPPz%7*cHLGRhfnQ29v=O06f}Q?$MPpn_NA=}55nrbiKK5AF z68f6Z)SjH*fkr?;`RX0Yg*P~Z43scQcHtb$>aIl4XyZ@6sy}2`Q{w%4r#0N_nQXxNFzNFWjo-3q`&R*? z8cS*4zH+wCAw6>6F00DejXp)WN?m}>+vSg-rSi&p$9UnInk^moh}XQze>gF(wJ{&3#0_Ad>k$U0ZDB@+Uih?M}Pu?Vw&hdj0weL&A} z?YS{LGG4p zrT35c3KyMBBOPShLexT*g)=tATt30(?%APKK%{D}UCQiL99U&k{HI5&mQa&Mo>2UK z?miI{NOQyw?;xe`xy>0k1g6?W$&1R7uJ3(OBSBb7TtN)`y zo0t7dIUguVevQFGH85Ft@ITqCU8mLqq2!5tfK+SjXM{S23APeOXPokVZZVH#Xu0u@ zFIOJ2V^tLNlD55+fro6Cdmr|%=(?(Ng==s1Y&MvE)L5k%Kjqs9AL=Vgm(FGMfbnzs zs)3R_3;&-gAbxxj%EH0(i*8xz><8{X1X8v7LLFe|7g@c=~2?- zrEREEY=w;?lc!70qX+`$aufY_2~e557{gTwMI+s@>!c63VywL#?d z=h=AdR{II!UwoW#N(7kyVQ;E_C`L+~nKZNEY3|&R=T;@kjHx zUV3J??^-kiQ@@d$2-YnqqsROCw_!3bBNS!ZQ^~r0Q87cP0C}&+s?c-UJKLA3M?DScwkir zYi_#02~A4Zpcgcg%XL_MaCN?C^Ju~J zGDOqQt%R^_*=t}H?!C2!fYSL!FF&YHiU~!Y_mFQm@jd915wc5K=UH{A&DzyGbqNnS z--?h2QJ9-$mcpN@r)9pwjBg@qq(uSPGSM=SuWnm977u1d2$p(6G4`GK$cKoceqqpa zcO91!8S3}0JL#!&zQ?t`Sqt4u{?Q=vnuhueLuHB=aK~!;RNCBzDktRs4R}5yY-74| z$!CrPQw495VZKuGTAP#Lp-CC5#T!=zK1yzg#ovYw()%YF0$!QTWu4&|piKFEOdD(c zY!=7KtzCYBZa4{fDRTh8*(I>Avpb?2k?m>F(T{W2$>;%Jlu)px$dCE% z{F@C-86{jEXlH#6!TSFHZkpL)rniu-OTkabmIZ&AHSzL1`#=YV$W0r(jIhJfi36=h zIO>tk-CBCEu-_pOYhpXQ%?v7$pV_fT!cejJq{)M17>*s@=^)+E8l^BiMDys=S}_~lmt;}T9v z5wD2WG1=;;g*3HKCQ#w}SJ)oE*zye-tsYpAmM?E!*zYs51kcO|e~jhGQJ{-b%BbOq zd~qoww|Z7#3ja;7(2VuC!~Q%OTf49nZ1r1h7cE^Cx&=RQCO55?jkQslzG=j=A}>N= zBF!KY*V@X49cZ+gzG8_Vn2_v>*;$4<^cj4jwrg9M!vA0A$d>mbkX^L~TE6P}Qjp`& zabi0Houb2isfPs!Wl=Yqjj(ky;6d>!P&r!jh-cgl@6~YKp274c1F3qHrzl{fo<3xI zs*(MC-I%>=@Vpfzje|nae`eSd0bEu7Q+9`TQ(O+Y;>gF<4gdo`tNK}xL!mD|;3a65 z%DNm_wu!mS*pyPG4?zAnn@{h@HKo<$j7NRQueXn{7_oF z5SGktQ19wo$8a}5uGF@1q4LLZuJ5glDY_LQat$9W(Oc_{=KNyK;SX9)0$5rtNC)Qz zt(1mud@P9{VCiX%N$Y+-?m5##rvMZZV&UfvJ(JXA)i5hW$YYQ~((asOZr3J0iLfo|v4fhyq1@3?!XCG77!I4H8RLL5e{ zA|zc3OfoL_S*h_#%sC(YwVb2~dbm)S5xF=`s#d0%ipvvmI*(}rx|8a;xd02(6IkpQ zF@x%7+SSI~3<&iUu%QY7;gCYiLHkd|3`g6JIsnWE8MSjDujRd{Or zO;x6r9ZvC?N=_p0jNo*08_f0h`6Qoi2JqyWa<(-~sEf#D z?4_bvT97+Sb&?pMr6+NorryWUlxm6J>Ez4eG+>F%?;k@z3OMnBTEV4GenX&7&Z_gh zF(F4gowG(u)NM{+1qfKL;6G3hQQ+yAu>bn`3tk#7NFBB(G-Ho7BPTnku&8yj1l70z z`tDid$08&>nob7&V?`rlY0gy-=mcA`0ISB27fi6>G2s`;nPoAHB*$Jvxnz$9*1Pfk2^pwG6y`<-sx(!eQm*#Yh@qzZ?5h8aPG)50( zlZ{LG?J2@OuJDr5V69xxV1TWA877%q94Xn!%d3u>?M+21FBv;f2Ikr+@}G|v9GW5t z{5dz22Xm1dychnn8qO@cGnHp;A3jev!b%Pb&Es~D6SxFILx@+}P5Wm>%DcFlQA_Sv z%!oT3hJ#=!h|UMOqEm^UoFv_hm5-F@!R#FimC&83MF+1#glw3*Wx`>#Js^5*T-JB^9BU=6D!ZE=$jL6-QA&czVSfar2+4yX_7UW0JhXKrFV|C30JtvkFi(WY@6zcK;V z<^=;!!mdZPkM9gQ4XfxNgf+f@hsSNga0xi5Ed=gX!CiyHbmBN%osYM{p3@9TT@gdZ z{l-oJ--j4_F-$0#0SsyPHjs*wX^HhN?o}#)l;|WBg>U41M{sV&-KUN>_~~ue4>PgJ z8ia}e{=l^!n;o)Y9rG}6i{~zZcbTtqO7t`gR+m$fuk|n2_#NgC05wPki|RT;n0Ywr z_C8%f{ZaC8O8a3kuDx&5fg0EOeCF_ikq^>Bk$ZV*Wdiu3P}1;{XZ0{aUKVOfJt=Y> zt3S>?ZR($<38^FWpA&()8c`hfL_cs6qNtx-46CFp`DJK#+#uH%& zTmR^~S0u;YCqOqsU^SOV35+#mz!!&mCiGcv%Q&{XK^G0Z!2#`;fKo zrznH8^GLuTW-2JK zbGI+w4MRUK3_p^MZbsr_E22M*Cd-zvH6?KDRqwG9H&N^-4!y6^ZnScbXXzn+N?)3n zp*qCvEdQA>qFkI4>ImZm4yw|VT71+|eWogdPH2=1B;BjJz{eTY-I|aQH(x`cJ#p*6 zG%i4l5ht}Gk0o=l%uM)V!cR|ZuL2}oUQx$z&wqIS6;^{l^^y$140`BccyhF_-JC`s? z)3w~h5?FH3pRhO@wGvID1GV^ZB&GzqE<&MDkKzLI<1*_SUpy@V%}H0FGlLi9VY-e9 zaKvtWJ+Sz>VTCn1&Z+`}`EcdS^PmhH2S8RhNBi~AJLG%}%Z6mZItV+?E;TBW(2w>D zdw;uk&ZPOjH}gq3ye#K}>)x=65u?CSg@z3gQy^b{U;(57e+Bx3e`v$(R#q}{JLbc` z*+A6XLoa2G*C*^pEb~Y2#sa}MzWm^(UteOP@3-DDmRew!puJbC&{otrQxP({zMd9l zp?){$#f8A+Fjyrx*(E6bH_jLUB#3a&7j$Z7j+;FFl1eTG>b>}g?g&KCB=khXDPZg5 zy|6zm`stGVDs*mfvvLrx=!JT}h&Jt_E27tEEQ2tS5>DG*Il+AT#7|{i0DL=&Te)^q zUqql0`u^F;>vnHDqNx`UW?2C9#Rxh$A5!pg> z%uiz?S9=AAj|ym(cqfs1!jY^9kyqOf*b@ObbE$OZZP6Ecl3hzGrb3hefX?P7U|3HJ2vHby(IrY)2xy17!3{ti|ib2d;`>d^aD zl@X%=ezA7+h7~>-3wAOcz&kISpBmSupI>f{Z>0J5F85A}8Y~c|9BTqBL5d?W37%Na zLbn5VuGzO%{})M7q(h|Yq&MgejHos%UYXBxKo~IlyM!x`iLj+nPCGW8c4GaXn7vGZ`SvYVJ zys;T%xc1)hu9pmSAPa`uu6C@4Wmw@TsfUE?-qB2Ua~6X=ZrE}!O35=vW>}#i<5z$j z${DmP2=HN`rX~AXk4&7kIXuvHks_n@r!!Mbbz{|5Xuy=Ts3+-1b%#U!*UN+~*6wg- zmZ+lJ#RkuPhVsr=SBsk)QE%Hwpq%LF{@`Use=GYH zHn{Lcv5_nF0`whrJbu*359KW8+;o^7*(HL;bEJ#NA7e1OWvzFWXe|d{rXc81Y10l( z?*gLk2_O;SEAV4Izo}f4b(mwk_TY`Uu^-u`Zl>H}nvO+-29i$Q;3pHdSwkRccg+IX z<#{+-ki@~BM>b(~-nzF*F+lFgA^zf^R6vyqGxkH68D9;Lf=ET{jsN_K=#{ky z-UbMH_e?-0!m$WV47>pV$BWKh$6HR5c;x?)BtlGN!T!fGlH1M)dJr_7#wzk@&9EF+ zeYMqa)S9$9Lds-fFD0VFSA`M*_~x`m!{))8sQ#qU$r9dmH;(3ZtdNi?Um2`X8au4my2dwR{!Ctcf6yr9G- z{VoVw*9PPpSbH9_!s(u>bEour+}}^+*i(q1M*cL>?rfWxc__eB*$wx-Y^Z6W3K;cZ z%u_PCwVK_%<>acK;No}ebx`i85~k=;&%v|kD|VnM zfpFGZ8*+qWnIqye3BAgr<@H!IM-^PZEv) z_i26&<&LL5Uh2fGXTdMN`MKy@<@Q&mtG>dL6W<W6jK+!skq{B`JCRN+E~&D<{k%DKTM(|7x#5^R;?)?CM-S6@_bw+?F!5?8bm5 z1fxpXG$gy(Ebexk&-#-4uac~%p&(69UgtRcKGt8kk;1_yRK4x82%&4g(4vMjNM{<} z2~a8)pv3obOO+rG)-IoesT^ird>d%W&CLs;9!gbrAhvsKCAX9LM8iZ8{*M0}1J+M(srU@5HXL zh`(W_>f1O?_Y+w}! zR9^~h2~MEiBk&Pd-0&k?B28cDLvKa<6w3{6>-DiHrm>y3P#XU?_o?e!DsmH~P$=l7bbd~DwWD$o=lOatDTUho*`LZ{JW z{>vD>z`>0AG3rE)ZT|=+=8#F1&(vDG$$<1peoyMcrPt$y8~$MUWj>WBf zyIQc~3UKslXbt0**Uxv9@+J_T6N>ROWH#w;)ZTIz0HKTQ}ze}6e zrHsdz;%uP7&kAq36hiT2T&`9pJwNul+J>m9EP2@G0B@RSH>LNa*M81jxQPtxV$h!D znUMv--)Uc$!_{xJPJlNmrDd2@gtuV)vH@hMhK$H&8RQzCUH>Z+H+po08+943@J*7j z743p82YWtNY85!D^4dKPn$gT|iWdd}W9@!^YfhESP_v~&vovHGdai?8z4YluAyYhY zCCbf`i(|+fT=?ddc%f?VgSUk#q;JX3_D2n>Hcsa-v~jo&bk77h3c7D!RjM{`#9Rl| z#Zef#!}W;!2C4z3V%7bLq<$da4R>1wFzVE*IDLAo494`fv=P|dZi+*ywk+Q0$N`I~ zHrUYG?#K4#Sqx}Q5e3x;fi*`$4+8atXC%J?V+{gQhO6B0TyW*zBM#~=3=Dv*ZTI8i z`5NZ58sRE&st=Sr(o>61Ed1#4TQ`h*RdLBB)mwpFq&vy)IW&1_wW~0WaC8e0QdVj}ALS)7Rcp!MojRG)gvdy}d z{tnyl;ymA*C*1f)7xZbxA#cpHqj_SfQDhCIkC9o>i?)Orm;TL4ET=wkEJ zaob<68A~1^EbS7G>byhqm~>_Yo)}_(v)G-M#(vb6#`u7eYSwxeYeA4Pc z#Id}Ft$gk1PCFVxn|pthIspiwK7LmcdIX&5-;L2k{w)pPB>Jg-WF;F1>inObH3N`O z@y7Cfl1}#(`I1uSf9`hkDC!KQtOG8a%#tPXRm8^^uNviw!Wa&y2)|_IWD{SO>cRhq zL3rh`L8feBv5d$K@s7M9FvJc55IquCVE`*Y)W0Mrdwx?T)~-bk4*pRCu92rg_Q;wp z_((&?IACR(LH1|g3_P)=4No8r6H&_}%Yu78!>jy;1Jl%Tokv0mR$CE}XHSd){y$sW z9x{CK(SGui_H1?q5jcrL>UY1B*>U{$JJk5X+6#t5c+?4Rjm0--8 z0#ACKDS&w_z4IP1^!lA$rwJAh{4*-X$KM}{E#!&s7-5;59uK=Of>=-$tejxpKc506 zt#5wYaS_#!?)X3!BbM*F#X-dyusccx(FXpKE~%&XV)or6{+w%r8x_WzaxwhkrO{qg zv<8q7LONF?ghH z{e)H@Unf_X2hhRn?S-LuYDWZzlRV{uDVUOQM`Jg(B)-yG_!}sN5b{JD;tU<@Gn$dh zrcDpKQh7qYuY)PrH%gvUsXf-11s(;BLfQ$k!Bkn?)H60k^>-U8e zdXXw-O3}`dcj?>09gasNaWrZ)-AONdrdKjs4I+4-UstMOGb(>a^8E>IWwTaz{ZtL$ zB{ln!l=I2`Dc_c5a;9DMwcmpMA}vH$sCHRLBP?k_xwJUeGcpCN+}+nHcownsy}!Mb zN??YIGa;79NJ5P&$Pe+One;FAlqZqp0YyOe(B_L;N#85U`GqZAj(7iW((13ecvd^{ zrsanLHWCXxPe%15ar*q!U)bk=^JDwm397`CMB*pce(T`6qAf<&(7SP#sccNuY)}ofcK*qb}5F; zR;OTvC5W@o0Y7;k2eik?;0#uWrQWD#bSD0~|NgTX#~VHYw!7iq!RR=vr?F_;`ng5| zbB_;x>_}(W3Spv-x{#R3!teTo#BamF>LVqN(_rd-ZB>SwMnfb^@4XTP(ge;fH`FrG z=bgs9`e9I&>v(!CP1Dz&xc!e4G_ECoRWH!K^;pGZU#({tK}~1NJVF}=uFfF~PV!z5 z7&ej`6hpJk7XEehgMZ7BO_rMuqt8J~xXM^;p-ZBK#8^evbechlV;y5Ts)V|Cm*##~ z`R>AJq*@P*IFWbB+e$p$UI#Ppt+7&H%L@HoxqLFzNQ5f8vVWvyMFWI`EwQLwoV(ft zXjWNOIF=$Uu+18IynBI-${#p?#)BtEl}staOryF@oW8eI$G-UOwcA$A{Lv30zi*YV zHz{{H;^D(Q^Yr;!F%H;cES9Slnr~B`4K+`s7Vt(+8ZQI%>oIqwDnEumJa3S;y^T%r z?C9i!+Z@-v+RQS>M!&_h7=|{oWtfV)^Y@KB6Q`}XNXihAft`TsNt2DLD5Lpc_A0PK zPqFS*)o;ioPnqB8N=Xd@_5o!*>#qOVL#^xmd+04}EveUmD0B=+EwYKbx~Zz_d6C0# zK+7>F<tW{DwYC~`Ami>tm>OBDQUj%gtSyV@<0bceT z8qBbLz<2hl;O3ACf+Vwnqn)lg(;!5ahAJ>tkI``&0Cl`e)9)|jVvT=8nMBl5;IL$q z>gAcuSR34y7rTuhj=8@nOHbC)$>uu92#e60N_?dw$1ypaRwA!7L#_C`*^X@($Iw=S ze}013F4ZeGuJuk(-Y#Cgo$L#LQjnEEams2AtPJ5yofd#BOCZxIs&I7FBobYMxTdJXWIe(|B%!Eb!jBfJ7AsKo%Kiha`YF$YgF5CVJAQ@a1UA8 zp}gpK7YV6yU{#mW;9mL1FW4@47q`nwg|9>kdBnrlyCDTvm~2`pm1ozP8XX9=#!?Ma zo*RjFhT-Z(*bJ%UdZEohSDsp>)#`ZWOK5T7@ri!gs))Ba?^r}YVI*3lKsO~CDi^H< z9#2D%b|mk5Fb7v|5t!#|w4NZUyo=H}q@}d6u;q9h-V;K!pTs?M&^to)HuBS(6o*Z} z{-nPzDOB%4j7(_5MS+{syT3|dL#I!;^}tc~%aCd+KWhb?3A7SH6f5U*eaba~my2R% zqxr066uCAQexbQDB9p~pChKyxNXK*2Qd30)_raq$L)zP8@6}Y=o{HeSuz2YODEt@h|l+@68v zVgrZPyn6Z}FQMmSVC$cz97aq*kR$ z*2|^a>$7c9PG>{0=#_`ZHL(roo#Y5@M9p>ZG={b;|8&|A-X<#4b zP|a;egoSfdOeYN-{$sq6iVDOJzgwJ9N;I)m!RoNdVU^uk_HSBS4GTNLSW&_NfU9jx z-E((VjfQo~A7{GT%BmsK9-RhwS}uWSpEgQE&n%qJfVzVXY>`@?72!8@gq=RT##-e> zNN|8)s8%Zqq%tGrs&Dz4WrAt|~+jvG^0+xjvoOT66| zJ5qx+y%`2J8fWn`{Xw}fjVpfSs3!Cr6AGNU%ppjteG<&j|2>7!iRYsqM`z68{{-iyLz0T%hQLF%iD*8V1(Pj| zANV^o|BD~_5X@iM(ATbH`kaBEGT8RS&R1uoz=%YdYsJDS3_E>weT4R&YE%dYJ zu3WEYiuYiE#%=%~HK+RnvIV!@fz<(=zN#5TaAY}BE8grGQ-fIadC-%Il)1Q)E`K<;0) zaoD$4^?Ko*sTZB&0ZU4+n+^fFSFf>;=ZL2TLh89x1uZlES;wvO%iy=bz4}ra;R9+O zks2?~kH}`S)4jnE_%zK0QJWote0nS^z@Rb$IGD~AO}WiJqU1STls~8p+~tx!(@f} zi2tdt*qFch_FrBCs~oM1H*_x~swKvwvH@l&5g5^7KJnRIw#Q+eN3ks!V?Ja={wUV4 zkraQB6%C=U#xFDmE1}RvqJW$=3#kxe!JHjAlgs)aQEf4t#56yV zRkjMehF|DY%vp{xrKyibW~GDO`JRg7^FVh6*2Kg%6TleSo=-z9rq`{nr-`PlUW5v} zD&Bht=2iO4Pkg2=L#BY>!3A3ut;0A=d+{4)56_|L)p2wjuj0(k`B}63pEJL-!qdZD z(wo{(eYefNKriw*J;mGtMt?hk`RMCIOF;F4N>nhHeDD_LY>Xm52pf9H{r1kXF-Ok& zuv({?t|T&T-Xk|*2ODt1buH>bN*&_it=()_VX3H_Wwiy)nNdZoPeQy;MsJH(p5KX- zt2Ollt4sBWEscu4N;-dSzyUSvUjCOBQ5!weCMS|P{Q0tVQmFl(^{S-^b;T|=^WWl3cR z2N1myuyq}e!GU(Y60Y~c%Lpa8hzU^kIbLb+?sa>Ptsx zo>sE0Xc8etKU*89Nv>by730hheNG#-=;~Zv)bB`}av9=~M7JIxP!pm$;i$raZ3GQB z*jsv9hI*vuPkwOEB()~nha%=8SGBg%ZLJa#!J zttE`QTqAaM{r#0e`S}T=uo95XXH&w0Ia5GC~ z6&!7O=T5+l?0&7#j#=LIpQ0~DpSmE(?z%dV9;Uw{m$c^#Rhh0~Ts>$+x}w#w)CM5_ zF&f9Xf$fl~tW@xxj)*39Wf?S|HL^j_slgq*&MPN=<81kgg@&uc$c6=3v|+3m+AO=U zjm>551`U)Kw?`?n@L>Q5yst#5$)oF?bYdLZdkC&;TnKz3H1K#;^lAX-jQ)(S9Z~Kc-S?T*H6` z+!+_FJKz|G+ym?F9lPgx;p&or%7rQIdjaebsvL1vrpfpCv#kcD^6kZ60VO82+03yU zqHkx(Or;shobFO1q1bc#DQ;3u>5_4^6hLm5l_v10s-EN82(?W`LSMnK@2AARp< zmK_SH=~vaOX$`Dv#he@V7+M}l@W}t2!rq2Y`q(OfCdykz1=w-%fbiFwutbsB@!WNd zHQ7ZcVg=JWMu8?zf8pV9+a*6e+t3-&(z#&6#1ky03#CkN@@9{L9$Gv^CyBsY%c%4_ z3EVK3puvx60d{5kI|A|b;{f5SKZ&KVxqj&y3;Z0|EFS~-P1*+z=_kLY`*dFSL2J9xO27GcS6TSEcWt>;(nqbDzIO9kfhv}mP09kd) zw6WMqT_@x&_et7+s>$qVp+Dfam#&=fV$A|XOu_z4WbATJ7*2l=<`RT=p`@B>jM?ne zjiY`F2(lA?%e_nKJ78x~6WU%B-S{uTDADrubuEBm48^KmW1<*j$r$+;0MJ z28b0$m7cgwsgZ+Mtm&t2XYF%W`T1yK1*O91*vW0|53C%eqfHSiXA9OO`+DiM_&6M< z4Ekd=oJ_5F?J^Jm_^{~F11GK1aNRG`2VqZ&Fua%?-i!UX{jQoAsX*&1! zpk8FG)7#|r%jQ!cl~nF^XM4Hv*;_pN^57|L@ufe`9q#}pL7(H)?f54L7%rnB0Vfh) zZE;rzmbOLb2O@POmZW-nvF3M^Ki;QsfRbm0_TB^8Wsya+Oz8x39K>m~YK)|u-S;|k z%tZcK)+SWs$+xd8A3?CpcviNOR6kN10xNtnel&NbMlnkYGUd~r_Lp`$rSk}PDzAp8 z=IV*mDG&|CT%cLsYu_G4rtPjdp`l&GP#qn*q-e&A{v2I*TM6%_j` zI-N)aP;O7_(Sdx-{9>41^!~p z_r$4HKHo3p`2il!IkJ6qj1?57_T~9f&?IM+No*wpnDEAk3{~W65w(r$G{)1n>f#8Y zq9EzQdYcTUIgEO!Up(GP+TKE$g?h5;ro4;1qFHldoDIfQt&D zm>->dJN&mteb~@@3c!CK;z8P#Y&8yKchOp;B3>ejeIjVU&+iLdWwBA*4IpP^8FYKQ z_sp$^>3V}LMLMOjAP8qPSS|AhMh#0d|cSs0>Z6LZWs`L%V3ArN>K2OXI$R?$6}!Q*USuwTg{ee99`O zgU^1SQJil>wu9dJOiyHBS&3KpZ?9fQtdrHUV&DT}4ehm}_p_Ngo`wWG1u1}8jXp%T zvRbFxpcYTgN_}kk?&>8pM`8$cIb>VCZxJ3#*}>~w0=Qd`Pi$D2Uc9$zq}^8U^RhLA z;FJ)vb-b5JrW4QH3gWN%zQQzH*~t;+8-G&ZZ&@yIMC^pkOfCToKW;L;?eQ#|zHPO1 zudlsl8XrjKESvEV3Kk48I?OPIplsq#B2 zVUppbiSaD^g)zO;bz#8f&{(Z5B0ogK4K~m`RMr!m!04owyOiKJb&^$9Bie0y2h|q`8** zy-`;V9?%3RukUlKGk7ZQNmEy<3x>vV$DhSYe%Ow}wm1xp=M=x?WL1QRPDQQ%E>QdI zxGAew7hphjRPGy`5l{tQ@xk6yLmNPf7&MsbgoL?Bl6;Z--C(%+jC1Z5fVgY0=Hkj7 zJUP1NEVT~gGJQzRL&W+5zW;uXl;nQANB>^WhfL4>BMPv-Z!Wr>%O`_FypjeBg!Bh% z?Ak_q3Fg;mL@9_eIp)^e;phyp;<&zJRszE=D^H5CNhm5XN4ZA0lqp`M)Q=k^A@yD7jWW)k`1`c5~dG*-vvVdR%06H)`nE8=b(z^UBMVnro~GBe0j4-%O5 z)+<50*0_}V2v38aXr+`ErB!fg%rk9oVg|ywCEZT)Fb@J%RY4|aM;oLbJu|9NV+jw) zsjKS2gsW6Iezn5B8+T>@>CO!puoN=V7~;}B48)=9p_x+0-G8*`fivJFz_h@vba6r@ zNV|6}7~5z>P=#xG!?YRFLUmNdX~tI4g2qmjo$3Lscd+Lz>um7**hScZXOyV*EC~Ka zd#PtyA^WXQSp`5CpaDpBKw9*C!CZI|uXj7ghK2;Z*roo#fRGGTmjjQe_twK}r7H9i z#__SUWi(G6xpY|x;fhK|rzWm1rM}}mTe#qR_dv>kKIJ8+$y^$`#7g&2A@}jReyY`3-*041c64NFh;!LzH%;7ZG5hTTw{>y&)4I@b zPCW>cO9;3GTodDJ5as()21C(PXpcs?kaE*)`UPa2pe+l)gYna>{xT4)f*X28f%-sBA%u~U+jNKVQaC%cEmIxH0Y9#?PyGhU^9 zMa^D{MBPeX!bGH!{7uy3_!37GE=fxUM69I?x|zGk9X)(`#>0Dl5^CCV&bnbMkx`){ z=dF=JfZJu#n*PjPoGKK({^MtwY7-T~eeML@FkHk!=V~BQTYE+gN`PM${91rzZ_)L_dq94hM22emjK6NpW22hQ{u6YK8WHIO6Q(>hGs$@-a2E_f9CX^~t zY|Dz2g~bamtrw59Clw?JGB>>A|BXgcaEZ~v$Luv=lS-jI7cZxcuNvzl##SdeYG#PL zP&M}qJ25_5FZ$d~ddTU7uQEEFxtIxnJaeQ!qO9FpiNT+Yp0jr>5Ic9R9566AZ1ZBU zldBGNBMRcX0lJVfll~40kz)tEm5YYg7}dlf5ajB^Fh7%LSYVlAUKkO?n^$(4t>)c` z2f6c18KbNVTx=LC!%<$KYq>Yt2dnlc;dSM zqS(x=h+ybIVQv~?8)&5b2?VOJJRz*yz_?8) zf1_a)wkB5Z()4ojcSJ5}fomHAM=R;c1$7eH(eH$soTo-K!9Is&Jy9T7T*zo5G`wLk zDJVUazfLg|zB-3gA?BYqT-1TFU1VXtswLdj20_>@T9faSP&TCZAeTxr)3+@h4S()I zglB~9@^pXw!kB2j4)Y8WH#F6UzEeChWQxeW89UhtI_5D}zK>%Ms3du(Xs2TO8?FO@ zYyf3TR8(SC%6o;PH(L3Rb{84fjE)TmG)Ub@bcr3LJ7rxb$ATrrTV!oO$|C2F8dfUP z(jmHpUW9{keG6=c#oWm&N?^mQ0!ukZR~Wg5ttt6mYCY zthZ3r;G{7ufDjDPYp)alWzLMmJP!Z3{N1#dpL(xMR7uEiGwlH(*oBa56PR2hN$^_) zuW$x9a&4m6&<`ePcLv= zyOE~RP+JMs=G>zQYro2-Cw*ZB@DVPe{0QmG*}W6*B8~dl>J*l73revc-baaxxq*&O zGHqZYa}l+Y0&rmYii|yt;(nUI_zA?cRqdj-q=*V;b#&fRld;4Dp!!)?i3 z|HMPA9mY5pqM(`-t)L1WPO_5R*?M46_d}%y4S@xBslwTe?e(T2n+A$?FvVrdmU26wR<`oI2xs-I(YyLlg z;{+&c8`MH!&W80)LV4n@+FOPy9IcvO5K}HjK5lrkb!0kB8*MM%br&D)sOQ(swLLo8 z$C3`_6p99KD*7PjM$}vkAtEEoG#k4#(7`cnc z(iC89X34KV7>SiJ&u825T+90j&i>W)$aBpYl`L3UmU$+`Q8Z1>nNPIo6{~#Rq6JFup+eNm?M2 zdqvtQ79r22AP(|*efSv1%L_9_d|{DcxC9}v<><$2m%o*kL~n;OPk8Jd@Ajsf<~6_> z=7?Ph5e=9io<8Eo2;V_k95uHJux^@>YQK1>ib z&?uJrkTz|lfxX(3nDLh163znR%Ebs)IcZy&&CNjv(ac=bRkg6t3Gvw@g*bE$p}qY> zMEPNJvBHmnI=Lc4aI?v#R2jEG{7O{rEvUj5rPmLVRjo=P zx{QZaCcY!&*s{)MblwSHdZVd^-Qxv-Ckwia;n@ZfSE7J!!Q*OCn%wlxo(0dhw{`ca zJB1&Ea{a~)IjwNQkKq>Ay5b$OVOjY&7G(!FlM(ili5l4i4OID&Xwu$5_2_(;d<_XM<@& z&K?)hqRi`U^|*?WXqt9Aa4?ZlP7OZWH1!O+pjLaoC?Za86bOlVNX`aKleci2$E_%R z?3sr^wy|luVL44_w zE!q?eMy{mxKEYWD$tFW=T+{Q8szVnw2tE&^-<)Ij$E6Vfuh?edEC7de+@`1uF8~c& z2OXc;|Hl$tmk2FJJdCs7YlM(Z64jm0VNn|3I9w_8h_AqHT|z3RYRcjFBUM$eiG7u9 zWps1&I)63pA+1m(;!YEEaNou@b`reP2$E2N$*8bi!u}1($ZAybgoZLthIt)No&lb_ zNW@LKKBas9LVQjN^OoACSmL(XYO^%kW;gBFr;IxYoIlg%_QcSmFWxrpo(_kVYlV&# zE;n}c858*y(9@#vUPTY&ki6^gE_?1a8UUV>RHT~|e%*4Wx2tBu0r>{pj=Q<+oT@PV zHhtLHimqt=_Hicam4^+$ltU!5ZpT9gO`fUW*oF>^05<5uSLnz`&Ipi1}VU-i`Z?(MflMJ;ZU`d4XH}u+xPnKew z+Zbz(ISScw!}fY<4Sf7Uu@s*lN}j>mfkt={U3pWj%v3fASB<=)+CBJrQ=W(bH`+tm zb@}9Zx-~|6q4-Hm8@P+4n1!e4F`8K>{U;2V9o*~QcbUXoT{vOpkorEA|1JXW+$`HM z=~d{}ywPEA3~ZsH(G7Dn`q8R;l6IYUL>VM`{_D>EoLAw9D+o&UWI$l)@-vi@Kaky^ zQ#r=-UkW@8P&`Y3XoN*QcYDAtry}MO*y;j48hv-E@UJ|@9P0t~FJ1MjXoJHq*Pl9y z!7vL>$GFuPg2UDhjfNX#GXW?eAe9?3-DQXVu9#msm}>kT@TCxnGCt zo9{quX;VBJnzq~5@M8(Let(G=U;us?HG_G-kTxGTPE8l1;ZayY7r4esgGC;2_nfxF z%5b3=22xjw&_Dm>V-oie8{P8+?1`haZjtgDNC+I*9Zw0&JP}Bi_Uh9kBymO)-}50{!gn~E2|Ml8Q4`nKg263I^`al_db!#CE-62o1%79dtcWb36*55N53j+xJGy}WI}%-u#fg6S4f%j{-Z3Z-NZ`IeSNCM=IOnSo{{7Yr)jFv)Ikt%v1S zbLFYA&vjmXsKMvm*J{iF|E0f4JjlC+nWPp+osoeTh#RxnBb_M7**y%6khwV=upL%k8>DCnF8$8=$* z7mJdnAP+wD8tUW#lh-rudL5V|iG-r20U$eM$>+tyk?Z;!ae zu}tsy!;nYs4;O^I>`YWFDihxDzt~|TJC4&5$W%oc49GosE|5{JVHb2D8@tEHtoy-g zCc@*fo&E>$UMVW1h09Pw5hXl7By-sd_7BAsjZC?&3`nPk=2l77?tjklvlokrdI`h5 zks+Jas$hw9x+)90S{BkD!v*8-1+%n9+1EL#kzMg4c9PmeInw~3VJ_t=>$c7&%mQhA zb{q7T6%S{w(0G=w%s!qRwN)YHKtuv&2M^OQs*aQ?BH}$FmXIJnoCYeuPa{elh{A>D zFO7&B-GmiC98qEhgMb;WnvY{gQ)BuoaUX4yR6TJrTbDn%`LY^noe>q=}AqkV49qz}I)2mNUO`za$NWUiFZ59|~YCPZK}3_|}q~Wn`ukEb=YZ z53H{S_tDtvAdDojw9Qf=g-5V=uzB%$ckGX6Y~ygXshvdFubp;eU!wfw1pMO=G#z-G z&}nl1(FQOd6F1*u$7*(EhqH$zI=$6uRW);l!_xAPZgEvPqmM`%)QbtlJZj!T)(E&H z{r<=HIJWKv91v7c;7E%=$^(rXBfDMi)Q*IqNaKI=Dx~uGu67=daG{l;?JqCjS>dxm z5eCsyx9#6LD1oMA(QB57NuPyy&~aIiNZMxkJh|PCx&7-pnE5zvA4}P)x#p&j$7ogb zX+%uaCha>|CtSKrvbVsb*CIKO$dx^hJK7uq?YYt7(wkk@Z?0u3d*Fwvg02muSyB_% z=tR)(@TL0!Xy;~OwV7&UD&ROre9*buK~x4-gXPZN)BtZJ|VaD%&WW#6yW3m&^-&k9^ zS#a*9+SY$zBF~q6y@T<$9?+3@K%&_V8&;*$5R8K$SZu!tU|*||An%_2a&EI%HIeN^ zr%7vfXUs{5MhoUTB9+qgC*k{e_Xlzjl$n4=`a@3jA~#7*634y5@$zWM>XDYtDG zu=drLMD`jHG9Bt8j42_83`EM-MjD@x<-TNtfrLa2s?x4jUhcUmdudKJWd#Jyi^LAF zcw8=~hO;w-0AeF-+6HLH@o%`SiqIMR*-kru8F+lVT-6;!&!!sKqsAYunxKRAEEh!q zh}TgTIULJ>&`tPymntgi3Z7_a6-?7t-i-vlixz&JH7%Ub69*$xkai+MUM0Kue;B=s zx3$Zv=hBC2&fP=b*hJdaiqxYa!L4DK<@2zKML`^2S}035W2u8 zS1*2N3z_GFJ8o=sXBLn6INGmqs+Xw_7Se`V>dwS^V$$~uQUjs=v;Y~y663{jO$%y4rbw3+9v??HY~oE|xjBjQROEtQ^cUz%)5WC{RkX&nd7bk&l; zZS!m0c9^ADT_U3DS)R4g&WV$o>m4QTU+~g7rnRJ9gP`99-Z`t*cJ@gj9+@V^JF`+- z1lO!Yxm@wcZ9jyxo-fBKUoJH03$2DI7T15rcAT^d!6}T}nMZiQKa%;@76~8u_RAy_#3;16`&vjz4{6kc z#RAV$z_%$l9hx_OQ9Sawp?yh-cXEW_{p*c-YK26OGX*9677rIN(98% zz|R4r!;zfErP~gMPMm_s zlre5Ygk*lWl1@6mgWGzCk=~mv?3zk?3xa1mMnJx}q`^vW9}zb z1Vk>$rQ9^F;f2QH)<5Wf{|!B*J5JG0Cc?S}B1OlbJ83&5x-5@o4tjU2VVwtcKr|kX z-#QGy6+W!>`CWg4M@(yw1W@=}a~~LL)MweBBdf?PK-CK?Ig{pcrH1buFUsm5>qtkA ztKG(m`u9xZmuv}fmBrzW!Ob&&MnOPo-3(MIoYyLH3TLJkq~xg zR%;HSRcM*v?o0rjxN|(zcHdBBjnOYJ6>Mi7M4uI(8+Mn(^^+_q-6*?LqV0aw zT1)Hvox}=rSXL-dwTo04$(ZT=leAt)bw33pq8ApQB7wZO8$R#yGWLBz?=SB%Y?+0YpgJqe%F5^GAw$zh^3GMXiI&8r`dUR6@?%OqZ}bm4w=H>)DFLgMvc zd>L6w3vTjSXxPC+dnX6r0vH1#n@U}*+~c|GoK)h?wa}J_N;|foY%XIIu$R#qW2qle zNf~EG9oaL^XCVeZlT~e?PNe!<>byu~jT>wv*=rQ?D;-}BZA*Iii9A2fZO0uGxsFF7 zT{Suloe8BirGx!oRLE@i`9UQFMSN~7=yRM(TjYV5CaO=IkG&~vhf%oaS2PA#pk#IN zIW(bd2!Bn*N-xhtS}Ivf^wAGl=xjD5c1P@#niF6Ak~S$fVNf@ail_^C2#mQ15cRfA z#R7lfKNtA#h2zRw=l~jT9qQSq*=;B&g&_o)?iN2n=+j`_f{JOZl4U#GC)f~(#e3c4 zY-VQKe861&e=oIo)Z5uZ6(!V4sqj_0b$#7+1l-oZ6pvy}W~4>{P4$kBl4GhNH<)6g zu|9g@LF|yczQH*F^OcKN^W+-^mxylimre+$ZTiJ{@5hZBa(r96M%kMK@Z@Kf<B6nG{NKh?-@MqA7-Q@2s%8HCB#F;#=0W;- zi&3Kl81&alGk^-lhZiQA8mrpML0W*gFSg2@%yelKGuE$X-4k4mZ-MRjpp2vU7*(S) zxab1scw@L?tuM!XW@p~}A=caM{R(zWLiCl3uYKfy%<`Pg9q{*$pypEYIZ8~5W__Hp-l0JtiT{%Nx>pVlk9gC0APP3_4 z%h7h`DfW;iIS~b?s1Q1g_@yY1y%ROvjpUdku@#CEX0Vt_hC=)MK&vUsYHM}R&<#VA90g= zkTA@`AP_lwkkY%F6RcvBX62XnX5;dg+%~@Ln}p$U-qa$0QBv%uyY-WH7&_1lev>Af zds#_oz>KX&Fr}kINp1SA9v%b@XD-%jl~959Q#%-z>X@&3oVqSl zxR0~D+<}j~=BZVrqwuThABc7yBW8(rb#`sq-9xWq&6_Jnp##(2&Fu%U{X?#cD+x;>k^%M% z=)_xmFtq}&mA!a~e2gprDtmBO-~GUbze&tN*S}^}m|(XoYfUR)icKtr$UwS;SnZzU z!iZ%*>vE*q{6;A;@U|rDZAAB`G>YxZPX5C1Xjq;~f39F|8ko&5HDXe0)xah?J2c@O3sXN7RZk9_Vj)$Q+f%E=Z%r^--LxFah+>{uFon>{oz&eYz&J9*_R< z)j;Qx9e!ZV9!S9T%jzTU#xW>lg5{9&SyHuO9s01-I)I^er=diFyKM4I{FAnn=Ci8w zR#ID&*GQRwXD%%r*K+lA;3*@7pbN-rUk{khITYy-)NMga(cGFBQny_sK|PF4OE%51 zB^aX}QDg|}%zD=%k1gTISa9R2lU~?kN}>OhY__F)NuL7HZ*8CEyAk4>MD8>>@==EO$jG28dd(G@Pa&qZ1={ZgKO!;!-7zT zZDO)|I|)X{Pnoxc<(Jwt5behk35JOqCv5)#*C|Tnw7|d4$Qez|7zIQ;a;3Ag-EL)R z=4^)D`1E3Nc*-0Z@qs_M!ic7y2g*sflc6E|c<=Tys&$ZvQ@ zYrL{RGxMT`mIoIcAkG6pzPOFu0VBCpPXV2ayP7LyVDDMH23$+Hi@Sy8O9DR-nyh?& z)iadTteCkeUO_!Q199uP9snwp&>vl6#<8J_!xGXfTZ*|Uu@g6@J9qX0o}*d?w7<&@ z%pek9Z=}gmZMkBq?C7>b(UBS-G16sf4XO2w_Xk8{R1Fk$Kww7Z7SHXNp(MKV|3(2b z7|!MsC9wbiARF=*U5}z+Jw5xc1;%G0Bu2xwwMU7_} z`gg)Ls=D*u}U`xU`0mFC0V;A||aDh;u0l^mbI=>G?9VKQ5C*Xj!@+AGagT(~7 zu)S|yY53WVz~!`#cizeaFxE1F3?Ij1folg|6m|O@V{Q6zf6&1-V(^Iy`1ZFzW4=kD zenImTIi?^weM$h(wh=;S?U{FKKZb2_pvZ#E{ZmSgc@-cxJ}>_Y!u76%@DS%s{eb$L z!z~y_!s>}1$p%8!HLpTYVSXb6FR1ooG>3+8L91Y8}7ag|(vLb}UHz2hY5!JX#!o_U#<8ZZEPmohI( zr!Q2og4$|p<(yn;N@jd0H3jpb43g>uGXOt8z`ya{RIXk+UIFTgCM*o@D0i!mmSwVl zzM|&*kQv~MPu)t(-9;@SPgKL!U1EtOTJ;vXx!`1MUmkkX?EIS$ZDbCw40Xc4@9F>-vmosWLPrMf{`5!S z7fsc{AMcYtDE=xS25BJSEim#W*}gkBr7mDF$eOWCU7$=#9TbVXI*3{2R4Ql`?05XrzANo0NyUAz+d<6Gp`I}bBF%M zi~L_8J3GrfQVwPzroRaW1Cynl2w=i};a#2B|N702``W&?1clcxituInntj#cEgSKI;Qrn+ zA41QOnN^%t?%I;I|GSFcZ3K{3ImQqsXJFN)0YjgDIDS|=CK_f$$VXHC zc5lt!u>{XaD|8y}hvjt^;x`_MnxE?^^E8o(&(N3@* zI6#;n!g ztv~lFm75#*ao`rvWdBzV94=R92M`fwF?cikW$ie6BJhUwphybQqy}8LFte%JT`A zAeFsV>$G%s#U(>9=sV=uAzp(EYAbKW`2AgSo%LvU!V2o~z(8=)J%M4j*}lAm;^&tZ z&{vfMq-J7=f%z~<1lJffO#X2=3SJ9fD7YCv#61PjIBqOam=2|P(2cEfy~)HG1*Q;9 zu+`yx&}uW#R5ev)W)yYGF9knyM`-Cfj(0UyI>U=^saoN%_QFCfnQ^dHBQV)))#%xT zO8o;Pm3*1`A6@PZVNsn}^|kDo%UB9V$#-;tGA#Yb{%Fad_kuhF>7z;M&i^%pKqWs=XnkxLeF z*YZkhW7enrY-&wH6N;xp$ z4h~!!!hAk4@r(2d(xI41TLq)vV*?GV8C(xmiEg!CfIOf!2D#eoj0$#UGCFc6vc z+`%wk-c2n;We|gxYWWi#4k-r=iYX0GYc$diy>$nG}>NSp}!m;_U+l*jxT+s6V@E6(}`p?>zd21W7qE4?C zAx@`k-uZM@P+NL6KTg^g6k6I;8avj~bj>}}jaS(Hb(Z7!)lv0c6m|Eo4Oj;5rXJ3+ zt0z>9S^gC1?N`3!rTfH^X~b6^P#?1IEU@aSI4k+iVsekW6S?Uw!6U1Lv7s(;%3H&= zKbg_c0tt4~zoed8T$(@y{^IDtZLn5Kyy@coC;^|}0XFdEVgnv>1rz>8igplTBu1LW zU2g$hyg@rWQbWE^fH}3T8?2qH=dYYoVFaTK>n8003&U>46HMhCA;C|~mxLV0-Mc(e zK31Q4>IlL|Weo;A`7x40y98#}K=A+Qpb~=^l9D-~iq15o34uY0eN?-)ym*6d zEt~|gvy)Le>jm<=sdx+k{2Z^h+Z>tTI3p!vpII^PC?d+6Uo{gr4EQW>FR2&;;VhlUI}v7dX6l2Wd{Em@E5Xckuh zwIX9gM@&o12(0QCy+xQXfnjWcmRxwlJj<%0RH+|5;Su8Ms;#IF*?bybvw%i3BN}tj z%$^fwWP?m_5obJU+w+)OYX95>1tG13?=0I=d@+&nk3Ew7)hgTpPT)zyVyVrTM0*28 z98h4vF(*L-;~pPSuuxnEmh4t~g>4vbg+v+~Q#Q7Rz$3Qe;71k}07HMWk0ISIwT!J2 zD7@yR{2UrSmG>K#PQb+9B*K@5p=|;w^V07R>AiNt5WJF9bud34XdgTtS^zS8kahXs zS%_R?VXqtWe&Er?Mi?H>jwt&?*Uu}AVE$MJZV;vm9d8CS97=<{4_vCutttyGuO=5T zgX5_ZH%|-r=wE-^@DCd7!BUn&hszM#Cf#AIQZA)i)DH3W# zLfoYjQnY+(tZPibi(Bp^);TdececmPY~0sjw$s2ZI(qESE*koKiJnHH=SStp`_aG) z&!5P38^;YoflZ|tXxAKWetWFtD=x}Yx8ZxZS|-6IqYoAKMlsN34tXIUL6J`ryt|IT z>)jmgHmN~dIb%b-Lrb}TS!cX|3Aa-DhjSuG78C){(+lMJ0&{P$k9~=;`?F=Gb=CK(3|@+0wgO$-HZfgwfa)+j@ zE|XqOpd7*)WZ<3gftjMnGIG4RAsR0End>QP3k+PHlU|70KNSl`DtWX66`=S!{M3}1 z#cep1(w&()71xnWJycZX$E{mtDZkd5HSr}u!2U!B@~T|wYJ42@nUo>+tRhrCflwZ? z$dL%_(TzY8UYv;gSO%fFzK$OKK$@m^C9_WR7rOhgJ@x}#GvsaR_ue;d(wpIkab&=D zIJ_M6Co0Cdd$of_CWzxB4)aWbyOS}c77G}B7T;@qp*o2x>yvY3p@iXMc!?!uD#2lE zWk4qbG3mIy@)y1VP}1H4M%Ead{!M~e0DcU1je_n}i|j3>7&d$|r7E;_;3IijSLZEF{@^XcEg9D5c{NxW5Y=s{OUzQe}a-`0K98v!{deuO_(697#f)#-X zwte~w%CLKPA_UV_n!I(y4oxCL!u+qcCz*$NUcZS`t_wd5ZG!Oq5`Q zndy7}#$(Rqvzm&*U%FB1ahc?*9nGqRH}iV>Dp)%MmHm_|;!pprKNtd#gxdTSq!

    PEn{Z+Hp>yyrlx^TP93^x77bFuAY zwHg8rhqm@Q zxs5~_HK`R`@J-wEBkx+rya5k>u*;pu!OB@wyf@<;R{x`LGLq(`20=y-(Ya;9afK8; zjU1_RH7J0xWqey@DTtWnOC~}+Oc*i~nXcZcHrx}#{rbKo;Vn1=8w0wZ^Ip+R2D2~6 zt-A=6tk9YK+ah12G;53MHipp)4M^A=(iy63Q=S=DffA(}Jo5VcwuN{X9bc$!QImjQiV<#}r3Ko--8p#;9A z`KaubA&REKVy#`XLjhMi0v;1}%Zr}BiX39%uu*=&CpZ3n7Lbjg7Rh?bOcmsQpnQs{ z71fP1(*JfgxyhhPY;DMzjIHKjqfuau3bSm(`Xui`QSzUN?fqh~@sd8~4_Xaut8i(Z z*36IkQQ#Vzze!bnfU+vQdB>{XMmJOoO$68e-gaBdW$CT0uSE2fX-ZJ$hiN8756_ zrTzyH&t^^+m$aRvk+6! zAn3lM@74UGYf5VXH~Hno0fKOI85r$3zIwCRe0dzw)f6*0Fd+C*`EYw7lA#;X$`;Sz zew+mdJBqto?J_s9bv|P9=*RE|ow#e(_vsSeX>mm&=gr=aTJB<+tP19@GgxL-wKl-1 zp?xz?Q3Iym4LP(8pB`0*QHbuzYV5vm;AL}7RV*{o`MB*@_y7sc<0|Dbkcvg2ky*PX zDu@r3KYPg69hKR|D*}x3)w~V06f77K zxn|kEo#==72b~`7qPP}#mX56N2$bZZ{X3|b22N{nT(?(A+ZYJ)QoT?uv!@s=1k$l^ zwG%tbrXb$@C16f}xYGVzzR7+0I2H4DV4bUK!vG}gZy44q*M-q*_EeMFHX`^5ZGCQW z@dRukMS@`&a0t=*SIw@*?Vv3Q$6*ocKBJs;8VQI~1g}&MSY{__qZnng0_A&Mb*vK%#W@K~QeriC!@RLG zmVxI#pVaVDy9|lM7%>{dX6@b(_%#ZU7C&)2)NR9}znE*}3*xK3_Sk^k9x-fC(!@_W zR714hkzy1PM4Pu$vKE$|Qjr3&-Pvo}2cGK$Y^r~J+%D%tvl%h3}y3wYjU-d?E1I zWF+7Ycc*=1FjKvtPh1Y-smLIsSj}k3Z-WHnN5C4%{u!;Ap6u|F7TwrQpw77yb72Y- zaEMn~#5F>-{4epnwK-*p3wuj)dCIHZ1e>?+uoFza1SEtWIrc&Q`ie<#ruzx#-s)%A zw_koMyFPh6=40A#P&MY?zVw`$#h@;WKg1&A;~)=vmxL6;+&g1Er7}qlX8j|0H?9U&flhO zdH~N`SB}Ex!EX^aq-5|&kijsnpW*dDtV>uWtCa4q(whm`AyoNGs3}9}254c8OsetPC{PBf zTl^8erQ{(QJDYzQ2xF}qgAsr83_OWiIfb4F2;z5i9Ox?awf7w5ZQF2Lsqu&e2r>RH zy;T2HUtfk?I&?a`|4kSKL^JXj!8V1I#`U_!^BSTD&qL5qym`LBELPH&4{J>F@vo8b zgBo8BaD5l~hv1cUq_#~>z55p^=7wf_z|qg8U;arhS>Vm?TZNE&U>x4+Ysu{2MK+;Q z7t?3jy;wIu_RP3PMcW25yI{c;rt^_bY{Hn`nz2AZeIfzM8A!JGJSUhd9jy(b<^5s% zuiISK-`c>5<|VfjUYNiP*BM&SuRd)&X39QSwjr?)9jk=2-VG&GOp*lg#eZX%(^JkA zcDDUG_6|k(4HlXZ?qBIA9N+YLZ-qj@FaIXa>eDBLV%tS5<;ND zkcS0P2;<&won$_6_{rMVz@8+Gh7Yc8Z!X0MRI=R1?8d`WkNa|7kqYoEa%sgC-=L}q zV#B#j2VU|P{@QZxMBkgHC0MjBLrQzNehD!r3ntT4evSIaiF&>YU@m7;{X^koPoJRsaMnpW;;PRi15Bk zZRB5yS5C7DneX*-BrUBZE5>k$5?J+Ab8-gNxK`M_REm=Z-;l(15~yJjiZh6QDSc>B zzEjNnJ{&HD50wdagsF50ob3brpiKRk!GcX{Li3eCH1kjFEi?L1_;u$Bx?nHEw!Ag_ zpLm<0%PnK}RkqI15*po|f|oB6_1Y%m+q%>bBm*>qF6}fh07eSuDwN3|aJcqrwtY(N zl~9Bu2b$L5ZDR*7evL8wDsw6WNW5=pOlp+7)ip30uvZQ`rwem>ll*#WA4N|*yFeJr zi%u#HLOJoLE1vQlhyw~?e3n2Wi&lvx34jI8IZLDwIGym$W7Irv-alPfmYvq=ZtgRchddY0 zm&e2UjN#FmNy~09?AL6Ro7^7U0O*tG{V48%6GwrA0NfFUXfm3U3CLkij^D3z0!%yF zF3i9t(}9G+6l09YX&xcHB~ShN$h^%MF6-AD>q73Z@jy{aMRk!hVi1zme)K1V=}FEz zWcmYW{C}s`qkWFgeAK-Fj~RP+N9H=gyW4sHoQCwk?%!y!_4A8EE}lftEhDb)wPDGS7i{%T!veIvCci8>n+r${w67C5O-3~P zT%M~8N^`2}YY)NPif6@@XNwzbY>;wrU$@ZF4aFWQQn{zs!rhc%D=Go-5&GVsBQkId z8QKgDjA6ivcnGv45#aoFm!@MSkICS}D)90)q@G)w{)_UwIom!l%wP#zru?wBJV^jd zzzYa`)pZ(1PqM$)j0tV;5B>)ms}QSswH0h{ zKJe>7Y9^)G55Q?TWO0_F*dN7&q5AvwPKXhnm1H?07x#pi89KMS+6nzI>HiS4^N<+? z?aYk($Vm%oPcwRIW3ZpZ4^eKy+{{Hp2|{PjtkYUk56{WjOm_wNG-P5?oJ_?>PmD)< z(gCK07J8U%L#RunJMiRt5DWm_MDS((FLJXU5DZ!#3py(bUy#|34bSTR!BENC3# z9l@JDK4etKMjy~z2*I2Xh}132HdImfIoW)hT|%JXr^7yWO?(aJpmPISzVdgu5(-eY zrKvBTnWNCwB^J%annLDL1(G>w6`~=DH1OqFV#f$6I}0AHk|`7LhdUr2p+JtiFt)Os z@L_B~IdUq86d-U|%#%z(@?lX>ncwO^ZRro-45G=d= zE3_6pw+Y51N7%ww;tQ- zKV>_^S~71|?lr$?!7}13yN407E^IEM^Naw?KSZt|Yl?vfo86K-rx=OHE{D{?xfOE8yI#m>5q^HDEM@FuvxlkCm;Fx zV@4;ZY2GzQY$5%>BiuqtS8duhx2sP7BZ{k1C3=p6=HW1=I~dIQ%gpfNJa6*Zb{VzP zprWJ8Hs$(ecpHQ^c>4{xcjYrR_taXZJvMR)z)gcC z1#u7iRNrH%(+MLwsQ>lIZuwCMWou2!*I?tc?M{7^=X+V#>;ciI?S$Vx$L4NRA>apH z@z=>xf!#647|FS`sA{=>Sq`at@`~G78D?I|;{i`bGFROR2giWc1IQt5Pa5)=xG`x( zd8@_Y1T5KucaVTr?*$KTJMqyx45nG9Kho0YG5HnLU*~AN2?_bxBN75ZAB!)zhKH^% zfs)G8p-!+#>TE1PSYzm85J_%niMQC-9VUpQ=F^u|yJE#>Av&{VFxpd8!Y z8ZI3K992p}?PWCd4$>j}^`p?GBXV_pFH!pm_MGiJj*9EOfrdWOl)>dzH|QAqpe7gy7f?=J3j-JGC87+JOSfARSdQK5_*u)NDf;6=WUK}O#y1?ibKTUdY;k<{d4({>E zfv1IC(K(kP2;YIP<&|g5$f0Q*jo4D(BM$bG;*JTP4W`@G@F;sj)-^E><;#pWl#wiM zh%CsM-i>k?wrTVVXqZjn>@VKW?^>t!9W}eqc(UjZj&*eX7@y_EIhAj0c#?nCzDGZK zh%Q&dZHprjQ+aEp1WeS8>)xCqHr6)ZBULi)$^M>-Qxi1wXexMY=zc;K4Qj&la#U0U zHY{%Z>Mdk`OqCjND?7SP1J-aMwZTuSwJO=u{@md9KJ`{d3(ysZ;s7R_o0BK+d-021R!2I8> z$KB{FH@rTwSMor|v*Zw{f(C8=Pq^P*b?igb!BX7h8qKIUtgECFdP7WQKU{D_p6Sza ziy;B1UO1Hu@@V#DRnmJaBZ6O5@RB8P;DE}e37@pb`M{vgC7NWvA{bgj?+xI&sy_of z19>k);@?=Pq8~IZx+3WK!J^=%_@|p-%0lW6X?EQlzF6PM$;O4}1?nf^GvlnFZYC5? z4{go>=4MJO57_%|QKU(C-vrrz=jseYIMWJ=6bR!)`M&l@@1%6oe=qhQzjfj4Utyzzua=^vK)yE0!ktcj+{_1&)x=k z2=SFfpNyccMWb(L?-`>pi_!3U5K7Zq$h}Iy1G?%k2}e$v&={+}2|qe;$UGGBP)8y`yZNGY&S+W(w~PI>aF5kR4*edbWfbM%=GcO@o%e1Y zuE)_q;)s5I$9(*uG?z7*#y)tkA@rJOe{t{`>-FsfSeVtk*dsI z8>yAS|4RW=XR?J=*+TGL2H24zE*+WVCd+rQSU0@v42LeOUo8}&%{8q=AF@`z_%0eD z_#l@e;10&Eq-@o#zKB^RwEY3LeO@fjCP5GLJ4@fRVjvZ*4VjrV1p_aWyZaxvDdxNq zqm_nFI)kT!42V(f5r`S=$LxW*0Q3%-W=-9qv{kb+9MU6y zuXIc1tKWw%v}5tbR+~8%8+3SH(05q^kD2mucOc`5c?m=SZjeo|v9aLuj+ot>>o9^fNfO zt%xw-GxfwKVG>}>#256)ZMQrIds1Sk1(fMFMkWDNw_K|{-9yJOn{ibm;aNHaveyss4!9t*6&`PgG&=ZhG;rM z8rPo7N14u7tcs(yrgpgBSs_+6k$by9(;a0gWf$7A4VS=s(_3+jAV*1G^fRZC(ld&f z*Ex{$*FB@le!&?;4(0DyZR`_=wH)oS!aN??yxqbC>|oJ|i%sECTV8l&wBx6D z_bkLtnrw{l6-;+a9B=PB=Eb=+=Ny_r5TOM7C)pkXMWY+2mGH2w^BgrAWIDyxOx_1v zrMK;z&m`#DA_yTvj)M5uhF~ZRvhPTycj1WO)8dj}FV8w>z_O*`t@mgElhkDvLvgqc%g+uohSR#ebbkURDs)vj=w9v@rVyDgw%*KFngD!_1{0b+_Vw zRQ|FV_=Q~(moK>c11R2NWjy0#;{+|8z?~taSSE8kqQZ8(os`nLP9PrIu^J{??E<;} z9&^2F{jxyhhrOSIO2bt@m;CB~zJ9CG9*>f@N($+Iy(yn>2X7EnZW+1e+&)JY%d#Ok zDl8rd2OVfcQ~DG(l#?)Jzv;Dt*i+015C?3`=$&od!iU#pB`k(FNMKljMMDrCP=6E) z5)L$RHZ`|u_{W>H+Wn(xVKbD$`sUCuV4{encw2q*v32E%IWXstO~Zxdx?0>^dR*M7 z*agZsuM!RrJxA-}H)W@EL|Ys&c!a9S_ay>H*S97}eXF9BSJFPGtQ61dhpH3jXmpPp zu#z~>-&Gu~p8d>nsgwxeny5VRqzX5ki=a4phKyp~N6{ud$F+IAm%`jdFpkl##pkZO zW>_~rviC?IZ>zU+0^Bcwg>2f+(o5FU60j0DRo21BDt*4=T)1{jtkPer3@)1nIv$xhp zg!V{ZrFV}-ZpJCBI+{t~Uqbd92DhqOt8P$H^tgWY0(4mc9pEZE89C)G!c8@5uJCbn zS8DT0+NFi0as6rTf-Um>ai+?}!&uPFGr#qM(HH_zhkS?aO?hTjnNky`+CGZ7 zwg@2?$Rn$hS20?* zBgJULqDe7*inOL5Wy@Z-nOn&XDMa%T0$*3BA_UXPSu6dwnSogQL$wx@OSN*4)8_AU zbOsY(s>c99K)%2A<0NDwPMmns>6w=9A}}uooHu_BSw~pp12ux5H-(1y>u1{*-y=|Ny;D#`=gdJwZFo1!-kH8{ zumS1~Nf>f<2&z^!LL5~PkbX6O#ELDrL|qm<;yJl-_X4rNye32LEO4kSWdY!ghoEE@ z^p;O#F_4uFl(W5u$4;9}qO$o!JZ{5=oM!(3ER)G~%& zBn#CqQ6gY>6Gn#S1YeUGC2cTto2)4%tD$%#3xfu-B*^zWMA9D%x)zTWTAa-A59w@n z?UD?Ut_!DDdanmp&*Ry5%1}oxvKIrp;;GszYqv<5Q5d&U8^%$K55?AvT9ZITDOKIs z`|O^|(Fra<&j4gF;JK9e^=fq4v9L1PQ*G{rDLh3^qY5@lB=aRIi@JeM?(doXon7>Z z9pcJj;jH~}B?ivLHaJUbrtF7-PUV6Tr7W>j9V@OBqYVXsc?d&S?!Uzciqu1+msoyK z)g+AL{FY3a4m}e8YT6C!=I0XMHP5$IfZ%%CjT> zM9`;t&!zyDqF~B?a>M@?CKBSPXF>om4J3MJ(O!Xl=Db_|!Wi*0vh35HI=q4IgPz=3m@#L)k9xBUQ=E#!No1XR=M?=Ni-GW*fX&)T3>unJx*vepj0{no1q8!XO%)@@bh+wmJ zor5~fyh%<@r^spFsm^UMopbk}q8T-G_{^3#dZ>-9b$ca4f^YUWQ|U&`QI+flm%^ro z``M{mm^=&Il1X|KFhk;H_R<)l@_=NOrLP)|=6io;R2`lL3mTBVX5oDi);Y#(_)nFH z3}G3ywagPc_X=;C!nL;fJr*A+HQJC~?J7e|wdGG(4|N7rQAe>^P9nTXL#9KpT_tD0 zce5C+(=y1O#-{Swd^z%gehE){O> zPvNlGYn}dr@JT+gL`?MlMS}Y&K=v*_kYU0ZTc|siGt&t z=`yuB0Tt!|YR^*^g!IXYN#yEGBj?}QAH~&I%@VR7gp%(eQYrtAkT}13-`OmgE7w@% zo0SmLVb`m_Az|S4x@qc2PTy5qMVj*6g!|$3Fg=zMobBGJ4In zPh*G4I9U_?h4b{?)mw1j&gud|IOaD(XGVH4O481%L$;V8!#0{dpe@Xh1!zFp$&hQe zY*tHzCQvbVLBG7=X~oFAzrvM^<<_=QUy)~odG<*TX<`Sns0Hb$991YU;wA}RCI3Cr z%Q>{Z&)L8vEVD*XR)#ptHRppumX6HU@!;@W&Xj@~aQaE)v`??Kp$NsB^&2^G@|sUKZP@j}ad znT8(Y?I7AB(zTZVbtT|?3k0@AWonTI&_5*nE2p>_DzN7wNsS!gxptEF&v-{O$CA7k zvq2zlnNunfQ~vB)$~>K6QYhn0HcS|z3^~lbZ)59hYcK^!5C%O$rA=9ZpyY0v#|3py zQSMoEkNW`eaE;Bc_k^nOr7`l}86a3QUxs$3MDftPE^-*;0PU@euA&q_qqGxx+2 z46J|n4gtNe<;wx1g_@OPX^KjVsm?5Z#kE#8NG)N)f&mRvM|)D*!pd zW37~SFCuR|{q&#Vh=<}N{n8{MQuB`(c zo{;>i^$vK9V_PqK;hQuhFui9%qwBaBXqdUTsMRU8f1Lg4{dH^3GJT`RG}vgAzwjt@ zciEM2%uUOS-Y0p=)LD(3Tk_K${?IVM+WASoY+_jbWaH=<`920>~pOK^eKGF83;Ql zSy_!seY01^wK|w{jI9*V+T%}-p9P1Q!&(t@%b?THTMDp>|5z;;Qz09i z;6+R55Ip4ctySMl_299Cz@fZx+EI5R6z&JT8^HtA8)!A|{!ywQ{XwT}%GVdlx?x%LWdy#t7vY_nXnxqiItf4FqSkT-|j7V&sj8*Mp!}TdpKz zew7Cip{I{h5=meKJZ4QLOMoh58iv!xh{8W3J`&=R4h^A@(j9XA``Yb7TYY{wBy3&xT9pXS9y$f|A^vepqp!-5-%c4Gp2yHePWoIGu+73y)Qf-PsK z{`JaGtC&%7&EsB+;f+n2i_*%Mk91W#CkKYVxIpIYLYjBZPNQ5(BCi1lY`R$(RFU$$ z7pr5+tgGG>viP_VnV#H+aM%K+;elOs=^?n0U+&gb^xX$l6wM8&T$mYo#tOYZ&7ESCX=UyI9x7&8w79>U5p{Jz^+Ri;K|{d&l%s z?jb$d3le)CsDXVN8U`msR{Mv=m!VziU?^ypr@QqV4yi`@+~l=k(R3bq;4A4_sQjF} zU3ocH(hu#wlTV3A{WOE>o(klaB)>!}5syCT_q6~VG%iYvk`&EU6bB{;v-2hw{srFH z{Pab!A-$l8I&j7=$YIT23c_Z_o_Y$WhF1W=-d-!5NDMT)I7K{~>k$q$Yns&$bzZ4< ze<<^#dM(7}u)MHdH|q&tM^@(J?T@30)2M=FmJC?|>~pS!MwUpS?MJ=`U$7cLK+)tn z1e>>0bpJAfZc2DsCWB5#ijbK<#!~GYCNUqf8nH~{w+sl&yB8xS_RinZYjvB=uTNe2 zt#HM@Y`aqm2+J4qRtBhDpHQk56=fY3hr1$w;7HB>E zD=$Ye(6IN(HRkJat>}(5IX_oa7fDxHhnRFgAtF3`X&q8k0&h0e7*qBLbyM66v2@?A zgWi75wm-_=QeMSeOn3FK(*ro>0m_6KE@-|SJlb282g0Ec_yXq#Lt!m}x-8j7^D+@a z`ziqpaxsb&P#Zp+j%VvW+l{W%7d%u>>mkWviVpcIW9bE~)UN{GZ~hEavEPIb>FvDd zSGE=EzG1IfUQ?-fd0zN!xCk6;IV5?$Gke0H^JMp6i?^Af|sHQH_InM+l}#~8B^#?b3Lh)tHNdrDJC%^8+f z+;$Kxz<>&4OEy)!a&Dhx6hYG~Q0ZHA<4SPF$Fk^NZAZf>%@wqqQd#meC`gRxAE%ed zr3M#i9Pic zLbX5wJN_&*?)bV6XvuWCGmU5(vIy}{rfoGlV zQ$w(jDBa!?ez}Jf+E6}j4gM{VTNnUR zDxvklp1_^oo;%79Ab}{cCu}DdvgoC zwiyJYc7F)v>{}bld8K;O1{K4AaSnYJ2bmo4JGAjQN7rJ9qVV?A>XO^rkh2EFcsDf7 zaiC0ZLz5wtG5mU}+qZ0F5D39-p#vy(`pb>+)!6~Vi5)1Ak$a$lA8!6PNS^Z-wk z_AbLGU3*DPwy|9uH8g>{oo}!pq~%M`tPhu2JMT4P-&-Vd zxDbuBY&|I)xt@31 zppek;emW^={?j>#i-QeJ22is%etl?_yY@l73nJa(liLeJwBnWi;z+OrK+9YBNG%2a zGYDwAO8vS=4%YEhPkg1!O@!$FCarFxE1SB^$O*Rc8$(Ag6UjXKnFjM>QhkvdUBKJq zMF4KVm+U~A9tBAJGBfj146T{kKCCrRm9v7mj|kE8OU2>&Pv7wytlY_cdcrkef-AhiDpz!M$e?N) zY)Fp>jwi&rez{SnEtYLd-oMAoGd?b_Q9m?9?4CL}9}idU`p^KCpr#j2RWvc5LJLb1 z+{)U%yMfw==I+JBxee``R)JisP(HD7#5(pO#RRl?#mnud!bCpjH8yZ76F6EuHF>Mw zZgiMj6kP1BDLQCndh|Okm>DiQDoCUyNMAVSC3w>gB80{oTJi5}*0>I7r0i{PE~3R> z{VDbwb;wB(i5Wxg;r{=$OH@YSUlsFeToCy>*#4M=T;zwN;jAy?l%W_^)Vxs36ETcf zKjR@LQUKM}n28j4)uVpN(Pt+k%;uXqh`jvnb$ZPKw(Hk-$=j7ID-CDj+Rjm^gtoLl z65SL6p&0?y#9FdyX)EGXxWUiOJuln6RKERd-)u?L69U{jpM=4}et8nRclV;U zvBCRKGHW;KSkKrG{yb;Pp?!2A+uRya2A6bcge?JVXU!dq!aDnGR-Ujj&3*0tIy zj1ry$01z*RTfBe&P?T8#n^(Lw%_>T7RSW83C1xW*W1zxBazTmY=OkW%D!1?V<@I)b zL;?Bcz%vJg$k0il`rIgrOWRMccJv&1(c=Af_zxp2eEf$bsmaTC_o}17!3qM+20| z?pNk(T;tOG@1@|J1ma_=QOY1ON-sDCz+YOLY;6f~>W}1}*FHtUUH=IoqRgPN6LXDq z(9ZTkMAgrsvBed>Z+*-Rovcp!Ul!ySDKOI)yQ$F`o+IS#XvUYhC#+(0H_9Q9Lb)8q zYIopJ={$-#FS@Jkh^<&)jTjgsMhM0k8*ZUB%_1htK-ncA(;0!+EtI;KJ2_@%$sWs? zU@}?1FRY^_y9-7&LW9D^`tOP>W*Pt=2KOJg(8tK{C$B-5b;N&>gL>RhP@Wy@^*|ck zcdFD2b@{u`n79xSC+$=FdVS-7|03J{Ka*gR>VME7cR|KVG30X;62Aqf%bL&l&xINa zAa@_$1vKeJ>g9reCUR%&*Z|BvGVL5KT$rjoD)llaGb_7(dKB3EW{>7CQV18;`!nj# zW2&wMj`Ajfs27Uk-PcZlhZ6Y%fkuL3C)6`501FIgOLb%q!C!dCNc%JJ68cV!kA}ik z3yGs|=jddR>GzT9oxg@44tyy zJ0z|ylxfM~*T=1AF|4NEHGkHRw{d|13)%U^wyxr4?|4u$x!48<%p|}>?cz$vSJBLs zwcflE?wR)KfTtdFBN%RbaXFRZSEp}5Lfw=Iy;UPxw--$#!N!H2T47Hp4jU^RzS4)r z=9szZImu1#!SgG3tPqum;S~i)^l}%&+0LGjsPPcv*6NjU9{O_uFgQ+Axjo-`4rW^j zMUZMyBMUc)4`_}bI1i)WO0%26{K0lf-M6S~k(D-vTCZIna)FSs^L~~Pd7`h6Nj$3* zHF3;eqJ>=D24<}yL75;s>{gpcTGh@>Q!i%TGS3QE1h3|=#l`fV=<6ucy}9Y}=0UY* z2w@J$J#8*a09uCCmL?qv+-{q;ctRu-b@+1wly~{Lg#@bp0m6>q6T@do7fr3-$!@ijBZ3$}iW&00-si)!b_~{tsqmz$+quN`*k;EpBBL#-FoTL+YecIKdhQM{QHl2c zRP1f~m#KZ!Y2jGUt@Z)jz0kSTwM$xye2MY2`8zvBa>b!~p_gTDR%A?4G)z=la`zsL ztN-#t3$IBn^8K#Uq3OHub47l2IPfgV_wsyV)K@7L7aF;_kM3+FA;wnX+`6c6XH`o9 zL8{tOd`UvFpPLTXEwes4ukS?U#-%p|f`8}8^7f2Ld=C&hNKEW4uzTZhyHhV)%1c_! zr3X1{I>?^KjVN|Uo>^>|JdD%tMnZt0L?MQf!bp#Z?_~byJOB{Y%rh|DBQV8)KbrIl za_#m;t_qtnA>O#;s5xuLB+*#W!i2=QBDxALDotP!308k6dBX@frA6jGLm^vrgZG`B zDi|u!S4agohc+g8O<_2!?kcYzXjP|)Kc@`G&lSOw7+tFx)urb z8khd(!B`TM=N0%s6Y`2)-A1F2g7X61=*kMXoZw1i8neg*lRzJL)2Ein`U#;`lq7g| zAfc+DR`sEkW%Mux2+o?yXS1D^d_E>7MuYVqXGSKDz%GP1T{3At4i4F-%OwKvfYJxl zUOAfA^YNlmlO&w`nEdA9UPmsp^aclG#vQEo$Bmooiksd7w?SftkmH)n8Ci)QyBhMM zYq0|P=TCt7F_K1!YJQfYHnhkQD5x-UFrAFSY1(Jokd{8&?S%F&EA8j{G%=hdM}AWE z`=(>OMBD*d%YZnInH(4>T2v5}=-ePCO+UqLW~bkl;_5Ho*`=KUt!_TBC=gcR=)i8n z_~#E&;m?6UL|y1$R=v^+432n7rA~l&VJipiyd$957!w*avuYb@CR*hM)=P&6pE%F` z6}8P%H*|0Cp85(W>`C$}zxKl>lB_}VH487%-2W(966i_7iCRax^XG+84M15{)vQh!lERxyegWje-W$9D@fOg&U8rf+2h`|cdiD7MrLYufyK&t zY%eqaRkC2BC$x+_U{1sU`A$rs>oq`SC!Rb^`sV*C)F_0e_k zY5mC6c1!-nhTkx008o<8U_1#*FeV1vu;)u9##87)8oGnSn>NBj`#F?&YD$p9g+pA$ zsIwaNq;Wx%FlOtV1`SY)K;%EXtx?%AKk@67vfP#yk|xpP2`?F;60K-`NMN~|dO8bk ziTIQtd%NO$c3*~fm>3;S`8WUq>~ct?=W`v}lL|?5bD6?nsK#qrs>Y8v5!VmuZbkTf z3QLYKrS38$jDJJzd#Y47w=4y5PzOAxfvpriRy=!!aruq-7ClqENs{RKMzw#g#!UP^l5hHf7ouLqV`_{@mmrfrNorJy(q0yuu zzKhrbayP>rtQ!F@LwL?8vVt4}pX6}-?JC|XBl%!q=|m2FK^|$smKYvUY3C}yFgeVz zXa=lQs>R=@6R9G~wG(~2_RKt^!=dHX#d%K|^#rcq&d}LmtN~Y?=Q0&5PDFe)`N%Hh zSF?s}XqSl@Oiln+S~muZoIL1l(ADSj!Ke`q0*P@mNm=w|z?;c-OK}-n^|G(i2oo1c zUS@b&ux%Cw7gg}Aqy3|UHe>C>lj70|7w(2&G0bkalO`4iPy!TNxjyz0ju&^)kW!6P zJ*TCYXm{?1`cz)3kn5laljZdr*$aM7V69wS{o{beq|R?gnw&jTX9apvn+bSOTz}gV zwc|PBkDcSpL@uFpHt$uTaf)GqG2fHp5dt5v+fMyfiWbUq;-5SV<}VqLZh50pP(cF! zg>}gcK(jAbo1#PyP51TcUE!`ljREq#lcNjS2EQP4NDBox_y|EpwMV>riH~$JaakdWWJ1g#41u51~Q&Xb=GKG zav3z7_b1731H+H~CLx%elx)p|ng7`j6d-*yh6_b_v&M6h%5t2e%`LnBs6qUm-u8yT z6ARF-sG#eMvZ0-LmMLCZr%fnTm+Mc-epvRvzGm&*V)_T1#ped?_0M(t43DXg-Oroc z+9Oh=a!V9k1-6!I;PB{F;ovH7l|?dawHVnbNA(QL5A)byu)%=={DB~`&2XG|cAii+ z#I-uzq9FC#A&WFz@wYDkno_zwySa*gW;;dk+LWk|;xBl(VWIcLO$8Ok^2mOyOpqnf z@|E!Q z5gjsZbc;~Dj>x*!PK=dK#cq}tz56=F&&Y_0}YYpV67P}5f&vsczt-<S#cxuetpQe1!iRbPLv&H<~7>HoFJ;b$#FHM=g>U&WQa8Tk}D|q>`rfbg?r-JdHCQwYOG;JD^g^j-)2kM`@a; zWO2pC(w5W4*Rt1Z=6Ru@=8Zn)`k?10%0dc%@it&YO!td-BtmfRX4yT_A`BM_a%Vfdw|73bX8EW zO$85ja!vawH>QS!36r4g(@$bGHx;@}PcWOS2sxd2e3dt6m#qhQ;X@nuM_TElC`Wu} zsx_z@T}k6(8s~YLRai{a$_{?PQ$<4<((5%$vX*`SL5%g-KL|pEaUYbM^()<2WOBVL z8WJ3kP0p81ifciQb3UpDuQ}6v)VaJ_>gKJYm-T6AB60Y23q>YOf0nzQhw1zP>HQZJ zf0>DR&DRO&yQ@ZAnzw_wxtm6miC-65nAt-b8c!UL?hs$#3D%!j#EH`F5G;w*T$`+t^54s4mO(y2*K>U8>mcxS%nR zD+2yQ`(o_Lx~^V3Rpn7#`-&nI`eJbqu*P&ZsQA0>4W;v(1f69Ihr?^qsRwQ+$DuJ!_LGr78iMaH?2QWz~`b2MP^W zSBg8z4rg?7n6l3sYmA%!(fTOfEj4MXoIBZ@no#1nk)8h+xCu@|!T#ZoZPxxqku(dm zbbS$|Y1DGB6{wbtzONIM&m1sn85Y!L09dC5N&>_Q;DM=Upx|Q$uU!PoJy824{zxMcw6PZX-d|b>*^FMLiUN&H*{4HbuYF>CwzCxhpbw10Z3UvQ(8G+*SFtzcE zmxU_A6YT#UF~##|+ma2A*Rq%fbIbYl+cLB( zS^Hz*5jg@VN`lk2$vIz)G2Y#;t|LbfVCC!ipZDf zIv@Mtt~5UAU}8ddf{!t_Dg=<3r1Yr?i(ekiAr6&ES8aw(TO$q@fLH3uFvm+ar`FbG zX^Ui@^pJEl*0lsCJxqY%xU=C^&!CO`JFxK?a4u0>Q7F&<&5Q*E9Rg_~Eg7Y)As$^a z?~9h_4WJ6eqnuMYBU+1S?Zr<+6XzjXTlAm(Chj_WoQ~tUNToM9lVB=ygb5dCteIL_ zlV+a?@JTB|BEFVtD2&wZe*5Yx`nc0;u5Z4R1hMCEfvwxLt=%l$$nLw48@O?2(N?`_ z`ltYe+sB1`2MH!|`E+>&o&yEJH$z~JeIB#)dzKY&(}xrtUC&+b5hr+DG#X>;zUNJZ zk1-H*qJE{>V$L%KJWw!Q*A*QiYhz(ZQIm_?LZ(m_-R!lqCYw9%cWV>N%#!l!G*@rpc6x)hm;mcEHVphJojc7FCf~Vp4*D_wfRchb0CYE zNEa)WcZp*9tLS!7hj_EIg0xjwe~p!0s)_v%Y52MXbDKA=SvCFooUvkJ`I{MDCtD@P zKCzXS4AIg!cZPTi^t~bV#)TSI#P$x8)P)f$DxjkPN;+)k({Sdlr`m9D)3WtIQD?ss zr-&NI)&mOzU*(=)wk6m%3R<=%ZwG1Gp?2y}HPiB?p_fOv8HZl0(}}Gm%AzY=X)ZQ> zHW`S8u~d__S_UqWIk8!n++uKc6&s3aySe3MD_1^-uCz|uUq9E+1eFNNHGZYXMo_|Z zjN-~JBW9nes`+zGZV zoW!hVnYEs)5BcNULj;0|25uM}$Haq}EEb}()hpy^3#sYo1ZUQ}<^#kTq4NpB;FvEq z{pyK^AEornbVQrk)(jQZNVl-DBc*+^IMP`2flBgf5^nDulk@<^r?b+Gg zz02kf+z8pOZhuCptOQ|W;k(>%fcD%fOh@Wp-M*w@8j1Eg(1)BrpDu!LY8CNYWFTpd zF8ZZ?N!yWk*16md!4VOy3Awcp%N)7YQUlCt{JwTU_o90n>0fw*3N|wfsWk`aYhuJy z@fYM}j%%8JlhxV?FpP>2=bPCwebN1B!F5@Wb1T$;KaGmTkz3V8IKJA|4D-gwS8qeY z>z(OpH-Ggy96OHf1Wk-*kQz|=MmP24zt_K5AdrG7#RIloUnrYB7y@YE$f!zy#|o9ONIdv(NiT(e@{gwOkG5UOoB5 z^;v3wiY|FK&eQFl-op&BQkD~I<6lhpq;{$7p6jeK913wjc@MNpim)!rTnVsYDW86U zrJ{dA6`Xb-AcK44YZ)p3d?-naAR}0CGtn^=`z2%q_l; zzg$gxgTRCg)Ql_Yb2?B#!@9V+JNeu*WcudoSj%ql*6^v*q#l1=!4jrn0)_C8Lwp)X zs}j+gV5p29ZG7enAvc%YcbQZ$O;Q8W#(%f|6hVopyE<=-bov2iroVEJ(1rCSIMCKg z`h}d(_#gln=Wg{f1D9$!($I-o%(6@c(on)spcDW8eWp87qfu82e?*;_2aT$u4O?wT z@jc8Rf6oqJpAH3nKXQvpkiqCgbQZ6M+Dtf?U#Z_aC=Ft@t?2ia89db^5;Vz|(O!V5 z8EYq0K9g>Z5jemoct5ep6 z_!VVSM;*NouF-e52iRF4nSqa+p3g!bozYJoN<}ohiPVms;VH!KlP{vtvU$Oi|C)>G z`RGbWfM?O=*eeBOuNjz`0V;C{F5i)$q2RR52MNB1L21(m3G;Kqi|EO7tzxp4hF`o! z#DMYbzhKXJ^f<~y77%!z$VC0c3#Ff7gxQ;LYYsVfJmyDfK6^Ooh?n)d~}lRP8HQOXP(QUQW^5ZQm60@ew|FOr9H;rMsedtz zK#B<;rQt!gQto6DFIGVXGK5EHQkuXMI>f6&Nv?VjB9YL|Ia47)#9>+Lcx?3L-H3EC%#y`jkFD;GQ=ssGmauudZ>WY` zDXA2j2%5!^*>xzVg7Wqf)X)9uT@PEosagkhxJO=E8pkZV`BoWUR}Yd(q_$J^q*Bf( zVgJIgDgs{>)5WrkB+hYNGgxS=OJsAZG;tye<-P7r<}DmDFMHN9GM*@ENZWjbITS_) zQj47~A4M6IJ~Bs`F@rh=XN(@~Ivrug4_%ah=l;EJ0;orj(+7)B*6v0FCgBXos_ft+b>e*?v61+3t@lv}k&+&%g{X%q3Zp^$yTCxK#w?V+IMu)+IN zl(Xs;He7ijh@f!S2thvh3UA!&G`z*e6cvjHbwr4<&m1-%A8E|?e&N~FJ^Hk>0ltkJ za^4BK(Ic$QOpG^;s{a?u#e)tnXp}xWgt+^DQZIzgLo{Xw@I2oR^oRKvNJA z$m7uHWo3*?pZ>%Y!UDAbwxd-kbV5LpsA*=3-?3f!bA!?(SA z36Z?gw&PCx%6!5t2Z34tO)-u+*9EO(NT6Lt+E{m`tqz-EdX>}D++LHpzA%g1KLcwp z-=vU#hT-~mqNb4ksl$M(!h*J^pMeGYd4SMCSfJJWy}Dm*EA9w27zWeM)y1&0?F!0i}Q`4im7aB)w9uxISJ=;4A!acTh=*wM4(v>Ur=!f!ib@<;7K(-S-Jl9TRd!G%R zy-O-=`MPfYQUuo@kxN@I)WqmcBhfhZ7Z$VbzoURf@soABCa+Pq;%dJQxQTEhCS7=Nho(UlHwa( zJVQE2IUkk!$1{ia)|o-}oNdpL$P046@RbFRnw4oE^A^)IBIjF(NFcuJ2WaoV5XSrw zW5bA5gi_Ji0bP!&&Geu6ViE+60FotMBs-|;*+g#ym$4k(L-TS)>)ozWQj=O z6T%jJH?q~Ot4WKhaKmqH?d@-w6C$YyU-!*r17u(1Z0GXRM+LErsIF)c8M$e(**fQh zOxUGfU3 zRnsDs%PckFR=slMU9so9lFrk(jWNh7%lZNk&?5b6+;^d!oxw5}6Ln^x)pu`oUthyg zF$uRQj_aqC&PDO@PspI2Z_0GIG_!$(2)Y{E7CZEoJ?$=1!1#Pru(`lt@)LpoSn^!o z^~sK)SXSl^jhuU$?AabNxXmiBLSDXk?atn-ZDkA<^3$f8MFgl94b6(O+g-$Wqg5;u ztE?V2{D_~lb3h43RHA8~Ra3Lf$mMxzY9{g>S0&1QV0$guBGLxL5Tm^}LLc{CbkgFh(2Ensc88ru!3TH)G*@y02z$& zWn7u^`5G6RX@oL*Gg1a;F5(m&x7I9n&rwWKm{3d}_l*GO=!HeGVpPodg7$O-CqdE7 zjCm0vFwy!!+ViX7G86toSL+u4AbAM56(tBSI%nr(YUZ{+nsq}@VdGYsQKRd|xEUm% zvFu#?#P0*W#7w%Tl+~+gooy-fGs$+7^KEx*hS@B*uCVi0M(Iz)X`GmK_@qfa^(%W$ z)vs9WK+IW0i?&Mv&Co+ikX|vp>6`1R z)qOVET?}Y@JlRZG;IZ6{9nf+nivzX1IhpBfp-Pnu+M~E&TRm538A&Zi(Qmep%iug?zM^k z&|JWCRFn9oVQp)?=4w2AZu(P=cVk&iwOd^;|CC~i!Y`lj_ynNzqlyA?RK!)lP^P4(6cJ-)cWr{~K0wdp zd6w#eG1vby3nM*EMUVWQ9!}0!(1Y55;M+Xq6@6m-8<+j@p^`wG9*}3}b8&sSh*S+O zQhA=mw%!$%(irrCiOLY@c-e<4?GIC+dO9LSyNQ8aaf`X7f4~BJ(dQ&%;uX-hHP;8f z(@I_*9}9vA^})uy}fgsS-#gTR+)8c^}i!Ffxjl*QTXce@-U zFqlFeL#E^v3QaBU1rKObrdioh&jq$pT=4{|%Y0n(N`t0+2aI9(T86Pd3f-tVk**^I zkN*$jGhuqHl2>c{QI3R&)FMAcwegM-e31SyIb@!#6w z-)PX=)mcJ?W-FR$c6eulE1U{=B4`@o^lEiw*5F$h4I&Y)ZfZbABr0KmZ2vw?7kYCB zeqQLN7pdACAytn#l&D_=a<+Ptq^u?ba z5T8gUFdC2giOJ8>O(KZACr1Mol|e~vr}q|g)b%gS_66WP6+afhWB|M@_AZV?jVh~+ zbjZoQ&`>yulV3BNKL*|!4T8{OH~=$97E2NeJyo}TdpqHQ&8#Mfm7T7y9< zkaF0Z&lU70W%UySnTp(ktNOAF!0sH)sf^=vB1aT3%=mHnn9Mr*C}BZE@eavIffTEh ze>&TRX#cUHeWlb9HFX34whfbqgghwnosy+Ggj1)uVK8*I&~l);Vi+-~J_7y|a4;76 zHBOGhbZFSYMIN|BGvsXYHtxQeuGE(==#Ge^T6Ita5^K4)MV_Z9Ix3rS1}DkMkvlJ+ zE0}{Q`P~i)O=;!*?M=^4V}5POOw;(2z0KZ8)Xd1}QpI|5pz$?oudVks<_)wdK953; zO*9+6taXS*f$GOPw`$+6^VL~Kxcg-q&UCz7&4~Y*?t)nIl6zpP^}Iuc(^Wb4?g+NP zg&mCES%cq{`cQv%pgfW{Pd+V+in;!9fhZaknKVhu4Yb!NxncC&2>~Giy*T3rH&qhZ z1s6YH&%DOZ|MHH*R0}d(bskA5$$Q*iSX>bcqUz9uJoC841&{rOGfTV%2eQ3vmFfT< zfDw|ZD88?kpyGgm!6#t=V|K_7#T*-h$$r=bJFirhElaou@tA>Q`9@CThKjsVV?w*EixE)zTuV3qW{nnb>gJu z)%)mP5rC*C8G-7s;NTv(oy(6^*y3F|R<{|8A(cq>*k7><+mqdbH{T@GT`xUnwybLE zdkUUelL}_pw%>MCn`OKYtdH6P<6&WJfuZ_OL;yAGoy(U19%+&s%lBBLJzR&MFnN*b(oxW@QPvz!Nc_l{(t%wBy$wmTYI_tZ9s-kt*_VMfsBzK`XZ2nNCFK@R zGl7)sPO3e?%zy+%IOtnUH&??`$+*AjuV&womzW#RXgyajv)cDH}^)7lI2 zezf8Kd#a{!%AG?6|KE|4Zc^2v30JTfcAP)>vDlLX2`v>vtv_!y*%xL_*SyY0kR@LK zZRrc#II|H?xT#neP?;f!MCmOysaf?m{R;Ci!ylYFNk8~J)nRU{-0J*KoVNDA3SfQ! zJvQ13?Bru|@GT^R? zrhpDb9DG{C6^Ub7*Q$nnIjXXrmiiqnDhcR)r_V_Z?q_>=GOgp{lux&|rF`cYqWYVm z!8$Qj<@|W50m1RlJ z?UP;;^OIzVTUl$>wuL!OYN;IN>6m@_xO>Pd4xf0sSXcd_@Q^Ki8S)t{N_mVqkZrhE zKRV+T03rgq4E&ESEZkuqi5j&SCqwMtT}xHMoaEC{)ifU7x(;5Pblp?0!UH>mrIDf2 z4EAmUh@#-J@b=i>x;KNSw2rMe!4h`N1pzag4=P%{0lj&Za;U(=qhu*E=f!wgV=>(MZmD(T*|qc+W~$_>}HNdO)U)l!`%K|Z8Z%# zeos>GoE!TZ$55}wCer7+Mc+kZXX7^J^A?%b_#Gup6)`1Ve zyoY{)AwZ69Ba#c(Db}jv$GFCij+EoGj9(3K06{>$zsR(DjWUJeTtx7{b7<@6rW3I@ zFDNy*7lXl7rJ7+o8WjKCY67ENf{;ThuS%G-7x@Lu^5k+KOxb3{oP01W7MGtErQ9!l z1|{Rp`B)_us-dg`PgHXdABSJNjiM5k-o*GwS$o|{7V-#c%Ug*bNqz*^l%juzc92xX zM#K(cK*}~E@P2J`2ZFsz~Gd|Iywj#mWO2@L#<@S*R~w@FErzh%y-mF)p2`|5UI7EOm<|jUjGl2~i?_=dvWxrCAeAyaSw48s#yg z33a^J;I(u6On9{qOtM;$JB-$WG0 z8@IMYplp`RmJUSdBl|$-=(t3=y%ip6Y*O01jEs$86r#I*h+rph${qU#Pyc>IXMG%4 zL8DTM?7vj2FcqQM3()+9r>;z4J~?sEh?mU_ukR9NUg!b{!<6`$kndCi$0Q;1Z7!z~ z%&faAQTXacp>6eHtCNi#&k+B4I~+Z7pOTz#bO}T}tL>?Oc`#Phqvs&d8RPllJyOL_LL+q82W`cgw2)X$GXM%XW&3)$3(F$cX=N!}+{8EFBFMD&n zB+pnrI0}}OCf0T~1~1i2i>iB!;mog?JJr&WFcN!(W(1hV^XDIb!&tliAXa2ICwW{! zpVxo@K7YR>+CH7eX4ddwn}YuSyi4W}4{E_5ZDTZZt2OLPs3Y7-4@@Fh!oBRKzTx;i z+WQ*mxpSW6g5%Yw*iej_lzd+Zcp$5!goLD6D|I$esPk)mt9fS~#oh+B&@m_x+q zJFSmN-1IN~Z;QjP_Wwrl7=0Rl5cWWtLV5|=z{l9U5+$-vr@5+a5!bUUvekpjfmt3#o64C&sCh{t&l8P{x{8Cj8cUtR`pTJj$G16&LZ3 z?0*svAfK?*x^sW2K9VloSsoayBfBSBKX&F}{Og*GAdzWrm6-ig;#v{>=g;?4S_+U= z0L_#g-m3F05%Te>ZzrbslgG5t?s#=)K{ZqIuGa7o_A*Wt&PK__x4?7cYsQU8G(g*DmN>{=a$AZguddi> z94Jyy7Xy8yy;1D8JVZEwx>~6ot=6J!I(}@_(f`+2n_*XEBHcOiveI_;hBFB|Ubo*a z-$Q-S7Ahwx68NSo14cix6ZICfk|VC&%qdh_EW$-e=#rAGAS|3UbkeeKvS*f6h_2jVG%6(cJHv9#@I!zt{d zv)Jkm@Wlf2O7tgcpVVW8fpIuwOcE57`jQX;~iB(M0bDd!O@fjgO zSs2R3wDjJN8E4x+Iu7NAhI$Q{Z^(G*Z48VbZ72FIe+KE|C9{(Z2A{gxZu#QYuE>27 zYZ=-klRgQ+)Jp=7;h9xFGPNW}bHrFM+((E{Tw(j-RvHP0>PK#<`LzqX;Uw5;fCk zQE`{SDIh^#MV1K>4C{hjhu#Oc=;h-Sy8_Lz(Q(YPTLFJ&90SBXjkYSFL05)M7I)x@ zS;pQVjTzCdT5?ya7)t;*9Er<8wWG(%6CP3N4O=X@XZTE(QX*zndhVAXO}F((?*VHd zV$=G{8f0}Gu9F0pE2|nor6CFcJ1Ed5L=bBT=>3pQ6RqxRfgq`L3AJ~^ zPf%o=mm>`Pq)!OZO4a+M$%r#EA#Y;?ZkXHn0lLc-R3bZU$d|nAdb7+=BoSkPc4%oAA#UYqa`_@yMLj; zZ75RUyBgp6X8Rv4!m+cOcQ;{l4P|E0e{47^V+=~=wL31a0#{SySr6!z%|JG`zkk!z z5kTX8r92h=7YLt8i0q2rgx-{|kj{s?il#TnDKl8|7eK4f){FTAbMA_9(4P+maEDIDmDabW{ z23Ji9O{CEQbWyi?=>s9%UubHfMAsez2g5MbHD*lWr3&{9CNvTqRka$IBI@~G{W$914V9ML+Y-;;R1x`3-eUyI6>XbdH2oDbYn~@%&ztG zL0_`qBh)~WpZGC6V(-;PU1V&IImZ&PG~CK4ZP#_jyxE8N&i{Gq3eRR^2r*T9cYk~r z+?kNa?nVYK1Ggw4XBWjJQ|Hu(C@Jo19hV9^-Y<(-op(FdMc{Bs>6?5%gdAz}J;-MV zHg=n0>s{);3Ki%-ql3{S>gUVhd1%P45oKcS?UkEwSy!oLz#6RP?885`w909}w2#4p z;U)PXjsXGX^nZa`ue`f=BV$cl%TMh2)nO5Uc69_vVgGZGhnFH+*6T-)O!22iutpqr zVbxF8l9RcYmN1oBB&H?nb@s8GfaoY=JI_3?<&Lbt4>UA*F=dHjyE)Gr|(W6Vd zaHW79HSQo~F=i_t1&w20v89=HM{PDdN>AR7fQJCc zIh#P+)3J7I&WLxOBe1e2ia6!S*x{({*l>xx&oS@TLKb%k-^q4AY>u~~tV>4vYjjIh zbQ<&#al$Jj5HM-_?67-{cEnQH_Y1z&@?6Z|6H47_HT67JOPzPF5JWtv4+2ch8q4t? zmrRTBX3v1h{LXsyPBMi*AD?$9R~KMRlQw+*0C#$R_lyYqF2(Dmr1E(^L|KLNuY}An z!$Gm6M)t+%GR|6`JdnV0TE!&n4HeEk?hY*W+65x8J?{Lb`K?Pze2o1VjhZtMrVt;A zA9URK-WTm{K_%M8F!&b76 zl=q|1%hg>YWFSBWGD%d@o|(`g<_Y8Z`xtS{Fq>4VOIi@-Jkw-S`jT%|o($sEaB%-Y8Z&1qH=5D7t!h zJ?N-qK6C&GiFk^Z7ZDIFcQ0O_n6h|ZEGZ*{lv)c(T)|N#ySpnZMwo)Xz@&`lB)Eb^ zIEcWXWuMFP!sYt=7~UF}OaqCTK6|Oov^0++achi4+|&8_Hj+g@#Cz~x^2zi$4@JMS zXGVKvXVCq~S{M}a$5f{9$Jz_O*ffAP;)K!0u z!WuqM+!tZV%kfFdTa|tKSs~ndQGeO-E8cz}(~1%R*8Y>{?|ItML-YkYW)}06V>*(z zW#AilX|e`vJ}Sa^^*y@cDHW)!d~GC(Mh?#Y#olxB4OK~(C#UkE+cpjpJ(b!3W{AS7n41&{DP&p2qk9_$|HEKMJzE) z+gF;n926#0cW{wiUM>(i(l~d;?^zM+-oE)N>M6uOXhg_D*NFxT_ikCBbalCF)z zPaJz1f|4A>y({|G@){P{aDk_$Vel)S~f@jJ|^TMGQlr<+Y)a64q+VGKu$HXp?VSa9ag8(?`Q3|vA-03drRXFz1} z8rgcQIN+tC4y&$cLJj*UQn1})+odSt@`P%UMew);#48BIpB85qP-Xpz zvohdRD`}=Bae>X0{V4Fj}$; z4LMy_m7kxrw%H8+z3vk0o+!OUxX=@di?CL!f2o`0MOawi|DPlLqu9)#YvweT@vp&{ zC8WEJK|AIg>gVt3KG%dV?%EkqS52wHg4tK~2Jx1w31|dWZEs(#gcXXGEP~l*UwCT| z+Sato%8TjysW14PoiXkZFVwHMg-RqelGPW@6w8$_ObIcOes>K*^b~mcqWWQDGJst3zAllqz3zOL3MuKq*o0{8C!?8wUzweCvEwg= z2>ldf;n>E3q%{4+RG%bz`>-lw@Ji|vYe?2mnjjS9{O6tjasb4J>1USw{?;|AUD}|H z!Pb@?3lF|~g8-=E2CY&Lm>`bSn?s2!=xw3WT0HM2R&RfoKLW z=dW$+zQ62!dX^w$N6&X-V4!oTWG8&1_aR)m)Krf~?uqqKgL9ot2Dg3SJKC3V%M}q4 ztnuI^Qh4l=JZR)2G43CT8P7@-7exzQu$&NdhHlTuoTI!PT?-x*c3cF}8uq@6LP=@YXOxAOiCfKwj6k$l^_7RG{$(RD2Iob5VoDasfe^FDw+#4UcA*XiDE^N zd)#Z-lu_S<90KTTXO=Y3?X=h@cGx8CEtZmKWr>W;#R+{p4^TO;ZEcc1soK#NrF|1r zwv_b2DBpB8j@W((p8Yo&XEkpv zgP0^}7Wh;XyI>6F*_3OPEA|csFsI*3pM%KkoiG7n^fJ__<`pGyLI{s-Nvtph#bUbE zS)z55uWurFHx+~b_kYYVw2~{Ov!ROffTr1k z77}v^*T91cYzPn}zoedJ&gPX4D826wl1UR}eilLe6M7DE^3@GOoUquqqwB2rQa-35 zu8^iM<>qyAvh;G&Jb973qwLOmd0U2z4Qroj#BbC&_~8i(JltiVjVb2Y>^aLb7xe$I zEl!xUW>qb!r;E?6xnpz{3yDV(>mjyVaF-U8+MpjtAK1+JOBuLsX8BUQ@w$za-c)F$ zHiu61z&g~aHst)w=eH1EK+d4;`q6yo+zq4C`i7c^DGA+RJn(<9&;*Yoja5ElOO()p_ej%V~y_Xxtf)!_&&g}p3$wI2dY)5PIe}Oc3US| zN;6NwpI1iXPN-_g@?&!;NoKZ$B+yjj66G?BW^UK!X&_#UTu&P=rW_X&71KTYUL1$` z#z0;#cV76M;cO{qHxIF^p~^5*sdYSZjQ+)FHO(jbBmjk1cRtd`u6{OG1q#c26j1S# zSUO*8#TT+Dxawwe;e?i0Dn`iJ(Z)EjM`a)`vjkViomKOc!kV1BRHZRL#S8CGFG)WC=dIZu9zd&ptH_hK z;l)mzL<2_mtDBd{H4*u1!+zEZg=AMG$vj-_160S#A z<5)GNjV0_WpZf8={z1JCn%s{UxbD@S%JxTSpREr%j6*@(e%^_IQkOESO|#`c*+8O5 z#Yg{X$=7wcx%<`tNmmrPNsRtxhuS!p*a%N67N6AC1q&5s^9Ku8Gj!ulDQaNHD2aDwXBXWuju?JjC z9d!giX2}9TaL_H$@~8b#(G@&yR2@?Cd(|GEHPWyixv8RS-7JE0Q_@&yjMf}h#8HxT zX)h(W7oc|BqNTexT7TzDtq!Z0^MPFxuJH!IlzG&s^i6v1Mzyrnt#0^5T<27_Ogh0O z^9UP`D1?VuX2HK{SZ*D_wCBtb>&ii1;R*Z3Jes^$?W2CBght1#uoPULKm0y8%BV^8 zpG1l_w?lg~ZikE7MOuK|3AM}|#7O?dTGQ6CV%H>HneqAyB9-~5^LuLNUxx3R++djd z%Lixqy#nf(X|4o8fAX;?l{C`O7>7k7nK9snhlTXqZb+{I>pullm};prQnc`>xwZep z8%ni&YxgM$Vq+$p^6H^pOcT4Svi6L;J>)3eB1oN!f@l3b!YIGA}d zB0Ksi8?BG)acOj?R`=Sf3Vnzws)CY>PQb1Ccx(j?O%ABw=Te4D&s$ZEn0v%n0y70W8xjgVe zI^x(USoh@@fjPuTS3k~eP4&BQ(~~>6 zU-V{0%DWWE@>ov#?5`oguEHBXBz(?{ur@cJzm6a9T${s?ju$z?gv0xU4LnSIb5K$9 z9tvDfhCGFwNiFB5+UW0HeBahm_fDJv{S z(q3qzGcNr=qEtrExY8KQVvdQ7<_CI|dO1#x4yzv*eTr36oN!%wP%OpZx}y2>rNJP) z))+gDy93DHPa*SE3ajH|tgk*LPwW-3Ttk0&aln0ZkHBlYXQ#$%51#1;Co@|zrYHLU zWi>8RI3JrLe=ofPY+9b2=j>x$Y$};ZiFS zX2yD}s<2$H`q|jH)>O{!1P*(&!7@X+5y|l)Oq?-w z`K4z)rY7kACRv-8ce@XKRqj|YN>s9*?IU7SAknKRrMzrVE@~pJHb={g;N!qD>Ef&XO0_p=mc-4EKVraq9Vz5*~(Tz3@>zOmwHSiX4dU zu>~>;ijdnjuYlE z>}RvIMN_*Qs11edu(Zw4L7}9Z8-VA^`4A!ppG@AgOu2`)cNAgVv`tXZ=1D46o>2JE8X*B8lRU zMZxtF=ctodgk%O$MhM^d{O*6n4Qt%qq}I`*nDug_3)_aoMVTgbJ7 zWBrTAF3rD_h4Ur^io1t}-^TlsVkTc<$QtEY$Y84NuKr$aw44WEfe@~Y{AJWIT>A(1 zqPj8&l-T5Wi00SIfYUG5n9;d9-48L&JV*RF{b8ID!Y}IECDn@71I;xfjOIbLHO|i< z5S{k3q;v;Ubp>x3mj)NpiraujDf*VEg?^gPobN{?P2^fqM)#$ukJ~?Y?G8cRf80N8 zTw9F{Ril2Ms1Cdo`mV5H>BtNRY5zC6s)!#nlK?V|)cHPstnr0h%+`rd&)0$ByRdExSsK}}l0kkQ-e77^G+iW4TX4gxg_9KY8 zy{#S{Z}suFkg+n&r9^`x)8$ZEKx0Y?lUPwM)Bv^dd`KQjg42M$AaUPBvGV2xN>;`k z^VnsHXimy59)mFshZ5><>G1(Z z-p`87kCUDsGOGmiv8}z|zS071cv(MqkHg_;U+?gFx`$zjAngny!&;0LaC&-Q2xGp> z4z}FgCqzo39j$DKk;nnh3RH^yk-fG%^t_&NN}b*Y3YKhR$R|9-`3cWK4}I4~30dST z{#o>yS9rcK4hi*`S?uhsn>j2G!!epw;eJdr7K;qd_#uo<-9w;_9kx?>y@=^DwTuTiGKGg9CiKo@+`dET>??Ojg}spC zcwM>G%(i*B(}+ZPs%*ROVUUD|9H&zhnPz$`6iE2bi>!dYu{Q8s`r#HPrldvi$lNkz zA>~GIv$iL_!v?!#hCroX62~WYWy?WeY=la|@S@O_L27p$+E%z%gg;-E?ftDu&c`rS|x7nLA7lQ3}D`zee8!5xG=1HW%G3P>+9r;t8am8mRDzTvRgPNF|vnsQ805U!t=t z@W@8{U>F4sG*~%K>cF_Zcc2Saw1c*kXcQQ2dRX^oFyCPLRaU8HkfXE;$O{q&D=Zb# zouuo7DEKylHRMyF0kjSxF|kEpCXHQd$5geV&(}k0)XdT9{)k!#v4)I>l3m_0Jaz>~w_PxZ!4iNFihJZfEx+Z_Nh z^r3pPcfQD2n25}46d(bS<2a2sM_MW*;_e&sue-L4uT3vlZjy}*dH&eGEa>$0WcDYJ z;SAJENE0bIBUF4le}v1c{rnwzbS&J1nUFqyWRi;X{I|+|Dr*Vv_zP>{B0Pbhs5^Uk zw{Ik}<26J(WU{H9aak9=sjMviccSdYO^63pQfH7et2ACv+iT{D&kc@~-k9=slt2~{ z-)vWmKzFd^GGJM=lP*IrjeRsQF~QZB)_QYln#w;oho&l0BFQu#K81@FFQ_B9=mT#Z%zv$*if&g*kLe zN&7Sp`K&WMD8?0)z`F!FnntXe3ACqNK%bDc-ZJ z!zIg6%&)`Sz_d?9@NKI?GfNmY_#&RjNbX_+s<<2qO2vZwrcvr{gfM)xI{7wR<3O<5 zk_?v0Fu<5P0FhnnZ$_XZ5XVs#Zv6U42wc-mrlJsz@%#Ug&eKlN^lL49$9@4iw9*J{ z+vxlo+L}T%ZnQ*Uzn<6_8V3fuyo^nKP((1JQgHjX#wC$mUNSeY*vFHlM=&14FgU6L zutT>Z+4PQ4Pn3Yi^&yI z7`6pnbq3c)xv7Y&bOwWlUj3L8NB`D`2C26iHwKQEj>3-)W$Y;o^Z*#~L{d+QOs-8Q zkex*R?IKi_4qPInRtY$fbCS*zf(v0f`q~*HlijsOq!mT4TffH<0~moUgTk~@?~kS6 zcze&9GR>2}eZoiDY91j7g{CMhibf(Wh8NJ}dp%F^IZm5kxU)i91GaQm7h5$Hy@Cr` zh%=xM7Feb{_MSt`I_RkpVq{l>pi}xin=8jq4{FT%+=NAroG2*g4P^%1=CGD#Sm8f< z3vct}2UQo92wH#W!~pLwvstI*TsUsM0s&O5_La|`)F5t~pgX{2Y(w(RYe*l0%6&ZH zm;@h=3Udf}J>Fe1ME6MoWyl_D5xr)Pj=Y_lvC0tV#U_{;+9;%Kv$3cx_)BV8aePS# zt~=!O(HHp^aV>b-RyPoB6A)r`*BB1y@mq6>-fVnl-jY+eD->h`i7=_NNe_M`)tsrz zg$6kztQpyWv$rOSwrubB!u8|4cMJMfdooxI;%k}3&=O?LlkAd!nYzLw_^y;Qc%VYE zXdX#e%;34ru%qFJrO*)i!du^`=Ha-5j4>#vU6f1QefByK)J&XRvVlABTBeFHMy7jy zAXiZIRY#MRna@{S;hNdcHX!oi0%#obq3IZ=KeBAEI-*7n)7~9tIR6U#>YPI^!LT0E z7&3p};v2>G?ELnlxnrsiF;Q4{5qrm)DH%F56;Mqdv0t_{4_P~Q2-KHG zCj__63Z>DHoh8YcaM$w}B8@qeC7r%Uk&$|f#Cc)%F%n)feD^a^+GlL4nV;UwjplG9 zrJf;bA{`kT^-+d?(qWpM<+NaXfha9m$UH(bclbgC@u;TVfuS=b^>k8n?u^nx1;8Xd z2wU%WA_2O_mkYCqPLr8Zo!t~k2YS@C(v75m!DjH}AjQLA@qI9aQzd(B5Sy>H$LT2N zA&s{v1i2NiFGP_G9$y?7jWs66`i3O!aA|%%F4S~bL9%6z0WUQylAao%#^vw{~=RhHKo5yj!)@h zCk<3jJ?N*)`6Z>rwY$xm0i%{)iW-pe9bHzw7P%Y^Oym{HVK)a0kFUF(5RXn@8L=Y) zhRUP^WIqy#k)$O$xqIa1mY{IsI?2VR%LCuNwN3Z6#Syb$1XLD1vD>?D*fW$(5h8iQ z$)r$6fe~?WmTirt{f%}2pj9OT+4q?RQHNJBM(dCy1*<=MM#aXx$arMBRw3!2^`J`B7pExCEWqj{WH^=v6 z^mC~St7k{_T36$>p5DdK04T(6eRhRrV*rEiDD3U58Rx6W8)l{SzL|k4G=$B8*DOB1 zRT@lumFyJ6Sr@&Y<7QiitD!@Ke<2H?-n#@2Z^k5iBe{3Fl_$!>L@ZBV$|;FeSyZi5 zcElRmnUiG)dF8{r6T9x)PI17`TqS2ahvEk}P^Zy#oU-)NQ$&)Mb?Xn0UT`VS;vY7X zo%@I27!JZGO(Fm8juuId1-}N{E&R%1L5Odp{=MFs+Z*s}`k}ajnMJk$MBaQMxvFj6 zna0mDQD)IIL*x&%rD-;QVml$M*-bHOZMSg|c1jN`%CWH)Z51sV+vHQ7b`i!T=^9>0Au*OMpn%3D zbeS%Nl{!$=dCN8X8gaqwSc|$|wcH((wNPGY{%H4ZM||4CQ}oW0ypi8?PCVBWaF})x z5V>U~JR+Hu+Fh*yDtWS{Z)|HC@05L*VYhPZ^4=5*(c73Acbu#)j-H9q#Cz61R|B0f zn}7|^qV$4(-H;ljk>Wqw#$6CpmiFGIt=@@}S~CxZ4bMKy1I##_dAy`+%R3?68l^6*k{Ob;fbCAT6*uYAIm?-IC{~Wb?knx zM4Puhm9S*I*2FHBe9hv6!BeWjpcdDEKq&E~Rz!8m-RvRO&~q^kf4akCQM}#D(N1J2 zCh1^05f0pI@;Z#t=cQ6IYseTJr9H5@3uEYeKz{|H8yI$0u($_k_m`_~pgy!Aw>5;s znIVXM-NMmcT_wBe7^q=y(FC%@0;7DAnt#F2EACv>!FQQbcY28W5Ie-Hrd7fLMie3( z`cQ=wqNZ!14JP$0e3NxVNMq;!1eHt5EsQxWsnUXx{@9f}8}|!Z`WbOI@Qg;un#4n* zZyN$PWgn1S0S!?Z&qa*xWh%Rrx~f_fnOz3X`vxY{m9~YEIc+mYx+t|nv?-?kZIQ^m zYKLUo&u6(txs!|lUi(zZe7*siFWv-dK=bnmEW3cAPk)Aw2C;={7wnEcpb%Lh0(L}6MH_G6c%#qM?+e} zJK&_ikN;t#URE1&i*LP1zky3R>i73*ldqs|wh&r+@N#7NKN~GA+cgA-+}LE9hAc=G zb*+mnU0O@^_Go5^7Jy8(v~0a^!}V|{iKX!JSQ`fH|56JD4W&Zlp*MDEM{a|f32G|i zkSuz9=yc<4GpR!)ypjCnGg1VU%=av0yM7W7jh$BH3s&;e*PRrF1^wLpUg+nNV#gFG zn#7g*4>GK`5M{s#pu`{WH^%SxjIE5UbJi z9+57w82!+I(Ti%%#u!&lofsJ2GVLB>#V5b{OZ+}VY|`Bq8ZDIg)&bajyjHJ1GC12a z(;GL>9h;<|4@xx14UW%~_lg;$vvkt%1f<$GG@%ChN243Ftn2>Tzq^-GB%Kc5XVe{H zmjSNN+~7>L3@D<6^khJS^kxXDqzildJ!+h6mNdhfc`3ymN@wv9`R-e{TBiuA%SqDR zCxSV|Y9OKtardmn|Jtjbpw5jy{|=k@ChsdKx}cD?LPhWC;2T!YhgWoYJd+yZ73&zb z)#Qo!EJH3d4ulYcQ_h7<=6wK|h0kS?dKiTPFsR7ff$IGG+snErr+kN)@vs7PH1YM- zvdBing_kVbgohpI7k`DG$(z1?OR6#LOVpE;J)gQ;rc0yvGsCdXV`KUb(bapw5sTBW zB)^BlLwdjtHldW*=w1u0#EG-WiIYh;R1 zoi6*;OwD})Upo5G{27XdL$oTcKsb%as}>Hj2SotE^!J&_?h&)Kdr#{qRC*nl&eZ>n z1y!1k3Y5NKa%~Euokl4T)T2IQ^-6Br4{=eLb;ef(Ghm0o;; zpeSJ;=wrsp&0Bnc;ZXDhKs2>N<7*c+FsW$q8)`m!L9ZXu+CjC!HamhEncyepWBOlv zqvoBnrt)~IX_p1)G+@*D6}@XjBU>>+3wnh>=rzl(nb$><){8(t_nlfKfCNp$ zD@0Ry0~5z^wc}h7oJLXSns9Vr z%WtjSc6~($(&mV2rK!LBny=cq@TZvYo5_-Vb+_>tUk-Xi5(mQ?KE>ar_MuLzWIx_{0y+%p#2XnFFc89T-3O9Gl_uCOYLN4gUxy#uN{;04hG)8X1 zDA{NF1q9Uad)=7#Z%yp9MN`f++G5zsUd~}V^>QwA?8oQ!Uxa|G^*_)k!vop$!gWCU z7RXe$!T@iYQ21dgi2B_qIbAI@jkscOP^Cq-PDD5SEa)d~l9ttNJTN_EXv+Lcp};G1 zvt`p$98iWPr7sy0(rq8qD>4!PbLEo7RGQD z2qRfnT#`GmfFG173%V1YICdbsPU#7`XBW(*b8~wff68l!CPm_4(pqK#Vq-XEcb@8C zLL$$Wz7ea~8D^?20k{TQV7l`KfJJZ}e~*Z#AO|2xCTBU~;q!rsD6bCx%-Ee){|5FY z0~QsfapJ2?iFgVHxt}aYfE{{C%-Up+T?Ri^I)R5NcJm1}Kv0{B9E*;RMI+OH$iu-c z(fCOhs);axJ4&@FO5h%7N0-*s7e7`#=1Zab<$6Mapu2Sz$%65xsq*G^ickA@pTm=h z=_)j6U6?%Jw9Sq9s8#tn@`cB(3c?YxVy_)2a#c*g{UT9t?7tzAIA|HJNH4ZmPoLep^1j|D z$Tzu4qk-5iH&(SW%?O}M5jMMfuEvn+-_>6)awl}Xw|LKf-j(FRRZ2^J7?;VFijPFTkA>uDat?{WA{#uP3i_}l4KXrx!(Fw zkQZB+pD9B-hekiT37V_~q)mw&C7vd0Q^-ki!npi=Th&ZQ-*s8}*S88^IdDQ)5#78$ zA!Q;b_Y%5$-?lT0q)1f>^)yhil{iu|tRe85!kIktH^TbX9ToY7SQy;Eu8$UL^D7rS zln{OL7!B&vnYIT5 zt%=31aUc5X#^Y;4@1KwaeC9136leQoIL=9@86z2E@2TJCS_(2W9s>=q#zXHTH^kaf zf$sKLTFaA2zp_p8q~p8Q0OuQ z(+M7H;mx$D)2}O-fMFCQ(W+IaJVyi)i3;>@tpaziNS#eI&!%vUA} z3j0oiGUz_YR7!ZVq+38=7}AbGzY%&n7_zXQ3IoSQcE6+GTxbyJNkP?w`$9P1PEC7D zpEBH;&2_hgqYfM}}i7=~=rw+E8@-3;%ZtuI#IOvA_ zsFnsNyIp)s%Cl1ZW%xA6hvKoxI_pYdD19uf@i5yJtxayy3^hO7*1GQK|R-?L* zpv~Az-u(Cu9WJzjD*h}=x(wD5;%YFFJ0I9cj+3*OPXZ-x&bTa7S3m5iO??fQt*f}d zuH(RAwAh-@ogh`vzO00_T)&xe%+%PQ79Qc#Ft#Z-{ak()HI91Pj*%aGJxyx0eD-^$ zSU@4;I({d4?9u0ji%qm!R}Ez!uvWvc@BAj? zGZky-5~o&BMf;DA(cuCO%-UdDygi}_kx2W5KZll?AN9#x(|N?`HPqfzbSsvza6Q-| zIwkXhy-qV0nITxBpVnmg^FAN)!U5dV+@IhycW!yL(+lfc$_jlJ!X}Lijk0p_ z8o~g3>g=Uu!M`I=zckWTSZzr6)+nX|i;~{Kjgd9%aR?W+DOTKT+c$oLyVqC=?TFve zZkA44;*OvuY|jm^!uMJI>d<>Bdt@=2&G^xqXCH1z%`+99bH@&TTk+~QbY93UVHX&- zrzoqqt^?dVMQ)e$f%QD1Cyp%AhP%-ElB^8rKz&^S|Y@55h0!GS}|kf{ziyG8o#2=VOi&l zx81iOV`PUe<`(=wI@RP?Z(>A~{*i~>A3Fe|$G{pXJ00#_qgYL3)d%Mib>zNp?%29n zmH7a^^5o;dgrOlpUh%f~&=}sFdsdWl%~t@t;3<4?P%Nj#MWy!oeJt9Ye9=bCH`ve} z1=eZaN+A}`#M0)PVXsvw0b9~FUNxm7mW+TH>2wHbq*urI{qoFHn3=AGcAhfH;VUyE zCF`Ur@l^t0T2RZ=O_2Xo1h^!9-EERh0vkZEIN5&hSJ1n=J-@3~3t@BRZgt$N^Luuw zxD-#Fg5UkqwP9CqrXiLl2lfZ$t$v-aG?d&&PP!gI#=0_oKKsP3WMg+-VcCG{rPK>& zfiA6Ae4Mgpk#UQQ%p^9~;F`Or$WL;*8O}HR_2O@B@Xx6t^B!I>LL|N^g-k23z_B z#!XqC3D+0k(=F!HEu*K3Kd@mm^2$RBmU}AZHo8QxrHOTB=IL;LRoOxMdy!yd{3mFc zK)PCC4*ukTX@!yS;Lozdv?&lOz_2Hcx6=c$gNt{@EKByiQ{}|3SD`d$bGcmwQ~GE>%rQl+X=Mod6z-?8zefjEz4IiYWQHYW$pV4 zG2pnH%Z^K+ zQ&x!vEYf8rueboZL?lr4~u ztz?{D(^$e4*(WGIL~_I;E`rvX285^Vd{V^m1|$k!#OJFC{91w%>!->ilW8ZN@6*-}}A z;^JsI&DzHWctg;Adyp5Q`$k)LqGq~$jGAZj(Z|`RS=~(V>BsFq*$C2?RIibi5QoWU01&QYbPTRDI2R^=O0cy+mzEP001> zX+|I&bEXni*(XeG-qk26N^gvr!pW?iTyT0L7EJodl4sic8pUFpN@t2}#qm9t8$~}m zK*;4q94HEJx{JcxRA%CT>r=9^Pu>shRrREagU7w+3mixRWQF@F` zx2(i}tXkiVSP?dyKen79iwBtGXVH37uiOF^n(@fsmtx#p!g0H|)}G?ie(`$JDzhg@ z?WL;QaO(LjE`2#y7UM5*nxSF>mY%>G9uEDG7a~Pcy`3mMx4La;xRe`mbFXnOq--kk zX{mSdte}cav+J{Kc+Z^~_M%1h6D?cRT~C#wf3WUnsQ1VC-bn92R1D=me8BfU!qkl7 z{}nfG!8V#;Y82%6>^VV<=IM2b3UOV}52(^uCl5;i(sKRVbu$UBhglHw^n*pK`Y&S9 ze9nM}WYMvd_bK38b~P>0RRX7B+A6rx1iwC^8(p$g^jqBVRi~3tPO;AbkEh|_$Z`iS zND&39`}a(lzfr>>F?@}3#+xF zdbFOh<{6w*Rx3$wh;3j|`o7r}{X2JR6-hD_9hvW(#_>$w;9lK(9Cy&ZhQcetFxJ0m zI_IwPF3K91N@{nixmo1c7rLspEjeKRJ8qN`1FIIGZ&95Ms?qrM+46?d2XE zb}-vQn_z$QxfqEINMIRvUz&Rc{)Rj$+s9jZ)J#s+5&4cAQIoG=FBSgxK?QwWwJ$`5 zy-^B57%dIOu(;i!VTckepO|L-O|?BxF!IyaE^3(=#4(756~Lh zge|CYc$vZo!5Pbg#@wVXpi@=e=f0CZllFJRJjVK#e`(qQ`STZ@q4y)65{;SenJzg7 z+`p>#RV`4itsx}G;O_P%tsSCbkG$~NOC#wyL<$U!Mt~%Rr z^&-dPfIC~`xg9K=9v6eCmc)aIyD}jbvs6?m{n#A?5|yZyr*A$~L!baDE54CCh_gd& zopOY_CY|n>WU;yCh;tYzO%9vwq)^d9h1XwT_uq1j_yX*NJz|`ra=7m>28=^*$Rx7$ zT}#3U5pUNDQJsSto<2GXT<=)Yyy|kx79mscD6A3%V#_iE0Q0159gm)|S@fCHAUA}7 z_x2!S8oib9tU8wF!NiDSu$WET3TF$MXgL1+ZPzEW;_Yw6(!DX5l#@K$fCq|7>`}iSm_c8E}qPw}V@$RC;M&dtZah}RVfh+e=!wG8g)T#$W=69$ zB|st3cDF1lZK&v+{L#o}fdoE*FI^1D)i&7z?IB>6Y82 zs}8w!5y{=Q!#0EtKiX_*XZ3Ifz-$h*-)C8qtFvdVXTM>T;(%e2R4&XDojrXkL^-vN z2E`ZwVyneiu@mn3vqTrSjy7I5Ll3jV@pvICBYC8jmrnMX9xLqFYV=wI#oOO z*O@j21Z|HKXq&ihg5h zEt6=!SUs!>T;}oa01ScW>U{jlnR;*oB%K*+Rq3H6kF?s&>nQ3(?DzqKh$><%%xB3i zAR;W2trjX&QO9nV(3aux8rm9fOFbrB=MQmCXw;aM)k=~W8Nf`Czb=x%FeDjc%pe=( z1-U{#BTQ9|5~E=CV$N0}!i!xoyMAVMr_1vA5bJ(_ZWDM*qjxF(!~xJba7@H{?~Ybn#q zpIa=AK&XoV5t-F3E8RZkS}8TQz60&}f3G2nn>6=Kwf`{NkgAyTci?354AnlxPECLs z)rv~1V-GmQ@RReUA4v94Nl)N)*C5UdeKF?FHoz@T0Mw3U-~**Z4xLu<)?oqF{wyct zv1Vx9^*{?}>N$}`K2eN_SpR&Jd2@3)B2deFHcMO3QR}gWAIX-S6DgnWv!{e55fUkS zz)m|K$D@695)SpCVZaCc_7e&>PnqR2+%&$vJQ)Y79Z1Z!R>A+wU9k=dN6~NnOS6N3 zpkB~5#Z6fANN7JG%t(M$mxmWssX+NQl)i?^dpkLLls zB>LI)Q8?6k)AABdAmD)$4(`5;&8+xE37RvjY3fqsl|Y|GHS>&?;<;$;l^Md-Ec*^A*8BBZgeqOtDP4vr=iLTcnTS!q}#1 zi)}cI7WV67qp|@>`kzcO<_=8`>4=LIpx9IM?SVkGLQEtw)L2>AT~wAOyWVK{jb3OQ zQff^?lA2Tt9hIGEGY*bqbOFC3#};;ddFU*o3|nZF)jZU)M6qNm`C{lDv4Zy@iG=@e z3HCHG&fS=ApY((vM*WKZ^eAa(puPVy;aWz$ zAZpSoG2al&6;pa?`yhcSb!%wGJ;l5qQTq+tkrrhx9kiT#Yhb9S0wMAN{8c}S^Aq>JBy-QjB8%w{&G3*y{3K{T?Uok=D)SSA<2qe1qlxtv#??s1OhR35(CW?Dr!(>K7|Jz%IamWis={WRzYG zZWTw+eHLCz4Sb9hjwh$z{jbn4CVWKC0FU1^-Lf=}B%}<30>Fgru^o+aRu3Xy|E=U* z=ojr(i2TO2z{B*G+p!dS7cANG)A|p;o1Ut2J{}X)15j@d zaP3g24x;Eb*+8r#q{Pn)hYm&j=66yh7%&8Df5*!6c490-r2WJ>@+<&_C1H%-U8Y*U z*%CX1p+EE2j`w1Hq&JiuDZOz$T-a^Gge2TsMEvaM&c~=w(c~G^r#;eo_?umTDe)qS$31J`Z@C$CkwA%r-suzY<#{Q z%^qE43(#2%V!BRN)S1=(0azs?qxtw(=s(XxO2~tt(m`9xjowFhCQkg>7_Y7Yc{*^YSI?l*%LPO_xOEI2CWiqwRAPHt`G$M2ZaW4=IMgk|7u2^ z|2fCxw=!D^r3(bo@0Z+~Dx?D0BE=@h*szfq+WFEXiRV0>M@;~TWQ%eTjxRAszTkDt z<~zDYZLdp;Of|%kjLN08oJaa%9pE@=s}i}VXtw+3p{qjI6_Vr_H-cDpF3)N)Irx_+ zA!xt#FgEhoqp!9tSEWBg02602Ior=FYro{Ya=hFby*q6? z5mhayhfUt;mnJ|qwxZ0Y#&gmMU^MZ zdO+?F$7zhe1YiZ9S91||Lqg6z^y8MEC8T()xtE#2bhE_54QD1h8y#fS^QhMCWu)b4~_RR-ag!ev)W#-^0coqc^Ff6@K9=t#9+Jk!$q z!;sizmtnO%cm4Wsd?3&uC^BVt@@WTfjH7Rmp<7~P(EZ9noMKyY;sJ-h19`X!*o<=t?+kI{m%e&n!ZOka)+7 zFX;c1E?G44A`fJJcsTOjCAB{B=jDWhXZm6=$StxOewPQZ2UDbC(*TKgA0VYPG7PBj+(EyHL67hNnW8tFmMs4Y(9QO~}CzX`f+!?$rlpo=qiXEOa^#}F> zyn}2d{)J1|Q9Vjw8KC=%R3U7lGp@~a$>Z3yIYwPbt%uVuD&RZtx&+gl2ddWF>ni_| z>7_M>!*U86(0+xBbCHXWTmkq#z>o_EX&yxsUz21Vt&{9~?{>MhgWTZ{J?7V)+f^iP zWCjU+s&{HRj8r2@l(8NcfcJ!q-Bu(32Ge?}ev?|oeaMlk80{-ag!0f|Tv)MS7B$g> z?52E`j*w73NeO2k#xs!fuQwACg5*tzw-N(>l6JC$c^OhoNL9hZ=<)={d7u0aL|3%A zIp1yA*Ldnyxip!DS*F}01Y88r+HA0I~cDq%(-<8rC%86W7X|8sx0ON5jGJw>rM z%gWeB68bNv7u$jDLR_l6&&Hf$bf+4@Kv=gki(G6!B?z%_~VC{mgc_(p* z^b2-I7~erx0B%&}Z2gPZYv=~OkjopHLD^(`(a6oOTt|cE8n`oqo*mL|lN+E{CF_T@ zU9rRx3mfRQR5$Vp(#5ryjm&hqR`{};6EErO^ONnTw;(U%9sxIz0FYz@xZBID^~aY) zoL{Dj4T~d5mQRsrCZirzOVelD99Hg%Dkv)-u|tyCL;l5K^av-@kW4> z*ur#FXmvU()Zo#Q@U|1)bN?YmvQAE|GGZyhf2!0qwF8~ovqI6!-^P!vb>?yk@1zo=S26Uzql=*G2M;?f9ENmSVq zS*GRLL&5&@@B$bYI+o=_v?!C{F=&gh{>T>{^43!tT7Wx(&jc<3YI*)|kBFmG546dXfxZI25J7yj#5P{%G;Slf0$*q*>u^@8v z&mp_nwl-pSf+ez4{A%g!I#VO^c76xjQ6eQdSZH|8LQSD3Sl!3vZWQ5kZmHEabaOam zt%AoajRmJ#SpWQpOItVo#I&2_aiM~g47WC&K&TCavnk$7cbJC)2Lsq$wtclj4Bvq) zVs5btNLWWo*Mk_m-AEINUHV)USk!>iW#}{MVjvfr`EulH*9oS;-|sDrG6QAEb(5`1j!wL=et;|U;zWF^hMRVF$~ zvg4It6876oR>Wo=GD-1fpH>``qt5O)H8=`UdzKxlJruK_@X| z>tdcBxb>mB6QT!t^&`s1tvSEsY&d>+^`T1^O4C|@JTMMbLf)a+F#~Dxbya|i{nrG_ z1)bJ_K${fXV#iHvBSS=!H5M!|$r_1TJ1V4YN)x78qCPfl_d;VFLtld{=4EmBzn_7= z<$;>g_-Ce1$2DnC!&L$ws{$qQmd7}s-ToEEJA_&~ZdN1A`=9m>hee*F9STgBQ3Q{y zH_Ym?{3K061C2zFzUp>H@xHwgKBQMVD&J?oT*veEKH4MmQ~UOAM0MXRg<$LRS}FTJ zu{1iKptVx^WNTl}PLcP&6Yg6sfHVnOqO)G~`wn{T^Etf>Z{o30YE`q&L!gFqmRV7v zydUQDAU^qC%iM#Hb{SIv@M@+_G8`)8GYOj8B?oj`E~Ls})YDX%*3sz}Gx+Wjbv7W1 z(B+~#mXK_hJ^_8Zy87~wa4K%mY~WdcbL;y`YcCPV!?OE0 z&l)s5D`U{JefFi=Lysf0Z$dI1Gmfo6GEOZk7oDATjPP6-1QYRs)e2c{$!WtFU6g=Cz5Z{+>vLlq!Lu_&l`XVd)7q zr}0s;H7kfV^IclcH??tIe7ooy>qYc#*DZIo-K5I!u)bU3{ZMGY*Y0SN$nyq4Uzd{k zsrQo2E=hl9mFxRU{X%W#NjMQQkN;CYlBdX%u=>cSM3)n;6CyHGLcd%6M(#1Y9191Z z{ju+W8fM4J&vDqgey2PpJO4?6^pXBM64Kr>*}!wa#4MI9e0i{`6I;)$ujle$IA%{%bQ-YFAQwHlU2OotOrzeSao6Tg2yK)ZXjPa7Q2 zs|J__`p5dXxm%3rqVdYzDAs#DJ|YhSgdAV!f@(U}1n!RXwtjU@MsMZh1cUJ;t80+I zw~)@UST0gi!r3>GcV%Bh*mb#Z1k!mrj}RlI>&pM(22pIdA0U$!^L&AebwNjUZe0b! z_jzuOlC*CNfyouBq7XZIJ5E|L-LGZV5}7Q&$!6+(?{l*Xq(z*GrN?$Agr@fN>nxGZ)KAhj*?a^jPwlkwR5*y83lkhYKsT1K z(;FX}?@h+MB9&>z{d4=k;LlG~^zFIAB5a)ilKUsaA1?&L*DKYL#_j*PSY#mt0$O09_+hi zEV|cH=*I@M@ASk+6Vt?xFxj#)E%j61#G4J=FYjgjB`n0((rXMI)pr+n zlaGSTXd_jaIpK`txY!B`iFI2--JK9lSeiH-mFbQuf=Ctk7jP8gMf+4lNgAJ=24Ewr zye^g&s5LX>CkDI@u}<9)92k+h3-9o{gXX%+a}Fs5g26VKNP^JgzTkeI*s_rdbKW(O znu{iuSa>Bg3t8!vP2mwQbGmpM*E{z@l3$!7f+=DNcZ2TBQ8d`hIE4W^NB7-8E7mT| zIeHxfBy{_S36uWs?Ul zHP86+8jiA5whL%p`=~v-q zMH((df#t@TdFI>{L3@!;wNzuF?hrS-MAw)08rN#cUwMP4nhk+8!kl|Bcg#T5YhOu zYh=`~s*eW+n>c1{z;045p&)G1`GfKa{4*JgS&Tt?Qjzwa-%N95u3?h`hH(fJwc+6Q z@E$(K-v^#Dxr(-JK=M8&J+7Qib!2sR)6R$Uru4H@q5d`BdxR%2*yCAo%Thg3G8;HV zeN^ci9bNTITwjN9l6uX8*W4~7{E@pWC^zQoP1KaPCelZ#g{?_b1>GZ}tF7!eZzQRx z`b3`0mi>b)!~L>5zF40$n10k}P0~wn9x{GhG2Ei@t{-B!s3l~Rw?G{;BXeOHGNF@^ z(`!Gcd?+`KiyOiql&4uAY?jSvo^7>Vb%wVC4Zg$56v@WvWw=ekeq##Bef_ECtFm5c z-?-YP(2WqDMtd`ifMB?`aUCYg%0#IwKk;{YQxBh>Hux)C7*1hLtYPH`y@PsSztNHp z^?%5Vt+P+~_i}-&)X;b#d$rf@Z0Y~nLHEG|gCd@xm^=gSekICJtbl;@IMnCiYk045 zFvn30diBFYG-_@dJ%SOXa?ced9|6ijj*)(8E;eigLfxDyAAB!{cj3)EK&k7&lpCV< z(VGOTE4Tn@aALmA7kRG>A1luXR_~Hol_o?cVG9O$J)B;h5w$B%R!OxGp8vUKeFFI( zU(YhtCWL42GZ35=iwnT4yI-h#!;4So-*`*xOoi<_iSUcxR13sfw}IR2YnBfD zyeUnTaR4=OvEF-ZE=Zdj_~Bxp)0 zA9|j5Yo5q?pscs5N3`eL(G@A3ku{gBu7Nn1=ldaK;3Y?K~xW6>DhZ3 zKSt9oIJN1s{6M=7RU3*nu~|!?)a&(g^Kbs;>6D#dZ$zQp5gZZJ40M5T#PX3F(UyQ) zEs5PTwyN&}1W#d4K^#H?@eby$d22xPPzH8BgP!kqjNQJXBn~{ zbS8m?8qVF*Z>Ye*UFUY|x=@BY66D|E*pG>m?XoEhokkF6?H){iIsrWfow%9EN`)5G ztFn@sxohh=3UdmWmx>c&gU(v{c7gI6hPa^j>Hg;!eu{9$Qw>WF61vWpnI%@g_TNSiIJBw?@K8C6dad{cRE*9XFUgw#gjEw!p?uD)9LRif@}`kwPAvVWd#sC?nzc536{365C@m$IiY7pd5n#&i{c4 z=n%I+6RPsyW-wk|Ts?>(tS>Y+bndw@NQdcAr^g!Cx!ZQYqcU$^no7dRawS`YyEP9$T#ggN7~!P#_EG z6|bL5sMU#YJkm&GA^4GJ&BC@ARAzTiKVD~}F6J-7-e39*$T%Y7Ssma#sDmU?Wm&gg zzUJOVQAAzEGmvI%goA2$4{A|9m1g+?kBh(h=km49{YS?J+TssQN3RXdGdL5HR7k3_ zI1=9EN@g*3ZD%P5_@|#y0vui@PI6XVP@ea2SKUJ&HRAHECvbs4UCNInH@AMmVt6^{hg&9-RIjcJvq24+rQdf2dDd&FGf{|@LG`E2ry1=-Ws z9`_@u)2mt#|HnXgBkk`7Z7CCMn!=?;`W(Dg*T5{T=S6vpLvtC`^G#CY1EbjSA3c*x zd&qw<&kWQn)4xvBVv;rW#Rqg$owHV(!mstqx`bK&H%IBUh~KoaU6z`-;X`;+H;!DQ z&!tcXb=sQYjyc3KUgZeP(|pxazc6bT06u|7u1hAYtu32md9;^^@if>xYO-r_v5Mee z-(E1^33TK1uvAKEoxth}#rtBiA2eiGn39{+o-a%7p5S?m5wV+mz=;H5v;DPhV<#-$ z#(0ageda$#v>j|K`>!|v>E;Hl`mo~#YGv_)dZhITCpI^BU-4KR6X{Kbx zO%EWqj(+ET5W!gM4f}ztKjrElIwxJpA+1U+1$TH9+*rWzN%A)-YzjF|jai|qlz0nN zZMwJH(yaHha!!kazn`$+l$1+6F40>LpsC%+!=8xJ6U4?lepqC7o78=khRzdo`^#D; zz_gg`O`TxRtz_03Ak(Q_VM29SEnSSp0&JJRK4En}TmMs&Y5R}bRg?t$IhrmmMtQa; zI?L8M6#(n}Ix{`l_V1$5r<>KPymUFq{O^HSVJ_loaKS=8u*8I&V$8g?rodtN7LBG6 zs9*@`R$ z)2}YMaLp4Lh32@MBXS&(Z|mGFl7}PaRs(U)1#J70H^fE0w&xjwd1FLote^>gjRRU- z|8~detuwkSvo>FWPR%pQ18=9?EcQ+ljZSIO!+BajoI_=JZN2{HD0n5TH|wq~`Q!&` zriY)$L5@S|O=pZ)x_!efoI_?m994x1)oqN`nLM)`!KY^n{`^4-;t)MHAjGvC6p+nL z@F{bT0l7YuF<4=W&7Y{upv~c3dWc6Vy!efu^e_F7-ER6{+*q{z%n_b;?qq3XAK_Jz zD+7~HSJ_pbRyGsXMs83$6=qQa1G{wd;3<_lI4507FMY@}c$$5IOAS*8EeE3m+=Fmc`;v_a&Qeq$ z;qOwytECqnleMAvFe?FZLG25gKQ6dJ+~-|Irb6~%R2H2=-_<$hpv0!08i#z&+e3{# ztL2{4RXM$leF^XQ(RHC|lh6(0D=1Y?^xJ29H~~~9tG=&ZUoqDs)71wcR=Zm-dOJmV zDcx3kEO0)$a7He#vx*=xQFCa}3Agb09tq3BWd;H$pXxREgjp8`Ue#R8=Fn0Hn;%`P zL$%XWHwsMkLDJJOWMnX%q7+YO2LV)bnxi-V-YYDH9*A3)!%l;;yHc6<2mMjL-T0wp z>9Rmyg%XU$4g=7Z@$}$t>fANa2`0I=ZHNuKgV-j-6p^o>8H3BPrmr{Slj-Hn*%Wu> z)O9cyon3puQ7(0idOR@Tj>Jv{Xi7@vgDNgWJwKTU3p612%dCuFy(Hvsj^0Qz=P&E( zp~jsVGnQ!KdbQR3%L$V$q%pq#GP)Pwsb|aTW*JR^!HPZzqB0*8%64O~NUv6fYPvB$ zaOH~=wE6c1?RyR#Wa64VT1o>!X?y9J(`>ewyp4fggw@Rv48Hz!-%Ff{jy{!qL0MNvBC+*Yf zMKJj|>a?QG2dcfVd&To3AUIMq@AHIMC%K#)ldbrp#X8P(UW4%Fj5#~Yyh|jD=FsXB z0tt8OcRYhw!8=uUe%IOHa|G4d_2K;yu}-1y&(oiZlt!s5XGun5bJg>@X9hz6^t#^J z!Izd`f@YON+(@6GFRDmB*K1+UaOByPQLCK3GQY7Kzpu%9Hj&Ro16t%_pKB!w-!c`; z34c9hWqpV%pIjJd*(xHO&7|>^?RkgoAnl4Jfha96cm-@^8XOj`(g)UUIsmU+*-F86(UlhVP#_f(G2j`5^Oq^17~5p`4D zs`#+%`da(i8adVBMO`nK@SMWTPlQe{UX9wuu(x=-4|Aa=mkLE_c={_!Ha z;bM6IJJ{xKMILb5hn6D$%G+*ZXfR-;m}Rx=JuJnkInDNX=!7EXy8eQ~Jb+!F~FTa!92s&Y8r(f4+LFtJmG9 z#lPRX>KLvKu3<1?N4|<~aiySvLX&|#^BMsMcK^?>C+e_>@+$O+I1N$L@xOJ^#YrkC z4l3|IWPqYhA_8(FZGO@EeCDK#zkjCIyg{FDiE>(bIno`a5QsZE8Q?>8y1{HB&TG zXdQC59&Ac(Vk|-yOB1oYrkp%fg?$yKP}`dmxoFF&0u{!9z*p77xtiBiq?QVpd#FTCFuAoVeQ5Qz>i%yRYqQ%wfX4veuiWP2;!sR_V?>D%$5j(F$1gf_3toV=$_5kR3=rpOhQTa73I z!9;6K9_J0az6Ax}f=rXI(w|Dus$2G%;AvcHx4Bv%Qh6zSv2TVX9!jm#xvX|G4c++T zNk47QeegwDs|0zgPL8C$q)W)fm0h6(L2=LGB3OslEHS6O7bKCS-8ZrS9GudTfu|w7S6UfNtT^^U7d%n*nW4@wR;hc!*ay0hqHyULi!js z0?Ly^-%R4xOGkl~OrATPs|FrMI$2#^-a+8L=T3W9umOxA$589k~vLFITf zqN;qI9!s-&S?J`*~^nYK|`_=U5;r zqPIhe10ER@$JN0k;zlqlSxOeK08pElxjW?t3y7c{z@KrISa`|R_ z6NGMQ?@3gP7}hF^S@On^q8k*jpDzbNMpP)O%lLe*sB%n5MfL$#3>LrCd5y$(a~iEQ zlYm27R+HrbC^e66AZ}>%n<;D_>t2ZOYG9<&aA=-Wmy7^NCCkP1=rh5^|6ME1v8;k- z;DU{kIFNn30R>egIPEOz)%DPEQEwm%;Vg$wHFwZcMp}O7O%Bj6F_rce;0qdb^CNQH zLvhry_uS^Kf*t~sX_)dqVg9D9Sn5Nt-Qv9 zfmKm7Ce722m$0ybZB&6%`7>vGzQjz)?m5572L6p(Jt2{A=oYfJ zq;=QFg%?iJxjNE$(L3nN(&OnUa{U2){kOORx9u8~6d)6RQJGV6tKH<7G2>&ce-h3D z3Wm^cM@vi_#iuTA|E{gQCuL+Q1=r3|JE_P*ASP?_${C$gMIw8kF61fRKDIH0{DQ>p zwGADRHce_Sr?axL4A3o^DoPMX#3P-ai{(VO3>xQ8i+**wLjyo%FqaF~_iFr0ZgYOv z?16=A?|YK;=Q+xoTlw|($P5N@0Hp6pYg9KuN+JzgKUx9|wp6T`QXd)JRCCx(I8O<# zl2uFkrfwH_*6v)49X96;px^c4IDSjEOv4=l%v|3FT8mrGLTf#v1HRd(5tT{^rji-sux1a?pI;@&;NMZ@Xa5x z-Sr=?mR3p4*cK+x$;D-s+P!6lff;8B(M8h?1qsWV-CEh!kxZKWlHrUdH7(X!aT0={ zd21}9qG+J1GVKAq5ztXIikO`vD|~aI)E%^@SdZH=1TlLvS9Oq{1q^M|0pWb=fK14e zDKQft5p3j4xr$|OZpx4}*Fet;3>2Dwv)=C`vn&YwAV9Uz-PU*%{q7#9hr8z4F7~jd z0~>dP;M_1@)bX6-WEz^WgjKfZ5x60YXnbvY4$%!O8yeoRCStojG}T(Tz2fc(DKUs9 zX`N|)wo+kp6hDvUb5$S`f6u048_Bn}t57@0Kl_`hoT5yr1EEH^h;Xb^Ri|Dj11$<{ zAjT+R+-zb4#v;0MiAwBZ;$F0tnJg1QQU#E2|IS_HwI!4@(o+p_3JqZEiXTYbgykrU z;ekqRGN+%sk<*6br@{SXUbh03*!AdOKAUiRAvQ1E zbN4gKkA?)*!*c1}BApQs!SY(c1a)9kIA=E3-f7f+;KFP;)9NY{L6|W-8OO6?2sC46UlbCe zJ{3HCOucJe9_WL!R>U<*kW8BI#6qz^C_a;A9+Pk^v|~J>f_5)QUqdIb22rx4SnTcM z>q!gTJcaT}!Dbq_mq2Ec-3qd=I?CRS%CjsB5gbNYXJrJnKS=NvDmJC!Mi^n8LT8P6 zJeE4_*HikFH(3yYYSHF5{9?97?lLW?Q2+sj`h=m#sCMyT{nhNzM`K5hW@kK^+RDrS z2@+)vYEe*9P`IT_3$3$elXH*8a+oi_dPBYZ!xH>)+hYL!d#Yoxz%xtW+nKEf7k zeCknk*0dm#4iJF5%piVDwFAkt#thh!^#XX?Sps4uZ*d3Or^0ld~=#vC#n5lj~BV2uw7#QqG}az2S1UBExla4i#v{e|w0 zPt(<(K~fqRm4^cMTw8wWWzFakgClZ|y<6S8QFlOt_a>M#+_o{-vHos6e9F zQBW8h)hHl<`a6zb-qhE4+d>p99cins>a?T|GOw^}Jewi-U^`x}?@1zIhftgQa9m=q zSzCyj**%=wqEId4puzbVo54JH`Z$EGAg;I@;0v|s zdptX}6(~3yl;=6yeu})$ncT)KfXQQQI70nfYHxN!H9~ZH|6FRhO zp*~hf4uLSv(p->EbaPDmps z4OdRwPWg}GO@q@He{i0j@r**7klxCj@JkXP2S|OdImgM*K`o1fd9YsmF{!3{fBJ*g zCeL^vB#FB_>YT{mJvXhZ?8n|B9F`7ik|n*7TLVyx4}aW#zp8YT70S{Z;=oW`JYJvy$)N1b8w@T_=&`w}t3 z@~Q7|)Y#x4@U)fOMBsO*;PKNJ5syTw?_TQ2hfLY1R9&uM2ESW$a#UwTr;fh;_%{Bk zm3OAqusd40zDBVWgd_T{!F`^Pm#0Zt1DafT#yXy_YN=6z3p(Lfw#gAv`DLX^W;Gh! zI8T_r9|8&(L)gvdV~jae*vGo$y`96vkOq>Co7hE*uSV?GT1TXPhIOU|#xE9!^GjrD z&&bUXZUw~m?*oFwlBS+Vp~ubIz@HAlf;+9GF2=0oD;fImIA~F)5Ud-HyoA_=?y?A6 z^?YPwFwlYHdw0XO_rbIkomf->YjApPia6y+jUvgS06;*$zn?jcT}%S;v2TpB!%luo zPYa+C3XJiw@z#M!yn3AO_Fg19F^qoEm12RKnUx?jz~~M2L2@Oq_hp~)IYn=e?8T=9 zYpOSTE_sdsvNfVV@{S-xnrIcYs=Ssw=oXu|ZF;Cu^3ZIF!3`eJD7z-9uUJQ`mq_|U zXdEkf-Zrk&ouZf?twTvhVY)y=hjpNl8N^}w7bjRai>k(q2mIcX zbEQxZgBD6d_bKIX6H2(?o9pOS0%g2jQ3|oK_VwI=d9Vh7U-&kB zzQ`U!mk;7QfD^=~Z>BULcz24ov(N`kL!?-`2FGaLqjt)cwft>EGcd>6^7}Hg zEotqgk^>5nTgQ-;fdIb+{go92PQn?B->KyH|C?6uL6W#;FMJM?EIA}JiM?%fa%A{E zUuYI0o|B90wI@YVKfqH~FdCL8Omt5;Pl$GVU&)2Y`;|*J4!-epLQy(1WHr1VAd=uKWoX^AUc5AA^1s#eu0O6f2@+{|qjnz~xR3-Ad zytFyI*-Lfq*N#P58;NjTuN4MOHHE_UlN)0iQe28;=s4=JkqdmFY#kZOrUW5k71=a9 zXv{}~V_~!(kt&M3q)?|-IkDXwx9%cObQNC^p3s(B*nTRJL7?^ZlQTBu!|FpRg<49iWyS*M+9kd=uKxah?6L0u7GDc1a8#s7 zZi`q#B?a>t|2q#pjm-Ih5D7zEX?H1C*MrpwPji`s&s<_LT5n%jldoehZl+nVz#|?G3tD@HK@#&&dF*e`w)Fm-zy|#)9jTzXyKQBn8d=?U!_eCE*r{(!(^U7kgIqcyErv<=#R&c0dIuO#L>`R`3Jcuh0u5`|CL=qi-6P7Tr zyZU_J>c#WfkeELg%#0?!uq_5@_;NoJbh{?Tg%X8O1k2QeI%sr_}5O$WaehT^;#}8FjAmMtp2kj7R8pfrF+^rT43djHVQ(WbtQUT2TH#4CdWmkB{a)7s z+}ph@O64@^Z!{9{lTPSZhA&Z&K(+>{7~wRhFhLpwzr`^6Ub==%Pv9nJWrfOT!%R;* zzm{t;+|6hLdVS`dB0+*<@)nj@iH&GMnixUwi48?dd$A$u-Gqg#RF&uZskFkT@=@1U zphUy0h$*X0@Y1bMEJ_P5r#b^5RQ^E_RyC`113Se@XKCoe^lG6HlzAsw{`B!F^E7RU zi5-Yr#btgz&c>C;#qAbzg%pNI{+^9uJ*<{%e}Un;Qfa+PdC4xy$X{7=hOZ|JZiO0Q z;3==##4T(o0UpW5)nYVAJ^05xk^ zlx!_#g{s6g{XMZ`HvKZp(CP_WXld$=Y>*$t-NXl8vf;cl708H56Ph^niI!Fq3-5D( zcW=R2_3>jjAQtNPf4VjnGZR~`t|qbF38;XRltz_Ca$iN(2YPl_IAs~-=j>$E&hww? zwH2jZQ!Rxs#pkss&`^eKK7iumB*$mi%umj=cRMF!bxDhcBl#kqerGXQPKoqzYPO0;n2t$ z3O7;&_6D#X6%Iz~$U*BOo75(>zmP0oimZsSzsYN4TIdCgo`?cNx9<9G0)cL#UZ!`P z_W^G1G#YxwufS=hRui<3K8O07;zaRpVKHbQ2L}Y6l*bse%_KXu1r=QosFjj;Rc%F{ zX&KN~`n@g(jt-F$y(~^K=(?mtHcOh&K4&f2pu8YSPP>>fc*NiaN}P-7N~ z8EDps4ThikW|av`O<#`UPGQS}FpoRxPBz#{5QL*H5c1dn0khb^iIF+@tZ1dsL-B!` zI%K3@&I zV6bXLYUx9APNja_NJcl<(E|a%rr`9mIG%+?)hcKa)T_OO?8kee)Kn>yIBULmN?lT1 zvwNN;lkxNQ%;d&=D@{jzkU{2yYgY`&!6;KGt?#ClH%pr9z=Y?rzP#f~w&Tw7yx0vv zhD*hwcbZl|3`dPud-W9ne#)6*B$OH-@xMJ;t8nF&ko*9JkrY8%>A9<}6XZiqxB$W%Oaiyus$K zjquQW;YK39eEs26P`bsv{-V$+Kj)qLyx}}g#gt=7ekfQJ(;NNu@^wd$Cyy0Gw z%?1M-qt!p_xaxN~tW^&$wobbvwMprdm_g5dz5g=_XytjtAd#JV>UGQth5i2zv7Xqj zvl4#{tw@xLD1`*hfJQE9zyrB1KeWg{Zpw&2<8OHA7d{jRks7YcK; z|DAZ@t~fPv>+3{#PWwr}vMX=mOBpjVL9h^NTy}dhzZ#d_ zJh-i2%>)=kF2j*IbHHh z;u;n3DpbUp7AzH(Q!wHT{sd);=fy|XLMEQrbncV%`Son-)pdAi`!8EqlxeT{wO;a$IoZtfM z4Eo;fdkgJ%v6aZWj6|`S8dVfBgXL*J({cdDF_s4fRq!m^$Sp6DBHTr{mwx7|LBPSxBZrpUr`m! zq65aB=e5e8JcpvhD)CNvk!%0z{GsENRs{?-UvlJXV|n0WYd19s|;pxgcg{>+B4zA|_2Q~et4bC&^X_ zLH5N*LPjY@t6nTsn_qZv`gwtzEc9l-dqB`L5f#P4GTEyX=RnS35NU)0pq%NLJcd*2UT%j!bZ1=$jLVUcq+4?JTUS8-V6r`BkjFXS%8=XTrl`pxF!( zVEGa?yt-))abVh$1#{_BWA?77s~fBMC_)h^2C1Czx2JwR`$Iwd{JMIs`^=fE$cn0t zlh;*5|MN$v=}awiiPHIM0R`mD+;n|U^?Lr&=`u9DuH79Wdh)9qijCpc{sRBV3Rw{t1Lq2Rr7(NSuy=)_%g*{y8i2rV8k5R0G7ol7I@O?W1DD#k z{{h@1A<>%-W|GgAF7}>;lrP-lL5Q=(4M12n&@9PvnWnwaqI7qA2S`VaD$fwDE+_`D zLP%z}xey+GrN3ar1Ie&OuEZ8{uluN=q5r<QUAg&@rR2>v51K&SCO6C9N*@lkr8Qcnh zr=GZuxPGi-1FH}A~0Kunj@tgg35#80R3E{iOp+n9rwDMjHAl2Ox?}~SmY~~d|9E!RSP}Y)2+t(Lt7qf*iJX2j~dE13mc!5+s`W&H7WCE!{<9fHtBw z6y4`d#|u&`IF5kSy(bHMP+C>zT!H)L|NabTe*jq<3tN$g9Dd;6T?nkJ?a`?sZ1G)? zTz2fSvxoXx@knYj0s&$K!y3)w`*cqm8UL1K>oBzSF4?gh2xv zdr5UvfF#0^=^mCFvr1A&o8wc{mQ<8+gHSWZQ-~H{O{@3}yG(i;2cBNwRLV6iY8bQm z+sX&?MKA^;i{abhAsI)zS!-_*eCN6qH7rH(q7ZhJ#laJt%S81q5?1 z&h)yPD?s52X^ewpA?kq&7G#Aa)sBChSvHlHOh~W{1xOQIYv*;<$#G<0uIp8uL4bu3 zOrHhI=K(|Z&8FfJ{zB4*oMUpjt zIlcn8&gPG)+Lxf!d5O#9UKOJ@i3*C`nf!S-@FxI+s`V5)%4HY#`vb71pMBRB0+-r{ zbTgH}82+dd@`@~C$#K3)$%5hpsEdfnI1DY@lRqCc^=n|b&P5Td*q5B19gC&EYPykjGKVqZVW>vh4IKTS6;*j?ZX?1K>JvxWq(;G z*&vmwrs}+w7^;qj>=mLdZcZY^j6Nv*5rT_#L)=T7+D}7^&xI4}%Uvz}F%2|p)?t0k zxC6yTj+WQx5>SlhQq!TS<15k8X{TKI1_dGb@Aq?LG- z%Xc&l8sw#iNZaz7X@d+P`>yr3*-OJRAfS-jU$uVAe84Zy@7)$MQC|mD*iR%r9>}=RKkv;=c%@m`bkE(cY1l) zx%+4-*K(J#CVMtb%j?)MJmh&TA}+q`a{zzW5Jc>p;5lT8pe#^H>bDX3;Z{O^4)c6p zd{oaMvgK)%%ME-PGgPmb&aw?(rBbfdWqg#wJp3}?Gc%Y}_`7pRmHkR8GtK^kngJV6 z3}JhE0Hn*OPMP(>d_+`%*J&#s*d`jLO`w|;s(FeG15-zF{w}-kp;2R17h~d zL+FbC?anVf=`>o>os${1%nd?fW5F2}6HHTUHI}Fd029-}_555v3c#hF$iv-IleM0_ z=)N6l>(X3>wjFShUoSUDHS~jfV+gc#yu|Yb6}_d>7`7+T@KPv;XD#h`wq{sIV{**mLPMpcT_x?K2#MqR1H z=~P(Qp5H-8Q|=4p75wUWBnfS`XJ;Cc8bn}eW}qQsPKgwE<(u58;$(aBP`<5O&L1~f z*uW0@H3elG)i!yp?niZzp4^%uuZ)6rHVDRL$*vX7Qoq~H4ZP2NyWC2gcLRnz!CA0F z`UUDY{$mX*MgTBjmRPE{68Wx*$Ri0mWKlrvO?1e4rD%13;0=Dr9rRm)mq326M@-(J z7x}ICsw&s+u+oL;Fh#}^Zf589br8XKKEQ2n5>_@z1er;7ldYj}G!-XeFCg9Zm5u^x zwGpi_mw75`rmz?zA)sOj4n*r5$UC-k?id#Bd^7F(aCvPJ*|`oUT%B9F!i+f8p5x>l zBq@K_SWU@#z|v;^&f>(BtFnT~cZa_w;(0*nCa}m(0|)+oeiXVhvH9Hf01-I3F9&RA zD*RTKmBrn^_UsA!!0R8=n}^U%%caKMWKRLD^f)~DRzF@LF*A&P${T_8AGlRoW$yla zalpILnEAE0x6l?3ZtJ>9krY0zO+kug%=vM|4RuUjXqoIm$RN2~aow&KoCR$Buw|F! zO`CHj`S99{3S~XD%G5I&OeZBCJ2(Ji#W~yx7*2 z8Fp$Uhc#Altk;c0O^sSC+5Wt_)tU(7^qh~{`Y{(EbmM?<2~h>=PGp!}%vz&ob@Rkc zSDs*r=M<1}`<3bTKShsfkn4yxq;kTp-GW9|I8@+(N$Axa&3Ya0wT$_oAd8g|n&=tv zkK&n*p_l#f_+MMG5De9-KVe%Bg9kf2evz~hB6sa@6>YufQpd`Jm|1!8#}KH*FH(jH zv&N=LSsltFr*pN>mu&7NlD>G77_ey#okUbI}ALEwi zJy8xB^9)p(#5zZdmuL+6)nG-en08DS6Z@y*geYqB(uVgnDQUp%2v2M;uWFM^hben- z7z}>tg1E;36Zjk>l0|k$zJAra97AaRC9{xCkWl`ukG^s=`%c?b9~r1oAqdd{&Dh_| znVI4+IG{Hd^!Suqvs&_$*3~UGgp=4+0skKMqQZ|;B*>YfEj_86TK6r^tfgHRCDwVK z%X}=F`2o0q4&mnLyy;@rc;8t*y{0 zHLZmw63;{V4$c`rCO-7QHhr_xryWO#*XN6A_R0Kt#VleNIoaFrbW=XH&)d?_8#~o( znN^VjPqYJCS2k>ZR@l9fLrCjT|Hlw-lfP1xGeDHtl^8^XxCTK481-6E z8xa$HcUY61w06kV&*&-|miCT9vy?wIV(E!xdvGF-e6-csjo2m))MURd=$;CUpm_5M=RX2m} zxB1vp{5GUr?el}hJ=im{d0Y88d54SG0j{demvd5^Gy_fpfJ>s7(5^m%90H^nHvG34 z5N)aA&MA0H`DBJq;;3(}gUboPc9HN+7CISZ@O&!fePa#1euy7inef7oK+6D~3cF5= zBo|gBuxjNu6T&d9#rcOWp`+MuG}1itDuW!H;7DfnI3cPYu4Wh?&rdt^^LrYxR`})q zvpe~z-i&&OHJQXt_{laK1>44f!-{X}+>d>k&5OdG?!s>=38!s`HmB8yN$Xfabp9|m zF->0u1|qBOli1B!2Ic10lT;qNfi<|q5U~Uk$B)I+A)FQl@=+OM&H0Vuii*frb5}84i8m|uh>P%05c}@9of=x;b>l3d43^o6}zU-zrm$C6!4a|{UDb* zRPLQ=o>8i0lQ1WVB#N;D05A70@)C&o6xvS9EKWwD| zxfe@f4u!Z^`4Fv3Y%5Kz&VRq#iPV`tI%Zhyr(1tNs|;QUADM)CRX`YT{?)hp#EKLL z#3+l{UkK>&zrhW3lIsV7+&MqOy*RJkKi?YtBCrZO9E3ckzD3Qq-_W9Kgq~=DaGCo) zO!H|AVW6*zA6}1YrJB3K;+%M5-k5FLC1{BLBWf{TedS_0qUQ+PEws@q3_|NV43AUH zO-ojqX4nNiLKc!`I>MjkcB>)`z7x=6fAWS&2OFchf^rvI9<;P%uYeL}>Tvu5M4HbT z`Q$7eB5C=F4wSJK=cF5|NO#S@^2I_UNGtsOu1q%tZ^0#oK13gM(-zwJLG-rx>f!nr ztXSaZg{wz}t*ShOS;@gq_nZEU)2}!JtN0V<3}6T`*wm6eH!3ase5t3Yr@J)jf|%*gR=rII{<(?gWXbP)xjp@em3KlZ$;-Lt|gYkMREtLNS&|ID7$aWofk z?a{RsDNq6)2%7Y^w)Qbb1E5u$rx+*duU_VA{*g=WUu-83A>O^`_1S?J$O-37;bh5OCoSLG;bpx>$)VLx;Yk_&iOTP!9_s zt+G+Ccy*+9Q1v2g__)T31oncFQmR#H+^mowSO5s4Pia&m@o#Z^7m67w}i)) z^6T4sC4@?StD{5#PJtYb{q&wx! z;9013wtcYgvyVO!kXFeDpG`pO?(Ps(A2B0wQN?|=0BhTgjJmp~(XHyuRYA!231ZI` zXyumDhaps737L5TdCq55Hk3W11{k9IezZK8ut95~gs+Cmb`U+?AjWDiX@yStmS?AN zl@_&4sfO?_bLzFzS$w0nP2|+%C1(P2~)hm7J(V}4>q)Q<4h`f?D2rpMXYzmo03 zm+66$sb+>YvL=9ncQEh!-PetqfPew6xJ0fG)-?nR@=m@eZZ>5>Hz>`<6={g^>O7^x zD@D6yWc$|41|a`A!e}Gz@Nez81O#N+Gp8ht0b}8So zHke7k zqo^~Y5rIqkaU;Q&s%*P%XvvQCQ>X>5v|fJfCnrco5mn+oyZS5Hjd0N$q|Mkkp~)JU zP@{|jak0->2YjT|r{X1vZIWiN#8~C_e|GOp%FgM)%6g?998j0S5^oMk1uK;C_XYA( zaN(<_6eDxe?)wnOvSh;~L|ktIRi(2H!N8=wLdwgh(f-A#ZPgO?4?&}?X=toQ zqs8YgBgG%g?8KY#8LKHcT@*&d=b2OooH)%r8vrb7@U~!MF70yQtE|{%JwL?{@rzKTo4EBBveq#un|v2DwuyNw|Xj49TB5oIC^Y* zv1F$x`6U(Vj_f7d_4mpZ^8?=+&(FSUYO$MJCK#Yi->z(5_qwiv*e1{t;cr2igvW9g( z5{=qAXCcZ03k*8@=2~?>XEfdau{-AQIy2dO>4Vy75?5RNkP?o(4 z`>D^#zNtr9ChaR(!C=qDtRk%yoyRn?9!C6v z#HYUSaX3kYBIZ{D+!}zXjU9@yAByZ%K0Dozc4ov6PA@QC;fN;T-ti_F)75mO7m%H8 z#8HZi(ngul7Z_nUdKpSj>t~)j3%)$A$9RXFkYT!{`$7)HC%6k&+d<<)HF=yeubJ=9 z%DLm;TbDKakIc9-Pss;o-fH<8K~U{LpPKC4B9(`UI*2o=jFRZ z**pVC-r{a@9Tx1omIr7J>@H^pvwa_qE;qDVj&QB*f=aTULH<-xDDGX@bQN#QpBzWJB6G*&@b0>>Z_YSpeg6 zy}&wtwF3CJrcD1%6YmQIL5n6I_#cV~;i&O%D~@L>|3Fv_mS*gclkF7Fp&FtXf%ga-Y8=Vc_8{JWnl zboQuG%n59|2c0yhxXkJMDo@cc8Jkl)oReo;?mDvDQ5S!HrX(61!d@9${x?(bvK&-W zdu?04riWLlq9C|h%u>5BS|u_*G0uc2{cF&m$yV267h~04!NxyE9N!l^^{fc~ zjZ7GEoEfuklPA|rQwXOp$cVD<=S^eqSEPQNQnu~@xv8*D*KAkdXwY_50K?m2-*VC* zlj!uzVNMcDN3&r8*{9VU2vX_0;7O&F>HOYB>rx)sNk4L+*zT#M z70*NiG5uEv-AoVzTwkWvE`hjBoGFaEtiy%&q4E^%TmiwH-u6529spaO?ix<1WOys4 z#0D3>*#Iw)gFZ{RHX;r4=d`*TeV?`^``yL%F-c52)<#PKR(DonYs6>9Ch8d{gWC-< zt@_g7(@&W%_LN3kV_I+@VpFEn+U-u`d2*Cq?CX$mzqb)p|Nn@Bn5n=uQ!k235?sRp zmYHNzoOjn}heN-PPUL==A(`N+ENuuePSjOUQ(hHFmFQVrJ2S!J-F2yf7g*JII0wG* zj}tpWlu0hddBF$48g}pCU?63l)MF>y)O9GDshS>UNGJAKb8qR+zPaS91O$1qtH9~J zHTbz23wYjxP|h499#F{z#?5AJYU!(xKd((~7+6cGj^Vy#x771bL(EfwS37sgam${-S)K{H5o0#IwKF1=2!z=nFgL)EDqxVqqzVgQ~4%&8DmrA zZQOGYn_b2QBM!TQ16y^L$HX3CP_5KaP9%rV8U*e0HtQ6M?UC{ZAjG1~*(zZ-XrA1; zC>_W&jvB)^?h&;GPa_fr%VT`b2gfWw%Z5ZDj}{6LsLv>q^=?HIF#0#2 zqwZ5t=x|zAT_b}-Ps~2+(2D5?ca{v{nO}6 zu#Ssq?|kyJJW7NX6~eRREoRr0ZxVmkD{o;nRA2o$$*knSo49@)TZ3K52Y2L(=%B14 zLMZ^UvX8D}d!<#Q5Iie7fOTKoUz}y|F@Z6Bd-xi69}2j4rNp@~H^|(F@FTuR*5o^I zu#@X!MUXD27rfWU*)2(q<2XX}`S7eTuCi{(1gHy0C7lpS82ggLUbAFx;0^mPYX!qP7fioO5U zD{kCmm43d-9qHQ&Lp>ZA3*JOUsoAHt5c64dK)Q%S&yy4M(zMxzFvjtmkmNqpP!*yK z$;y^DfgG&zxJDty*?RIu7UAB+XzjTLD8jXku=03X6&0WJ8zYfY>gIEWh#>D$Wj}Y4 z5Rq@GXJ|PHD`?!z4sCMr_`wY_dvyjJ$vhv()|iW&Jo3MTDvyl^3_SS~DKN>uP31hq z<_tz02Z5D-c_xI;$UN)C(1O%Ko%Fp4arWl)xkF4GuW+$_?{JI(A|?|}`m6<9_3!G= z?~pyL$!ogm7_{z*eiTv88f8%~W_cxgR-iZkBf=M&)FnO*8-|+7K-A9oa6F&TD^a*m z_Pf90o|4oFq(;x`L@TrL0p^PQ?RtvG z6beMvui+B`1_|So#RLy+Av|<$V}#b<%KVY{l7O+*wCKaxJmxyb4>)H)Dm07ZBYQmn zRX|6u^J0jBT6OHjtGi_-x~m#YzUmqZwxGpDtV_$CQ_%g_!qO6WB`#g_qvvbkfmZm^+9UIHjOBpJB;7E~i; z61U?=iE+k%#VZ&kM!%n6sOJ=J0AIE~UvA7S}lt~k| zVCQ)1D^f&wRDB{tKpUhs+F~TX@(lW>Xww zm9yNCbUrOP9*2lD!U%xppiebPRez9Lc3bDKkgCI`-^~JUi0l_t#F1jrMP-n|7Ovjw zWskgUW*Z=kjVU$=)`2ltJ?D#2-m)Glw2v7k>Vuw-4n}ag9nEK3 zCRfwjOmT^y=ot-r7U+CSGT$)cWyzy9=jle(*k6NKq0S)VE7;nmdwWis z-^89dau{m(xX~>C&t~3J9fmRlPQXb>KM>TNcu-i~pfL{5TPK@wOvQ(mlbo=XTgn;!o4 zr7()WDOIH6CMP}DPtc3rS6x!o` z&BGhniu_vGOuH<|F1QBnKnkbRSkG?1TUmBh()L|vGS&`zwe8SKYApei;a}4;w`+Q> z)^7SIZO6%OFvnHgbe21vK_j3mehC=A)@b4+*$*BzzD98KIieodMl>N-)=Bx&^-Aiu zb_W>O-?wO7Kg*97iQJUG4TT}vgly6Fw%zTWEij%ekNf;3#v0$*a&LJXV? zp#}!vI?C(M6^5#tWdtoz#+~B9iBa=JBsu=pAvr8iiNC1*SbM$%zsWZaLH_wW#~1wo zTT0HkE73+70MuWs8V<6$vnQFm=rpKKXE%Y!kyI`mN0>Bc5dK=(Pn-!)Zgg!^_2E3h zJH@40R|b@gDr^xeEueE?wpsM}eQ`qNDTBzWS34)(t_a5AOaru??>^k7xU5%%#HiLX z4Rbwu^^ydM<|c%#Y5AFk^byVBg$m>i0GsFSH_r1IW~zUIr?>KB^~4{(M>+1^^JNct zOF)%V^GS)QfGKjvu`-tufICoG)?wwEP4(0tFTeXF)bEwRkpM2x9(U4RomE4`%~)9; z4r28XnV8a^QuD6wmH@#YJ`ats#CiJkm9I`0Gxw8@hTC0%FBE>K#yQ}nd=yD6PQc?t z2ZOG5rbY0v!$fcVop;It=(8c)_1&%Zk7GaVfzs~{b~5&nfI6rP`D8A?NzW}Rsv|z2 zgDQ)zBoWJ_G@N$A7Fb?r(aGzQ*-gLAXt@h6ZDTc9KScWKN%?15dVZMLg3UtMo%$VC-v zaK){Sw$n1RKb{6)>-So}0}MCT;XXlu*rHNeuJMB3LgQpQ;^!jVRM5Ou*^2IuzIdFp zLn|&K!sMgn;)52}9XUwtW_rF$2@wCrun@o-?g~+&%RKE>t;p(wl}WH(nI~yaFz3W{ zEMf5Yb=;@G(}^pl)-n#c0QUn0Inq29WnmgPk2jI0F!clVXgGN(nk`?k2_b<$AjeP8 znFEH>kIbYvN9l4?ZhR;<23lC3K>4}p zhn`W66o#9w$AR6gXq%K=X;a7FLdI)N+Q`O)N-Bk`pH(P#qkbPKQU$ys{FPQn=)Rzx z=j=sE>q9?j>7yea2k(m^fPmCfU2;!W8r2-nN%N9z1mUVScI%_`6Gqp}J3!A;^H``ACsd{-q|0X9S*n#rG?^MQ0$3~cPzlTYXt z^Z{90-wv#0Ck(WPfDF^f>LYD8)3w+F}&9}Dg2>>Y?twF8a-~Bo;G1+ zBO^R$I)_(3czT(}OzXKsG}cU`^a2sAi}R2^fK32o;K#U`H0*k&W=-H-TDFr4#cd~s zIEJ}DZ*~dY;zBbln3cBdH0?YA71bQP!-w3x>VmUHwM3dD`MJE>zJjqH%|{!@UlWK4 zk*utjc2Q?e7-H4bz@IE+Yli%Hv;R9eCwcp!&x{o?4pD}gZJ4?7a)Gw|j3&qSkGL## zC~lDUVB(yn8$ED5@l^aN;f7(S_oS{^-@p=SkqgrT8hRc(t?MlfmOwv0HB-&ZKi%j= z1oEq};U8(XIf&<+MqKYpnV{%$hn-Cie5FdtE56k_f~s=hV%SQn57Qx-(NfLx=*Yu3 z61L+u81C_+aCE?1{6d3UX$RuPzGn8zVAN`5P53;mV`8B#E|aCZh%dhVx%7#A@-`q4 zFahqKsHSgFQFiACd8{X&K!|OeP8wH-0!m&F^^w@4Z8!OUMpe10K8QTALdACc3bzPXF?Dua(Z6 zb%VhI{_8AK*k)2)AMJve3j=Q8JUi)RfVyhY$@<=+C(c+4=X;NM@1jT<%^S76Zp8IE zOL`ohJH8131+3nO*kACR$Be^f(`A9F5nbmJtB~u}X&V(vUQy`pv8$2U7YHZr_5LTK z{Qx{G_fy^Sp+D}^Zf$JyJzK>p(O0L#Ae9w|Q6FCYHobh8G{!BQ;^2GP&*CDz8{4N# znAwBWD%TG3XU;Y8-z0MkQcEVMc$wpVmx%?-uzc>cAfaI(P-t?Tb(}oLli349y{TTm zI$Um8UR#T+^MV}E`9qApg>vxUE-aOmBGdOP(R-VF>gt%Q-w3OKMydY7=JCk5R|FmO)U6 z1d)S!kJ`$eb+Y+2h#Pr%GZ>;-Xe`;j6u#zwkKxuqhf!a>m+Y$VB5I_g!3kOiC-qK< z63C&1C6!>lE0P1<`Y4TsPdRiI&nxLFTBBvS{Iwze4Pal$U_0x7JZjnB653^+CJ$X_KvzBj`c2HxP&c2wZ=c0O^0aGc z+a&r5PScbWJ(Ss2kaTbWuc|XHjvLuq0tSXo))in*QO_w_U%`RN2!QovBb7D}E`|R8oPsW4Pel zbbtehK0lZk;RS_Sd|*bijg690#8*kxf1Aa3GQkMEh_ARje*4O&QbW zANyP3qo!HvI<_qI;Nn&84$~8yaXQ#zEziaNr_p?np5~(T+_I*j?}z7~!|7W#Q!6{? z;nX-r=0gg0tdI8W>H9=fVn&M+B#sLHecST?cPIflR?h-5dTALaXLCKaR&-w zlN;OZ4S@2$WKGWceZDkjT(WjW3SVV|Ick}9JwnGG^(-h;jj8n~aIC(sK2H@^jLvOp zRn@Fe|I|y@57H49jFiejJnzv5V?UW(sk>uTP77~N{)WwpF!jB2)v7}fcK5#{fPXpO{Q)M~KB&o=tFGMkQzMWpQ3-AH$r``HXOGt*i(561y zsQ^Vly1##_^ecrdWlf<7sdI{xrbeaPsJJVdVP1($!Z*O^{|{w)?Ih2fjhl^47T2{Z z`kzp0*#Df(2PS=uAkC4`!V61g)+A29t&`8M)WMc-9XKBM5~B2>|0kMxGz3-jX}C=P z(wj?(8oG?LW}ev=4QI77!$uZ8i>bjobal6^-m>48LF@Cnyxyr-q?Vd}-J)bbbA8_DgzOKeeFCeCYH>vD>KSDWgf7t59^3DV}zm4vu(g7>)8FwCd+wD))h zA$VQ`ileD=5!hI{WC04@#v|Q;cv#g;#WMe~pQz(OG5mHW>mJ3W(!U7cWH~eLaP38( zO~gcLgbFu2uE8QBIf!y(&9;HyM$ze<8gBp{fjIJaNtk6-z}VcwDxb+MyFA;B&r(gb zXYEmK23VlPB=_a-dEymm6+xR;s3cQbA90sPeK)!gyIIMNf`@?^BQ3DZSg-N==n#`c zn)wdse!&qh;N#t(NP;RK8)+nbfZJX35?2z(`5e!r-N}7i<5v9R3ljwa;1aYGXX6M* z4~Za-{BKCHo2W*lDpK12%L|06^KPh8&_&j`{*uGWQS@SC#J5>2FF4m zBLpKkAT;#Cd5s_~llS1`YHKZ|Nx=l@WUDIAlSZ=FNa5+-X96O~5W9B!BDT{$mpk%N zX2#}i6&T9|TE8&OD&RfuT>dMEVUNLJ2Ov>dzSmqS46_eb)^r&Gz~&wv^6oEDW--;& zM0(R-a4`30kC7l672(1WFivU0;O1U<`xo$=)7dYlDfl%eu&74|%mwKvSCK_#yPci| zg_|F|OWvUy2;G3m4O+Mjxk)34emyUzDk*W13o*YwE(n@;Y8M`h=w`ZZtakRX}V)G+ERQypNF!`uZdVdK^}L2iBLb<8vsLBP4#2D`6CYbLVxI^I?MF zmy&lVNWL|GpmFh4^eda0Vc4w826xQ(Pc$roNUXqF26-{dlI9!vaWCP>+_>PBsOgN$9H zgT&M`ft-QZv%R@X5nzclw{L9lPIKL0#069!1i{Kwq|P*8soJN@D&86 zzz^>doGX`ke+5^AvlIlzU_SWHAi)?QgCgu~?HSfMRM!NNz8&f5gs?_uNzhI8{v`A# z312*uV^i1tF2y#f%tj^a$N&Jt;6&65CIM)lh3(>wsYk;6BhV&2qpV~BY5rw*X3-=n z=+T>jq}q3i%U!h!=1S&v&fHJfzjDU(EW;e!i7dgVP}A}69RNjAdq)7-Bfw%c-H3gKh~Or4a*J-g+Y25WSdCP33yt zE+tcA|D4D28|%e-0Nt-x7ZObnGhj1pbV~3Vr6GiH69Z#a0x2tLus(>%KBvC#iXUJt z^Hj)JWXFc=*G-7lH*4;{_l;U%;cAj1mc~Bi$1))zL|~iF5ZV^v&G-*CzhABFp}HER zcHkN}q4JWv!h?N_)Cz@TKGVinx|fk-`9%U)OCgbC5?L%3^ID9kFarTzv&+Ma(JN~4 zAjCAo9_XWy%9j-WfvKqo8$SqUd6V7=`8w%EX2C>$;J-Xz5&4kgO zEDp9Es8`K}MLZuan@D+Z)M{}^vWvHSc?ah{7f12f*XES&jEBd@Efod z^hsjmOjmbVTI4Eqx5)ToKoKt-gku3n=jj3s=0?^B$;QEaInllq{FZlNhml)>3(u69+7KOj;xt45t2UxcqZ5nFsi9NETp&Yalb~lepG2X& zTtFJ?Ue<2hpu`0;hW{UF zYAkxPOmV}Sx$Ra!yQ z0J(Kg(lI8z?PeoXBxyRg68#q6As`|3w)@T+>@bgAbR8vPUv?=_Uy-KAj$Xa-|eCuHKE&`OO3~D-;VlFrUTtenWRry>E z%u__!%9Z);?Ehd*6qz{T>98H}@&Z`0N4-pa%H9r3yI%4E8kPRk2bm>gE^e{H&0@eW z4FAdF!_?)P2bc&_yjo=+%GUOBcjc+evQb;uIPA+togeP=-=QwbN+th`<_E>=y22sh znp%F@`b=`XUcPMv&tC^(D6dAz7H+(cpX(#?Gfc=@PY$GUiaV~lU^cv2%%$-c#oRll0bD; z6JzH+=c#!{&uSW}`}}J%-Qd|ImyVSn+cqu{rlVB6kP*Muu|- zXmWNw7DJ-vFi6x;rP5~{>AIq@Qj-SdMwh4sy>i6=zPKbOV596dZ=*c|EaM52 zY4CbT5WT1G5|1NUYCRg~Z}pXn8SkU#Mc#@w3sc(!G)VMW*(& zfsvq9g*h~GJH1X5%=|bdXKR$HA7O=#DUQy^?~6gfrGHhD`MGB}KV}|wG+nLtE z5iq4}f2lXSzfQAXzO+UM9RDOy&9t6QaXhv1C%67GvHNkYxLiU@Sv(8zT(U=ZgAFi1 zSLQq!jdr;ip*BKOi8$7F2c!?q=uFz9)?CS)18mV3+974@p5O;z{z3*@m)xI%FRAgH z;fZ1uRS!3AJGZX~H;Ct$$Zb43!VIDt?p9%n2-?#Xx||-qxR!3fysOGuFZH?{-uD(Y z#-#B2}~UUHo$pQRaOJA)% z)~Jbenu>eM<4f9zPYD{4J28v#aEyAf5g>>}c!bq~2G3su1zuP%4Evt9i_sEQ7P|x@ z`u#1FdZ3s?a~+QA#b8u<*@z!l|Mi2>Q(DFKR9h89V_f! z3yzfJj`$l?bM%JCL=@m^H*Bl3NZ$FdYu85bmgd&}oNO7HRKioZO!1Bpc&FJ5{O->q zuqg<)&#E4;pAT383D_ga4n;rD%x<)g^ccaPvP zx9c$NYY{9#uC}OdP?P4SyMkkqrQ=}Ni0jkb#!?XFT=F>%kt(e4mf4pctZsq&Uu9Ff zsGfUi`mM;6>pVHEVE)E$>v4SaP!KI9hFNOEgKO!*SjPh!GZe{BJ4);g=Z+sFJRHs~ zx5;!oNW}h2qwz1(VcJ`vQrDIUX5k{Uli%MTg__xv=CYe$@{_V;1Ox7c+sruPNK33hz{Sf1M=hfkb1FZz}qZwK0 zZvw!d0y9Dw*8}=a!B`rt5~2Xy`+haEY(31o4SCn{u%jFm354c_a(y3Wm5p8pKk=8F za+lJ!HsoBM%irACd1sqvq4)WOBy$oSg-B*!kVhDDq@ARr3x4y@39qbP7IOjIF&Alm zvw*cN5?zqxTZF`P!u<@~X~#^$@T3~(?Q(U7<{;{A_B)ZEb@3e~N!SKgL|aR)uGfj+ zqM;Y_Bu`k(mYEqTJdw?SCsKAnE#WCa<(p&^FGoP~mc z31qO^SsUUf81KSgkC*du6Be57u(*{z#F4C|w$(0;E`Fe;jM{#4%8R7L=E~8wk3!Cg*_^*Q6yHrsT}DX z5B5U+C!K`AX*veNfpKFvuWWM^IHBY}jhyABHoLXHR!{RfVx}h{J78+? zar+J)T-wrqu37oC-n^SV((8dcp=sv(A?6zX)I?>{fR81Yk=^O1s$@u~b!JU|nDb!& z<8U5Eu`p?gi>_@kFlfXgc07`L2PX|aDDha%Yvj)X##Fg%k$E~aT&yNrktT0FxY$3D zCRpQwY@$Dmy9O&LDgR<*LJ`a>ihHRl2U%wiJ>8w^gTmrp-_xJ3uK&JWL>SUo&;F(E z@1K2JNf+Dj(*$k!Nr1f=^NmVLJW$Y4T)#C&0v<3Wj}Bo_Nr%I=HMgvI-eR(UzKzIP z$dOu^JKO>1n_xQeQ?>-|qNmVieKPMm+z4X?(7$|l89?eOCb8?_3sZp=#qliTmEvLZ znJW>4+5iFrE%P%C$v&npBtJ*Of4x21N4lWubG7Bnvxl$lmK9cnLa?~(G+P3gZmpZD zKnjKA$DKT&A8_rxv+1Fa3G&VQ6tJ}C@?S16vq)+1E2?JUroqSRSR5qyEiS>3xfj^{ z+#b74cMDR-&yX&9mZpF=c{C5PZR_Ij`4{NI55A{&P_(Z3cV_Yb|BTn;(|=PhPwkWq zB-ys9K#&CJTXYbZ3IK2;GwAhk-Ns>1P-)Kl(U{=~_|tBC8VRa@S-OI$oXnN%Mcasx%eO&0|ih0;IxG+OfaZgOYBA*wuv)qfBjEhDL{>@yV5 ztMyvEFdbS|c`if9Q*O8mCdTjuzAYJ?IYD8_%`aBB4YLU+3=ak*h|98UyutTSUD8vsWTkyvJU53iza)6KJN4Vi@Eu0L5^AZUykG_#{$8#aD zb!t-VTnLfTNUdpp+Be^X1ZNYaQpbp6ryLsE=Xyk3)9*FfG7QGrDL;wWj~TIa`h5bs zzROv3_DSoB&PhYa?tnQ5iOC4?Yj}EtJf&|FXV~&`ytwzD_gG!I6ipvUkr8-;x&#zK z8D=4-30_TLH&%+&QWHG@t$LEx<}Vl_;+hV6Wj$da*6~x+p{IZ|eRpqW<AWo&0HUKVIUAKjubD9!h##E#86nJfsL++29q zUw>hWyR4W!-}#YMYq9e+QMY-MuYZZG&VEk_&b9Z539CRUDJ3an3vSKA?39H0n=LY= zx8~vfwG3y+%RYnt2K^!4en``S_{Q+Yepx3nCk4?;UaP1E=qy>gONn88xqgHvm0^7-{A($(j1A4d^@P?8({pH%!6A^1 zMPbWH``T$LZbP0<a8lobXFMYbLqkp+d!{Qdfu0q17Z;M?uls_t%KQRf@oaI)lPC?JjX!ncPnF*-H(x@ zwKF@|uKs@6J_rYnvcmoyqeVsRT7qYD0G*i8hT5ToxZZ`6U*EQ&Bl{#zw@qo_4@~^lD2B@Q|%f5?9WP;H5jI>OBy_gWRB;8M) z;p&n)``i)^0mxWq5Wg`^D2O)Qk&jB z&uyJ7J=EGMcgnD23e=#d-SbA4b}BX3D?Xg{Q|s}Y#s%YVYz5&q#+WZh%Gg*_bp@WU ziMB*fMQ->>TQB;2M4Tk9N1tB4m6*WNVUbPHgmPi;sQir4>wq5Tk=Yn@(ih5by)4_{RN$fCJiZ3?kZ_s@KR9|lFp$i&g$~lfc}N=&C#y!K`nc1qAN_b#ba@2JQLH7Ha+^i+FLBg2IcV6on*b^r zR9^%1K3G6+MERGzEXhr}AH08Yw6uYpY8Z}0+FMR5soWu@xJ}Kn4e&*)4b549R3W@@ zUNOaoDCz1xgjv}o%8XXqEHAPTK<8k5SiaHL$QDBSy~ihT2qMw|tZ0Lem(&We3G(M4 zrvS8BR^-%IozFT*&Q*0TCr8Aiz`EyNCuzyGt`jPAHLq``7V@*moacXK^7Hc}%2R%v zgY{?)tq1CW#kP5J;_qtPkwp%Nb0q6A1d{!nxC?|g4N`gsG^_O? ze9E$~7Kj)|b~F34jd=g-C-@Q0hy=v(r7jkwuLrX3DOcy(WSG}|@nDryvh+?^rQcd< zZze$deryMa$5F^2zMb@Be4Wv!t;A&5+j|)%8{HRSWLI(2!}(9*qFkTJ-@1fWB}Gtr zFg=eN1s)J|FJN)yC?~x3q?r{ons?`t-)sn}VrN#Cf9dN%r@(~NE2ELiR~;4BzF;qM zLuH-~7m2&x+D>0V9wUf2b}U^G`sGiGCtsxT@FN>EJ5$|o>>EA?D)|#FzZ5y5a2M16 zY-Jsa^<3K?-5Mw+?er0k-^1cQxW?*p}U1rQ@nEV4rit##s&_m%;ozq3%L?PU#k; zn6pXpCLospa7^$#e=F_61F4Zv8;#N4UZ`K05l57JkMesm>Qr?U1M$2S; zqvg=M-QKAVD`&IX3nT!pi?k1KSv5W59dgp+wk+Au?#@@j`Dg#m?9C-Vc_g+5gPyZK zmv`cqLG+GFKt55k2R<+?~3j6~gwG z2Wy(~4`YU)Tb^|l2;6%986b?_B*4{K6M0lzR^0{7GO_)4vygFd@;x(`fw7+~r^emE zw!TLaWl@crGq-;=b0TSNp=JprNuN3$)x@Vbm#XVoiAb; z#BnQ`{@<$=VU>Zv!_4WHjg3tf?E2Mt!t_N<=y19va?7$UMqjMsr2~!^cDe<<+}6S# zOKP@fD$1q)F#;o`55?;$lrZTZ&o)JPLZO@!ju;iVxF`k&t*C{K87A^9FhiJg?bH6s zMcM24FWQYxGuN7lZgATPpcaB0g$3wzF7(3vXR8eoG#0JZZje@1?i^iynur&D>K@C~ zn5q6Zj&`#!AY3WL7)CoE-rcEHx~{J$NJR~;p;kfoyhYY1=Km1YmNGdsMPh{ zb>Ayqf8mG?ddh7LqR~LPh<`EWphDQ~IGB_Q!~n0xMMwl#rgVosFshFHl%`7Cz%>T4hQ?{E$mbvx;EkDLT?SqepHiL*oR>7Zs7-kmlIPpZ^b3k&lgY+BhY^=v7k` zvf0OBxJDdB-41qTCgxZ7d>&~WJ3ye7y*iaDg>)DB6c*P|v%|_j8~fljoG?r^l&HkjoJ|D#hTLYVEbq4ur9IB?Zd_=#(1F4Hui2Q*fxq&*}5B{?AD7Q+hEWA}!@maKBCz(PAQM_t|3+@9Fqj4&sNJ#H4dyfToa5nhOqIKJH<4R?d%THTe4qt_ zk=~!YJl`QqA8srWDH^Mql|%Waz!G~{NfYK;?l3u)09K4(N6GFu@M|t_TvZl7t`887 zv_HQ$Vx`coEh_>Hh%+!Q2Dj(RMf8wKHb{6;6?Y{NBtC@;=ul`5D3)leu@FCJ6P%T| z`fIIO;v%~Oii0<@1`IZ!4a!5$i=8!oBOSVlmJ=X4C<1FMmd+-*c~jWCn#*YE z_=7%L3~6mVPra8Vf?u7yg|XLNJbMRi%CPz}wsRe|vP+Nz!>DjfX*l?1A4l{Vkh6nr zkE|(2kmK(87=>><2%M8>A1XLL@rR6YEcILK#SmbvAIAAU?8g;BvXzCr6*yA`-!NEv zD$NrwGv5(m9(vj(+VHHmj14C1rwS}?+f?M&Snbg%QLjJKB1PzqTFVDJh2Ol}6;icJ*VH2xzBx#%OHy`|Glz$Y3X`8+pA+KcvYIL+~y z$KETy79%EtuA2?YJ)GgUlhJ1rHfSJPNXC8Lhn3~TW0$EVArqNgWO*;r72}(+HXa`q zDS2*3UW}+iXn|^VMI3m5x~UdU(aoO6=m63MJVOpH=--l)s_6v>muq#{5M5-1E{zVt1(m9gfWiVQs>hFKN^tIX{%e(n%)NN9DU3YX^|T!dd}W*~V!`IGOz@tc^VcsC+;g(avx7X< zLyrE(k+zmeDk#Mr01Afww_j8X51J~<&=dH5uSAICriPepHpocoxBr2X;r+KGo07{r zI9Qj%^s=wn64z6uralM5=LKYRqQ^uEEil)ConogeAqjM6cmeYJW>vnUb}yv^4zzmk z>!NrCQSb*zkiz;>l9F8V&#<>N-f2GaVHe@jF70Q(IZ>TM1Wjd)vSwcgAo}n+KYmke zil6XLAeA)Cw}*xKwl}0T!-^ECLq{s9&tw_;ZaE;_J`#?{->zonZljIx5L?b!$DER@ zF3-E4mxveGg_`){gyL3HQ%phFZ58PUXQE1O7{T^ex#}p(Abj88`OX})E4Z#9(qLW= z#Ie$$`_cpyak?etO$=F8Z=KkkcKdp_CZQ67^sd)uty47QUF-kSL+RGjmgM}gw<SCLQVw;Wm*zg9`EWtLJWqh4zPg{%K)_|>7B}5lg*tL5 z+cC)&@CrieEpOjL1uALByAl7&I2m5hJ#!Qp0_JSOcfG5SJbrMfLF>8}7y6STpw==J zyUlU=PW*SMS^;Lob(y$YJ;Lkpzq_GuufYnEA>=>0?0W80&c3qOdpw$fej$k0NS=A5|oV#7!wXo zulOPeNgJdm_Arb!c3nQ+b_LF)DZ96MWUk-+O5kKn{yfUt_fX5mH}OD zl!r?~I8+2LXPl69?+X-)aGGS1a;yf0oP)&e5vMD8Rt>b9NZU~cZX@Tr|2QnKraeLQo>i+7M?nagkqu<>i;OGBkN5FjVs~ye z8HV61MI)grKaem{j8oLIgQe0vz9m5MhOgqC_MeM;s>b>OnIpppKMJbP9rjDH9GhCu z@H8l^LXpM*Eu``dHARHinPU(+Tu~$3SB%uQ-~AULqNJ-9GH%YAT$mOLIs=o%ajV8R zoc%x*K|#cu1=f7k&lQbY0S$@G``+Uqc}{A(tz3jFw*JLeWG}(y7)ZqmDN7Z8K8T$L z`r*=#()|ZyicIY1T;1vvZecCy&~X;{z+7C=4P~@_3oJL8VHBv`+Ez=#IrOPBlMFj> z&JBQr9tp4RC6F>=`xbGn(q2p6BM9?I98A6-8aGFb$Lt=s?XcDQVgDsq5`Y?OX*;qGY+b5yTGulj(KC zsQ;A9^h>%1P=%>6Bs3qWs2jO*c$^+cJvb4Te#}dMULGIH=LFxEqYg;L!#Zhgp~sd& z1l5<4)bv!qI6w;7)=eJ@&t`y33JMd24+tA&*A5sH(iOT>CY$4|xYwQ{{>L8hp7ZI? z@rJ+J+_VOLDrs`pO9_}l5cD${H2FtX3m~xiI^JA<14XCK-ZbSf`WOAvH^m>D&q;hi z6C$~q2LqBTE%amW5$Ubj3!-~_TeDwdl>a~-4rl&DzrXufGZ7t{g4@rufQR7g}fN$ z(uroL<5y4P@S^Hh3oe$PZQsHNP{}KIt7(#^wY+X4mY}*hz6=WrVAY))#Z%pB5P!VM z>#M6WH^$dJd`BgOfIL4SDHIaaw{!*&LfWlzhZe#%VxDoz1~m-_iwC6b7j4s`r(W`n zWGS=?VxIM-v>oZ;3|(K~Vx#h7QfCH97aXHRk%G5M%V#yrCC+%;+YM!pQEPmQK~HQznR2e%sd3bmRboKd)oJ!m~$&zv&n+W(i?eBkdv_rH*eLSO^5wSZ6P zj*5nZKEXY2nIk@kB?^Y%m)>LZF9>?0${aUm^*|(@yTFT)s z#7k3p)4Cs#%%XYCu7h7m$S3@@f^rMH2A*X??5syZAGq$lnwr#V8w)d;6`bN&EJe^U zKf9MZi2@gT^iB=qu+NQ|xht)MJi>*X= z*B$X(Q_?ogp13xppI%X@NLS!f0$!v3sJmeu^Eqwx`6J`uG>%e(cO<_dj32I%PQzHk za7VbvjSYK=eGU*cbL<-xm=nDOW{CQ5;FGlM0}Izh1?Y0pftpeuOKTJ-qHY@mtB0Gn zz{Q}&ejRIr*4lYAC$+D{gAE}?2!7HkNQ?=KEDkG??re!({hAxsP7;=4WBYraVg3Xm z;J$4c44E?S$@!Z!lY}9KagJH@4gkHhsF?S0V&VJq;@PCZGX2bQsS{fF-1I(R(ej6- z;NQMWA+THw?~<|;aAN*Km#1f(Q5Y=i2i-}DZav|bijsqftZ*E-cw`}iM)H9Z`4(ED zAWekUyBQ_Fr`RvAwkVv>iDR<7^J?gz(>7E@(d%_TA2v7IH&Pb)Rd;foev-3}`$a4k zUFf{DD04EA!X~C8b(rQfM@E6(WE${*PXgG|{JvL>Yi+$bnn*wb)I4N+k+~B6(JO=s zM=O=&WR80=H=54N1?e|l*AVr%1TQ+bf40&KC>lEzoKLp#z3zlY$-(prA23idD8bN~ z6{0W=|5M1Q07&pV1r^&u9QCelSak$3-%}l8IQqS3s~tX)VX9Vjm-L9eNQTd}{gP1S zv^^v2#u>H(`#t{)7WekRshkp5C7vYEgPVae;~kXwS{Ga@1F+NN_l| z1~(gqIV9XD!@iF_Eu~Fk5E2rf^|Qe zy!F9zQ#o1izN}!>whUio)}6X%3wIxggutBQD||i?HeQi+LarhME(6kS)@|T4*~EdK zMT)wE_P{6yLng_X5!~#&ji|?R-J_h{d@>naq0P7f>2DyJUkrxkxD27or9ksbrK7mg z`|-?}ELwY~5a~cNR!3yNhn)&{)a?_W>O6 z`aYu=#v|hA3-0$cdup(v(P5^9z8W7;6toT2>54RcG!Msbxhbgs3O6Q5RjN}0(maMS0z(oM1 z5Ag0~S^RA?5Ohn~T#f^Ls94D8IP?*=hotAkiHCHr4$>^#5lZMr%?O(I z-IWu69pqBl;Egfx?-{|_T6CZ)lM}zpsvTy;J!V&7aF!v_;goZFx&ftOYo`hz>*m^AF0? ztq;cs>G2d6i0@~>!hVxjL1IDG|M}n2v7e+&D>MZ}t|#puTfV;ncbw{T3e0+`X;9XS zr^oiTUnt|+bFk2ZN;kUvkZ^^^w53WL*z1m|&5;~r@a^Yl4>p2t1izXp9hnIb6?*AA zJjqwX>*1S$vO90YqGNp$>6hhl{L3l*8)&QyEE6Jd;s;?J7MI;u#?jGYcuqB_kV-fj z)mA_mb|?KlJF)edDI`{b(07&@z@K=9LqLNhFn-iptlLk)VAftq^P5a2m*GI2m7YrI z{uvx8^)XZK6MQ+tDiFzF^t&7*bK#b?5Xt^h55nbW49CysSK_s_p@4Q_gBgQ(h?R!& zSk;^{x5BEwNG+U5)Xm_EYZmQ{pNk6xLtE>7GDh;SwT7M}I7sari_>m4T#X#9?Kf%z z5kKEnnX1vQsF%7gqC%pD!ZB7bq!s?_eV-x9ob?XI)~n@8q3U)jZj8UswMQh<=;9&W zOdxLzPtvG0OYPxo)N1=yXQ+`v!c&}LIvjK@$!?D-m=XwLGt9#tWP5DEG(*Qih_BH) zObO(TJ*b{|FuWx?8)jv#W(g8$JjmBrAZP)M*;n#pqXw+WiN#Ftghhc?@mhmCCJ7=@ zQQFci0avS53F5HsA2xoU-Lp{JIrEx9u;e}ImY5_b_nk{ zzMA}Ysg4S|X*gYBQJ!v1FwLNb4);UeVp}g8^Ay}onW6gDWN=*jq~L66z0Z6aH@>YZy1YHvsr8vkR+yx_wvxFhRJH_WA1pkunqS`(K-sl*DVKh(aVdbBFtob z|2)!w6EeDQb{ccS;E#qx=m}Y*h4T7J`4e#bHp^VB*SnKPM8c&q-L(qB8Iae#;I$o% z10MhJ1cOm@RGE0GO}s@CZ6I4y>ZM3DUvK$9s7HF*=?3UAcUo=W()yx>prt&IzQK5$F_okl)U~%J?ot zT7u795kG)L39s{SqGm%wC5Bf1FQ!dEO$YYLvgW5`6@Rp@6_&0dG^kS#><6#lOU8qs z5+l-X8`BKHuo?RQ)bg(+6&;I_zXXv$gbsLv^i)KnGU$+RvwrV1)EIkjh?SjJB(h4R zq#blV#yJ$Y@f$s6;w(Y19FH}O6)PG3ZoPJ7OA~lqUpH96sh$BrSH?dZB%3SU@LFQP z)@Zg%8O4)aA)t6==1%HX&89y^hgy?2Stf!0&=o_V-`0~l>9!M2$-Fi7*U);jqetX_ zGzh^)*yz58jwZy5J%Wd&!Gf|~sEWYdLQh$T9#OLE$mBDk1e%v=) z2rL@MVPQZM>hE818M{`E1LT&0Y36-q8uGoBr-RqOVtCjC9Af42` zq#6JDtPoZqATTZvGdr_%AQ#@aP35V^nn2aJuntZW^d&^|!Exq1x4kz}(^@Xkm-H1E zRy8!7zgCN!WTv;dANbu43P~(iNdi^p&HC&$bSCozlN&Adq>tzVDvq->n^LfIcbHkT zg*syA_CJB;f?%`%@7{V5mi&@JG*SCAF1~4b%OseWDr){-^**W@fs)of$Zfl$U@wE; zl_rpVCDT2S97Q^jfk%MDKd`=Tkz^|#3~yocbw!+9X3oa^kV}3x?W2L2_UE|y=PetD z1{AAXx6@cu;*@HJ3&9Or*g69c@~ygqvjzENtlMnzi{{pE@@5w|qtKc%-`*fYwe z-P}6yI%6L3hSfvVM9Q+J$Bq>m#%UCeuA;htDm1|>y_=}Ks9m8W;HzJJ?{n=J&u$`! zTW!-v!cpJ>#cRKe3mFvK5og`TnQUny_SjfnJyFfV6VgaP9E|vk2dzx+-5kH3w$8y{ zHrt9N>bULjbqc~CGjZhYwV#G3>e+)PWyJp{11vk?{OT zSVC~WMM@f7jbm6&a5}CI(&?Q%qx@>XJEhCK61%2{{?MVOj`HRQrP&d9idBuH&*{dB z;#NsAFyJPTaP5$^1V2`K<0z_OHUeirpuuL*(R{v!oImMkGFvL$fFY=aOf%I83Rmkn zNoQ|Yu1GEWV}KkJgataIhER`=RQDo-TP4F>wpK$@DzZw~N0Kw}J1(OlaBsNNe^vnJ zxbg?9xT{j*QI(obqBFg2Svx3OL@&iS#4&pD4AWCITKSXc+V%Sr6U@CuE!p8S613Fj zA8d$))1mCfw@%e`j0`=I@{c9oStxQ09U*>XvS~mJ9e`J@2I^}rvc9O1w~)>Fr_$Mm z3*m?)wOLI6564KpKNxWMTRCFOi|4TH%Em4#hG>HBh;9R|+7+4$z;#X`k5Boc1XFks zcX4}5i5U_RNp?x}>j66R#)aGZY%+He97*tZcdz!1>~(lM(Eb=96}F_Hmy4e5+fya$ zAs7ry=&(zAk%w~0&24hSE$;0S{d4S8Y6qh7bPjIW|9328bf0pHkpO(ViGA_4CKXwk z1;YBZDVM4|3S_b5GZ3pl!-khh13gHLcW0+{!y1@RmAjssV?Js=qLYu zo4wDuPy+}((}=4!>({%AkU{X+TrMeS^_M{1jMHQ30Fw`-)`D&+>3XHAbKVkkfE;kU zH;=4{TW9`|>PM@tJu$hRq`cn0oy>GEHQQ#xGAxy-S``LNYzWJkvd94&wqp6o#x5wO zhAVSOALTF-0Bb`Swgb2YR2G@UMF^pE4ZSpB8`2pR)q6ajT<%Y`&wd=ljqbg?$!Cfl zdzv|7qg3o#`^%#*sXkoFtaiFoZ$Am`gokhobh!o`_One~c%d~#T-uCwsNG?m zA5vWwchG7teSFk86$rnevU!pjY|r>H=(@|Yp!|hA*0FOodgkSE9R?|0p}27RXt-dH zAMx=5JIAQsJ~f8!;l~$In{BYGWGh%ZC65UUi4q$FpZU{)PClP<-1d|Ml;#yPk+K)` zVEzd6b(mKa5R}y9U+9nnNN`TrrSA_-cfPc03>QGo)n`!j88uuttXXpUDOcQP4pa8V;Z}N7a4#U37n-yG847&&cqv019bPMY zYB0?;IPyJ@mUgFt|7AI;#n71%I#i6E1XHfRvwshc9?j9<*S}D5bMPl0tOL+iI6U0U zhv|X-TSBS!O?)(=SPN=*2j!pca@_EL6uv-lmzyxQtSH06)-BSsM)06rgZ-4vdRpp* z5dU>krBhe%@YBW}G@QW+nIuwxd&itGO`st=5H@=!z8_+q2P&PTXkOR;aL$!x(n zCxqF%LiR8krzl@V#&#H{zIAVc#s)2#g&36O6fw3-x{}-h8Rc$4yC5y`^O!o)I$1WL zU&9AQ4$%g~`T&lHsjtdCO^+D|2FmG1b%B6BOLkD1sriZcR+=Wth8Zg_h3Iz(P`8O7 z|27-3X_7D>gC=WTM{@bJdb`O6m<~(dQ8+B%Y#S>IwGT|yvwCLON)kPVxLdC*A%R*PYeun5+rw!7*%bsHm($S4Q;ak$=5NmRXQau zXFm16&$(QD29jGE+e3(bNCm*(LJ-3yJQ@%DuXpoZ+(<*@ph&Ur3fnXYSBH`Gzae%O z0RWL9_ph>#2b=CTdy{%icX-+A*s>9=#6eWEC^W(?TO zAGXv@RTL6yh-L@0Gb$3Ln^O`BoIZiA{t?H6(?cT8vRwJr1NMes;vst|T8M|D_|1Q( z-o5Ecpg%{&>7tC%?okClJ2S9N*?txexd7J6vja|ORz@(8-iJibH~_dC>!_H6j(P#b~4(|Jl0~HQa+_K5Lq3DyQZpeNkh+Fdaj^keQNjIjcixbdZK{5rgM@jRmA$m$-YdUMn3}Q_k5oLY(2ed zd^J_GeTB`aj^ed7lm(!X^^oC2#r~*} zm^YjKBsW8SK#v!g6L?R^f+9T0Sc3CmvQtM@m`e)hUHYo>cUJF0vTrJs0upVP+hyH?}O6yxbI@ z`}4oHy(z%jjkRNnO4eg^u>e+z3GW`+J!=`z@P zNV?*LKj#3_nQ5?Pt9ZtBgAt6u9c#b1MDM0F&8z2@V~g{Ep`dxk9AUwxQAc=VkR1zdzWt{-#`PpyVHgVUMJr`bYjTxF z(Vl86%o$DuHlg*Q4rL#alh_gMnWDmiAETj6cd@upU1mhnPc@l4fTXWr#pOJvyHT?%!)19Nu(^j3RPfeG0bZDN$olKW|jp}iYX%!0AMuA!efoY_g%{gkUg{egv$_(?C z^{?`o$$IO%rVvH3!z3gGcd;VBVHUwtc-+~x1vO&%YXWT@UI|DlUMd7b^qEcahX{n4 zD^8(#Den8-0QZv<{n4m0maduRU@2V?qn$xsXfw68U4Wg+G5m7tb5-!?G&+eu&pV(_ zXpnib1tM{$Y%}%q=pu8ZWFXw{S1ztweik;*96pbC7SuOOyYZJces#r7$c?eWQr}cd zr=e3>uf#pTE825J!(7dR2JFWdM>X0>XN|@G=Z=9|(;|&BNO4hn5_E+@zgzC*4E9I}VCOhO)o~=8vaL0FpjK+dhYGpbo za2DIcBOy6*({)qmlr3z*r85=|cBgg82AdISG$jOzqSKtR7n@@>N!9A)04qQB0Y~ez z$@|@cEyyCW(Tw4}S~-)G_PUh**o4VQ65YiBK|sF0H&~kqm^+$#ZV_FRwV7zOhVV~{ zT4N80&M@4I9wCQB4~E3pI_4MDiHo=pewJM8ZLEF3>#HY0(oLqCQ;Y+o!xSEl<=n3x zG*oc!F289emLw2+1Vw5kVOFdC>>;ek*ctYP>g`@CJI zy|lcQm*m}1b);^_7=-~A93QiZJTFInY7C3g2KTS+O$E!TUu~V(|`ctd~b2s z9dmttqOv+vDx)b&MBXqi!T=_NruMBs;)hUUrrKg{F!F(XkoOf@bR!8kCEH~%yAmR0 zi=1NQ8yWmh=ooHVkI{(-2nDA2s$lr9DbUIK8!og==Ev*gW_<{({3 zXu?dmfQ_vLc*Fd;Slu2Gy0ta#KXcWhtFo)ER%^fNOEUha2KM$tzd?^k1Ma z0Ek46{1n*rMdT~-l1~XyejLNpOfGcrN!XZ}C)ac~d&l~kFW2Wd{4VbI~h`N4as zLOJG16IJl^hDKHhk_BUUhwH-1|65}6k73-hbAD>VI2th@fw`c*ui1w;jL|avEU6pD zw-2>pefX|sb7jypE$9UsW{H8T;oEtJK7?1wKZvLoy64jZ7k!V#M^2|+%Om%`b9`r> z-m;95Q3*WJLurH`d;ZF#TUk>=YeaMR2z_1nILzU%o9M$TwEfM zX6GA0TP~OQctUv47>AwYTJ8^2Q6vMC8u|$g5+t~G9A~vdU89nZiy8*^$oR!n2PKsx z-ESBql=D7&If+Ww{L&i2z&NRsdFecpm-iJ*`*6r?|70?$V4dHv0pnf;u2S56zba^0#$=C@#L}T8i z{sNKXL>(sAO+sG==Pnr>XVX~eQL19e&R}nY-&|-;sVSlersP=vZ>)EbL`rzj8mi@-dG$K78 zzCXbJ-O`9ND7ar8WeyV@*F#&>*jgWG-XX$scLQ7O~>69^pV9S-LYH`?8lIR zV`)q>5^STu<9lQaih1Mdp6?la{9`|ZDO8SAuO0TXkGhBsJz0JSD*X;w2cx}~96{ai z;yD^p#iX8Y5Y=*y*X2Mcgp~tXu_U^NHs8Nlu`-f{)B_|Hxq~Ro&pHDHCvK!2M(m2D z6ZRyS>KLbqo@*Q~a{lm}L}9`;V-pNt=+Nn-DXfgL`7?!R}HpnpXFY++RPafF7ldOgHH0cWjEMA~Z% zIcLiRdTSB7Z~}9{9ulSiy3r^;3fejUdGCS-f)oe8b3aV@*lAW>`WF2eXZ1CP_pRH1 z4KI|I@*2HH92R4Hy?AfEgSae=$__CqL#_>+Ko`xjp(sj@QBC#^{?I_~Y3TXpa3Z<> z+rLvY#f`li?-YV;8ys{(@qrcK3f>ng%J6SyHhXJg0Ae$t9X^orsUCEbNoy8Hz&J-C6b~yX8KMFw?*h0U^%~(O z4dlHc$AjNmh3ARU6dgailz3nsJi88pjz+Sp_socrQQh!Lot6qwDwd19`TqkOgg1V?1yCgaP%sk%>?8*`rYMlDw2Cca zl3_6#MtqSCH4Lej!)Nzm3x8Oza~vk8X_y2ep0y|a97zmXcBfjn&XSnoD=0%3Unt^f zgtZrHlRLYJQjD8gtaZkd{1N)9@&sYzZRFiG0E_}g3!YM?&?lPrQjzU;3uZ(_ZbsBYFs&Ro0DmIwK7x%1+Y1hqe&nduSOiy%dx5RbMi$qNCQ}It_=mICSaz zs7|XOJYZc(DDAr9K;(^oL7jUAc10o0daU)$e>2VBh*s0ntGYOmmZxx=jZ7!2+5ulJ8sQB@l-KkuVbI58JYH%^w_ljz!n8O zaAy2k0y;7sck`{EN}yPZ7);Z}RrQL*62$4|wT^o7S-q~9`n}M>@WJENFaPEY?1VVmM4qVO24YlMpw-zF z>Q0b543gQUpquN@BH7`PQKeY*zA9SMZoxUgy-S*7-{<(7*cLc_{#MjLwij@ zp|&vHw_;x){L1fM6E=SxE(o?Yzw`h!h0MYpdD<>8a(Pd9AssF;JoZT(1CTEYH=POX z2p~ePH5LKkGCmzO@~pTK<&Km;oc^iq`*23H4XLPCK#*Ee+bf)){=AewnY*Au*mwwe zh2l4+P-~`ZW40{dJZ&s0DFJglnvIzk8uiGry@uKW^$6t|opO?3xkO#Wdh3f4hs-pc zN#5aDJ9NO;x>V$xXORME*8a2UV?X{fh@D>B$O#vClqpiE5RPA9dWq>F1&Wrs;OP2R z)lAAg;68$ZXfZFkK`BMzO_r`h?w`lPk*VB}W;z^<)8bjKvSs_i8%Hk)N#{GeA}2`Y zl*3#f62DJ@N2W%L&sg}1l>-afjQ!|dLX(J6e$)o zRVVwlfd-g=%Tti$g-R*?u*!$OI)C8*=Zm7pGbV^y9y#xu-i@0cjaHnVcSP$4Kh%2P zae&sq_Hy}@Jqj9fFtEQZ1#?i_?DJIi_3jez@m&%|s(&eEK%1!CIpD;|;ulgltyqMn z1^dJgV<5s4b=nX`Bq^D>1zS09Y;^(7;TCYuF%I{lY5uQ0Ou*rM08O8L8>AXyIdB%b z!(WbH9qA066wkoO*)fDeof(5ME|47xmPA!5;7fR)*uM9K*8F-&duQ;X7qg*O`Lz>E zmkSjFr{vbitz=lsKr}p@pgElGK@27H7sQWVQu2 z2)bq-UqEcb&gugTuP64qU3gk~DF)WTi2I*fs))?BW1I*Ngd6GzV4$x1RHu)1t=FD` zqG@$|@`2oZtj8NxwEODt!%_ogZrYc2hXu9c)OHkn-j;o9$kK;TGU%b-Gc(3Q7XX&) zLQd3Y-rf~gG&E!NSh+er(#LelO3WSbN#{+_wdNV+;*C6cnZmhZV{@ITq5!N=U{_dM zXIjqi1Fbs`n(E;paor*jN2xO0+_m?G6SqSfzA+OfHQ2}$J23^1=%%*#22Ds>D^U8! z^|$;~(fl}wV)C0UGRiVVBWxXdEU`z$dBtl8#T4rNw)eN;bz~=)$BEU60?MjxZ~R^^ImLBAqzLEA-fwaQgd+beq>gjhqiifIs5Wp6-K#y3+zH1{OV+WVRb3{`L3XArd?6W_kkTYLxABh z<~Oz;#nTV_@`MewLUQ4I%S@@m(iR=68YsP(FpRt0Jo_BaQjXmODt?xf)d%5J(aBqJ zq!<$8g1?!rb@{Yv3p3$KF+KYue)`eD2JhGt{p`AZ&)o2xhGO~DXg$s3rzZw7!7z{l zRAezU1)>*;ZzNynwMf!RFRW-I@p}_NTWO{VKpbSY3L?ga`ihovjC!f!(zJ=Ds7c+W z(5`0s1X_=_acZsO2YA>rxM|}pb%l#NrM9z7l*-F-@2=&rJ^^jB+qYo9VX4GH*-v1+ zTJXk2la^Q?)D?REx%KTSWc@ohgidadV=ZD{JMk^)_AGq!&a9dIfE zAy9Wy$t(^dN?eKm0F0&xCJ6--Ud0^ddAB>@I2a(Mz}Ssw}ajMc@X-%c+d0mlsgUqgIp z8B{V3S?vuR=ea+0*M)ZyK%=SuEg0GL!gt?0E|RXzIW*B?71y#YU<6j3V(100#zN!R zu1!CieIHl7u>bckfWA4n^)`|`FoKKT-EkL)|3XZi4=Mqj%!zrG9L-rhNY7(?;Pusw zp4?H*cTx)*BjVQeH0sdZgavXhdX4n?2dbgsxf^hl-e*(-j#^B5ULomFKtx= z8{H%UTbc0ZZZy&qik-f{+P|yd@-VC))iFMR@yr9a1;Hep*YDh=@S1CAR&GyE;+*qo zUoGSDKegv|3M9!Rcv!^iowHNt*r=n`wW>%Cb@5I#x9_oM9%qfPsS0sxMOS=5{mD{s z8wYl!x-I=JI3vL!c4wLtxJDfDH!_|3&{WV0edlKMOJO?on?L%phO@;Urqau2RRd87 zFOHG9$O$~3Z1~fkZcE=jJ-Nchv=OQ1-0M4@)ckHhkJetnVbwo{% z_4FNHEXLtJ7o23&?`?G-h}?wg_`ZJQafg#~ZO!QAA{%#%m zA|X9(N#;W}zyiMaR0O>WJ9kg9D;qmo?o-^tHzJ_2F?_f&=qyXS3#XMK1tdS5Rs7Yu z%JKPrILC@{z|vj<;)g8PRef{^M`Ni>COV*E7L&=FPVK95{i|3}quMGnq?IT= zRq_q;EP!caruY3Ws%X9xr%&Dnd~PgZnh6d`L{iv1I1~SplxnZ(%V1REG+%J4pKDP+ zXHA-WB{H7`VsZJ@A6a?>^2Pg!{mwoIyh*4Ks1gvqF``j}4AWiI6;h^G!;RNJC}Q(7d>g~dUHz#HXB&u9-DPrH@|pVA zgz+3`s@7AyvUPERS*eg!Fyk?6IdYcl6`vlehUOqj_$$O54yib{O*yUuEr#ZmGf6~j zW0civMwI6Rfxv>z2Zc=X-$%F}{Gc~Ile~+wMCdxa-vdi3@YS`Nn<08!RQE7tDzH7@ z#A?_`DYpNNb3KRjbB%g8g(5#wF^OJM4RMmJINZemZKS$j`N2*=32ZOJn*S_Idvo$( zC0I&i_IpRax@6G4kWNdnBS8k!70qRVK~ADp84@&i1@LwM%MgFnx(a>?s#)~+eYJ~? z{1D-Yemja*zzJ``07tiMDmVKv(zr9(zII_1b#KN<|5w}XI^tha9HwD|2ZJ@;egWqA+}*AId&_2|Y#a%sb%D!l(#@VL{tVaq z{NWjSz>Vfr@?RuOUYDhP>Fhhw-Cab|JH((aAPn+JJ%TuJKDCFS|1E=A@iviVkkN{- zGCiWOvF9w2sIy(Qopg?KX{!`C)iEoCQ~Tm(KJ4s#LWW$z=?m)Yu?TYAeIh`YP!2Pq zSn@tIfTN(E|KSD=dKlT9LUrQiSd4Xc1gGz#go$%yG$Iv`a*mY#WLaNO`=M)I+Z7dm zZTMaOpw`0jDhw7kJC>lKU@YsQOuBMBZyV1?dnB?xa&_Z_?v2=(VwyH+^Kl31u3%u& zY(u8SchwX@OEzYZ+CI~(E&|C-ffE8rK4R=wk0O5ez`p`|U~MD3PU=Li+~&dj{ti8L zNsQKzoHeOg+Gz|!QPj@Fte9O-fN-wTHMp@ed*tj{3y1HrXk3_9YfemC+qOK{hM@at z=k({{MpiOvUH(Kb4&Kif=4xiJ2j5U)8)@QAsZ55701E^r<5Y^3)Eq0X@1+G9tQ9#D z%Ln&m0EC42CdJltYDTh+gd{(RI?TV#!dN?lbOi&yNglXr^r08T+T#LR0`^k9-B|Fb z3CyczVbB#GG|zp|cROF*X z(JP&LK8vS42Smfs#ceq2dJrApY@bZnFi#4(7nxP|ph&@ubNC#Y`qz!!-%J$Fjazo` zSH{BKE;%l=Ehkg(`MI%M#c(;aJsWnI;ax`=+@iU>2fU{L-t$-A2?a?b89F?JWZ@GT z-QGeCTXs!myj}<_G7`%en>UtyT$o9jiOEvx2opk$d3-OU<`=MFV^LgPExlnDJR*^%fVtU z&niVJAATXvj0U=NYn3~;K>D`nc%L9Dhl3JjPmrEM*kXv9YWJUyTMGJY*7hPWtF!2- zsV$dEMNQ#DnEy@?c5I2y94ImBK7_fc;{~!Y#i$$?C_+A*qa-;^9GtSLZ(% zF>SaPmL3WDo7;~c0N4m3<65}BtrRJbE})uY(l5^ znSAw$zUPsNfTIPAUDQAt?B2Jz=AV4%U=kW|F^}@_G6MmlCaB4m2&4wbHMLq;bK+cr z3=qdh|EHpIGLDY~u|iyhp~!nr9U5y7;^dU| zdOs<2_ZpaEwE)#gI0w$)aNAZ581D@x^8QH!(5!6!BB3yEdunv}O?* zcBO}`OQ@3i{?GTLjGDsGz0EB^-o*H7bfoaiZF>YYHnwc!&np6Ha*URsvEFgYKHOfg zE>Jpa0tHplNpJetjM)m_lL-qE1adVKgs;b|$3OROG#}I^pK`KmPWi5?g}!{l-Zc-; zg7s!BkePQ+Vb=}REfTWUl6A9r(hZ>g^iVQSKs862N}>FEM{adG;AKYKc5}ZO}@A?UxF&0>kT)J&g`K5dv}rApoA_MdMmeYIMXI zCm<1Ls_{>isL!z2`{$@$!Ut-ASU&!)KkH%{*}s(+9{{R=5fUCZ8{$XruVx#e4HPxW zm8*6x@nWH+@wFjf`-oZ;!!)vyFhGgy^jJFpq>banvZH{k^2%;StW|W+U9_}V{pU2r zXKH;(3yh$pwFnYgN+9D)vws(^XQQgZ?VT+#xMp2Ej-D4EJ0@E-@XvjNAEIe}YnjX^Mo+pe!%x_&Z{b#UZeR*8ZoLgewKLfdlmQ z{ewMa5u_KpeFk1=PyJHtVpmJxrr12|CIoH-uk&SXEKxo{Z=!pq@S-}ZlKlsz8ii(F zRy`(DIHGH`wsZ_nd zgFg%EzmEYb2X2KY5U;j_8UvNN$ z1T_Spfe>yUlm*yND?Wktp*8sO>x||i0IxI;T~8?kp5QaG!494HDh{&iDy5Gw8A}NC z6mpJa-EZdLi>cKYexuMaSo!BYO{Q-~hgb)A#9SB-C+E)m@d!j9DJEkH^LjtaPD-`Q z^)YDlocAapwiG(WhQDn2CkS-oU^+Naw8pGPIvys51Q#7&QX#r{pK|q-oEhe<;`g0b zRRt;0uKR#e@_W8|b@_T%{ug6h>jeyEt;QQMHSX%?|(tn0#wCny| z3>-gR0F5HCnodEneFL@mkpq)u$raAfbzjX)t&IP)LMzK z#Y3RuC^oZI+Lhm~8^OmM(cP#f|DDrQjJ{Oi*SMw~wc=BA^1aQ&i%y;quiR|+&_$$I z@Ln%9WiPd@LD7h@8$fhhk5jly^E+X};OJ6Ki9VG^{1_O}#xK)v<~=!mrJN`A8(V%t z+_`y3mKjE`?VO3i<-Yc&SBmK8AV&JH-0T#=kYmTuW>7^=%d-n5&99?w%hgmd$lRVo!FXf|-Qc{JicZK|L^evpdvbK&??v8fmT zoUR2i>qL7zI9`jBGVFs4Gmnz#hP_D}sM;LkZWjXww3}3HrObs(2(`q_zxscga9=Yv zu7xBq7wzxx)bWSbp=iSnpuon1;?RWZ9VL&LEhKHyIGbr{{n%~!4JUp{(yuxU^20cI zgHa36BZHG9F*mCzqvpgo8RvlB@Va7AilvI6Atm|E2PEoA* zWN(R=vO3;Vetcm{x?c~*XI2F~B2kD$Yn<;ix!+ToMu`L-t)nDXFMMOOOPz=d>WT=^ z?pZis>3z}ZWL4Z(1)!1Ys&?#GwWWty+(fe5$N6`j zctA47E^9HS7f+Onh@h7D3NT)BnPJ*D$|KLwsp;x?9JkLHDf~V4?s$VcITM!%i~5v_ zC%W76!ldBI7j%wi$|7+LkdovF%BwC~;X@yH~4Ti`^E^ z9b>bP4B?>mS$I6lE3Nj;uR%TzF8pC9 zit}S+A(TdU=*4+P8Xug?+|yOB}sfDlY|$Y zSMtlwajc+71dIGTim6tB-(@BiQ;!1l6ed0t$@Hv6KQ4}GEnfn|!l&R<+ zUt%~`1(Fiiow>ENO7k(m=(J@@-bx)xKPeEGTJq>R9OM$zP#O6V-9`4cGvA6eA=1Qk z2enp<`rsA=wcCA^m1~Q@N@^c2#_Ya9NW@940QZz01L8W2_m~!a?y?Ek>q`Nbu~l}n zIAnGR$1mm+l^+zEy7VNm6YYi22j7LIZD#zH|8%IDcoj=9qw()tYsQcUTF9{on`QHX zs0(C}!Sg4uaR9N?EX`mQHl)3<&l38@2*wn;gjHdMn(llzd&v;z><&icG?g*V|NLIl z-92ZqCWL2Fzf;ON?I?2L`lE;JbYUcMT!n?jxs}9X7adlR9yy%%aA-hR7ZN0O90gG3 zDwk^hA`igkH1@{o8^3lB%64%u3}+)jrA}r}k2$nn zAy!1)!B(8IX2?)Q!3Q@b54*iGC}QPfqcAqi(t!%)j7<`)*~F zSXug>+pjKJJtfw}54b(7X?S2xNM;%V4d+7Q=VAx8=@e-Rkgn@(6GlP_;X)O3mH?b_v))2rwoT!Irs&Yo; z1m2V0e6HRRN)4WU8h4*=?HjWE9S27ZrDjPP^L<3wXsR9GaumOb8MzXxh2ek@X(>&b zsEzI7#R%^{2_u>#C5e}N!ONp)6U@1Vr`qWATS4a2gC73MLp-tD&FW)$Blynn1lKmg zAG}u5)Sqn1H>lZRdXPqVVDl-3rF@EW-@w@)qCtH*(HL2ga!o$>U$aR{By z?X*~Z_C3*D8rQnx*IiArw-eD!PaRN4WtGSKkw;HsG9Z zl022QrCI83VDLH`O_;j-4DF!X!K&fO7l?PFPI47nz_9aMYMk&(p31wapEgx8Yy9Ly z*kWw=grOJ*er-XiAu98gd!dK-4hg`rlU)y9fg|{w|8l=L<#;c};x1npuz&w2tPZ2N zSf?ZeupJ@y4yI%XKW3sY8dn6`(>s}4-!q63{N#KM6G5W%Vx5NrnAJX>G#|-`BY|6i zqlUW1qP1s5;2g#;iUZkqDsrU!6HhxaIkKaQi(0KrB3L(Se4S9X@+?{UStj&@v zcft!`t5g{@x0+R58QLWaHnE z6cbhT{JlWI!5bYj~V5+Czj2<-{lhcDqi-NMI=zR%8>z>svF#Kq;?cjQ%2SZ6oFNly}*cO(%btyN-&mVd76{VIMf44dSBN`!jsZpsj z?^k-V!Ft}@X^T`B<^eTAE8V(uMWBm~;_XI^%5nN1%7BZTdkW9E&bknjvHu>aYxk&X zTf~|}j%FG78>Z&x56QNl_BU zr6?=O#rwk0Y-pQ?zdXxSsVj4Rh9M^H{Ou$bbG}dGE?QG#X(iW zN!GrP5vX#Q%Kl2Cl=>13VFc@FS#oPB>MiX^fBj^-#)G$@BPrDkB%ymozuk{CV;WsD zY5N`0IFq!nvV&vJIwIA8Zg!)!u)9+j6qYu6mH^_ zFt-leB#`s^U*h*vjTwXG`J%O;>06Hv2FRS`Esh!-Lq{DsWRS}4GCHijXq+JasTapQ z3QVO^OhuilovvEsXG?wf7p;z9qzXy@C`-cqWBF|{m(@T~zsW3Pl;-%yB0% zB&c?nPAi~>4?#0=cgWw6sH^8y{h-Qi7#MfA#i|=vJz0CnAgAxMm?ThvEAxEec0_mz zp3P#V#HNf5yF+SG?#+Z*$k*@!TNawE_jPx@*n}?T?PL8NlpD8>fn7($w^t-8kmX5J6gdH{YDMBrB<{hTXrg((1& z=@K76$5T+H$4ejaV@AjYKzU<-NV|ZUMMk%Wp@`oq{XpSv;kJ_%Qm7b>&DjXOY85(_ z_5#AoFOcQ(;eC6kef$L-*_kLhGP+B{n|H%ng|ccz3(|OWi33CiSX}jKjRc9bFwRie z*xhsa8h->UH?;hsIk`}l$6Mu#O;(jdrBpT-()~cM0t?ebjDMbIJPH^VG9!MBMPz@m zNaeaM&VsSyw%EHzkJ_!#w~cJJI0>S; z;SwoVivUy^4X0Kg=E;3$Wzq#E6O0UwYNr-n4lqTdB=$l+D5JcaqmsaA zVEm7r{4+euCLMd{#obZyOA}iwe-60A(dJ=mt7;7N>CZ#3Jn!ukNsIPVk_U!%aiQSf zgpY7TBRPR?^DELU1TfmhS9@gk7I!!+KbHcl-$$WZ{u_s@Zr_wVGff$(RdKA|o0F z$aFbC`~|x^3&Jlvi6?3)+f`=M9nM~SoZ>g!sK>Q%kv|36F>-|vg2<<*{9ohf4W_fG z&){)n6{PZ|2+xfkn^Ys%Sdg06w2$84yOtn@&vy%chz1TW0tc!OfyipR;KbUPXXddN zBvUyXQLmb7a8ypr=lb;@E_m+L%}49HHi5-!cRQgYFp}0wxP9aD`ZYYlE$pSzZ_JfR zd-S$1J97)SALk(tVpZ0g)E}xtu(bNV2S#rS@GYjS8z^^vmIJ;{G@zRn7CN$t?Pi3d z!vv6w<#!x-8FNX~D0E>Isi4EhJQo;c(8+GktVBU0ovXq|7C!^~n1qZkn3N4dM&Srn z_!EE%uD%u;e~Ic}>k{7nFX103hve_pup82dV^MorTBL0jca;g%I6bdzzkswopy;pa z%&dasOn$lEm~P9#)7`EO#;ceZ*5SFViRt0PbgQ#kz_34Z}M zsKFQtSI?CD#*78c>nBS(iE4$}DmV~v75N|1d;4t7~4oyGEGgM0Qi~2puW@CFs?j=Nog4!mU_gbL0xLkucTP}Cn zsea@Zfs>c;3#o|N1SQB~HI&WgLrX@6W(@&EcVLO?wQO0X7Kgj76^HA^O{z8be zcY|-%>d}r8G@A^nr*TuYo0Ly^W-&Z{<>DTM{ z1w35nm*PvTg1N-d9@Ko;7QK9aGqycZ4Exg)h@1Y_UleK`MoiE~)<_UiCpR{LEr(Cu zneNOm)KB@x79sG*3Fo4&1x;4J8IIi>Fkoto4w@Yxc1(3wEd3$=M$n6O6ne$-rI<6t zq-wora4Rbz6}B&gbt45gl~<}iG#mAomvyK z!*J!yJ5Oix>;+Bgx4{1qCSaY`|*9?1SQmToNt#7 zL{y^CihPmYO)n{xEvC~0xvyi3ELMhl20H1)2@#ADTRJ}D%*7V(?eMcu*<>4@O^N(J zYat`bQ6_?4ey-uc>Ie1ctIWtS47+AtuA>U1?M78U$!|9H)}?am(_L8-gb}1Q_4BzR z13Ik&8BXSs#jda@w-2wx6-p2F(lv@4BkmK@TBMioM6l}%C2qD2Pq6}Z+xn-wc|O%a zTU0xe&?g72zDDEGA79W1gc`U_Qj{O>$2U~{TV0moElmWiULK3n_F#(4*8Aycg1v-T z$Ab4dWDmTcYpIWMZigP(CS=rz{{=4|=G=Me70O&_icV9MhV`p)lAPy{_iFtcQpnz* z+l>2z>yJR@n@_=h&3K(uxXD)yW$wB6D!--mAKoRHrK9Z`qYD_>UD0pGP4|>x1|b=x^ydX1CpNr3!XvavCgY8e#?bj^@}3ImU;W70-;D3vkMYj)~m z^@ZY1kRr>jQZAq3s#VPU)Q8l7kt;u`EV^BBh{J&1!zR!ACuV~)-{+}Lb2s3lUB7=i z9*0h|WqgQ}=XapCRidD&JYh{uT*#aO|NO)&3r z<-7q%cig)M(PP!tP9(&#k}#TrUM2fDE=UBKiPDVxWY40xq9jC4t_J3i9>n{29j8zO zc}Vck5@%}|Knr5Dw84H&O^-5oiPMaPT2qmg28&}}=Lcv@swI}EL~`a zTYS@b6QEE`8~re#W>K2mk|n~fWmBNrS^8+y-V zw9B$D()A~mJpwd^K-$^O#+SBUMf*R^{mzxN-H?fSMofsBE`3w!vLl^QNrMI)W1KLW z*h~Lf39hL6M$sS2xfEQLC`dacQnnMeF+G)`)(;e@I*HuIBt8lCtIA9&d*{^DH4JM_BfA4FG8?*^wL zHmHegevw6&WYLZa>7?NJ8Y(99n(!GBeH8Dhi?gPV>e5wUXE08_0{N5_d=E5C62HxV z-|K{6yK@VXqY;PZpe*o5Qq&u&FeL+X0A(ey7!b@MD3 z_`4m~CoBf&V-ET4%HddJKL7OK(o2D33G0+(NCpWVW$;5xD&XM@vzp6VP)oj|g^aENtDIQ4nS!1gE4_g6>l%;zK95Cf6mqWFWTgdk|esgBn~zVw_N* z9vg)W*n-tc>fFCxjCc+~jwekVmX>79N6dBVrg^C=F2Mg>9b5txOKP?`<^dY7x0OwD z*Eh8}2M7C#X7=l|dtrvefK&9CsLp5(!J zITyh{>?;D58-OhKEX}7X!S{3hEi;L zt-1Z=08Jm@DPl?L?cLk7^@yl~Kqk~x4{}|EEa|V3I*o+LW@O+C)5J^;tjw_wNS%BNx3OE8)UNsdA)TmT< zGQcW5$kcBGJ+PP@?1Af;z_qZo%C#YFwCh{VOhM+%W!h>gM5RCBR2f{vmPCu%>W6OZ2RhnY z+~qdLU}HK`4#LfQCa5+1HvVI~xfSBx|DlnoHGg;1{3R>ThSDXG01j|m+1?1uO{0JI*hbS;TvGY83=|XNJNc0ocnL{4 zqfoYt$wQ@{4`W>qhv$Jro3A*_P4GaY1ff{Y?>$mMde?GOTvG={_vU1`N95P5q@N8Z3p1rsuRXB=aZ9k|-5P{vI? z|7b-(BZ|;i0tBmr`M2`1OOh$*Czz{`UtfA~ z+bveSg!I%~s|DZ`po@cQJY0NhtMXjSX_?a5$X|bQQODWg@Mi8kcAIfP^V+ajW(mGd zcT4eS5Jo(__1;;njupdVDJm1SW80AuCX*fdHjwkCrA2f>*5ij#{9Mm^d$mr3UAJJ9 z*u{t}7KuuaKcGT@92!|=?Pegnj@nV90Z#PVRh$jmgi?4aiq;$o#EFkiCW-_S6}_ze zr<#u4Jaqg%jjn*Mw0R|21+K%{9WKg&GM~*HaJ_HtET#C!Bx=u3`rp#}_~C8Q;oc^@ zb2gV#cr6;c?am&QSUH2d4WVC5(JiJ2VQ zP0_z@7y>hbrRN$88=P$npYnU85{j@)z)`@L?ch|#nPf9TnUrT~&Xf(mE9*sx{rxsW zdk)YuMAEz>ly}=!SY@#5Oda|1dpIX>5uchfQx-^m{k_5<8R_h=8Kp+o=e zxceqeABp(^kuea%pmuNeZ8!d?j zOHR>Sg7vy)m$1LH3QmFT(7eoYEMFk#?vXWE!RMv((g8@R>ZHCvl4ucUAY5pR(*Cgd zQ2m}BzXB#u7{sPwvbvd~CaU}k%I(@7FK4rF>x1Uu5#15~ep!)>mc}VfC{2`Y*+qnx z*Z6O)nV+W8@H;yYq#v%xkVKJ^Z_X}f037?L0B9m+2%nR#CxsNrcJF_|`A4rrR+#e@UBRsCGQUb&gPQ-`u_gHNVh2`xKIIj#t7Tlww_2vo!7yhF-%p)Y zaU=U_v1g1~!#kukO?uzMW#(i#*!31D_BdjaMV^s~6Kt;gqt93d-w4(&Rx=N#@bk-jXwDbv*@M9QpB7j zofTMWX4^U%_17J6A*a-1k#?kag8=cpy&Mt&P4*5y$D-2&!zqj9HTY3kUMI`#lA@K! znchf!1h=-8u)m$HZ)jE3BIUb%-ZqYwG~J9{Pt^v^a3xZLBNxhXN`4-gUoPealXZll zsm&0-JvA(A!qiforW6e;8^=7*ZC_9-M6c`OBtWlLTb77Vz0{E91=~@LJyn`5&B+FOXL;v%&32VD2t_*Pd1L z+`m{%9%$i8oEJve1ajKZ;8>9JH=OJjmq^QG3r2>hvg={n;~Pa>7$UYZ-a6NaP~^9m-_G7Hoy zPqhqf#P%&OFa#awD`{sCLOHC*K*6L+zJfm5Fyx4F{u|or^`@7`qKvq24o(ge#R;jYzgp+`pA=*S1fiHo70f z1L6>Q_IJ(CJL6o}uhkGg4JS0QlP{S%fI&db1d3&rB@d)nNEGt`%!+DS-h->11!mwo`jqIiR#b`}Y0-QSkb>+aRCLDF zgo3#Oh;{~`bvgE9C7b?O5qp@FDlo6$-X~G&K=vZbN z4ThUb6J*1q4K}Jao$3+NCb|EpM0xX9$%J?pv5Ps}Jt?iGU3AZR!j7gg3>74w%jMZL z$^Lz@1PIBb#gF({c1&o5 zL#a%3Jb~{cm@%XdoE-%c?kdT>aU`k-O|tD|E_ERK^-iP9 z?TEbNdkJ~O$MBb1*W&;$eEQ5K6@G@cKpeaH%L_hKG=zw<tIu#>CBDBBzFFeXydJRYr_P}{81Mimd0 zZ9@MJDuZ1kRc%~we*X?@ZI0(kZx-sbXZoQ;Ikc5HfJ(3vaO^aw(#RZ#Ki#}DZVoIKw>6ZD+65+Ej zMjFa35BTZql=ca&B<_Xdu7-r?@ot>sD?2=7;$g8szu?iNMn6&h37C)uU()8cUUL2k zzQgZygJM;F;_0rrh!BJPBYP(bhCZWoJfJVx!L=>-YNIqp8>njEzu?t5VMP}H_^q%V zJPgu9H#bUamvT-F7%vt|EDY?{Iz?wPBK*P6H66n4(QxT3cLB<;qp9n6wMe2SXsaz= zLv`l6?mEmtE$V=*Zd*h*?T{|Vs7W-40Wn+0wxpd14Awi3Y4IjH)i(lqXuaPULYGsu zJZ;B6Ux0qKGNA=A&e}i8UcLgQ zL+3iLz9dMLK$@a1Qn`jf9#n0D_R<)7FER2n^ta@AX{SiivWM<%Z@;gP?K%y9kti~D zR5_k9e?bK6Kh&lA2tCJRBSTuu21a^^z&dn}57q83;2*NI@l=-)#P=^ig$Zd}*YwUBa(Os1-xZX>7wc#K#v#GdL=02V{>;ak8hxW@~}HI}Am zAkQD+J(qF(xn#bcwH*8@Ug3UK6ki~;{V}V3t`4>E5M2yj%8~s&O^XMG+s)3GuQ%TpoyO%rYxtSIU&u0U3C8NtvzNQ_3zVmFDdCM#M(3Ivq0Yd zHTFL$bn}Xj!oZ`>aA-wT{77W`J;EDn!wxSc9a&1fTnHZB+V%Wj%R$TTEpJ%Hw5|okN*0Ymh$!*7qZrZ2stA0Zwzb3||C*AK^5hEI_1}PhHxhSKIthsvSk_s0xsys%Q%{Ep zG8CrWd4b6{#z?5`Bku5EJD52Gjb|(0T_gr9REAmRS4tqoGTU$j2?J1^~AK>IS0Mj&aT zfk@4Wq0S980yYBP*y3tlD0CVX)m)wgMa29p9}?9&Z4a?sm6{7VvDRTygEbXi5XdY( zV%Q{ir`~;}(kLDU_n$ezP5H_h9-TF{k@502_xy`Acy_)t4gIdza-l)4UZXqaMycNJ z!WJyBBJ_Bmas{-&I?BGKc(iY{TeA6B?2NqCowAWqRRavo>@;Vv7c9TQLrxAl_xC?r z-kR*I|42<& z#3hYK*fgv%K&Jo?*p~J)^lw~I~$RRm&Sn9V#f23Nlu2R+8z8`lWR;{ zUr*I$Hseyv{Xk3CXXe}6&QXOS%hV*K^zvSF z5#vpJj?!p0?8A!{2F6M(YWeH$(L0FAfT>N8Zrm|?C~_b%>T@#FB0__E6|3O*1g9Qu#P#pmZEfNdth0lf)%VgCog1RNFBEcmqB&B%>eX^02r~}`)wU+vm-sm3 ztR8f~V+*&lh{A=>2#T6oI*uVhsI=)hcJ zih?8Tiqqes$Rn6!&fcp6+P85FEOgpyV5hj2cJx&Q$!+~#%q1jak8R9n+|Yy3`wopO z-8d?TTihDa0RqDIMe=kI3Y>eTCK?alrd$rwOPW+B*b`#KAl5v7Kl_(4;?pj9SXtF# zk$93G^$09{C4tSd1_lB6>LG!pG4a~}`ke3Od(XY`pLVF4vdIQn`dDI!UB==&Ql~5( zLqn#5F_D;#dQFK`PE3(A;=uH4s70r0zqzbv@rLkm^A2L9p@!fZmdv~(j1X3&iLF>n zt?m%Vi^$`2d-_lpb`|W3r*(0o@2UtA6|xDtUpf404!n)#0M8=RKJDq_Pd z5Ak9cSVsBPUpL1>NdC<~Gt{JD4n5(%!ENnO`MioxdP zHn_w)DB{&DHQFVtvy>cRLq}yV8uK$>zZ8cq;KJMH_u7Kqrb3=hI_p{YH?@nVGY|4# zN*wTf+49j(E8rA_-Y~Sqd(y@GUu_bu7bLgaxxYvPzDv#VeZa(X>58(UqZ0+Kv78=1 z9FobD2~WjV;!?}0LK)IjJ#r4p`vnc`BwBOA^!~?}6CV3M=s+*7nJ%@_gvZCk48;Fi z_4EA>N|@@Z5;jy>e*{BCay=J=H7^^xQa+kWRG5G%gvKn=9rG+^zQzw6!BMj|N3f;S zYFU}=$S0O>SV_r94WngqR5%>p9XU+l!sRG>WN840&TWvv=?qH17{9?qd(zQe-x_B) z?>{Pe%EOrYOzfFvL+4N#!4LqtGlRG%Bpa+`5H5tWAwuW^>5vt`Z9+s|DWQJ-D&<}; zG>1cP=+c6?6Fx^v|Y=1u(Tw6(P~1Mq$Fr7yl< z(F)T>wSb=$`|Y@?^(AKBE_E%_mV7TFOYk7{Nz7R`il2N1?ijhy!5T`bS3T47Pz;y%ZNvmoo_uKvr421x>o@}X88t8fxQwH zO(O5JBp%>EM&x!Lcx(`lAGP@*<(Z{V?qj_Q@}qlyyTJJ|DP z5*p)~MXKM)M>RY~E(8yOe4?NPu19(L6LMH&^Aj(YK`=)2<91P?9dVxsq@ovh+j~t z3+$05fg4wYavrL@gs>NF2O~yNlK{lyUK2`Ojua{fm}{W|>1#3=_qkvtK&yB6W?^AP zmHG%HvAtmb_ZoE*VG%HxC>W3Q7!LjXgH6& z%EulRAm`p+V^NZpw--Jnw2Ftp6y? zO3QCEyaN7*FG9l~E|TZtQOoJ^R#GhSRNgN1Xn%e&IK)r8mpHn+>eUAsk!VVU|n z4Vtc6P+-1f_M!ck)h`=A7QE2L*LLs*y8Vz=1+cp2lZeRmv>duAnM*|LIov*qr+wFs z$+9qx&itsb+<2<-kXEMObPCBbL$`!keVd#fm;@wQm1LxSHL6y5V+Mm2suACJFOYI( zu)I7_J-IY-4B=Y#*r<#NKn7fCgIkZ*){J?0=sLN!1^WZXJ8J+F;hy{TozJA*tRt*0 z8i~V=(19ekvn}^ofkmg_Vd`v0GcvZ-JKhBJpzxB1oHkj@01Md!glG{1^^Kgz5Jp!( zFjgO-=RjK7U{l9Qw~*hfiB1Yyp=fDeByqT^wvI?hoHQG%|#{VA( z81W_Jl4R8xt6xth13cUiUq}#5cHs>NE6w!0Zi53rSr~6Z(EsB7VBtu?C6a8ZJ+spX zl*c`p@fws#>hG`}_fy*3XmEEx&``N}7nAMXl8HlE#c8fc-g&;{|nLQ8F@UB{M zMIkVSJzs4OcNGo5v-u#tFHBn@&wj_SQ3=-7c9ke(P70a~X#QdhHgw95#?+`~$XY9B z0ITSE=EkBhYs+QvyO^;%7&k?~^%EV9B%j+!WrWc9&GA3_&E99f?VcIRpVlQP0hv-AmzK8Tqv--RR=Q&U5i* z{89~Z9wiaNaLT4S0eX&@x0r6&nYEpvov?>j%MZTjPm2GKuDHs8TPg7iRhzD7lqQ#2 zD2u}&MN1_2j-nZyu%k<9&WP!2axvyVo&JK5;-F`ZB36P;|g)WjXZy{<2mwGiv z7#m+O$kAggXX1s)hOZ7L`T*e!a#Zu7;4|3%N@&B`6$Q5DzUdu1M?y73kjyh|=GoJkCo zI$)2&5wl*T5rnV;=FgudArqva8BL~;E9h3^33iF4pvOWFQN2IV6$iIqpZ?YMN*drl zO%p6Ojq!9r1X|&5KTen@wIJ3Ukv~zHIF&;e<*8~p*YH_vzM@))+y?4LFm%DctGwGe z*LQ*jDt=Tk)HH3_~5d=!|v8TsTLH*$5X;yqoy>SYTxzw?B4P;ym#gos-C zSz3Q!KpvtPkp6c+9`%+LEF4fq>N}lnIlJ zI|s)ASe$D0P%0KD)7L`RmNaDo?}P3$x@#9qtudRvE$>+)B*+>E>kc*j4~Pq?Xq&2> z2^0yc`X`tXb?WRs6!5>%<+3Sn1Y(LGL1cAl+$$HO-Y}K19nvGo_LCZ_zh#w6uhl5G z>LFyka(>)MbJuwl5VDL9VG|gv`dLi=zTA4_zsXkaxhng}e`e9(8z1}dpZmTXL%~2` zARx{^loLzNP_Net!DQLRJ9Hq?9HV8zPlJ*eLdu0(9k~zdpItm5j=7uGK=nP9_(E&- zGCK|!64_)po7k89SYYYR>(p#wG23?!fe%{25foD^xI#qTDIh2=;K08PWI8GU9)0RI z7gpVR@`FrN#?^~=@3tsLu+qY~tlZ>0ikX?Mc5fU`r?#B_EeMfhd_8{Xfl&}oNVf&W z2NWp*N6JD4Y#Hwfie!}GkffpDKHpMAa0Cby>pfD;QK>Ef(v*W{lWXzMG_f91#9f5H zQlI0&+fY35Tpy=)MRxVR)u&Gt{1bAX6pc|3M$p7=cv@Q}dSHVV*-%O1H6hEl3cGK& zD0wPz_^SxS-Ly?vH@jd6sDTt^Xc@zDI)wA4Ts;TH)M|59r*C2+zT_J*+4Km|6>17$ z@oC`@loO~4r&-De; zEoc4$dDIOYn=i5G@x`8Lz_G|NmyiP_*#M$A>9?0WU@V+RY4?tc136SEE`O$K^%y6mg#SR*oZy&A1W+3!Apa*n$TvEv|ke`ilHHNXRpqxI){Ainq;-z1lyZ6s+qNW321 zP8Bgp#dBsJnVGdz;JuzlMapt-{zP|f4Lmiz|Kuc03-7N&H=1usJ4+l3EBtP{b^iA~ zTlnMADTGkq1EGflF>KibbI@ZqMVLOfc2fiYQ4ND$4qxdbSGTev8#j)R6RosW^P0>A zT}c6R1>T_?@8DHqo4mOy8q9Wtui@Cwj8b1)=Xk1{Dy++s2Zyw{j=&g;cF~4QOD!kN z>E-;5)Fb~=3{6>f7TUMDUVc+0ft&q@&=v0Lu))Tb>MPZbra5Cgo?c_wpC~b%EFr>1 z3CyKvs+)C1;N!jiimq|t;0gxVuJ(! z?bwbPmoHd7W~8cqE6$J4mVIST6>u&hS4$(W&rim3TfE7Y>VfJiU2deArK=F-;X|{e zpNb##L9jISJ(ce@DR;*2DU%MNiEwl5y1J_X7oU_(d%NB^P~B!bMU)V-j}`OmgbC;6rOB8k&4U{$Z8h!1zh#y=`rcsk@vieuu6(9=rW)~w zjF>uQm?fH${d>Y;TMu%!K`viE2>3ZA{fe6&Ow{_}J)J_A?dNU|!OQk}oZ9`}>ee4p zlXjAh{r|MDEqzjGoB;e2ENeNW$5Ch*Gv-W2gKlqPf)cb+6DKfJt%cjd7MC|evadmT z4=SThcS?*V8wDW_Jcm`0^Ph#CQSXjk0=EGc>rjt7 za*o-fi8jT%uHmmASs`VE6FJ6b_GfL;ZXh0fcn<0C5DjY@=Fi*PFkwDw5Bxm6#EI7D z+pc4oZ*pfchwcrz-v-o%%HCrg*i3P^LQ5BlGfyZRj8cLcUgls73HQj@qNkNTGX~*e zlbyYJzae{a)$NmJr8S@kT%+*(?wy~7?$(8)_N8Y@+z*V!$V|& z79_AdDZAYo5$g2+L~%9lU8E3_ZylezyMNOM z3FqK!ZIoCS8bFzaL(MbF?RR>ZoU1u#l^P?^TSOd#7%-aFYHc_Mvvtql3h|oQ*qX!Q ztP}ad+1-pi)}GvfBAt59ukgTJGy;+1SGZ?8Jl`BmQ$18LckLe4C_xF#|!g?IlG0PM>>&JRq) zAD`ga>%btsZby0#Yr`LO>czj{vGwDJ45U^7-tugsO_(G#S}%cC^cDJh*nC^%d_x40 zX&(6vaDCJnNtQ-*#%OWEV9W5!{l)t!k4h0c=W2r^t?^*_^nE~sh9JdVs!qAtT3?>D zqGra4{T=J2AZOZh;{fJvDX5N3ohlVmQ{l{5e(6{J_a3Rk3+)^XUy$)7wO7awTH|d+ z4tdPEuHZpIib?^*5>~{n`j%M?L87M>`K(NRo0w^#wVujeOLPrP@m-|B9}UM%v{7P| zNtTH@{6uL>euD-$1(6q$x`=Q|CBvp}y`ADj%U0MAW}Kz%E7=x)DgdYl9G`D&oH?b# z2K?mF_?pIk_@!_t2T`YXzF{36;~WKOaQdnP&~jN1UID;HRlf%5t~u7@7darh2kqYR)JpCsJylhi)J6|SI%Sh>1h;F zR?Gsy)VC3|isF?DVuePOHG^|fF(CDq8M1ZCAh^_tbYZ$8Fw}hF1W{YF19_`V#2Bvi zE?m|Vz@8e6cL3IMUF7lL2Y%m$uk(Y8A9<28Pn`zd7@Yerh)(fWK zwfe@HP=ut!qy$_1{9xtL>6d3{2N3=PTjBixBO;j-^S1s>RJFq6`0$E-3n&^Utf zLM?wqFFz$Bu_bIcfMKbCpjmQK1GR<~{vAykWv|`^y{pKssLvmg`KtG0?+kGi!yu(m zJ_0kaS?>FGk_SpW=p}4cem?yuS72`{8o>|V#DnlB@3&yPyn{qU6BxYhVV?j&qG-^I zXKEBv>Mn;qbPPnr0|%-C>iPTG`MIrrK7;!R;0te9TZR5^6vIrn?Q9Jt46k81tp)!e zDsiuVp%R-?PhQHmzZ6m&R{s(0dtknDj-`)8!SIce>RT(Au9mj45xqPw!kzaqU2)BF z4>8x2)=k)-QkXa3{=0iYAg)sMq?yFcA9q^Po-xlypZD2 zx1awtZ-BW~-EzV>6G)NtaE{A1A7mEJ%uZ^kCxKtwo1xOpIXQ#&#fxe0W(gI60p3bc z3ZhB4e-Nt_c{QXgE)*>R;ysVD2LqZOBGx>&&U*HVvz{%hAz25n2%&72|N0cvq1I&) zctU!(p7A}?K{|aKY@xP&`h`+V5*zY$$tTZTVq~}`lSRE{3?=FYE!zN1?C8v-fwj}L zrOg|pHlJhm%5KDXE8%?j&t^bPPtup%U47Hu!L{toF4@mVzoZr zUw1n`>;!apTsLca0HJI~CO$feP}>V68ms_moTq7)S$F`GweMSJsg3>fhmCn!{qt=D0wK;IogsU8zBeo z{^N5Su3V@sZ8JG%!HrWqU0_k?K_=Xn{*I$ zEOo)3d2f^>Tr%wu)cNT<&lr9~9#2jsbYkC6ve~;id)~)iMG%No`;S5|FHI?fuLF#K zl9BBOB+-#-N%(J0%D{cKS^JgDF*Wp4z(X%HQ5fx~akBj;7uD+WPb|mFUaHeH$ohh_ zN(qo5`5Y#I=U&F;=EXVB1=hTX!vpbnEpt-~1(U)_TT%|4F)ekqt%fZd85uO2G9!u|Q7!fXuqng}G`;1T? zt@nxVnTACr6my&srrqxJ!^?(#E?@@2*P_&<#V+z_h1QR|_nmX`UJhuEYxyEI__LLC z*WCo7+*4?cQ_^uq4|NIxTZT16(iR7 zw^roTZ@3s#>9Tazq2D|`Mzk3{OsBl1#f@%OX+3<8<+>mt9XnyI2 zq_&KBddnhEX|}icsA5kX5#m)m5feL%XEGf3NKLhYDODO}5(XyKuS1*Sfm#BYkw~j&5R6UGELors~~L>KA|&7wVsyugttg0PM?|aNy}2);47>? z_kCQ7TX3?|be~rqvBDwVthC1-CKXePNyNxyuFuWM&H&$&uIOKB`eUpO%u1^?;zH6` z#GgW%&D$&q4kg}T5W}e;p54KZK$o}Ybx;3D>|a2Lmm?@iR|v3%U#dukx*7&*pgV8b zJWN#B260UjJ{dtTsc=@-8$x4=gKqQF+xI#5nn~p$3h<2c2~Ry-Xp`JI>(qK>p8JVH zKf3WioOR(8pX-6eTwknXk6>Dt*TQdKPk7mUh7bu?bp#~J@TeJb<&_S3g%7yWV)0G~ zgZ*W4X00Px?+lXY(a&N0DD%=YsH7l%aU&MNWUp6KWS~Cbn7mDNwmq8mZ6A`f+2P=| z5YBvFzPrTpJeI3&+pRI;d4m2}$Lyqe161dEkO0W>-LW1HSE`pA_H!UIGQ}*)tB^BW zzplc3>3dq<60VjAG`T4D?2Lt!SUFY%PoolP7Jy_!7JAwbuf|A)4BrgV z3w4MIcg7{kPQB}SID!nN&@`90u&@Z66s)<88 zXP<@Tu+n_=ABRf@^$n2q0!~^H_s|s3By<3r$I#;2}hf#Tuc0?W?*q9ZhpT5ei+G9}|1t)%+n>8NfO}6>1wU&;@uGZ@Hh5;jE2E54aBV{%2xsVmb406Wc zRdBn@lEFU6KHSzqS^gi4mc;HGH&nO%*U+3`ir@jskd+M9~f>H;@n-d9B+Zr0P)& zd96aFs^LaOUw;T*CAInGliOx&CTCQT=eia2Na+DjPnZ=NH1-3RKMB1xq$O$7g+haJIzszqQHtphu!Xn%_~u?Y!Ml?QC(IJH593=oB?}H3YyBTG0 zVRouPszU3%<1nD0S{pT|svCT)(Bo37U>}aX{we`YL1M`fB(c1F3I`+(#;;<~Ji7-Y zbXx2^288+3=FXGogK;HF__pD$IbA1MWEhRE92a~CrvCt&GXHkqbNH8k+?ZN`+Sz-x zM>Zmo*X+KLyea0;0cAD9Fyc;_02wlXb-|I!-KdKC+^<9A92AT|DjTPM)5W`Uemw63 zAUP?xSM9l{&X*QNb(F#TN4U6Jnc@H*Py27%hn@mWDZ)Sebt~Oupu|e*AbdVaQswfr zRqaf6MB~VDTF`S+B#RllZ)Hwb5!{NT0tk~~0CC1KcNv=)n0l6BiD+AZ)1@-|+PdVSKLnuB{C(hwAt@PcZ7CwoJKCA8myC(|(7)4?#FX`Z< z-{=``YeB2r5zdj8NKt%q9Yh>QszFtHw$07)icxkvq1nKoXPfu@1)y>Z@tNuHc0E{% zLm92}HGal0*UqY6@vj>Uf7uOPF9k?3^&N7rR?tz5$7% zm2yUyVg@$L|Aw=+!Mrln6_m`1-5^^dXqkeMg|8lIT;+rZKli#w+n(7)faLGEV~C}= zTOb9F#u&Oqs`j8?Lz)$_bC5VF=sdvpcYQXeIEvmAx3^GHMDmuRQ~6iy6LvRMl`_Us z?vc<0;3~SQT{2j|h}0lcw&P;kGql`^&iKw}wQ1Oc@TRWDkA1I0c-}hOe=(R#Z3l-U zHV!NR6L8Cq`ogejnVLOTO}dGY6Wvodh%9%680|m!05+6l2!(MTEDDknQfDTr)#XVF zrzK6(-tqL73R4A5UxLX8To`%{-gu|}fkGK&c~x~D26}xooU??g=ZLH%y$`dg z6)+7zS&v3|tFW7<`QPKV?A6ORF2cV=8l>R(P_$YAh=yNGMOq+=SU(TWwAx+*t8eGA zOYrh0WF>P*ItS{|5;ZM?ztNu0@0|++mBJS;#L+tBW($tqS}UpfyeHtpl68<@drN_D zjMl-F)O%2B#yo>KcaO}?v=mxF41foH@f6%@}_TJzG4F7kL~?x>KZJhcbNuQDrmstSl=50%1xDK!pn#Nf;MEw zb$z3OvqpaBqZ&^Is(AXTG3@y&Ec|X<2Gt-AeTJ68>#>^M^#m&Xus)J8f5r+l-zFQ_ z=R@AGRTL>*!&=9Zeuf=nrkW%7pFnBD#B|i=*LR_7QO0NY=5JVW4#6=+6;L?U+_j3Q zHxE4T#FNXy>E@bOn4B)2=GN+fJ&bF@zU*cO7z|A>!_8i{v(9ERVwA+i9_xf6fFpe; zjN#RA!{iv-r#2lDjAQd_AoO(FwzV5XS-q=3`a`z18<<@~9vfYm8cbY>(QHK2tsa8z zJylfx$^fGSIfsW-@YU^>xDmpmr+bZpWCcr!Ju~Foi`l<@h4jM3Db)$R(b%z++5iyW z+$6Yp#%qLqpc;J&mXRN8-hm_;@A{TaNM90SQCm^a3(^i!8xnW+n=^nzE>XnwUZ+a*SSTnP0`PYyOgL#UpfBi5QQ zTj(idEpjx2R5Xutx>`)}wNn~N3U6PG2?JpL@OymgthfI`T>m|4%kN*Bha2Z!b+7pO6g9%ElOrtO3_=z$yA@cGQ{}F0o<+6aZrZex9wiK-6);O z1raGVm4H4Qk$(p`?n>k~0Zf+!!7+o)d%ee^49a_(@TPyeCxIJ`99IFB3D~$5B<=ud z%l9OLBpyOBunt`r5f|skX-z3(k6eQ)o^&y8hktA2jKbR z?q{^c+CnOM#N>*fFW*6!q$51NV#vzbHEeI4x6UJ znIQnQhC}GR(zxeh{Zti>Zd;&j;0u@ae$g$O&Lth(va(s!2&D2)UV&P)Q<)k?y698X z;(icw1M0+PHo&sR9D9niu56JTYuFEp$mFa+`H3h`B+O&!{n-28)bw(|WDm2A!F%Q_ zA7q4XsF9RJ7YQibE(WuC7(N=7Vbe|55v$gIpsq2#-786yAHJj=BMmxMDDqZ+H|((5(6sT9vT zo%|D_({=4^_J?N^?q-6c(!>6!UM+>(9(3WaIz;qH0EGFzotZXb0zXUCR+pq0e0Wu` zjQeVjmw8>SP?ve>=5XYLs;3F---;|6y}Fx#rZ~gqpO%+mYf<*QAoR#YuF1a@E*?G# z_YEAT8>;gdIw6_es%&v0O%17HOTzi(a#P|2IeDYMda0->h)*s6CeIbamemr<&dp5Z z#N-VH=$9WcxjP)Xmu2R`U?vAEZY#W3i^Ir{gw-TN0E&tUU%Zy*BPav>-;qrN%Fj1^ zoaF8K-O!aINRc*y2%HVXh;V`Nnd4{E_a8ThMG0E18-4IEhyHF3cz;|<-FOj#Af(0& z`vriKT`HoaRwk6o@;fy{)}z=4+)?@LH>^YA+fr$M_41Clvon~Mic{G{b1o5a;3`0m zJ1nrgDde|fV~ciB@dW^-4(!}IVX!fd@C4+et@?`6yH6|vf`)DqW`>hOQc|sKEbl-U zZ8Re_X#-)a(Y-qXFcIp;te`X;*=pJ_8}c;8+zL3TKcdt3bZ?G&ElFb)L(ma$N3Nm) z!q@v1P63$Hb$STb#W7ekFf``W847!}xE_c;IvU|$BBLAr0M9jD8@-3YFG|1AFqUoN z6_msl1zSW!B$npDoQ4LnFqK!>hswY$;U7E&CY0dD>MT!L3}Hiu%rU)l$VxD?wl$69 zn`*aTehJW7h%y1`a9b-asQA_n^vwGm+i_m^)7U(%@5~GfC-EY`Qh!z(D>?kg85$Tb zpPN?*Vp`;vt~hm(iAST)jZQTWDRh;n_CDZ>L)xZNj5Lk~APw*H9ym|n^o;I4)i#Tn zvIsK2p{*9U6IUvq1kt^JmVpMrdf3Z6C%jCQ4wwfSfbXHu&VA?0`D+ikz7n2RxB_$4 z{C}bVPU#rLtX;;-R-o)qJZ|e5BCDm8o1atPD!>Z`8VfPcd9)RQ!C3of?>*UlH(<=3 z&A}aW9uAb+&0~osrGhIa59b3D8oeyL(qG$ zV9hd<*_lyZEi>0SyMl$0Gegy;J>a~Qz%c)yts=O}?F|zS zj}H5Vy2_HTTF#*-l`lvPgW-R(J3VpSewq~0uf0g78siS6kHe+(tc`+4qmCtV$t zB@!a-|G_4WX0@inj#|)N^}SUX$5y&p{fo?d4HE7{_Iy|Hg~Zh-lTl1slsEKyn^On8UNiKiz0QK(w- z3Tk2EY2c0xEwP9As9Ze)^kmYZ=K|UPzGY-2xb$^m%L-WUa-au1%cNQg^b}=``pYO@ zDP({5k&xYIPQB@)v_qRL=w9|v<{H;T39|@0m=brXUpIhi0561 zA)l_wH+rYGe{9}uu~U4=D0C%mz|4})@6QFvi?o#Eqa@hD9=@OG>X7`Wm#^pF{;@s~ zpP|Z`iEKYr#X(dxszmI4F;AAR{eng?MVC*2uhYNwyfty$xsjwO$RWEDRTMz`4kHs; zXB!31GJG$Ukk3Ajm$Mx;=s`yY3u6>ffG}DqAzhGm!%hfyXKR(IO+xw`N?NVH0vdV& zBlB-TnA|L8GCnvHK{C)+3)EF&5bnx`T;>eTFu0WvTO;+_K@!vruCAuV98H!9fFJD0 z$;7FU<{V{ecsrSR6`4j)|Bi0{I5NQ~=+Db#!d#xw_BRklH!-W_pmY>Lm>xK?exigx zC!i;Kxs{W^s7nr4lH%t3s~7H%z3z%rnTl}#*Ce;;2+hS*y`NJuf~elY(dw>iC3^Dk za9-4b=q4Jf(!t2S=l4i?r;hlX<6drMm3xP!X^#=Ioip7>-L2C!j9xaRe5Ru)-018mhZA z61URS=2L1e1ye*k&4!&g$)SEeU|35s7`{NGb!)kLIQi++)0RDmgomMa9miVG8>f^o z?Wm3BH7<#suY`7=aQ8t{;O(oisJ@4#`o>#CkRA}@{J?<#Lu5o^1HH_T59KC=0PS=~ z!we7;X3s7Od!f@zBbdvzVV!6|MOq(HkPAos@eSzZ|083vqia9o8t^ObrCh&QyPaA2 z!cX>sT)fGZ9dm(#eX#ZY7D8@>nPkdHcgP__gdnQ4ac{M<9Jjr*rsu=oy)Po^6a=a& z(4u(}zN^;XK{Ac@=C_ZGIm4Lvpy@6}?{b~AVf^#(w;#7QHPgfP^c~;6rd5@(H*KzJ zw9O5IQKV-ik86?{1P|_QNi4~y)>s!VQj^@j^lmBuqzrPJ1%N`!nub9IvI?OJ7ja_r z$mX&mfHwcu*ylHROtH@1+@z<0b{P-EKE5a7{tF9v*qD{M{4i) z;ompU$0bfOun@9Ab8ozdZTqC|&J)~)0pfbg?7HhAh%f4}2&E1fEU@ae4K$E&(Y8?j zdq_kXl zK@>R^!WlL-4#A$s;=TQWKEl2B)wk%Js~>vQKNoZ?aG?Iv`6B;4EvMLj)>Y<^MIBjK zkXQgmVbT}$s2Tk8OIaPrVb~&`7WIJ9;0-hlz(7_lQX=u&?-O~zpCXf1Z;5m|Bj-3( zYp#m(W_u;?WrrI*^ATu;vOdKYcfU_%d=u49t?3sfn;m?$PCOLq)BrU=%D*DH@&K;) z9wYW0taY)MQi};8U)D&PGm?(=|2JZj&Pdu41D*|~Piv0fG~zKq-^KJJ?3y>0rf@6E z;po2dn0Fgs%Q-=W*P|c~P~4oabZjEFAoZ%Xq7jTzbi3i@oFZm9$vgij)OeJ36d>j! z@5@$YP1eVDyb^eBvCh9Z^Hi9!&5|_v?sd@Jif_d9^Wj-j3c&8@n^QmrU3%j=TJY@Y z8I>tMMEG4D05x^}NciA?c82#$KOv#9ti>sWK%W61THG|v06*NMKQJZx^L1_l6kp$UcrS-|l+PXp0ogUK^KHhMvCXI|RYvu{gnB%b*WtE!|(s#79C@ z3ANO-!sAF^f+=^mlQZZdWwiFV$O9?=Ab1m7X*{&=nV|UNpAYi2a;W-LwOU+pATeL`I}^Ey|$DxJ_dYRK3vK$^NmfT=V-)ekaesITbD#Rwa# z3rf7J1rfcs`71V>^6PX|DE$go*>V}2XunVnx2z>0FvL^O^o&-v*gn(<=H;%0@ANBqugRZML% zCcj!wVI0bo99RyR&zDmuH2PlH{GKJ9WoobC2wB;VBQqSUvkTUCjtl3RqHdmI`^~eK z$j6=mXdr#Rb@^(2a~Oe1ld2))r+^Pyw6+1J)NP5!z4n&$ z&mHu9>gLgbXn{rK{Ps*a!E(79f37su!NP-C`(phUi)Qe;d_5|j9{^qG9Tq)mG64Jx z#4An{t4O|2@kk#J0u6=pG}?AuuAK7W+}_^BjUhm`s_3@!XuRNmnt)#qLcH`X&dCAN z{g9rg8@X91sd}M`e{(!(Z&)Eg_a$bU!)`HCM2L#1hBfZUezcTC0^Qq>8Odb0zRR^k z=_qEhM@o0A|0!m{)WAdg#Z9o##BbM{=|k&v-W|11?xZ_N-Xyyn);r^66ncIv6xx=` z%xQOwdjO~#wthfc>Q;eNQYM5^gYWm-*}5~&scLXRpkYzfWZ}|%#)vV4lVg6R+$n$@ z=h9S04Ei*`itQN%!o)sJ;OrH*{%LM(g!m$qV=VNpQ*^un>uh;PJ%jjsYZh0~IG)kQ z1Sx1zIwpQeb+`=@{D~I@583;Ur$jxcW7kLSN+yC6{&br~Zi9=Z?oNl#6(5g1ra)P_O=E1Tz2WExz$-Lz+mT4|vivCc%z z*nzr|G07ljnA@Z{Yz2D*8@SaI0?u~O$pabUU-1GrE`g|&TAVppO^z!KBt3M12x8h#5CzYsf#nII?*VG}ad ztf6JykU{rlNWmLS;@}h`oe{@uZ=mSfnqO>*RdRCToZP_-+jz?6tw~{`GHkv4 zjVezryBd=@STl51P#Fu8cIp<+G{IvM5|ug+$dW$DD;zs+Me_JG`h0SRFv3iQH&Wgs z+TkhuqcikmB;eBy|*1qK_pE^Qr)RZuX=}eYI?Hs6sIy-15w63 zxmPk|w{h6Q5_=28kp6JA$K zKnAh4%FIhK#tDS`lc6?4EpPWGI|=MLwN4C;Fz6X{`1@9%HZ^TK^&-wX@n}p)WxNVEdMu&k3@$iJJkE%}fQ69^+sH z{`n>a!HnlB>|Y9#jv$H}9u~a%W5;T!2_9VtnXeqkA8PKeg?L44MbdyK=(|`>NstY) z5AW$s?yn?k1YIZoc4++sa^2jfYN(7%7i`ZO%Z35#y9>(7xsuMN23>49@jMXS2Q@=x zg!x?9R_r}F(!E3)dr($}0BO`!Z9x_yTf#gNxsJ!g6?#%O$^t;6{-`Skhy>>VpmyND zn*#`*w3b7+hj#S)lHmDc%1DF!%-m$Ss{b4@e!VdiRD2*uBj)iX2jGRp;6!Mwx_O&l z9)%}&%r29+WSj395C8WjL`V)|fiow_aRr?C~AAH_jx z#XJy*QL|bwK`QCQ;CI6qiZyIHs{H?IDn$Hp5|SdLY4#{fpG@C}kB)yF%gC&9vSskh zqU1gO14%E1eL%&L=HLss=v?z!@P(Hns&^gvT>zNhxZS6#jBg)948;l;;?LzlRf!W9 zW)bfQu{n}VmV_28p@nG}3bd8Yw`iK+uSrE^D24kP>VffU3DEB({~C|dD2;x z>P=plx6r84@iKPk7jC{+*?_%3=fK(BY}n!O9#R0b2X?UX%9&6YUe5JJRfcYAMD7_v zy1ijIN=JSHY--g!;xpdi@pX6Jz} zn^MVdt66j&nslGIKP%RfIrKXJQ*YHueX=#lB@i`ZpP$Ox zZT+hfs3j)tMwKmjPS0{Ta()}Q>>;mhwTzV}U$f6IXlm1ALD;R77`fuz@~vC8p0`6k zA;zae7EAj0hP##!&<@VCY65=e?^6bV%3%a7l1+F_QhRm34bUQBCjBa8vlnJYu z|6#i&MK=|V=5!4zyc-Z<0uEwx>~T$Ra8eP>ZnkaqnP1Cs&3-C$fdpwinaf9z09~Ne z0r_A^NOin0*1P~kE)3YUI5_1{E;x&GZt1l+g|p~8&aSP?A5dTVv%(;m-pk2%yzp1K*2ZIn+q}Q6H)2mUX&?x36!cl^tn2usmJ3vg}SN zHACJ}pcinPAm_5PtG8RiqMA9>WjIx+{px>LtKH_iBUV}&H>3y<>?KCIB+ z8r`jm9A|Ij3PofrbTnh>8vW-l_;%ZG5@phJu`-bG`NJXWi?Wp;T4TSQfw<@GF5qeT zE!j`K-fSa;vbGjxf;KriY<~plKISkdl^~vH>YbEwHrf`vIrq;MBKV;%3O({xgckSl zA<}P z0wuN@i#>InmS0nK52s!WV64hg%l{}|N2#qx3v_B@82OJHu{+ytffF@zOd(zUJsx{1 zHg4Bw^B23%vgJ|{A6l{njGac1toxtBEL?SjOz>dp-?SKeJ`$Z#&3DMKjw z`jEq`~CVwZRFD_u0S*SD-AUd z9}8!bq>ASr5?GE1T3i`%7~7*)TQ^l$@l&m_HvhG(FK4to!DYiGAHPCcW4zy=MZzIu z_E|Me=z^?I?JQTCwLVwttQrV2Cp&Y-?7Dh2o*65H5P)fc^20)o-byfQdmw_Pn`D)C5^)hQm*PdxNTHzLcbyCc9*Mdho~>aj zTOO)xRp58meh6t$D-=kvnRmn>k7sZcWXb}N0G5#8=+oys^-;2CQTdNwc?9CpITPLK zGv`;en~Orvt9Z-mnx^xb_I$E`mB|O**$IP_eFTwKWzr_}!)90W!O%-q)S~x}SzTqO zsx>O#W|M0jKwWmkMX2j>_>goQRN-fltzQj3n%RC*)on-R;K9iPYSMv0S$Xtl zgR1mSS;AURNZf>DE6z-jw8Hy4 zyPF~VjgeX7pI$ST$3Jjz&6k=AWP0 zFveG5EqO9h;mgtlI8shJNZ5Zoua+qbRi^TrE9sPUxHR7yQ^hDx)hOyE-a-C3a77_9 zo3?}#)(LspAfBO@heZ@z=<;3|g{e=nLSuzNn--t5-gU(De)>*Z4RV%)`@m~V!kwOz zehLI!1q)Md5U&||Yum3hu};Ev-GRPvR{mO{+m*@0@d}w`rR+eq8$0B!khDld3+LJ@ zdwSlQ_dVjqqE}E01ZzT*KzYGrw3TnD?uX*sYFG{*{@Z{NQZ2tb`wZ0whd4N~=Acrq9y!x{Yt})sK0Mn$O0lA1<@4};oG};?s`$zs^ z$hAM8SxAnJL@8&$Cq=yQia3t97NeXw;1cn!p1#y7)5(_F$2?@$C9sdXEZ5e|ZwL1q z&-wI3t4##oXLJP_ZY})q8?5kS|ceK=H^2tCtF%wEGffHNp{Do#Z~dYJakgFmk(iYLevA9NSvmroaCf$U88ayQFGX+8G>@k z0`X+Eu0p6bo6^#Lg@ESmGM3t?CFKX(kX>WRy!EKXh3y%E1EID_#SQ`!A!r~_s5@XW zkjk?MaL5|kJiY}`+y3;YUEhQCzg~()jZTp9HJ417r*45B3NXJrfGI}|?As$Jf|iYK zzbSjQm|+-|ZW?YNahEk^SZgOae#5H-%1|;*ydHc<8s6c~0WyrO86Di9@crkMQLjlE zOpBa|5lA4mzEM%lb=55-6so8~?QjPwyU%&u0kv-*5m7NXR?%hZAYekjRXKx|0pB(Q ztmTqXrk>IQj=qps4=;(&z_~G-V$kkS&6Jiu9=B`g=1$QR!nl3Z3jVt;FblfZiagU4 zULi0X`45?Y5hFnnwY*IO*qr&61l)VhXM89a$Q;M0oAwIJMyzu2+{)b~b9Lg2*%`L9 zw(AKDmo2qBUGXws=liX9aRhyiyaiQ)3bW z4QPi79kuD$=Cx9NY!m=QmzBJ7xyallzC+9&<+qb|-Q^1!B!1%GpDumSxSqbaQ|}cd zOG0aw5Z-=_8Oq_fwERDp6EgW(Tihja~^?>j#f_9RT7AB#-aV9+NoMGmJX#SR``q$3uGv1pfv zu!)(#E@VtZ_4F_7$ZdH>4&2KX#*sf`UiNTpW`jH%QHV}%qHnId`zbBC69lolZDc@({^yTo*ex;e z@Q)Li;tE6x3aapIdq@7;y)UbUdKpy>=+r1?I{}AD&&y>5OD6)_gmMq%IAUU@Vl}R5 zPs58M`7Q!fYxA%w7YNG4hBk7FU7mZBUOqB8CNE{aM)+@zPf2w%rgj zfBxlml*4Vk$KfohJ7ebe8Ru!Ot4nH`0q$E)I+0RFE))5ybiB#SP|cDSzQ7$pA-r-SjEN6g1G zum~4g+d{Pu%2xCiMLrV;@S4qTC;k=d56%-VWJ3o(t^MD5HaEn5@Rvll^Y12BW+%jv z(sV8F?*O^QTUeIwPnl~bj|J1O9B_Kd)7)T}9}^`|FMZ_$1oH%9nPXOv#eQfjGlmR# zZ&(9kzWA?*oG&+p^eW#@=qKxZng9luS zWOmN-`LC6b?;3oYEbB#06Hgt*Asn#%Z%pq5SSi`b%^ zukZnt%nx`uI!v7bd4Y?GhHwC^N7k7G&40S?#P{xfS-|eSm4#WoKK3@j3lFU0dFkTe z0AHY=8XHtm(Ha;0o6oNpn#i@5ASborsJB+ztXB|_0g6c{eX@#C%u00%={8@$Izq36 zXrAuB6E4+1?N`fI!!@!6e}gN!B3t>TrhVLFRdWatl;E(~HoqbA9N9b5{5y)y$0*f* zc}di_ZL_bq{)FAbKniawu1YkQS!lyU&zPHzb4luJ;2{g}9Du!j`x`j)+hqMC-nxsIvi z%qCS^Nr!xwOnASa^(sQpk9X+$U@m|jb>p{r7trWh+c2R_2%foX=R~PDVZAqNbQn0s z2JG!8L9k*Pn}NhEronFTcm`ux-Wy56tsK(jg~9DGWDGQA%$SKvB*?k$3s&aEB9Yzg z0ZB9l9)2GGcJAyk@FI+!TI%utH+iHH0k{EbSAy>}Gm|VMm_y}nsYWK+#d4UEDR;D5 z*C+tpl!U0=N_5CE#E;BmhU><$cmT$2(#B{h+4KYBfAN9+75(gw@HyD!_#G2ecTy>l z{(rj-&C7j~8^_E;HGorPnJwTXLBotttd&^?<1ODhXp^$7?OhTjlc!iK*U222pb*iK zGYIq#N$E~&u@l@ceWT1~7Af>(q7~-Q*(0pD?c?9)_92kKjGeVu;dsRL_aUeK1?0~0^|2gnrNSg0wx$R8(?OxeB;&x0W``tcWtCw4qD`{RDXSI_8%m&b5~zQ>JVHjrW?%`l@1|6 z8b+{dli}CWfS6XqZYR8U5=H_%>HR@|rDqR!u*hTc@x@p6JnIqWC>Z(U6U72Gs;t$j zrED8P`yO1>SkWjri*Pq;zkK@R`)4M#93;5R*N9Uv;^(HJUK4(!L!?YoYC`N$7`W@G z1H2Tx1Jb~Q?H{OK=Y!2v5eUuo!!4VUcl}3gI8BxtmNezt9~yl$+)VH-kS@}rXa*=g z0izL<(f&oHS)ua#8IX`2&};6}%cE3_E~9lN4g;)ioQMiFUGC{VDv|?)=aYSanv50aU30rtf?= z>*cLJw$Gz-{7l^xSr}i&K*t~VuBd=M{&uB0u!=q%3)ygR0ySWqCheDu*AQ-_9{lVxL6Ho<#T;1btE8yuG9Z= zo9c^MGV4nGcQ~HWeR(r(^slKt&NyIMcfKVD{)A;}EK@-^wL}Ha@$ZyDvCi%}*erY7 zS@=vX#pO}yCiijI(l4Hivc61QnuLQDPwH*f4}-Cu@mKwtGaaY|-vZ}`hWHs2b( z-hh2BSmG~*AsRC0==*9G8C1vHo?!-{F`!Ve5q# zq;*Qwblq8_anU&iH*K_)&^7gnt6Z|Kh2t83#*6LAkngdfpZW;9iA* zIYo-^uaz+>OX%9Fjez>@Z}X=>Q2sWb)GtZG_zD#>zv=r$4Qm@1EfL#_yG zc{FLAS7nF_FY;ykP5ZG%>E%zQsQXY8gHkYH`iT=fj>X%rlu(3&3TH2p*doJrtClA6 zYIi$%N<$6Z9|85j3={0wLqCjGg(|`J!7R9uUubZyo@+4pMmP};<8YR=N#vAj?JmtD z7yphe3?$bGQm#z6OnH+c1HtH#u{#hGFL1Fim~w)3irtHP9q1pTi?PrAt2cCW>f>i> z7=Fvh-ZuJ}?qKfOKphG3{llBbRfawyX%g%jHA9aDhf%&9mhgZGl`lSIl@KdugFC#G zS#t<65VRV^YeZiJhs|p9{VV|t(YFqLUwhw6giVI*1k!6=;<(GnvJ14*Hwa+oJmEY(Li69xzK0D~>l=V;2B&5V5h)u&)u z5}K^IQ;vT^1)9+luKs8ykWk9hvs|=k)^VQf{1E)DHRc>nttB^Ae+4^#cV4Rhm2l~` z2~8>IQhx1&#l_n>$XAtY;*r;Db8P!uFePwNBlS#6JP2c;grZAz$k9%K(cMmlObh1! zoLU4JRGQ;EHvblc(a_9h2v{KF9#RUZ7*GMjD61f40xbA~3>p@DNIsZXd`f zd87M@mi)}3rc7aP%_`_I5Y8}MH)dJbgc5COOozKfN@jVE4}A{uH4up}EyY%Kz4>P| znJ4IiDG>4sYXTf_xe$k^zvr3CoWD|(MYD-8=@8t{z4Qba2BClGUfGv`ZW*&8#5lOb zi(Q@x`+$SpoN5dq(8%6SVsEFP7Pi@#9-QrJ`NarF2c|WeJSS+|mW(gi_`xfR7*FUn z{VwqRFXi&ryJ0R*?t{;z3o}>44t>&R$j(eqP5oTbJm5&$iKU2ui{#-n!*<{OE!x2dDnw$K*7ZybhMVW?=C*#EftqnOBl``FgU?#A|Q z=o46MdN?2}R&(xgSh_I@Zt3B;uLfGr7^q;qqQ}1k$oXfN{(;-{iek;qHwF1lz)0=S9+V=cyMN%{& zBs#sJK@&lwIV=dFfi8RYRma`a2P0Im5xQ&X{xbnU?wTZ6We=SsZXk+l@@s-=25f-; zXtce0jS`lb*m01%>Y*rdR9L-?v&QTsvMZecdcnr8n*(aMU7H?^ivMI35Iy@ji3gY6*oi_O`Ad z>*jOuVLkhHF-SYBt(<1SY0WKWqOua(ie!)w)@`xmG;762zSq9Xo8=j5xnNwQcUoStVOC=j=qv#r=b z0I{B1+lri!xS!fLq$+U!tHht*^TN>o0k!ij`c|^KR|%RE(uaWNf7SMR0Z*gir%Ein z;c@5c{*B)I;=9Tnr&M=Skok__T%&B35)mG{TFYJmIOYRgBsIW-d{h7(oG0Q({QejU zosa)5{s4Dt0Or0Up^t~M@M+Uc zUVW*C*SQOaz81R_dkvt@{`%zyO&x zSm|>7VaYl5AdX&?$}@J1Rq~h;dw%LKHU7)@7iD&44aP!Ra?ijH zU7ql8x-pWTm;Q*M!-1YEHX0~3+eS^`AVBriZs6yhi}Gw#2${cRvSj4cAOMF&1w@U- zpSpPJ)_-w{R318gD_>H3;!ez{hc>6Fjn6e3aGuXje_^M;=l-VaU;t#_*6^I}Yh^vl9PZ0mb7;JbKm_P>r<%_wNx9yhA#sAU6f*6<) zB}NzkU75{Xq7|(sEjcN3i%4ctY@=rEL^sJ71QBJaP!Olc>1yJj;yAcTW3eNPpY;t8 zDo9_aXRsKNBhG`W(1Q6sIku&$JwdR)$1>ngLmgQTl2cX%kzaQM8){BHGZUHZN})ZpeHFSFb%=@CQA=rybIL_ zgdN!xU+8cBrw~7>4;S!DkcBI_#fhd@_a>uxsuZa zZfPunFMpxN9%L@ln>W`T#g3TF(?=uL@0Mtvam7uP@jf9_TD`V*M3W6z_Sv6eT@iwG z)6U-2zS}(lzIO^T^Ol1+o?^>Csn?cEbb}95c5=bmd|mvGY-I(`w-O7sGbZKx2^k=V z6d5=|vUun*xT1tbPUr9+=6yX%CJN=7ox2u`JB^}|d4xV5>=(_?8JTV|$!e)g-ao{a z|2pnoqkyCF+9P4J60@SY@Lz1-;2g8M-Mqc)=7$OM1IhM@{Url5RY(Xuh9JWaV*iz$ zER9^FyySCWnv;KVnoa;C4y*D;jlt{ht_<*l!k>#u`3CEu8JuP{pfHW+Zg%fL5VBR| z)v)`csv>#nL2qw0FRf<^_5;miPf} z+z8E#>>HjWy#ODD>J3RJTY4y8y`z;6JN#*JO*dp7ltQE@$^JBG#;Ys9hne|tKPG0o zctt0zCaE+V;r5PIub+n;hi-P%2MtXy{Gav6ZH)92EHNZW%#WOKd@U(erq$!Uq=~e4$1SZ|**P``@B$=*?Zz5HA|Pbo zAMoFjKu=a;9VKQ$(KUVm*IcdUMDW0v4vihr;Gl)AhYC1Jq!RM|o>Qd|DLSXsg7MNK zHV6DkC7u^H|M!Iw+m6^pK&hevhg*h~gLV?hVBgfrbmFBm{ECr3S7oVjo%IhsIDG-R z1Q!vQn;=FbHKp}di*vD-EA&DN6|yMKGvHWx%S$?}TY7II<)_hmD9*(zxzT!t5F?d8iNtSJs#I-%gXIrK@;s7ijeur+2Ap4>jTkC{p3!? zJI=O}8uSiOtD8a*_Wb3KMvAa7;@SC1uDFLIdEK;s9|Vn73kSZHLf<1&w6oonHZ^v} zwZZ&DIC+wmksfvTCF)fBN7Op3==@nJ%c@HAsA4N=7XZ-GC;4r6*>s~NC1RG^&Wj+jkODS)@jk!+4upc zwhmy3E|5LzcxXz)WQM=1lPz@~koPut^q7(>MaJ0X1)dP77_1~MyVay?>^lO#@9f(W z9|``Sn~+UMIL;wfTb^9;s7S(=h|&rRKkGcNiDJMq%ihWrp{@C+^P(u)m0|8J{K`oI zZ3?AA351otZW~^8%XZnM{Cn-AL>M2D!`&!~ZcSl%FEeVN!`x8R|h=W40F0=LZ$_?p%UI{1Yr3n*}~m zB&zHYa&mR+gUk@$lZ)nxc^lJq0o)|_oP%73zQF2Bf;N#iZK@U!p-aOANVwuV*8reu zKp?PHz4FWvuib&%{%O%IwH}!HRhqVp=Sp9mM&~B=f<5jN#x6nr*hS1k}FPztdW?IIzpsO$+atE`-`+M<&@(px7Hg>T_e6iJ*u>sBjt{nC13$G%t)`P}M6 za<1V8qPlWog-jWm=jE*0n=t*hGTq@1BE!){^jmWcMi^4F$4ou?5qIpdcKaMY6f#u$ z0~+s)?yX6*D`o>WJo_lAi6+=^J+%D~6*|w&JyVga0J4T_OK*@%9al5&3vAQ%SRFX?Ic9Ve{o?OeY%am)2pQbC^R2eoY< z7S`IkBVY;t*rqnmVsk!;_hTb2&5ePvc4w;w#`3D0P9c`ICcfo2Qhs3P-MK$W{m{hx zk5Otk@wTcU(ZFAR$O!o(nWz``6pyo^zwRr_bjRpVclELr`MmC?>Df-+{(H>v-Ew7lBFi8t6W$nh|=WZ_JG_hx9>kmgkMbYWp- z?~!vKLX$zVTIutIXRZXBrqFXo#z1^?Rtn^2#6L3%=|Xdr-2}?9uZ=7uIjox^=Nw?* z{*(rG1p%)@fboO&|FY$s(}6U;Hi9jN*Rx&V@A@#N&}{#UyqI`?%<9nT*jXU0t_O9s zAHf%!%2v(&7Xs#-U#xU++hDu~1fYL(ec+q@TkGn{E_(Y7!hM|&c*ElIr5uH44SN%E zgn?aG8$pf3AsW*PzG%oJX3AM=8htw2SvfZULw^7M+=@5Y z8bU^Xy2MwlPQ5dQcrFH&D)GO8Xy2yd%(``|&Q*T5vWQm;a9V2L8z>bh8Fu^mP;uXk zX4)3tKw_%GGXv$MvO-BG5;&CED08LbRvs_7R;IfL5xV8QSIULiAoN49QVF`5-SeEOy;K&Pe1nqj*F5I=@dVu5xGN;TMxXCV zyulBKXEr&YmrNQisi04s&a#GXAAjUPwu{gry#jUU1m67==?b}76AxU$y3DS`yVIc& zSn*a!W`dU-8e z;Dln_S|Tf=oXB6n4l~3ljvfP-tn!&+=W{~zxXO9a){P6*qz$^OO&JXqM=SC$a}OYE zXq<}T**){pIH@&dp)a5OsfKXT+B_JT`=AzD@xX91Lq_@FC8;dI~|9WDlOz zJGXx~Tz_cCj+BgXO-89WD_O;{|JNPYzDfwDP#eOgImKa%oiEWZLgi6nZqtlanvqrU zhdJebdD}Xr)c_haF-qC-Cz0MC-OayrGjSOCm`3N09_7tiIF_^4Ad9cj_OtGdth~5Rl49dr6fuK*gQ@LmBkn-c!4!`kwodax zsDQfu*;fE{#EWdT;j zj)?62XMi3a+k>k*Ms`D{r>;=Tgi2WR;fEBcy{}x)nyBA^Gi`N?KF0|DVrkBE063wb ze-Obr!liQ}Z~>2G!!XPG7L~P)@a?80eEn=gkRx6p2|H+u$IbG{4-T)rZWAD>GFQI6 zaZz`Keue#W(ICE_>b#6`5 z1U|Bm(tX`97_^Y&01mpa(QJMXJ;)+O6tt827oIUg$+bG1z5Bs#V>LbUZj|NfQ5K6C0yV`gD!#F`*JR=&df&C%wovj#B3I+r zxH&gn!V;r(*S_}2P~HzTmeV(^gkZ?uA9!)ABcdfP_&$RAapw*QaPj8#=v=c51*|G+ zAAXq-ai`1e0(bY`@aVn~Gd9RU@mJiHSA*wRw0Abj+>ENKad}|2@O{uX39nxB5yRXZ z3CY`Fq)2uwmwaW|YTPtU6?Iz{4kqKDUYg(rHTCdP`%yUc>#~741fE)`15Emi4=y&Q zv2t9iKh$NvDhWNzorSNtwD|Y4I&dK!v2_zaq_XAdxcw)1)tCRSdEb>rG+nd_Ud%9a6#0K9B3JA2{9%%^RWPi z{V{DO%cTK;VpqP1wr$V1^YkeR{?8?Jp97bi;Cc*VnHO7xr*H{%AYf!ckx*3p&ec7c znNzWp9e8w9qJLmjR^fLg0$XpC$_v4FU9DN^qoxC$_wE)rnF=-@F_wA4!c?fW5#{8g znw(f{k4i$NJ>`bNL7JQBIod!KYM!T6N@NL2#b(T%<2=LQa&RlJ?c5Q+eEflytJm;#vg&zoj zrEUUU)w=gz^R~_&gd+&}3lRxz|Idd8nS?XW^eR$JX;P0LwF#IU?>xb2A2F`8vycv2 zsv(7wQps&;T5&(`#tpn5gDIy~eByvIpD8#xC{=8|T2WA_zBy^#8tZ8pXK7+Y;yQUg zG@>P-;R6OaPrJ)S{Mf@N16d#%^aibHs;rszF! zx>4F#80fRNkfSyY9?3tA&OqX1i%NNET6H)9< zv$G1ikv~ z&9c-h)zCu6k|B*I{QS;DE4Vdal_SOk)wXxv+1G(FX*@6V%b0~d1VpoF$%o0l6Wjh` zzs+~_bg>`W$pA~>2y4$>1dv`^l^C0o&U<&2X#o;iSmn^a^Sp$g%W_6;S zB^u~__7f+Of0Y=nMksHzXL&9RJ^U~{R3A*jq$7MK;Ym4`h6eRJ{dJuCJ3mT8G)R~6 z{Ye8&_H3dsf{KHZI}ME5naM(yV)D}xg@C-rpE%}T%YAV3Zd?-FSwqB%v|6RGR8Q|E zAK>G?w15~{4t;3%r~F_GJ*goYr&Gsi?(>if^SC7X zC74u3cMFX+JJe=io@ES8{n%u?uLwo8ld!1ZF#u`0Oa1vv6QYK^a)KzoziXwQ6LN%c zifT;-e{H{2KqwBP9^4}Ns0R0K<>{(1W)^x-PPJ^)PmY&&FMs3Qs$8N+OP%{XqfhcEsnc~2&gzf_vv^jkTB*y`jL14pUaJd9Nf1Pnag3+V^LX3 z6E>gmK_Ns<6InlDk}OMtUek}GC>S=n>LIRywsNU;*_H!!+Yg}H(KW2|0fbHXr5tw1 zle?3&!Kht_iw`i*joe$u?3w_p3=HFF&B5rhS<5qs>@#z*N%xKpgCZr1!B6I!=MFnB z?fFG!3mUXia%5mMGggtUYP9MLfmuEkwE<-L`44VGVMy~Bh7`hzAHi;w2GB!GuGxP< z4O9#ImLCYn!>_9MRro`!Z{xbdz(}jN)U#<}8T!K&1mobd3Z6 zewD0g=_v1H9CfJ}C0CmIH*dc9Y$zRuD%9D{REf?S;VI&9(yv|KQ?}*Tv>7}b4(d~_ zUNRV0YdRqip_KgteOoPNH3kt+#Ka8qACtxFrGcMcA)FS7YC#vC9}cQp{|F$FyVcJv zra`Lug@m;`y1-D*z}~xW-B8MiC9_r~K(}m`+O$NCJh%@%~ zADO;g$r+XkCHAYqb9S&_5wiU?u*#oEPXLL^xl&A@5~4g$>op4hN)hu;*0-8GAr6BG z)nNrsMb3fg*)a1ft$B!phNmfyWwy=3;H$d*ADX2}ZyE;P8Z5uKY zd2eVKD*5~R{qvYT)N^$n9X4Za#y=E~hCH;4=Em8?k9}Kbtk;&DkG`DY^{^!4mvbjs z)h|Bzj0dzF;0Qd~<~6aPZ!ahJKtlgk6B&Kcn(Mj?QayVMD@2n}j8wCdtYWZ18-ICT zvmT>7o*#|h@!c4;8u(XlI$wCjUCeHCz_y5GYO2Jh$D|gwsQZLAr|?MS?av2hU_t@% z6@Ug@w8HXsXlD{Imvz1qh!Cy>9A>?1zkJ@-dkkCUBpn(}uSr$BpW!93pkGMuESPlz z(p|~riEuH08_mtQFag=yW6lK{H|Xu_Q)&?XmRA{rW%M{2V4J|d9ZH84_h(6)F&@>T zSL^o?6Q*{q8TE&9`IX$n0Hn~xEZ7qXxp{B34MQ-g(WO776UU(9FbMKBd$4k>==Gw1 zUAZC|jnQwB;OAExu`N_Byd@qxb;Bza&9@rJrCTvd{7VWvvv)}7yRF-eQvI1h71LDS zFY<3|jdhdJEpsXsN`aOQzxCdSB1>i5)1NH(+AeQisQkoc=WaTC62OaG-mi^D)T=19 zHWS)s&lG*eOsCpf1^6F#`atAp`CJ zK|sF0aPMzRWPhVbq$wSzk!!X?b`{*tU-CInF0TevG~wcgUsNyb`Ey1{*#BE!!Q(Mx zP)U2dnVRPc-#;zk1=TIDwq%fOTziclm z`jQs{?%}hOMdB|f%z0vn*h!H(`dtuCg9 z>s>4M>k$f&L&#WCsLNEV4F{sMi)Ij^0S^BE*9)(uabCIcvOy5U*-E=VG?OQ`Ef^*&( z4-;k&yYd`!e}1j@d<}Z9kR6nog^ZlAr6pii83Je3TCC10ij4eVzVrd&a>yIq60#(0 z1ZbZOpA;`!GedEwbUPMOT4^byb^k4e<8DEC6}!9Ws06iFbXZnN5Y?mD1Bid8jh$rL zfV5AMoJpzNz+!}>&m_QXculntnls3S_ZRgKx&nP(tMw^!1uCf!YtNntM}`NqVBe zRo|ri0Az^vXE(cWwIOLn5t2!HWm~vXfG$P+8snFlM2*71_-Rg1_Nd&zqqbrrND3G^zc zV@K|EEqoEo*?99Ew(hnA#kg?1QN2`MgM5#%b9+pA$4B>vFW4Spj*F^v?E!bIhB2G~ zYJ&BW(mGMB(>Q%A!nj-scWqUzx`mCKy3^F}sgz7S zB+njs|80iR-Jg~*7(9dX-f6h!u^BCt#k{qI92;?7Tf@LE>&O?ltVg>}P@ z1fa_jHcOLiZs&I}Yn)!p!;>31Hw{nMtHmq9@H0ebUp#r|+Mj}$ptlSvBE19UIHfS8 zIry68;?KJOfh{0p`nFgWrqc=E*ndXc>W3nGxk$ccEmbJXRo%mKCfq5u-Eq;yqWFf1 zbM$AYJD)QF^)W5%0=0cMme8-a&#wYI3`p4D)N9|AN}Sfu&s}mlkUjH)0kHdDUp2ci zJ%+d|d7D+7sJgN-Y#d_+9v~})^LY%mQP-C_Vu6HIsCfPHQm0G2mkf&}l)Ugbe@LAH zuS2+mq7uW6RRw@}n(=wSxL*TxoXKJj4q2a_8P$tc?gYM^s5J`W)zML5OW3q0YrPl`KL+uzTUGEE*A!Z( z2~#=Ki#GG*CU;P@x3 zd?E%_?#j{}kc(V=Edq>`!>Avyci(v-x-`|wNWRg}wy5VYNF*sQ2vh+&m5I|6$Q6@O zDKH;FO8SW9?FI0e?UQW%rSb<)_iEZwBfl4%pOU0=HJSFXF82RvBAqTZLjy0kJF&It zIi`?v6n{&SMkTY`Y0+Q-0Jv%R;2dzs>o_}Zww=|v5~||ul|~FMX_uoC74nsf{q%#) zNI~dzdWQjkCh^2$O+iy#6Y=k9#G1gJ?Jm8>8i~d;`GM&G!ET6~O?QUoLoTwZ%(}*kl6JwyGVV{BkCC zu3)ZS=||TGkFcky8or%Ns5+wq$z0WV3&q3#*8*aQrSO<_fb?p}K!<43Lsch3bJ!ZM z{amKC4lAnixRpdDHt4S4hF>nn_r^4~NolPRD?DL5+wZ+bUiQVsNJio@;3}8Dv*gE) z6U+HeR#T0Lh1n2d2AjATFa(?+47+a@2v?1S{C+OEO3zCv)KWN`@}+Us^QpbytHAJD zaCjz+8z?Z9rGFvI zdzwrcAc4#NVF9yTS$J{M$o3NU%z(AQtPA=f#30qOZ~Z_3_MsRcWA+W&!R@wl^ck1k z&TDDHOrc8qF&IXtR5HTCu*6}9f6+q5g;05#k#;dYkIYkLyQT$C6HopUmS6iVc#!@> zWa*8Dt^e<=%u+;pc)5wP!Bo(_W%vMDbJ(b<@}SGz=&FB1tM6Wd*{3A@0Fwo6U{$Hi z&A;F&H$)rvK;pN0cGb0|-Z=y=FXwvt=aRic<>h)ll0?6N;=DTw+xrf`EGy7e6ewzN zb1v<)rW-f)qEn#M{9Yi_$P=qpr0_gNs+*{8JOj z?;Fa0xW4tClwvaBH-9@7$2$>~?sP7?RiD{-rVE+s6qBt4sy&<|91hO!3i?kiBcO9L(kRi_v=2Np2`?rJQ>6r>;SwcWLMS;(=QY@+6R+{pIwk)C# z<5`}i7$byJ_55+nKDr?DYrr2-YK0wlAZd<}~`prrAV$dUd z;kt!&d8M%vSING)fw|LGW3aksEFmL}(}P9#Ov?LkLWC#lm`pqNir>5H7x#?!_i6a_ zIdXh(bVfQ#1l+mGpskS&!5_+EYCXPhAg%_uxzvxXl6#`1_>r54xZ}0>;hQ>uIE|VV zpu}LzL#xnRnKuW@s^B=yFhv>sOp4#*BWV0pD$+v8i_e!cCEl^%qy}@8D*Q1cAiwem z`PcjVC3J5xWtj_h{FxF|s;kT;a50HnA$u__^nIUdd-wN5VExsAWV^71>Rk;6gQ|u#i-p1on z?Qj|j>kRI_7x(6d$fwNtIjV49GV;vBa&ljy)a;~J9ovYD`kUKllCOeL>!^)bE!C6o zw`QYiJ8*;bK=IlN3||_}x)U;b8N^&b4IeEV%eHJcj2Db$DR_j8p0DBf6Yu2&-6ZQi z>klMR(cRE+^iB@XxEj;PGP}qHWV`w)&F2gF#W#!3>4`^;wtHedn^fqZ9N}`RG~rdh zmoc7>!bPBhRmv)QKR_|~KdgMyic!bO3CA<;1=pAM&BNoQ-6^!IK2XM zx%6_kyNlfk^%ah4XV-fv;4a=Ae%TMUP6ln~5_3g_ZYBqptYZx2&nQ=n9B(qJ1r!O& zepwg37TZ#9gUWE$TC+KFWj)Fo(hj#Q)a`DKzW(z#cJf+~N=CU=^LMJ74>pcA{x}3* zhf9c8L{%9B6k$s0`SJ8^wnt_l1ZXQe1$@-CgU$9&;>r+7yI}sUse@m$^hBpDk#{(u zRZ-O9lww+iO3-E_+V2;<2v7hxl}1BZ$8ihF{NnW&FXG^TTOAL5RzUe=GnAb(8KG7< z@w@wg^J1YU5PE`B$6n>FZYJPcfpw)K*$nMLkj<0dOmN_Wze5$L-BS(X!M`%a)Ij{O z%%X)68Od%`oP@@nH=}8;EtzD^{-Fa>pRg{$S)LCfzPv!HDNHYZZyOML912`~vSQ+o z5;aPAxyg97;$8yw&f z?W0qs)L;qTa>g)5sC$G?ue@Apts&goZ<+~$DTQJI7Osx2FTH;j8O>%MSsf^I8^W|| z!D7XpsLNs(=YDy2JOxK8b&}TuCMNhGX&fvJyB8b6OR1v|sZ9}ERO?xo!Dh!W19pP9 zUHgu6+=ygy{_hp#Lbx5gPo0t=h*v$#aOE&c!LuKXqgNR?n;#LodNQ0lBp?5_-IqfI zw#lu56$OGG=oGDlG&+ogfu!+0UZ--85@BpRBi)G#!Z9!xGtp5A?Dq1UA?$erMOH=h z1imFUww$s|CDV6?G{D!5s4BY zC7ZDUq)+=rti5;(_U!Y2YXfflXCUA~1}&RF^)_1PXSgcqg3$vP(a&4aR#ZmFCq}prx!?(Kn#ZqdEkp5)i0&VqN>&CL`eP0M zWWinG&JZ!fkfP?nxk?$gAuv|y1gXQEinLGtdfnFf@fSaj3XhVDPc*{yu>rguuc1MCjw)2zHm8rA5T4*H9P$KQ8XFM%z@f2SsF_wc`^V z>g9N|-CKc9f7Bp13@CGRB@kWgc3+Aq`2wmjdasKl{zcvj2Cz3-H3Go^ccO^mLT?Ni ztTmtk-mz5^wtAaw4(OsPmZbb*ygy_u0E6v*w zm#tB=pRR$K5QFh?9a~r+s3j|cTnG%fhNMsS-GSNI+kUe)Z+% zY+|T{4fXH$_s^+Q)gJXMhHMj0bL*!_!~)zUQ7Q}z6B$wgymm>F-v+BngwJzq+T<~( z(bHO1!-NCLj2uB1@`D@LiQdA?ABsXMmRR^gQ2leB3Av!QDh@7|xsdY+Ieyq0hTb#W z-;jKsY1nQmEn`8f9pfi$amCbNfETyJxDfHHY4a$*%?LZEfZaUbdGG3|zSWOQ9p_nr z1{DC=S__%zPE}d(#?=DuhY=E$DjCi`U~wi-PXh}E<}Y`JvsJ2FP?H-hoLx=m{1;4h zu%Y6t+E1GvDzXwP$VQ!`MB~4x(SxW-0iC;Ksg0ZkxSJO8DWCC);_?lgJW=f{yzz%| zVY}y3TQxr?Um~7>5(s>$P+*T~bj3KsDLT5gOk|ypq9d%$MMWCLUvgsrwtk0#ISSE^ zmrhzh^bor%0}zGu3PoK~v&ZLx;BLIen&4xUr_eP^Kqf89ZumhQ%no%FvHcKo z@0V!}@rkQIKRX}DEsBl@61W}d4*fxPSgC+Oo1KOp-ZxjrQ2DmZOXzCj;R3{WCAAj) zhgT2oSRJ`{2TzT#Azy}_m{1oqU-(Ml0fvKI>&Q&nt{jWFaKe6lh`?h&NGXVM@_K2{ z7z(CVr$;EC7|=T0Y-+l|_eLn{qhfm~rH&xkjS(RQy`A0<7uZLg2B8Ng_3$QA zLU#SEg-RAYtxmME9`U}<#H^6Fqjk$4=m$t(y)5|dzrEIPr`#D9p~WWacEm$>cWQK5 zS!JU%^Z2|A2u{uVh?n`fHHO*G5Iuf$!zt~bi>vL(7HHUs3swQmtP`%^U)ATo+JRCqCu zplCen>N_a`)1*;)ZLJKaJN+#0tuPeC>+(d`=H755c?akVEW9UZbSwu|4nDqD$5ILm zZ>@~n=nAi9oZ$NGnByx8t(E|%>{~l^F5c?%>{OQ+*!V!&%sBt5TF7%m-2o@&VE>HO z0h#j`u#lN_J!jCyMZgdfv^OY;YP)fMOdj=IE6mRny)!68Q<%xgX=waGWTTHk_c6Qz z={c4qvWil*(1kKB36tTHvs8EV;`%$#X#%MEMiFYOeI1QFJuVMiu^3j=zzlfU?~N(fKaSB| z_f+b@7zfv+KQa@*gN@Fb71{%hkFuam=1%JuHF0 zC=R)74;EUaG?{O!6@d@LN%SL6-It&CF@dD4R$6mTZ7;kWA-m`~Y+;8J4O%fmy>%(1 zQmuFNt_nLM6|G;Pcc>@PTQZY)3FNC6W*>P~5xQavJl?jdpP5ZhT&JT8s5uVMPS6yg zZ@J+eXWn%+C44E{8kj62_47qu*P(Du1Dw(JES!)+W0a;puZn4V*C5fBzLEzx$7?716aOEa8`O(US`F8Ags4l_$uajE^M(XPQ@WXklB(GW@`hRknzXM^sTyk z_HRlvV8B<$VNYx*ETYUQp7T`k8(K$R|21$v;UgFTNnMna~{A`;mC zKDm8o1{Mjoir8#Q-_f@M6L(bA8}813vc*yQQOvLC3CWa+K7V#*(Jim~ciWCLLEWGA3L5`2I6ZfHirjh%GlM&UYNJJW3?M{(w+F|qvS3Nwl!yp_rVsRsUTxRl zP;D^y1)e~TMYtroEBKGl6LJ{9DLV=HdE=;M9lc==?HSTYCN^b`dn%F7-B#1|fXkRQ z&&r79tFmGUOOGXR594nYDMY`wOaEDuT>GSi=iNmcBCfRj>Jq{ni0{?)9(A)Zk4gwh zR;ZXvaSE}QnnG>0s(E9>Tdxaw1iC)=2Kc!qyWvR9IF&`XoDYQsv)m!;aMotENe=ex zz?Sr(OKz3mH{XgtGl;Tw;sa*4_n-gF>ay=}DFB9yr**LkT;KFtCL(DIgy+d_H}mz? zrhT7?p+^gc6ntK7NK8;$;%0_W+e-?$0h4}|^(YEF@rLz#VMNY(_m}kP_Bexx=o!B< zuVWwq)uO_MzJj7BDSZK;43c60I&yVqqKh1jk@g|Ba_IU+iFR6L$?HarwE(?RSQa8M zhS&G@(c+l{-pc>K@r7BR*lJ^U*e=A6l{(Qj6XSb)*+#p;mjG)hh6hK=odL}t9!TSJzATY-e3W$IIHfZlLz|2(Hz9SH#>*YU;nq_cB@sbd2<-X)rX-kOo+U zhF>>mJ+=?7CFc0Y9C5OxBESEtGJv0Y5Eg>Gl&C?CDd0Xy1=dD8=qj5#V!r%W|_9Dq?kE(CxkB7Np^Q7*;0uj?aIc|;UhW)$JD(oeVkPd!?cujSg^8v%S_ z9-hT41GnIt8*X#jRt|;yU$t8@>clYomo^E@RF|z0Y9MbdS---Et zJDfUSj*jW{K~m<`N&3>Q%}HF4+H*RC2)`u?FlY^mB1?cw60WEUwaxYm(dX0C+J#n) zm|ECWvWw)+5}#ympf4)Ic@W*KL!J*KYOsBGC-r}(Ii@1V&4_q}l41ONt*{qaRn7W{ z9EcyIF?IM&NoQKY8DuKZ%T)8Jx2~nJWI#aE5}c%$vBNaRt0-m0ZLaszN4m^L8HnV~ zW@etieuh}Szyi3Lkj0Vgu?y?!07G^n#NC0B;-e7Lx|HE@5KcU(v!eS-;LrfpR@6$z;D z-Dtg?tw|p|G2Hkcu=r9MQJ%RsGGDHK|DH~X=ydZB$!1+h1wXtHw92=SzSLE_HxpD@fU>LU(JDr{?b?mZLUg^MQ59y1ttZwALPr!+9AE_>7%;EOzu zd86qvr?6ZK1wq6sjrY+dxXfQ%S#=Ja76ZS!FfMW8ZT{z zoa%%A)+B1*1Sur)-3LeEQGCXkLLY5iR0^ee=$5vBOX2>Tk8K(`G%ayq4M`M^ggj`2 zZ90#}oT93$Phr@0$kWQE6yAKhTf ztWfE=)(v*_s@XO;oR{U*WDM9Zo7M2D;Rf6nB{yW{v_|Q#z-5=DQ9!oOJp-AwgqmLo zsfikVsbTZ9g}0UPMA?5)oqF+ewNWt5*U6M+L1oGR8iGxz8X(TJ2UU{`MkL&#N4W5+{uX^zX$lO=(`*FA^|MAEy2UBY=@(OD2l&`M;Q z4qpJ-CS!>3$N#=%ydx3NODxn~D3yc*W z9oOmwmfp9XCHJHXh+ zY>~v>pnj7~je<+8)cGQh;Z^5b^CXbKE4J+|0M`aP=}L6ngXP7|fnMZcSIZKgN)_mF z03yi5Y>Up>Vo&qgScXaK(aEFz;w}|2m_;X8G>G0DXGXoJ9m-C)k1K=3d~RqriMzku zfcmR?MTc^R+Z{(R%JbHMQJhNB+pSfgr?Wuky=LDEYq6JHQtG@rn)`LN5C9NYe#WS% zhL+Q60G$=N<|xQ(YTJO{mL)4JY}I+gURRA_)g(% z4`0*}3_UHY=eQzUb_GS7wB$=eK*}+3{_fi)N+?dX43Gr2;Jul%9;798MX_Lmdy_jT zafI#)OFLHd#NHp|K6Ui?fz?LPOnpP@Vj|kfK7wc@Q8n5ykaX1Yeo8yZkY-RO#UBo% zc<&GF60k|{Nm_2HqH3#FX3z^W85?|;npIPT!-vbsW9Xm350bKrb5fGI zi<=+>J?IWiy24*35OQ$1Z!M-3>YhiAZ{~DibM38klT0rR<})8!<0}Ps?&G(a$)Gk{ z-^v#>or`VQo9(sP!1Qd-{XYR|@z}<=YJbfJ+&39ul{lwWMj%!1UMcEg6<($-pKTvW zuFOm9arQF*IE{BxjmZII(D?I;`GsUVeJ8iJjQ5pU+O9DJJUJSO8Ywm@yd+9)v{}H_ zGGK&&**RNudG#l{`uvk{ydOnh-~ z!sNYMDUg)7pj{+=Pp+&pUrI8ldMRzJ!+JwUg)V3Fv329r;{TNajlk&upTQ`DbP zGFaM@sG#Xz2BmZkPnFrP#xFbM;I;QVa2$&^TNXK62hkoi^I1%Z&S7w@SgU zY(2cXR9yNE_Fq{h3NATt260bRc=*hhDYf&Fz0b9jv7N1Ny&Cd%F7Nn(3~_iT1{KE> zMK$O2Pm!98Il}^kxcP<=pgucFv(`ECS&M&|G%20R30fFuYv-zR8HPJM1=0;ZO-1W5 z-}YC;0zZ|V3I2x}o+rLUsx=Cm%LDjc7hX(+ z-hZFdrV85-sWu^kI!;;$J6TdXuINd>K`6D11kuVq9XqMxK+$cZ~z%12s^XekA}s;)-B2Wx$u)~~7B zGMJffXbO%gyt|#!8L!O%XWA9zx+suDF@AoJamLptVvgbagY2^MHP8 zqErzhWe<3wOqJ6zU{6h1GwB26J0Wdyk%t6POxeTk(!{Vt7W47qdbrHZi^YV`VVv4^v->EYs;uO$>|;7&-4aa3WeK;X=p2D4B$uEF z%P3}#9?t4pAELraL&s6uXFx*=eY$UojWhwC(5jgy!sm^9py`5%5#xJ?YQFLd%Qd`5 zyS4{n`}+Z%6Zn5VMCQG8<4~UpykU&K6J{0cN6)UKwisqZVS35}L!%JI>5(4m60|pzqpj0LVUDMtuC<_GAl4d9wZ9#ofhu zA8_Mo7}@fpZh6d{FB~VyaA2#8>Vv-%*%mdZb%Wr)G%aus zx6)Si*Kql;QsCVrIoj@Wp_fLDFZcXZMb$=0%M#2;cf(XJ1-M_=`!~!=2Uiw=4t#i8 zaXzZT4p7Ho;(kvQM#@EThjeM@-_ezzYutJjkY*8WoEQs1Zud5^+PVX4kwTurJa~?n zY{nmaS3*ohy_L@^TV4HH2yvW@8j5yYT}#41hdh*P#x=D1n5AsTF{h*UvGrsrIU{mS ze6THA_YYB)HMqVL4tjlkZqV(%mZ?3$FW!DNxR2WVJ)b{klHtFC73%Q<2q_|K?#qZ! z1}+rT85@|KjK~G_ax`o#1Ulm>&Q*J8Rtfn$?Po<-et#E2Hf@e~yesNKeCMa=OW&g- zG^AT;QW1}FT?tlMFcS4sx=B+DQob=vK*%W5Gx1+&500cb@slK(d(X|tk%PAPI@1$K zVVrrW4o@gI9krwUBkiUvMQ`AJRyy2!nffXX;U+?<3^%&o1P+?@?8m);`8r)2wXx%t zGcb#eDry*3qNaKq&cS0a2CiK8W!tVtPow;SdH0gDG)qj4bNJxcXQH8tTMW2Q z%(Dya?!a~zBoenpZMKhnjy#_+fRbniDIet&U#ZpZ3jxFoNbj-25^T*hgSM#H_OA2A zaiwd8U9I!)uhTVhBrxyo%Z=2jCn)&Ub8r_0(Euy~c=S`MXlf7JX%t^h^85l_TNb8| zoy1uH5pU(NWDGB7m)|CQQhVBEv+xtT_c2RUdLh75=o-6@YielI&owXu%CC>xDv9E^ zdTH`kFjWucP7{SDuAyVx6~t9XQKTq>UGb+76v^jD@V|jltN~P;ub-g1jFG{%Vh}~W zBjX1+{~cCYI78U?aITEq${AjWU3na_rXVE|l0pGv;dIIs(`0AtWaKlrC<|p2R05ML zq11?{l+tA!{D~8vXR^P52>2wu;UO6#;$-hkq)DZX1ebCND(lLtDtYS1o?Ja^UU8{2 zw(NULE_T&fvi`Fb@r>x0#Rmrd*EG0@yjmWsi^o0V1<;=6ZVq#5nx$Q`VFycfDlAjsHKkCxvR2UHC>&2I0i)!Q)^{Tm z*p54)STkXv4`%gkxv$fYPnu@y>Yjo&WN#3L+_CIRDgGkq&NnrL;aM(J*oWpc#?hXU z3jj;dj^XsxHfAaf8wlcVzhb3gYrN#;=*OD0Wt}8JK%0X0f`mItCM#{Z$C0CC^zcs2 z$fKZG-8l}pWG6U`=g39NyRf}Hnx|yxOCuK4U`5I+OPiYL0c#>Cd2~CbJ@|r*yu6wE z%D%eb@T2r+jC9N$AHhJWV@3BsB{5n*)t1hYVOQjEQTyq7FH?LNbld?0nL>nUWifNC z4EZU(3zc#|$FX(A=kCwb=ox~Y-Yo!{N73;Dxg2o1t9YAP3IP>j zEoMI-9YUB;wg4z|mLeJ&3Zfa$7=WCN5YflT8%1?uC0MXc@dLtYl;Y9(Xs^f`MS#~0 zQe&tJ z6Jq^8(M~#=xI{x#x2BDMZcI6k-n{-g5x5UY!+WqX=^hP-_M~zHC1yvr_xpx{Gu-Km zsr0S`I9(swO`#tVbOCI3Q4-pm$Qq;qs2RQsNlFpr8}Ew}c7Ssx z3Q9al{8izz4$PIZYfX2`wMjZ&?jgp*oL|EhTOnY6B}j`j8;5-7%DiMXt1c1|S5f_| zBFjz-MTInKAA8m>sL0qgF08&PB(Ooly-f(4xYROO--kjTxHm~L+F3Hyl}I@bZW%&u z7e|Q6^9j9CMv4Ftzh(#Z?`Z~{3hQqzB4B>?IGZt&l$=3-o3)AM=Tjt zfqkA&4;3S_2nMDISOog4Ni9#&@`87cYP1Awv0i7AFZF=xVmBSpMUO1ki>|an``W#m zl;rRz%b_(730vqp-i>5XOpXe{sE)^gwQ$a%}`6GruD__@0ZXeHMNgB-6;K$*Shwi}lNT<|Qom^znK5P1JjUK$fhsz#j zES&VF=7QlZ4}^11b>&^R4;dyU?W%-eFJ4nh+ zKatdDfJ~&GK}yq6Gvs%9oV@ZBUIQW*ZC~mDlMMiPLsd*LAck$0i3(TS@sqW|K!`%v z{5ao8@@9x6*p?^#C%7%$hvr?hvhJuyd&)`2I=4F=tq2>a4uC9U{uXUckif1`*CPD2 zA@I}{dR;*36jHw1Uw=6O0@ zp8laNPOBkmQ^SdY#`jhT-19tNN`!<1l**VHSF4%-!>G%lk_G!*n3P($apH!9;8Y%r zkVgNt{O#uD>A&x2`t5V`&ec^&tBbxeM|l0jVX4LDK_O#-qwi5Y5zt>SmZ=ZI5?^S< z(B#_>8NDj-j%A?Yb#gXbbkv?VtNYmntdN?EY2kJo%$i`oQZl+-$mt?`m7cVBQoZm$TsE!vtC zRf*(9FAmAjYH{!X{%0OvL!+P^>N)hdp_Z|&YDly9U1%v@*>F!D8_j2H?>jF! z6Uza8$c&@S_V_LpDOdSMkvT4D{+yi{mq<mm#r7M>-|7WA|JJK=9<3IZ>pzZQTMGnb5(SMbVkr2ETZqb4c20x zW_3oy5#4;A_&CB6(4Fdo!{$wnmyS~%eFI1YV)vvgTsNY8HbyO6Hd->LhN@caPG13g z-ANMGZl&1)eevy(Meva{&0VrG9xU&fGu{)26jVqJkbqA7k$l)2XI8p=Vo73z7Pfi5 zp?Vh)*xiC*k4PKNA{Kryuy|d!77?CIdhmXj$YECY|3SMOW|Y7cTp%pJxj80I*i5Zn z_OX2EXF)8&!p3w`}d5qM8ra>qNX!t9#o8fBvgF&@4)O0w{G#6u9jzJ!)dGnG$iMgS~rTE zvwe)oSFXm0xO+_mGg#q?TQzn7^bfH`81?=GGK zFx7eO*FME_jX;j&Og!QBMfZX#NkyQ81z9j?Ox-uYQYU9TPWj1l#MljhtvUeMxpyB^ zWTg`bl?C<&ITkF@s;F3H0(g@1Z@$E;wc}g;mDGdmcYW%H&kS#!VI^p4fXJ+OG4vTdbwV~3qU1p+ zmy)H08-K_Ffq-`u1KE?s$}vMk<+#x(7WXv}P+W8!?E9z08W)K7L3DleI`?9b@J`m) z-PIi92|xDTo5kx<9_r7yRsI2yULFMUmo@e%j09S+3)57lytw#)!18gFgb(KBoj%ga z4Vy7>(Hxqdf~WFFop#hgwXk@Oy;ku3DJFooF=y=QhJ0949dIv+tm7J7Rv#|3c|T7o ziD&8A5@@dNA>8qiEKcMI?faFU&#X-*@|2DvzsGExfSlLh-rUPrX=N<(#TlD%em8>M zFR{DUoj;;p1XnDAN@XXZQ2(LU7W>SO6g(lH#+uapA{iJpmppk~oQ?5rWv~Ye9BTDt zkq=#zVt>79I0$>6HN`ibV?h*Mf5V(#^9*D6Gy%!GWSe)wfR&@$%B0Mj1e*T)D_rDb zupGU1$m96CTF@nYSC);Uw4otuFDK_MFv(^f9;wNsv6{5s$?({cXFM_r88Yn%VpBlF ziw|JuZ9_bgO*CEBalwo*m$*$|tpIl14{d%pngdm|{XaeGJEj#Q*)&`4zy*ZGB-iyD ze=`hp7TXS$%hIeyk1?PYoahKCg0tCpXJI?FSTjUzyN|*Z z+JTh3lf=&C;r9Qqy^2AcAEETTd$2<9Bc1+mQ=~y`{&b|ZC~ga`n-XW%U=|Mc#N#ap(((ltq?^phv-Z=S zLy3W(nfQ*;efOuf{e)*%JzitLRKLro@ah}w&H+zkSHb6Sx__U~r4VP6OvgN*S_|hR zb@UIEEdJ-pWWrsq^H?0fHGZ)N ziQnzy7^=8|rJ5b5@ZZoinvOVhjtfD2D#BUE=nBzGZ^&X!C)DK%YeJ59^Kaw3`u46j z)-9W{*20nw=2_wzEA+zNfo4=uwnx5k~7Ro7ij%3QJDU&3_4w4IcCa)4HHzbvt9y`i?3!V~1HzbGN9%tx9ao(!x#5X(|snWS|Hc$q4k9}M*-rHOE<0tB*l0DI! zi0+Fv1n-6u+jjA%uPx7_0$iiC!R38%uIrJQd0p5ZGO{>a=eb|`#9ADE&!O(lYYtzF z)SUGMA7dAhItLMjyC=p!gUf>EWoEJX8zCV23zAn$iyj#W3acCt5QktUUTNOg~f0q&9-iHk-R`w{mj3*3v3P)V?2*j}P6;+jSS3p%X(l zR!`$S)hwWQqWa2eRh^>!K5PK@4yi^6pke9zufZSFYq!Mpq{ zt8q1^?kpn_R@MjD*T^xZE>yMsk|7gGvLDAjC!IA z1O(=gy|^S#iHJSSF7mV>jeELh_5eXZzP~6&5#$|V_jg{uYt37|`Q({+zIs}9-Ri30 z&tLn@E#hcF=<4|;a6by@damyxv{_h-*5hs@epbu}MzWV}hRu7_?Y=IooBe%@SQyxC z>!%z&HT}|!3^gN$wnRRb7=e4#H$_WdaG954wgxNJFrdMW2Jl3%U&yowA-l4s4YCB> z+WN8@-CmO#+m}{@A3qGL!A4=?i~=Wx3pGUhGPvX*O9g#^f@ZiC3@%sIo_G#avs2gVT z8AYb4lR;yHyxM zo`&8?*hm*kn~}hBJR7i{?|xDLS`}r}JMi&weU49h@+i~(U+g}_P|x2A8I3=Y@QVaZ z(w!9gxOS_8Z+nC6OUtyLUs-|mkP#%$$m`ZbGv2wZ2>SbO!B6x-nD?K zHm3Jl(r2&oM3m0&uq4)3#6c^KxuVvlmw1C5*x*9^bE}+G12GW%O0Pg&m=&eOh;J#Y z$GHC$C>MPaeNu`Bk+9s8MH1lpXKU?{d&Azcg-scV#xW9oxgG@t9; zdv?O1Y%CUE0$2CqBc**dgbmSYfENGSKOzkqhKRLrkQtOcWUJu_iiw{)X12;>$g`%! z9*Gkp3ei8B!xnukIL2+vq>UDDY%(a*I|B&>z;31eaw*OXHUTAyz!cC@+AJ&@>N}W6 zsfZqYLjxJtbh4nX;L#UzcsJz_OjGt=Ed(=Xy+UylROJ0SIyOy#ui~^<<$??|ccj&- zMp=JE2lzl_upS>G?-Ux&8;TzUY7H~1U#@xkVWZ0Bak5QX8|Me4I#hM~(!YuQACAfh z`?ObqEc6I8yJQ3x8`&cEIMkpXp7#fgxg(GLUbc%8+MY}EeqbFO9-yeZ3YF{H3Q@o& zVL-F-37F)vh&w(yilB>N#VHJ1uG&1Wr(OX$S04&9Np!&JKddn~_HO0@K6<&|)OT%o z`$63t3&kA^9$Hcl1eSu}QHlk)VhOYXdm6w_5!Rg~`jyxT3~xc8*ms{X_nmhI51h16fMZR2tb9NgRaw9H^_ z?lL*4XY6^VX8I=YX3{NE+mGY!MM_LbgeK;CqfvjcsNh1ShY&P-uRePuAOIU%+@f75 z+hl`75yJ|hA|1Vy#_Q5Ia%eF+$zqhk=04XNM$RB2=HF%RC%d|MH&zBFQl*BLtNt-F zTUA$6rR?e<2-eW^j;~lEIe+%A$U3h}gPao$FxjL5POpN_A-kZO4!LKida!zh(>y_m zs8ZBM5I}Kvm2Bxg_VFLuwf>tkl<_D>8wqzvFBJQi8n%H+3|hGM{u?=5hGUMuPX&Q~ zHMG4yi^;};CpwK_+UDNt9#}v|68P6LRTN$p;}t`t9S9X3AcV&5RV3@n#hM^XgwgrE%w2=nIVM6si zPS^Tinx+@Bk5`@Q%u`%7j`$dHhqd9!CuT87hsB3t z1V8z>x0@oOqN~P1J20Muu!IQWJT_LYUXsrpgRFMT5(=ToL`hs@Tht3Ff&=QPmI!q+ z!eXjkONCkGLz|D*=Ed*kf%0}^OMy$$4TUls?iS*25&JVSu)HOj^Yxr%LvOnaT?ZQnCV~EpygxZNOH2a#|VNLkWsJq0KTs9fihd_NWi= z41?Q|G{TNz+Tr` zE%4ii;zR7xTyAa$Ku?e%%TGb(-8)8ce8=G>w$q4JPq6EdG=+O;7wh#ISjaL2h0BQ7<`v~hmC2qgrR>8%UbwgW@CwZpl}JJ#c(3% z?9}n_N$+k*6`cvt=#I&0max!S@HqCs@hQ6gf6*;;@@%M-e>2cbWNsk1xtrK zosj7~0XJovbZ=L2s5cOOZS9pTDlTE$>sxYLP{mqmfO8$t%DWBW#>y}Cb+pLfc{dOD zF*}TBaEf!(c!h*$9o0TY@=JlFtN%n5tC$w~=C}kc-cgIQZkJf>)6KK-by^Yxi@-kA zV8HBhzv3BurA~wSqwoGx+6 zPC$pFg8BXk%p5{cKc9WSIXbzamM^ zQzsoLRH_mzSe#SQJmLVA-dFzq}wSMhzDr=XVeux zM5TfWlJ+Bbm7#*d0j0ePSx$+&;2*l`O5Obvhe=qHCPHLPgt=B3)`V0Zx*O9Qf5Bq) zZ4SA^k(u?#-}m#bNp@L>C3P5<_4;Wz5L7OJO3;a3;yT2451cozmE}(5MU={C?gEbz zzKnp%qsNJMvc=3;Anr_lHvhGwW~sGP_v2qh4H;M(CJq|rQsezEsyV%+MFu8bOB}e_ z$!c^Kx`&ov-LTSZ%BUQ30QC5ZKd={X*W9y^5%Z=W`PZFr7}@3(wSs69n(=J=vV&H~ z)t@fE3=8WTisV8;@UcVZ8qwmJBOsNAtur~|eWGHeGNdQN2)$tIPoPeiUL6_r5G|hi zQ1ZPs|KGGgPpJc&9S2g%mi~k1K8z`TqpcXlHqu(4ccX@l(|QEv#~!TGDN2m76%7s%x6aJZS@Asbw?_ouY#^L{WjnkO=h68ZP!>;?zY-?9gE zFaEm;XD*fzqcBcVQsVILFzqJ>Nnw5dguVKn2-R>#?kTj{n!{?P71d5n2m$`F1Bx|9 zZu(LmCH_+eDcs^s91f{k2OOntJnN;*XqvWrbeitXZ(I1vN~Dx}0kSLmeqj}q%w3h! z{ma>+GfQd1UtO8Wr`TTMxPH!-8q2Z8E>HuzDu2np#6BL-sleSBRGu*LkoG7C6*%Dy z6&|VM$2`GZRFBUT&|kwW6jUyLOsI=_EW6)~OKw{V>?UQ4js>H<+D>lF#_EDG(Dj^C zQ5BS;ul&0_jObQy5?d4TUG+*HUH6!|FD;lk#(Z2F(_Tu?jMb78ki{s>GxeX5I4P?0 zCJR8BBHo=zE6=|$%i|v`txr7b(7O&UA0fd55!`!MwMNC~C5j`2gLlvJ5ChB+{7no5 zn7VUA*0g8IK_c*arK=_XTF&%pD1W7xPp|2G-eG@FgNwEomZet>r9e zqY*AMZ>L|pf7o~xR41VIx6N$d0+qMbgVpMFzlwDn;)LS^eJ_;} z&3^qDow^su;H@clczMyol&OGRT|;1_vf}Ujwjv7Oc8Xotq)$KfsBPJ0hMvF>+g!>> zApGwy-Fv7p@Mt|C4ai&eX?+}!vaB^m1@23EUdoYOJ_N>2CS!VMg;O=BBju(XBW7_f zue3pmD6vva=VXN2{y=8LonW+^u{4){mzouN%G?)EmTXAea`B1MG-lq!U=e{glhaWrA6O0HXZfn= zT)QV#0;%ht4C##3S~^LRV>BZ`CfZ4wJ|JFvULTq;&h67K+)y_lD1kAD2cL82X=FjQ z=m|ks-Wrdv3o~kLd};3XzMA6Ta7{Lo$~M5u>)l(&S%K4JDDl|Lw&MV^_{NQW zTjgEwOX;k=LZ*aqca5(n$r?WJV`U4^h#(SxreXFon~9O}bSY?R`FwZk1(|)5>18kx2*_K-$6$$yO5~Q#S+qoHe1d;MWZ!V+s z&#%L%;FQ?n%UN-$Lqh+trHfX%kdZT40;>=Qefmnf@^@O8SH?lI*8Oz-cRIJ z=lR771xXF(3nj6lKr2{R8wX5lj!jUwydeGo(d$Ny7;{eW$m&}kldOM3ygdWzybNs? z5p}6{3#Tzf`#&)poE-z&-G-B`qnMuGGwtq-Cf#Wi~-aldaZS7xFRZ8#G= zPam**W^dF6Cb(k`!ngX}i5EFWd>tWxD@CF@@%CfdssxlYN?ogqf9af|oTl3bJsf2$ zXyz3=#;fobh4b5ZXbcV>><-oLPsTLJV}HmmedC2M><qu-k7dxqzDBAEM0A`FOk+G-u9uB5d!fIMIOBbtyOhJS5T)x-wiK(r`Y4iBG z-_qz>WRF?4p1VRZR^xZ8ozF;+=aGJsJjchUAd0ToL(Wr6#%pGGkXi^@UDZ*x2PzMe zUbp81l|Av@KgXCv2Syye;L01{4r&)JKd8j5hnw3RB$Lp(J>THa2e~<_JkdrsSlmH$|AQh_8y#ywrW{r#7f9c;P}lQ>+un z{Z3gIHxJ?gH%Zt9KUj0P_Ark-e66+v>O$RZY}6i?HR)SgZq@B}%EP}S;I z`)#@RbrJswBhFqVFeMD~EcCoiERsoPKfB?5_I%{7vC(!SB7bx%HvHPRfJxWu%)8=P z+i*2d>mmI%N+P1aYR+EI&0rC4fiA~kX{DE#eNZ&hw0~yxruTjl!d24cHI)B`1o_Z@ zVMg>IO3W=aGAu8SLa3)Esz1LU#FY&2 zSzl)Qr+~IBJ@L75LUh9i##A>;mJ^iq$&iM>_7KqyNZuRX9M~dIM=X=rnfxL}n5d~m zK?iIMR02%wU5!P>^%&|6LnEo!E-Kn6iyDFUoU22A_Dh+jKZG}SWv5>b;7gE?xcMm* zLy<8SqQ*)^B;?$@_41`uxW<&TGG|WfFCUY?y!C`ORJu4=xg1I3TKSA=GnA{+KVAF)%QFykIJr|3| z;wD@$6LGPjyN>XPTl2p!u`>E?dmWQj82TfA+;9L2d9FC)8(!fd}CcvdQ{W6wA~-tw_k@e8Z22qHl8^6WpSvme*P9#yrlB9AA zvGfjE_J3fBcF6%<8L9KEPJG;=gC0UU5XVE(G}TMu&JK4j@?e3QIW5FQV%2Px?+_U_ z`EYr1g7=S%!9Nb;tpR=QjTwmlu@t5B{B>kR+Hy)_*{QU#vu+I<%~V}W%rt8D5ImsC zTDUMYU0dV`}oUtfpV7?|S3~ zkw|^3ywbowOWI%94x6wCK6JR-^Y9OHto9|gIBSwO=vxWkQ2Dq2nQ1~ra8xPYt3(dI zsd7P-ih|~obL!wX&Qr&!Gt@MoamC~;q$4V!(-ckJHghE`TQ*2-IqPkXBu(jax!1}N;0N*?dlyc zx1Sm8<#W-1C*eQuV0So>(4Q@FHhcL1mS(3S}>N$5o}?RGn%=$>Z>&dUt1g;w0v zY^Rrn^!~mmUoBN9#Gb1hk<0MOUU=`k1H!2Vr*zerHu2uQGrDk+1^iU|ez<|GUfGx~ zG}zVu%h6TJb+pr#AK;{-y4m6H>NUJ1kI(?Z^T8%ZZ$8uNP=8{~wvVS3A$PnM$|qy0 z(rF?K?_VtMMXmo^%QnJV3K*O{8?Qapb>Cab5f1Ua$TIHFXsbrGk`bu4bVwhZO(cgl z`&ORf5lPzdKXh`QVa}y(BP(g=0|mBtDi7;_Ux@dWc-7VAhNUX~%GZ{ai_E#MYv3hZ zXGpP0iiPot)-xwD8ZoCsL5-OI2rge^9IH(LRsL*4G4OOhs-KK2vRfH@G_kK70sG(& zgx7fwh3D5O@7J(KKU%}I5zkaey^_CWCf(AGG@sEU46PN009(8Cz?H%uR3@70B79%& zI$pbb9fOW2dti!jsg+JrAkhj7-?Sn{0={nl_$V<6^x!1$llG6ja^EOf z%xdAr&8WpXF6$&2M)U=Icn4x3sSj!mABPJ-pHK9}ypj-!`{>lE0d@8^K5&8Y3(A9n#X>CZq2xR3* zc8ES#_II&hGfeA=~TXz_4HuwuICsuxzxl6Yn2bpyZ@%PNmfm-XfKEofU zjRz?>HIrZhFRSfMGO>bwX};c`I+IPOWBW(5L8=?hjJ9iz(t;IJ5o<==(iO?3@{7H{ zhTz=<%kmmE;4K%s7hsKk>b3Y1$l642A|QO<0hd&W7S+4mC{!WBFjfUM;shL@8j=!- z8PO!>iJBR)W-_Ou^G?>;^1B4Gou$sRm6^mK(b$({@wcHI58c>`?e4gn4vcgmHtCvh zN5GQs2z3UTIS`Q)WUz_zs&m%;)QNUu2piz~ux%OPVw7IR_|yXItcz+4RejNm<*DB^7e+!k6&bg?5xZO57rx9f`vRpr6QBRdUUO)o)qL(9fg>=aBfxlhPaiyHkiEkm_dNqUImdP2 zKs02d_5qAvID#gIs$!E}?&N`O3?~ijN#+Es*_z}tQm$i4Rz1_xsh!~SC?XY@#ck@P z_zxBNrq>|tu5vdk)17BzWdv<18>gv+E0FDm&!UQ(EbQ0(8x z570WF4JUW?nfK5v#FuxGkz?=Kb!_A=@dYd1e@$Qg=S?)@s44U0y8<0>s1)`U@@+(P zm}O=cZV4+lUjW*q%Y!L`;=-SWzgtY5gYu>%T&9NBn*up+;TtEhVqQK?D(G^ZNs~@Q z&Lee?&_}^m5b{Um@8na!p1hw}69nu9NId^0@qxmGnQa%Bx0j`5V`gVy`dPI+XJptC zRZ_zWER6saB)MyX*Gr7^fD&|#LVZS1r5I%vsHmD0|57+3Fw_tAv=Oze;C0EBSc_yY zdq??Nlv1L{XZghVC(hxN`!qyWJ~FE_p6+oM=Av++s0|Yu?+zUiSe<#YwA<22h9;er8({b;C9SmRnM$u7aKQJdaL>X5Pi5~ZqfG~Lr5=X zr^KRSxE|arX5c^(-89o($D7O9d0~coiYnelZz{c04V~_%G-L{d*dvjXx^zw*t8%_| zl}_%l)SVWA?qox8v3O@z>Zl%=Bvd)n|MYCclM2^HC`~6uULud=(s{@fMZc5V?A7Pf zR=V)V1g4wW8#tFi*CGl1$z;fr>PKJDj^w++y6m!%KudA04PAT=(>RZf*oYsnSL>1; z3d_NE^s&B&njxg~9@*&**D801PAyrC@$73IlR;mN8&Xxt_)<&R?ZXMyQ0BLiR zC)@rL?yS#9I2_)37mkP^-9+xkuNQl+%dPA#KP9Hmb>tmjPu2RB+f9sx2tIV6m9(O9 zw6e2cP7$0xS>|r?r&lO`I%>Z{h3sCy-Z_t0%i^Z6@?f0%L2`y1@x#=aL4i5WMdh*bw5 z_=5O|jRYMi`7`~eo#G1Tq8?sp!@Akil3Vq}?iYiuLU}0^iWHOD z@L?%>SfmN7q+Y;}i>Ir()fR~^k6<{r)%F_LJ?fxbGGeBqP zMx68V1PTj-2zO|uR^2C^Qdu?=Caql^Jcld;&#Z=|?cXEwGaA%f6Tn;WwwSZbT3-lC zNA}O2;2=If)-K@*G_YOc?QMVXH%cu-#e=KPBBe7=Ye=kHYSQfL_7K{+Td+C7uf;X8 z<+uX+O^uF~&2+(u2+HUj0~OG=WdbvOcFA;k*)#~yK5jf8$eP;Rp3;WIERO2B%xjcuPn z!VFub=0~2Ap;Dn8de9ov#MZ0bvSv(B=ShqjR*W}FXG-KLxi^H=@u91zV(SbL`tCh4 zKeBYa&F?dp>0U(MwBND?uvYHnVZM=r(;hl9 zx?lkwAvAIx%A2(Sn_^?Ym8|y zf&tjxM`0^~TwWeL{+Ah+rzn zNpp7uaR~83y+UOb2vpRL@9k^!n`P`YmMlsq)jwZx)&t=0lRwEM24OxAu(4Op|9)mK z=v~qOM_>NfP(kV(&6=>^!LEa)X2Y zgdd6k5N(g|s@de>@$$GLm$sMk+U>(v;EaRcp{&fLC6|!_8`75O_1v##WyGk>DHhT7xm%y~5vX1qbH0OW#~*fgQ5$ ze2mkg{3@kT0k_H86!;6jL$kr@@4ClnOz~#TF5-eH@lxz?sZTcw9^xtv$-cS{F4F`8 zb&3vTnnkbi1k9GFC<56IXO}HfaTkyX7^wgI&Ysk@J$Em4=5wu^r#;wvbKP5M`$V$$ zSyUmgo+`{b%D~j?b1Xo6jJ-@xXOqE>=P%WLhfKvEp~4@^KXnWm2hWThkS~V9Dxxg} zUA`=v%sJ;VAeU5C^hEg0DxZ&5XrXykAxU$N8rK60&f?Gm3f_D4-jmQOO?K5g56Beg zuec;*p>Mw^&rAVxs(ra0&Ke!|v%P;=ZPSLaT$)NrwO|HE=B8%khApxQD3eYKxRnd# z0w0-~P*H-3I{{K-VN;gV%@Iy^#O-v|r5Kywn)c1%Rcutk z5zqeB^?Km=$_d8})PMZ^-sgu|*k&#-7~H{j%*E?&dsSJr6*fY)9qDt1lDiF{nn7?~ zqqpItAiU+lR{!o6hdfouu!T%avwa{q|0@?hr)1{-i($C}}F@0@`=e-qa`1l{ z$!J7fMJ-v=>7W|-`Lm}B?ehHa$e{nj*Hog`{BuqfaM7xAUhQHS7=ZJv)CgNA2NvPWgS@jvj6GUz+H1=82Aarw&<+Fj+fYbQN~2Er0JeMW4|s%_~i}KFn^q zEltTp|I9QR&cJrU!b{C`z41fXovgu#i9MXjXIawK)6%RLR6V6{r!yzfoFRtRcO$p`EiC$^aefD&Esaxyn+!3$|d5AtdLSGo|H? z)|WBqdE2nt-=3rnz>E=SE+BArvfQK)eKHu394oM89)J*JB$pVNf?O7gCi}6keR2lS zy6Z*q5hhQ7ZT0FYkkk%nPTCkoP(~Q5sFzIWBT1ye;B{tSPRt|7I8@0I`6KrU>+DK7 z_gjES;Il7j?J&gRL#pKH<(dA5M`4Ubka0S;phf#V3*LCB9K-AOBZC^I(Cl|4zU0pb z`}}IHZD?*8YJNwc_(UTwG^W})R^yYk0~`vPp>`Ufw7~3qodYl5lat-AzZ_(yk^1u> zD@l_UL%K$nizVYUYUE{9^c+GBSjKK_3t@wiS2XwS_q!cSkx$xaAVmw)@{vyN!Ajx) zfGxe=eH12-gb3euyP|6IPWw4;9B+vDboi%LXMJN(+qfxYbGS)Nxlu2UmFU zjHnHaq@RQl-+QAIPrERH9A~v{v66b9hs@0UN%ayQ4<^~75*0fH&GCTzAfI)&z5so6 zwH&4h1Ie0e*9FhCvawD55V&_A^GJDW+LQa$dQ2RaHR?XWVV2Fmtg;BdGbNTS!!I{o z9ZIaYM`STxV6g3tmB!O1(dJSc%BvPwnjbXqs>ifde8ToDX-!!!jht~i*M^+T^P{mc9 z*@Hx!MBx)l@(8NWH9K!eZnE+K?lD0705s2OJEsVYI?eeWn6?i((DvP1qrDpJA9z&M zMW-LDk;NX(wQo+>-=$d$BK==W9#k>o%cy2;(qic*Ak%qieM9WyF-*6@Q}$(vv}q?BV(Ha{bS%v$pgkEsW3~$=L;%can3c$|?6;<~rW?>> z6YaVJ@^)@04F@<8G$@m>k_g3zCS%-O6=@IL)#T%FO&9?b4#Dlo?kfK?9-Z!vj5^0( zz6|T*r&;&-6Rh9_V`fg0FmM6Iat<~{HXpXPyhH4H)uW|IJB?%vZL#fp4LqrXuY678yy$Nvy7uAGox`&|7j7Chb_=zLTh?M*#l1JT8^ zt}8%t>&piQo}1D`0$G0h+nJ2;<|>WU{1ntF-)Gq!5)?a1$Nu{W{=QM&vZ%%%xz>uH zR~f#ABE~w7p+tz~L^Q)55;nd^VlP^~q`Ee&ks8OQFMC|qT zpjMX1ae&%BeiPa-gFusKqO<#<=HR=FgIESt?WlsxrD?I4t|Ir&8?8){h8HcgD~4so zOV^j5vcCS2VDQ-}>Q&+yIgJn-FG0|tV{hlhunY6_UO;a$gc-ZzG-;_~{MDSV`9+ql zzOx=?&R`nD^i5NS&#;9-;R5JH-XTV@o1a$0x8YZpE5+)g^o?985e~xHE{u#co2#Sz zf>06589ZMRt0+A`A5Pwa2O&EunD7mQg)Mh8_Q57{=#1Bmi^YeZoEmZM>iF9I?e^Fg zR6Gs=eQs(b-WmJ-tumrQufoadXF`T2kXzYIK!*r5+zM6cQ*1rId}QyIz6ijdn-gFk z$?l1oLuhxFdKhWBwme!gFy4#gojTtJprjj6-SPh0X+V@Mo2~ZB>(ax(@k!lMT6z)-L4QVtPdCYeZG82x49;1L`Lr* zgFUyy*?2Q?D(GNU+9rpTh4HwRkpV2kTWbI&;pvN1k zJj;bM9G#3JZ;y{-kV6>Yu;E&J$oqf&^|RWQMCFFBaN)F~kZ^wRhsoLqZ182?FeqRU zDnPm@xlhb`ZQ?lVDG$g!l)WQaWy!J#+ewUF73X_8_?AJuu6l7GaW6w_6g9iIN%6?uhP@4CyUV&oS(5$Oa3RHkOmGA5l4;bR#VDT(nN z7WK4=F7gQh7#G`=t={FwQ}SYtjv;A;qaTLPH(Aj162A}~D8DT9T>ptiyWqIg zWgT*hzlN~NhtAVeaw7#3C&{kym!9>nrrm9P7?{q5Kzb5bL>N6^XZGMg&->K^9!U=$ zLEs>Se7}{RgrSpjW)n2cSix>-fS6cT>D`8mx&<&*%R-lPBRhJ4?<|)a?|Ph@7|uRFA>^uY!j)&a48!63-)nJc)OqUVpJJVt zl4)I&uHo>K*F``}2MDz3R}HLTo*rjHQ&!+b-Uw3@vcvfDM-sIjH@Y}CY);!wA$QPA zel}jwKlUmOQS?KDphVZEUWFwA*>~f3`(Y1S&C^R8POw?<8N7IJ{z^@jYn3L{Gs>G} z(l8!#hwE0B*#{9<*gZ@EC6FNQSdiQfEIp?S#z-Wwzz(`@))*|hdneAU9f<}{H`6-u&_1w{n?4j{ za@vKG?@*lv5Ews2hXyQ1*5mmDLsMCUa*zG*RI*2PJ`)@VT-ZZpla-M^*Wf^Epzdnd zuT!bEP1~fW6?vPr8RhP_>Tt_LQzIdj)@;8{l~mt_KR~Tyf;lIJjMm(B!y;ShI!1Z@ zj?djE=3)qL;DN0~93F4fvv9QMQ-%G^h_ke{XdDW&Y@ZYP_2OB#$gA5pvQ4r?I6H~L zDd=u$HL_miL+oZpoz8{!Wcgybi6u?`u-{EwDQ4FN03HAh6A3fF-~# z|Ec`rsG}xaMhtG2h~Z*rmtr$ZrWOCA08Z!5i|09oZD{duHg5fdFMB5huYFJ^9aqO( z@hIkTK456#}NTaFyih-X0RZ9DMBW|}hny~pSQug-7I=eS0n>|!k z-*wJDouz;?nvOhdnxZ*6-jWUmI~n`M3F4M;m?%Wv(t~X7WRgUtFgL>1w|w;vx&Xy) zYX7Sb%Sb+>7^hfVa|$?7sm7v`H-gR4T%nBYfYYHvm~DzESTP-pl^hox*`Yt{VoxnF z|B&>K#Plj{2n^gxlz&L7hw>kv>_LE~vwlyu#;ic}e6=`pIo&+a4|_>RS!A>Gh?2(L+MBVJzg!v+fu?(XYi)hOSy?)8wGa_*k=8eFJ~C;U_i zElPV4jNz_UoyKpC80Z1F2=>{2-3reUkg;<{uD$QV(>S^WlWnuj$Rqo7T6Qg9fYoCE zV`dluzaFrffz8_xCxFfLFomYTAOIKQ&DR{v$iwd1L~8b~K`Y0|E}sb{0GhUS=AI6v zEm@>1P1kBu{Q`5*()K;$=kfaig}xgj3@*5SV6!SrJiewyrCQ9XDU7m(OXAqRDyzz9 zdZuB&trS!>A{NW;Oe<2+#7kgy4GG+8$@p0ZW=w6QkX8!zB8Ri1OqQ#!v~vuSf|V_(&P8R?;RN8vE^Ob0Pkk5n&<+@sl0P49P%8XbmX_hZJ*O1pMY5nX;p*k(*O=n{Ex*HNrP@eA=+@PiXJog+>eG%aKGw=>4=KNqPzBC_-R%N4A0jI38-)HIj}(W(X2o zp67o*4H489*r8lFMje$^S=@OBvoM(7)zOsaKhk|+p50hV@H0yj24N7sGOi*;GJ8?H zL9Tz~H=!V>lTqN(7S;nk&()-7Ds|6afA4hf&a(Qb7%{8CCCwuSmh(_oZSwZyVgzai zf!D0-LTExP6&NS6A!u7c05S+=%^CUE0grm5bStDdYcrJInZlTr4k< zHg+k2E*&a>g1xIe_9w0{4sgr{A76+D>0EZe*-zTK5c+};>^|(*{i4w#*^5b zo^$XGVfnQ|vjy)wf0(>rRRuNAtS|GuSTevB{<9#Eo(kuOM~6-Ym^5tGW+TkN8#-^f zN(TwFj1!eNRC5i!Q%aInJ9n@?m)c)>d2w;UbKj!?V3zLBkK7k6ZIx?&R!*f6iB|r} z;t#4a97+7_gphMbst?{Nj3*xJ&YidVRr9D|H`u2^d_T4o{Go|-!}$mdMMZEDQGm`R zszgbyQ{LjJ3RX(!@}b^o`|lDy%VRfj>p64T`cXaE202=Wr{Ky zIa=WY6?0uSbW02@5j`CWa05Z;#Q1OBl_gII!ml4#FBtY%T3_L~x`0oo-geL-V{s)t z28row$cxfb0{yM!?CgG?*%-^P=ii}$o>1jR2d+IyY`+;I;7%YhMxAadm1J0)OcY*} z{+QDYf6y)x=Gi0^@2g6Dkn+~^%AsLV7AkiZwXy(3Tto<}UAehsd@?`T<`%1_j)ngR- zZv+ke!K-Abnt3%34=zO_{$4qB0yEbvb)~?f=-OK2F-}%z1*hZrBAJjql9^3xsXD^g z0eRB?T{bM2DPVk?9&=XGCP7QI9u5o7;Z3wex~5FxmNc<#?}PAIK;37F#4 z+~&GFP>o%v3%o5gMRhLWo%{jEcjcoG!%gTshYk)C-#$*6Lx;(hqkL7tT9&=~fD$+8 z>o->QJQoQ)bq8c(vnb)8`Ct~^zm|0i$w2@58Iaj1N<8}kn+Cn&SK7Req5z&;ULdCK zqP&<8g#v+UWFm_%Wbf|!`()LUN?@x&qdIM#2id~SJSaHwY;G1zj_mIlb##hc3!nw z)Vv2enl^ONHx}LF=e(LW5ED{%w2GzKRILVCB$)sn3h$idefKcmnX z3>VGO3u~6(@^T<^2r_c?@LbwU9uUXRdZgz`&K;n!))_29{qzGF1LdFZo5X|JL@)J% z$D3F-uQ#(4)`Mr)Ul7kL0$_6opMqiKeVzE^sGi9E{Z2vg5R0|o%P2`H{|%XB;Ptn- zUZ;E1r#_4e{i0e??l3=_GE?c*w{>lNsaGaO{WtRb{bUDo=YAwdzRqNsr5R8`r1==<3!EvNR{gVLqNR0C~*b5 zjKd!!(H?zNGB0Q7i;4 zf1_rg^3&a_hZBsYgMUpE=$C_W*QNP=ytg@kK>c_g=|`0i-c>o9COp)V(r?e-3_oU;wpH$1Dz_ymCnVSEi|s{4Ds@r4oW~FnMOYchSM!HGqYKTqTzHTY!5OFj z2S!W5yHpO&^(xfeSyjt2yblMKoS%yZ9C4{$n`B zH#k{k%{TSS__MwJ31qpQTKVr+866V)t_?#^+cEZxcTI(VIct0+*TKX2P%l69n9EFq z4cUD$%jdRN?2JS!AZOH3F~1%)K!mDu-c!wYxGZjPcvm%6AD8W5Jz-FZ-NVeRUm|og zJez=%q6b1`;V(swcsZ5!aHu(D+&)*Q>U2guVFD&%Y5eH&DLjrjN(?-D)g@>i+iN(r zpo89GdF>V*M2COv!=2%S_^EY8*$LoTxPM{u*u9Kk3=Z_}^uw_e=M294Y90Bs@h>pp_DdhL zk6;vqxhuu$^&^EAx(*VPXn|?!CCgi;Lv}Eu73D+UTWB$@+`M&@LSjm2Y)dtDMLGyU z;@fqwU|fstG}MNkbe0yH7B<8Y$CQ^K!(+u8RAHhu7nrCT`QGo%@>T?Jf*I`Ky@1MX z&G|BuI~(GG?nm2m^)WJ?mG1tzh3Oe?H)-}5_W5yr*pfVZmuZ19=TY|Y*XBgB?#3g= z3CUQRX1HNE)Py8)Wsrz-5cGRwQE=nUE_hI@r{k;#(~}hP?ra&tHErELN+EiY^rmN1 zDdVThMN_loz3X)IOFbO?m`?fF#>j|E5wj(lHb2ss6d;){j5n4f2(I}l`%4sWl-hUA zh_BMwUs4LNuu>0Rhca^h$O;+`kDv>TO6i~NGQ5>aU3RbtT(_WG}Wpe{4C*Yd;HAk)8a z*D=3uT%lG_{jxkdjlSf$fPHxJ39BAY<0?3eMFbZ@Gh+J~?tbzj8bg#-p42fqmh&^4 z6ADR!QL6(D?fMJ{=cNCZnqAdLlct^{j`JXORVsljC8!nlSf+TYq1tQ2WJ>BPZ{ zbi1Pix$k-MsS)RfbUq%2XmFAG$*il0YbLH`TSiZCcoy{%xsOCmd9j`^IfC`+By1Z- z2RD51N?+kg3h&zlgS`{rCF@MCb}M{XnW%sU31^p`t-S0-ivAaIfgeZ;5M_88Of5^7 zbJ;5}`ArkhF>(To<#e{W0Ep}2N4>b^(N@;XP>!Y12i)|Ag8DT;i9D&x$OndT4F`2g zt!3eU?^8bALf2$AQL1H2J5*NePzT6;I3B6P@*nybf8xYCd5{BS|MOqRRel-S7u8y& zE4jX+UD;Fr8HxqaOs;~)tGRWVFTr?Z=JVyfkG8v*!Tc~@$XIREJV>T^elR;@<*UNO zINVyD5~+(>=9~YO>1DCi#G$ql$yWcti>GK&3`*ZPgS#13MQzrIx7e8oD|=uqkvA-i zOclO(cWqlgT3ZPP(vL9P5i@TyMgov8>>dmkLg&5%TY|3QWF+Od!!}hx^n>qQ7pKx_ zbUQ?QcYC}HgcHnxSwStF+8mTP5TfNl$k2@_&cV=?iM~&9yvgJRDyo%4Fyi3nM-hQ) z@#hjyu3|&EsxWJyGl8biJ@{5{rP^em0%*!tOE$mEsw;+pX|TuQ8? z_vFp^f|mu-I*Ys`$Tn)cZL4mXny<*z#QgFtAB9iWjZtHfRsKXRp)PObDd!rm?kHYC$ zDHAi~G0ev;Zl}-nLe{rkrBLz*poPVvE+4Q>^!YQ`&kV+)DzEOno9~EOKNZ?uliFIE z@tn}|)fR}2a~3hAv^LMZlSgDPWo&mVX5$L!KBD9XaTTZmG#$i(1ImWpk8*^>fttgA zM)*-gMtxR#OEjE;NN{lYa`I`%nd5wOTTlVQ_pRGf@ve6#~eUIZ+W%HsL}kW|Ka zxfO-yp`T8id7L*;`*GdOkP61Ckc;M&zCo{XID**V#TSRfv!g^Q?)jfr{6!zlF?*E5 zxpd-vbIhW$Ws2=i~n{wG(lZcH!@hG|`}Uz*lu3$tH~|xa6W!{nc*6yPE+6t-Ot&!(<}%a8ddFl zhZ=dsdY~L9So?3ET)OO7-fr3~q7U@m=2;JB7n$!`Ueqpygqv14R7cGyk(F})L{cBM zjF7+`E|kJw`;<%W6@8*_w4jC;1OWy4;kHwU)DcAr{aw5R#ff|q-vSa1pE(F}0}L&z zppgPO??XrB=J;d-Y2k?@sHhDS&2<`IrXspjq!5ayuV%KfR|`kNTRAe3Dv*{=HCm5$ zDaNyHP|+Bkq*WdoYw1`(x9Es3YHTb`kWm)CMgRTShU-^CwxF)`M@!6sk7MqU2dfTv zM%^khpaU+Bom4$#}DvoLhU(WUlZI40bx7;;7N+U+V*RSG|Gm()@_>f>nM@ zD7^^ceJvq`mBR8O7OB9=Du*ZMOdo*X?rOlN{p9BnTzyt+CT&an69-bHnQ^^If zjt}!(=x(n!R*OlPz?#u*z!++a@)RT61CHAd$Ml*0HKM6;M=Vf*5aq_B@R~c%+1OsV zq6Vy4x>p}R~jVvY6X?r`yPUjBZw?BNcR#rsv=(6SyFgpD^fCY zP8q%N+Q?jQs(Lv^J;ggdOF8APe9OzjsjFC<1i!;WH^1?ZaqoES5-7y!gT={o^xHt? zNYRwv88|W*l}Ek}-PnT7kOV-TYIm0Bti@YOsA} zXv?cBg)1s0pCwW-kn<%E3?Q)R!KJt1n@c^v!)6nADcb9B%?f@L;|pr%Y6CpG8VaIl z`DCtL)gB2Yb)3F0E9%9^rUVS6x*0i;r9yVv4icchI>s=|Q5xy9&4M%kL!w;aF0>lw z&}z#Ezi3rsR8`C~&j7Dg)j(Qa=ZUOw3wtvP#m$32;hVUb%!q600-iL{o|Hx$-ZNf@ zh+oBxh2P@R#Bk!`V*p=Wh_)o{xpxK_ZXIWPM7WmvrZe`1_{guN;X*}3C4u%fG1bRM z)k?pQ$&5KUJ|!-EVdGQviWjP5gN-Qq#4k`L$7y*OzB0=Z>efyp`Dk$@e@9W5eN~g( z{<)En++iuusU8xrj8>6(nMLvo>1fM+lrH_D7juggD9+%ljDvYkr1GV-acevwit_m0$3gduyjfz18K@{&B?rutVebWDP%$ zqQOh%u?RqF(Y`WL9w@Nzxiv(}L+5DXjMI)NBn7$m#(aKPBSgp+?=dD~#EUPKv2-6n z$!2^m=rv(QcuH)ruCE?!ib*7AmRS_}%%}VR_P) zb%GTzR%FGB8PM*F?;|$yWsAxo<`c5=2U4WndqbvDq{utl3{@DwLsMSM09SIH0U=>HcX`@()8->z81*7&NGrRt|FJUHxwSlBJ>JIJBta zG0C^5^}Z;A&(tAGlpUPl?q?RpEffmr%ewsPgkX(SMaGolKbRFWPpwGs96Q1R$SU+| zn>?0nkYd9jA>l5jB)`6Sz61mF{Y~CtA+cRGl~p*k)dIA^wI)^{+UFO)%00B&MeQhV zRce_EIHLsB>Fk~!lJft8S*9v@)8+e=9_`Bs)eAkIMi-Fz_HF}58W`3I=D||=P(_9! zPlH82c_lO&U6jVO9C4*v%?8NqEn5wl;%{q=e9W8S;|2b5NmR;5xiL*gj@Vu(u@9-T zyE?vq$#xImXQs9xFtCync(|mcLd-%^-75Geds476+eYR`i*33Kh;g>D84T?WzppRm zae$x6vGNSzfh3rhD11p-Ui*6saHS$J;UT5G4Y?tjPhnc+FIpZJ3O0>K1JOIdAyv-q z@?A75bWmB=0FxYroe8uE-E{XodSAY)v3M}j%`<_L6xaX@7pV2oE^CG6MP+=;3L5dv zry6_^?!w=j9^8L$0Vd$u5r1tn%#A7 zQN2d~7HBzeS()J;+uQDqS1EirQ7N&* z@k4gUcyLVELTM&IG!RbKFn!5-cw9>c2_4FUN15^I;Bh-Y=LPNp-+iiX9ip zlNKn0S!LZlozr*rEM|fhZ{2dyDZC*}|5p9@Me0^~TWmKv7JVlRB`qEaXe=Lj+}LCz zXuYQu58liC3sR*^idGF2wdLrcpI`M}kA6b}Jz{BOs%{9Ikq5JUEO$DK%N*ZnAk05v z3UN{NV|fr03;wQ@&Nl|~#l3#RiM=B@eM|@p|7;l?h2ne#K0zBa45*3RSK5(gCJ%t7 z%!N=P?3pCCRjmSs(2;NG)PVexEtzzCr z%Nt(e*xr*!FtL0V?OymIamya= zKG=-}(w4A-GrmMtR`CxfGO9nvSXrM!TM|`1L=+!eJ%Mf-H2bnuw;cFGVkUzE^*!4v z=LUl?-0iBn;BH{&Lp5yBqD3TPLDiW(+lIlt7eZ6MqiH+_AE=K@tSfs#doZXIeoaow zOXR!NM&P*ggZ-P#E;F`^{5U^j=GX!k(y*C1#gEv?{NPL{JD+fJ0TgQmdO=X^gL@t~ zVqPk4b6@cYVP5d2Um)h<2||$skT?odzQZCd0|5{t+lN3*%kew?X6%%g$Jy;`NN8;+ z_7WB-dc)ZApmGlO80h<2PsoO!tT$$)3J3pP(45m zbwu7lPBSbgG0-OTjBG{$Y&2n?#1##y=;YO;wZ>c`C_h)H!p^mCH|iq+ib_S&2CwBC zzVYL{pB5eabt)F4b(%^cl;We3Q`|Ynll*9U(7Ryob0$+WPq9;nFVznMAR=cjrGRkN z#|{d@4^m{>>PqJcXJA{+2Dt%`nk%Rm#3B{7{{%ufgk-0ycrw2qUjk zvX@F+piO~JqlJc~{Dor-CE>UxS`fb*{$FEIRpszIR2D<=Qg=5oBf2SRH3+u4Li%Vi zR1O%^Ob&p5&i-Za(Qt244#v~IVwPhRkMG+4Eb4JRJ6|fybm&Zr-UPUH5Wi&ldGqaPP8a*W7vnzg?JjoAHa;|rjP;& zKI|uK*Z_z_bJ0sB1v$w}2-fGpi?X2JJtqRWVF|_zn9EwiDI8P>ujC-MYXP%-!#+7g z7OQ2HLPAVk4SSIRAYTKB+x;_5ual#zMI~93`MMNY=kY%}X&X?%Z$^UU;yQhW7Z(Z8 zK#Pz07BOLo^c~bHNsOGC?9pBpnYH;X^=r1sdmRO>1CBcPQhidKsq02oF59858p^_p$#jfmNl_7Rh^XA+6{)8QKThoQyquN+_@kV+9>CaS%E8t zW~fgxkw6=@95BTrseuo}xNA?QR1xb2?rpYK3Bd@wlKKBH?q02xf9CXh0aHvq4;aT= zV#mG7lNJK^bFl&r>q>O%KgLpH#WQ4?o=*Rh5{Dp(E_SkX+&h$o zI6X@1R{Hv=J20IsGtp}fw3Mee5_NW3hhxl`RB-r{_d*Q9_Y42mVn3wPryInDaXA{DPKCD-z;JEbPyedjRMQ~+K$vJzGFYJhZa1} znO3XhN33q|vyG?~pPNcNxe=HRcOr>X$=bV`Bt0=g8flnAo_t~@!*IKiT3nI5l+>rD z1a^CCAz}z)7@x5F*{Dk0SI!8d5?R59zJ1t)c)S)GZQKlxbuG7h%D^i z=3y(Tv&^SAPd*AZ-ktEZ0y`fq2L58?m;i5FhPDipqwDM`uFG>t9Sfs?I$OE zVnNbi5+j9);D_0H8CAR#Xg7Cc)*Jk_r`ZR!YZYRW6s(-1?#j{(lg4wci^=v3H zX__G_hqth*@TGmhHo=3A#qrK?9k|tP7u+b--wNklds0d9c2hKLd|2IG6*!k>(BUCt zi5!m<^^Gu=BBsv5!k?>Ib(K`y%5&?7iuc%Gnp8@x0mWFScR(^+!iH2@?$*zK4d!3@ z>AH8}+?%Fsa$HiU0`>Lx(MgdmTcpz(Z$8S@{sx&>!j07sl)&&@Df0z?#gufVt^cN` zc+WKwiWc6~o?9_k6-m9on5`0}jNCk6mD{k|l$vNSJ+g%uZhT_LP&gaaG|BMtx3FG6 zh9Vje2JX_STT(};()UDc$1on=3K(DAs~RPEV0H8#lW+C2JUDAN7|><5XB&LwTAo3S86`>%0$jzH@>VdrmZdM8Zz z29wUqU0l9${j37CBZI*XJiL|axN8n%L8+GWsEvL3zq?}q2WP^H98bJUOS~@t0J6BM z0@{U?wSHuo0u@A>1GEt+Ai=L#1u*IL3M_$Q-hm(8iGbW}TV+OMlX;<~+q7S42SI~r zMwwS)1n z4H|`&D&Y<=<}+0EJ4*IR(9pIcPukh!sE7ZME6_AJv4b&AET|sIxP=-1p({XgHx*laGJp}L7L(4RuZAm?jH@Fc3i66;m7R1D5 zUZfU7JksGa%6oqlbn7c6pY+DkTKXLCT?Ys{mhTkcJGpKdPO`D!Dr}1lO11+B^;r6- z$T)wn0a7uH1tGaLEwj2J_-~?Z`IQTg20?yFJ+QKR5{C`Q%&#Zrmz;%BhmzW#B6*T> zo8#VSU4(AF-$-ITq0xHzj~**OzPN&{BI=_t5ubdy=LlGVnH;cw9uAjptw?qPs<1Zh zJ_!2ji<^Bw(=u75cHC$@6k&pittFb3e5`NVJV*fi{G7zUp}{Eo>(Rc+ZEo(d6P8hb zA9vXj5WMx`1e8|U{~6}gySzg%v4}Spb4cu1YS2}QD~jaZS?2iGpc*M`mjB>Oz!V1t zLc`7=<*W;%lbUViqqF8{B$?-JF>E>Zt2O(HH?qpxod4JQtt58W%{hp6mxsl7QR7>t z1)>+#c;Ol;cqB{~UOGQ10>1>)jnfO(KWR&n1f;z`%rqF7@UIM!uC4=5&)Y#@!qN9koZk5gG3E0roG!5$d-D?6X%#!v9Rg!; z$oCEaMM%w159~x?KQ}8oD>wRe^@PMM{VZFKHBt3!@^$;!?#QbA4E)flF63Kw3}VmS zLxy3QD|BG_fMwv1+?2LXomQ0Y$Fhr@KxpM6%l2!>*YJ`}Y>Y-+F{d=f2)ql`h~brH zS)<=7Wu(R}Y2}-ZogT73^-7Bz#{1|^0J>2UF#zVdl{>+S0LC~_#;nr#W+9%VUBpcK5vHcT$MqZ@sdUX@wbic)fQ>-^$8b>ol z_nG=ESAIwk>u_NAOgN~wAY3ET_Z9nIlFPV~AXTZT&kls;WiK;>^~{kb#IMvgc>e;H zdPa>u_ogm!({wTgR14|^rn3TrXALT$C4c1h?6^}uH==zCj}s95f+7yc*6UNpi#U&N z)rdL3u7v`{FgLQ3z;1JKu6+6Q4-z|Gr8pPafBR7hgRvGGC)3_QhTG(qn`W znc0OX%d)h{w_B%1G{2BC{A=AOUcW&>oxgO+Gq}yOJp?ZiGhG*JRTL0Jm z4602=g!M~%nc2i}CO?G#4*3|HiK_mi)gCVjukXCfdlAQ>TkZfC?27K+;Q8PG50dp{ zqK<6Tm6ayz-w8)P1UYmDMD%Vp`o#xoM(1=nA@~2-VAh1#%xWFGjl$ZlDmhVl6VAKc zYxbt|>z*mDSZ$waT$Uk{UgbJhEFk1GC#b{N7Q445Bz=o z3Tx0y{?g?VNGd6LL*B(@?^UZ3t;U$Kpp67^Dd(Z9D>j_MzEz}hYpR^4x3Le&R^7XH zC8^1>9RyaeSK2pf!sozV;4W zE%%w7sEaYm%X1~ccnmw$cbX!^Dr+H`jesD&AsMq@9D-Sc1@hb|oI4Zgn;)Ygq=)LU z1hO4_ll~t72-b-;NF(p!PER~q8;+`s^5JJ{RRz#=F>7^n@+{sgjZ58JXlZe=EmX;c zZDpWEIDNy)v+kg%SjiYC&@ zVzV|e17^esn8JJ>Sp3l^9%B?+1OFfpEK!&lce7_0*Yq>;{C=jogKP_U1%n`{#QU5% zhxqu14cZivyoYMOh<*%557agZ>1GA5)j#LBy&7(ybFyGGKq)+>4S6GT`~V$ zk-IE)I(ogsY=iia7Ris1!)e)j+!I^vh1|Mc4#N*=4tkF7DiQhrV0BHw11*%=Y{J~t%%2#cbyNXn};)tJ`oD%~<~TsM$GiHpo*Qjw>o|L)~Mm)FWx z(<9>8I;NFSX4ea!6jf_pM)FwzAA9EyE{lSmYEbPb16VU^;EKKaBm2iK zhhc;7q7QOHQckrIU2E(sn>C2m%x8zGTW?gMCy6_0`SBr&54>9B=`vE{-0}oO%If;s z3DU8&2pL(Ny15+|GDE!-$#gJ&M)(ZldXcE9OZKZj@TA3^^=Ma65XS4~!>RhvO2|Q`Se7q7G+iCca zr4);h-W6UrxUE)JqREtH!4qAMT0CYH1InKZ{JSvXL)Y)8W)clD$-8mg!-B{}QzV{0 z8!dPqdImQFsx-CGC;%`U!S*QB6l*A;0ik4RiItQ7d5H_Wt6UsiCqfHeH9MJeyJ|eyx@+ z7rnDXwIxRaJ~az%-|f`}hU}nT>&RnofDIJXXw(_YC|8ALdFN@?%*)ugxB=$6ja(%> z;Yeb^Zbh_>O&dX|C&3~xef_?3EPNSD-GHn$Vt_C5*C{0KF# zY1Nw$__mxUrw^#2{r(AwcS%^ghUddOJJPi-q)58H&~(Hc=dhW!=^OR-b`b?rxgBd@ z_H|Pv7;p72mG8Oo`qAKnD5P~9)O{9|oA*)2IrzQmD4~w(ij%7$-h;?OFFTn)@c2Lg zVfk4y(wDW3!OD(1k>~yij=Bz`x6cv%JVi`T+(!dPaNjx~W|y-!u!CF_o~$H@%VkWV z!<&cA-*$nnY{9f79j2<6Io3aqU>Yf%MQ0M*N?iY_4{@pB&viF-FP$1BRkD`8W2Y4b zx1+}Hk@=0R^J1?gHuT)ks;tRIvT#o@J@a}J>nx!!5I`lD(tQUwI;jbQU%--!h&)-( zDzo;I8ypcGlq#25-_lN4?Z-}d5LooX#@*Ee5AiQu6~!S2|Dr}dZ?KEt{>%4INt%1o z`Ir2;>^b24@QZ$AdA_iZTG{D2o_wLQGEFmiSTRRL|e7|5_(u?`cEn8%gleBm3uzG}|V9(EX+8Dstx(gi) zoMoz4(5N<^-~*OkQ{gGewkbxdf&YRwG~dR%*wid2O#7Q~3#K^nrV{RozU5-HmO|7S z>^8s&Higfg+RDXf|E2i$LX>#ya#nujB#_;J|4|ky@F!N)op5fLc)x!f2^M%7TA=kLByd}oVw4|O}Fh_FKmkIVCZBG zv&a=5H@Qo(&RuM9ZqcrIUW@fBHZ{hTjD9El4J{l#&goLBjbvM#27#wl?uUbcbl^d?~jUaMfc^ z*7dJF(9&~PlnMgc6+aQA^h=zlsbwFPiXFVBQLFQ`2g2Ev)RweQ)mybAlZElW5X5QE z*$8^w(H?!KRrKpzKV+PfivJ$CLDB&3JGd(0>N~S*;(vBeNE#c(J;WQAGrgGS`um`O zk-ryljpVi_YXa&<2N6BIX;56ky;W=$$!_;)ZnR~{bD4od=k#a)qyigr?k4q|_P~fW zs5iBWHkKDAr6hFnI2i^#jwgE+3`i0@AsgzngKPx;zsT?7pK8!96l3z=us#y~AGc0~ zAE|L{7&APkDdr7(vwLx$mMw()tfnvZd-A229x~`uxd3oko{GC+z9*5b8bzT7DvSq< zv#%=7q-7U@Qo?ExWDp^E*Kou#lh0dyu9l%@?J&+Ll3nvvCZwL$5DBH&4+c8qUXrDz z^L^8-47wTb5oo?AltBlF1S&DL3%S(5faB^53OqNX5I^MOY42rE$EFCe1aVo_O|87_ zJSD7<=I=>=i)v<=FYY9X4-*Q2FgZ-Ab%KAY!MACn8TrW54?7ti{o$6!k`K*rlDdIO zEoTK5&52l^l(NB~BIgOKZ2|q@Xki`R>U|%@N39cM435?K#JBYS>SRW!fRy@7SGl{2 zmOIQbv4e-Bxi^fTR|bt!YLH8kRXNUVF*-oH0k)q;D7%+7(401f>7?5$w5^fH`X~f&A`4HX!g!k z_%QB))#0dR>aLFouI5k zepQM;vg}c*fQalVaqhL!&gsBX3WWf$xwd6v``v6IoLwGYl(VgP82cH>ygv~7Y@mk8 zGUOnN6Jd%0>VCB5U%<1PhxErFoKx%Hw?%Ncq5VU_2ZysT(1{u(GZD?f2cZT&^INYF z@_*-!XzH%@xz`DGJ(k)4GZ#nlE)?#qskU`+u*WQRDrE&Z%u9-@`P*VC_VAjTcbjhY zQEle%bOWu-%SNvw7NR%*{3Y{?w&bNw97~1A5a!V01TVfk>f{RCQfOC z9H5&W&etA{^2(}8+VEU#^z`2{9&M;4hi4$TV@ig2yW{K2{Qr?gHdA(y)8LW4%MMZ6 zN#0IJ8rKB~euE;?SDGW421MIX`kwUJG~t!qr~9Jz=;RUW>UU+f<(ZY|G&Mgc1l&QM z26<7=#L1)cYV^=Ixo$8b`SaJ1TGUuFJM*8s^@se<)sA@g+#=kCY}R86LsXbv4 z2(}GVwE&|1u!4x0K+h&+cT|*vs6ed*r+F$65*+Yl3I$c56mZZ>onqZXA3!OF{vb`@ zQLh~t7s}!Rxt?55CL#h@i$pP~E|u+rVtY&pdO^|q!LSYk&wl%F_7F&mj`NZ^jLW=G z)3IX~&!BButd^?8h!ug}J*zf{uxruX*U+1#sDm7cTKRZ3*2=lkKbxA)3>H=fU*$sG ztbi9}$tLqSqXvF}vhS>wz!Izl9yn$J5AgqFuFW+P^_~>gis;b(@?261DX;>|PjTL% z!z#TPiIPs5;P_LU1HNSQ^XPa}UVU0&g^ls2qjI+uKFu|XtalBn`Cw|fY_=XAPduc1 z@SToAm5#L?a~Ouj4^Ao$+*NSU$mrZjrfqc>WvL8FcjQkkK3whhg4%nBPS>uTR_3=K49@LBoCC|9XubXEJyf*fJd z^)4e_b@hX?ZANu5%Xy0ZHTupSnlF_2t(%oKGzKXFf2iC#H<5LRBjk!cVNl=&!q1O* zMhlf08??uc*OlA;%A6nX6?}g!yVIWFB1FpByod9k*0uS`TDtY+%ZfQd z=+iMpZ0uOKX|;WA3bmoN;WSG1Z4d$yheCs6w9dkZZ`Sk_|BoQD`d<@=?#QaUTd#ob z2uWqycMz+ELU#ln-8W$;9^elX26<2cgCwmXl=n0(%i~I0LbxgI{0VIa`)cpUH}h>& zHsuRuD1Ebom(;wP3H92+Xy@N-p+^hs_5(j6z<Ce)s0igH47KVBa3Z=X-+f0-%l zU|!JQK?FtJu+yO5-Gea2^ofyIdDaIw74^Zu-NP{=jjuj=RxdOG)el%`uHM$QW}hfi3d7I}#fFL}<4#RjNX zwpm2;v_G1PYOXF)~vPp7q*jQ>w$mvMK?3KNg2&66VTX-W)_CS^3dc9A-C2UqkFx9)%DXJxo@o}!AQwbFEh*O-S6J~nZ}O+diNdA zcpis>^H21HSvQgBD&ok?ZYQ>iu1RvQYUVzgpatabyS4Z* z#6z?s*yAqy8f&FJctGZeDIN6|1SzP%NGhl(hdre!nFy%ZIylAI@>GFi3nW=8ADJPu ziF4JN2xKlqsNtbkw=OUXVLTE01uGnRU-9EIs!ozY{UblIA7{?>n4)}~xOL;1S%-XDfF7Z0j zT~^&lUFogzThm*4i7{OMGfrxC8=7P2n!f>TvMufkOzM=TuWZoOkGz@nr|bq;1O1cw7!a_$5l~ETN_{E!LuZHT<>py%q`cJ97V&#GhK>rQ~D5(5S5wOOQyKw9hX7K)SNav(g~uA-M2B(5p%rh=S1< z_@yk#mr3TCp%R+QZcsXr9Uvp?1v}>kTUO<$L3NCcBNLAGeFX%3yb~R9Fu^g;#;g*P9p%XI@gaDBp(78F#S8Se1{7!`^4lAD z0sdC0N;7VBBI?qqNpQ8{?(45-<85e9%&)Kme*}AYm*WJR{Je551qqSZHD|t&)0x-Y zRSuI07Ln5_J^S49<^a`)LoZgc9=>W&AW*+Oj7hz4aN-#${vz%U%LJTjKJiekob2!S z79tbC=yt-;YGzvUj+38>vsN2IHNnU+40p{OH^T6>hBYeIJY|0F^rbqQ{GAIHBLPQ5 zg0Xk3nO(918k79<1<>fU3!X1DRL3;}k(xNDcT7uvxWOiU^=+=+`H&ac8y(NG0ASZz z!lM-wD78cnf&zy{PfT{6VV(Vt4yyUhq)mCsxAwc7v7~Y<2J5I!&-xaGJvm)GWIEBY ziYh#~NN;Z~T3$K){UTevx<4%?TiR)jx=bMSDi-+uzdGAf(TdvCTyO4jW000g?G4cS zM(DAhK~QcZ4X->e*}b4gL8kQZ=j89pA8tqQ$R@KlFNJ?h!MA_?SW3jeiaHoamnaXI z#1qH8YyYubEf=r&+5P!BT38U9B94S!jdQ!kp2Rb+B_@a8z|9`^k4V$3)@ooNhq3UF zTkpfiDG;_?d05M#4X;HjIyPjVzfkAfE$%*#zbJ{{Wj(G~bJ!A9l zr&Dd&P@aN$pJvALdQ2zGEs>&6E0A-kK9o^OrZ8;EE!|{()v>CoUVu3N*8?8^fSmhJ zelWb{9qnMEHPiS7Jd$SUfFBh!it9;z)0)9_nZ2JIY_InlTQ?aLA$$BMt;jq*9ik*B z11Bf;R2F(jwPGGRPos9ZWZ;p?Ue;!dki+)g#lBO)7G>OyvZA21-6dn@niWek_tQ&G zOSE~}lBbHRsP}+5t1UPq4LtY?&U&1AfQiz$kpoG*-*9dCa<)psF3Em-@3Nvql!Zf! z_mrQS_VDl5ZcT52tH;2#_FI^uQ4BYvU`r2Xt%f+;=O;XCr%aXrT=`gubdSxhNzDYBAu}18`77}sL%GA{NXaU+!ijrT zDbVk_SuYzWSRm&#PDuINQW@BXMTw|S?BZa&FiKYLRtovqUR`)2By@;Q?4Ec{VW*Iy zVIHupx1!cgxg8hzjIxj?e{fbX?fk?w2Z-4$@MhE(ZQ}1&?DnQ#Qodj>mKUVxfmSb( zfr`&C=&;wzL07ckY;R@W&E(}c0X?Sx#u=b_ZDnjCc)w{CnTCVYaQ9&%6O)EBe0>)0?fOkwBl462}WcQu5bRlRqStN*=r4dQRI5 z@xk+$+y(+eO4rm7!s6p^a?#1w)xp%;w*y1Qu8@*~>jQPVu6Lf80NI3U4HLc_p_qvF z)55l;Y7Q7A~IStPAEs&WYu_a>NYh(S{diJ#}KRWw3D?@PY zIa^TPb5IVC0O_m;X*=kx+WJI~FeC(77qYVdNTWN1gwbmws^Y(9NH=F;oss zH?xl<}n6~J1np4c(x88;7&`-Sr=8x~?|BWn;-_4EGZm?=k>EoZ$^B@K5re$An+)jpiT2en3iNNaSG;{8~+>U3- z=}1lpQ;>zLa6OaS6xZjNGMO;f`-MxDjsdaeUjiAc8jnK=K^3Qq=L=oH!6D64uJ(Sp zwHfvGz~}YMr$%wwDS0~(6fL-_^;Bs01YgwQ&|C;IJdS2e&FwQpL-UmH<1s+} zCfV7wW;^23HGbydnJaLxP>*Lax$SJD98*GAyx@N#W9XV?x4$W_M@7cQA@oc>CDB^{ zu95kZuESB-_N=Iy1mI6a%>&QV>WV9BNyov69cu1ppBc((Wu52xx`~-HXD#|6=zECo zP*0-M#cVezK#St^Cu*)$D1R3O(7FbBvh;_4PX|kIJA6>Jlc=90Vmc(A-P{=!1Y~8f zr(A*J_#;tDEbHY*c$!UU7LUYZi`f{e|3$sMCZn2hEVF}?3p{_qw`SUf6jjMm41|iA zV)aO9fXHlQz#lg#1QG9I3erbClmNin=!g0GBQYRW91nx4+7D36JNyG6ZAx6uxv>2# zaGhU_`_i}ml6wd~E)5h`2TfcruYKU}70!pf`ET2L;?&}p{_;Pm$NrJdH$MsOQDU%--2B{VR{5JjfL~WO_v35ZEeb6K`2TT zATr)VJjJ_}f+-zW#TB`w$qIfL6SSzyLCDcc7ISX|_{C|<5_}xkH{{ipoAy28M0lvx zY0EL38k3+}j9fdE^+YxSaOE}|;pR%wCu+%ubXv%!PlUISqvd3c`}q79C8fgGN>mo% z1C3-33i(3KO@%Tm~(%+TWanKAn_M&69nZph$nRErncG1mCqW=o6h{I>M0^0F$apq}eQs1=J9>E;wI!UAJ0eQ%pb;RDUBA0!2H(H`Sgo8j zW`Z(iGI^vlKEJU+HpuTfn6U2E^WXG$~05JCBEPs`` zjcq6Hy*}!bw`scU=xA<`tc*TV!5Ytd=fPr+jwPz9BSkNxAn7t65VAA$rcki7Bn8N` zCozZ^!tS_1?ZFEE<3faTp$?gG9j%Hr^l|(MFs^|uY)c!HT?n0Hz#6n`5+KIjMJGE@ zT!Wo&+4;~vz6Y7^26^>GhI@zDr|+{W-K^@z9JPo#^w@)@E#Y_uwZY>6UQ>JEovzeG zQpY(%YbnMVM_;|>`Oxlr)9}a^8WP8hi;j$U-vIAD-LmRVYoq3yAVLI)+1Ymj|EN+# z6&RH1mL4+I=1uqaW(eK>wzyNFN~j2F)p?Gjd4`aPIR-~@hYxquC+ztKK*cQ7`6Ojc z398}cr)L20;slB#u=ECz>{Rq+a(4=3F#4-wNbH%$3Se-m)kbek-&;*PjcEG<$P0#x zQh4c5MMeNYfSTp%uB~1t?b@}?tuDSp$9Q=c5csI;5dn#Ch9=1x3E$-PIN>-3ZS&UmCvd)d z4LR=NZj-2rGOjH@vDr~)#gL#sc`yC|pn#hPi=3)Y+;kK;Hc>yO(m$|Hm?r8}gc!)q zrTr*ef9YkweRR>70|hd$-*YS$oPoB85 z`#uSTNgIOKG<|^!oU3$bVXxEI_Xf=sN;G!=CEW>FH_ScwSwr!>zevz{RB7@hMQ*A?5jZ*7urbjXU}6ADg~djC#*YQ_gmo( zgcl8_520{2;;%TFo4__LgeX63Yp6*-g3c^U*M-}G^tak-Tf8_8na^%3MZ=3fXp*iv z;e8kS_M=NCC0z6j3%4HJ-?ib-s~X{+#j{985M|Gc%#G9;w1Qa^wc0nj#d)5+EQG7> z4M)8Ejsnp(xZiC;Ttdx0y~UFpQ2F&DXg?R;;n&_b=` z8svHm8s7$w)>r1z1KI8Uq43fT|K83LX%%}nUufR4{_)CjI2X>&wY*e@s!Or z<7&3W+8%v3*=1&wIx<7=gRf<$Jm>D;MJYXz`|E$hSu<#AH1IM;zzr36M1-&7tp!I0 zskS;u?Byf6m8R#g2-t1aaRd(uQp6z**wR#}#;i++SO&wRsX}DH1;}d+ENAB{fs^(=zZb(j;m@BwtD%KL(a!%+}0`t91#u z*A%bC)ugF&tvWdTC~`8J9*o~nDqM^c^o zcj6y*oXU7MWv_qDfG|Iz_7IwhZ3>MQLB+(S&-}nC(S^yaL(3TvIYIUUpR3_eRHDk5 zFsjR|*b)AUEz!@*0fK?Oe>Hr)dakvBWzxwPYdNP?lX7IzxtdX%t7s}_B#pDYa#5Ql z7LYe-EOXvXOe8=KFK!wp{}AHxAIO)@5P5?@-E$aEVP_F? zvAr-ZNNKSy%VxtGAiBy>^e00Ea{Kn=Zk?#$N9YI8ND{M3|}p+(zf^6O5>+t8?KxSJA@srl26<>F+;t+MZB1PbMY zD-3BCjRMcn=uIl^EPp4D!0tVWejQLds$mpoMnE)VonI6WE5`3K)r60cd?7H_A{zD{ z3L}@xU`w#u65%}7iGVW{F9_okDmvuO7oP$M%1i+h!~CclKEZkC;ZpJ}33Sak4jBvp z-ZmoJ&}ke?wz4(hR9gBUN5zG@9{S!z39f^LJd^jGMPRydZ8&^!4d)RK!xO-<{sOvJ zEcI_gl;(8{Y{}Zc;W&jw`mx&5d1G0kt@tELYMy;zqg?pC2aG>~;=AdBs)r@xq<4b= zkqhGW^_Dj)&&kL)j^173lYmPn<1cNzu0s~y6-0zufUB#9c#Gon*N&S~NHwKqihum+ zg}{U)U9O`c<1<=3JE_^N?w?yP2l*P9R=g&+lLc;W3e3+kdDWf0=Q1;&YO0TAnr}HZ zc>HH3TPRXa^Tjzv9}gRvL!Yig1)jo)ZF7TSO}Kc{h^a@IQ{l9b#%%NS58Cet+oO(! z|JrV>E-vHmIpQ3%xcmp&enN1EULcvbEdhWTmu}4_VyP(L7@BLX-P6Zc3oZ`{7?^6+ zGpd-a4D0?H`lKU8??e>d$;H=LmJVBCVA6b>R*gK`;G5ipX3(%> zJV(%*M%XcX6)4EQTRI+NbRziGte{-4t-jTxc8@$0!?7E{=9_v4(|#_DY@IF&PP=99 zT-~+c*PKF@J7jT(JE8|hYEb4hINc)-?I8ukESeDKb%WT3ReLm^xiwE}d{d{6tnP37 z2}W!w$esRdOQ;N8OEc(jaUvMG-Ans2msTGDl|72|vLgykL<}K7+81gD%CocWkTa+9 zRp(Z7H6yOYp?dVYVR||;6I^0il8F}$KwV*MA7=S*3?%F+M)x5!#WEf;HKhR{6!1lb zvH8*&m^-;&w$ZI9z}O>5N?;baT=14bGssjD8Nqd-(6FB0NQ|$ ztdA+AND!@h7fJiJ+3I!_xdg!JPN& z(4#D^Cxy%eJ>7o9JZkeuS&7!SMKo({0KVZiqAZ%Pq*I^iPlO_xNPF;wNG}mdxmEXl z2eZlE*WP(_9Es&RH_*ML@;nI_3(RC~4jt~=7XRh#PH%o#Qw;MDP&%JEwPwNFNjGT{ z)}wvoLdxoT1ZV%?*K%OpcjYHZih?MnpN1CracM>U4I|G;e@R6jJmskjnOd3G%;n;B zgqf+}I}h>FlGCn$s;OE=P1e$H@lGJCzs)r1PgW2tdo6a`WZ

  • huIcKo4B!=X-(}R{%rxEKa!XExd@U~)##boq zfl%e!B&o~yrQJg2V+zq9bhvRyTp#+33=rt%EZ*KgaS+BcjAg``OhHyg<`EQ zAs}z^ha}$(U-$PG!ze@G=oAFBl=WoZFvvlPLS*B12Z(ROBI{ssP|YUP;ui|Vq*Ahu zj($NpLxSKfjW=y{{9D=QxoJQy%iu7;n;j`{AS8J1G*8rpahnjKB|1@>vZ-0Tg(tMK zDN%x^#*TiFxJm}D7(mxP3O?H z0kkv16MYQRXu=1WzaB2a23D8^a`m@CfKAl4!&VWohNOPoosxj~(>1=SkCV&d#~K!OT5C4<%dc7Z?D^G zVYv}ft|fl9fQTDjCH_U&x~_WZ#6Mk;6?_U!sy(8%3NgmMI&ADMo>Ij6kAksy(&DWk zD(YA8n*E*TN>*~Er)a})6cpxbDVd1d`(bqeyT({@SrJSDQ1C!w>NoLnb_eT&8>Yq` z#qc?iS2Z9Xjt$znz@qIyJl01hzqGuKBu@JtaT>8Lpd@ZY;-{zZyO2?cZELe#qCW### z4{iF~%T$n`;eh2B;h&DHuNr=)lm2~6Bn8NV_xX3~w5bYDSQfd<4I(J%1=n`DknDr4 zzH-1yY8+@dyU(e$;(;iMjve6_rHm$1??y-d6_lzj=7@)78)3Uf!WlesF zY`?HiXdL;<&p`Pn_5IZ zID=kDh#r(j({7fDBlPhkR*#!2vR26-t>NI|u^E?J-H9LcH9m-w$ee;`MW1_M`rCI$ zX1>%V1ByjK{*Vlxm>NU*gHko)UnaU+0JlxhAg-kr*g}P5g_Z;_*{}{46Ep+Mz$g3ujswKm~{bWDm`rf z%qDggA=GJ~C48hwQ7uewKOh!xIPPuO({6Gecfm_W(^MaezjOae*bLtBSC@q^(Q-86 zSJs5$60HCJ%FXP=hcTD$Az-0lkOBRoOZ#Lsr|J|EOZh7rPfSboh?-EIDKU~Uju9i_ zgRw|IR?Xgwlp_aMlOQc{i8C)$$xiA};|>H!Pt5g4hCd`yN`+Wn(=#KP`b-khdnG?AUloIezmn}1D&E+HptsvVfrZt~%*!yz12$*ysPdgy9Uv!80>-`;?< z%gNsa=we1>1J)wr^EHj;K9rNNqBiSd1h~gAWW>pz;T92ex4N^y=O$)^ z$Lb?|(+VlECJHPFfQCofKL`K`-k)92fX;V@QBklm(wf{d5+V=g37&q!32?1jeD+YZFZ|D`w0x%!P;1dSZ$T_e0H=yrCu+2#esT@>eiDaLWp(-*)B#2 zJ1$pK1;};yF~%BbCw-GucNAei9(>Z=##=dO-lQ+_1bm-l7sIUI=Y96RUVAe;SCyI# zjT|#ONB;9ELIpN5C(ZJS7ey{(+q0zaFHNFb><_dmad4Wx41F09(YorwWCpbUm_JL$ zLxD13LBHHf+*{jJEZ^3u1nkB5^)L?=ar=7MZQJ29qFkJ>a1YhCS@lO82Zby=1Gbai zvM9~wMLCg$CjT&VNTJq;R?fmRPws4HaxstfLp1uy`|NnJ)x(xP^uwXUHV7aLMCBfo`_uy66JK*wNq zRl;h=+_2y~;K)7n0lWM-R=g)FuYIT=;b6=Se}b@f@rST-$(&V=7_zGBiGL~ zWfX~;*Jf>nTX+(1mU*v@UISm$d4e-sW$Pk}d~lE6F0DLITHKc>n4!2`g>;EPFGE$h z#p!SGi_0HJ7aeFI?}mNLdX1?iEc6+|Y^=?)0&_Vh!K{f08*tL;OG?HO;epRP8<3j1Eij-;Q>J86gy4F`Mv%=4^cgTA@G zbb(`hNp*WsN~3j;0}%M<8KmAvv7rWn#VR!#?nBPe&XvN40iwrKhn3-t)6eJg#1*^a6De=D~2D|7~Av0vKep|x$Qv9c|r4RSq zV4Gv})y2RBX<0!F3a5aiJT(nm(wh9?(0lt>3K5Fx%|IsT-(y$>Ts4Nsiz`5S-@;@t zY295qQQ|G;+khFuuI3PS)g~vRniZ$B$+pgd5k>r;kdEB!croI&d@8){kUzSA2K3~w z%-?+Ls5_9IIIpjvB3}fd)V37J<*($ue=T*tfxo)(EM+IN7DoEz;&(KvwXQnxy(`?= z6-XyVKXRE&Z)B((A<2$?VYpGfz4%?IKFdtjEErmj?~{ya8&{KEpS-14h z;`q`vr(V{w?~r>uHu0|L*CQ2=9qTo!k?Zi;i|xMbjp7J*aET7)!zmkWhJ>lFoMEbh zvXa}^1ASaH@ch|?Z8J+M?CQIJ<8nKKF7Xt&eLK*{^=EuY$+1>0*xDMIksc}e-P zGH6nYNhT~ZL-7Owm(gckO~>Ez(DOiEt7)7i`Zzq1)287_#vAoivb$4n#&F ztuS6H;Sbr=R`au!HT0lE!tx-&&QyODgS@rziJQZL5OdTRl=+mDK1!=@@bk(c95aAZ zgwxU3CkQiz9OPSp#Nb~ zE_E2(bjD2&;xZB?KT3;1T)?)=s{?K_Zf^^M%usdgmSW3p|4=zEV}S{yav2o1=W=%0 zHT)w>5nrLx>W)vR_)59&Y_0JIjM;I50&|l=r_+_C{lA9mW0cC`^zKp7FhX>0tV6z| zobu08&T_iMCxdQCLy9?K(1k)*AY5thaXvKBTxrR0!07a0C@rCwcwt`=c=Z~F3JC55 zqi^#3z?sza;^l=f!d-R^LXP;-RAIg`?_Wk8*FuA7PpA_8y9P2q&IKFzD7XHK;9Xx( zlrs4WP%vmnmED?;oXFP*#+B{Ud~>-tMdPUv1Zv2-*{eLZlHk9sPCFLlaR!QxLD$|GX1A3LV^dyQN) zf>~t|zH|)kx()pupK5g>qOk`vLJ3MwA$u3Aq)>|xVi%dEIP>Reds7DIhi)#h&0L#u z0(*rTI5HbS{6C$4H$^+8D`G<%-r+$yEGXIcl7qPt4l1%kvY-Ms5S1Irf|%Y{DdI3B zAkJH|oUKkgkR5STUiOb9>@js2~zc@?D4mwZ}^w^@7^1dw&<&t0RrFD-$b4uyEGcLZX z2JT-s&R^zUoh~q%*QFA00}#WEyP=Dw@7a@Sr59Wvlds$nTWP0fd!w+Q&J?h9!`gAP zo5363M2W7#DJmz}_3N7Crg%A!(%~jtK_wY^FLv}TZx41I54Jhy;{N&RIYTZ={j1EVKOrnpU!@L}!Q~V9P_6fR8S>_=FL|NpKyan#KEw@xRzAMv zq4s>w3T5WV@qRd@xE-etg+NLX585-6{b`hWj(n!5Mu_?x>6@&YP%dt>EjcGPe|y-f zY8k6vZrELDw(A-iRB)pZ$!(}zl>V}0+Jf}(Uap`7xmIQpkAyL?G?GRLkFkLa6wmO3 z4+RKhs&O=B`}>S`o0C&XVpiBXFc*_nXYF*Oy?APJ8N<@=SObr6=0Nz|v|9cl1u8Fi zjW?gU5SC*2I)STrVWFf3rzd3>xhrvx42>vVXJ_t@f1}N68~4WHgPU&z3N0dT)E)TVbe#Oa*UUK{egfeT|GTNo`tKph0v zegr;h+Z&LLaefc1b3#y1#U3k>>T#w{lV4R5slIoL#r4%eg<+GhrO9pkyC)dtmWf_2wGwfI-!yXk}q3#yKt*N$$-wRNS zO`u;z-)5^}*0qzb{q^ZcAE57C=jBHE8$%>An*j>R!;eZ9;$$%2n<6U4ap#HRe~`d; zsQ6b5a7tL?z6nL@Xy98;;KQFpJ;_*v$ibp`5jd}+LZNca^1X#Z@T)kvu&J4-i1WjR z{Vwq9S`*4{I_EkSo7-oQjv93z-f7gm+Bu?}m+FEEXqBJ9z8%ohRvv`qPl$MWVtgQ zoIL)|IBS7N+syuAo|MoD6 zHKlBu&MoDw6*$fDWAs&B%>n*S$aN1ni21DQGeGd-c>^j)b5G7nA8vpTbNbanaLpQB z@*M%qbyw6s7b271pm>!XsCX(f@?cav>F01hyV=9}a^2QK#;d{)VnJiTY{KM)1*{e- zCWh7;UMYSVgiO26Qm@V1z3QouA7Pm9u?YnPbZ3_76O#iw6D$$~4zPWetyjsL-hZsC zlN{)I-Cm8nW7wG<=FZe@mYHR?g4LwM{9=xaQRPyIQu!`|%V~cESDxPVF#LhVu+?jb zx!G~8AqXcesMntVNZWkg|H3j4)#J?%IVCI=*zO^!=PJXBbL-Kw9~iP#pz}yS(@_~C z3>DWUg1pQ=6A@t$?F8vCC_Dn@^M&t>3W`c(zS1JmQuP~Qwc=b*GhVgB{ZE3Jp0slW zeR1vFCDL&;IBY!nMYsaCQcl&`nJRdefmgwsE>Gjf`IamSY7|gK8d{F@01*t;(k8p4 z72M1Q4~gHq6%HC0IudQ+f0QuR3Iz}e{=wFTJtq1F9BEA+Md6Q!l!OofA8{r!L z-|rOWBkPlskz{cmXi>nB+_8tSmP_Ppe@FHz2#C}T;5T`CK&_yw|7@KDU5j9rXAo?L z5Xr*{lau}DW`jh3O6D4s5ZIqGq@H9ey3Ge?!`62`w*yXs10>I?+XQ?!j9g@m1A+6K zAw3*?js~%wYimr(ap;s2^@F8#kSx|_(lZQP*euh_0?lgf0H=jO1qP2yZTc9Cg{Ao=kO(>157)P z>7C=i%--)DizTFt)fG;nSq~5Z77)mb)O}55qI%@ru(fc+d>i}Y-&~1BcEE6U;(VT? z-5UP+wwLTnUKx?z^cK)hYe* z3;{4ZPwe&e9NxvnhCr;ZJ1kC84E7TFMZ05WjKmsrScO|gXcjtz#kwG_uJ_fVXCb^l zr{))B^|ha+IKZ8lsQe$D&yV`e(u(!;7lYsB#WQ)Z%6xUE#%HkAzt0l9=C$UKI7mpH%CGhTbJx?B z0rU5j6_Hr8d>lCjR+OHN4P^b)1uJ63C zIzYtnKbl64=rXnY>*W~r0Y&r>?T?I~J-2U=^`x~T>zN1ENLc=f2))$NXJ!PmrA=~K z?mKw9<;zEj51zGIBu#0DWCiq++pfg2u?q#cj*hoj7%sqt+R%7W@@%x;LN0I3=#m$c z>8`bFDp<~80CmpJ!HDU9$iiV}UoOHY7|nPyx~!&Zj4gqKQ0*3%k3R?aL2C8{h2XrR z)+W=BA)BXR<%B8px{Z)tA|YqEEbPl3#?C-08?BEoRg5zXN@1WhVhugt~e?kbo2^9*6)v;C?pQVsr*t2PAGf4z@R=qam~n6J3HfAgFF6;$1-c3(4Kcqk|6{kD+W6gJI$eu*v(KZBTU4NgDdDED{E1vMr{~b;NX6) z<9~%SH#klc94S+cHrpd$m(wlB4wpQ|NM@QE0rvs~svt6ZjK!iD^$ZhUN<3G2IjGvR zS+=}hXl=lAzi3y)fZ7x1RYyMSmjUjWD1zDdx(&tgjXI1~F?$*kPta~JolJ-( ztCR@R2j&+@Y3peK2t{$vMK2EK?%(wK zSmZ{C>ak=Ft8GFK+=pkA_;bz_cUounNN;BDx(FWnw=GN{AOc8xp)?DP zu{+UZ6U#7%?nS82CxiX5ooZou$=3&f&ieriKD6TK_O*q9mM zs6kJ;IuSiq9Bze+FMgh2>EwgR)u#dBeOkN6d30j_=yG_hj3HB7gYo{V!$eV zi;$m=GR=L6Loo$6zaU}@%|d5&{%L%Z*a?t7P7u0Xf~|BiZ9YC)o8Di{chz8JR88G! z*Si8+lOFs}_c2{jJtAgO0}VbxImYkjB($+Dw$)De&dxP-MFQ(Wl^ zXTT`t!|HHS!D>r>-Q8z`K2sJ&VP4<(UiGJ8FI*3C21{VZkCY%i^qUBtYQ1r&r4`S7 za-fdb0Eg(Yc;>)%r5ck)0cyy4iN~lE<)`M;<*RDH+qx%qpxd3LHED=K`!;g9k2l)N z_+J(rjL2s^yyn-Ck)aC+fjjEq1|6M5cTcHTR7_P{si;H>QnoO@_l*n7asU&X2BC4Q z9%bw5{(aMThn~fdXe+CYRx7O~DUY28<&G_lVmW#YGMpJd8e9Qe#M z`hyg0&zE!e?0Rww$MPbf#-P|DJZjwaH)EM4N0QmzDvse0z-or1(WlFcG>NhiP6;)0 zRSkJH;LtF3F^}=TKN#6A-*KDla-`rIIj#~_TTwc&w(*vaDTCwqZ;*1W!$J^rwM{qg zV|!Y(1M|_i2=pRTQzWxFGvL<1UI}WHJs`<&=-ebW2ww4r#UU~}E_w3}Ikz`YS3~nM zNB&ek!PkS90Mjy~+HBqP&g1~~3Vt8#6JlCX(dv1Si>1={pIzn<#mEJ&$ zZj(S6%a63Siln&G!CA3>FIRt4><;S1^}5nU4Ht9MBIRk!1x1|l!Vb9>9Mn!_2%Uz- zfXFdbHRhE$d3CCwo+iv~5>8)6Y(MbTbKQ=+n?-4%Tu_uP=f~E=cGx45~NGnNFkFo2~@196x4fp4S}FCXUBpZ*lqJW z1l>>xi$McEp;|{br+5D+NDnYaqy=lM@&aMpE6@;{VK%Nt zWoJLz7HNNsjpHwrAyDHw_iUJ7H(uvQy43F~qUQlX{nD zL&Tvq=u&e2Im$Z@ahC=!@k09rNyY`vn9%g~$<`RkS9 ziQB%Rm78Dq1pNUd7TFD`MR>5)LdU1JWax0)tE_4u&O7C+%$|h5yy$VKGC1 z$pX%;dAI!t+?YaAx}<0<=C&kWW7#C^@meJlhoo(vx96*~OVs_3R~?G-;e=xl0@1M&-6g0gp@sUZJW|n*vO{Z1moh|bigA7!Q5}tYnd0|i=7-d6*mkLSL%U)lXTTeq zZe79E67W(72HDpK8Sk2$F8!iktI!1Bj)bXGaCRx`IB8&uX7ynQuvuzrMS#R@+@8|A zHvZvcWDahNw2$R4D9u9uLdw${uf|{tvAjxsEu|@ddbLamb_vqMa364^? zrn*kS*;Uh|GE?lg|M)BZ6}@JT?K09DhxUrk+d%7+5n@D$%)#=xSK8v8P{ zMl+Kzo+sc80B?8d?2A0S7PbJ#L^9vfC>tqX&uow`34v5kAKR7PCOG;j5hFAiT@KKI zzN4drk&m}X#pbg&a9DEh=(IiwfytM8Wu%V_(`v=f#%u)qII%P=4XwGa_8koXC=3Dn1VrGz23Y{B;ChURV89LA2y~|Um3*sM#Zj+M@el3|D0mh2+EbQW z<`x&;I=QQIWZ?%9{6zb#>VVe-AiApGMGcx<@7fySx-Y~!l!P#LHr?7w)IGOQC;Neq zQh8yCxT@wU5rohwfsovHMX+HMgVl}=vXs3>Tl}!bgX3&3NxI(z>Hy3b1d}*7mBD|s zb(6S)RJWiZvjzb;3GXi&IzB12Z8z9TB0k9)+T~}82yL+>aH&gFzK}NY$y!C5`=g$m zNz$&rr+k$GW)Kn%R4V(4ohp3AH(=-!!mt$;=ZhO;E!eSTp(SUz(Z(Spc7Ejjx-p*d%2@j zpR~>;FBpD3xb`T(;|RpJ++5*3vQvtzx8Ce;pRmEmR5Bd5G{n(gc24B(6FF{R10lhG$iRPPj9m^^l1loeZnQY~H z28}kuTjIp4WYV+D8j3u0;s|M&lah(JodvZlRj!Mbmi6v`-%~DhHw2MkZ}TGu>kHHm zEsBPF3iFy#g9aT5|Fn~xJM=m8o(r9hU-)3F$*uQt{Uqo30C1m&@HksY5v^!p%&}={ z1h564aIy{zd!-ExAe(;;p1PmM5U4M&v~uz10}$CQJ`!Mi7u{gwaj<1FyURxzrd=Vi zeJGAKlN187wC33Z0yuK@KL$x_=H#h_9a6$q>wFZ|6rQy06c9Int2s+ltbMnHvP@?> zv&nSKsAfI>j^!Idp&`|mz9d>ndrpY1Bz#Zi=+hir4fbadS01xaI}HTDhat&ObCE5v z{6-b?n6oWQ!~Zl)bVyL?BbyzLRA0#DZHTW%9({*HRB>LR96)z8)(?AnVR|SiVatRF zC2EpK`~iXp$r13sk+;r+N}SrW6~*}_0ajfKH2+W_XEQ|5K(Q|T9!XgvMKv*QA>(yP zJTl>ge|f!E#-*Rv?wa5xX5&P7ZriJQq6u0Ns<+#(bvY*BU_DdJQ@-IK^-+gopNxnq zh%U*yofbn*5Zs!kF-H;Qr=kO>?WA#M{yOj3Q$&ufm%nn~iwM0h?p^Ty(LH-T5r1E! z&Es}x#@813v^N%xugaMkQycM@%J6mTVm)wk54ztfBEPy>xB%(W$9V0YJ#G2LV2jp0 z-7kqD&%q-@6K6l}R9Ked=Us$=1HpK%u3(4P)t$i<&Y1$TnU>?DbOlXX3yz9`#{N8; zcCUh~Fl#78Qf0Qo*^-_m`VA^RB_HJ+oE2#WO#2f%wg9M$7~-FRQmmlk^UoFHMF-Cx zY_BJ|=&VebUPG;Q;M7iTWfbAScme1MB{&dBUDPtfSe7;izA)4e~hQ$iHG6{Ac$&FDpzT!d2 zudRNed)9e^-!X{!L-!1b1f2ga)4p;g)hC3sWIrCbYCKi{jsuBK^LSMrQD<4 zF-2B+bnCoS0a+`X1HQ>x5209SlB9zrHZuk&kE3YnPhRn@L<9hE{Pz0PBaz0Fr$BfU zuA0w6!<4MJ0~Ube$g=2&(aMSSB}w>7XAQ6Nx`Z?sxu=hyQYa|A*U1X6X@=DWOE zTgWzBo&kfu%NR7NslTI2E2_|4PGQ$=5}r0kP?fE4176R43~yw`5aP*RvMCR=1)7DA zx};fCwibCPB}m$J~w?CIWdP z_U#~sr-5jfw}Gl-7FGwZP?LFe zY#3@uTfZHT!e3gDAQFd$WMrbIQ_$e)!VlR$uw!-U58ryTyKoLTli=W+xSB=1h3Z3A0n==@Zu*{#rgXgzi3 z>CTdds>5%yvj1E`mhtWoTS65BaP7M{EJGdYSXpZWLM+Ts0(9^?mcmQWGGY7;P8mMU zFLs+{NMaVU?Re(QzYAz5W5>ixrC7s%lERTi88p<@q^7-$_2*hxxtReJ`QGdn1c;7b z0CWtxn}{9;*mXk?ilOPXI7b%+B=-mG+Lm|*>iTy&s=|Fs)1!J7zJM2&JX)lQoZhsI zp=5nPJ4@*tX=IU;_`(iGnIJ= z1s*y(mVQD&2=3$lWIK=CXYy|c0SUA#XPLI^g}&42B1rZPwl3q%uI&{LI`6Z+W6FBi zl20y5P>PApy=q8ge2emvc^`CLb?&9WRKg`;1g0LywSL@8;2Df zS`=o@%paseZm}XqR1|*jboC$`Td;aC>73nGD1Ou*9k&8R+UTb14xysVjkP56$Y>|C zD*fpWTv{SxAusWCYXf{--E(*36zpIkph-jPa)i!vNFp&IRO_l%e8yhwpSz-)vf7xy zaKI<5bpJ@c04d=p&|Obctj`Yp<6JVNJYA5qIM>>X2_)e#)=BEMR47sH?punMSo6t_ zYw=ANv%cUVFNa~=DoGYm@%4kMwf<+o@nBpNxF1f{`U!fik_?D@+`6}WQzjE4kyu*s zhpS{@PSiA-7rK1w8g6Yu(WPxl#S)2hoa^lyuYeaQf#jR zqrw9VsI@i2?zYw8fYPgR@e5h>IQ&5(iQ(hRmx+=~vXs#31=ehE{a2QpsvB?}QQViU zmTIWQs2xqGNZpkE3vE1lAVpY3)RA?1<=Dh?2Guni=qp-G#CHi_!4=4yLVG|m$K>m$ z1dsZ1XkaPz)^fRn*;8lsoa-FaGrGVUDJV5SL#}Z86N)A54fbX?iF97M5rGwB{Z&3&NFmv-DomzQCNYFw6Q==&4Q zV!(3Mv1nn_uZ^ z^Nm8d0uMB^+ICFQ2KUk>=em@|cO;H~xSzu`Z^h3hR|qSp=_SW~1E9w?w#hhkee8a^ zH}#s(`%u6tDb($TJa+J`0hEn{?1SIyPuJ-J|7TAI4$nUKYMEcuf!QGk6-LNDKY3A| z!c(R6%(D`0=}ule>QbXpB0x@ucC|sU@Q=PQH z%&5Aa@EeAVleTBT`JHdhS`OycD(`!RXvGD%e?Z5}VX>{cL2>t*e3J<_w07sTC1xup zV;vL?$@Y_Y^E({*^20Wr&P2Oj+AbSj^{K8Z7sYx2^{>|?$1Zob53zK4EdWYDwZHp$ zkniqsRwwK;*bZFa@jDJY{V;rSi+GaHZhd)-C4SHLiA7ZL$Tjy@P8Yp(#}C*jkRjLo zT91QJ7l`QT0MygW4`ks?kj%Z@sUd(d-4BaXR~~GHL!;RX>nrl@e#cQ`dU<9!b7vlG zq-o_190DMn0CMg#22nsf_F^0ur3-S-_>JjQ5-j2+49xhg*+4VO$IX*8|87me`Szy> zz|lgyZAV5ZGb?fZCRx^pipyUzwAbUvoB^N%rmdlN*a2MYg|y-@&iYW<2WEsFMGLlFQ5^$0`XT7-kdihzUc-zZ+kGj9`7ZEx!>Vg` zxN7d)EqZ9J!wpNt3dp(F$R}j6j8&xXt%rReT@vixHM9;m?L`BA;rULpm^yPQ2VqaC zJBe*K)BSj8RI*yL{PGe68Op6gwOn2emR34R?h)A_XJ92C?Q}y3`gi9O}k za^<7B2tk2Iy~!}~vLO0n(Ms_X1if` zblIFa@xy+DAj7Vd>BDD0n@|h#K=7f_Q^z*1vjlWpb*4 zg3~eN4=jqP?)pLm_u=dG6BAN20`%fl1SN}z8x>{WJW995SQ70P9s$7T_(0?l*hexH zA;>z)Q?@QP8;Syj9MOF#rPg0|0NFX$FPpq$lr3h&BRGD)0}!izLKO&{dYyl9AKayV zs4A9JG&Li>DLqAMpWq;0noEfm8Zfcg3rH~6k!6L!GS-|<(nTpRr=TbmhJ@xFVnns2 zI@XD8ilq8)=PtwLqPYdz{iUKbFA5=9i_gkEGCit26mJ}EJH!5TIn}s0b`$_1f)DMo zMEJ`RWKrVF@+30~t3gPdLAf+dmf}A1;rYb-!oc(~!G1YnvxQ_>!J;89LtcIH!2Q>r zz{?1MrKN=n);ka{Kn+hsH9Ou@Y=^BTwT!C~UMvo9ZG+y8sXLdOgqzJ+W>8E3u4ZDR z@))EF8mlyYraCdeVE5*P%bnTQL3rpa59b^t=?^JgIM8>U!hDxF>R(3kK0b*-TI z2*bCy8?U}Qr``GznyWiSFW`AEAuDNvYg7TI_^lmX>a9kLy+RA^Cm4<_nMi+G^h1eh zdqJ&COQczq33|vI{yh)6+bXP&O}_uh59XLI<;e9wTgDuf9%uGeBu{G^pS)h^=5$jPTEyNMyur80&g8X} zJ!Uv}k2yn)=5x7&E%v4U8z$mR%KwaztpJ+w{G10;2NX)d+=)1$Y5~Q0&np=s$+RoC zF_=XCegb0`5E}6dR`ATnN<(nF&2;PcM~9P(O!0}!hXhF}{%6ORp^}SJD)(^J4mCkn zdsz)XFsE?-EL`ZWRC*fb<546B6Y*Cf(?*&X5#g z&0e_ozGm?^I%(!O_$R&j(=L%m#*ZgX3LQ`{x&7T$vrVBlD4c@Ll-EQSw`0MC=#~SE z8!`y!^|sW|UqsKIzux_ejDOv~#dOdj))acI^(6k%)H=x4BJ|P&S6#T;%t%7C=vzAy z>a^V3AjA55zv7sgHN4wC%j-1&n{dO^ksr*6Hz)>a84{!fb7aY1a5RCPvDg<+x#XBQ z4+%+%cadP;!|5S_i*=V<;$%e&2<7woo9c)D9OsWLx>J}Sr`r~$u=lb%nOJwRk zSJMm!A2<`m$r5KR?}9QM&Z;xSh{_UE;z6hT3bVsGm0GN!*~xtpiem z&3F@<1N2EtKI}wdsJUm@dfsQ$Thv$tv0W0bmqc#LE72$|Nx9!3t6w^rIH?MAY9LB3 zt@&_;QGa~$x#m{uhgJKX6g*}JUhXN^HRu0=vug8lGP5k3*96og~#VroXiA~|+&_4uSV0@NVD>Vp>9FWaH z_?%~KOWS^}4-;wpld;N5P(p&tP0*wC>gcndJI4qtQgB6h0-OeqJzHW@<=X!L?kmmW zdK!UMD96AXE_OxC|Ko&BvTcWgSV86BAJmoPruSN?ybk-Ldp5Rdu$EvCblW;G3up3U zL^CguY3FvqNNDYiEI&0X`U}Sy&Za3TUWY=BtUKI5x{Rt=jZV@fHDxSeOv(J0zHaOU zFECGD>df=VP!))x-Xz5IRR=P55%GVu?Yl4tS|f|F{g^P}(R zE0~gp;F?mhtEfNT~*=*&k_JYvXeR z0!iY^0EJ}8lyi1P`xGPOUBFwnGcfuHO><_QC~cOOgkJbA3L_KeJ_YHp zp^d8syfQIna`xt_Ckr(HvkD-IAj#FbrhY7#h0Om%4n2S#QM(Iuv!1Ch;43quSJm25 z2UE`G>Jlk~y7Bx6T+I+KVm+dTXv5aZ1;zY##66weUuw*!6qnh;GgCoeWz$W2z6_kj zqrjND(i}Jy-9BT>4=>}kS*aMG*5og@PIO3d1bFPgar=l4U@N(|{HP>^d_+kLOc@CV@fEC>7Vu)xJmr5Om%IZ-28 zaV-O!NnE#Bq&(`xIP0a?BVOi8A=3hU_}P}zH(0HQK?|p0FpGKOdZfKABts)5`8#B3 z-=z)s8m=c~pJ3BoRsls01r=@;13br7Aoox(S-%PpflAr(b-TRsSd`ZBMb|9SrRZia z2tDe^YVK2b+J4PXrgyiv;mpXJSBr+M!X0)x<}9~S);D)><3FCWQeM5e!qKd5W#%|L z5Yc48QZzzO%8OI_>HT;%a*W^Lo8?fn-YS>Ry6dxDU)=FZE?b?G&LY>2nPISIFsrc0IuadojM^GLdHl(nrMrt#?bz++e=%n&3h6o* z6Y=r0w6&8-l?~=}=tdFpW+Cd8UiQgStvF!)K z`>3~*(HS~ILbEG6>Kzti-xix*p<~&agD3-G9Ywm4m&NpIjwSlE@e^3RhiZ&Iz%{G_$XuhqOp>S32G+1Qvm8Zo}N-+7z&TR zDwa^A1(U`k)*}L#z!KPug@$bpGtVC@v2W+7LME3{{{Uhij*K2xhi(RJ{+y-0LOZL8 zs6&V5tNBYXu$cx%u7W&4CHnL(82nMK3;`q@v?`W6f#Ey}KmxZ=A3pGq0FA;k>J~Uh zd+NpAy-HmWfj2r2a?r69*G$dN>Q77vE^tc<3=PtA)~ZJ~u9OmZI_2id;6b?IQl(5- zCiPIDMcbT(kdi2}*jawePLDYwR)6v0GPCKgubCq8sp4ZrB;YWu2e@N$pH;Q9x4I+$ z5<=zgX5a(~fzPG@udS^-)pJyJ!DsG7Mwk2lI~_GgG~W9|gFGz;jG9uXN0(cU zh_A(0V2jM+!%y!qiLCR_?2Ao4$g^fWRWqCkpe|J)reho*UJwxAVc@j|3Bs?DxTUk4sW&y1HIWB5 z!hAo7(vwY43W^H8OXbP2y1;GwCV_$)@Vj$EC2aJfl~iKYERl|x_W1H`>J@8{fvA3u zkfpuR*i&V%i419@km61eF4l&p8@Nn%dE57u&qzK@M}6JsU6VZd0Vl$gdub`y)bn~) zvwHtE+i1k>z}EdLJ8FW}TFTP1ne+9**NV8oFoflm_N~D)>;Vjs zT7UHB<5Ll+R7Ij zWKFtMbt>vG?PO6!2JMm5+k*y?JR^_eIn`|+#Cq*%g&2sxLz^Qt9BVg?<6UqzW?*x;soxW zxXBxdq>0557fz=$=UNzQj*Az97tvN<1(X z^Z7lZ*poz4%YfDItE^VkJhfs`wG7Ls24cC!_XVB49T}=X+?=PExJ%%)-oq6>u3jH8 zn6rec2|wHO^vmEZEu}_zR%7pDf3vqbe?eaXhzCyl=Qoxd={l_f4Ga(e`ZW&uffdiN z)n4~FpI8dUA5Q71F(kRB)qaiHJfK&h)7Jj2={x|U2oa0d z0^*z`V9U9>o2f==VcnP@=`N`M@bt{OoKR}!)bSgCsdy3fip!o^MQD@EUHkN?;84HG z=9%P|Xiyx9?Qx`g!3J#^l3;g<_dL>B>`kFc0=lIkU>?^t$LY`0&!}F1-00GKt2*tZ6v+Oh^jKAOJZqSLev}$LtBPq3_0f~YYU<>r}ceixMuDU|j zk{_UZl+0u#ldms>^s%=)a6qK_73+-6)k8(b0lSGbvmV&^SJs)Gx01*eBLQYb=>5$! zByaA5FoBSw)Y=`s$xFtW`>X$Bv06N^Q(hk{uq>}LTs!*%0Rq9qMfH$F^SVQ0-?EKz z1PDuKn7Y+({>g5v*SX0W^=1$e{^LsFFHmZcV-1PSlnYn_o+F=YXu4$vi4@|`Wmeq{6aZ(n5`591Cm!!EOaHB>3`beVqMWitK* z@wdkie4XTn#9rS2;{zkblwD1C)d#PSt*O$Z0Kw}R&3CCHA#1N`8X8jDrwTM9WJ_}W zN%HQL8u=!`QJ%TGMBSHdMhMUAJ=Ncfa&;~#qAep;2Y%sxlH(aJ9RSXeu&H6cgi;J6 z*faW&a&fbs)HuH0;t+u!iJZl0#U8aTf>^w}2u3JvUXMFIewTDs)-R?mK{y(oHPUzLkywM12Wg0fr6wD04+l$xtYzXkQr9P*M+zThITy=DmzC+9wKJ{PyNw|>3m)69 zCW0qbj4eL{^)%?5KQe;Vr6S5TA-va{s|U|&shCZv^U;ymtn(<=QsJ6ha5hWd967o1 z5-Yh!pbh`k2*7l(M}lmn(d(LxZkPs>>I}U&XtnM#a#2vqT(U-9Haf+Jb8e>fLY$19);CVxE-wOqBom=(F@WZ=GFw5L7=wsr}mOw3OB_?oh6KmC^hm&CvJ z0*?TdLpLe3!)!NhrQwG_e~wI)$T^0bnhL)t3r+2G}=byM6gPc>|Lj>J=(RE z_+)_Vy4~`EGam%UA(;U0C^VQYlFLz)oB2R=ixXj?tN%648>X*kx!$GffG-J`+0g~P zOMVZ6Mw6Bh4uR$pU7A3rx1NoP%}liX+RC>Q7d%r_g{==Himxb_4-aMx`FXyrhSzXw zi2aXe#k|jaCfyIKBx`HC)+EIHPdjmO?Td9cl}mbnX)s(v9wlOY8oap#Q+ zz;bCWa&Wy_a0h%&xA)9EWzOk$+3|*_!@T-4Bo8ai2~g6P$vrF)^Wyhc@Rft-IM>$v zXi*an&R%a_pq+R2@DPz)vC1lb!Nx9!-5B4yJm%+$I^NK;a1*Bqe8QatR4n{<_#f6= zKnwjNPLs22+%K7y3?_8-O=zRq8-50;prJg0p4Hx6Hj&-uYPN!%fo(I;39<_r#41^~coma&` zD2Mrrbix(V`IGiBNIzZZQtAKjqa29g4!61*l6cWn`OmkC?)&ewX={qd(5=TKx9}$3~^?tlPk^aXZ;O2^v02j+g&4PCMS-nxGrk?aUh?2hw${>Yj*53>p z#!is5t)1toSpIP>)dzAT!nYy(+l5nkOOlQ_x7~DaPHGOA^UrHV!|3A){!&HqO`Nft zgPtR?>J_Ogkua7O#3qVT7(~K^UCz}erNHnys1;YoAQ9}*J`wwmk=sSxi-UX-@o@S0 zq;Um30ZN!_ni=?;K%p#yH>P4v_sIQtqq!%V|4C9`Y^8lj{~qC)8fS z4S7w$5!C~_0$4exNN%iMc63tR5tafADjs8g*i0B+yxI#6%ffd)Hh*EsyX%oMTU9@z zewd>4;_fr|-(jAV?pj2%)vG%gh8Y3FMTgYv4~<>W09FH3?OXe_DiqtCnS=Szz2E9{ zd~#c_DA^5<}iFYSZmli*t6LnIMDMINFrrbLWS~^r)*($(u z?&d3fr>3m-4~XHlujao1$dZBC8pKSMsa!L!RXb(5cvhv$^GTI=>vTZO@G;Gqc(^?ABShy!a|V zfxO>4xihp@nmRu5f{A4Q5+{ZFjztw&H&Q~uzfN}A@$ExX{@#dp- zpr$cJLVnEbEF%n@TC)lpb>_m3v0|oYXYs=98LJ0^&#yLj8Z8{Lgf43pgO0u-eM)ab z{9vr6$1%50VH!>m2HOFkIb?Q%F>Md#(a&Jle?|GM_)9Ng~% zCp5($_c=2*D`1)c-prLZQ!!!WqyKcu;R-7L{YKIQi#k-g2YlVA%5gK+11ztn%I{MR~pn;tCx+E z)k(dn$F7$#3Hi%uOL#VtPt}Cx;My!k7Z875<5fjGiOYBf@lnX*@W=GP)u5FhIExec zTpzSQ-*mY(#?ZK6!2*9+QoF@L72KGQPQSvlyg{#6jFmm*ddBTXWn>ZRgMKIBLXuqK zg06*9^4W#ao$Y!=X66;m#u!9m$y2@8isfr7a>&Rnr;nCaV&^!VZX0sGF$^Efjf@2W zx+o$YvU&bph}5I4vT*Z=Rg$uOikq`e`7`J$CYSD#1l6LU%Ec z6g;A<2^UG#cbqs+3Y3(i?WLd)zx}s>Lzx>ZkF~@Q09q(Z{}om6j!|9TvBCg(}$6s10~S?(L1F|p{n@c;KWbpcmll=kr7Or$(^;=!dNwIergFQ&TwJF{&ZGhyhjk((_g@dC628C8vouDO+jI8M088&A2IFtg)0r~0GS6xht+GwOY2U&-vL z^xu_mjoJbA0xCH`ZiEmM&5k6ecM zO1ggfcXUIL5we{wWmAYdF|V5_n12HxENIUuymSoXT;z#+ERop|p8u;tu>c%pEsaT7 z2R6hY-s`x7M0Kd=vSA}DW?BQ57>dt@-kTGP@w2AfmJUJLzB7dRUwuuiaTMhk+M0o^ zR=sr$>oj4>RHD4su}aTlXbWdEPp&+*n2-t&NW0*J9wk(?U@k+u5pxFm=|-wjQU{!B zq;BqWq=5jKN7hFVDdj9`G{aHtG2gw_-i=Ye1o(u+XAD6gCw{;CBcK7@h%#hTi_e~J z@Nj)Ri6#)eYZ1Sd>w#dEyoE@PtG}fTrN>-s_Ky0{&c)&YP~!20Cv$M78A%3J@mqpL zhm~P?S%TMwY)n66T0Px2pJ4Cy3gsj)*|9wO!>f~kXjl0o;xleit*-(NBP zlVdMyc~+KKwKG6$`6`-~%Bk|{ozV$MrXqzNDm6G*$O$bqpFuLPeAACeBalBAX`G?B z33Of)vOdnDVxEU+WlgTUf=ovNi+mv|hYI33Ir&0h^PH>{W_$v5kn8 zn@iY7PF*veiT5;XaV15oPdH!+Qp=iA#|$m2F-|qJM3{-UHOx4bK%}Z_7o@E*M`p%j zUMEw``)I=c=Jb|m$Uc+b%Hv^wd&yjc8 z4bbvH+8;QXz#5Z8^X#Sq!GT13loB?Bscc^-v z=mc=8&bDvsL~};@gXlzMDnf_Ca0u`i-ldbBhEhcGR)iHfWx&WQFB)Kc)zC&3``>4w z!-p?KJr|7B_dDHWl8swcQCY){P@1flOGH-I-vhX|41syXDQMPQUtG7vO6B&C)v9lQ znI4QMz{1eH5+42weu#LWh+ux2`HYx1A64qnV#!w_$o^lpAVfdYRqyO#6aicE{W#4aT7d&Btnb1MF}dBOl!?3)kagP7ANm!)EvKjL2iQ z&TYB}sT<7ueKAO@FGbygzW@$u<17X+U1t(TY=!rdmMrmXyuOx?l)HRxwvx{cIA>J1DT;YQgv8frkRI~ zjg$1)L|^E@Kaw&jybsA#NxQg@`loT9)P>noH?>Rs_w3f2Pv27E|(Eh)O@cy;T@^2?)x`RQVERy?QE2R_C$pFIRa zp35L}cLr|M=dqhXMH_7q?Al1?ERi8U;GJaQ&;*{ID;m%H4>3%rrBTvrz$K2s&gOeN zhQ2vA*VeTe zBkUivl-;X^G%pzpBS-?{^?em`Zv?oAF(9x)ZhQ`a#cT%SL17Eo*9M-EU0eVH7wHp{ zsmujB?$6}l))o8?&Yudsj$_paHT6TK8!S{5mSF1FZ0UQ&^g{o-i7+zZYT5@@@#+j-rA4XZ-A8__=~~o zqtL@iNox_>?QO&5ECqyBhk(f#lW!T!QXR@D8l$7dr}IQaV_*j;C>`htnI45hQ{M&w zRCRBt$w2Vh^1Z(5MF;ox7?yf+7mCQKbOc+t-%NT~cxQT1r>T`yJdgCo_P{Pgd?D+; zd4M!JBH&joSCIiSwK{&oqKrJ975$GTxOBKuBEy)p*MNJDE1g!RG_@c5L7){TX`@DFJu!~TAEWMr2^k#prmnM0$+6;MdeKHl;q z4j`p84MiaViOg`njw83;^OiIA>gFB5K$ud`WE@=DvB$3S6vVPl_@d7}l=7UJJb#KUvH1BU=rL z7PO|x;aiA?wIQ2&oX*c{eH3b9vW6>^N20--IgA=Kc&& zXXAcSjz&P@P61)K`WLu5@kp|g*SMxtJ0kbWv?nYrW5}m$6jUFE&Wqn;SXS!Wd;et* z20|PWD{TShlvME(iUfiL#%1{h1t$_-$R(BJY_;ba(K^4=oba?Eq=(}?%r)zQIpfpv zTe;5iQ{g8aUcgi;e%OaXY4AZW$s3ettl&*uBQhsAVqzZLqWTqVSBL21@e447Utfv) z8@!&hsi_GZzU&6*S5^d2V$?>VrdCZaK_Ym`z4ekm$Av+MuGyS=eNdtq_+-}?2p={CXR|@ z2h5IXsZJyd7>%5r&WK;@zgb_GZGI=_eW*vj;db*3f?rdRuy$ zb>ro+>iF*Fo1EAseKs1pu`r&xUdYUT^ofZLk<98 zgrAvn3gjJZXs6k`6dYB?wjFqRxK|Iv>W$R~*I$EjPuoF07yflO=2g*|=QA(2BynSs z>b$qi))JNp2}w{?=9z=SRwG*2v~!_;l-9;2jO69epDYK=0h>+n207R?&OzUT!d9NC z6Ee|HrTY@?4jT#8h^F>~0$u<-+5u;&%U#P=6bDsl61I}$`-AB0$~2wLpD^+Ebda&R z&bX^ zs@QA^*#Ja#xRNdfL-tN(V*Dy8JQ71A+zZ!#{2a{1nyW11V#Qy$x{z)8NjqKaVX(zb1?CHdK|gz?ab zhp6a)@JbOZ56%F}?Tq`y4_%w5o$9hypnZVHk=wK>7RO=kQ>IOw#qyr}>o$jh1Lv$I z@-CSZ?)hOrr*tf%EwBDVQzp3)QB7&F{08Xtk{IXrEW`Gevu`5$pj}TB$D`gBi3~*U z)j6X4!PvdI~ zz>r&ngmUKz5A3CNd>Mn|Mc$l%(V{_>7m;fR<;EFq8uGtykgo=Qq5-?UrF}S#P0Uwd z%i9ia+)1?93LyV>#!KI&-P0Fk~-=`}NL5 zMoM?>Ix}>yS>)0hn7zB##QgMQCCh*iiZH#SSh+|5NYs8TrlgP-2uxPVMl5eGyFj~~ zwsBx6h~Ed`a-EPVZR61xncK1>PtwcHl2z#-9iY99CidTNGaXo+9Cx%=D?1}FjvJ1% zy{*!zh;3`q)ZO<}TQ=-}q1J0Je8e3=B>9l~e5}0+Muvj^VJ>XLJeX#6^@nS~nSfXr z1!?Jb2|V0J7Be}XSm>B^c9o{oKk4&V7Fwjv|L`(-@anOP41pf1D)d|{c* zW|L~zjwwP%FlGTz52GEnAtk`Mm5Ni|x~gC46pC!BIMU~7ef0zy1!$@Khe{v#ABfcD9o@=JcNKf+MJKE(qlH3v*0JpltYQE^W`u&@ zIg+?=}HHXZctr5&_^3 z#l(AeU{8>A!if~LeR&lby6A6g;AXZic-oQzdh1vJ#uc;Gf2diZ-gtHNo!ZGibL-A& ze1#PE=oCyXA9-1@3e9;ws~8!o--l}P_g&Gtaiv4XK@MI{BQ`H`ip*8F!%S~Qv7sJU z@ZgS~?=-CR(gP>CyEe>$ehj;0^x#GEq+j+vcntl$H`|N0>v3lIAKEo-d^^X@!obEi zRIt%*2aLTu;l$J2?IZ5^0W~Mu|J6u!b<>Y4MEG9@pz>&@50gJg3WQiHU&S9uOu=c# z!{9HXTomZ}?6}~v@9)-<-l4C6cn4Xyce}+@kJMbmB~^;Czess0m2x_v^c~T1-=w;J zUj-K|zNXspeXeX-L!%U32j}XKy}kK59smesoR(|E@%)mx=FKSNmC;~?7P zi%to(hg!(K=&(eW`Z_PEbayESW=@|$fqlZuAeiN8jR-e#@07X$Iq3z@&Oe-caIw&R zSiwbgq(pNBC!>9`puh`iY>QQ{r0jn!K%$Jl8~|Rc=S4`BYu=nX`{+I&R{$N@2yT&-tPnChhvwAP}Di@(0YIyKwhTn`RtY^kodCh z^g3B^#_m!2cH2GzJ?0P7n^yF&o{y_LB^nm@{>YX=Xj>D$0(yZ6-e9$EV~z>O)2)P_`p80ks7ZDe??Zj7-8eiE z?R}B#e~mOK@ZI8m#~jKC&T(pS%a}-)>wL!{44#Jt-SO&jm0FQj_TP&Z^m1*A3;8#b zvm;6JbFAG8dus>5E&#`at(*sCt`+&w$gVDKkT77Om60XMk>%{CMu#VdD@Wn+f1Fwad3a2zZ!1+KK#W0NRzrd=R9o+}`wutNPAe8O z_L$nznsEE1wvnkeO{L78(7-2PNvqx&8rqrB@cEJu#aV0M#`}RMK@#uI=#a+lcZZO5 zrd|R+4Ed_srjE!LqSw zjCbTmEG@v4leYQr`QgBOP_=%vF~^nHh~P{_Iq#MVHoeBDGrReNafQ8fV49ETy=Tg3 z)iO8+=j}lz=~$%pT9Ct#vy2uH;MVm@iPvg83F_>kELe_ubfz+-fVk7f9g2w7?^*N7 zPNb<0(X7{X-{bD{WYPRBN=*Pnh_YfwTw3I%Fb%F%4KE@Wc=x0aNFa}cKD#n$BK@99 zACV;T;CPxpphm-%q)#mRkr^SC6f&tQeYIw94ISa-$;pwbwOYFLMl=EXRqr&ZN9Nb^ zfY(qh5PhcA06KFK=oSqq82lz81|u7@c8_OOkVQjuhmM1*PbAP3%|D6VCLH<#d>u_Y zx|2BrV< z>lDqbx+)q_MIzQazQ_?pmxj0KA+bH5W3SoERX40RyFiSlGE{?bK4~1y!vly(l}MJo zw*xfyvWmO`Zz%#>%dNWHeV_$?RFa3w@F^Ukl=SQ!mPHNDywH`c7A>CiH;`rjk&1vJAiC! zogMCbv*|~UiRGd?$(9eL940x@;vlctVuSno>w#LG}Hs1qDAk#k!wZEdsVKw*f89gTZw-?B^HVKQZfb}JY`f2WV zIwx?~=>&9vii`sC5Y4j^n%0iJ%}qDg7#Cp5z+m9gD-J%U<_$Oz5*V%<&oYz^fPgNk z&o%jZiikM0R&D^ig0lL_oo?pFf>*yLfsDhqDP8nNxZ}&dHGx?{oB@)#f9b6Gj%TL~ zS1<8FRrLpjAb4JHZM%bCu||Qxu~{RArE+Qc?sS{}G9S(lr<-7g;U4~wDzgP9NNO%iqS!kcue=pFlwIk_CUv+e~wmxMR-BTxm<>Q_htKlfu+};UbXE?WV^$fNkN>m z#8a(_y+oVgxn5d_NT}Gwt!aGoy6p~2EI0$BMI&f$++&b`%=lWvo8S}cHy02Vu_j*D z#UL?_xP;Up>nncW7_6(eV%5cLx~co@`989)kZBgjhtma+eC^!mx5w_Bnww7fpK&I4 z{<-?!O~l4-{DoO`^T~_Bp$OL*%KqGmAG>>-;tR!k;_Uo;Ud94ER9mD~uTp)?yRB`law^o_C;)wWidf@c64xq7;?5f(OyXu-=fxz$sRItOW5 z1RW%`-YoBnv#1-abBCvAA74n*2bYDrGo}B6%+ys~r{qmMR8cC~lqP}&HLBdU)1yrq z)E=gIE_XnoEZvKUL4GN^VE4yk6=NoB3}wkBxfPQOK}_Q{P5{)xT|^8G?1_p2;E1;l z@U|y&@R=qzU6KjK(J2)2wuemuEZoEVD+2pF5M0l z+D$<$#MugZ`M;IHTb$da*9CBZ}Eo%6B>KmLinAc&9MI0-weXEUZH8a1}g z>loX|U8WYK>ULdl?p%nxJ%whb_u)mSNfw7#i;e9bIfNoFE!taWE@_Sx$V*DJ)D3GbqD#IW4W6`=G5pMDuGqAq?G1-Qub zVEMYO$L*x=_D?Q8C{Zd7Cfp<4=enHgzr_-&Nc%eJhx@2gwd-W|o`pB&sH7%oMpE7O za`SAeMbcIMX2QTgsz|R8jNLaUb@-x~4{0N)%SU^=TTui6ocoS-n->-(zsPrI3J>-$ zzB4KGDe!o*DvIk*-7GQrVoUWiDM8|>4L7n^8ox&E?-hA^7i@`(#!B*8hCOR~6$bmF zxJ^^^l}tos_$xW?zn$h64rA-ur(hwfBTddY{R{o&_+W%XJT*d-0Xh`}#hQ&&^Xn0z zOh{_t#%u(V7ciz#F|$rHby7BNyS)~(!_ye{9eo3Fk7^6}*GYm$4z;Y9DQIg^EwY9% zah0B^i9xAOpRKq-Ri<91;n_ns`nJXx=hub&fYZkXADd+O-aYWkxyW(~d958U4oB-G z2ntTBO!RX#0hQw;c9pu1vOg9%G|*pnv$`T!j0)EY9oR7-T7eG*s$xKPtS zQcwwbdOM;Wj!Z!{>oZu}IS(i=lNs0p05?F$zni+cl3YX1i^HF2YV0wk@w8%Rbbj>Z zjb(q_5%HQr`*6JyTH+jo)d4vdq)LAkgATM~ZfSL-Sn)SdQB3O*%>z>UvWuz!Xlr=+ zSQZ)ZmO8)%ze_l;OemJxpio4HV5OnjsSmcx5vS$1uR5uGzuD_wK@sSQ#jd~I0ia8* zW4M#4jkV)+jsG6ZT8r=QY9C(@Wo%75jjyx$?fVwDB<xHb1UhDhXbX0@{sVct}GJvMqHuOXo9GvTrOV-PX;lC8m`KjG`7$n>+j3szI|u zlAbkBBF36cRW0Dr0J5>RE4{Yj(P(}Wjj=9NfUkp6;h{hx7oHp?ro%?WT0fP|A7pJ0 zaifEmYft_Wym1HqxNHY4X2M@fvEds38I{pV6VG&X8}CQ1Aojsvoh+bWY@@&m{_OZ| zo36n0ME#@(is@yw9iPb7pOkf zqCuI%(asxh#`ccphm;}wdDc$C;VI(cLEd$@AR`7h>QHCs?Q7-%IE5%76$h#ulK#I| zBd)yMdLsC4OMmZr2kGjrowHfhU_x+Nzw>8x0pLx*|D;rAqs@xAX?0{UM|ry)g}(wY zy4WTClr_;fy#RPeicQ}ogv91?C-DRxM3Eb>EN+m9P2~wr&^M~HN@V3S+3vNH^)Z^_K?}4LvAB=?!-} zea|CY(#gYOaP>K5ZER;~@$q-%1-&Ic&aV(&c{Ns>0lD^}II#p6(`f{T$c3HCYI{dvPcUhIiZnxX>Gjp7oVnNL@BfZ}?0KgQ^4logjoXxqU{U5XDV0yG;b) zu~a7c2Mu-z^QzD`%(x}VUV=*;)e)_)Rh`Q5{I6XGy(dt0q0EwkaB*>FWg35Plu z13OJa-2JzDH`YsyYG9b-Wp^y}1m`0DOT_3u>(?M@p0G^YXH8W)0*dggU-snEf6dY@%Wz}N>X7j z3oqNgo1x76?Atq0?PlfBWt9R@FX3@zQIi+${Pspk$%!I((AW-ARSkD`U&{BfcBH0~ z%=}!A^f`5Jy#egmBJr2ar~gn61|j&= zmB5W6^MA6UM3C3TGrQ`_!2rh~2D^JxBroJkg7z=BNHB68SHd&jppeleDb6fq(Y$4z z93P81JHnh^aK!0E_6raLya@Nwf>9Y{nagMuV$ckBDp?7`#jD(XV4cbDF-ga{UY$8Y zUwI+g?&tM>N5bl8Dzc}|^Yn5jecBXTZ*&ep@oKj)!HEHJ7jN0N7gigZTM+W|jA=#n5>%9BHOpF7Xy;r*8Ct4uyRF;Zb?T zJzh{U$Kp^`jZ0K@fdF!HY}@=D)R|2jn4mzJ0R~?u|GKMMHC$mGsc6T*93|nb$`uXL zHN;N$UG~j&*_5K?cmAu2_r$We#27zXB?-9c8x{t<;ej_<0Z{ZbKZ+i9l6Mx`eg+a!t6R+?a*Fbo z#m7fDggc0kbk_@4MUAdS!nV{yKnm}`nLz~)#$;75WpQ*SI_A@wFcI9UwlZW+ z3$4qr`Fru?jhGo4CiF<{Oh?GP9X>lU7ssi-_ohV(GBlH^#(;1{eGE%SZSR>* z^8?cUkqhrcSGAR;U#sg2i%tN4!v<|7!;fH!IYGX!stE4*z*E$pHO37WP@d_$4f46D zuxMBhy%`i+!ZnlJ;N}SHZUG%soY!5g zAHwutOiDiE+KzF(#~0iDs{d~(BviOXJr2hgZUy1$sH3hZ^^hM z8;nAKdk33X>CUF8rh8BKFmpw#$@T$C%`EXoE%hFSwZXUpL5-&3wH*SgybEy%pQ$JZ z6$r0UwXX!5nNdR0BXi|U8YZC5uQb%!j6ig5+c2Wtdr@?HJ#aZj@(fp|%}-xwN-&xX zs=V@4pX`l5sPkZrL(l-qEvWYNl}0W4u$9XT3?GvMKzm)c@3r5#ukPovO~NSDdpIj{ z4Zzl_h)*ZNXk6{_Edw&6};xkl)%)oWJ10#S+j? z9?vhj-<6(LNZtIY;Khh!g zragS0j@!2|%!fTt&rStvM(^t%k(w64Wn_aS9Oe6@7vc{j#Q_9%NK}tB3>*Q1RSO#<)b85*$$A$~N5PVK z+1Q*}izMcyW-t0iXd4F{?1068GM0YQ&!<4d#uqmZaM3_(mpyq4b4 znz$AB=lzz1ey#@-8_W_^qEOMu1rK#oeYX(NYk&_WqbK+Qur|uPUplV;8g=%%vIpqc zX$WETpPq}aee%ss59Uh?ap<4FtV@%gA}e<_H$@+=^Ox^<=9BVA%^D(9DO6mb$Y{%= zmo1?1LIv0YKCYrtRD6mxO@8A9fL_2Zpwv-?47h%vMdm zswoP)&y1+1OHle3V3D64`WCf^qB8~paq$K*>}Vplgqf=0fk8Oqn=$RbQ8u3=hyMCsYXH5rHnT#xR^Go$ zKa9*`c3aJ%>a~PzT^CIkBIg6YH!_tn3P?d+DG%X=5k*6n6=1t5mflt$3hbwiHlk1F z&5Aa3<5ODnj7LWUNtO97Ni3Yb2t}y?{b#Lj@2z{#EuV`gPv0J@KAOMWgc= zE%L2xn7>PDmOMm$MHrzrKRCBupd(cYt`?WY>bAVHBkABg zC*Es8R|+lRI-SrIqh}oPs7O7oFH?YZ31Cn=og}wS7N*S|)dY>Xjc9=Pd_uPrR89~% z>Lmj^tLwm=?xqU|kGEAZWPB}_Gk1u(=;kMTP6m-3OJL(xoof+-duIbAC`+o+OpCEXmg=1oksNL$-cJFo>fb%u(~h2rF=D ztJ{lLg$6F3h{<=TOHQ*I%2)E~rbVu^Y~gbbP7jw`3T6^RGN0r8igOjvXxo$n5<%{} zo-(kNm{f0nLWfJ{rmwY>!{GanIPKixT#M7r9_I#=UMUW$Ex$VBVYLSmKULE&&GeNV z_%2wIODbDE0`tD1gF*;zLmgKEp!R^{$77CakKwQn(`1|ng4mfcAk1%+LpNc11c|~RJSMZq#@8&B9@A)I^cRAMWHNB! zKao0=2BYSPe8tqT8`uEKC!$g$U{2tCGBB+qPQ>kr?&hkq$Yu)88T5o@mTFFm~ROl48?Po}Lx=MYW(F&!y|O5H}dm*z~JU0XLdnnU}? zwBAi^syf{D@=VgCPadQ%@J}a*>GTtDJ_K<3gWMd9(@n^FMNe7J)EZE5nfm>w{2M37~e;cD{C|Ff|JuCX{JI&;Ic_#UQ5CVkYw32 zn*@jr-i`WvQ<$>9^yVhF$!jaDuK*GdR@G2Hy5^5=>{NF ze8Zg>{o^S&lRBj0xaY6xF!cca^sJ*wWI}e^x_f$i|L&FwEdLqU#?`s;cFNV+&yD=` zWl`#1*lU$N0+w36d;$q*Pwi-X3~Xo?)y(_F13U@@qOnO+R{9g7!B2ZqBW`G{taQ1) zQE%Sd3SE~Mzff7A_mt~BtezRB{R(rp428) z(H9R27|@t#rfAot1qXiU)B>7EIrOcfF)QIo^ft-E-Lq15Jmkhv<+&P}im; zCJ+NA0fvY+Fe7;`r+6Qx8pe$Dvh|89_RG@~j~lO~eU}&WVU)xPYcXGE41r4DGYVa& z-PAl`6hSrW4rO$cr|{k-eWiz>nU=-3cCy-d%#!jHV#>9%&7?Jm#s0t#qZp*+{^i~# zSw49HQFUIv?_3tgr_=SKEcV-njq%<{QpZ@S&pB?A2C)L|qsK?J4}|Lh+f6C@y z&+_!^ED%$0BDfKhodbd194PmA!F+>YZf6&gA^*A`drlZ)zhwTVgI-refKbo6%L&3d zeb!b4G@fZ<{x z?e_6$xDNv0YI)+B^x8U+X1>t6bBW-`lMgqvn1IwFdDls5ktDo-=v}oHpo`%Xago3S z0GfRnp2Fa%N;TUKH6|cxl1Pg?^pm_af*BQR;jt<oTLj|E8`%&Zi8za_)Ki%4pa@v4{F)h&hwXt&UNY>mG(8C1}?R1Af7j zt2n8?$RZ^M{}M6u;9Om-#?pnBRk^!i26?#<1Z`bp=2?&uY<pAljOe%z@v9eS$_VgFYP zk&H|a{~t8sRR+}3JBx>7u{vM_zH`CBVjS3;`3Mbr!`Zo7-+NUaUKBc$5}MV}J6WHN z#*vIs@w+5h5^oS=6@zhd)wflQn@1b9dQgD9oPD7MPI|@S-E1YH-SlcHdSm*3{-YTC z&n&L`<23Z1APMA1!DPRn+0SCPyl#L;Kg=$AtpvP*4h2ISM?I)^!W%;OCZ3f|Zng|7eF zyY-24JuTfEXKM3uKSSGAO|hRU80anD+*sLyg-@GW>&6p*QJ-z=#Ye?YstF^|B@g%0 zaE}S>CoT(XdA3ZDItbTfq!^!4GibIZ4|J=|{U51I9|;!3Wz(N7+Y$cH=L_T!Mm>Y`uXkwxhU*BSl8QO zQyYu4c|MJnM%2~FPh5f1q;>jB>)f@}IyjYD?{LA&_UP@*GpO`CM+=yRw|TJhHw~Tp zuon4EnIJ+wgr0^3E;Ar5DpO=&`xU=MhD+?|EYzt$L{Yup`t*u zO-%U`FeO@Fjm|<2Xp_JJ{9&5PDFT+FWWHfVjw#oA;h>8ci+r-7#{r1jw)`c~Mov%0 zBI<|=pPtI46+4gol)Nha(Orl>iDN5R6-N7oI*3i`g7!Adl|c-7aYBpbX~3dSNm-Dr z7H#G6jD;kNdGPVDPM36Vpsz3X9}U})>y3aLwE*qZHx|$fE zhZC7YMg!Ixcw`s|zV|9B{JN99rmj61%*SH2M3#9@Pdo?Mz6R;+z=5DpNQ9Z6^!GI4 zvP?Lc{-|42Xs@IhaZ$CelyeWG5;((63Q2rh{?^n^y|y7czA|_k5Ah7jUw~h_6Bi#z z=dbnvc6F1MWOKbe#~O42GH`4{y~YvCaAuptUajvuGTVO#U~tc_DZF<;?5R=daB7pt zYq!A4Xt2)IC+9CYR1F+u9>L+DnjW+s!8+V-R=2&gqDW!9i37?TyN{Yj#dzw?VJ&sQ zujlh_c_yAv50))0<=03zc(V?fV(Eqz@Dp(hP9v*cF4*8_eDwO0Y?EX@U1IDL56rdh zG2-Kovtzm%r?j|^2fcwP170l?)A%W*zwn>>tT%NEJ|e<-@Vk_qGiYwf(PDc3{N6h-{uq} zD7Kd1+%kLVjmG~HXE^DF8kaWI4F1*5w8Ig=~^mRTN&H95V@jl2}7X%-OXS=ZDKx1qTCQ6 zfd^V5WjxZj))OYfzc%)hoU)w^s7Al~)#MSGZa&zISB&KDZ}yI@@mVPWPds@)ZhjU~ zqVFz(kT9#Qy)nAh3WNPE5(%9%N7G#fa@~42Eo& zb7&Xz&v9t3+t(0I?OokF2Yi(?PnK|#_Zds*Ebgy!Z(;Tu z`Ek8q`%cBziaK1qf+qU%DJ<`v=fy@``jFf}85NX=DpTnvk#BjL`q7mks{zk3Q41UhiA1@<) z`(=Ks>#l!44L%7ZjvE2Rj)z~{`2yLZu>Fs6MLsHa%AVTpa;tK$myHmA@#q&O2H(mK zuVRfq#Q#lvt1H)E{t#_0DQHLv)x#6=RwVn3@(Yi%;yrf4)zf@&DTWu{K5Id{$zHQ> z<0T1wH#IAAeUIa|v9Y-01OXrJs+qqGjh6dAs$ATogEYWBtt-J`v9g?=Sm{aDSxh5y zBQZ)PE0cS%y8&*9Z`H;?`(DNkD{-QSdQYOysm@sL=(AM%6v6V!BdsGX;NW`JOk;Ca z7UO;QQ|Ko)J&SHoSZe`;PZ;lrih@hT7XMK%W@D^p1RTT$*$L&lPVs5#-biLs z@$zKRE5o!Ve_o16WOGTwfPg1DR|gQHGi*)+l$THdz;!DPv z0h+8n4Q({r+VO zwn`6lk4$`w!`^y!hFlYJoiBURM=f%`@is&&mus>^J&>}%A9<iJX2 zsfTP^KFt~VTv1ku0avu4@R4F}lx@c!a}q56>OMmKw8WiF8@g(ZT5SBjPI@=#OF@>#F|DMx&LLX|QRr;Ab(OMIZ zEJ5hp5v71f&dcOo7lQxf>qJ)B55(VEE?WkfOazx zzDY94H*ty9wFXd4)Q+!VGaYGiW{l3~&OSFRKPmD6XT`OB8{DfdOcbX!{ST1@*$K5me34uS7@`5{h1w@QhEc$! z5~{0$Y+s?jVx|)};MEe|-&nLcdOBUbv z%^Z~oAIjrQljW(WouFPn_Q3UV1IQiDAFCRH<8zC*zfg&G+{XBnkwF{4?J(}!P_afp zNXf8_60f5$!JV}G8bh|Y3>mjrS5cs#YVI4d_*atFuw?E-;$ZcHQbAtH@zDGWQ8nX7 zjLEG_njo0(M-q!BJjK)j!KK&3>hH8DmLNfPh)G2LI(H(n@NCMOI@kbb9jfQl&PPAU zzp;0qnl%;K1KiGDCZaVv_!meNFE9DjEtpanyScYP@NP-ffDiP66f)uk$l(^!y=z}6 z>XK0qa=F>fk@4L{KiX=1eYc>JlYy*@_%P6|K@IeKqfA@@XBTuYXaKMmgqAZ|3S#bXkY=!)^_0U*{{zU0kol(_v z76OL(Fsa-w3lCo73PE19J|?WKg;_F!0dCCsCF?f z_M;blU}jN~3e?!Fn4BviaXwU2;NqE1Ls@v~7c{5?o`60h4V@?NM>6c&_@n9Bd)Vfp z^b_7H{C8YuT^RI;WJ*1jM}|(kk;THHCb+vyrn5?lzt%!<#bOwFqxC}QE*CUbo4Ix{ z-xBrYmed&aHtWN<0jp7KE>}*UaB>dTscOxB;g2?UP?3_3L&510@(&#Q{u@nDH$~(K zytlx96@7|tPAt;q>udEBt8txNS-F)+{Z&zEP=_iIxi%FX*6J{M-&vLju4(P zcL{EQVB0s9`(cg+wCbYlO*A3JHwy~)h*ZJZ=o(rhyEF|Vj@+O)=G(f=qbnuHzq(io zzEu0ediO6-!{WJ@<_~sH%g|C$xB*>kO0WF0)iW!3wit%j&`!A%F{TLBcl!s5r6@KS z&8De007lA?z$CoOWFbtp^!I)pIUdd#N9icpS@p(PwSQ+KCIsB++bO~`!&Gnz`BNNL z?~5Mp&CA=YNOW^ig8bgwVoi>iK`&`>#PWfkV3<~GzrWj^sGq(;U;U&Kg~Y1pJ(_4CLa|YM0m+P@zugjV=5cR=LZG2pcW@t6(tKtt;vAP` z{;ak;_g*KYA9{rJclJUTK{5Z^%;OJ?g*g(FR`rd%-Md!JXtE)4_1V3#KT~>rF$GGl z2Be{~SP&9<0Bz>9m$Z%(DqNMp7a8&SEhQQq(utS{5M1F7p^3Zr3lX51%{6AhDd4?( z?p!cKgZ9wZ*wV<@hIcU-6}-iAaoj-wK}_z|967c4j7u$0Zs4}4{(_TzLeb5NyV`+G zE=9xHzS&dUd&F@b2`7ygbLaic%{P-AFY{0Nf{dpi>gZeDOeAG8LU$);zF)9qw=vJO z_+^Nou}0Vy^r&}YCd8^kuRZyg=o*!Qq9~jmVlNsFS_b%=*h%ZXZZtEQZkz|uZ)ADLu?9*Wrrv(P9i zFa|cQ=gwe1HNC^nK{*m_T*N{Gn2L5hLBbBDB4Ml+^3Z&jaX1FZ6U6CxiKvc~PUG*9 z;v2KK;*K69HF~9YK-L@ba?;xg@g`>nqEV#`njFhlm#8Rsyss zp(7SO1F|Z}L4n#fJjq4~3Pwf$9YMr^)B8t%PapRrsE38Ho^*SqE} z#f52)>TOHBI?al|8xJI6KsOg@pg=t7uy@4&4iM5#>s&#s44Lo=E@Fk;_|`dI2zP&c zuu|t36+Q@*@)#cwh{19Z-7^D>GC_FAbTCc#Aul`P&zKy-S$q)yLCc677Ex5wo`D

    d{>rk>eukpu9Mmn2{E z6(%sj|MD#`RqkwUJjwrIYQ0s$f)C$mVACfnuPN*#GG;I-{_tk|=C|TmxZFKfWDN%P z$W%p1WU$1FF2<^LLzTJMy%yZ$iK(V9SlUtt9OlPxm%b~OO#*3EJ>LB84}g~B<29|r*s}|4@uxE4b`caE_A@32 zYO*au{^z5y@9VFq7paf{qi@mC603wI0xXo}Oo6+?9BJ->N+bw}JB_H*<_<4$5sx_Z zof?{GE;A+au<0f08Px-GG-^C?OGwLzNHj*ViO-V+^SJB=?_jJ5rknCW%D~}msDSGz z5~+sxT@IB>X&+F@RYLr4YgXZq!NP<3{Gwk*v+&y4qk=U?zN4&_OM2ZBD->@O3k&W72$8k~4h3J&jTC;x77D z<+ueJ3fQv&wP>T-TCaJU^z$BQPyIu_7qrczX`A?5ghEmH?>nJDrL(fb5R~Vk%as<= zE!LG}NJZ*6dt=*Q)w;*L_~cVCnExR`n-#1@G6zlv1T-UtsLG ztB`&4gA5~)rWL`z<4+(sSpg-ls4LsN)Z}5LcP%sIT^`ZZm#96^U@q%LELHQAdh5uT3k&O99d_ z)KZ%|jC+C_z#-hFc#T0T! z;>r56No|beAhb)Jl{ezFoPcopcSU7NZ1AYY_h2f9`};|( zPbgT#77LH04Y7clsFE;298=%blPpIwlQ6;40hU7;9vDfGsty$k=2n6NaLeynJ;cr* z#(n)~uv{DKG7xPrkx;@s%)*v&{_*x#hn}b>TZK2rtX!QIXvgz^tSkXq z5{K0CDFds-5&LiQW0e$2i9ea(@b#zd@5*|-4MWaY+RjYHj9hs|6dRlLyMl>_6X~U2 zm!H&UI@v*dy-JdtIK7K^%S%$7ta4Sq^R1C(bmt|LtIDheBzCZ~l`cLXj>e;}xN>4~ zD6SMM05QS~`G0)WTNzm_9ED=H4MkN=w)UHD-N%t*7ye)1>j$lL2emD~;3TgCg(A zX=X}nGz2tnh|fF>!ceF~D5)PyPUq()uqOzgtW&3OhNC8L!@(;(9nzj_kPZ*K5Z~JY zhfi>c#1xO6igRvBXgWg^eq02gau0RLL zpIMwNi*)PUu}20l3dI{{^pb(`m#Q%Our9wjDf`O8s~gh_f6E$99p?f)@V}gOmsJLgNW?XF>dxoQG*Bb{k4qMSEU!)5tsTY z#_anTtT@PaRt^W{N#j|7A$`{l)|GVHgL5PBfnIVIUJK=@_P1L7WLEZr@;B0xM1)j0 z=nniqlqzeUgJc5Fa#O8>+I0TJnwKC9`Be{YnZAo z+hi&`n+JOL6N2$?x93nWreD*?eL#_MG(V2uzwu!|*k(Ef$skOQ==~{)we^hmRI45J zoi4K*@^vtz6<5h9Cx)7JP*L&Ey>W5-Q3EUNH zzwOa?vYX<5wXe^vOb-I)SG4=9^HCVd`HN1F?Y(9rAKaJZi-<_kBr@>wH=bPiY^+ZT zgiHY2iOID{fUm?HJ@wyV&(z$BOF`Yj`JdA-bbTNpcqqzZLLf+n0_ipkTpUrT(8JW_ z`Tp!VZat65+{)vK=Ex3nO$lVGpWE`q$V6Uj*HU1+;1k7n#3M)*6oHgT2|HYAoMEzY zuT>;SI&B;e+A=HoeWoCI;`v+xyoirBEo&M4{MO>Jkv?+egYyJAw8^Y6Wd3F!4i+j) zPM@TxuB20*SG$NY_@Ikk=DeQi>`Adj7=x29Cjv$88l17*I!6T)4bkAwLPuVxGscV* zXCi5!O0(mzk2ClcJzY)3I5x=3oq#m-OC)rQzT?pg@sZN<=;POo{-SQDBZXc65sd5U zIEDjSAYGMn$*ny(OBvA~`w@@g%PGxEFtYFq`kjBh$yJ=Xz zcUZB(lYq0(#I2iHsR9j}HMJk?;@A$aUNcOli0;}|nsj<#E5K@mE_f&1X}c~NtREu! z{Gz%cUUmUM?!-|1lZm`oBjbSI|%Kw_>Kq}wMb86>Axd!CQsu$yQGbawA<0EyT8ii zu5cuQ{=aC7Aew=k2v)N#nT}}wyn@T4uT-n{fng9zb+9kwLH^1TsSI}2ZDnD~5(f}{ zsIE|1LBopma!|n-36y8|Z)DZJ+}F!RA_caUj)M|vS#Kv-#_j8mo(Y@5Mji+bN%;}o z(2*oWPP4!o5P;P4sDx`aSaIRj2vpA3HUii(k$XxajN7g{o-sM-FZyJ{%^g(7Hx@j= zgQiD1zC-lqb9Vkw+bnT)sBT8&Un0GJZ8AH7(-}*u6Qaj@w_p==J95Xr3#oMomjzQa zczzjd!OSU-xLxr&zZ`cM`ney)>?RrcRRlG zKaQ+Wy#;Nc#i>$9^8diXP&|C#TPIQ-71}^#ht;p65N zJv0G^JnJ;8kv&6I@ot_|*?L>%p0%Be44q%Ifq$WGFS4tN_G`U(pFbA+}lM>GSh7$etf{=eRcgb%n2T#hM>18eDu|$ z!Cwut)x=q;{H|Z9MfkHf3#a!CithMtgyd;ElNk4tbU7R!9|qG)Ho*SdyhM8g?Og-VDLmoR{Bu>15>@wI>){19TkmxBPF};N4%L0=Us?8auT(%NXQ#Pr^)o(4!F7Z z)SAX^piJUgMW1jn3K+|UqF1W{^z7p1zAOzKmy)PPvys>_+}Bf;V7D)Fl}{zJe|nAs z$?}0atRsuL&G;!7`Iq4@H;!cO$*d8>tQb_M8yD!coB+?lLa~@$`HG)d?nXys>Et*u z_ZP`umw<$wlkRR9QP9Wrwtc9ESn-)D!VD-7|!$8qR{xWV% z+dqJR8N$)O4$;FI3bKCuoSGo)d?SdkXGlY2MdJ1ME7%}OdcPT^xb$2CF7YaLAuXXX zOOe}R76>XmcK{*BR>tpuWvz-VKr8@2{g3lsC~^7oyR%ZUSHSO4^}Q~81G-dCb)=~t zo*BHwAQJ0<|8NcJ0w~3K9}=279}}xsscVF}!4=TQ<;j2Sr4*d9r*$%@*+qhI#}yg@ zGi!VC!uBq8&I?-XaXmdtYkS_zHW4@DNU=QaTzwK*m0mz#?JaC#YQO?nW{KWEpz7gx z#E}bPd533Pu1F!;n#ndjWTU5*?_N9seL8(K0m1PCqQrmHQ~@QLkB{(niS>hem^WTE zA@1pj&M8>EI;+(7uyp&=c;n3KyF6@c!EQdCdY$iX{qQ92(PvD&u=VpZMPGK2AwDrp zQ}>3jOIv1_B;aq^2P1>H)fe{7jt{`0KVK#KCwJ(3Ic{^7!Fb;~b`Yc8;576C^mpA| z!Q`_kI|%65E(=e^NV8|SX?gyGZ^H+@@lN+KNf?bPN3|nqlOKNJ=b|i8bZjoT4u1Pn zl&muYD!;9;;xh$!4-1hJs1Zbfa|)05&PrkWM{D!*dk>H}(q?NA#LZJ{cHw__kLj@b zQ0MMDYv%m}_Ha~%r{)RhW$Jvjkge(=b$n12$?wXjH<}U}Gxta39da@N2nQS7{t=AEQjPS`O-=Qa1I#8-fe_fnb3ANTRno(A$ zmegCB1>$FwlnNZ$hQ{42250n97d_o{isK84 zk{ztXP&__)+NuWPXA8C##Y?e+jYu;=QP6;`TX70q>nAi?z}WA>qM5Wjc$={%-!K>) z47k`@A9D?ylWY5i&_r);)gAYBT!LdlcnbcQ(CF z!QkCs_I6>?Whs2xf4yAk!-jn#MF7BLNnruu7)=V^uNcA5txP~P`FCBuhH^upchgL1 zq6m(}1(F#T!O^X%?Bg^m^Hd*HUUT0twXTqGkwGfg|G(A&z%d^fZFK;>D2nTCfX{S-+m? zar0i(WXF4f4_E}40dxKGc(RWB!#dp7JNFuHYOtxKSFEGz zR4=T+XxDKSj1q~n|M5#-FoquB(+u-vq*fzWH7pOc1>^`9uJu7-L?j_7rKUdKT~b+P z(o%-#AHe2k%`7#L-ZSmB*io7h)mQjc^ZI+JUI$epydK1n#bDut5nENJ81=pM8?`kv zD`&^6e#5Pa5T0zs0`1Y&brb(-Gpcp)lP$CUnU_=e1Gi~i0vMshBbw*2-LFDSEdqpD z9!9x@LMRJ2(Nj~RyS67fr@Sxeycv-kX*9=rN5<&(G|-0fq=T1?eMYJi#>+riNuWFh zgWYJFM5GL`%UDUS`!3ief9u9%MwKWxBlCq3T0LwE?8ZN!3~LZC6B8k5*TSYS2bko( z5KF3!S`Q=42+)pVATQc$r!4=UTUtT!Q#cf6^1ifPtMqz|MSAJs=c`Jzagfd~7^D$u zC~;Sr2rjx`M_e~$qrwl)x@vgPxiT3*xB<8$?l)X}%!GnJuqK9|G3_g907S(UVk2@- zuA%Z1j&*A6=g4`@&z~Fnj682p%anX3qmOf$Ob+VGc@f(K-^w)hq4m1@6O2?S4|Qd- z=iu&otp#2lt0ycCNn8z4&8}BsZk20j=2gAqpg?gZYxMMsxX7t59ZG0`t_(=BC+P?u zx)6Tvo<83O4f+wt4dliGomF03^ks|7gkWrXdZ6?db!$MEIAV8gxDv46rWvx2nz??; zM+ZtC?*SU_q*nq@O9Y%Im7N$|%P|QFzsO)AD#aFha{CSr05w3$ze7U@pTN3wQ$;0i znMYkD;T#^BBAyf>kx7$I2%<{~a#@}#E@st!OKEHuAVyG_&=@#oD6WZ4rDHWzJEUgs zy+NA;C)K0q|4ftF-#S)pde*`$b|3S!cJrgTe`0(9BO!I(B{50Lnvv`PDj?_gK~C#^ zo8JtgZ75i}syk?2(4FsCG^)GKwDgnWwG7TS#ioPHIU=X#TSWF;TWR#Fy#|wv*=Zd>;=H*#QPA^3`~j zQE2|(xUG7?M}PMu>U7)%zeuUhNIV^JVf<=u^QS^awnkagq4HAt} z4(J+VI*^-kfSPP*EbC&f3!lm3Z?gd>WV0{@J3|0W2b0nMJl{Z9DW z+1W*)n9zTQ5sGJXxo%J#AoRJEmpPC->3e*`Xu0t488>FV@FImeTGv@;?Pj{RvXU?O z)(bWdJsdUsri$tkn9M7Ad_E-;y_^h0PLq(Z(WRXVGITlmJcxyQS zBv%B?sXS-=)ZI=Zp+3j+c>%ta6O7)#jK2J=t;BNhfsBwGHBw{&MQQ6NO&@0h*vNS0 zu(Gjw59piIeyVL>Q1W;&%|I+XIO~Mirn^#mbAj}dS$|Xq~{W<8h{V|QuhbL&4;;gPYn=lYKYOfu|#NfTG~_AvchnB zPzxL4kN;xsY;^mV6jt9*0&9g3T?4O{kCR>Z$|r`>Y5y(44cks=c$6r`Obknx94%#y zXvfvB6pzJlVpE!cOn8lC;X;(6k9l7WNH@RQHYx0 zfeX8h-NUMKCcN<%^`&I%Ee!yf#nL{CL-g+>1YL*Ii6dOOG?^uorI$*D^PqX*BRRA& zgTgYG=u?-9Xb2fZCdy&&v}epnA-Q@-^Z(m;$0;NeHg zRWva&0rGCn0$u_GGFVoRE&+mru8~#0D)l$|FO7`kXr3g<8Ni6C8#E~B5w++`-lK z7xwkpSYa!8BU_iW(=|1ves5NRr8ny$ZCx$@rf9~h384QOAk(9vzCYl35J5*Sux?Lo z-<Uo3^e z!&Al{?AbiUN>#D1@zvz?bbKuFB4fJ_5)U73U(*f3(cvZjqIwQ|vyuN&`p$vJ+k+ck%|6Vekn;(4ybrMC zH|R=^Vv}H*ebFM?0Tw72E)@j2ha))6Wxqi2K8{XX`+&1Rlf%awakQT;uSnLZ>5p`= zf03Mn>j$D4PK_-f_UywY|^CLMh&&@(Y%L&z*7~r zX%AC02NnY+WD>+{{yrF;UGJC=+T32vXnXYie54b{qvrgpSI_>OZ<>Xa=y9l#-~X*1 zqq#|tRt$gNOWD;@f8C5kQWo2PWoxlfN7WUFPxmVmZaC||?wm{yHPa=+Kguzw=&8C5 zgL)F)(CWF07R*!Ci=Ey2YC-FBRnF^6AbBS!5ybYDaxG{G8WLpN?twzZ5QzAhzatXT zcD)vI%&*B`h@^@=kiR_3g`I(d!Y5`?tWL7Rig&h4Q4XrpZ^U@OZfUwl3DxAIP0y#j zD<whye(e! zi9?>vp$2>RA2;)CD>tl@<+gw;hP?OirJu*s-Am~QsIl_ay{ghaD_M$qC1Es-{9;Lw zr8>UN~b$X1OdEE6qc$t_UX-@q53T)mW=-{#j!W^20Y(UPnm~`9rT)v!a1$RM% z<2vvbQi5r}aJ3gW&ljgb=m%T~;2-Tj*M{&Ak5sl52F;RMXY5Yw?%R*-lj;+zXZwJ# zolc8YAze8qC?1*6$V|Hx830+V_GZ zn(=p7F1U=bSQL)=zjl%NMlZ5}H+EI`Y84mk38$*=N1cnEKV2;YHHg(pb*P$(eIw{t zhkwC2);<346Td6SENEcPJCjbud$KHTtI&+TwN8{!pt;<~cqlo%??j0%t%ZI| zr)g0&1!9ztlv$<_2!xl@KIM7QQwJ^P#6%jj*>5L}1&39Ev(0m_6%WYenf?YUpwEKD z%Zk@1Y$m|*2}~P@Au+pGrMx7lgUt8Rei&5HE^1+p*_1bzL#3b6=#1LO#sBH)F^h0x z1)EE&wWe*~*iV&*;L+ILVam9<7sd5bSY^QE0@cFt^t|%@`3DyKZV;=4%bZyGgU;>b zK1|d^kn09@F3%EDm+|7$NUNXV7N7^=zeVVxf!VJffUkjXR&Ryi1Kz?gfYB3uInwIe zgguC9yi;QbthBkQSId9AwX(!x2d`v;ra&+V)_gVHOt#sz}*8{Hjgt7-`sClt; z)_821_*dd`88-$$5YVQ?fZo&sgqcJz8o-*&;%cLcs79*2vIB$@=8bUl%9`g4&V=K6 zlhYbTcu_3OWG`SyA%p}2$+g5(+r?(}=}w@r=!4fKNVfZS2SQ_0#2$T!T=S177shzJ z&HZr|C*bR%zc<+?ImbL9vt1&4o{y{a@Z5tp{?|FQu?u&wdkiwau++Ps7TC z_bCmMSbBDWZ_0>`9;nfccMvxH@}!S5pJwN!hg|xsIznOB9lK=kiC%c6{N97SrZ#`< z%0rfWDl2RiO1`cqf_N#(a5Gy$)+~n%|M{HT-u_U^U+XY8^22t1`tDIb{+=xOsm;4a zT%->m;p^hce23o;261`l@O{}`Z<{6*nV+`Mp`D7bib8F|>$u{Bo=%NHvHVYJw5-V_ z1yi4Zv};9HlBtXl$wdg-66$eIUMwHx$bjFxq+emAT8vg!bv~cRt)mC>DsiX%0JCtp zX9xa#1KB8h95dt-JVSaM^nAG=x-0PBE*yajH)4A5H_2(8hEdDrz;Ftt_gaUJU%_uV zGtJM2w9V}**UDy$L3r0v)814vDJm(4e=0ogJ5H-E_nq13WHKwMQ^L(4TUv$~SF9~a zM8(We3;EyGyeQ(?TYK9>yKYbU)aY8%QgI?U$e$hZfGOri7+|hdTL>b$0;Wn&Tn|PU zK?r>A^82{UNM?mYH?1fQL3Px!^d|>HX|jrxh_Bx@$pz^X9XgEWm(2`9w)`s#Ze5F5 z$`mDXL2F^M$pDh(p2Gop?oqq3SSwLb^ zh<%ARU9oG3@E-p{5W0N+Mot+5tI9!ixwxVRm!4BoZZd4!&KFUWL=&2-!9@!2o(a~R zz-3is8;3ke^;hu<0z%?>Eq3EDkFT4y;q;%cqm~mJspRHy626ZW{2k1lMjkt=miENd z0@a$|7zSvWDcCM!gq&W>X+UqOs490(wl}j1&ZKXkqRnCEE);sY8Di$fF!+zUR`B^` zp8WioBrXQI$eR1zV|Z(Fx!4(48nz-iV;+LlMp zs>v_Hgb{{?KY(o5a1EO_l&`f+S!?ML`?TjIK|xY4@!{GB2eYN~9nx^;)b*JQ%Z(7s z+X+tq_bOcw8IuM$uasVv-NNt`z}o~^=Q)b|E()Y6$_BLqU!v&nog_rcClp2c>(;!j zxc{oX+@wyxEiNb=@Mc7O_VElGU_A{rd9c~`A5uLktU+H`*i%xQ^smmHv!= zccHi!TVQf`!j9GYa4!5kVrW+C;Y}*`Ob3T+4+K-83 zKg4vx###Z^b_22BKQL<5w4quASPII#b3_2r-Rt(3Kx+6{6^e57HQq@jC9ger*!J!d zss}$sP?CIXRbUJf$hwN&S55s65Z8r$<=^3*=+XSj9>JG=O@g?6UzWCu^KV=QH;9Gj z9#A`cy~}~O&@>D@KP(HAJ_mb8fn?2`y)yu^3 zXDpjDN_;TcCEt;4$hUQdE+?OcsDRkhFg;`h;~jziky(n$0%w}kJ^@{y^0GhE(*uA~ z)7imiLPQVextMDfj=gx)+c|CM->|1?olG|!SB-XYxes0qezk-yLHNQGMFm=?0cqSA zSP&F6j6zVatDlCc0(Vmu0sCazI^lQ+3OKI$LBd4^0CGvPJ@4v1IOY$$8z}0Xn`8Tl zY6|}Wp*W|C)q))}X+4)gX&~=UsN&RDsaq(Khj54zaD&~krCfZD2hJ8g+)xWDt_Bw% zT7=Hb%nC$+4QfFx!0y=thGBokt!~Q11eybbQlf)T@p70K5jj;)+1wQqe$&@vU%!PZ zx|!k49fms=NrHXfYEtf|I(CP)#;*LYQP^az7!pf^qZ?Fq&$}9s2T}Ig5V*}<^d7ZY zE&j|(eLNV*4x3wr8=&x}T<5M>n0&#;K#9|M$GccSnq8klI&I}F!0LwNa*fT6f5ULn z_B{k5t-70PDy{TrpL)@sO3C!LC7kUvZgma&tEtk{*#{piuNl^VPD*Z=Bv^P4f)RvG zH`Q7=O9MqP_yj5_P3f9ld06I+Kjid`@@tP6j8+Xw5Ub4AIYe3v2+G&9;O`BiYoo zb2w$;AQ{rsVvK?s0OWJ`UB5me2U)+`OrSs`;+%NDd9 z(X)Iz4s0+X%~xE{26YyRDM}IaFrDggpeYypTbxcUFKWmlTWJC2OC^OtD}c!|g@!K$ z4ue{Wrg;+wf}Q_uLx`p(LXH7KClSq#X4cq_oqD5XT8OK>LFcDpAm)quaAi5%+8FJu zaJ)&x?7l$8`)sIVewUDAE((TXRdjk}$reE#EOLYm?U9F8>_0X-cs+C>XPcggIT0k3 zH{VB`H;FUd1w4^^Jw6Ne8$M)eW*@eNlfl+2m5DqllK>GD>El7N_>hrezVkM--!Hzp z+qQq>WxZihO#pOlaVkOI)ZeYxE3D*tlS&Oe5beeFJrop}uD(dmGZR zNld|)N^+H73e}j$0iovRP(rJYw~<%8_V!T#uF{ogC74`uizTdz)P!*W07+Px*Ldj% zy@CVUMc;^)fi==fsS3BO#$rbw8dNpKoF()3FAKbB8%~yi#q{Ktv%*7%yuATf@lWUR z8LNWcmY61XKneSpXY;CeJMZMiDc4WCdAK9F^^SOq+M$?)_wY1pOrg{m{C4KnuOW-3 zgNtFeUvn`;;Q(QW9U*ekE1p}_iK%wCV?Z+d>!z^)ZKAw};Qbvd{QEP6Bq1E^aiRwf z2ZWEu^IP$`)SDK4B@&R-^?0inH|BzrWL~%Bmw1L3Kh}e1b?Gb}M+ucyPQ{Pz&xL-a z5n7DNUSuc?B#~G4bAG-s3wq@vY3>Ce_;{4o83R$POq^GgxPoT4g~aF5eisey^budU za(dZa`9TZLnX)Gjzi>`CDQlL0EoKv6UQ^PaCEE5c$~x-`HxC=4+Re@F zrL_(-2)=^>b8c8tNeiPiPEUjITnF;<*UY(tmP-1Kpu%tthRA#tyoUxAiL$jw)&>Qe zpBg}}ML{bI?n+0a^D*qz9ljyJZgSnovC+3rh0{LHLkB5Q6^#1~n$ZCTr$%4v{zTcc zJ%*>(ONmqiSo@<;g86*e6@0FyM3T;`7MG1x%rB0hz~hl|_{|4JinN%xq%rBY^9($} z%11bn-g4+zKi+~+VKcE80~_(qUSM>LDfIqjJ{n%_Z@3AGiK5~X^z^+bk-GaLsitiZ zce1b{2a>~VlO>KGDJ}-VPoQi;hC22CAry4&=dmD2W(?yD6MrpA6Ug=@9>W2sHhTnu zZ&AbAK7Ki`U%MTd=-IMx0`LR`C6m9$In{jS9rQtSPu9uDN%jn0<@cn85wXoo<5BAF zCf8jzx9R;64FW2qPtX?rNt0Mq8wzk$bgk^S9{lHjYF!^Ffw;r+iQJZKu+CyE$~jf2 zI?gR?CL5C_Dp(j!Hel)WB}JUO>R03&z#c<#{-FqDDIXn3116){1>TO;AAr1@zH_E6 zZ=q#?xNeUJ(cbK2k0D-XlJT(qb?dyZ~DNh9?eHd zkF__w!&;82QkA}JD0d7vi(+_@V3Vj+DtbXhZ&K!UMVE2j8Vm zxe4J-o~SHd2qvNLZ2BP2jbHLTbQB5P%zuP@_hvo+jGlUP0rL!M2>d~%NDlcV#!nBq zyZT}uYbjHcTR@h3aHQ!&(lr;QeZZ1;Q2r{?TwB&L<$ka=T8FbtkWW|c9&G@YFByQXbK%f|M5*Unk;BKUBxJ@KX8d7W zM(8S!HNuh7Nj-*TXqR+|f(D`-A%|4#eSxWA#IbxFhrhJp{e>e1FSG$-d#5)0Z;pGt zq4d5`Q*$MZ3x@C`e#a(4S%XW!CTc*R8Bp8PW$%^`kxSxL|64n?gGhd?uFgyvWS)Ou z;IiCWX^_D=K84>^9Q|Cd`^B(P8ecgd5BYsv6Oog~bA^tWx%wU7x(p#14a)(3Bz~U2 zN=_xqq^ZT>G7)=b!0s8e9fvW z=e&UF&l%9fq)_Kd{Q8UZA&KXo^7nF?%K}C+j$J{k*|61R8?WK-s}9GOjrtKVJ#u(PO~v z{FENxQbv0##9O*BUgw-ry!cpUXX5e9{Wo49UFrVn{yKOX=ldL;w|-5!u^O>5vqtO1 z2u+0?K|ro^5~hPyc8g7<(yYeTt@GQXWc6VA8)icK4whBw8+AgHD~do6 z*E--H*Op}%#D|@_el(<9vWDj`>4qTr0t3S}OfVVHxIQJNXjZz2N4yBZe1dAttc`7W zJZI(=$Yv`HuxTy4yBKxiPt-+^A_JIIj|nV?tmq&mh#+Hf)lS7@)k;o1~663A%O3$f<2gs-Ym4js-G@iwIl99q3DAXFKi?Jb6iasM`PQ6{(WygIgW%feh?{^r##l8Kx6hpQCoT#5eNEp7lTqx6 z^y87l>=st@%Nu=whRn{NHB$N`UF41Dbjl`lX8@A7AI{TGKDAW0^;`0aJ{Gk9h(eg= zJUpj=2Vy3f$8d&Q^`&c|~@{+9&C5*gPO$Ew_P#Nr=AoV_j4>j zBI4p4igkGS;>(N zV0LUp-N;8NE7j!1^5Qc^Dm3s_k^20CsmhJStuD*qw-pIo!sfBVJ7AE{8#%iC3gG5BX;f5;eL!{ncmZ{iig79D|l78@IU zY_?So#So*E8ZaYRkWR=<`Mif$Axs~(tf?p2uI+CMQw6^ehjt8-AsVTT`b*a(tz2wY0 zK1AxEg?4=_BVRnkX>`f)4>HI_HTUhK_wj~DcpYCd7L+VuDrUmUN+MTcCa;51{t5F3 z5IhQRf36% zMzIHFOA;9E76a)Q?F~H0JBtM|UjMb|4iy!l>_|h$)JuvSsn+8bhQgZK5av zUzCmLB$|-?)&<|ncO${qIWJ3CK_y3lH8bM#{g945L&}7oMpk}wI8TU62rfRy-xWD$ zTkB{&(k~bXtE-=U+tjx9JkcO6DzdZF0$lm2G5?WhhkuY1yQ<(z{*GsQ6A$fKRKct~ zV4Z~WZ)cqi%#CzAkvM`Ke59Y1SA7NT^7tb(3EozqVS?{SrqIvOE8f$3k7F)Q7xK9( zW7ceyQAcEZycB_#5A;6g2iEoPphni4AOHU2sn~n`AJK4MJqJJK{6msAYWfH$-d--N zAL)ZxW(a!{tkJ?lq>9)O_}#!hq?Eq-C+U%EfSL0E0_#bMxfeMlcP;Xc-P&;^#dEUhz0`U`B93>S z&!@zf0a*obIyPIp`Gp2_z0)i%5Pf!JaHSBe`*IZ|-6&yg#Wpt06nNXeVtXLz%`Gq& zgu$KJ7B^H4Y|97K+kY?r_K=rMSR*+)>swDQ@b?F6JqcwMdxNtZ#O|=aLme!^RXEL$ zJV*X+nFl%*`EYwl-Kg4Up7rB4y^R;Str1+skH#nsw;8H^R$_CEY=R-{H+(}?EoHC9 zCErER_mI8})HwX_<)Th^e;9~r$pCfhiV6mno1f|{2~zOQ|7K_ae(k-dOELSTu=Mwp@XE0-jL#bi#g?vP>B0CQ zr*SO?X*_=inBa3^#sMF*M^pV-)7VyA{=S0&ifv;3rFEX@AKaf~=c?)^%jW;hOK^bN z+O?U)NTbWYbG#B$wyL9>U9hc3+!lP>squ}9I33D9#n^vLXoeAhfqO!!ZNH?F(~I{Z z1%VIpBU99|sg@GJs@^XxB-Aw`p`1d}J}c{LIP|tXpEJN1hxI7f1Byfy9F1W^0vrh} zBpl<1=Pd{}s@Sk&HJ>gHgOVgKjjX|V=i_1u$m7zfU1W2y026`Ik5IN_uwDNwcQ

    #rmxHs>I7Z+xzX-P%7cOskufaVU4!H~@9ZJ}ct8tQ|E zi%O^Yvf8r3P9#K0P?h*!-)SXD)=~ewAg?LdBS;=gi$W0@FxT}`lYm!4`#e8*-M-!y z#(u8p8M#P>$&c$@3u@ZZ0mFPt{$p`+J{12y^f?4xBR9q$gd#{3HxW2!-JHd~>a%td zS$kan5g^0Q)r@FFJ4>2S=l94&r21CMta5LG(|g?z<04ZpWvGxYvaK75og?c2uC!gI z=u_V4KmGt})eiNJL(q>#8`E3+)ra(?oDOrf|C*nr{c55PBvJdI4?-`~}gBQ-aym-3oM#ImOhF zhS^-4p8{D!wM0f_uGtgeo|*-9Nte;Go>K&OLw%s1fC$@;&z}a&Zq){sShK2>XjClb zuxQJ#-;?PCdr*wLYUCK9%R)`tI~McSyYImwg2_|ziFv_FiF8*Qt+AI1jOwr*C3#ZO z^A2eT(d5CN8qicYyFx|(l!EO%+^7JhoTV#=w6%XMrmg}Fy{GCAjtBM^2UaX_a=>~U zW%7$+-UZV<$M6~MUfV43>+eE_&dR;K;ojRSC_pV>01u&)HT1W`3M_;q;-wM`J~}$| zmvgfh85~!MVa?cd&9p19aqpfTeORO7-x<#6 zC4d*rSQpC*9p%H)ey-beT$H;Aud`ky*^)kKu)}h;7F%~u`!B6a+}_NN7mJDvvj$`S zNya!C-Nt&edXc<{ES%xi#?_ap#WH+9(*ip^d}FFgtN6I`xwWYONMPx+I*KLI$8@;H z1@Pj}e1UY@XahKcK#w}s^{kAx`&T3O49WFH$kAnjxog8dK|TjsOk%EcS4;|X!gVUB zCPy;9Pnw6{(MR>BSpg9<3{}G>A!RkDE?!}xE5F9)Z5;|z*AKNM>F0R+5dM=J@1iSr zY;a5(BlCMVct_8Qllhf1#ZYDp0Y08u(0tElRoIi}CT1D+$@rDRb%N44WavD;_=y>F zQtnjahe6jPp@>oJqLC13rc&8$6)NZmDMU26eE zdbN&E!kwNP05=U;Y9Y}x9pnEMQeTT#?GdU#RwYhF$J$nAEJhc(F^%CcD*9DVlg?I zF(!>FSfFX*8_way*eCXDAObV4bdbxeE;xX1doKkILkuvY%;hU0iZ+RvJB} z+ru7s{95SXoYhd1vjkX+BG*MG4^TGpORM+FU|B#&^#{JpX%n0yqL){) zw8anZ$-My4C#XGjb7C!6Ckj~Bo%;m@61>hx%>^<9j=C(Vs608~)gSA7zq}M>8&_4= zucfy}z-e8K^7{jBSaL)2`2eCtb2iU`A0oAUL`>;iMMjcvN+=}cyHkyIaW7%lfdRx~ zrxcE1GLJi%#ZSlY;oP{R-{uN4UF%bPbK&$mmU=Ph-b7&wm>W*xTUWeSoJ#XfwA>5- zW*)CJmBEb5|Dr=0QTG=(lUyXkH5)96-l!59r6nCrm{QlQVP+cRG_@YcWIJFN>hXw4 z3okO($;vCHu-}VHO%ZVllb~g4xD`wkkAhgmlKqSiGS4dYpXgv~F_6upT<+ul>1y{> z#+YevWl|?6+fNTDA}vF7NMM;1p+G*-_%xqF|5;~M*wE6qz|A3|i4ahWYBP-MPc{!B z#Je1gY#^L_fJhE?)=Cn8mBx<@Q(l~qbTV9CsYIQMP1j7J!~_PS!M4!D$uUmXZ^ep= z+DIZ@kaf1xfFji1+e7I{OOk(%X`^7}Bq%XrPH@iRNu8#8G0R!#DW@9meYtaj!}w*` zSCFu;eWCe#?2SkdsL7#9l_n%yWM_=Qz)`SV!>+ZjX*CrUM9C?gRn9P|@M^ZMH9vfb ze@wvtQC*JZcxS6NonoC1BL7?Kl=kX+ijueJkSx#N{M&ih3@6fxH#!zSbMlG-?|Pkq zSp07?sU=iUxqP$Ac>9MpZrVx@ZD#|k>%jRifJr~xf7 z=fXJ(-K(-OJ{7ZTyt(-FGKZK?n44vy=493pKOc-%Y0f8pzXL!YS}xjv;J*1B%#l{^ zMdIX=cNB3t&?vZ?Nm!0l(Jygh6JOu2qpB!dnKZ0j@bM(iQ0#Vq9gu2A0YfM zKz-mW%kzr4XW0*~EqH+|2~jMAXk2J?2p5y;chu0_OX>DDN zF$=~vuno=23z}9lHO6@>^R2aoLa58a@hE9Cp@}rG2!lFYEMJK-SyvjL3+ttR1|!@@ z?)SB~wX<9jX5H4g8CMte(^)+6gBphjd7xc8|Na`g?+LaHP6P{gDp%%0=#ULLzz?M` zuFDh9{wMjN`LgM{S9(%@u6q1o7O$dkBj2tv_XCZB2SfMm*z@mUFGyK}fb?Y~=81|X zKcmR7LkDLg#4ODd_AV0$))lpDlmE&Bgln-_NK~;*L9f-xE#P>La8#F*m;t`=%PJ_{ zRn2;^xP#MsI8S%Qc|NL+2)o=qZi@)E7K6^AjTS$x9oB>e{@7mghTX$wg~*`XU~#4( zci16yL4A*%Pf5F>puRiy+Qj4W_&B_vVEqHLpv3jt@>X{!BvHlKk%eKW3a&@PAC|+L z%}?1xPr`8g42rTX)J0qV;e*pceBw>7{sQ=d>iGwVcH!Y^qYbR`-c`Eo80d-+yF|xn z2Ns_<>~7Q*yY*2}To&}~M8SZUe~scNi-0QBW%+UhakG%2Rgyq76ER-4x@!b>#tf80idm<)WI}7LDm%%Uc*a^}u`k{@wwE z*M7)8uTM1=+a7vb3^zV0GQB&#GH^l8c^9T-T`wse1NI_MHKAE+DWgI)il{C1)BxQ` zN*IOy)Bt$jR6--*&HjZ8aw=c@Hxoc9vV*-JX9t%OeR^<VLn3k#ax3i@#NH0lgKWX z0Fq_H2XdMGkpv!wrZHgBZ@F2Ft#_H zu1^qo^EiHyH6`c=6&>O}!B?#p*5pBjBZpqL91xQD^gUkL5s*IN;I(B@NQ>~A#0!HS zyFrMfJ~i_yg!cQK`n8s#J~)4hVC93%|CGc6k}a#OEm)tv)^F^TJf;z72##;QzWe~# zm50I2?c2c<=!5!ngMq~5n!#EbU{$Q9deE0RGW3D%bRr#88OM+t3YP#7=Sb{tij2{? zsV2-wn7|huoaS_@#4af)M)-Gf^_^8VH10~iwri#%IEkO`12AigQ@kqDvQ7IXhbbFx zh7qezg+zL7qN*((E!(_K+6=r6$kff$>!Pa2Gu(8|xXO1Pc&dw0MJ~ePhmU3f4&+Z=VdBAgl0h99}xw|M8WK zip}VyWHTc1CkSy7eH|dlbnCq%AR$8Rzx4LZlAU6-^^l1cGyJXP`zg&7n`B1$iLXpF z`Zs|$ten6OC#rSa3DtfD@ps>V1?DY%>T#cLY|=AZ){)Kzuu!z$fj zMRC@G?HrWvYW#nX&uShbD6s6Jls}1RV-2Q#!WDbcF71tDSvTMO$=0z*45OfX~4{H;NMSST9=0|&M z!V2s9i1IB{9!QMkH9k1VT$3zp4KX3pNEG`@TL0G{H9VI*+OGO0RS>%3@Ny+24`B9A ztk0;O(acb z_XX8UH!2(m%6VQ6#}WiJ%OD07mN-SO0Pu`Si#zWwzu@eq@G9RYg^&r?;-@#)k)6NY zWCgks+cLrCtObA?Fl<1JXu?noy($1pppe;y--%rfsf>i?><3m84PVymucSDTpqBVp zu7}o0#ayCF@<0bt0QYHy+@P>c$XHI{##;Lip}sCWZJfO$C2=~rR=yPgL)1zPn=BL^ z4-s1&R`)GFzxVNk4GSXK1`9yG%%#yAm1^SY4@T)(N`04Z&$-Q&YK; zd@>TP&~*EcNyHW>Z-tW;Rx85dlHlIZMXD7mVK-GJtn11_zrAo^nK4P=wS19q-`-TU~a;*Z?jQ?=Szno(0Suo8Y`R80~ zZGILFcAZ3k)-wrO7x>1ZP&Q}+=SL^IkXr{fduP5%RB_yUuzX>lhZF@IBGw1 z8%toIjNo0;d3YZqo$zkrW8cMR7s*61|R)Qmbz6Ogn;AQoUn-@Bj?{wVHK(<8dy{Q83a2#>&O}6 zs?Z7Q=+qe2G||B8K-}z?M}BEHvU(xXe1hfmS{-KxHRHhYjAW6Min``Dd&e@2gsSMg zupe*4kG|u{H~h=s8je9ge36>3T|Dy zr}=4}UIcL(!b%-sVH#|mTT{)r>;LQKu$#3&tW|XOh7k@|@F`$mVfWuBnI}5-xs1bu zDu%}>36E2YUb0`qnusgfcC$tuvDG4cJcrASIsd7PCieO4w{HE^+DVj=O|eNml_~n7 zu2tlE8q!##F<>++HUTpudD?z}l7&h*X;e%WoPb78NH;>x(W)cg(HtkuLeyhp&KD2h zRjlhMJwE_D=!;T7gP*VGs3{@n$91|IsQd3;fxnZP%+_!~Ut*6pp~Eg)7@IGOmP?p) z;M^wzoV||TNm%Chm6rC?=RX_7s+thCpj5_#-79w*%_?ONY@Ngto31e8X7LK3Eg_@{ zv95deT_vJXho;=FCkbLgx6H`BC^m$*E;w|DI|FUCm=!c*Oo~C4LFCV3=U)l>BsGb) zZM1Baj-4on4&Mgi-MWzRma8%Wr+_@HCOaym{rz8jLb*p*IiH_V!Ee$vka7gxsw{*S zMu_q264ZYgE7D~G-oE+uuQc^g3X0qWS_fr^no9n5LxKx;Xi4g+_CUyrawMI8SdIk# zw9|@*Wj&mlK-ELfJKI+21`oA-wt#*;6fX_^K@!h-b6CENWy)s_XUnn}69FZRQz7JYE;T1Og!vZ=jr&IyRYARQNdJ9AoUV+T#+w4oG+hrlKp{ z;iP%mWCTdG0)JT1qPkyw)*d&*59#DGhd=c!hO(F{E0K9T-h~vC7WoL@;<**0nn6d zY3UMWYg~mLv!Yo5lj@Zt9KB z}5Y6~&O+)tQ%{glBJux0SO27@msMlo)o) zMeEowTwyNv+udZpWb<+rfiG>Sw5&ufGNSTk;Y^8kLn*;G^U{DU$NYj^3;xGsUs*7C zUf^>dR|Mo7LGziLyf4D6hg_*=aq6hZDpBQdufPmyDZS`Az zRz9f|4L$$?0dwg4NsfTsY@sacWHGyxLk~W7Q8Xf~1bTc4S2#*br+=B=q;jx+Y%zpK zjcQ%jN;KX!bwd7U=UzwvW1lWf5zZN--}VQ$-bKCB5kbb9rzaw}acdgWdL){wx z$t}?4K^KyQ$Y?Bt^$1t;BCeiyLB2d{t{p)50Dw5ohTIg_%^&vh!29hI*-G`OmJy@A z8!BN)T9aOte5OOx%Pe&6uswuIAR`OVG%ddLuXpc98B9D;v_YQcI1HXiM!LWkg1-bG zl7*KNV#_>54m%>yYBdNOv{K3rgJv5r^vHHbG=DH{u~9nO9r6us;YUic;atJ3`;0}u zZkbFS zrUfAl^zNy47?ft*X$mgS!4UBBNYUiM~WO>;I6|2%$$Sng#0N%YUK=OLJ z1oQX(cG8Yzc4{h`9|=#q zcHVNZO`7{N3*fAUN@J)SDgYRa#{MXE__18B-p1U&o@ z3_pXx52lqF|IR^NW20u29kjc_2w*%!-N>9x$w)}if`wR4xhY*BPcGwQz=p{ajQLpVD zyi5c^1Tt~@4fA+6c-wg@@CjyoTe_2)3XD;ckrM1sF|v@A0cErMVUplBui~uqzU3vR z3nY$ki&Sy$*#N;J1~iGkWm?0GqP;2Lej78CcX`2qBBV`ka%RJP`-cqyF>+c2JWhZaBHH?8n$c1dX+@3$ z0yft=;3^&;Poq??RlgV;XHmLArZvCD|`$IBRuc^ z4N7=r^s0zl7wPLKpAsW_)jbBt`+ch2oKnZbO(BWxD(8Xj zm~1(uEzalV+Ux`jP%$+!;U7Tmz*V6kvh>PQ9q-BE`Qp2zGC0@jmotm(sdZ+{Vw1K2I}wMFR~zU@{Gd+o>DPV97g)aA zQk(A7Bd0bQu6B#(?5mB{9~`;$;wl~x74;d&v+x2={ye38vC}eND;iu1s49AiGm3tp z$1Z5v79SdzjWi+@f$xX-J-((lg8p**k9=2#T33Q3Ek5B{+DS=uO);<4njJcJpbBhi z;4x}bJ@*T>^4~*%UYp&>9 zNP8W}If*Vkf7IHWUi=3NH1fSwfM*1*$t#QtK&^n6&)P({Vr`AP2uUh3I=?L+)*@V+ zqGxxY|8ZjZe}q%3M_cck!S#lftiII{MGGIOE}{m^>@pjZ1N+O+>xfnFZBWx*35 zi+|5xEk2l*0B8TYuQqrs00mK`9`CDXJ;5-~%}#W;&P@5^)QfVCrl%$O*-nBD65~(FqLS-j^!{=a03{6RDHda03&B&+(Ci`^F^37?ZIJ1CR})>{bXe#< zulm5fgomOh^LnA+@iMAvT|BWJ?prMO_3MF% zzo(Rk&;zxdl*(GkP8-oX?=AHd??cMOo^pZ_l+dj-ea`N|mr@3VWFx9C_*nJbs_7d_ z$t|46(}H0(wQ=Pv*10UI7!L73fy#=vLBLqcL(grm3Dx>9$n7sao8({{k-bVmt!26d zbjHC5fMB47*k`4MNS0=tCToD}>czzZK;{4K$A$Escdz(oo2ff)pN8N1Xj}kS-s5gb zdpPa7ZZzbjZHK6aBWen z_~8m~<`EGiyy2O@EK@K(0?*6zPVx9zm;(p3lVsnBT#9sJq06rC)(ZcUnm zARY!NoxXFR-nv$`s%c1T3)W;$j?A@c)D9W=$k#H|=2cW1YHJt=l+e$UV8WZVV^81b zm-CEvNH*8GaP5`+>1o6g_Tyf~e}6(fyanb;Ri@6S4a-lEPOlnp#+>&ujIQi<@WJ&J zik{swP5V;!JN7;S0xRa)@j6zepYo0&-GE!Ct*Xqq4}p>}#q1Whogaxk zWm)?ZZxAc8$~R$S6<%nphxxb^SLsU+PTFkmK%j;XGV#8Iaz#s!w}h?!6@q7UprZ`P z?U_`^?$pTZ`d$n#POYAvY_8Y#VdBf(m2JF~bUa3%pQ(Q*$x-~cxG)maKkz&D!Gv?N(zhUI5=B*4XeRP{(HX3fjMzbUf0E-ELQ^@Y0Ryk z9#QiFj+ezVpjP!@fpslQ=lY&7+d=Io`0Z#Ed#8SsDI7$-{ImGRKpRKG5>%rO^`KbA zjzrL|<-OzH4i-vwPwDiiRJjfm;69!`iI)JObSr^kuee^w&uFS?Dfy!?j7*1^JT;lx z$o1z_+k1D`)u|6JD#wuMi*7Gv808;<<|}>4i{B72iM|4ccyeV7b*7CSU#9cb3^XKp zz>Vhl{Q`h?b;nE&snXtp^DHvNYe&&Uh*f%reii3bm9-{qwyq|CBiK5ozDDF44*qCWoUi9JOriFt>ks(3i4Mxt|*s4mu7qdCJ8WJP+5w(vguvB}3;yP_sQa!7;Qn}bSLut;F-<7I` z7nV_RR_u`Oxq@a1^dm9d5%ho$cg5kBIViqoPE^p(^BISCV-2FOFVbK7#i0l~ z_3B3%|7K?umA5UKU%deG+e^;AiqQywgG-AdYXjGtYb5GGz-oUq@Ek+x;$Q#L=Ruw@ zeR-XOQVAV0;mX46rDr{_YXuo;sbg-Z;z6~lj`8wxU(lkl$|_2wP8wlZ+XT;x^sk9% z8fdg)0~h2voquCAWAiX*WrwfSBnHPaKTBHQ%zFp!-fTSBk9<_e5)Vk1#dE!B=nb{c zJNE|*gFiUy!KVqjoc}JZ9H2Fm@1a4p;3$}OGAA6D`wHV`Uu!7OL0%IeJFGOns$Y(3 zwD=tGX?IoD@e7iI7hOE_Lv&FA1!mf!w6U=%sGl`!RpFxROCB2x%0NnD*uouly6tI? zo!EogT6!enzY%()g}{^|OR|5)LKqt6MS1a;i#RDqu7e^F0^7B|VvnVdrm9Hd<4^)~P1Y1I|%Tm1!FyY={OFy7ZHt;)$=;l(vemSkk) z%gTGn7QQ$pkQyYXO3<43C~P^Ho$-KeW=K`)b6izHw)D^7+p=+!Qezcw_pz&{60#J# z&dWNKcC=*7!uoVkR>hb<{nq$i+@#Ps!Bw0qf=lr6><2KyNrLtd+dmyk+}IIN3^mHPn$t9Jh#}nVRV_xN zPI0KLUD>9$xZ{cKH3mR>$MH+G&80y4p`GtqJw%UXJ5^1tnLXKpJQ`&%;E9Fo3$m#p zbWOqQMg5(_PB>qT)XBcEcN)IgEP_yPN+=%6 z0ej{ioWJezJ#%>d$^G9$7@8^`FJa>AS7$6dmVIQHYeL;eY&pgP)jz3R<9O-{+q{YZ zLdi?w8yJwP(PFJSA~DS=Q8n(xA1S76LOISgDZg1J^xJ~@Qm(;Mp5JYL^fQx^%yeeg z91djcR`RGRXS|a8KkMjrFz+6v-)H{(w#(@2qrOGF_-g`M(=f_&3E+Wv!)ETpcQ6TK zI``OTZyxiLM;E8ib8_L+LQ)~Nc~9eGx+A1Mi}=9c(6fgeOIq+k=I|zvbN-;Yj|v0H zM&-6bK#{WodSeE`tivDwF<|Sm=#5sgTR_V0&QH2yk6tCVG}%RAEr)Awt>qAt>n$##(Z;nC{y zRN2s|47}GDH*2VR1-3dv(sw%F5Lj`~ZivKVtwqAHATYxD3a#>KoJ%Gj5ldZXGBUCA z#i2r0Kcu<&H9NN$@gH+a0~D!M-=FZFZe@k&+ON!Yi~(&s3eq!VLZGb9-~qL_IY$;< znrU3orzqcBE?f5-_7IxmbRqHg)?}S>5&1P#@-Sc|6w8cSwc6Uz@<<*BHz=WNOhOj1 z*yay_Mob{v`Na@IPjBZ%ntBB&dC)e6n72baE-6yn+R+qX2t!vky&H`FK~>`XWk(uO zucP{EnnO+Aurce@ans>pLCJ{wOz&o1aF9jaz+Jct|5^E**Q`z|`uOik2M0n;=^fsX z@yoFj4rp>_f{Ug87}D0^%cm%}@D6~i&p=24Mm+oy+VTna4Txcr{WFu?TmC)(lcAGw z3d#Fn#w&9JTRDyu33Ek2U}$r`Pv9@;-`|HsW8nL8ntmnJ8aaQ^WAKMAHtmO~6I*lD zCB6zVTegzG)kn!Hlg|{S++CTTTdpO*a%2kJtf2o?3&;Y*CBZG=YClel&`r^c?YTp6 zzBcmpy#^slTDoVJy7|V%-!U6D=wh2Sp&R|9(he>1kpG~QYDoRKN4G`l+|7PAhi;bh zJfp{%0ytUeC$Xd%ulxINP06NcWjs6~oT>}gryc&xt~2atvbV1$ci9T10)p*?o^1&F z%i(t__V%=s8+_VtVT8LzA)P~P4w+>{aVm2=M*WIe7@DsqwG!n%TZa*0Q(a0gxD z{5;ilrw&4S$VJo{9|f1Pmtfd!2s(T|Xu;Q&_t$P@R37`Qw4_KID8~67M*XJ}0fU@uVpYg9 z=3)l;FxvXI(IiFrd}XHTQ`ho{7o3S3V6%vb$N%*EsH~H{PbPTX7|}fpAP=hRjO{ZS zW+B@sLiM6UWL#WkcUp+79BLHQ7U}~gpss|G<79ln2h4AdN|L(aMD?n2pEOt|k-*>D zsSQcQT(ucF#o6=7&k8b%B#yFj_(_~f~iDvIHU zetQjl$1x@O(OQ=A0*z)Ju}xynrVfi+Pj=Dnb_>hC&lWInyC7t3X-iKBojj*o0=5>p zzlGzR47$_KbR8?~9GB;mK=~4gF9i=T^@Ua2C8q&h(=7c}isJQmN%n@s&<~$$E={)8XfyzgRD;d>jXyaGo|IK1ek94`k2BM$Ghd=wfb;XS z58tvEc#fyr5xBWDB0rPNYkr5oM93aAudHvNumYr?$9eey*FF(hX)A*Ih>7$W263r` zeZCA_S%bVl*bH|-Dw9O1d^^SoSDP3=$$iwAf3 zPU8$|CGZ&=;kIo~rH(`QSE zFft3lYgORH1+sgb+J1OrW8Y?dVLO~H2-%3N;lL2+mP5~N=cwr=v1pk}m(S&lRneQX z@rBqL`dC|;_A^08wUnI|*HlP&XP@Iag0mDDH*M{U^HyAHMTWU6A!~1_vU>s8kp315j~jrofH9?C zlwyk`U8Xvwvtzcm*%}7ZZ=phdgVE4bvH3~b7^k|XF3oX50-(UOu6!&IVzv+4s8c9W zir9LQazHm=-{@0{g$F5!+-YOjb2YE~bi+4Cdh%*;S`%p2%r2 z;Y1f_f+WXJ5Ucpl;HVY8L8_!iXGK>{iv&%5K}g0&f+fyzUkPb0CI_1S0GtMbt8X5H@&O|0n#;mj7AGxZXJ_>yCWSR}|T%>_ds< z!TB=CkmmT!%%QB5SwX|O!5R*yh4q7<+G;fGJpX;1+&1WR z!-?bw{ZPo=U(<3!um1Q0O7=>U_g?yuA8zI!$vO_E_oQLZG%Yi3k}cMxp%ZWu+MX#wlnOi^`) zT(xK@7ZavEemCdm{yQBR)c^06wLDGb2Y{f)soM*{sLHUbDCBu z>@>ezIjN#e1Xi`%3&cHB*;IoVHuMK$meSnD15OfMO0y;}?9P^cfbe|AMm7R^nSQ1w z4^dI&pr@X6w6sF?D&`JNc;+PFkXOK)X<*l=u}M04IU+mYlk`9L+K;P4RfBl=H@_f8 zf&L6@8%CA{bR!X!25IqV@zc5||IYhjqe+kFWjBdA zsq=_fmk|@IR|Q=W&Ry*kFBlK8lPQ5;A68k%VV@Bj>lBK+bOsy)rrI8f1oW;nOC_0* z_?v!9E+d~3gBtk2iKAi1)3(?x(OW4@*KMHF4)pJo;}aBWJn|9gJxNa5W<`P(j>&EE zk&1EGYYtfp?7No?cJ?(#^wG(i^OO(*{WL5>*jl!;=7$MxOGH5GRBs8~AWtgRE0!Wo z2@v1RR!%wkbHb1Z(4@En7b&;KFbw`QGoV_lZY9&ab8vQ%YRbsXd+cJw0%h&k?0WJ+ zW%Qz*U74A%Gw|v}@xR-f+_P3dgaDdV>bcL8Er-_w9UT@<6`X6Ua4^JK|i{REx{ECKR7swkBzls zM_ZW)Tg~lx{5?<#BQFfYHz#!+d1x0D~k1q`D|E;|-5ezj^XOVjFW zo3CsxRRU0f`Z*B^bx^cEVtB)E!pFpRX|>A65HzYx#T zn+!TWJc<*x$Muyv#%n~p>Mfae!&|=S1Z6?c_9GeB8u8vXF1x8Eomp! zl$Ji_HQ>X4Efuan4M&E=={Oc^=>~RtIV*B_S>IV@&OXfmIA`YhFkQ+f)h&>8j+g>x z{s3p27E7~4#)MaOA`tJ<69i$gQ(J|8&6H-hfu%C&o!&nr9wCZyONFOZnqs#c!LxjxsTJBzi4CXlCWh zufCNva@Y9VtoX>w&TO5}0f$q5TL(u{gl7*W;vON_S8fhb&KbDwUO$~Ok*nE?ug(g2 z?m(wiRCp#>!Zoc$P|;4Gbwf+ial4$?s&LLGqFzg8+{xF#t82?Q?o*gC z?0k)-k_AS9b)^wf;QefoPFWP9;uAsn;+Z^L<^gFd0B)ZnNNh>J>O@Q-%|WO1+jy>0eao ztS)%?Lg!zcN`b}Yl})DwVyjb5!YvWNVSbgO#Dhe2`_9|_Uokp-8QD9y zF%kalHa54{SuZX;>!HYPByF?rZmn(IQS)NtA_Xd@YV-TXpuJ>@nU7qOD{~p~06|$h ze)*mP499#cMiyiWd?!k6(sD1O#BX!7ezI<-a!b)y%>&9_-l_0bA~(>2dBL(K<{w}J zJgr@|Ur~`~Q&2ZXdd~nkLs?cQ4ZFAu6||hsR>AgA^VmaTR$w^(tZ37scTb>pXc8$p zedUhM!2=kx*>o%C5HV5rst6a)wU#;3rFOX(kn$kW@18uZa$x%SsL$Ri6WxsXLse(e zhxmm=R7KN3;KiHlS%ewUIBFENj$&83vnXZB!H!pLYwy61X%J6%2>&GrfykrBWbj3vA?sW^Z_GQJ-;v>L*{3a|M_yKN3DqNqQZ`$PBbG8!8K`LDY) zMW+-w4W(Snei!4#7URK43+9z)1K4hN&^1^Lv@y8pgP4(a*AJ7*996sJQ3^ZjG$zN+ znJ<6=3&Rsr^_@bs^>0c0adv7Q3Zt5Y3OX3Q`>T3oFeeB%A!~->&J$IHGbosl!Av(X zN%^_WP|xFRB3UBUf$0%89zj>xzxgmcDo0~tv)Y=6Le+cgdEI5GoG*QCv?hD1Ew$m^ zcSH*I$sAQaLQCv7fPf;E=EnR}UZb&7dbM!|*V*(jU1=!&+BAif6>+k@Uf6Q8`%7b) z)5BlV=yE(DN`uH-Dz~LI$UeE?Om2s!R-XZV_(nChD1ecS@~|$vvpBf8*+bwtO+!;; zCd^)KYkFVvJ|}Rv5F$D&&MPl7lRFTrSMU_#J;}FlD7I4yEg5|zANK;g@O>|B>}Fbf z^+xk@jIBs^M*JVPu_=eKoVP40P(0ZW^_+S*Ao>qUT{E!`TX6FJY0~}$M`MH-Rc=3K znwz+fM}OJSj@4^s==Yye*n}EU8;zK=QjI3(C;47WVusS`&yMkb7B{Uta&|d+u_jh} zR1|qt<@62)2aTnM2tZY;Vf`wXu8KU{3@QR}t=t2ZDD<*l!Fov{xt!sjt1Hfq=HaES z`5v_0o)>1eg$)$LveY2~3Uq)In7Xww4R3uGc2Bx*)OnE@3+O0c*3jCI59T~svKaYT zi!sK4Fo%qLNV^!2Rj0PS@n~h4$r&cFt6%T5uWfso8_})1W0wPb+U#g(;>YaX>+X%? zb*h=v@Z`(9zgX7AHmg~XV*Ch=lXg|#?mIBbn(he}J!7)f;p2z)T_h$N0Wpin&j={lQUuy4`(4;}V%V?wo!rlrC z_aZ>4{9bLm0R+jQVqOo_(YN0FDuZ_oEi+~!wk#r$Mp(fYnfN`Y!*#4eCC>JIlVh1k z{uH=G#NyotRfi#A2{u=RM5w#)841vtsM}RMgOH|`%DV6g%v~Luw^-0|BzzttHW7n5DHm15<8$BO?RXK@bR%^RVzkm9|cbgrys`K>DDo@5bcxc#Qc8_fQ==_1aL>0$2 z;MLvC$(9+nnPZJL+Fw(zb;BB55log5^#nt1WQ4ds#Gt)mMwT;>L{J3EQ@up0?kNd> z@L=pQXH(JoPFVu8oJ%fwi3cfu{xRqT)T0A*iJmhI!WUmj*Vk!gS=l#_G7X(MV_Rwy z*`|c@nU~-p3ocL8ges0t?h?psA~s`V@}`c+B{gZfM^ulcJ;ulOoHH@Z52T=d!{Z7Y zwm}BK)s?YIYOP9bR?%{gKSTB;$&wN+GB)&wO|$Ua;hL9bvPtcb%AL=RcBwsZywvmt zWKem(zlr=P+{Z9l5P&Gy)ihk~Qr2?c>Rdj!CfMr_U+U;tz(P9|ZgkV>-^J6E53w_M zvJ=)XWr34P9yw9GM1$!1P2L@9HfF!Y4rAto7gMt(%OP`f4WHj*HjJ&*NNsE;n_YH- zAf?7ETusk(`&4z_+OQT)d#gx;wb!!(DncMB=ybV|cG5-Q0rFE(7W^nczQ5Qo>~OVvCiw5Bs&o(tBecnJ^eKT36hJAf@klH0O3sOf?Ca!79Zp6Oj$tVZ#kZm zXQ2+^CIm6Z4=aIsK$W_34S%2fCUxSo%Ptt~8c;x1<@IQAKmkec4f4f)+Aod%c@e{nSKdhl=va&S{#w;i5v$wQe=yYjV>TY*iz}SSR zE|P1z5WcS=j^05_#%Z59Y|KH3bKgE20}?D2fHD1e*nUl}Q1p3LFN^d$01 zGp%b&P#BcV;U}JOY*N^H^P;=rH?ASqEH}X-t%NPWmu^eqM(otm2Xw4We#k5f>L+rI z)LX!rQ1i|`S}j#)jZi>DIN1vA?mh3gR{#f#H$Kx{&JGjd7Rb%Xr)pi=PLrMiX>qa8 zJBOgNN{W>Qrj^PwZq?oM=EMHR)P(c?>1G=@)L{}_2vhlJCLM8E602KkzzL3sFMW?{ zYP*>}a@=4SzMr?BB-XYq+GCBG$0vLq z+;U?MDvKi^08xOfI7h?q}(*Tej@ zt=pTZac7@P9}8XT|IG)iqDL-{qmn*omd9_`9Ev zOB#L!ylpCOl38IE18mviW?1QGy9|)od5q~$`FNVB8nYihj(PIyougS>2W-(p@tR^a zgx+7(%qU^vl@s_!vq4*HMz#B8Xb*i$Eo`0QibqGM=x5j6rlDOjjo*z*b$lJtCBa1mq4~x^)r*sU?O>3L)xcVIupbku zB>{rY>%V*(E?3#@Yum>hny0K8X|o+yB(d?%c#0y^rv(@#0`{nO#el~;vy0@ND1cBw zt;B|Zp^jnnAW6B!y*x4`&Jfy=%hY@#qZ?3Wec<(kgqzZMFqqF_GMX)tnrL#Bv4*I2 z52I9TD)}sde=w7M0Or3)VbJ>kY{gvEc)9wAGG2N53gNk!pFfx25^>}vaY8;RqDyFF z|4@QTE3vT^J)NocDW|-kk~e2Gb88Il4~1n}`}ZYjaDQK1S97t7w1uze&-K{2V-@1h zg~N8z16>70Domw_PhxTm-MAjak666?BZaorJ%H8Y)(f-Q(JPrBCEw8gk-OOry)O?T zS_-R9o=rf6jB$^CKro!&72rZ$;1sV=!B-S32To#qn*Tckj9cXr*#r9&>6icj+0@$| z_9It30w3Mn^D}$buU2YmHa?Bse=8rKRxPg6G7_$BnZUh%x{6;G9|-%NCM&o*!TSn9 z-z=nht~za57U|JUU1e=GWFn_m<6c(()5k-_noT@&4d4?kx)>2Os&MY?U3nx zC7k4p=r@#=yiKhgE4wVxxmTm)XN0beh%~d)P5?_Io}_k-d~lF4pxZ_;2ZX)-7tkP> zE2UPKggR^?NKR-6VQ&%#CXhH#o9Sb3x{*=2fXVRM;7zVH z_zM$W-EKw{FcHWtd<-R)<+bOPpmjjjA>*FrFkym1TqtqAfw%6^`X+$~L=i3%(fcO8 zq2)x4xP0%+Y8SnjnJ{5Iyn^YI5i{Y`!wL`(-V(%CQ9+50VYE>*J;^ixSISUXkZ? zoQ0D6OOlhOnI@em(heh@prm)4gOa#DN&f87mkhoHWf7VX(`-pU0{g<*SmguG z1|E<2IqY|aM?nW3Jv9U6ThxY+KFw-|_^O(c;*wZ75>JDo=wH8pSKo^SH!1~bT~%g> z(O1)2pGrtAD)_W7dYH3O?c$NHG7iz*>-h=^@26HVO(1wnbEtrgUn3KJ$?YtzW9oP7KO5!$2&M17SBw7NH$G@WoL?Co43gL&jG&viVt z<<#an=5U{6JlJ>K>^(x9v|(L|q4mgp+G#?5vo?7#dy+^%%gLDA)K>GbuWc>nDWoC` z5+b2js9OVBHiJaU#_Bi^&5Rh}#ox;lXhr}6ep%sv5{6XJ&l_6|rw&rp+-HbO@kp_3 zy5wodYvn_an-xiQdSGujxLs&US0kKm*sX$~SzE>UL%{osTBlFryw>Q=zs`-$9`@J@ zWSmXGC1PD6tIdX#lCVBa(QXBPDT4L=OmvC z{>etVH;~Qz8mFPC!vQaJ6>Z!=Mq)6PkAsrWKV!0AH8ch~!-6X}fu4Z7fv}5(zOsdy z7j;025&`;i9kD{Bd~@`foeD;z>sih7urqu`!i3Gmj?^xD$J3qHreqe&k^kXdRkfc+ zuf|xfO~2+Cw)tm#!+ZVo6(X0o5mWYS2_v}iub-Cn|HT^X z>nm-NY+gp2K$AQQ@?Vv`VQmH5E&sD@^OBZCc=vQ@?8w}px}`L-r6F)Lo15re_MW|* z{Hhx7*BHCP5+behR9Bpc#JD=4aH9A*e&~H7s9BGvS1I!?+Jo{|it>fn85;|9z^diU z`U5@P!>(#M2g8YDF!opSBW93xj8um9o>qP9sH}?Kdze%}x3i>a+xs-pJBW&`tC=s+ z+$GO|FQI}tHni)b@$iPoKN}}4k0)#p^Tf}Yj z!u0P)vznL^zWG+QuHk8&m&L!bugIOQSAJ4F1!zO>!2J2ITZJ*M{u`$d2eK~&G29Zq zUP1TLOitlNAKqUP1r;cSYlXwRzCg594DT(yWfwywc6tEMRidQVSJ!fD?83~96@7## z4j>?%ZkCV4^;s+H_@N^m9H8$Dcd*=KyY%s6Eba)(MfE-P)H-V2mJT0nss-Lo>bo(9 zkxbEQRb=`4K?eA_glK3H{D0K|$vQ8r7u^~k6Nww{mfoZgCOux^hSb+XJ`R(x&FrfX z^=74>gOlcSQ6E&Wnd~ zX1{AiB=wUgN9-8wHl)p*Vj2-;8CfV->6v{BFDI`94D1jQP)O6#F`T+-lr1V)T`Rke zbt>}fuYomQtuLin<7!0%6L#-K9}UzXCdGk>M3`=jrEhN7uyUTanb{HQsWWR56xUeb z`6Tu^DoAB(T|l*#6S@M)E9tdwRN9*HQDVt#nS}|oen6pqAZxTe@nxl}pySf|LdA{S zbLWhReDTd=u)V>q%QMCfuA0H+#;-Yr8y8P@`APkgy-X6ZPt~a@bHpWDHI$mP*yHnE zayqAbW?>y%shFlzsO;+Y!RS5|@J;~kaZ-udA8@BKWZBv23^AGuH&ae27y_(YdfJ@A zgK7IO-6FKb%2YJ1ogdhm!Y?KdyIlv*?{uVM{!(KwenKA4RFe##*Gj2BY{1=k$#3x4 zMdy{48ZEkzZ>)l8@LA#4sf5@A1MTeJ2+)0>8|CYJ@ir^RfmLS~&4R4o-n0Cq zO%4>2!{=pK`Gm-vrv^!6AlCw)j6BPC7KHF>;(}owlQ?U)V80A95LmR2e5Nci_u9k- zwHCmJX|m7LGwgpkDy1=?_V+7u{6w|`xK|~XN5I1b7TvXSW zUQeOAfaGG--7gRGQdLMdSawAO5K?s@cgDyzH|NCB#>ykV;3|1#_z=y~rg_#f9TYH% zeEb~?{}@ou5ucAjRk((DuhwFKx)lNEk-HCFJIjz{Z_~8bXp;q{Sxm{qL0U69DnT~Y z6r<+9z#vwTU-gBvkh`iN8N}g%?L`EC_)Nok14f3gXjU<$HCo=%4+Cwr4>9$O=(lpc zlRhH?b!-nL(d`po2Ly-+bN6vyS6?bv;#u&iguTOX5^ONcAwn95@8i*b5sB1C8*5?7 zV&%f=KOY{IyjB(-yg7kmmV<9_N+cO_VkuUTnC&>&jOj{taF1v~(GUB!x6|wp(XR>k z1qfc_W3SgSJBmgiyORaV{%m|t2&KqsR-6I*yvHOAUoitRj^uTYr9~De!w|1yw_=nJ zeX&m&QNOhzPC*!ovt#m0{k#`$^AlU?r1&N5#O!vR%by)6ppal?Ggk$}+b^Fo`zGar ze=LC*iWB@LOkR9+O~;z+S89@XkS0fO0V?JuJAt8}Q+)Xv;ffuJD8&I--b@}9fOQF^mI{FnIDtB_13adCxPiSj!~MI0&}a{JxYduoTdfM28sqJ0ABtzcXKI zR7{K=Xyf{#Dd@#{^pZ1#I4BPrn71wbULr)AR*oku$_sm2qR2s*9NlT1Xhhr)3-Anl z%v#}R=3`8QTofu?#yYFB+U6&<%}GR(rKW{hqQT)A3NV9<2zf6ZI(3lG&P3KFALpBi z#*&?N&3PK3_5(~Rvc#;2E^MCTZkYi-&X+`4O00z4eC?|(GcIwCa3PrUTgm*?5PvvI zwB@8;1+tNyG>i$qzfQ&9Ql6#7wnw@?W%e5y~Ov*nbP@nmzdXU<*lx))99`YlDV2@pQwxSA_+If zo{z%!(+CG^i&0mJqP;~K7nQ7DPw%|G{47I6tEl+e_af<*cTB8#6QM7DzIawU6rE_4 z+k#tvU5rP_GrJ4OFdr(`--}<|0W>;63H2k51B7~vdQAvIh+w^=@R91s&sU8Hl>BoL z9#`Y~>28R-2Z>BiYk>sdN0E=o+jdk`N-Es1MR_%sq+i3d8GkrRvibZ~KwV03B}_ZC zIQeir%DuQG&&yY>GfdnK)(qFah58#S-Z|pjv2Qjx<8v8d0(4A}v@DqhcuNASh1i(B z9WDQBJ-AWYFn{hmG3uL}^Hh?&%c6rdWK~jaQ zZrU!5tIlT3uhDr4T|{paE(sq5%QhLHkStQ6Cyyt~jst%3#cg;pJGQr;6K2lYE_oP? zZLf~3O7eHqJHYquz!)2uQUe^pFC_MpmN$gnn>rh!v#$IJQ!nH9YUQY zVYmue4*K0r^Jl0GT)|WVXrb0A1%FOSyf-%EcrEF3HigPy)NPloQM2av&lA&%QjU+1 zXs-x)JKh#hw2)BT{A!fAnLlKb;4F2qoDg@9qOpd~GX=~5g0~Iy2f1bvbG~@9od6I0 za%-X;tEZ|{w~~_|8Fphk{42g*r|Vu#UX$;OSOG2Hm!?oxUtZA{>qt@2P_s}oct{^=Nx=S}GpraasVc;-Bs2XDPcX~NS(9j!c{D!=W*y3fhicCsof{!nnX zsBB}7WPKM%=I)sXGoYJ2gtZeWnc(+EHlck8NusH%Lq`oyq+oH`^dV_mbU&y1Lk8Ih z$XNp9N7rfQtFeLJ_Cx?5wHod+{jSLP2IAB0i2A)xnR6fOLaqTL{*5O$!b=>}qzHzcTpuI)pqCD*pnunJD@tgbG?wfKB(<@)N~y2y)qh z@t$1QMCmh?8|f>pW_7v$-YoW*NrQfs3_z|O%6wWzI3wc_@Zp#2w&W{hP-BA8RIlR7 z?iVib=gM+38@WeDk}o>yr(^^>;A;v?u(g#IPRtrcSzoM4tSn?R6hOwtB+v^o{Ts0c zT}u`ct1$%l&RG{@F(Gr0Fey5OT=#2lJfqqgB(~&^b^SM&clv8-7!ZzAf=0N!L6KJ& zfRLRBdw60l8c^=nKToB#7NU%3Jy@S>@y${x<2raGe>G&Iac_XyE(PF#F*Lyg>8c<; z$M=rkKC-ce>M(YD<2D_#%_jR$d^+;76ssOY(N;Z69BnLPIr>Y6q!goBA5^YQf#X7M z<+Od)s%<`KH{gwM8iAPS(`l0~ZF3BU{)y4ZHiQhhQ-2Hb*$0%rl2;mwafy5WW$Yh+ z91mn++CovgYLdOWFldpyQV&F}G)5Gn*3j3^Vue)yfGkr~0>s;v`@l4OqJ;dxuNoYP9KLBVm zXD%mhfTDfquohesu zF}!in=$|vB*Nk+op~caUWG;|s(rD01#7<Nc(lsxCc{#oj#S5>@V`u1wm;?hp zhV+`iTjoV(?X{^rr=P!dFpKD;ZT2b<{OJ51D+jP1dFP``MCT5kD_^@^Bd|r-=ZBct zVo;FjIHp?@ATtUtVzaPM=aSLH=r9|;K7iJ2Rjo3$u*Z5>cU}u_*&%|M5Hwfl zq0zG&7zi+|7$tg$nz)_cz)O;bLrj#tG6L4e00X_SIXIXK>W%6s8Z)uHZOkX3>JwMZ z-ZaNoBzdZ@aIxj)2F-HeA5%%kn_#@4cP8cYH zB$Z*LLMQZp0%)Ay=e6e2ign7X%(qd9Jfxw%RTmk=o=|xUH|U+%2FePf7kXZ&L4a9r zD?%2q0v{KGybZquMWm*#`rU~4r_wQ_usFBfLa>p=U5q0*AI!8=mQi*B@Kv(kgjK(m z32LJpSt<^;h^h+XY8p)0?8`gkcI=ecPOid;LjxkM#ljFQq5Z=Q%`IAC1_5h7f z7UzXeC}tyN4QMrsJpcK;R9zLeu|H&FLDK|D55u@gMUo*pmfzMSRmt3Iz7p({t;YF9 zM^S0~8GRMecbgWHZvp%c;@^^3x^Gl$)s3uR57ksb8 z=SHjTPr+G{zON5CiC(3|OX_5lH*--mfkvMIH9*S0@3*d@T<7QXP1^*)SRwAOV zpP}uko&a-G>#&kmVZWdY{bAMvz5)b(fa<&B8nC8mma;M)lWLaLv3x%aGLUs5B5LJH z;phmIQ%+UVX)VRZ(a1GD^O1t~1*z0BsFI}sc)OWn;yCt#eKtuHUQ$C%^l@~Iw9p@D z`>tTF2Wu~^Z5hP}aS4;Mz9dVnvCZafQFCKC?EON)OyNQGtN^p-x4ZSl;fR``IUWg9 z`%srt;f5%&$^Ev#2>eg~yXTI7#Pe>Zsl)YEygA2Sc>?_fEUdTn$`GW2%$<}2tucUhV_0q&;@bS5J>OvHQ{7Z zFl0S565vp^%rpC>Vk4H;QRWB5d##RR{(?1Ju$Mq0>!;=m77XX+v_377c zszgkp<-^1*uv<@a_Ya+}oZ*JyD`#cgb{Cnf2QXkOCvvJ=f{}>4PU(l#IwRc zosTcUe|eYD;3v4DVS9?Vv;8rQKnE5a$fbu%uM*w4%u3o#F{CV{2a%TNCU5O184wWM zYTotzQ00ZQBiZv&Or1%Gc%%OBDxSZ8A|n8QoD{0<{GU78eM<{XioD8Jr+%kWj!6O< z!(+hpYf;gL7(giCfz46e*wq%+B8epaSc3weo*9FEO&r*A{bmhT#~IBsurT5UyIt8A zQ^1LZ5>)Sk8^IIkiO>rUmt({=Qgala{m}epa#k8!RaYiQKXMz*!u;y?2cqkqm*pE3tzD!9zHR&e zI!KxgHmTwKa8!2(^Mvym%!x+kU?iEkO&#*lsBQ8sJh^caEa_cy zMcWzJiHrH1bPAH0akP%FMaHJoN{joz)NC{WFRo1IZ^f?u)3uK;d46pqx#BUT%{iDm z1n?e)+@PB*{1IYZFesct7+W@^!>&!ZiY~0#0DMUF0fGXCsIUbE@~uYyUYFX$zNnC_ z6grP+ORZkhqE%sVvl6@i&H2lf4d1@)on#A0$T-Pt2G##!ZWKig7VHA( zrd)R&oC;hK*--~qVxAN~X#S*AduFfQ7@Kkot`c@pJEjNlGp%p%PQrTewI%m|$Krom z%&6wph1u~A7{}+{+YbhU%JOb34V#x$?9K|ujWm}wZ+UmE7tsnD>XaqS{`fLF?2F&! zN7|E`pLPfvt>!b{YM>Rn4J>{UCoWdLLXo|=Uc;)yp1#Y@M>P^XaN5eAhJS7nIeTTT zwb2L^|CHB{iN)ZhPezku+Zy4Cx}d@fV&nT}RoMVscE9ZK4J=Od9>5epyOlNNv5a)g=wt{Rt}R$$T%vJC(+>7I!_h^@ho&E1JsuiP--qx^F{{WXuN?^9zO_YF@EIJe2(wv`#h&*r$a7aK2u zLZEo%-Sy6erqlkPbaD1xnc1)^-6}Nzm0PjDk<8eB*qWh;{Y%0l<+O3h!0pkhG^|JdNk7L10MWtoqD zf}}Bb(hO;C=2MHdaUFkTh!ApIfJXk+Zc0}NeOKHlPNC2HC$83D(QOr(@{tRsXOe*B z8Dtg*G5koQG?L}cag!py;EJVGsuYA91IkZp)Vj~!eXWMo-wIS9P6uykP$1M59!c!- zY3XIKYsC8UI`#)UKD0tZ(-s@PvZ^F0dVvg`I=?5HU`_MSKWOG}_ zjF?}yHC{$FT~Dl7`7^8qL7$2ZxEwg;hYKLl{u0d19kqOU()qMiiv7lbBq#AXdL`YN zF>JK$ah8Z#t)c`-@8@Qr>5N6vFI0tgb;Q};r8Pr#y+_3#7LQ8DN36LWYGOrC;vZTLEJ?cdi9_Bur5(&%C=K3p0GONn}IoAD|qcbgM0C40J;I)aPPQE zdnp)OE|D9oExbOuhzv%v&TvM*rPZTNvaec{T#m1{;#UHhoBDF(Cl~lebl0@$!py@p z{_-{Xxwh1^-2r#NDY<-Uq?Mk{P>#k}2IG>(;SsKMP}Z3V2^-9Lu4?{;KgHJgM}?5* z;v^}PZ-sY0*w2m%On7C*0AjK|qEp^%gtMv|M~boz^x{1Ux}GPbneWhF|E%UfRLWg+#bxKj7XRfOJj3Gha0d*-}9b7n_&Bkv?r{ojl7 z$3WtfsgKWJio|wGhb&p@V`n{$qMyGx*e8~Of_0c$Y$7!+h$-wt)9Pk7Rwu<}jka3N z3%!jC|15L`CQ>^wd~@zq5OHGw8Jbkhbs!~Nn_Ge0F&VMz$F(J9wjVf4D8>;RaK@yJ zHA3R5fq69W?=d8+;>maadw zr};z@&GUHjhA?*u*K^SaHmTcTjipEJ07(%8j%~A(a4$BC5~_a?ROowos~duHp)N;N zcQ^u`z@BNc?DP>fjmJHNlm2?$Q)y%s-X`;k<7z;O4+Lq)Wt*=~yNHsZ%M2(2a5xo< zL|P;E)%D!gt6V^l68$KcC`}B8(15w})S!|Bu~6|zFAPfDkg922iJiLlb*_^>artw` zw>uBG0bdBR{gw!6VWuQqEqa(|+M5;HnqSCs$!)|vLJmC>B;}~52lTy2kH2%=SO{-R zbsS_Jr=(kwWoFJ2$P!LEDD^buGx^*@}jNw4j$ABx4 z)4Tn}G>eBF*$BkO+4~N?)}bgUD5)>s;zTT}HB2Nr&sO#$v5cfd}0C zWMBeL37RdfV-HxlkmfM`uQQWu4NQl-{uPQf*nLR@S)|A{HmtB;L21J2H8x`OmB#`o z`mX@5Y$B+z_}gm-Z9~jE{;pWbwcbjk8m4>5G?@u8LGC}8Njd{mJQi-CmeQh(flM}t zU`^Nh0q>iLVRH@!?=jtCO0-Jue?L_G{dwjBmu@SAx-(C!VRpku;hU1~t(1@+u{J!1 zwlu1qdpf8xzxwt?vXpVRa{01n9*1A!TB`2fe2Z+T&tu~KE}n_O!P>h;By@v2TMVkO z0fMz$?K4dcNC>rNr7-$A?%!dsqYT)!vaM}+@~q+CYf?~CRiy@}k_qvLSRJmu<1$3r z9B6=^Ln>z!tfgm~L6rN@ft?>LaXNG=7mQ3%RfjOz%Pz3qI+J3kH7}1C zzBxONcj267>?LiiWK%?7k&|3}Z@VR9l?#H4^uhI3lflQj0v(vg$5D9u1_4A7b#_WX zQ536^;9LaPn3gp5l&1scFTx3LKGnJB@zuIgx{=l5=NlU0HxH& zo`~Y1ywSxu7h0i!MCZ;Y+G_KBq|c;#g(glO1F!$32S-%^SzI&g%;A=Jj>B^83tVWXx;c-+e17V;4|-e zrwj_mO^(VT2DV`@<}_&BM<=%AvHU&p-g8@ix=p*vGYt)sg1V^qHlDmCkOuIt z6KjCg&shR705dLu(lny5H>sP>p8UN=3Ei~kfxYF>YbyKi41R~LQx0SH0H zx$`OtA5;*8T$9%@zDN-47X6#1;~#rR{uj;;)tP!83Y~*=({1L$MEASw^U>V_WyC02 zah3fO8FZo>U@=BF`LUkBxB`X4uti%O8mf6guu+7X>2V70}FkzE7-Yo^hlD zz%KIi_pZHvW4NniRr2Xx#3d9+5@SG}bz^x@nyclJ88ch|7c_qy2c(&>h)Cogqodfg zgC?WXC)LuoJ7uRu3YP^g37iqlq5`-lehZts3=Yw9-J^$5!j{#4^i-*DzeWdTvBF$* z&&7`}JmHZ1xT-m`A2@HL9^6wlY>mR7=fZ5kYaAxPs57e;^(NQ54m-r**!51XX7Qq5 z{_20-sC!%+@g0(i2;&`eB9X8zN25o{by#IhEn#$Rw^)-ZzWNsOF3w~|P#U-a&?FT; zsxo)PwHtaqJdGNh6{76WwJ$nbMhd&6+O%fZrqaO7^ueWv>c}c=!DAq1vC5|PmTpB^ zvz+sDYZil5m+n9&=K8$Cnm^;Pz3OK%+$1S@m*Fb;aFv3N35ZzjpW*3{GF#q^7lvY7lf*^GVU^|qok@1>D2Bg0e3}cw>f6U?n3eY12Re+?U?;IDmY+ z#f8t~#+vHQ@METXWyAk(+V5GtIE+C%CIuxCd%^SgAyO{$QgIF$w?;xpW{8D@g$AXj zXBl?B-#YT}#a-S6s^?BW0tqeZv9b~_dT<)do-NkUee2LyJ#AWu+!Yvxh%ZO}!vCF% z(vH9BHu$aD0VRMlC)Kt2PFO(lo>@S^M>fMX?Vv5n=tJw3i0=wx)c~ad0*?v;fi|fh z8<1yRrnZ=m;&(AIYs8B}xN-mq;M>zAX7C6{)?eEvY#g#M1yP|7<=0DEwPFXHyeF*w zc5rERHc2yKTd57MJ+K2AIO$JqhLjU+EG0wZ$J2?Axu+YdpEtqKx9MED%6(lfj>u%{ z!C6%<{8F;grjyQ59{*$V5*IIoAYP@47;MqI-rUHlFtoBTwsz}NJ|(|%RQvEnjbsRl zQV$5ATt(Rk2+igt8WQN942172jY24r?lQ;OkfVMXsT*9$tHNUeKg%5+=4M$sfCt~h zhinDsI^YmNB#8y5-N>jrK@YsInm|u^;O_L-p||IXJA4~`V~HMlg92FSS~*G?LOq<1 z{vfUC@vXqovDF_p-Y$>TZ3!&78ao9pA!t|94@&I<8^I9-lPZhDRSu^KR`t4VWBsfjqBg1D@oGaTADO!(-xZzEbFcslVL`Ky^zdd zYf?#t>YZDiBBElSvG%uTBB({HIFgi`ey>?WJ@X5gfk0M&uq&c{B(e4ogZ9uaV};bS z6@7Kjo|JR-;Kb=P;c24X0f)jM(a-=97^B}?7O1*8;1$z$9lc11mD2WaO_jpUpHZJs zwKH=72C9}vS4I}sbk1y%<*%tv_l>pX43VFlCcf8DoG2b8a!eF~WS4I2`o-gE(8$a= zeF*e8#I48Q5$^KjnsD>Ap>pe{C3=WuTrvqdZ`;pVPn7_7cNKp!yHQCyHO_}dviV%; zIh&od-*Rt5{*%~$s{S)8%U#vuvW@bA$QeBlx7vShTh=OE z-#nR0ZNDt$0AB2IGZ%kkJ?}J_B3Vdv;*j&RQJdtfh=J1CQYDk;&Dlb~w7nS>bv}tIWA4Y7XY`jD>KBIwp>& zMMqnN&5bU4xsb-jFYumg0V?UM&)d5Z<>l>bv|prC zN6J8^BKx!_+f>8Y_jvzyOK9~Ydo31*D`MRUSRp8D*;X%yhGV@}qq!K8_n#(}BA~cz z)@t=LO2h$%Cl`l@Y(RodnfpxqsM}3Os=E*@DD$LEfY1My5!cIMDj;ur=sL=aq>N1E z2M;7~{{n3$-*65FS50F60euB%B5cXI8qA z9^+$LS}!5qF_94|a~ORElNdwe!U^r%XpvaB9%|@|VCou?eB4I1>4J~f%%d8YB+oY+Kd{3%EfvH5oUOyLKd3xbi4o}=MTYEz zNBn+j8o3C41IN}{wnSKV6tXVs@Qo)}6P7_wl|b3X;K4zBvgU+Ex6%?n-ymC^`-v$?QGTEbk<<*lhf!H4INdS z{#l}&fZh`~FWv)-dVX`+mGI`WRft<=y3I0nOx-}@jej{Mm&ZBLg#f*aXOO^cBaW+s zQ_OCDq}NEO;q*MtuTj+$dVs+~qO+;hRq zMrUnP5z)@sFZ+kpvC)vQyk=4j26$Pz+p6|+uy)eFnS?eH5+ zt&X5F3*?m>yz$>{{CuFeY0J3uiP?nY9X$j~ApjEzdT&iOpCf+M3RaTAST&76 z(?J9w)7@yZQ34nd%ZXFK{c3asH)weevZ9YU#uua!GnT%iLf=?p;Co?mv&=1647Ydw zf4`P`{ey8DlA`iol+rkQ%4|A%JXI?#xAyxm-1W7RqHeAHTd01RYWo4DI0@`xNA?e1 zJke=*-Fcd7cK^+YCZDpZqIYG?#+eC{Fw9mj#T)N!11&vEE^_?{8R)E<(g zsrXS_vnx`73a{7EcBJ07J>P?~_b>9*z3)CrgD;+KF+s?#e{z>JX-m(uK(WkpUKnIW z#q$ZAJR@i(=$2%}Rtsnk5^OHnbVSecXhR(CBG;qHbw@2(P_EZ_7!G(cP);u2A4=Bo zD0ss2$XwqJ?}=GRqsKLD#Tg+FR*-|k4lEfW^>|2#bB1|}A*lUA$mT%Yx^Gmqihk{K zEKDZllD~?YOCTQBMUC`JwX?V@GxcvcNaRAVk7iJpQXHl(S05r?p3912=f?Lnzw?#h z*a8xrQ?YdRSAmz`Vwo83s%ulvh(EiIXu=J3i}LJc2C9yEw|gMwwMJ8Jf+M!ntReqn ztXXH|PsvECN1Pn%U1-gc|voFu$Iv7Y)x*} zm5%0f;E)75+pM!SJZXcXX914a^(L1iG`hZftOaI@Nak#;tt z9T)OH`-7x0HXdsGtvR^I-m_V~#2py+eW#9QZQkpDxpukiS5hR(Ja&i+43*Y2atbK) zp>svFX-k=Ne#`t&y-5`Ax*WfWgaNDuDmbV*DoUgV+zqgRY6_H|cY>(_v&|1Vq%e}f zm_|fZ*`TAbxbDGYFQO4T9sRLw#YM~IK9?uqbQ@u3y?yXr&suRnGJ(6h9}XL1{*Ju3d9;Y((2C?=q>*duq)XqbwpmnR1}(|98F?C=?dn}AJn!8SPG2p zat3@K*N*54JxVrnFIb9H(F5imV4w z6e-x?+!xzCsHQ+ooEYH{DCXW{Vsr){UR6)*w9%*|Kuh02GkxD8_)Nl^$5~a6e*9Iv zXuG~G)HZ~AGBCFH zuJcck82ZsM<0z^6ZDhSIJ`q-8k{=lJZW)*Hw(>BCn`90jw=swX$AXDZ!Ok8JcBb`2 zbhGpKZ&rL+Bk%E@4KgMS^e~aY5HEca?RtcSIkL=b2dYPq@z>_>>Vob5q{1`(#`!tb zU{z~-Pu6bJy(PRgX~?-tYAxEs7RzHdFr#uExR8AJXw)9Lk=Wb>td4x?f5G$%L_a8! zx4u))^S^JQCFyaKFakWMYlVWK(OKW5QgY$m`Ar0(9(lB|X4_f63~;dVQ~?)0pNT+x zU%U50!ik37vAu|*>rl>|FIwh4!YKpwWc3=K^Xwtn{Ee(%cCX#q$(Km@r;}?tT(FG5 z@fievNO47a915iS5{|NC)#$Wmqv~!H5j6?VAr6RdCZh|i~ z03Ra^`U)(j@3*Zhy6+ZqN2+|k1sAJcBn6Kg)1I`)co@q9Z!lQRlZ66HZ!I`IK)SmX zU!x6a4pRr}1Db!6EvwTjm$m>5RgoIg&-(3ZbB&=AS3=a75)m`4dMp4I9Sz{lte=X3 z!c5uPE;&>=AjB8BQzG(v=01D;_=ih93#ynWN2pD8`lvKm7s+Wq_3|1Ela69bEra2O z%P}#*7W8`T;X$q#h%MSLGsDe~!*|C3Xi+6%;l!`oa5aBh^R>->AvkZqgaX5SlzBJ{ zO2R?u#O80_!=Ybn^)bXIw8Z;xp&Eb{&2c3?&48JO0T&Wr{E2B?!zSw=Qp)o^p>g zP8?-|OoplGei@nh_QN(!iiw4_HsqJt+#$LgX>&%A4GntAFR5#rHQoLs!f(VT4~QQ4 z!bj6z4F|2Hb1=lmMt{4;sf#?=UlxxEUL*14WSstM!=VX z>gLC>P;-X&5qb4WwziA|G1Q;dWpJk=Ye43Q>QbgIi(1p!aqm$nwankY<%k+4yt&?9 ze7+Nf>)*Wr)2fFXS9RPBw+HDX>K9+0)~3c!L?-%zmVx1^*NkHp+pF1u-Cr|T3WR>8 zj^xagcLjd_gP7Y2za`45Znba$)A;4qXzpwN%FB)#{>U-6cvC@qk?Nd+b2VygG{cBV zvL$xi1~dlKP8}MqA#LU05bXQuKCw6{d4&Ug6NB3}OYRH+yOvc&`qWj)I*W_X^nMJ2uZ^_XNd}mdw_A zArTRC5+~b(N^uV@m1bW0k;rPo=gqUKr+Y4;Pi-I>+cBkah-n@+o8sxt{<)(e>r&_h z(S)@^4`or(Y6H~^ER=NKOd4#Yz7Nt~B`A*uF`>xq6~c_zrP$JV1L+q7jDBTr@U(fg z62$@b@eUD=d~q_nAYela2q%Z?}%b`G6-;Qw=+gfQ|KO^79l9m zENt!F2A?m@*24dR8&t|Dw^PAnrj)(@-CyZiuz&oKFcl?G#!~&%OMPtyWmJ?aN2D)& z1YNxkf-Y^n{-AVg>)vt}AJt^k=JJ8-xzbi|h9D+}8Yn+#M*O}&U=Jyt%t`{( z95QI6;8B;&Ap`G;^^zzr7-q;$Lb`3|3kzvDvX2{4ZH;0aF9_9Y@Aq}wgQ8{G6Zl3n z+$-a&>FFx<>AUs0T*GXXwYjje#JE$#$jJ@uJgjIk`vT0_q#w6W@u_gR(vg^G&(@j` zuq4J|TpaH1)_=nwd_O_bv5yx; z_guM+VHYJJ_#W>%%L@niBK=NDgseR|c~(w_+l5{WVta5hL*Ec&PRBtK?y z6NZQr#e)A6;`~YYXgpD5=6{j#o*(;r1^Op_Do%caeGTQNPftfPsY$C;yf{GPr9mxI zNf?J|dAy#oT^NFYv_)ckUGtAwC>u%W@*ZaohX7}KnAGE$Hjt#DIjV5DZLV8*I1G-n zi(7p2DWB)OK5J1?6m>{MbdxpHl(I!kxfq6!nNS6^hS{n|-on(d3jJWq6-W|nX6lO6 z>TaeFpUEui6zled;jT;i&iOKbCfxVKHNtsF0kmu2*u$2C5v^&-U)w`nXoIQAA@0fm zQ}YoRW`)BuTljryk|R^Z8EX~C3SoRr*QNh2RSpy9p z?)LYs6zfP5Xfat7v@(?_V;*cb#9N)<&oAt7(d(pon!D{ z?sWU60H3i>$vpICSal7=?KUsvic<0nR0|z23CVi{y?d+;*`pDHcDtCv*XXk3&e3 zUo;|^?z1t%*#pMA;QKzpPL%1$hPVvP(KN!9(~`Mlg`ZMvTxegyDBqNc1{qf)Nb+-` zR$Yk{KGp3DI0C15)rUH*+fx;yI+y&1Es#O+bmgb)in7ULZC-!ELVOzq+7vol_gooa=FrWUujW>i~i#<^D^L0uh^ zt0R?1=(oeSi4g%jU{`~E4cukYp97waIE+aTY0Blb%5&KGfz9>O_O%gI;LK zrxU6uUp;00NKLp{38b7MUPkuZ;gK{FI{&TVJuDoIh`M;bj*Fj#QON6YIvuUom2)8Jcuats>Sp0 z9h;z^96XWfbeq4jOo@*`#=-f$HwVj^hx&qQ&!CbEjHKbCf7P#WdoR$IY|_o$RPJ>f zx&1Q%%g#(l^RNj@?iRPKp`EI0u|TiCu3!y@3?oEf84O#&MC@*S5FaLy<(KB_!%Y(n z?tnzPXWZy={Js}Q;g4LQ$Ju0Y4xoAF{A89^aD1faA`!do4lRQMV1SC6x=G>`^8NU$ zhY~n{==v-KtGAwfqO&pqMi-hi(so7BLV6MzNtk7=vOX4IB~9_RZru|A*%6j6l#Y+1 zAYMq^4+(;*oz)g}fmLI4rlgDgzMf)|VPSpA2_fZw`aqR{ufMzGe*JjQd$gu+HlAwA zvdkNG^1K6)70Jk+tTt&CL6ucKebBb!Y`GF`I9*KAavpwAu)(0y`~$a9eaq%MqbKnx zHs9&}eemyS|LNy5gUUi5`S%-!aP%Ra8|?p(sD#?%?ah$b9A)6Aa)Qgvfzq0@+$&*e z?02`-kBJ!$lbSf(yN_~&C78uTX5w$qXjPP(2~^@=R;MV&Gvl<=u?V!zvl-(ez{Vld z`5P9hYfuGl!@rjSd{glqI}ClZJs=q%z-EMtZgicBf%aBzf}@v-TkJ3}&QJW58JdP_ z9|BidvlwxouBpCe6);U`MK%H41kMoT!&{0iIjQ5V?0bq0G68;kD~db>#hQd7QA#`k zQC|8@bqevXizjA;?RS z<+RiZMV^qet@9wbbmYd5>(-vw9|%HxVgJ-EHojsauJ(rG#7hOfVJFQ)+Eb1Z-*|u3 zr&ilmA+nYULe&8F9_<_AL!kyf(4tU`Xeqy8r;$SVx#TD#9U!_lxocZZ^3b6=w@MN{ zB=Hq8K=L$gd8oRbKbpB4@eglfw2rYjGvJC9qQTdn24xvC0@V}B>2npKotq+y%XMpQ z&VZWf&TGZg&8oG^cCeJVKY+p|D4ZN;{ecM0cj94!m*77un_7_k(x=u;arQ?-oXm$S zD!E0{T#br30uNJWa3jIkrc9zVd+`!$38mEPlB>9Wjx(L35o&nVXh#g0Ag@#J$=DIA z5_>S>QNRMQFCCEq%~X5-_tm@sR@hwTqq}TEV)}G}^bfT@=pEM5Uj`i!ETFbgbAOXdapP>Wh@FUye zEN;6#9Acdd^rx0-X(u{aaC5QnKp)z}7!TOm;TxDoM8bt}T-$6NE9Hf?l>;P|Pp5y& z8lOlu{7C4BKt<28T8T7pET*Y>=;9J@4PYxa<6N9u@2$P3FtsbG!FRSF9}p-Yz45&Mj=Mw3hB?wc*-33 z>IGD9T5D>R`=;61S=|~i{U8#Ysygz|P}=t)xtM6OKU{WagCNLtA~4t`-i%&!Kfl>i zTeNCPP51z-_q6_Vjc&<1^QQ60HS`e6exP>Sk4~V_YV+C5~|#{wkJh0o_Tx!mb7H^s;vo z)&G9cmhX2t%BEfh7ZKePgYpWd5wFY8#R8=KcQ?j zPjn?)LaPUt0l#%4ZeP^X7CDggn`VPa)vWK`bIn!K0U+pr$AR>~rpKJ#z=;?Ulkx>&x)dGw?&A4UOc& zwk`%BC};h?g&_-?5lcyD3)IfJAp6R@di?FBWg3dF(+&98XuHY%afamzC^IV|an==x* zu>!5F2rp1FUrYRD583-hZ`pi9@bjFTTL`D>E3}tl2*Wb?N4%aCdi28qi3!!5BcQ)R zzJ4ZXoj)HyFet(JqhWLPgIodlx+-=f2;p*MXB$Q};!mv3YFJKx+zT`QaDPGF^;Bl| zWjs}42RqAt8t)9fgeYfW!lb;F%sdB510e86Oe4W|6XdOuhA^vnK=;~?J`QcTvRH=q&2ZV>9Y;MHC zhD9S^^3b316@5`(INP`-^0kM@uCO#hdD4^DNb|BeI!`zguCKnNvq##>W?aqc*|DCt zu_<8H-#b0wl)d3{G4HZeSu+(5E`HrAe+)nK%g*ksqm##hqKRF{0c;|}@ZzSAWKw?} zxxJLdc7M;0oPXjT{#S!@WHT?_E+ZO6&^E3U{#I@gUA zowg$!6?{?3)WI8pkNnK#)t}6sr8P*Jr6+`8gd`iXXpcV0#yex=@v~0S90#IDWZrpu zg))+&uLITPNw<;91UUn?&3OCz4H>&mUMLl10reuknyvWsA66i%+>E?320+xv3l*qC z>A4pQGZWyBTlMrOY-ey|a}I-(F(&NCMSdmRnpTQ4hN^LI$TbXe zWZnDf_6{b=oQSSa)IwQ14S-VI*dy)Qldu&U-X60 z2wxKmaCT6{fbd<8++nu@3k*&tqyyqv^bq69uL;h3sr^J+A(lRNMYeoO9H-RL0m&OP zxk?;`0_@3b==WGm0huCMisD}MWGS0iI;ELvs>1&8o@S$~#5MA5nKYUVXHX;Y2Xp-E z0qCM%+D3k#ih8BdddsPM`)}@tQ-SvskgtM;`b7|8tfDh?EV)b>ibwg!8jK3sY)N#Q!ayhxgVcL zgeC0NG7b0L^>(K{4nWuF$u!t^yZS++$#X**Av2~c^?CSqlRY>L2S0=8&pK)W2B&v}80eF%z>;%zy< zuE_tz>^)=yo1RoH9#i}%Txhwz9r-Bmd~NkXm8Y86m<~F!*MknH%hW^9u#Pyl0D6s} z#eIB`f#yS|aNxJ2a_6V-1s;XH6AP6jB^AaW;;CWuIBn!`lWauMig@X5*>ad)(yz&k zMBfb#heg(QB)aTP(i>C3DA0)H_$__SB4QhJe%?A!H=v~)*S}Y^l;7+u<9q^sYnNq>zoRdst9}70_ z_c%FD3u2Oyx;xp^T}>a_TBpe>X$;kDQ{*PLIXa;20?mp34t(`%fNCF6fd`rKP2ZLY zFx#S(4m&yA+q#FhrOizX?=|aufn8yQ&#(EU<8H^}iHk+eIY*d4}R<8eijAmEY} zMmZ(a)@#4fdun45MXH1Q@thC_R4y>oZ827O)n2#4q~*Cj>#qsv2RmEbeFgPW5lM{# z;le?My|No^9yziZsfWDHwt^=Z0_K8V<7h}I_adb++B%uDpv|>1&FNqC;mxYx_b)yy zbeG1QSV7PSVlR|S2L(|t5{5M37VFgg4q6E9GSg9m6WbA+HWP(%zN(NY#GE0<^bMD878hdrbIOUzBcJXA}-WAIjT|^=|Btj7RQB z#tVJCWbko{8tp#s4Uqg_d;evbW0A}itejQKJysQZ^WLhVmxMrl@6rYf&Ax=Y8yU@w z3%vuU$*LH=G4(phLXC3KgpLJG?`?;77A!rNn#Y?@2wj*CT(2B`i@*L zzGeAXP<)_7us~4A|!NgW=$h>yoKHdDHjUzFg;DJ5%U> z6WhqSv0X7Am!UiVm;u)Y+k<--5)f$HwQjEa0nX@ zZ4feXcyX?Tl=r}+geAIT`57av#TuNd>pGYaP5XPNI$Qx04`5@eCp0jB6}I-+f~)yp zy157?HtG(7+gIUp`}KfRr9!!$@UoVeCjZO3YXyYkxM7K%0nm)^wOfT8xK=ZE-CK$fcP`s7dFtn@Dhu{z<=3a$#7_e#~|9Y|JmKe%vTZE74qFmw3a z2?;5c%l~M$VCxjELj08~Ydz{k0s#^*UL~yqM4_Lmw$?W5M{`xDST}2I)g@_A!t&97 zR1X1q63*W#Ca~sDIr@I|iE?p_VS}?Kk%qmWm~cl`=pY+ysdNR3Wp^v8lT?*bjcl-} z?pmuP^RSKm_M z``9$#4~up7zuq3Eckx0ArfzoI9NH7F20IfOK|`7tm@3=P4t?*nR1N1;{ye=8FRrve zz;bCn%&Nd)JaNd7T2$57aY<1|MYMJAQ=|VCvEo)vhxVx>Ng@Y+pF;z8>NflIdqd&| z%O3y>ptIl(MLcbQSX;?-YwZd+&wggB_vzch^Cx!s$Po$l?*cL}Y%kXr$|Yo<`T-O@Rl zz3a;ZrGgl$_h#!sSXe$EbDBa5!r3-NydYm2U2}F;@&PNhsb<4drm=>K1mMxYv;De^ zwq`5IVGAPBGj)$RcxwrpI9Vt}B1K@DT@#tB8vKwW-#T36pXMmu(?$&U8Wy_ANF`Mf0xlwHQiXZ7tdLq}0 z7BN3`+b79r_5Vf+lS&F9+?>g}_PDJGk`RROBr?LH2S}M$anH zi%Eh1g3U5s^I*q{`U%7!s?6Ci%NYTCNdPFrw5qSCcv|7^n2~auDE_7_Jllb)_3FJ@ zsk!s`8Z5k=e8+QtyNSSVQ6$9OW75`39y^vj!vJG%QKipp8FnxR%5IWACwW7==Ni8C z_<<}Ki6Wq1c+Zfi0==UXaJk<~X!(}MWkta=acUa`>oEVrCK0-+ zVRA8&>m$ht%ddppR|-9|N!Y?K7YZQWJ6`6t$OS*ZL5oQQ!9ps6?*?s|U=d0XxS2xx zZR)eT^V9OQrsVd!h8xt})Lgatm!kf;TmM_RN`u8^irO!6fRxjj6+4P=Pu zPCMXsf7YvOzW5bT5D<)NMGmeO|A&tuW6Y9o5H~JvN_jCJj&ENt{MEmmO3I`0qzukN zid1I15(p#0zD{Ed?B3qSNQmCOUI#q-%XuF+q*f`w`3zn(G+HrX&jnPFue8~mUMYP_ zkiI37XIM!TpRLc5WjqnGmt=h^R?%{BP8)Wq*U+Zf#x%>|C_5vY$MtvCl8W5gCJ*R& z0H$41UIB3ZE)GRSD*AJvcU_O%>46-B8Yl1wDUUU;RrT#N=n>k~K26hP+5nTF-?&O* z2{HdY>Wu_KGF?UY;Ca2x`;e2M0r;{&3&eiB9~Dw)SIlO*uZ|dG%Vo3vB&u6qVPawR zjvN6pXrelRyO|NwDTI5CyHI@6W~Xa$K*qccvd7RZahTzoV#brrmtmQY>gxp2)7+VZX!Ko91f6$HD}DtH21J~ zy?k>!mST*zaSzZC17&r$vwX(2xO!rKN|`x|#~ioJAkeXkC*e{rx`(gI(5Dzi)4;n% z>XXLrvO3gHtKlC8vOF!%nFs+2`d3fr^zV-cmx)vh?Jl1%fYeqCp2Dvx=<;-VUiVgm z>c9Ok(mZ&s?nN-S8z_>_QqbfBqfDF@2*=nGpB5##v+%1sRBvxr=xwCHkh?ekp{}yl zr5>1m+Ffdi3KJlOeH1H49cJ(dAT*!nHr@gHwaT-qiDSDLvB;dQKOXBJIQ<{~C@V zmr=8cgb^*HkoXwrW$l^wO;pW#xiTp~YJℜVz+qqi-A#OP^qe#gS?BF3}rI11ZA~ zHX$}dR0?hByzmVPp}k}45z@uxAUGQ;x)%2l|fBgVrE@CL#(7wLppZ_Dh7 z0HS&dkpRzX?B>nQ$I*8nM6jIbXNp3fn`&}O zNaW0)53w2=^1DNsM5!SrT6L@1;5})t*1*U}f0)aWc}y>y)$mGzvFkSlxHY}8D4IPR z)k3v*PS<4F6+xCZ+~eL(**Nr?C*M_RrHF4BKD}{-+ZlX5{W}cU)7#b7K`vyGE%L(j z5i%f1eIn(mcp+>v3#HQ(P#J7`g1o42l6eRKpt7ebW_ktLH3!E=MZdJ&7`5T~8#~gT zdvGJgU&>sE0aGbqRsMagQN>IK()E;WNui(l*3FQ+&1D&AjC~^Iy+ydUYie8XW-&xx zpmDfRJ~S`@dmgB$mlY?w1?J@V%j{X8Lnjp>MJ94X4;yitV!}tL5s%{<6-dX6#G<{< z<_>+%b&ojtmNXRMt#f`CgmAQ@=KJq6m+n(|tLo8m?Bm|DuC^l(~ zPx7OZ6QUM5I5LodH6yyG$PgPMJnXSp`iCeDr|5u=H9l|BXw{**4~xk^?15o6vhJH- zC(at4saH+nNFVr&nEjYxWX9YL|HZUaWw-3*0S4PX=nEbSg{1%N7W1HEB+?Ooz@`1F z7Q?T?7oV$l%935h-BBh3vYv1pujS64Ha{%`ctSyO}{HKgfiEx zUs*0&DRv+nfAR1C-bvL%iS}v0yk|N{O1K=V))r7K^Ec!PZWJL?(z`fZhuiN6zHWjK z^jMW!>;3Rc5wF=6VF|$$K9)NWL{{kYBUy*#-#e;mAS(lpl$RkD6~CUQd7Q-eHtQJFWHVRdMo zNm$n}A@G_DF~=!tRTV~usK2Xc7U7D!7af6hZWBl-NaLpIMStnI!Nba`UD3u=Lcnk44@y$WEd+w_~L8V#uKS+WHZS>>uJkRJLdZIQW-~ zJ;?&8EMJDR#rpLJF47Z{_?fAzRIMGag82K!Pvo9sv*%l#4BIQicBi1dQJ#0{i=qly zjpgN}Ng?YxKLu7E4@ybs_Eow9DsR-L3V<-rRcr29mCqj%aVyj5NTDKQ-k zYp(0{>yn(W<%*1K2w6_zCU~jiv@t`B9W}s19y~UJ6lDoFkL6cD5UKZ)X*A1$Z)7p=yR2q zKSU!w^VIZBx-jqtmDigA3iv6Y<$}ly)ZW)F^(6Z;k$8cu^|3?5i^LRZYOYSj$4R z|D1rBc$-DHsZB}w!5MZS_i3r)+?%Xf70Law!V^)GJDSi06sng$XPX?QMip~GB6<3f zk@15GMY`*{49VVQY3Vo)5PV74&UZ#JQY{6+@agI;lk))mj10cq*)PoPqe3_?l=HIt z#%>DjrlU7QOt<38uVrZWawYwpj!Szwr#C1u`PP;a2 z*wt~uFD2DLV6!@d2{F!6bj7av#3Ur;#X}tJ>=^JSh6V&m zk~HA!@ri$_Em;Fm6XMNZgBCOOrtDTeb~$N>VsqZ%W^?Z7gRLWNmF*3CN;Xgf20 zB_I`Q8fKM>%#RQUStW71Wpc(8y z&DF8uGz4ix{Xzesh-H!VpVB|u(sPoX+k@};#M*^$`Bp2S3F~WYdV-hIj2Vl&uM zF@Md3gqVCsN*&h&4RlCI4whe^pw_vhzdrWN%#z68Vc-yQozk|{f|~Zz^mY`FM4r}9 zpSs8IkZakl8_!~&0%jR+4h#%MgXBfY=FsKYk0$DmjU6SbMK*3(Id7K=-{8o2F@O}> zEt(u05-iaHJ>?ObPblN46k084Svi?})e8WtIPFj5EWtezm)nt7AHXq2<&Kw z6TpScoiz=``t;EO`R?1`o4{CnfSX<)SX9!#^W;k7fr*R6(F|0vZrG6 z$;mb&Qp{i2h1p!L<`C2wC4OKe0zwxT&YX0cT<`$FM%png2G~D8D16lb;}!dc;NA5| zn}=V^$w#fZkEr)*&2H+XqMjc{XR%ND2ffyg4DMzs289Ix`IO7)i#<1Gv=j8TcCZ*X zocstK%lq3%r3U}~>V`TP=Ltp+im6;;yqipH$D@N;#ibTC=_E@3;i5YQ$J7`L8e_4U z*@}`D!GS#ntl<-WNjS~MkfD8@Ukub%RU z*>82BU?aEmTT9}=ZN8m`d`Dr#%T$RsOQUc=zn~X~QG?o9Mz@(0;wY=r{&?hZH83bu z)8n%;*)S7$WGolcSN6l7iM_KiwsX!(ME>(LbqWtyhl!*D&fpGBz^D}h-l$ayf!`&2 z`deMVu$uCIckFX7srA+?!}|_!IsHVegXl+X+0bQ;CX$GZ@6zIkOt>H%{jnKBPF#PR zY%mxiD{P|djkw$J^oI#dL_T%eLiai7m6uh|Jjc%)PP^>D{RY+Fs>Qn|=z-NZLf1?n zi>^bRI35jisD?oI-1Pvt^^S4wm$W9B+W)P#q_Y*79jg&MpnwH_wQ}@xufJSbiLk9* zCH*#>>WpZdrMcZHhQ(RTTMMePu5L_1d?j{zilT&>Z2heEJ)j-Vuu{j#Kzbxfa;!&+ zm~^1+AzMa;Ws&+9j)r??*wE(!E0qvLj2C*s#tCuN1a}ie#I?M-Twe9eXigrbn?z!O zuYW;f;SbW_g0+T8uEhW0=c3*anfvLt=PRd2->3|T@aevI_wfC&{{S%mS zKM^(~!tohgCP=@)Tc~}?j(zPyN`f4-O82|;w$lNt3QrZr;X(-%a&xm~T+Ej#Whb8x z3RC#ObR0a7kjVRc`hGJ#(7}AnQ`%N}mD}r-Y5#ibeeF?MohByw_Y-iHZ=FDU=hxV<^oDM#<2HRTMECgs$soo8aJfC53XcK+a$EcC#%Hahach|R zj#E|ee5cB&FtCkp4JE}IC^T*Av@MLC%A!9oHhB{S`9ZiO=#|N?wzQ=d>otnQd#h(X zy9QzdfBOugy?$_g*4f8>^_=VJP`hY>{;hBi0e?cAl8DlA-t|;)LjyS;bvImkJTIml z*Bp5Ra2ZhUkJD906ygLTQoTaBx6P3K1b<@=kZC(^wW}zZ8V`x|VJjyJ|U z&p$qFGZUlkE+#gX>2Ubdt;wTsr%b+X)e?q5-6A*~Nqe47_G_~o@6W3Q&Fe1OB91rd zOV82dH@hVw|LbrJkK%dFt?#X>?n}s-mPnrtsfxc?iic88JC7bZO+|ByfvFAvXq( z#&vEuH^8yA2c$hGnRz!{)A64-=74#7;KJ6#o?M!87t$PDo^?m$rP&^j!Ld_&o*|VNJ~%39cL=ibxF5SL zgZ#8)Zq(CJ_X`Lb9_bH===g3pb%!O~nwj=Jjb3XQ5v1LV4hr$d4$yVi&_D66`s~@P z?>KJRW(jx#5R$Kho~g9>XE~RUj(dJwK3)oZB5@6E+0W{jb;o#yC(-gPa%qEBmpDG; z5q&xJyA63;UAP1YJMiGV)wN%8&{lW!XUQ#G?y`cXxX!ll-V|g9U>hM8b@@{oOkUO{zz*G^(NSZx7I?98t>vX}Q=f9obwu;G%$X%S+?l0_#J?20x>Yd`R?O4!DBGW^zq2MV4 zyw^4(ZiiNKFIY-z3#bnmG&t%DgtR_y&xl%-i-)O0fxveo@?7x&?JppyD{DZrN#6UV5M&Z7Mo0rd>|I{C37lhx+dlq{(&8SscFA(7s~6pz(?0Ez~8 z^m-r{n;>V?$)veP_G%H1`-oy;zaMxE-3%)O-4|Psd%-2z43pTdK~mI!ly;F=r==23 zyL~pR@S=bYqzsLJbRVa8bQ-C6*i2}am{!dxEqT&n7Jqnpc_M)}0QQfO@X^+f_|rGk zDdbtS=y=LDzS0DQ*}^RS>=Ij_xe~hrJ%u~z#UOBkD*ixTDlWkH=gK_kA2Ybf{*En+ z8s*g}5heCabzvI+%MP(vpVxkBXaKljM#|&t_Yq{z*fsU@m-L&-BIc37Sf5&r`2^}W z6#-kXrB@Xt#uRbd=JwN`+*>E#+|o>;I!nfJK&FPnrzQ**4mYPBsG({Db+7IR?tL@O zJAWfc?ofu|#On9>O`)eo*8z)U!G1K2RE?S%bKf)+NqE;Kx+#cDJ^6}KGXrMJu za5DJc@VqOw4oi8Mkl01iHIeSk9u#dI&{jzZQ%{A*YiSd!X6JHoqKxs~QLd*F@49rh zE-9S=$4rVM;Jhi7j>$^L(28~FYwxO~I!}U@7CE|n3Q;ezZq>^F&CWJxvqRKW%u#;h zmBhuf9J2-Cd~H#l2(dS!|D$`h(NO%+9qbL9F*F?KKL;;pX%nIJ7Jf5@0cE66i0$rb&O4YPZL^Au4oOb{MKyxEw!A}VTZo&^~K z(qppnaBe<7=fE!CaF5kDk|jQ zfyH=Gr!1AGj6Bvo&B5;?G_~*+?UXP z>q4&ALwePxNC`jrS^8AzTm9Kze0OkR@?EsvdTl^+d4LoGH_aq;Z71>}Nc>`g-$kyu z>-M0xHKXYOo4=`Cn8hhWhd?t%hc|<;(`vPeQ`j%SutOu;6|5Z(RgQ~PLuJqv@2K^B z*LP1A`=DcL@;&_U1X@fPm~@nJV0NY&SVbWQ1)_$bwRk;MIt z?_4Piv|~LO(bz;UYA3R<37>0_IVp`v4GgLwieYf1NvNUNEjk^l(%Gyp{%1{9hrfe- zb@EVVzFJcsygGTBew3vxX1?DMA_MDxOsD-QSSk}9M?)_f{W}Lq^t_`Pi)24f$;dd* zsyPwQ$2>d705!+^(CBCe9%92b$rs-h5~<=tq(qQROJN+ksIOOtZ-xeHh_|S zW)Yz<)oGfhp*<+!EAcD|ps0Iuj-b$IjoPc;@Ec#2N?~ax-xSRIVdz{d4CSv~VH|-S z^|T2U=b5`E^lt3!1G{kDHeA7Rs6q~eXPn!?Ospm|XL^}t zY{Bc|Rdw?+SZVxAZc>M6|0NRl!{q1QnP7Jq&eQ$LcJe1gJjkM{5_x^c?DK}S!v+3! zSYq_97$a!xhFJf$6genW?H9BTi@h=%?mK`H-NpI3hXb$vy51LATj2KLy-;3ziXI^Q7O@Ov%DWugX-D1s>9V#m+MQpHOJ`*armn}fy z(9wx|$bA`EZGO@ZJe5pgkTp&X;Qz5fo59m!2G}ku9)~bi4R-kL+$9q&N(?!hI_;`C zDo~)`0WFE{wx@$6(BW(jZyy;`0a#`U2ggJeSII_wNIb9r5cl!AKtOxKhR6rcymnAN zuKp8JWa?K-#jZKFgQZu=Rt?$1%j)KlFxvZl&~R74U~%wP`tln!bHkv+JLwXu{iUvmUS8IYIniFrg5F4ElI@GYbkI8s&#kzq}(|q@UFo8=%vGpd@}p zQD9|Qt1B~gXti|kPUhzRxU-akd_O8>5T{Uq=4VN88v|W~4Q(AAGo)2o6FZxR$fq4< z@Rnw(fo={#Urkv9i=~V$Kk05$gX_@8PRmG7eUKmdTzqziDuH}sOY!-GNzblFbSdyi z#X$2eAV#$D!#fc%RR5yYOR<_})7Q|4dLem6Mwx;|C~*^qspYxM%#7I^c+wjNnctD2 z19I7(he=#|6wNa=u$Yuq7&jnsjoJ(}%c;emZ}Emk6i}PlyhQsc6BC*d$E-*Laz3(o zD`i#}{;+;7)sw5phQD@NP9j8HQG8K|Me)G_UL4+mspN1D^u2%&W-RpdA-NC|)vc2C zp@m|{CscDlF*un8d7T+xRtg0gAzB}zFZ+=$lz>uW2rTKsT`ZnqA7_s*TSGM0GNhX%&WQ#luI7_lxzc{X}lcc08WXD&X_g@mIlsLKs?;* z-polflJE=4ibIxICG#@d!fWI!(AP@Zn#ehDx=U|GAbPg|g~U<)D+-r5J%8I2lVZ8< zZlcMHkLUtrdkBK8xP)~EzG%C!yVr!mWZ7d{vheoFq8qfORGDDuwzsRqPw{Fiq^W$p ze*%PTIkL8e1IuoT?7GyEx58mRr$1b+aN`y_Y(ZR-O#)p&{38ixKIgTWC*4EzqG?ECbkxd?MQdDYfH z30L|-q5P$guL|RZwSQHU-PU*8GiRd3ke7lWH=4FV~<9BQ2&$d2}Nf%z}qE% z9(tez0MQL3U|gGxsS5k_j5ey_)&Mh*0134G*CjSFFNw>>rv81?Dun0S)}$&>AN#bFrPU1{2mw?aaYGf)f5DBkWIzLIdQl z1nN9gn{TTS8><^E?{oghi(#+N-vTMXDH-~a9|*|2ljN(A0s#blD{VkJ*ad!YUvkYE zpBp+Q#LaOcAhc>JL($nMd`Gs^Tvi4FcYMzlg(`N(>^2pW-<43t$MGhSM@wvf2qAcU zF+=$U058=9J24X?a+NOoNqJoO-Z=nm{2aS;)LIzn0fMCke7_zeEc$K22Si=dQIYWBs$PSDS-VX_vUvT|jMIj$8`rWy`aw{9}O zT`t6fkf{pc+m?3dX4Ekmv^aiaD@^}Fcg=8cSzX0vxFMqB_ou4;Ob^9=@_XWI-xLO~ z6}!y6h3OS23gtCDu0b@)!L_P?dEj@gYOPvB3!U4ah;E$5sz~bHO%`JlsMmV%p}4jM z?etwunkg-|$ygcY(#e=<1ZT*r0gI{H*Re~eM=JjeEd=)U9HRIw(_c6Z+MGW$fW`_K z*DKFYNeo@*7P7WvAdLVV)`?dHS_I44_nD*nznLkntQ6(CQw@Po@>nCDC5r?_R(4>! z43>o}2`pf)_ZWM&e4T-`U__`aI6V^ak!HS{P-BiC84Bnj03e0Lr1tf*eVT@N_3Y>q zRld#JW(mn`3uAu32|3B>F(vAp?+eD)kMa;S+gK}`(2V_(X85Z+@QOwazd4=TyhJLN zmbNem5HO*xcp6sdhU71rlDQCbiP$xMcL|ukm+cvbH3} zGP2DB7vk(Q)mKJ|BR>97b%8ej2ygT_Fvn+SB+6baPV(yBg;#%Bt?pu86STX3kFCMI zmlNori!Hx(3YOPFe4m2zg>HFYGfU(<#U{DS7D7M1mgka8n8NxdXvX*9D zO0^}`C|izOmQ=z1epyfX^@dzSf(Cclo~YV5-HkEfBQTg+z(7_i4uIu{yrO|TFir|R z+Ge45QKGhE*Io1*)6<~wwOTR0V9Vh8xW~x$pB=_+_R3Bjpw7FiV7gu0#M&#vXD~A+ zu~RyxP!0;{--5L{kiSYaB%ZDOv^QsW9%F+3_KvF@3gm4Uq32hkoL>Dww-kJ9dJAPQ zz#TDk!8tK#`&NG;mF%ZoF`?Z(3QLJVD-D6Lkycnr1-m@jH4oPip}w}Pk#nkzA7rT+ zMj97jH&Yo9#b}RH78Ck2I8@9H6~g>$sjX#rSJUJrVaX~&7vz%$g29Jbr0!-bzIXCp)CE^Vd$>LqJz2v46%*JN+ zTF(Y|h_z;wH;~{dXV>+Fk~Jj)@tLL1mtaXum66|j?KG1+1lrb*+cQ0A!?g6fZFRTl zzY0~=UMEj=T6p&8cU`GUVLm807|#iGo4p)Wqh+KdGMY_a0jhG`#4!qMx;#4kzH+vj zBtu!&EFmvA6qJ^ZmyDdOOKaCu*5kA91=aPiAh{Gm&m#%++vf*?@R8bR%bT~{D>j{ug&y&`4?Lf=#z{PM?1tI^o!@q$@Ze; zA4)hOdc}skN^;l+DFx#rKPAU=Xt|skc{c&=wJqyVWA!8Saau5V{RoXpyNZ!-L;G&A zW6K{oNrK|d-!+H+`OZ>3mF7jD>j+xGNg7rN`OrsCj)%-lSNMA5IiQH$yq~)Z{N{*E zgWxjUJj80Q-ORZ*0@E8<`wmrc@>uY58~7@Nr+0Ag^(iUL9tCQBaMQi4TeM}{O}18p zU;Kjd6Sr};Hb}h@2&QybYL+XNIW;|*~;DA?G9NWSgHk&J|LNDj^G zcqdBgUNNofyyLYj0YY#gv~q9wq?z$41|7Ca2%M0RDSz=Ugot**_2ST;aDYd-7j~{O zU=KeVuI8Q4C{$7V)JW9s`V>Z?=FK5)#7cGvySxHv{YY227cBY~xEPT_&dXg92KE6t z_7SPmZ|-vj1HaMlhN?^DG2t|nJ?J92WX|??mb#-o5eTeHsNU}rhAIMIZrG@z?rEg6 zn+m7-6+GNnWsA-KJ`;F*=tNEAe0vVW^~!AOGVn!QXGZ5E3U27@fX|&phX!QE{6@Sv zkT4CTU8uvHLi4xn-I#Xy)J`uF9$1ZF(zU7X_&Ww|@?F&FQXvq0^mbX>;2%tOOUOm_ zt{^(9vo6C1w7GZ1;xo^WDX0o8+KKrSTtPw1qRlbw64vV3U;K`?H2C(W{0ikLsfhH* zHBv6KqT8Vk^aa{!*I}$;s&*Jzr^e38-JccECpX7g6emiWX3Z6NX4mbE3u_|wk2s>v zAwWPe@#Jb^hhI6EMhdgpKM3|DOyRa$TEh?(^yczgfo{Ol%5MIF11wC z)92(lcjcE@Gw4ICvs25=`sKf3o19?pY_bM ztOEs_6d7Q^G3JrWqZ7mwezJ4^vPXx}Em-$R)$}rkH=F*8-KsB{oRq7w^5)bzqvYh3 zQW98~JeEo0x}#d@Hfvof`Zsmw&wGpLM9bnetdCRhgBL}6i^ySt#vmN9q?;nCzqtmv z?doOIbtD&1=$?3Y@$uTPzu%q_b~WB5C3sX}VIzV)GJ)%_9>?og+F{adVz^Y;rXmT_ zPC%0naGpZTyV~k2Km7RgLU#E^D?Y9D$y|=g;Zc7o-i zG5QG3><(w0Xs%ZgF`~bMpBtWFMr1C0YjQ~ERDemmJ6mrV8Ly+of1KR&o@Ww79q(WF zirs9t%B{4aBf&8aty+ zi6&^DCFiO6eXkBCSOjX8`03YdD@-?PPdgCPlJDwVKtnb}i z(jCM`3A+FEtbUr5=A2=>8yLa8Uh>%6G;0qKj*KYO$!sSERWDZXr@@n zORVD;c>6S4%kelfRfb%nIvbtTZW(;#s>E7YS$RjfuPy(h7583{_qCYcWe^+xqv+;A zZiG-R-h(|%t!?@!l9-tqP!7>}uIp=wp_O}ugf9ls1hUQ(Zg!@dC^_UIH?b+vsx)v- zSY5IrDkDm&fuyQ7UI;c=^B|dy4D72*I9mhsag5DXXyw{YT>|gwiI*s?kYLc0ol|MP z6fkQi_5tKSfTiBp%xo)%MuTYURvrA%x1QR!`SPn7G5J>q3ec(fn$9%GBC#FpLzJ<7 zB1}v-RM#r=5ab1&HgKqDyc?m%E9?GG1RD_n;{seb&Xfa*!=v@kODf({gz&rxzrey; z1LvAjpBfi&e*eNBs^;XuC*)5TDxF110O;uJ;X$#*LYF|VfBscsTNw)U9iP~$dK&GF zUi)C}TxcN?v4JOx+gQ1}^qM~e?N9&BE9z%3jo|R%=6~Ufn)((5()Q9r1oLI5W_?%Z zXB&nQFLu-xN*kM*3$S--T_->o&AVA=a*GQatfQ6WD?w^^1ertYV>k zB}N-1<|hRd|M3X^Rc>*Jbo*>KU?K~D_3F3*CHzb_Y2K+O<_t0bQZiI z{D-2fy3)Dy62$r@Px%yv=V-e0V*zD9Wroz#7?udq$m3!FEZHsU| zk)LwM)j`Xn`xp}bR8Mi*CER(zR4SVh*9${^h0@CAGs(Ei_J8^>k_@fzsTE>*a|)*S zzW=fxCYpH-%J?4o>*{=|n=7gay#IA5?(ZXCxk@6=_Cn8rMTfSyf9ydDN z{xwKF=8g^363f-oYFGvoJCqZv^N?9MY5Al{IVTO|bczvJfp5zOL7T68!y{E^BweA; z5auUY1&d7;-~vG<*w!nLP!g-0ka1`kt8Wx)YeFS4k7>5+Or9j3d`V;=|BCvwm2#y6 zVJxqjd)}G9>uNrPkyLsP)nODrHH8d>kU-SaJoWcg9Wu5p|Gx4g6jv_Pg}a9iR+j2T zWh|C6*{{Li!IVjgEx{iP&); z>p!H?W!&|xi)RfQzs%VX?NjJ$J^#New?>m&ND&$)tFCy=UX8UmVu8t;yvQKdi z41tl{!>g_ZqgE&clAOtEt4}9?rLOwCib-|^aALo5olf#|$Ux5R`vzl8U(&C+`Y*id zQ8X2x4Zqps`Exv-qcH~D@7^?O^+>S<`5_}eb#GC>Yayg~1?gxdKV)BnGcV_@9ZN2!at)hmHym5>y*lFnS{O9gRAcMBe`#rVaUA>#)fz zg9b0k7^+1QngDYf9L@>F$niXNs;x_zU$VzA$YE!uDU0Rj&F%jN{iy6ieGQgJSl5OOeY{ocHDJz!MbbhBR7i^%=Y#O!@LVzj817(;y!niudYhl(0 zGgn0s_;zzpQ@znQd=mZ9-NHO{wVmklcq56HIKT>qxUvDNJ@o%FxEh#zda=r~Jjzxc z_V>4hD4KE!ZxM*_A07#C>j3gOp>hZ4oXh@gRYBCqrcuN1K^9nMk(##*PZzF(wkx9w z4$w+mN8fU6@O`0_C2fJv?Ks%vQT10(VZ~5!1g&`mcS&A@(Y^?9A+t_$2UwHywO|Uad)L__9s{n zZL66+E1L~GM(>%<2RuueBr+lJ;5N4ivX=OG5wg76!w{PxD}0VIeX3lkWuguKyM(#{$X0*$ zF0YsFaFg^y_gH9jF*F6}S1-y8dKN*Pmt(|lYLq6vAmdY2F#Mx)Y-biwUML-5fK5F+ z(&SNYhvNlMnkOkZGukRzAZQO-DBzu@=NWXRWJ*G*vh7V;KYKblTMNA)9GY?A_|1z> zBo-Wn#=q(28^h^W?Nc#sDOSW?=oA23d&7)Ae8g`hiQ81oORwrs_(9pMGdm zCOH`bo5F5q0+2ysJxr!Q`93~a1HVfPOr|@981CgtHsyoCzYH`Sa5*MKTdFx$09a6B zc<%&Z;cNrJv$*BJ<3g-v>d0ti^~p{ejz6q z*pYwHeD`-V9(Np=pa&;W+hXK3Fs_&=}u1Rwz_XKIpT73JCuT`&`9# zB;58k55j{*2e`HgX%u5cKIQsUEF?1~?tQrDeYLd#(I@Pp;E~cKXqjIo12?tIm8Sa8 zOeN@w4!AXg2`>40{t=LL=t;x24ZMoCt|%sDx|aFqTV?N1!>~whkW) zWi-h$$?Kfe_B=S~EXIx98L*4DmUYllX4}d_wY1u=u0KCs9=6`AP$C^g`!@f11Nk`j zhv625fn1j@wDS0(C3`{Lg2IL^y6hsydU^UEjqZ4}_pMTvsfc;9chDI8;1&!gYBlZv zLTAf}#>&hEKn!ufRw-ek@Ql){ck&K3gP&#@ zT_UpZvH$Oh#{60}XZo8uP!bc;i}2sgd7JxAXU%h3_Fja8^0n2?7-VLldOcW3)R$>{ z|3HMJuoK>PO`dDa4Xux1SUWS_n&y%=nQ9kmrDTpZ9vUG|v{aAA72~CMIq{Jg6`U{Gg)1%3l_H`IVtQZM5TGcW~8N5j_TxQ_u)-ugIDTX!~z`nOeN#>;hI6m?&8^X)q;pxV5 zxYs&l-+C`D5ez>kIFIm;441C|SgPq+Y?|tWPWy1H)}9&glx(hmrcTHK^|QuB1k-mb zcZXV9oaFnf$}8TxgrhFvrJbVnPToel=yjmn^}4(^DdhotE5zMXha9)GPiT=XCKNWA zkK!Lu2%_@9e)`QQ0VioyRC=XBW%ni3BmFzsM9!eBH6QRABk{oI>neU5QFj#2!G2`i zu`1qM&d!#VGAz*a(|-G$5&*jG$GJnL$pLM1);EY+~;fi2PuSVcw9}$gX*i!*WE-8JFxs8{J;GDSrn=ML6Y$ z=|7@qvISwq$d#~X%V5&tMCOx-+ZDcnpe`N%!H=-^>1XP2C|4N${$k`EZ(&rk&l~DsrKmDxP7T_@y zK~+Gxvhr04P%$VBLs)2T^c+c!LutIn{jDnd;E_heT|KxfEV`6h39haRc2UF9?~m?k z>?Mmq(lDiZoSdwjBS6YOKno6Rx?9^jQa!pSxVX`2IP6yM7zfl^MOcp;W-MN-eRP8u zOtN{gSqI=Gi?YOtz*x;0Nel`{nlS#3X8V@xTO*P%Ak7}b7*%V6U-2@(r^kvt$e=xr z@gqvCgmK2LFE?N#r)=TX<5Zyq$fZr$H{in|r$M=OA}Cgsl&f)~i6acnAQywLHv{^S z_#(=bm;1S@$n}M#^ezqO1r{Bkd(wK;2!Yqs-A;A30FW89at@Kz0mh5$O`1dO zkHTyLoV5Uftzt1YSqbznkBoxnXx~Yd6Fwf2il{fS_o}$IwCThL+z9GfmVplj(t7EB zx~40~5F(zM&U%RV`alxEa!mcok$9cGxKe9m;yOR)1F98Myw&}ee4-IXxf=W?%Z34L zF03n}X3@i9YW{_L50QhAsMma9=O$dg{^ho6Fd}9@;r%W#s~SyY!WcRS4OW?;%EIiW za?xs)PRHNJ+x~+gFrAGp{h1Ht1dnU5slj!%gg_q*BhqQc)w+448xiv$QTuGFW$7@N zHq!v1H##>F6VQ=CQF8VZfV6X8hIzZAzG1OdnSd@igm6|-iRB~t3qtW*=^egi9M>kxK4Zt%U{8lw}Bk6b%1=#$MVE>Yf9VUB#j@h=i zU|bs!CNT&XoN%s($4(u{U4z&Uzqw2ZL1W!UBRn}8RwDT9^p)qruB$kxH}VWN{_fsT z)r?s>a+(M^)p0K(4cAoiRf*=x2oP(Ij^-LK?mycBIh|*UA^f# zpwsfuJ*hmwsbEOuQZ6uz7<@8dEy!f8xqu`R^lek)QrUw6}5+7*tnO+ zH9B)dd2z82hUAk8xq8kYMjHu3$!%OErqnD&#Or#X4IeOVLER>|W$rbB&zq#rEj*PY zzl?_OngaZ}<_Ma=vKL)FeH<|6-$;5B6^oRY#xwjIoV)%kV~%l`*`brJT>!tr{)5^0 z*RWr`YYEO!NSC0`nq_RYo{5VDj%uCEsh*)jophg8*w=MeJd(c98 z0ffrw#jc!`g@Yg5;y3;w{SnQzI_DFc-e|~P;;rzqbg{pI93!k7U?G$cR*UuM9zfbf zByVw;G*TBB=*Z(kAN?c7AYLF`;7Bzp+1>-tNO*6^dY>s1xLciTJ@c~e!%GWITAYaa z_ve4k6w(L+i^UE(W}*>qqPhil+Ew`1sin?9SL(bf-|U8ZBw<{njAK0nQREKcrV)`! zoZQ$h2?;(HZWS(5@4f&{N`wdTK*K&CIhyfbJV9B=q{E)Ej!!WNZo*Y(ps>TFtQUk% z=pQt1W5XS&HOXZ8RAvSy0M8}$yME~DUj1Ilmor6YjoN?llLWdDTc&7QX8tkyb75c? zA}q%}PY1qhrRPp2y)h$)&UwHeCmo_q1%aN8g2Gk#pa=g(zuL8 zDLpMb`r6=&TXxZHyL&Okwpe>j*8n|0!oSvUq5M0hg0WW@CqDRgo!C%PCVy#y?gsj% zZIhpp(ddB;WBi5NoE6?dosO_Ux&o{%iGhH+tk&7rhT~0sxwAIHyhEWCD{9rR!)jBV zM6Of9q{$;OAb=eN?;(2zbf%}CApD3Uq)@u~pf}*tw`Kr#go56}S3lC>mqaa)+=);=;%|p^d(c z2)sG!&r1>B00w>nVd1&*^bWC1nVvJlV*b764M}YrC{GSYgIR2%LF&4EvXE!(Lp+=9 zC9PFgo;r`W3YhUXzaOWwA1vdpW1(io?ql)C+fHU+3@pE4Nn(p_fan>LWP+CeJ}njK z*Q7*8GD6OWb1;gGop?C*guy(v!{H*<9VSVAIU0khNeD>x9?GC5Dgl!namWiO50KIO z2Im0)pOyH2otT1n)Fu+9OBIJd@hdbfaH;gd;kvcUCCRTTqnX#h^Mo_v;K?>v&8HCV z2+^;)7BEoZ1~fF7qIThx$F<5iP~Yz5j~kg=S=PnGASw*qQ{@$Cy+$0=4#^WgRjs}J z9qR#!WmAy={Qw3w#p(gt|8^L3L2jrgABS?(f$pgLg@y17>m)v3L>%psic5mh%3Ov9 z)uULT8;f}-XYZkV;un|+_0h{KDD?9g-Y5i?(t^WxrlCBcdEPcILD4(T^Pcd+PnX^3 z*m*X|Al|8o{cKCe277>DSz73^v#}-F6t%U`->k{m*pAhUvC4WV`!moqOF$o$dvm-x zAXyLxk%(*tk5*4J;>+T-vSMEZwjP4V$2TrrE=9CnvM(%U-JhU+)x2hAI1q`!1wAvQ zIiZXVI|weqbW$~kxgsHwc!zeJ3P|PpFQvo5CO%BMt7A1ON!}!Hl&51WFD=6=NYaK|(M4U}^8uzyYG>A0ydbpxWwfF5&D=soTaKBX}b!{OTROHz1O94uMx|WPXG9iv!jNoHW z*5dM5r=XW_7xroW3EbwSQ19nQ!Ou;=#*Dk~3b;$!fr^BF|Fbd=hQ8eKI7?peeQ~GH zeuj}q@?8d7>US%gQMI592?_|vxDeXgp#z^2tTCZ9YiW9pqORHvPus)|V~K-;n?mvQ z`);S#gsI3$PMZmr#i|pR)4}Zi3GIAv23G%)h@W=NQ|1)8m{^g7HF{ERyq)K}BloT5 zJjAD{0U#`}S4Qxd!iq>E(X+xkC&g@X4VpwuK{2F-B)>S?o4thRo*PaBd#Sl+s{T-s z`HtcimPP;0X>FGZp{}_>=wmQ%?1TQ>@}NFo>in>oY0i3=MgjYQ-q~$j=2;q>6 zR?PNFz85isw!)ucKMBQF+kq|AR>uYa2S-KXUD}-vYtctK&9lTIX+jnMQb*6`v3)3t zDb&z=N$BejgY=-Ro#j1J>wc;F5~fIi=*$c4d=A>ZPFvN1k&~o8=ZVcUE>6|6+M&VkzOM*rw9Vhy z>a{Ohg0zT;`4Er2kg>}YZD29(^S9Ui8`v$(L{!Ma6c!06?aZiCDLTUR?DsiI@Oa+O zH{poOZqY%kfwxAovG&AC_H*hB{DKCGp^CL{Z9ZGpnST6g{iOu8z*Vz9Nm`l3x^+(I8l_9`s2g z>0U+d&Jz69*iEXt7AM?S?SC1T&L}52wG=tz9;@Gc!OR27x6dbrXLksuruvC0zn0;$ z<;PGOX6BL2-|bylzYLCY_1v=1u&262BVOc{O)A@PoYBoycr3nBuPoMJPeTNZt&@G z_NVnY;;CY)_>h9^l`#uNFMs(vF>n6{Ho&X3^S1Nzl{;{ zH8-~TsyO;Mqny@+|16FED^hxPKX_~CkOWV~p=$-qQzWhm%~k`x4RVg!cJCY72!D;+ zX=mDepjm&u=A?CR*j)N|_*gy^~KYeoU3J=&m`*pQ6wOGN6M zNOImHVVfjF`mI_>FqI$X_YVeoZ% z49Q^M+C708Ap$0CNkLm8rg68E$>%6Q>@X2l%omYmfliyysonONG|FwkZ54x@9(b4V zA8h^KVy&X5T;WRrtSdQ6sECAKO7`Vbg|%L2jE%nANXOB+unrL|DH_n!sE>@`uKh{s za5S)7*^*_Kccu`*vJ@$?e#u$|aZJfU5Z?am4Cynlb=BU&6!>4| zLI!CuXFg15OXInvi z^PH!$2^?yqG>~YNXOan{!pp57^Sb!9wIiiRuvq3NM9D6Ke^ic;Mxb|^k?xH8eCltHh6<`X<-YAb;0!y8Hoo+>T-mQ-RdPl6+i@J%WWJ^> z7?;g}fG7uWyZ(CQ;k;RyP^}X1+)To^Rm2PmLPLzLu6R1>+)1}>b-MugU`M3*RAgJ8!J+B$bIs6c z-cmja4-M7{5v-a`+1LH}U8;!>1uPVbX%$PqUJ1cp=EzrFkzo3xCaVWiG=!Zm?;Db+!X5}*9DqKh-EABn?^0X15bs{d) zMuR=sQ3SC}>aY|>M6Z@C}j`*JK|5q`xfh<->qd%}1nkx(yuA9Ny7dKUy zMyC?Z=R(Dw@WRqWQJwsv*ueJV-82&{#crjCHw%H0tBX?K#QIgkOuf;=<|QYR7UKkb zE+LYG7P}RWim~!U++`=F2F|$QMKz?!9!Il*F;&&N<}vZ z9zFakbj;7lAahZCvb_CSsy7rGAWr3EG*V)EUU2qvxYYjv-Oc1#B^r=Y~0z}r4&i4lE;vb1hNm;XB#8%{+DYb1K>m(Fu?i4OJDWMK@-JG zS7wR*Bs+w(6*JY6q?;~-OVx7!*!*MVUhEQ}cvN)k-?8{;y^{X|w#ITd>xIQ_f7F0c zT;UJY=w`D1UiR|XglP>A~X2~wEJZv7s;IQF-^g81)Y*a`0-y^<0By8n5WPAKfQxBxk}=MpTN z{2d4MV+H=-Dq?`S98YhJwzY#KmLB2|Bdl!s0519*D*DUH<2AZxfD0jv9??wBV8huyaheKKV%UKyVJ8u>MVnh=nChp5dx=!=$rHjrtn^|MqXF z)c`io9imFcAT}ST;sE8!wxlP(a}t;lrbBAO^+VW)rr$HXBu%di?fFR)VvkAlI*Ufp z_M~x_c@KSVT#pyCiCkciKu7dk18G~idiFY+ihll$^Ju@afHI17PLRz|Nhs{MVsHqh=@m$SbI%`xi(l=GYY zX(+*Wj?(jl)*`+Q%GQ^H{F1BsZZ1ezStbWtTJNJ3lTSGVjgc%&6eNjB(kZo@_RH8h zCzg-4RT$F4X8CnsRva!m$=AYS@gB@;)8Y=N1SCRC37;JX(&JhWuP)joy@a^bguU2{ zDtu--Nw1*a*4v&Gp60SR)Bp>#i=lH%)}->9)q zhznUD_`}s4IFDbWlM1o}A2X&6d?Ui7_40o#x(R}CA%FH*+I&(DNbNQDhI}q!@ z4PfXTX_!7)_FoJ`{NGGK?lt^%x@pYX`FwB1N;xDIp(ebkhN_YP#uu<7TKBezS-G|| zOS$_q*0OUZzO*t_x51_V4N5g%*0d#gt=~@o7bTiNY0q>ztDx67U2Yb1dk`ZljW(lE&>b)}L8B z?ea%?C%)!4Cda5%3UPiLv{EWrvsqJWhMz1{he#o8 zINYFY0S$^ikJyA!fwPH`9iploA!pxT;0Q1)8aR`9RxC9d8wSsTv~k+y5)No5^L1Tl z-g-(=wK04pbx)V3fCAmmOg9Q9%VxZ(H5(*b|GowbD#yy}c}Saaq)%kW9Mh@>ncYXu z?@V=mxcYodq7=ElM>64SW0FWD2MI&leiYI1$ipI>gk03T+^|A8LVUPDqBhC(-C)Ks z>!$mwfjgJ}JrTE%d29NfOgPJuS)yumxXXOf=<;ll-*RPbVkfkqI^LetBz2lV`9qW)u;#q_xNEM(n zO-|ux=9CVHMyhiJ9kYaymR5V>F79Ms!M35>4S>iqosb07YCx4Fac=C3QWBQ=+4v(! zkm25Rw-*DQoHqk8#oX)E$W2CzEL?Ka_fmgaVD>;gcj(SZ#9WQ^HjjC zi}37GpK68o<1}Z03v77l_H$=%w1E?g^#PhlvJo{}eK|bsI1*665}Xx?B`Qj_R7{CO zh4iJSb?1acL6H47#`e2ghS&*)F2>s3(82gPo;`p>UB_ot&hh>FfUQ)>gUz=O()ozD{vZDa3i)1ugS-_ zx*4DcftM2)@!Z7bPJJKw5spr6dc^OQ#6}^0r zBGtBSu4v*_i}kvRuaj0~$2q*(Wm_#Z{sbQZlx$HL`b#{?TD^k!?9OJTQ&WV)wkGhu z!Ph)*Y|6|{VU{wIKLcEAjkJaZU|pT(C6bLzqK4TcVx{SnOK4yQUN%d@@w9A=>dfE6 zCZ5ekZt+7COhjfA=JxXGg#?7mWj*jSJNq_%`)1=wHcLJft>K@@S1GBzpovZVrqr~_ zg54e)qlY-3qw}K=KtH7tPw`Av&*Aw@bUUFJ&<-*Ri!e89%i9E&7ZHs$mT%-k$xde} zJFw~E3Q08?m%uBIwITdU5aP^A8-O5$WhCSj;mfJeUjos%P$wDIK z0YQ*k?ybojBwZ0Ak9w5u8n5c_e=XC0L0+pEMXc*cM=Kzq+pGsuLdIiZYSD0ubA1-` zXSAixo)T$`t?ey?2OU(Wim7Ub#^xyC0M=<_l>~s{%#WmRFJ|R-rr@G?h-3kW6b@@P zpq7SPGn%M6o!tce@=sNy;D2@(rU-!C`RP~$Cr&@tm zUV-_hm*fzc!@{V<|NJ^}UFOl<8FHE%OYD*78?#|yqpPNFqxE)|CO5mWv7wFG*{os2@AECOEZgRrTH-=Wfa^nwBLniSO#jSK7*a&va zG|m%s53SFR_Mr4fkCPgR9p2@|B)Jg+tf0z|z8Lu$VviwJ*}Em*oYGbqO&=tsx?9Y# z>iR#+29vl(U|VVN9>q@O@6BSTYB#gWm+*eQ?&iV(c+9Bl%fJD%8CF!obOJ3KwS7ZC zfuA0;=U*sQtcZ<-%`_hIpA&50Se)rK=C*%DIPv9B1?_wU-#ikG5PB=%oft>`lwn5* zZBFT?#PYDZsj=ie=zp9;!IH@)mH*c`a*pf4yW7-^-oUp7;X5`n&awA(i`r~Ld$iolWxAQN?}&eUUK&QGonW1m=R~xM9^+i(4pvhu^RY;LfCqHHXp-P&O=|qEIp)q zL|NL}JSlm|i^xIHx})hoU_a$YaMwDfG5%9Kpg+>0s;q2YgqyU(bWg&CvQq`0`7T3e z%r1mQc6k1I6j&*7N?_{Tv~1|=uKSo43KF7Chid&oFEHk%K~C!dzt29wxL}||X0`Z< zY9q%hqx{sRw?Ih4td!caBbip}%!`4rz&ct)71^wA`Mwik6wil*#ps!Kskjqjpg_o% zL85PNu)?3!bqW=9+9Z&HX`l;9x2Zn&t8&`!*8+$PKZaR96(q8ntYBnsE7tO$2per` zue#gt0CSP2BiZBKQX9`-WF2m#JDrP1`QoS8jmHozyQo4?^;T?5knu*p6H!K8D&u8rp3Pk^;cZ5t2KYtG z^&SSv%aepwNwFjUW0D#dpnw$MJxDPq`w~A(mUmG&fec!+icXEM-?7unhziB2VXRYN z7J21Fhbc;@zBpsO>86WzvExT`4P&LQ=NsYK3f}}R zd^r@wS^t~ucFC>N;F02mvLoexMwopIi)fnulQ!`HH+C~0zU|NkqK8lK3+ZC6Gaq%( zOo;BuwwQv**^ThmRunu43-}6}+Grt$aZo~=9ADCP81J<_=#s+RGahji^8 z%4MKX7FjLNW*@BuzIFfF%bn&%;_%IH5<_r(KBbvio&)m-#`Gl+@=Aco>mvqeaSon3 z7&Eo~z4u7ICKM1OD_^V70b@qA5%>D-sJYy($~#o8=pUCPhPx2)CV%I@im=f{t{avz zHDAzWen3T!9URQe$}obMFj>P_U8J4Tb}~%RLt)PaV~%mw-gbG zA5JtzKt5RW&Tfu9_X=N{0I72Lt+Ko(#3BSjv*Tf%{bHUGGOzra)yl4`cLJ? z<&9C+wY&)`>&<47qJa6BC}3&@ZonhJcVJ!Bt}bg!=ePc){)rp$&6oXaQhlFwo_-=9 z8=F3oJ`s{H$A<*_P&bcY{sNNbMIZrIg*>=XA;j$j{ zOa;EzCR`zxw`M#8AeYjHYtLc8DoJWsRM}cPx>7gW9toEQK2$+Ef7e=x`j1dd(DoS_ zQJW5G{pT)TSpVzKTnlAB;Wz#rP${FzD7|mN2kkOT&c)qkE}3sfklxNuwfdox5DXfb zx!^neYix#u74&^N5Urm}vHc+gqz}jegfC!Q&P=w3XjXtfC$rd;0 z-ARhvv*sOpHIF+xEUJ~lHZ+@={Q= zh)k+wpo};WUy@7Xfc%Isl*Gomymj$MqtCi@+g2iSLTCWjT|m{mG@|LLN;q8F7H;c7 ztA*rvdCeJOR3};=m43IE3jH05Ra9)om-f}51;v+=61(0il(EVUBwj@A_UdgqGBW4YF~r3rU}oTBZ94d$ zqB6i#MI@{eWGT(l6KV|ZK-rMr*27F!iuAb!K2!_KEIj)d+KaUi+iXGBOI7{1E~}fG zqy&>tfPQ?}g`m7?pRfk5+(y(eDXUK#vE)ySI|3irr|fTTUHQQ}%`2KVy31>; zx0-CWAZR9v z5>hO~qvS*Dy~GExUy{Y2?Lw4vg(ll5I>zic^=m?!LtPK1P@GtVO zD%#jHX$$1icNawM_Xzjl-}K%AUVM*ojD_j$tX4Ss;YJtK9ps;^k6)#E=>cqD`#r8NoW*vX|2fKTv4wQsJ3 zw?!8taNbP~b>N%Om&eN zmbDDO_f8GDEmFqcKZ3^Pph!pL5JGc)6ju{P&nFb}wj6;}*!Hu~uIpGh!l`O!_1mlG zVRBi9cmElBGeEHLyV1JWcstp-a$bX_-MPBx{L&?eNRQCz+rE`f zR<9Fh-%m2G?&bVoVc`)=b1|0EIjJqS@u7VlRw@hipc!_h00TG{>*|!bdRUveV+#4_ z#|mr#F?!3e?}TN$X?VsXg4fBgWA|eb7?95Q2q9*o#NOk57H_VSy{2Bt8+G zE7rQNDManT_%L&3S8jpNYHiu>*nyATMIjtI*pggjoGj~+(`JExE)iD3#=cOI6^Aw( zxYoT18*^UhhW}W#x+Qd0tO3*J@b+urw?VojMKyXTksKqQdYLUnSGAb13NdC7VH9jcHxxAdZ{<<{jjrZCrde zFHTm;k!g|9;~qSwd^m=z!yW6D7)-#va{#W1ZC@4&I&g#$n>b~I?Pfz?K?LxPze9Eg z{Dpf9?8e^^_qE$WY%XGiIo>&}7Pb*oz9p^L>a|9R1)EvL(^*5QBi)n+mUA*AG7x|` zi~4uJ&%96{dg~7hvL&gDu%Qb$U4h8QwsHy8!iskwFO$!o{qv!Bds5jvOK_>+z>18z zzIv%EQywP>6vQ(#3D(UZ4o4d~C3AF3>+r(c=K$qni@u`8AVUfS1I-+ad;|lpa&YL2 zk@N}j50Hd2-k1XXE4U#Ikx8ZlN6t)G%ZCO&ONU=ED8bu?znQj(xU=+AOF4Oabn2NG z7ly4sk}e2SqABnpZ45pL_Fo(*WBb9h(SA&}Eqs20U~Xs-EMt-Vu*48mpIcU7{?P|& zF&D*Lf(uANwZch>^U`eH-O$Nf%3KoS&@;E;=NC_Nt$gc98Cs{QhUd=KPL8bFyB;WM z{x>dm;p*{K3P1**-rb`#fs+yXk}biw0}@h^_H_w$+c@v(PE`tx!jXzZ=*A^XL}q^? zQ&0+vh#+{e{EPZmIAhJPUeS<;L8$KotnAYIIvng9NOEF)PXLH0@_YdRFvJ#t)tWGW z@ruy!QVyi^QD-&6c4d5$^2B`NwS>K|D_^GG3W6Ilx zX*>90I3FDr!my09KEjr~#zu8@&OQN}G34i3a`hp6D>`!dBG-U*mGP@2el;XpxoY2z zaRi?<*G6R8L3vc)JDU8T0bQZM~>sdhNtg6(194&5tTPk@T$(JR)>g3f;B2i*%ln^;X`eRc~@v z@tiY%3tl4$li{cr@4+MT4NO$$D2)$$`adW{G!El_VXJcn9^+sghho@bv98K|)h})W9$Sj=0isjNw%^$5-A;#K<|DcHA^i zU%!p2Fc9wUd`0si80pm!W_#FEy~LM*)bG*Q4wbAMV9|-VhO{GMP2HyHp5^_ScF0{) z%lx2F?Pvhb3(4nJ!&k_i>Mv@nN)DPn4XpbD;rU1s^WjS!E*KO*8YSqTs{o7O=w#aO z{o!?B&OW{c_iY+~LhPhRHYS;gG-Nsa3z;l-i!BQ#Pm+b#(*h(Z$*`eo+zYP`i&6p0 z{AO)Jx?R_0uzda--tr05jLDX9Kd5F>n6i2{EtcpToq;nX!-V3Q1>qZH?r(7^_9)y%@YkS+IvIRkKIKA+WRif`6@ zE=00(stM37-G1}2U5cH}EFFfXlF-O66jrc06j>CaN7aIO zv+->E8aKdpvb$R2REp%2=ZkPFJ50A21%}ej0S*hC>ai z0*5<#b}dNun+)SiY*0C(v;?fClbo*j!tUXRZm`W_Z-XQGwQ{=>I4dyw#}-##(_~V9?bwC7P|(>YB5p-0a5{QCf1$ zkb5WKULcw2D1yKrBB?4>(%8||d4C2mz=Km*;ai&Mv_gxOh4217N2QD@;F9cHT*4~2 zqtgy3{k%&}P?OKfHh+*Y1a2JuyeLj@nN#|REx3Snt_oyR=DcFNCBK%reI}!4r4ZAT zAL2|H(}BW?G;kE>-r>vXNG65oka8$|`xsu+Z@Mzot6zj(Uw4k*>{)W_7r6(pSM1q4 zES#@zrU3*q?Q*yBlw3{5sGZuqefoq{dX@0d2Y5jkHaJ_9*vp(TDP-({{2(meVS=(A+pDIh(#cc5Zqz51RJB- z1_k^AmP677AH-h~kuqbNs(v3n!g_OX3%dN@ihTC#Zgsyd6ZRHG40uffEW7^z3juEsLZaP&^J? zEUlw@WyHwiza^;Rdf8Ie!Bw9d71pk>qNpb-yK2%I3MyODAf9!v+(x+ywDawz>7~=j z^E;D3qiT;_t9NXU5;RNLUlFwen9-$bNY{iN#}iz;9YBBfG<8{w2Gd!t%_v!m*}`N^ zY_KW-duvWJm=Kt@I#;4F2|FgY42d4PWjzSdd{n;W@D{j~Gl(!rl9qaiX4)nbz z%Vtmg>150U7_05DQxvr@e;~0w=NVwSQa}rCvGi5k{Mp)(FHTdTH;#!y1UEX|bYn@` zEmX5yNde&T_nI!utHa>SqVMm|PI;6t=Lf^!ohl{~GU&=a0gbIe<=!q5-Dy$Z>OcdnSAw?sb>|2{gWI{B+UZoCD+`ottP#-DBPZ)Pq;vNT z6i+umf`m-i6Nl0cxE76O+HY14H)~{}X_}Zo0by``Ec;3Co-*9f^jOdbCD4+XL;U~K*w@s#o>|1S=Nltk7VH+&05TOreSeyYbXeymC2P& zPv!D%iw|+883pnVtE>ftQ$9Vp2l3%4rI44$`T+JU*$4^KO+BfQa*UG>6iOWOwv%yr zztmkk?}(n{1`p>VVm=Obt%={7Pkk4R#^q+lb=;;Q1^HRK?~4fx>g+>;F3rDz2pul) z29|*c(@Y9qddiI~7F%;A$J_n#d5VB)H5BZ(XDz6Ba*iIGPXVd|ppSLp(HZ|LnrH$f z{p|Zgnw}Rkw3>=tbywZG?ZYv4l2J_Xh}OTxnz0pI_MR;TBR;u*yL^o3G2kY7uLMwM zTM#qzPU6@k$Iutyi!gQuCzrl1v9#Zge2O+pX>#zlB z)0w@^YW<<8v3z!mbS=J1pr3cRWF~qfrpa|+n(U9!z;KX2yavDS&#g}=7%{95Ot&;_ z%#Q#Wau3SXXa8dw!~j9sQ3)^^$1~X^&({K~mWzLJ3?zqFCu2>dRqGdQAA^3eP5Rgd zDbf$*q8z~C7pZN)VQY$?tpOt?6!-GQzYx3V!qr<4^Q!zE)XVT@pGSK8{SXzz5**97 zSCpwbEy!VG?*3D5;Mg^BW;5oBx$t@N%^qpw0276W*7Wp2_qm!$B%ux^67l@LGJ~=n zU(v`{duSks-{9)6?-Mke**=K700wdl>4M1?vxLA(DSvU{Gj$`V0se6>lTqmc+SnQ9d;cs*CD1&s8|LQA_xfTADeY zZKpiU&ZP#nlwQ7OHHw&*WBb&gTTGk1h zto`+PIR_F*5Xr#VyCqW9ODGy_CfZeG&|s-A_J{gI3%RJgGJOVfr0?!g^lq)XsXua9 z?i5YVlO!@i>iDf)Sa!|C)maAK_yt#v$sMx3j%*rhKaF^cQV(MEU0L$wTauATvB`Lo z(>jB_kVpkkhmNFg~^Gq0Pq=Eri@Y)>Y7tWl8qBy{_tY_lTaUa zP*afOHy0cy47VZ{H6rD!Qz92y#<7$Uofo4=Y?uZ56XyI_5RwDJMpoF(7c=aBE*igpJNcLP2I% zkw`pV^Io+kni$g2=DQ|ra%Lm$j4XxD;sB7Z)a65gMX}{@Yeu!wn&8!MMDR+`v&Aua z1)0>eu$P=7OQ$kSXNjr06Ktk%@R!Hz%brH%gkjD2Y>EpLEKG*EY>kI9x)GHZLKgb4 z<9Vm|R_<3~(q(ahU_JK?WXt-7EdXPNXXARzNZpz?)5yQCx-i_yMPYEr4ih*M$L3;$7aw&Zhr;T3>M8=CU%)4I0!l{Wb;_1tHTTn`cX`bIVN|U>Qf$?TjGcvHeqLe^m zkWPWofH6N?M8?kVI@km2CD51|62eKm056vtj#J`zg3<9Gb%T?IIlnMh{EEvdEN~SU zhF{6yYc}uKGpG!=LWDMdmkI@-_ONS6D%)RA<71tZT{Yr0L9I|=X&5I+vZ0IsI+Asp z7p6*%FU>nEn*hSQG%r5Am^pu47@>GU)rA*hRN{H2%zbi{0(>ypZ&~(7>!D|3j(IG9$u51&_Z526%Vn^^pyfyflXs=R4BAR8=2Bjp9 zG6CG1X{hD&dd&G9;@eN2WH4UxbNfk-XdI-hukuaL2VOtc*qm>o!ApwO5cEEt$nn*Y zl(;hch37P{uwgB>kONtJ{Ic(Mui=qJ16rx;oGd|;`0Zt7`0BT(KPY<*Hh-3CuPUmX z#r%6Xhp+)a8i+L?aT1%*h;^X6IrQ!eS4IQ|bK#HwJ*BhX(glA5#;!wP z&|mGap|u?gueW9Vty$_d<1opxCNs!o-z zqnh2-x~QCnH&NZ;ZHTqlB7)EUzmc1J^e5?u>YdRK;)Y)d3dR3UB=w0e+N?3kAbPYf zJzxs!sgAL%LmHl_M|>Kkmrn1BPuBngYEm3v&q$eJ1LHqMU@r;Ek}89Yg1cZqnZP5s zWle0JZj~?a*gVZD0xFZ%l54HOeQ+f_aqUX$%1r)u3spWCdoc`fuxi2U;*I=1AN-5m zD;nSx!l%GQ$M2&^-rD~7?omF1+4r)3c&2cnEP}^8#gb$+-dQVkH}ily3R~2^EBbI! ze00Tjm$)?bS`WA z!B>Y64eOON|L2F_md7GA(SCD50e2PH(V{5buDLBieVl z;D#HVlmCSonXX|eXf6ve%(Jcx!lpIbRq64j!5P8QVF&}b9jF11y8o~WuDp-U!9FW;0q(lGzcq9{yO z@L5d;VJjePKk$2e+jCOb0ayoA6V4+M3cPB;+K+tgALDbQi}W(=w>M)f+h z6a)CfVUq8T;6K0Q5g_R#E&vy%A?5K1E~Fc{uHztQmy!(_elgZ7ml%^7D(-1SY4OAK zv)&>&TrK7K*`&Aa2Luap)b?ZY>45@U0Nl zLhkMHE-qu&WS1}JTn9lTF4Zg`m?v@d8}uGkD058`beqVte15{ zuZXO@?+ajVmnH>D0U{HADf zxGregi3Vy~XK%yV<$tXG&8Alr?09N;D&ezDonYcb9(i1}e5wyzwaLrSHZr&y{hig= zGMF(iS2S7}7&r@iNL``8Zvf|^0fjUj%~ODV>gjKX0>eRtzzRVg>6EUtA|G83rQ0UkNd@aJ_MVvzgfhHC3&{%Lq*45y!;HgV7&z(kXX8GtNu> zVo~&^|Lz)Bu;)YtqGfMs zh!4_WOV8wEeN2iop6kwvS!w321xPVv&&S=Ha1r74?y95RDmFZj8tzzcoRSE@I!HC1 z?J4>^S-f)E(#qW~DZBzB-{YS`GNYcGWnz``GNmC>mxkRZ2Z5A764uBZ(y~!rKh;;| zXN=Ko#b2?og7v{Jc5o%W!>GOD?KSXC)MH%-6OH8FqQ#_T;Ikn;cV z_aM9+IR2My6}n2`mz2>YUUPS>ez$uY92%p*ncXxS+VDI!6_;V5SV?r=#o1pzH{F^T z#mbBCa@ug$9iMs@&lxG~ykrTFmPz-##@yP+q-gjhWugB=RQayC71nqQCPIY}gl1$p zZgTBL{-nVEgju>=($=$+$pv1zkO;dj#_k5DTDmSvB>z_zn(^-DVplWpR<>~#$9@!c zg5>=HG;~8^F=1vH<-*MMeEvs*1~b+>9_X00zsSqLysViAZ-M@<1ltm>&fK8#@wJDZ z?+{Q0vHb?$T{pBYT$w7QA~OLU-ugWqhU_?U)HbGXJ7aK<6k>9#_y&)VMsZ6Bcp&ml zDQwqaZ9wj4=1G%!o&1g*gdTTly%yNjlneL@kJQzh?_n&5g1RPXmQbI!$=^kOHrZT3 z_qC(FKjDR6!;f7)&kgH;viZ2~8=mgrfE7A3n5j)j+8lNLu-V-rfxYCrVS7eH1TkJY z5nH>KzU>6&xy<%R5RAAs!ZMA|lyQ85VkS1@Ia7c|ZYuP-8QNT6xDz~5&Y@g_$Gtn4 zp11)J6E{fD#Plnj-Te_m^&pH=q{}=OV$s`MWLre2O)7hJl`{_kr8rv0(4*j+wK`;y zx2mQ>QnBRI=oM~Ti9bdO01Y!1@3G1GO5Ppw{J)6L%QcrVp5jb@b80ciu#Gg@`~Z>q z)w{L~9N!;I>I)NPWoX?bW}|W;s+XHowA@9f<^T}hdGJNhES#)u9qGCtr8(A*~HKr zcUl7=4AqEDc{Q}k@NT@lg=FZg)gFg{dF9}dC$9#t{KsoX2hz|Kfh9^DD77Qzqu^G)=JQL{?{5Y(kxt#CTYAOd{hE+O35pSBO|2x8VL~}bKOHk_{piJvla{Janfbb;f42ygcPfCW50<7 z1U{=|YNGG0x)g~x*ue-(?^1y-(aS>!txa4nK?kI)QB*5OsUT zeLN}6`xV4&KikWF%Z$fh`RNVX8TKZv;%UR!VDg>f7%f}8+|s%@TfUF3uP!(!%WC=$ zhS|71;N}pDlC1nmw!Yq>9uVHm5Rum9ppP9w1K8xc;!Gh>f$8I>y2wj<5#S&DfzpznR&1Bkf{=()RS zB?Li+x=&f+&Si7_b45NHq1GRaujjNT7BlgtNZojw?XH_f{yel*zEB)W=(d}oMJomq zYgu%VVQUam*iabOn=ork?1{u&nuS9sdQ)oB3wQ*GG375P5({(1s;hf2M7i$HZrW(gdi25)pR3V~2h3ZPn(yfR{Ar`51{t;tD^2ZBk0+jhUZrv|9=-b)YZ7!TgV`F|MG~&54!%p z=cC|aM!5LLj3~@3=9Q@~kQw491^A@#9swyUnrr(0=1l{nCsAyN5WJIH;a6ujN(CZt z)g+rTvEPbFSv^O+)Cw0n$Xy5wKw9vxWK7H1OLC~hRx*QkTw!ix72KYTyZC6auvA&yb=BdX4hz8w()=mp0na4WE^b}0bcw!)9@-*)fVks=n(8j zA_Nxi9Ts@)^|nAeTTYhK{mZbqa;OnDOBKSvz>*qaC)0S#+IuK6z+<%_*d%m|{jg%D zksaH$eNF3J7ux^Ht;Gvpz{wHBsuF{3oMj9#n|XKSx(vk()%Zr;2lpsGJ_0?4oU0#b zcbMjS09x#I1(`c$4`Vf|9B4qI?Dq#_A7NxiF>1 z9etczYp>LY@keWNT^^C%^)w%?ZUMEvOF|<_fLC}tVql>8X2`f5w;%cCYZxAH5oG{@ zG!!dEphttSs(%qDJtR+C;VU*g;}KR= zb|Pl;Qq2OdlNx>m_=H)l*xsNTingjP63|;)pB@2!#`-n)?1Rpvr`JPvp`trKXson6 zfPZG@W@J8|@FE2hT%J!Qk53;z!Xf$!&Qw#~b%p|$Xk`zU1`gj3&tBhJaZi593#G!9 zNuqQ4W0IfCt=goDN`(9>uK&VSb4bDq?S@`5YS4QLsY5hX(3-w z$UT@J%G+`sZsqC7Kb}g!W%G4>xTS~PGK3#Sh{}L~1E=aU3~=>ggt8dd{D?=|*i69% zIb`Btq%KMy9#=cQve)3;cS0-Uqof}auTn1~B!_ly4Uuj(f$YxStc%lE&yuIY9k*Nn zGl)#D&(oYaqcLBrWvMlgDbXoss~Ajqz-aH~>tUMg!oym!VGrhq!K>XjxUyEI5wH+D z?C!9=GyuBJO+7JC=U@*L(pyzlS#*~7@jpYi_zFBpJJg8%zx7A4#cUwrA^mll!f#dw zvlOnHK5|J-ib_qzcBO+1LRb8`{mw&&xha9XT=S1UdE;`RrM&<_3 zour#oDzf_INlDcS??18*Fh|Fr!JZ6%k_(GV!dSzmqBFj927yaF=-|~;6!#w%N()ml z2+y<5rnFarplni#j7@5)WSRi_l|_pw#bIz+Vhzi<@j@X6TnLvPsQ)kv=RNjtbQes` z0qgLADTh*SttFSu77xY>8-RoD;)+pZ3Zl$<;dqm|r#qw5HID{beB{mMKw`v=*pnASt*uI^sH#tVS=ru7qi8?YzCw1T6rJOjSy6_b9H4*^z8 zb0_GvJ*VVFaL*}sUo{PY+_*0TtiNO)wTo<{x5PL+2#s5{kV3GwnLJyWbc_&cr)}G` zz546<8&FzZ(ud*1p$Jz%1rYAtDer>G=RbFCxki~rcJ9U_KCHR#7w^mTd|ykB`k}pE zY`Xj%Y$ZJXUQ>__4Ml;Tmi2^y9IpHwrI<>Cc+fP`)c&&betCJn(@OM@VJYSOZ;dkG zVAzKBLUYblG<|0a{?H;>cXPf(pSm0Fc)G&{s}~?M)9CNrv;C~oxPHGB&+rxCtyp<9 zdo$Lu7Tg-8+oX4ECkFIMiX9~3iBrJRE2)JQ+Y`Kma; zEq9<2+TBaYcf9&?Z3S`gjyJ=-%e=Ph9=z>sWpI))t{{O2tMu7~S!tfIZ1g>HA>l#} zB~ug+LNY?55`|hN*~&WuD1FZ>Rrh^h8%Bncs?4D}FFm&BIBoE&- z?2jE^@S5MOA|TLewgX8on_GWYSM}48tWFo&|52q!0%ye~)263Dgmig-&x@`97z>;^ zBf3ev=y9x+BlZix28P2{1`6B;!IWj~n5J1(g;oH|lLWjO%r3*K*jj{g`+ZIC zLu!>7(wk(9^D#02%*ULCcT}~g{!7K?Voxz7HZu~Lu9@3Jzi|C9Zmt}%$U`y(ZzzR} z6&Ndhj|S{x@x0KHf<+@y(y^84utmprskLg%|ERYw09W@rODw(!Z`zRJ|A`CN=$TOK zR%z1rDDfFJcA*8DPj^_o8Kp*;PAVy()Nz{sLe|n&} zyBUK+AWmEv`vy31%DC@AC4{4^v@G>dnqFN4a87B?!A1jbKLT$1e#Y9pmNX<2Lnaz@ z0xOtv)ENV_r^yI5sbtE0nMN)>7EEnHB*+6eI#4wFQ3Sd(1X0>iD=Mcv8@kw1fBR<`l}@ z!A~Lri2OB3Szcm_eF#J2DCy&%^tH9eT$57bDhxlJ_k|5LY>d4Q;1sKm>d7?Q3oA>? znQiIMzNpH|8^jrH8m948#^)Trh38@Ku^o5B$F=~#kQ`#T6XZ)FwpnK7taZ|sCgIIx z>Rmaw`r3W3Ld$lwB32a^J2^Ve86_nm#>r~guf`tiy<0n>CL(~02U^*mG+t21*io6E zvlH7L&iVP(GnV0FY>NFOV*>&lZG|?_;A0fp!}8R3nPJB&@B;j3K0c-KE#3A2foD$S z(QmZ#VHmSN0o`opXBl{@&f$kSCJ;MGfEhUXx>ylu?AWa-fbsr8cEfr)mx8x9wx5>R zDT(g`HZb6S=^xcQjj(f{S(042MQ__3e0mA{}=KgC7$8O5iX*3pPZkAUz^fcG5tP*VAHlRiL)6q!IG4XV{8O*P$Tj z9oU8VmP{#QsPxCYKq6`Yjw5-5?A(I1VPt+EJeSnq<2ZX^@d|X`2x^sZl%J7^7~NqMi(bf8>0U=*1BuWe0{*@!q*tSg3D z{%Cm)0JfdH!0Q{yqlyj!VJt^@`~pk-;#|P*Y^Voxh7sbK6+)Bcdn0@{5Aw^5q&`2e z%)Tzc1<{h*|8n{%nSqtzVpe32MfmmiSS5M>bJfNoa(P~u{36$U?Q1j5`y_RKZ7I*5 ze&mtAATku|u=J#BLtL!{7_$9l&5B6o+2kt8RmW)M3t)1hH`gX8GY$U_Qsf!sMD&+- z_uHoF^O|q?@knmB4ML9hDp>T~xdwW{oV#7-i+`Yr37a{FAX#nSP`mkx$h?LsE9Ctv zY2N;d#J{R;If)IcP|rrzxnKGV7~0dLUl`Q=KfLQ0Rmy>2;{O*a{TJ7K#Iar}EmenE zcZ}4T(7n%!70^q^AA}Q?H3Q4^`1SDBF2=~ zE^CV!>!XX;t)n5OqI8sR#wR9`%QBz6!GC4)Vo>#(RRd>0rv|D#MD;{TITYb2tR$kX zy%{W@4jwl)FCNP?$=LT^P85&ea0ar&sHG$r4R2w4w<+<_at);NuQpGG3E)m(W@&CQ zN%~wt2sxk9BoaprP3Ui6uk3$-snL&97`bNP zWohg#aMd6;kb`7F1dLj{gr1M2hddgMPjPbrDDFs0=5@PCd}Y@F)*ORZN&(YEQom-p z1*?vqoB+C8&IKe<_K}}LL@tFl`oN#n62XCa{>aSfc!`zIk>$y}j21waWbvTI>Bh-| z>R03z`;6WDjUHeC!fX1fWJn=ZP{!8&cXK`ihI_S6#p^(nv>VA?MefH+#JlEz5)ZrE zw9HzJP=z8pkusHuqRi%7U>&QGjeXR6c4_Dy9P27#qP#7XiIJnm0rU8hj>)10$IxbI zxS?Ok7e8YO;obB`ejBmWy|Pe~rm;}|>Z)Xt()3i!&HZ@%PbJ*(oNkv8C{toumlY6K zo(@h!l>Sv92KTn$=i7t%PHt62t_Ro8vU5{AS!b$wXhx4=+*O0*td-RJ5-8BJ7k(Jx z#&1WeBuiU)U8;`?8J2S(tX83P#4_;;sHyNQJ8nn994S^;x83F+ zekI_LB6DQ|hFv;(8#hfYhEdA4M$?@S17p@V<}vB*&$yOVyH*_lN96s19)cQzf0a!i z&0qH$R?6a`AVgfgI=%R`q(IF{=7S+$zG#aS1#kX>!L?{8!?zb>t_lvwL+?<|aVMWy zhmamxEWpOX{*L9T6-&CJm;o3*G=Zir)BbpXWLzVh$^vbum|<6t<}zQ+m9I3Q;X|U} zw%bS*+?hKm5VUx3Ze+dEWMA^1%ITcb0CK>n^ye zgb*ib+sUCO{Djse7?j#EMnrK_9FA?ODGdh%29W2J@NGA2z#nO5Pz%I+lXsqPal-Pqdx{dgkiN3fF!s}4c9NF zZ3}lNp5u4PgLS-dbS2Oiq3pWiuen)Bcr$J1Wwc#h_`D>8p>u-si+C2&bs6;lqexo{ znr|$kuX~Hbmj109q2-_Ya!${L3z(($OT#G;ZZc^Q(0FSf8(@LZX|2=k+D!1B*g7vh zh9D|1bQwxPfuYm``3rWS6!JyVVgP6O*Q1QlWGHXRR{ z30&j16!Y?^KbCbHZ!VeD&m~(c(S+K|sX-p)(EU`#p%#Wg$lY6k}p^v5cm zJf7P@iI}i1m;yr)!>P?io^#18fB-34f<-WKH6?HWGTeS80!{^_eQ)EMkd=I<<0VGp z4tr1rL3aS(l#Mz7tx&o~#s>l9js2Y9aXv=MbyjbA^oVPM3spgOeK%5o|1ULWi4A+p z3b^*L6j7ib|67kl00pvc?rA&8y1e|>g3aIWbS-USpkaYs6R}VK($WsmW!!&Y1qPBK zVZ&5v{hT^~hGmaM)pXUZPlVQ`!A%Rm$4D|u{Aaz!`nNZ*atxhf4261f*IIm-lvt4FEe89TJ9O_`w%tf&C9BUOI9i zEXALsGTdX?v!IFEevi(=(fYsC`quvLw*QtDY?V<{S<52mc>;RJG{R1XvJ4^Ws9)y? zUJ`luA)Rnjux>~&^0OSxc>CR25>NqDL-3C&MWF=EaS$ZIukCnG$u##_M&e$fjIYCD z8smI6Goo7M_{Tm|>wxmLl^;nGjcA@6$nL)9bps;|TF#8xvZgB*ljzRZSzFk4m5nc( zQ9_Jjnu=Ga#?Dn|d{}4C0$R)Wvz55D(T^|QijJ1rOpym`+;_(Y$aQ%m=;paOaq@8d z+tC>{cUeZY$VEGHI8Z}ZCzU5XNRyKp<7sx&S_6^!03fi8-a=2wrs=c=dP9rJwWq^i z0v+A-I??DmuY5!$E9n2(DX(Wcv@7A6lsXE zWf(<5)*)7HWFMLpxJ?#^G!lqE$IhglnwlGJe--AV9`?0_?21iJ)3v0Onn&#C9-H$5 z7}5=9&{UIF?R9PjEXQ6Rvl;e-+QYa&7 zDk%BIVnRvCDSy@cqK>f$&*^$(z7nXy?YXmQnJ>yQ_zyhOx+Oxb*`p~g-3x!%z4_vu z*c-kB#~X?rFznM}(Tj5kVpGu@SPPacY|Rhy8G(I^e^ZWH2^IB%UXr5Hc<_=r5`+QN z_#HeX+SJsLP_N`ylQWw>CkSSwa?hY8Sdd}rKB^vxN9?&{R|{jZFkuvqtOugrAG44W zqvm0eorOtOBU*_%ZPgeh;xN&gf~Vaj`XJPOH)GO7b1u<>9eYC8Q6neIfcy@&@!k7@ zf8$O+=y|k)2__CN59`ZajWBtpd81*x^E{H$x)NZJZOP*^Nk4xksJrj#j`S1%ea4#m zj^tny_9>a)xGo{LRySs9n=ymw*;_L@5>EvV!Psz`Rz4X`cfW$uQS_XQ;+`#vLC%w2 z1GU04EtrH1n~m_zkjPJX-~I0J@O!Mt*b-3sJs9Dd{VF zIS4X>B|t~g;xWWlja3SiWKF3w_r;+bEZLHMMW}SRJLi-WS7v}wx^aWVtyjXtChT{6 zYDR|7uY4~XBvjL+4(n?A@>|c}DTqoN{g&BZiWGZEr~Xl?^|Q*n8v6Gtt1-_q5`m37 ztHQQ}W$wOWph+LvTBS=nU&`nlmfdz&%B9;YFuG4#m!h<$N#vm@tMVH42uud~f_!9o z1d$Tux^o!i%w|^yC5+PTueni6-d(AIpp$z6jpA*u9oh`|v--F-U12Xm%sXYSpjENE zw!XWM?zC)t(WV@-;vL+U(DkWce%`u9VwElVuNHFmu)!*C3?t^O_3D9Eg{tfR+c;-D z6_HL=tcC&+4++VhvidKh!sF{ctrrwz-#UpiP5M|}63ZQ38}kl6YuPUUMnmfTOY-2<+)vsx z!VP}daHu)aRrcZzWw=&r>~5*{K;IkWR5S!=ffQD(``-5h-p^`XKGMX-1!z-B^N2KZ zgS17LnSAj=pW#U-#1DH{!#5)!f_P*T4HIru7h*!Z!8_L*OA>yJ3@^=9Pe7A=tl8>2 z-sce>jx-;I;9QEcg_LJh%zP(+N&mV|dFv+^zSM#m5Jz0E1n*umyt;H}cYlS>JsF|a z<{aDEw+vXb(7Rqk=e`fV3K>Zqf$}x;ebjM01+J(Zm9Uc?VjL~7NA?7u)RGnSgfNZ& z1N#vU7#bezbNRn25Xds1_?j3dSHLntEhhe8zdO!M5(KCsi?Z>d5||Ed9hKXFamv?T z&Wy%N4SqpVsASe?1PXmj{9#`_r*If_(BW9mbZ7o=(9e9be3|@pKoE(wlc{P}hDh0l z$u+YY_Wxnufdjrqw(ui)#+@ggaHty?!h7Zc<%lo4X`e~ScO=eH{ncZ4O=2ycQz+dn z)$}!@z(Q1^XYG`3q>kb%MPo5g;spYIz`~NV-0jb7cICTF2Z+$}B>~igaP0%w4fyUmW2$bZI?PkF5Zsd3d0r-ICKfwtC$8`4HyLOAFY2E;K`2`+|wVlblNCkf0&?10#96 znR!{kQ)q7IPp{Dg0_6?R9r?)GriYr=fQ18~$pc-{5mV3h3*jpK?CGIU3+!H_V9V@6oRA%JFy6EqEzV@QkkuoPr@2iBab6z`EI~<8?`FGo4v^bF$qa!1|Kpu7m zoCHH2HTkk|;{m=W#Fe5nv`~_d(mG8%r*LV1x{J6r9pJ~cSXHCypOQL9G_-F79Po;b z^z%DfHkEriSS4c;Sag#gU_j6U`??Np5{|c;Lij5O_;4cExabMuf4XJ$>lpP#DSob; zVI7Ix?WZCBAj|Z+-Gn{LhvpH7S#!R3+9-psVA15-MEf+fjXF$pO}(IZ8qZIXZsO1A#cgWWi-udPSW#16 zKKm$u&ct3+JQ@@sxPIFH*`nB1yQDHGxO44G?=*?t7(v#)#cwsXi0v%?J*Pk$J7#cu z69KazGG3?KDwZ;GiIE&f?u=2f-NO}4%&i@AKG{})*Gej_3OTK1)bUUK0Nl@^QkA1G zu1{KOFOz(9Q3QRKkNN5Q$NHOV_zxueUOG_ajCog{q`uU#h&{n)lq*=1mh8{MZTP*= zrrQ9`kDHj$w=NE-k@Zw9$e@48(w5TYN9$C81?md%D_S2Hc_4uKiY2`PvM5w#!jvU0 zEkT85l82CmzdOUJj_lATMo!&kmmME04APL1U9pc;vNqZV>$mwut7auuf!2W*y7WG8#%5fu#Bg2pKR9($!_?RRVE2WnX68 z#S2tC(LMWg33rI^;%Iah?W3~Qqm1g$3*B<42p=W?JLwlW2^o$gxa9eXn{?F8)GZOG zIfu@#Ev{+8zbPHK;KuIMBKGbd94t{{$Z6&PLe)~UeWw)ci-|QZA$`Rv;Fym zhF8HX)n5?PkO#Qd@sAySkgUTT==I@7zUe0(;$l08*m=CI0FZwCfo?bl(G(kv64RQ- zi!7i|@Bk(Wg{2k=tU{Fg9Tn|WNN{!LGFab@lUpHh_ z(Z@(-Paw~dk+^L2u!|<+#p%fefPe@?n56-%u-}nsZE0*Wb|q7#gl~miZDEVPl5E2N zlVHKkrTlVb8Rn%1RZwv;TDSm^yU>){d3s}@vt&qBa#C+%^nAT*NTifh%MHf;UX0A= z$u2ibWoz24;vJLSTFw4y4Mfl*Fbo@lMiS-Aa6;n#)zq zNCcazIq<3jPHJo~^q2V}WD0N{@X*3nF>DIh>$wj$~igN_9I z$cY)1=m9ZG^NL`VMxs}~=uDXST45V9Inb+*30rUGKZ0FunScx|o*yZ+E?GZHA>JiZj+q@$>&%^T6s{0ae`*n+=haa)UZWli~Tme$Xuy40i7$7iQyA6 zNLbP%z~693RB~IH@g5dyiMy<aex*b=~Vzzk4yAnqO##p;C zpHoFEtHIxtEK)$KD`+g}p92F*CfrP)4Qnycty74jqa**ta}~msFoT0y!%NTr-5>YehM0R z3833{^WycKnJ;eCw%LrOntW-nH}prw`VMvH<1kd)es;I9XgSAP0$j$liyr+hmJ0{3 ze7rG0o~_(6+RA%vUtbh%Pcl?3dq)^;Upvy_!mp!4n1%N*btyW`YV47yJ@&5D_P7#v zaZWCR9so01L6>~C6aL`4V=ku_kSV@Y)xq?NW$^kr!FNgaK$vf1NgHUJ0|mGarc#YC zK8R90NW0E#p14;{#Z7q)wtJ24NzAuC9F|qFNyHRzqUxF(drbfYDbC}IH0-sT>CllR z2N=fnO>#(;AViPL7@-uA<|`*ijLe0&yW4hv@bh|dDXCqmwgB8{As&!sZuWyj=sXjX zgD@U~7voa!MO{_U+U%o`g+yuK_6gNER$5T)c0=vY%D?WavPO+nd;1c!m99*O z3s26$#aCrq6LkL(TdMVbcI=D#Y=q?NLch{@uKPkSX3~N0Bw_JLfwo?dunB~IdqbMd zkACHAHR^ay`_z~Rm#w2Se?(Vw!%v;Gt^7T5`zbI3GZaBE)M3h`V56RZlc;`yM@4fr z+0^gxB>DU#LmXySd2|Im^(m{l5YSW^UBv=G&e7UlRWF*{hM$vbmQuM#(_RRnexG)a zc5T4b+q!fuhjwqtD~LdG2ZRQge@~e3*7Uu8M<@_{w0fYpCb5x$ea;mX19Dcu#_}fD zF^mPg&#H3Z{aaj;ODR19pl&;%-*}{K*UFz|!8|Xvki7+5$KuRbEi|0qrdU1Q#*V@YG1-a`~+z zA=653k><|t^FiV-c`Vsk7JQJ2g3VBkfcaE7uWp0y$p46!jOIlO&^M>j-*%q^+sthv z5IH0@&ob6=E1t=k4qa-+DBFL+DsItIZ(WD}*P!78kt0l>}>ZE;Tgrb>1 zol@jsQhw`87?Z-pCwD@LD;-G2?eogR8^bnO3?&~S3w#iEs_A&>*z}de$obc+L!sg& zWW&rCv;VJPg|eY>xj297numw8wV}HM8t5mwKbH+dLVG=PaybC5qeOm;E zz$b`@I1mNwDC{T2SZMwhg86sdg}NcWoF*}|9<>F@4U+@?@8)G*?l^bxMlCTi$ zUWexlO+9o74mj~@43}l;c4b_ABu(-bTXf8eh6$>GFkN~|%&{m~ z2|Z2K_!@wx5;-aRkh?9ly@o)KGIKYw zImeo4L3t$A5^)PxdTz+xfQl&9J;%m~MF3FvV>o#dgh?BgUN{*_|AbFL*Wq2&T zFTk-%rD~6R?sGhd(D#9c)dix^3I< zjBXj#rjY_LVQ(!67pITidJ$(}9u`rYS&4!;O;ROqy&;%e){L3N(PC3cz*^9&18Y=G zrr;_YRiWEO9Unbj@rIL zZV#E@gt`f5oBYfHcyYvsx_CJn#htLEme}yE+)UHY8vnk|VTsOr&z;VSZbsR@DBLaL zL}>FtLvJ%e@IUAX6#;%ou|Q^(4&s=eS%8*Cb2#wbXE}e3pjELnO*bDrl=s0aw+*3% zR4R3`gwsBN_d^awYfZavyWV_qh+R$mS~VJBwVH%3{&SK_F#ZbpA#Q z23khs27t&mZRjoPRBcyD7!(DYLZh|E&dSSyR||;=rswa@gbbwOs}z(8bJ7T^kvEu* zbk`rL;Nn=WQIfJ`4}-%GP%+6Fu^rWtAX8O9#R-3+ha`NlznfWX9@Gc64rpYHinM=C z;Pfit9t;WGkND1b90fo%gmsXQv4Py86*b(wh&!!7YrxZRo!DvV?}7b7$^qL~sNg1< zTLsApZXSD6g3XkSgF>o#UXVh3Qpm1?j5|$qX!FhJy|Rgp@^tqg0l&y6*NRxgVQ#4&AEhk96`r{Q~CU_6W1$1Rez+Vf{bwyO&=?far0k>kf`zDXb@rWBZ6I zKj|1dI~9E+jWCK&_BOYA5LJ2Cpqtr*f?<#G+C@xp`M;VlbpVvnNZHb8dD9TVa`oH} zLXF>+r4vt!YI^f6a-z zZjk2y-*DEYapsW!YCKymQR#4i3t|0p6*Gfs6=_-$djtNill}?@biIO$m+&S-HoDMI!P5 z)_^vY0C0byAofGsQ-VVfL=F0toI`)ZLHp(L+bq&9ah5VD(v8ZS@mZt1W1oPW7Q|Th ztC`AMazey4W=@>t-D8?Y#rlO?oai6^3eG}m;(ry zQxAAb*Jsj7)HT`SaOptne<*EI9}b)y|Ql^;t?yCl}Cf(+HX2wGtPGT1j7kz(Y`A$bD1stc6&mt59 z&K1*;ANUo*n1s!;-7D=hUSTBGqj}P0fh*8a3%=)juSd~g3hd^g8sAH|Z~@`+g4LQ8 zfXXG~FYRXBr61DjS@c+yDc_(-bV+$09;K_STwIze)Y$N%OMYsoP&}>GBzV}C^l`7G!3~U0e=d*?z0)ret$xkfwIts4j`4> z5g>8POH-=!I$M&>5%hn#hVf~fjmw47$3;06mm6mrrlDFKy%FaGL#c5~f{JnYDXLe1 z2sP#g-M2fyOzcEaT^IYSL+l6fDceXyL_MD zt|69dY&;`U<>nHB>RO$$Cio(K_rpDTigbk@^C!J%mARSiqI9-hZ%|fjpRxPTIs#>m zLpU_g?}OD@I3HCz+n#@uz;QDw0`crjN8&=zVqOLRO{>&@2)$HZp`!-zZf<%KUB!p= z?@0ViI(s~|C5}Yg{k$V^9miIs8!^lNq3b;5k*hk1>BJN_sk0w<>O|eaB5dgT^|R$8 zWKKjLXUO<(^^lRXIuVU4sSyIXVvQ)yF|gp+CM~cz6PWb>bih^=q|q*7Jg@Mwlye3U zv4J++Zv#)I9A)iAjW3u9;C8Q{htN^KB3{4BQ@(Xhg1OOF~NaFn>THBl@vqf`f7EBRl~ z1%u_r^J8F4Kxwk(j@ZT3K(LY6VF1s|x&n!Vuhry%Yu307fl4GgSo|`}t zK|@!fqc;)7qn0E>a)%A&SLM)}BO?gF;Kq4h*v;?3*^g{om?se^7MeA^CehB2FdR2Q6$st|6^uZ8+ zD8PTC-Z<5F1QkSeVxMV$?Zn${Xia8V z9n%TtrZErSYC5EPcV6FOQEPWr8FOmdXWF$91yo1Q2W?67a%UGX#+SjEe5Zp4?vv?4 zuamlm-K5w{lFEDFS{XjpUJQT_X*Ke{8KnY+G7#zf8Fd-i1fCc}h9}%{-G_BlcVODf zIV~!Va0CB36Rh^-6C?6ccUHtu`m%$0M|F{w->?1sV^?dlhEV29>pTRw3q2+Z?-~R+ zKewUWm4Rb0ZY5atVR@kWQB#NwGPS))PpQ*IsBwA0HhYwlyZj7F9TBtu z4Vo!i3xh26WfNdEF$YbM_PVg`3o4p$?;686N}n|oG#C_`pd!HMEZd|n&r~#1CmO$b z4D9k)NpCcRZryGoh$1G9wrTYlDqpz8pnl*g5C){LIJt3808)Mh_p?I<)!-u5@*}(sB#=v*U8Yq&@-Ib3Cu_5MZ%BqZ4@!>>p zTYC89`$W1ymGCY= za{2eJZ@o4ocDD4D#TnjC5`V2hjR+DH5I12!jK^JD^97{kRkCT=O$WGY_d{#g?P#A_ zS|(_Zrpmawu8Bq0ob(fJk~N>x*F)fVM1B$op!gpI)<|p$vsKK@t*t-Icruwux8A2J zCwejMc9*k>NP#clQ`}l_Y_xM;sBKrNpnmamO1RExH~t@(Nx7qYqgk1X%816ZjKdy$ z=yzRQcRN|@i~^iePI8)Q%G3B(0g_78H+rp?@YQe32A5*|MS@lrv$bL_<5&YUjia{} zTH@bpJgJ2~pjS(A0Jr%yJZ1=I5B+(d0Z+Y58aO5HWIOmDLnT&jU=8qo3rL?hBG|?9 z-H2FnMZLF_m>x_zM^q8(S5-&WCb(*8E0Y{1!*q1IZeP?&3Ui+}%W%<8kIfsTt@mF| zYi7MstCasqRR5aoGz|EaIhJr#rG0%(5{7@NI1y|B!tqdrb)~^qmN&p_d+|0s3U`O1 z-mgsg<8?S&14E%~Q7U!~{DL{3@$E&Ge@@g|r`FdUI2q{!Bm30DqN?@RgO&}w8$qIz zmRlvx#KQIG4vcu%&pr`->PJk0nZ7myVC5EdK-g%vOF=1;H_c`EVwLosXVSSs%%&iS zSal*!5R*Fy+d}a5?OhXuX|>0`zbU(NbA5xf7K3*nXF`HzzcWMYPyMVBPm!Km6)kU^ zRX|mlJu^DexsO7u>i|Q1xU46rZ#?KC3e!gODh*d33-pJBRo_. + */ + +#if defined JOYSWAY_A7105_INO +#include "iface_a7105.h" + + +#define EVEN_ODD 0x00 +//#define EVEN_ODD 0x01 +static const uint8_t A7105_regs[] = { + 0x00, 0x62, -1, 0x0f, 0x00, -1 , -1 , 0x00, 0x00, 0x05, 0x00, 0x01, 0x00, 0xf5, 0x00, 0x15, + 0x9e, 0x4b, 0x00, 0x03, 0x56, 0x2b, 0x12, 0x4a, 0x02, 0x80, 0x80, 0x00, 0x0e, 0x91, 0x03, 0x0f, + 0x16, 0x2a, 0x00, -1, -1, -1, 0x3a, 0x06, 0x1f, 0x47, 0x80, 0x01, 0x05, 0x45, 0x18, 0x00, + 0x01, 0x0f, 0x00 +}; + +static uint8_t next_ch; + +static int joysway_init() +{ + int i; + uint8_t if_calibration1; + //uint8_t vco_calibration0; + //uint8_t vco_calibration1; + + counter = 0; + next_ch = 0x30; + + for (i = 0; i < 0x33; i++) + if((uint8_t)A7105_regs[i] != -1) + A7105_WriteReg(i, A7105_regs[i]); + A7105_WriteID(0x5475c52a); + + A7105_Strobe(A7105_PLL); + + //IF Filter Bank Calibration + A7105_WriteReg(0x02, 1); + A7105_ReadReg(0x02); + uint32_t ms = micros(); + while(micros() - ms < 500) { + if(! A7105_ReadReg(0x02)) + break; + } + if (micros() - ms >= 500) + return 0; + A7105_Strobe(A7105_STANDBY); + if_calibration1 = A7105_ReadReg(0x22); + if(if_calibration1 & A7105_MASK_FBCF) { + //Calibration failed...what do we do? + return 0; + } + + //VCO Current Calibration + A7105_WriteReg(0x24, 0x13); //Recomended calibration from A7105 Datasheet + A7105_WriteReg(0x25, 0x09); //Recomended calibration from A7105 Datasheet + + A7105_WriteID(MProtocol_id_master); + A7105_Strobe(A7105_PLL); + A7105_WriteReg(0x02, 1); + ms = micros(); + while(micros() - ms < 500) { + if(! A7105_ReadReg(0x02)) + break; + } + if (micros() - ms >= 500) + return 0; + A7105_Strobe(A7105_STANDBY); + if_calibration1 = A7105_ReadReg(0x22); + if(if_calibration1 & A7105_MASK_FBCF) { + //Calibration failed...what do we do? + return 0; + } + A7105_WriteReg(0x24, 0x13); //Recomended calibration from A7105 Datasheet + A7105_WriteReg(0x25, 0x09); //Recomended calibration from A7105 Datasheet + + A7105_SetTxRxMode(TX_EN); + A7105_SetPower(); + + A7105_Strobe(A7105_STANDBY); + return 1; +} + +static void joysway_build_packet() +{ + int i; + //-100% =~ 0x03e8 + //+100% =~ 0x07ca + //Calculate: + //Center = 0x5d9 + //1 % = 5 + packet[0] = counter == 0 ? 0xdd : 0xff; + packet[1] = (MProtocol_id_master >> 24) & 0xff; + packet[2] = (MProtocol_id_master >> 16) & 0xff; + packet[3] = (MProtocol_id_master >> 8) & 0xff; + packet[4] = (MProtocol_id_master >> 0) & 0xff; + packet[5] = 0x00; + static const int chmap[4] = {6, 7, 10, 11}; + for (i = 0; i < 4; i++) { +// if (i >= Model.num_channels) { packet[chmap[i]] = 0x64; continue; } + uint32_t value = (uint32_t)Servo_data[i] * 0x66 / PPM_MAX + 0x66; + if (value < 0) { value = 0; } + if (value > 0xff) { value = 0xff; } + packet[chmap[i]] = value; + } + packet[8] = 0x64; + packet[9] = 0x64; + packet[12] = 0x64; + packet[13] = 0x64; + packet[14] = counter == 0 ? 0x30 : 0xaa; + uint8_t value = 0; + for (int i = 0; i < 15; i++) { value += packet[i]; } + packet[15] = value; +} + +static uint16_t joysway_cb() +{ + uint8_t ch; + if (counter == 254) { + counter = 0; + A7105_WriteID(0x5475c52a); + ch = 0x0a; + } else if (counter == 2) { + A7105_WriteID(MProtocol_id_master); + ch = 0x30; + } else { + if ((counter & 0x01) ^ EVEN_ODD) { + ch = 0x30; + } else { + ch = next_ch; + } + } + if (! ((counter & 0x01) ^ EVEN_ODD)) { + next_ch++; + if (next_ch == 0x45) + next_ch = 0x30; + } + joysway_build_packet(); + A7105_Strobe(A7105_STANDBY); + A7105_WriteData(16, ch); + counter++; + return 6000; +} + +static uint16_t JOYSWAY_Setup() { + while(1) { + A7105_Reset(); + if (joysway_init()) + break; + } + return 2400; +} +#endif diff --git a/Multiprotocol/CYRF6936_SPI.ino b/Multiprotocol/CYRF6936_SPI.ino index 9880233..3985acb 100644 --- a/Multiprotocol/CYRF6936_SPI.ino +++ b/Multiprotocol/CYRF6936_SPI.ino @@ -215,11 +215,10 @@ static void CYRF_StartReceive() CYRF_ReadRegisterMulti(CYRF_21_RX_BUFFER, dpbuffer, 0x10); } */ -/*static void CYRF_ReadDataPacketLen(uint8_t dpbuffer[], uint8_t length) +static void CYRF_ReadDataPacketLen(uint8_t dpbuffer[], uint8_t length) { ReadRegisterMulti(CYRF_21_RX_BUFFER, dpbuffer, length); } -*/ static void CYRF_WriteDataPacketLen(const uint8_t dpbuffer[], uint8_t len) { CYRF_WriteRegister(CYRF_01_TX_LENGTH, len); diff --git a/Multiprotocol/CYRF6936_j6pro.ino b/Multiprotocol/CYRF6936_j6pro.ino new file mode 100644 index 0000000..623ae5f --- /dev/null +++ b/Multiprotocol/CYRF6936_j6pro.ino @@ -0,0 +1,277 @@ +/* + This project is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Deviation is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with Deviation. If not, see . + */ + +#if defined(J6PRO_CYRF6936_INO) +#include "iface_cyrf6936.h" + +#define NUM_WAIT_LOOPS (100 / 5) //each loop is ~5us. Do not wait more than 100us + +//For Debug +//#define NO_SCRAMBLE + +enum J6ProState { + J6PRO_BIND, + J6PRO_BIND_01, + J6PRO_BIND_03_START, + J6PRO_BIND_03_CHECK, + J6PRO_BIND_05_1, + J6PRO_BIND_05_2, + J6PRO_BIND_05_3, + J6PRO_BIND_05_4, + J6PRO_BIND_05_5, + J6PRO_BIND_05_6, + J6PRO_CHANSEL, + J6PRO_CHAN_1, + J6PRO_CHAN_2, + J6PRO_CHAN_3, + J6PRO_CHAN_4, +}; + +static const uint8_t J6Pro_sopcodes[][8] = { + /* Note these are in order transmitted (LSB 1st) */ + {0x3C, 0x37, 0xCC, 0x91, 0xE2, 0xF8, 0xCC, 0x91}, + {0x9B, 0xC5, 0xA1, 0x0F, 0xAD, 0x39, 0xA2, 0x0F}, + {0xEF, 0x64, 0xB0, 0x2A, 0xD2, 0x8F, 0xB1, 0x2A}, + {0x66, 0xCD, 0x7C, 0x50, 0xDD, 0x26, 0x7C, 0x50}, + {0x5C, 0xE1, 0xF6, 0x44, 0xAD, 0x16, 0xF6, 0x44}, + {0x5A, 0xCC, 0xAE, 0x46, 0xB6, 0x31, 0xAE, 0x46}, + {0xA1, 0x78, 0xDC, 0x3C, 0x9E, 0x82, 0xDC, 0x3C}, + {0xB9, 0x8E, 0x19, 0x74, 0x6F, 0x65, 0x18, 0x74}, + {0xDF, 0xB1, 0xC0, 0x49, 0x62, 0xDF, 0xC1, 0x49}, + {0x97, 0xE5, 0x14, 0x72, 0x7F, 0x1A, 0x14, 0x72}, + {0x82, 0xC7, 0x90, 0x36, 0x21, 0x03, 0xFF, 0x17}, + {0xE2, 0xF8, 0xCC, 0x91, 0x3C, 0x37, 0xCC, 0x91}, //Note: the '03' was '9E' in the Cypress recommended table + {0xAD, 0x39, 0xA2, 0x0F, 0x9B, 0xC5, 0xA1, 0x0F}, //The following are the same as the 1st 8 above, + {0xD2, 0x8F, 0xB1, 0x2A, 0xEF, 0x64, 0xB0, 0x2A}, //but with the upper and lower word swapped + {0xDD, 0x26, 0x7C, 0x50, 0x66, 0xCD, 0x7C, 0x50}, + {0xAD, 0x16, 0xF6, 0x44, 0x5C, 0xE1, 0xF6, 0x44}, + {0xB6, 0x31, 0xAE, 0x46, 0x5A, 0xCC, 0xAE, 0x46}, + {0x9E, 0x82, 0xDC, 0x3C, 0xA1, 0x78, 0xDC, 0x3C}, + {0x6F, 0x65, 0x18, 0x74, 0xB9, 0x8E, 0x19, 0x74}, +}; +const uint8_t bind_sop_code[] = {0x62, 0xdf, 0xc1, 0x49, 0xdf, 0xb1, 0xc0, 0x49}; +const uint8_t data_code[] = {0x02, 0xf9, 0x93, 0x97, 0x02, 0xfa, 0x5c, 0xe3, 0x01, 0x2b, 0xf1, 0xdb, 0x01, 0x32, 0xbe, 0x6f}; + +static uint8_t stateJ6P; +static uint8_t radio_ch[4]; +static uint8_t num_channels; + +void J6Pro_build_bind_packet() +{ + packet[0] = 0x01; //Packet type + packet[1] = 0x01; //FIXME: What is this? Model number maybe? + packet[2] = 0x56; //FIXME: What is this? + packet[3] = cyrfmfg_id[0]; + packet[4] = cyrfmfg_id[1]; + packet[5] = cyrfmfg_id[2]; + packet[6] = cyrfmfg_id[3]; + packet[7] = cyrfmfg_id[4]; + packet[8] = cyrfmfg_id[5]; +} +void J6Pro_build_data_packet() +{ + uint8_t i; + uint32_t upperbits = 0; + packet[0] = 0xaa; //FIXME what is this? + for (i = 0; i < 12; i++) { + if (i >= num_channels) { + packet[i+1] = 0xff; + continue; + } + uint32_t value = (uint32_t)Servo_data[i] * 0x200 / PPM_MAX + 0x200; + if (value < 0) + value = 0; + if (value > 0x3ff) + value = 0x3ff; + packet[i+1] = value & 0xff; + upperbits |= (value >> 8) << (i * 2); + } + packet[13] = upperbits & 0xff; + packet[14] = (upperbits >> 8) & 0xff; + packet[15] = (upperbits >> 16) & 0xff; +} + +static void J6Pro_cyrf_init() +{ + /* Initialise CYRF chip */ + CYRF_WriteRegister(CYRF_28_CLK_EN, 0x02); + CYRF_WriteRegister(CYRF_32_AUTO_CAL_TIME, 0x3c); + CYRF_WriteRegister(CYRF_35_AUTOCAL_OFFSET, 0x14); + CYRF_WriteRegister(CYRF_1C_TX_OFFSET_MSB, 0x05); + CYRF_WriteRegister(CYRF_1B_TX_OFFSET_LSB, 0x55); + CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x25); + CYRF_WriteRegister(CYRF_03_TX_CFG, 0x05 | CYRF_BIND_POWER); + CYRF_WriteRegister(CYRF_06_RX_CFG, 0x8a); + CYRF_WriteRegister(CYRF_03_TX_CFG, 0x28 | CYRF_BIND_POWER); + CYRF_WriteRegister(CYRF_12_DATA64_THOLD, 0x0e); + CYRF_WriteRegister(CYRF_10_FRAMING_CFG, 0xee); + CYRF_WriteRegister(CYRF_1F_TX_OVERRIDE, 0x00); + CYRF_WriteRegister(CYRF_1E_RX_OVERRIDE, 0x00); + CYRF_ConfigDataCode(data_code, 16); + CYRF_WritePreamble(0x023333); +} +static void J6Pro_cyrf_bindinit() +{ +/* Use when binding */ + //0.060470# 03 2f + CYRF_WriteRegister(CYRF_03_TX_CFG, 0x28 | 0x07); //Use max power for binding in case there is no telem module + + CYRF_ConfigRFChannel(0x52); + CYRF_ConfigSOPCode(bind_sop_code); + CYRF_ConfigCRCSeed(0x0000); + CYRF_WriteRegister(CYRF_06_RX_CFG, 0x4a); + CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x83); + //0.061511# 13 20 + + CYRF_ConfigRFChannel(0x52); + //0.062684# 0f 05 + CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x25); + //0.062792# 0f 05 + CYRF_WriteRegister(CYRF_02_TX_CTRL, 0x40); + J6Pro_build_bind_packet(); //01 01 e9 49 ec a9 c4 c1 ff + //CYRF_WriteDataPacketLen(packet, 0x09); +} +static void J6Pro_cyrf_datainit() +{ +/* Use when already bound */ + //0.094007# 0f 05 + uint8_t sop_idx = (0xff & (cyrfmfg_id[0] + cyrfmfg_id[1] + cyrfmfg_id[2] + cyrfmfg_id[3] - cyrfmfg_id[5])) % 19; + uint16_t crc = (0xff & (cyrfmfg_id[1] - cyrfmfg_id[4] + cyrfmfg_id[5])) | + ((0xff & (cyrfmfg_id[2] + cyrfmfg_id[3] - cyrfmfg_id[4] + cyrfmfg_id[5])) << 8); + CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x25); + CYRF_ConfigSOPCode(J6Pro_sopcodes[sop_idx]); + CYRF_ConfigCRCSeed(crc); +} + +static void J6Pro_set_radio_channels() +{ + //FIXME: Query free channels + //lowest channel is 0x08, upper channel is 0x4d? + CYRF_FindBestChannels(radio_ch, 3, 5, 8, 77); + radio_ch[3] = radio_ch[0]; +} + +static uint16_t j6pro_cb() +{ + switch(stateJ6P) { + case J6PRO_BIND: + J6Pro_cyrf_bindinit(); + stateJ6P = J6PRO_BIND_01; + //no break because we want to send the 1st bind packet now + case J6PRO_BIND_01: + CYRF_ConfigRFChannel(0x52); + CYRF_SetTxRxMode(TX_EN); + //0.062684# 0f 05 + CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x25); + //0.062684# 0f 05 + CYRF_WriteDataPacketLen(packet, 0x09); + stateJ6P = J6PRO_BIND_03_START; + return 3000; //3msec + case J6PRO_BIND_03_START: + { + int i = 0; + while (! (CYRF_ReadRegister(0x04) & 0x06)) + if(++i > NUM_WAIT_LOOPS) + break; + } + CYRF_ConfigRFChannel(0x53); + CYRF_SetTxRxMode(RX_EN); + CYRF_WriteRegister(CYRF_06_RX_CFG, 0x4a); + CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x83); + stateJ6P = J6PRO_BIND_03_CHECK; + return 30000; //30msec + case J6PRO_BIND_03_CHECK: + { + uint8_t rx = CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS); + if((rx & 0x1a) == 0x1a) { + rx = CYRF_ReadRegister(CYRF_0A_RX_LENGTH); + if(rx == 0x0f) { + rx = CYRF_ReadRegister(CYRF_09_RX_COUNT); + if(rx == 0x0f) { + //Expected and actual length are both 15 + CYRF_ReadDataPacketLen(packet, rx); + if (packet[0] == 0x03 && + packet[3] == cyrfmfg_id[0] && + packet[4] == cyrfmfg_id[1] && + packet[5] == cyrfmfg_id[2] && + packet[6] == cyrfmfg_id[3] && + packet[7] == cyrfmfg_id[4] && + packet[8] == cyrfmfg_id[5]) + { + //Send back Ack + packet[0] = 0x05; + CYRF_ConfigRFChannel(0x54); + CYRF_SetTxRxMode(TX_EN); + stateJ6P = J6PRO_BIND_05_1; + return 2000; //2msec + } + } + } + } + stateJ6P = J6PRO_BIND_01; + return 500; + } + case J6PRO_BIND_05_1: + case J6PRO_BIND_05_2: + case J6PRO_BIND_05_3: + case J6PRO_BIND_05_4: + case J6PRO_BIND_05_5: + case J6PRO_BIND_05_6: + CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x25); + CYRF_WriteDataPacketLen(packet, 0x0f); + stateJ6P = stateJ6P + 1; + return 4600; //4.6msec + case J6PRO_CHANSEL: + BIND_DONE; + J6Pro_set_radio_channels(); + J6Pro_cyrf_datainit(); + stateJ6P = J6PRO_CHAN_1; + case J6PRO_CHAN_1: + //Keep transmit power updated + CYRF_SetPower(CYRF_HIGH_POWER); + J6Pro_build_data_packet(); + //return 3400; + case J6PRO_CHAN_2: + //return 3500; + case J6PRO_CHAN_3: + //return 3750 + case J6PRO_CHAN_4: + CYRF_ConfigRFChannel(radio_ch[stateJ6P - J6PRO_CHAN_1]); + CYRF_SetTxRxMode(TX_EN); + CYRF_WriteDataPacket(packet); + if (stateJ6P == J6PRO_CHAN_4) { + stateJ6P = J6PRO_CHAN_1; + return 13900; + } + stateJ6P = stateJ6P + 1; + return 3550; + } + return 0; +} + +static uint16_t j6pro_setup() +{ + CYRF_Reset(); + J6Pro_cyrf_init(); + num_channels = 8; + if (IS_AUTOBIND_FLAG_on) { + stateJ6P = J6PRO_BIND; + BIND_IN_PROGRESS; + } else { + stateJ6P = J6PRO_CHANSEL; + } + return 2400; +} +#endif diff --git a/Multiprotocol/Cyrf6936_wk2x01.ino b/Multiprotocol/Cyrf6936_wk2x01.ino new file mode 100644 index 0000000..363dd61 --- /dev/null +++ b/Multiprotocol/Cyrf6936_wk2x01.ino @@ -0,0 +1,449 @@ +/* + This project is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. + Deviation is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. + You should have received a copy of the GNU General Public License along with Deviation. If not, see . + */ +#if defined(WK2x01_CYRF6936_INO) +#include "iface_cyrf6936.h" + +#define PKTS_PER_CHANNEL 4 + +//Fewer bind packets in the emulator so we can get right to the important bits +#define WK_BIND_COUNT 2980 + +#define NUM_WAIT_LOOPS (100 / 5) //each loop is ~5us. Do not wait more than 100us + + +#define WK_BIND 0 +#define WK_BOUND_1 1 +#define WK_BOUND_2 2 +#define WK_BOUND_3 3 +#define WK_BOUND_4 4 +#define WK_BOUND_5 5 +#define WK_BOUND_6 6 +#define WK_BOUND_7 7 +#define WK_BOUND_8 8 + +static const uint8_t sopcode[8] = { + /* Note these are in order transmitted (LSB 1st) */ + 0xDF,0xB1,0xC0,0x49,0x62,0xDF,0xC1,0x49 //0x49C1DF6249C0B1DF +}; +static const uint8_t fail_map[8] = {2, 1, 0, 3, 4, 5, 6, 7}; + +static uint8_t wk_pkt_num; +static u8 *radio_ch_ptr; +static uint16_t WK_BIND_COUNTer; +static uint8_t last_beacon; +/* +static const char * const wk2601_opts[] = { + _tr_noop("Chan mode"), _tr_noop("5+1"), _tr_noop("Heli"), _tr_noop("6+1"), NULL, + _tr_noop("COL Inv"), _tr_noop("Normal"), _tr_noop("Inverted"), NULL, + _tr_noop("COL Limit"), "-100", "100", NULL, + NULL +}; +*/ +#define WK2601_OPT_CHANMODE 0 +#define WK2601_OPT_PIT_INV 1 +#define WK2601_OPT_PIT_LIMIT 2 +#define LAST_PROTO_OPT 3 + +static void add_pkt_crc(uint8_t init) { + uint8_t add = init; + uint8_t xou = init; + int i; + for (i = 0; i < 14; i++) { add += packet[i]; xou ^= packet[i]; } + packet[14] = xou; + packet[15] = add & 0xff; +} +static const char init_2801[] = {0xc5, 0x34, 0x60, 0x00, 0x25}; +static const char init_2601[] = {0xb9, 0x45, 0xb0, 0xf1, 0x3a}; +static const char init_2401[] = {0xa5, 0x23, 0xd0, 0xf0, 0x00}; +static void build_bind_pkt(const char *init) { + packet[0] = init[0]; + packet[1] = init[1]; + packet[2] = rx_tx_addr[0]; + packet[3] = rx_tx_addr[1]; + packet[4] = init[2]; + packet[5] = rx_tx_addr[2]; + packet[6] = 0xff; + packet[7] = 0x00; + packet[8] = 0x00; + packet[9] = 0x32; + if (sub_protocol == WK2401) { packet[10] = 0x10 | ((fixed_id >> 0) & 0x0e); } + else { packet[10] = (fixed_id >> 0) & 0xff; } + packet[11] = (fixed_id >> 8) & 0xff; + packet[12] = ((fixed_id >> 12) & 0xf0) | wk_pkt_num; + packet[13] = init[3]; + add_pkt_crc(init[4]); +} + +static uint16_t get_channel(uint8_t ch, uint32_t scale, uint32_t center, uint32_t range) { + uint32_t value = (uint32_t)Servo_data[ch] * scale / PPM_MAX + center; + if (value < center - range) { value = center - range; } + if (value > center + range) { value = center + range; } + return value; +} + +static void build_data_pkt_2401() { + uint8_t i; + uint16_t msb = 0; + uint8_t offset = 0; + for (i = 0; i < 4; i++) { + if (i == 2) { offset = 1; } + uint16_t value = get_channel(i, 0x800, 0, 0xA00); //12 bits, allow value to go to 125% + uint16_t base = abs(value) >> 2; //10 bits is the base value + uint16_t trim = abs(value) & 0x03; //lowest 2 bits represent trim + if (base >= 0x200) { //if value is > 100%, remainder goes to trim + trim = 4 *(base - 0x200); + base = 0x1ff; + } + base = (value >= 0) ? 0x200 + base : 0x200 - base; + trim = (value >= 0) ? 0x200 + trim : 0x200 - trim; + + packet[2*i+offset] = base & 0xff; + packet[2*i+offset+1] = trim & 0xff; + msb = (msb << 4) | ((base >> 6) & 0x0c) | ((trim >> 8) & 0x03); + } + packet[4] = msb >> 8; //Ele/Ail MSB + packet[9] = msb & 0xff; //Thr/Rud MSB + packet[10] = 0xe0 | ((fixed_id >> 0) & 0x0e); + packet[11] = (fixed_id >> 8) & 0xff; + packet[12] = ((fixed_id >> 12) & 0xf0) | wk_pkt_num; + packet[13] = 0xf0; //FIXME - What is this? + add_pkt_crc(0x00); +} + +#define PCT(pct, max) (((max) * (pct) + 1L) / 1000) +#define MAXTHR 426 //Measured to provide equal value at +/-0 +static void channels_6plus1_2601(int frame, int *_v1, int *_v2) { + uint16_t thr = get_channel(2, 1000, 0, 1000); + int v1; + int thr_rev = 0, pitch_rev = 0; + if(thr > 0) { + if(thr >= 780) { //78% + v1 = 0; //thr = 60% * (x - 78%) / 22% + 40% + thr = PCT(1000-MAXTHR,512) * (thr-PCT(780,1000)) / PCT(220,1000) + PCT(MAXTHR,512); + } else { + v1 = 1023 - 1023 * thr / 780; + thr = PCT(MAXTHR, 512); //40% + } + } + else { + thr = -thr; + thr_rev = 1; + if(thr >= 780) { //78% + v1 = 1023; //thr = 60% * (x - 78%) / 22% + 40% + thr = PCT(1000-MAXTHR,512) * (thr-PCT(780,1000)) / PCT(220,1000) + PCT(MAXTHR,512); + if (thr >= 512) { thr = 511; } + } + else { + v1 = 1023 * thr / 780; + thr = PCT(MAXTHR, 512); //40% + } + } + if (thr >= 512) { thr = 511; } + packet[2] = thr & 0xff; + packet[4] = (packet[4] & 0xF3) | ((thr >> 6) & 0x04); + + uint16_t pitch= get_channel(5, 0x400, 0, 0x400); + if (pitch < 0) { + pitch_rev = 1; + pitch = -pitch; + } + if (frame == 1) { + //Pitch curve and range + if (thr > PCT(MAXTHR, 512)) { *_v2 = pitch - pitch * 16 * (thr - PCT(MAXTHR, 512)) / PCT(1000 - MAXTHR, 512) / 100; } + else { *_v2 = pitch; } + *_v1 = 0; + } + else if (frame == 2) { + //Throttle curve & Expo + *_v1 = v1; + *_v2 = 512; + } + packet[7] = (thr_rev << 5) | (pitch_rev << 2); //reverse bits + packet[8] = 0; +} + +static void channels_5plus1_2601(int frame, int *v1, int *v2) { + (void)v1; + //Zero out pitch, provide ail, ele, thr, rud, gyr + gear + if (frame == 1) { *v2 = 0; } //Pitch curve and range + packet[7] = 0; + packet[8] = 0; +} +static void channels_heli_2601(int frame, int *v1, int *v2) { + (void)frame; + //pitch is controlled by rx + //we can only control fmode, pit-reverse and pit/thr rate + int pit_rev = 0; + if (Model.proto_opts[WK2601_OPT_PIT_INV]) { pit_rev = 1; } + uint16_t pit_rate = get_channel(5, 0x400, 0, 0x400); + int fmode = 1; + if (pit_rate < 0) { pit_rate = -pit_rate; fmode = 0; } + if (frame == 1) { + //Pitch curve and range + *v1 = pit_rate; + *v2 = Model.proto_opts[WK2601_OPT_PIT_LIMIT] * 0x400 / 100 + 0x400; + } + packet[7] = (pit_rev << 2); //reverse bits + packet[8] = fmode ? 0x02 : 0x00; +} + +static void build_data_pkt_2601() { + uint8_t i; + uint8_t msb = 0; + uint8_t frame = (wk_pkt_num % 3); + for (i = 0; i < 4; i++) { + uint16_t value = get_channel(i, 0x190, 0, 0x1FF); + uint16_t mag = value < 0 ? -value : value; + packet[i] = mag & 0xff; + msb = (msb << 2) | ((mag >> 8) & 0x01) | (value < 0 ? 0x02 : 0x00); + } + packet[4] = msb; + int v1 = 0x200, v2 = 0x200; + if (frame == 0) { + //Gyro & Rudder mix + v1 = get_channel(6, 0x200, 0x200, 0x200); + v2 = 0; + } + if (Model.proto_opts[WK2601_OPT_CHANMODE] == 1) { channels_heli_2601(frame, &v1, &v2); } + else if (Model.proto_opts[WK2601_OPT_CHANMODE] == 2) { channels_6plus1_2601(frame, &v1, &v2); } + else { channels_5plus1_2601(frame, &v1, &v2); } + if (v1 > 1023) { v1 = 1023; } + if (v2 > 1023) { v2 = 1023; } + packet[5] = v2 & 0xff; + packet[6] = v1 & 0xff; + //packet[7] handled by channel code + packet[8] |= (get_channel(4, 0x190, 0, 0x1FF) > 0 ? 1 : 0); + packet[9] = ((v1 >> 4) & 0x30) | ((v2 >> 2) & 0xc0) | 0x04 | frame; + packet[10] = (fixed_id >> 0) & 0xff; + packet[11] = (fixed_id >> 8) & 0xff; + packet[12] = ((fixed_id >> 12) & 0xf0) | wk_pkt_num; + packet[13] = 0xff; + + add_pkt_crc(0x3A); +} + +static void build_data_pkt_2801() { + uint8_t i; + uint16_t msb = 0; + uint8_t offset = 0; + uint8_t sign = 0; + for (i = 0; i < 8; i++) { + if (i == 4) { offset = 1; } + uint16_t value = get_channel(i, 0x190, 0, 0x3FF); + uint16_t mag = value < 0 ? -value : value; + packet[i+offset] = mag & 0xff; + msb = (msb << 2) | ((mag >> 8) & 0x03); + if (value < 0) { sign |= 1 << i; } + } + packet[4] = msb >> 8; + packet[9] = msb & 0xff; + packet[10] = (fixed_id >> 0) & 0xff; + packet[11] = (fixed_id >> 8) & 0xff; + packet[12] = ((fixed_id >> 12) & 0xf0) | wk_pkt_num; + packet[13] = sign; + add_pkt_crc(0x25); +} + +static void build_beacon_pkt_2801() { + last_beacon ^= 1; + uint8_t i; + uint8_t en = 0; + uint8_t bind_state; + if (WK_BIND_COUNTer) { bind_state = 0xe4; } + else { bind_state = 0x1b; } + for (i = 0; i < 4; i++) { +/* if (Model.limits[fail_map[i + last_beacon * 4]].flags & CH_FAILSAFE_EN) { + uint32_t value = Model.limits[fail_map[i + last_beacon * 4]].failsafe + 128; + if (value > 255) { value = 255; } + if (value < 0) { value = 0; } + packet[i+1] = value; + en |= 1 << i; + } else +*/ { packet[i+1] = 0; } + } + packet[0] = en; + packet[5] = packet[4]; + packet[4] = last_beacon << 6; + packet[6] = rx_tx_addr[0]; + packet[7] = rx_tx_addr[1]; + packet[8] = rx_tx_addr[2]; + packet[9] = bind_state; + packet[10] = (fixed_id >> 0) & 0xff; + packet[11] = (fixed_id >> 8) & 0xff; + packet[12] = ((fixed_id >> 12) & 0xf0) | wk_pkt_num; + packet[13] = 0x00; //Does this matter? in the docs it is the same as the data packet + add_pkt_crc(0x1C); +} + +static void wk2x01_cyrf_init() { + /* Initialise CYRF chip */ + CYRF_WriteRegister(CYRF_03_TX_CFG, 0x28 | CYRF_HIGH_POWER); + CYRF_WriteRegister(CYRF_06_RX_CFG, 0x4A); + CYRF_WriteRegister(CYRF_0B_PWR_CTRL, 0x00); + CYRF_WriteRegister(CYRF_0C_XTAL_CTRL, 0xC0); + CYRF_WriteRegister(CYRF_0D_IO_CFG, 0x04); + CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x2C); + CYRF_WriteRegister(CYRF_10_FRAMING_CFG, 0xEE); + CYRF_WriteRegister(CYRF_1B_TX_OFFSET_LSB, 0x55); + CYRF_WriteRegister(CYRF_1C_TX_OFFSET_MSB, 0x05); + CYRF_WriteRegister(CYRF_1D_MODE_OVERRIDE, 0x18); + CYRF_WriteRegister(CYRF_32_AUTO_CAL_TIME, 0x3C); + CYRF_WriteRegister(CYRF_35_AUTOCAL_OFFSET, 0x14); + CYRF_WriteRegister(CYRF_1E_RX_OVERRIDE, 0x90); + CYRF_WriteRegister(CYRF_1F_TX_OVERRIDE, 0x00); + CYRF_WriteRegister(CYRF_01_TX_LENGTH, 0x10); + CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x2C); + CYRF_WriteRegister(CYRF_28_CLK_EN, 0x02); + CYRF_WriteRegister(CYRF_27_CLK_OVERRIDE, 0x02); + CYRF_ConfigSOPCode(sopcode); + CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x28); + CYRF_WriteRegister(CYRF_1E_RX_OVERRIDE, 0x10); + CYRF_WriteRegister(CYRF_0E_GPIO_CTRL, 0x20); + CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x2C); +} + +void WK_BuildPacket_2801() { + switch(phase) { + case WK_BIND: + build_bind_pkt(init_2801); +// if ((--WK_BIND_COUNTer == 0) || PROTOCOL_SticksMoved(0)) { + if ((--WK_BIND_COUNTer == 0)) { + WK_BIND_COUNTer = 0; + BIND_DONE; + phase = WK_BOUND_1; + } + break; + case WK_BOUND_1: + case WK_BOUND_2: + case WK_BOUND_3: + case WK_BOUND_4: + case WK_BOUND_5: + case WK_BOUND_6: + case WK_BOUND_7: + build_data_pkt_2801(); + phase++; + break; + case WK_BOUND_8: + build_beacon_pkt_2801(); + phase = WK_BOUND_1; + if (WK_BIND_COUNTer) { + WK_BIND_COUNTer--; + if (WK_BIND_COUNTer == 0) { BIND_DONE; } + } + break; + } + wk_pkt_num = (wk_pkt_num + 1) % 12; +} + +void WK_BuildPacket_2601() { + if (WK_BIND_COUNTer) { + WK_BIND_COUNTer--; + build_bind_pkt(init_2601); + if ((WK_BIND_COUNTer == 0)) { + WK_BIND_COUNTer = 0; + BIND_DONE; + } + } + else { build_data_pkt_2601(); } + wk_pkt_num = (wk_pkt_num + 1) % 12; +} + +void WK_BuildPacket_2401() { + if (WK_BIND_COUNTer) { + WK_BIND_COUNTer--; + build_bind_pkt(init_2401); + if ((WK_BIND_COUNTer == 0)) { + WK_BIND_COUNTer = 0; + BIND_DONE; + } + } + else { build_data_pkt_2401(); } + wk_pkt_num = (wk_pkt_num + 1) % 12; +} + +static uint16_t wk_cb() { + if (packet_sent == 0) { + packet_sent = 1; + if(sub_protocol == WK2801) { WK_BuildPacket_2801(); } + else if(sub_protocol == WK2601) { WK_BuildPacket_2601(); } + else if(sub_protocol == WK2401) { WK_BuildPacket_2401(); } + CYRF_WriteDataPacket(packet); + return 1600; + } + packet_sent = 0; + int i = 0; + while (! (CYRF_ReadRegister(0x04) & 0x02)) { if(++i > NUM_WAIT_LOOPS) { break; } } + if((wk_pkt_num & 0x03) == 0) { + radio_ch_ptr = radio_ch_ptr == &rx_tx_addr[2] ? rx_tx_addr : radio_ch_ptr + 1; + CYRF_ConfigRFChannel(*radio_ch_ptr); + //Keep transmit power updated + CYRF_WriteRegister(CYRF_03_TX_CFG, 0x28 | CYRF_HIGH_POWER); + } + return 1200; +} + +static void wk_bind() { + if((sub_protocol != WK2801)) { return; } + fixed_id = ((MProtocol_id_master << 2) & 0x0ffc00) | ((MProtocol_id_master >> 10) & 0x000300) | ((MProtocol_id_master) & 0x0000ff); + WK_BIND_COUNTer = WK_BIND_COUNT / 8 + 1; + BIND_IN_PROGRESS; +} + +static uint16_t wk_setup() { + CYRF_Reset(); + wk2x01_cyrf_init(); + CYRF_SetTxRxMode(TX_EN); + CYRF_FindBestChannels(rx_tx_addr, 3, 4, 4, 80); + + radio_ch_ptr = rx_tx_addr; + CYRF_ConfigRFChannel(*radio_ch_ptr); + + wk_pkt_num = 0; + packet_sent = 0; + last_beacon = 0; + fixed_id = ((MProtocol_id_master << 2) & 0x0ffc00) | ((MProtocol_id_master >> 10) & 0x000300) | ((MProtocol_id_master) & 0x0000ff); + if (sub_protocol == WK2401) { fixed_id |= 0x01; } //Fixed ID must be odd for 2401 + if(sub_protocol != WK2801) { + WK_BIND_COUNTer = WK_BIND_COUNT; + phase = WK_BIND; + BIND_IN_PROGRESS; + } + else { + phase = WK_BOUND_1; + WK_BIND_COUNTer = 0; + } + CYRF_ConfigRFChannel(*radio_ch_ptr); + return 2800; +} +/* +const void *WK2x01_Cmds(enum ProtoCmds cmd) { + switch(cmd) { + case PROTOCMD_INIT: initialize(); return 0; + case PROTOCMD_DEINIT: return 0; + case PROTOCMD_CHECK_AUTOBIND: + return (Model.protocol == WK2801 && Model.fixed_id) ? 0 : (void *)1L; + case PROTOCMD_BIND: wk_bind(); return 0; + case PROTOCMD_DEFAULT_NUMCHAN: return (Model.protocol == WK2801) + ? (void *)8L + : (Model.protocol == WK2601) + ? (void *)6L + : (void *)4L; + case PROTOCMD_NUMCHAN: return (Model.protocol == WK2801) + ? (void *)8L + : (Model.protocol == WK2601) + ? (void *)7L + : (void *)4L; + case PROTOCMD_GETOPTIONS: + if(Model.protocol == WK2601) + return wk2601_opts; + break; + case PROTOCMD_TELEMETRYSTATE: return (void *)(long)PROTO_TELEM_UNSUPPORTED; + default: break; + } + return 0; +} +*/ +#endif diff --git a/Multiprotocol/DSM2_cyrf6936.ino b/Multiprotocol/DSM2_cyrf6936.ino index e6769a6..928d24e 100644 --- a/Multiprotocol/DSM2_cyrf6936.ino +++ b/Multiprotocol/DSM2_cyrf6936.ino @@ -42,8 +42,7 @@ enum { DSM2_CH2_READ_B = BIND_COUNT1 + 10, }; - -const uint8_t pncodes[5][9][8] = { +const uint8_t PROGMEM pncodes[5][9][8] = { /* Note these are in order transmitted (LSB 1st) */ { /* Row 0 */ /* Col 0 */ {0x03, 0xBC, 0x6E, 0x8A, 0xEF, 0xBD, 0xFE, 0xF8}, @@ -102,6 +101,12 @@ const uint8_t pncodes[5][9][8] = { }, }; +static void __attribute__((unused)) read_code(uint8_t *buf, uint8_t row, uint8_t col, uint8_t len) +{ + for(uint8_t i=0;i. - */ +/* ************************** + * By Midelic on RCGroups * + ************************** + This project is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Multiprotocol is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with Multiprotocol. If not, see . +*/ #if defined(FRSKYX_CC2500_INO) + + #include "iface_cc2500.h" + + uint8_t chanskip; + uint8_t calData[48][3]; + uint8_t channr; + uint8_t pass_ = 1 ; + uint8_t counter_rst; + uint8_t ctr; + uint8_t FS_flag=0; + // uint8_t ptr[4]={0x01,0x12,0x23,0x30}; + //uint8_t ptr[4]={0x00,0x11,0x22,0x33}; + + const PROGMEM uint8_t hop_data[]={ + 0x02, 0xD4, 0xBB, 0xA2, 0x89, + 0x70, 0x57, 0x3E, 0x25, 0x0C, + 0xDE, 0xC5, 0xAC, 0x93, 0x7A, + 0x61, 0x48, 0x2F, 0x16, 0xE8, + 0xCF, 0xB6, 0x9D, 0x84, 0x6B, + 0x52, 0x39, 0x20, 0x07, 0xD9, + 0xC0, 0xA7, 0x8E, 0x75, 0x5C, + 0x43, 0x2A, 0x11, 0xE3, 0xCA, + 0xB1, 0x98, 0x7F, 0x66, 0x4D, + 0x34, 0x1B, 0x00, 0x1D, 0x03 + }; -#include "iface_cc2500.h" + uint8_t hop(uint8_t byte) + { + return pgm_read_byte_near(&hop_data[byte]); + } + uint16_t initFrSkyX() + { + while(!chanskip) + { + randomSeed((uint32_t)analogRead(A6) << 10 | analogRead(A7)); + chanskip=random(0xfefefefe)%47; + } + while((chanskip-ctr)%4) + ctr=(ctr+1)%4; + + counter_rst=(chanskip-ctr)>>2; + //for test*************** + //rx_tx_addr[3]=0xB3; + //rx_tx_addr[2]=0xFD; + //************************ + frskyX_init(); + // + if(IS_AUTOBIND_FLAG_on) + { + state = FRSKY_BIND; + initialize_data(1); + } + else + { + state = FRSKY_DATA1; + initialize_data(0); + } + return 10000; + } + + uint16_t ReadFrSkyX() + { + switch(state) + { + default: + set_start(47); + CC2500_SetPower(); + cc2500_strobe(CC2500_SFRX); + // + frskyX_build_bind_packet(); + cc2500_strobe(CC2500_SIDLE); + cc2500_writeFifo(packet, packet[0]+1); + state++; + return 9000; + case FRSKY_BIND_DONE: + initialize_data(0); + channr=0; + BIND_DONE; + state++; + break; + case FRSKY_DATA1: + LED_ON; + CC2500_SetTxRxMode(TX_EN); + set_start(channr); + CC2500_SetPower(); + cc2500_strobe(CC2500_SFRX); + channr = (channr+chanskip)%47; + cc2500_strobe(CC2500_SIDLE); + cc2500_writeFifo(packet, packet[0]+1); + // + frskyX_data_frame(); + state++; + return 5500; + case FRSKY_DATA2: + CC2500_SetTxRxMode(RX_EN); + cc2500_strobe(CC2500_SIDLE); + state++; + return 200; + case FRSKY_DATA3: + cc2500_strobe(CC2500_SRX); + state++; + return 3000; + case FRSKY_DATA4: + len = cc2500_readReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F; + if (len &&(len>8) & 0x0F)|(chan_1 << 4))); + packet[9+i+2]=crc_Byte(chan_1>>4); + } + //packet[21]=crc_Byte(0x08);//first + packet[21]=crc_Byte(0x80);//??? when received first telemetry frame is changed to 0x80 + //packet[21]=crc_Byte(ptr[p]);//??? + //p=(p+1)%4;//repeating 4 bytes sequence pattern every 4th frame. + + pass_=lpass+1; + + for (uint8_t i=22;i<28;i++) + packet[i]=crc_Byte(0); + + packet[28]=highByte(crc); + packet[29]=lowByte(crc); + } -#endif + uint16_t scaleForPXX( uint8_t i ) + { //mapped 860,2140(125%) range to 64,1984(PXX values); + return (uint16_t)(((Servo_data[i]-PPM_MIN)*3)>>1)+64; + } + + uint8_t crc_Byte( uint8_t byte ) + { + crc = (crc<<8) ^ pgm_read_word(&CRCTable[((uint8_t)(crc>>8) ^ byte) & 0xFF]); + return byte; + } +#endif \ No newline at end of file diff --git a/Multiprotocol/FrSky_cc2500.ino b/Multiprotocol/FrSky_cc2500.ino index dae03c7..f3c6d3c 100644 --- a/Multiprotocol/FrSky_cc2500.ino +++ b/Multiprotocol/FrSky_cc2500.ino @@ -20,7 +20,6 @@ //##########Variables######## //uint32_t state; //uint8_t len; -uint8_t telemetry_counter=0; /* enum { @@ -128,8 +127,6 @@ static void __attribute__((unused)) frsky2way_build_bind_packet() packet[17] = 0x01; } - - static void __attribute__((unused)) frsky2way_data_frame() {//pachet[4] is telemetry user frame counter(hub) //11 d7 2d 22 00 01 c9 c9 ca ca 88 88 ca ca c9 ca 88 88 @@ -138,7 +135,11 @@ static void __attribute__((unused)) frsky2way_data_frame() packet[1] = rx_tx_addr[3]; packet[2] = rx_tx_addr[2]; packet[3] = counter;// - packet[4]=telemetry_counter; + #if defined TELEMETRY + packet[4] = telemetry_counter; + #else + packet[4] = 0x00; + #endif packet[5] = 0x01; // diff --git a/Multiprotocol/MT99xx_nrf24l01.ino b/Multiprotocol/MT99xx_nrf24l01.ino index ab4c825..5e719ed 100644 --- a/Multiprotocol/MT99xx_nrf24l01.ino +++ b/Multiprotocol/MT99xx_nrf24l01.ino @@ -37,29 +37,16 @@ enum{ FLAG_MT_FLIP = 0x80, }; -enum{ - // flags going to ?????? (Yi Zhan i6S)ROLL - BLABLA, -}; - enum { MT99XX_INIT = 0, MT99XX_BIND, MT99XX_DATA }; -static uint8_t __attribute__((unused)) MT99XX_calcChecksum() -{ - uint8_t result=checksum_offset; - for(uint8_t i=0; i<8; i++) - result += packet[i]; - return result; -} - static void __attribute__((unused)) MT99XX_send_packet() { - static const uint8_t yz_p4_seq[] = {0xa0, 0x20, 0x60}; - static const uint8_t mys_byte[] = { + const uint8_t yz_p4_seq[] = {0xa0, 0x20, 0x60}; + const uint8_t mys_byte[] = { 0x01, 0x11, 0x02, 0x12, 0x03, 0x13, 0x04, 0x14, 0x05, 0x15, 0x06, 0x16, 0x07, 0x17, 0x00, 0x10 }; @@ -71,8 +58,8 @@ static void __attribute__((unused)) MT99XX_send_packet() packet[1] = convert_channel_8b_scale(RUDDER ,0x00,0xE1); // rudder packet[2] = convert_channel_8b_scale(AILERON ,0x00,0xE1); // aileron packet[3] = convert_channel_8b_scale(ELEVATOR,0x00,0xE1); // elevator - packet[4] = convert_channel_8b_scale(AUX5,0x00,0x3F); // pitch trim (0x3f-0x20-0x00) - packet[5] = convert_channel_8b_scale(AUX6,0x00,0x3F); // roll trim (0x00-0x20-0x3f) + packet[4] = 0x20; // pitch trim (0x3f-0x20-0x00) + packet[5] = 0x20; // roll trim (0x00-0x20-0x3f) packet[6] = GET_FLAG( Servo_AUX1, FLAG_MT_FLIP ) | GET_FLAG( Servo_AUX3, FLAG_MT_SNAPSHOT ) | GET_FLAG( Servo_AUX4, FLAG_MT_VIDEO ); @@ -84,7 +71,10 @@ static void __attribute__((unused)) MT99XX_send_packet() // low nibble: index in chan list ? // high nibble: 0->start from start of list, 1->start from end of list ? packet[7] = mys_byte[hopping_frequency_no]; - packet[8] = MT99XX_calcChecksum(); + uint8_t result=checksum_offset; + for(uint8_t i=0; i<8; i++) + result += packet[i]; + packet[8] = result; } else { // YZ @@ -100,8 +90,12 @@ static void __attribute__((unused)) MT99XX_send_packet() packet_count=0; } packet[4] = yz_p4_seq[yz_seq_num]; - packet[5] = 0x02; // expert ? (0=unarmed, 1=normal) - packet[6] = 0x80; + packet[5] = 0x02 // expert ? (0=unarmed, 1=normal) + | GET_FLAG(Servo_AUX4, 0x10) //VIDEO + | GET_FLAG(Servo_AUX1, 0x80) //FLIP + | GET_FLAG(Servo_AUX5, 0x04) //HEADLESS + | GET_FLAG(Servo_AUX3, 0x20); //SNAPSHOT + packet[6] = GET_FLAG(Servo_AUX2, 0x80); //LED packet[7] = packet[0]; for(uint8_t idx = 1; idx < MT99XX_PACKET_SIZE-2; idx++) packet[7] += packet[idx]; @@ -138,7 +132,10 @@ static void __attribute__((unused)) MT99XX_init() else NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps NRF24L01_SetPower(); - XN297_SetTXAddr((uint8_t *)"\0xCC\0xCC\0xCC\0xCC\0xCC", 5); + + XN297_Configure(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP) | (sub_protocol == YZ ? BV(XN297_UNSCRAMBLED):0) ); + + XN297_SetTXAddr((uint8_t *)"\xCC\xCC\xCC\xCC\xCC", 5); } static void __attribute__((unused)) MT99XX_initialize_txid() @@ -190,7 +187,7 @@ uint16_t initMT99XX(void) BIND_IN_PROGRESS; // autobind protocol bind_counter = MT99XX_BIND_COUNT; - memcpy(hopping_frequency,"\0x02\0x48\0x0C\0x3e\0x16\0x34\0x20\0x2A,\0x2A\0x20\0x34\0x16\0x3e\0x0c\0x48\0x02",16); + memcpy(hopping_frequency,"\x02\x48\x0C\x3e\x16\x34\x20\x2A\x2A\x20\x34\x16\x3e\x0c\x48\x02",16); MT99XX_initialize_txid(); MT99XX_init(); @@ -210,11 +207,11 @@ uint16_t initMT99XX(void) packet[2] = 0x05; packet[3] = 0x06; } - packet[4] = rx_tx_addr[0]; // 1th byte for data state tx address - packet[5] = rx_tx_addr[1]; // 2th byte for data state tx address (always 0x00 on Yi Zhan ?) - packet[6] = 0x00; // 3th byte for data state tx address (always 0x00 ?) + packet[4] = rx_tx_addr[0]; // 1st byte for data state tx address + packet[5] = rx_tx_addr[1]; // 2nd byte for data state tx address (always 0x00 on Yi Zhan ?) + packet[6] = 0x00; // 3rd byte for data state tx address (always 0x00 ?) packet[7] = checksum_offset; // checksum offset - packet[8] = 0xAA; // fixed + packet[8] = 0xAA; // fixed packet_count=0; return MT99XX_INITIAL_WAIT+MT99XX_PACKET_PERIOD_MT; } diff --git a/Multiprotocol/Multiprotocol.ino b/Multiprotocol/Multiprotocol.ino index e9fa9e6..46f6697 100644 --- a/Multiprotocol/Multiprotocol.ino +++ b/Multiprotocol/Multiprotocol.ino @@ -1,6 +1,7 @@ /********************************************************* Multiprotocol Tx code by Midelic and Pascal Langer(hpnuts) + fork by Tipouic http://www.rcgroups.com/forums/showthread.php?t=2165676 https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/edit/master/README.md @@ -29,7 +30,6 @@ #include "_Config.h" //Global constants/variables - uint32_t MProtocol_id;//tx id, uint32_t MProtocol_id_master; uint32_t Model_fixed_id=0; @@ -48,7 +48,7 @@ uint8_t Servo_AUX; // PPM variable volatile uint16_t PPM_data[NUM_CHN]; -// NRF variables +// Protocol variables uint8_t rx_tx_addr[5]; uint8_t phase; uint16_t bind_counter; @@ -65,6 +65,7 @@ uint8_t hopping_frequency_no=0; uint8_t rf_ch_num; uint8_t throttle, rudder, elevator, aileron; uint8_t flags; +uint16_t crc; // uint32_t state; uint8_t len; @@ -100,6 +101,7 @@ uint8_t pktt[MAX_PKT];//telemetry receiving packets int16_t RSSI_dBm; //const uint8_t RSSI_offset=72;//69 71.72 values db uint8_t telemetry_link=0; + uint8_t telemetry_counter=0; #endif // Callback @@ -313,6 +315,49 @@ static void protocol_init() switch(cur_protocol[0]&0x1F) // Init the requested protocol { +#if defined(HM830_NRF24L01_INO) + case MODE_HM830: + next_callback=HM830_setup(); + remote_callback = HM830_callback; + break; +#endif +#if defined(CFlie_NRF24L01_INO) + case MODE_CFLIE: + next_callback=Cflie_setup(); + remote_callback = cflie_callback; + break; +#endif +#if defined(JOYSWAY_A7105_INO) + case MODE_JOYSWAY: + next_callback=JOYSWAY_Setup(); + remote_callback = joysway_cb; + break; +#endif +#if defined(H377_NRF24L01_INO) + case MODE_H377: + next_callback=h377_setup(); + remote_callback = h377_cb; + break; +#endif +#if defined(J6PRO_CYRF6936_INO) + case MODE_J6PRO: + next_callback=j6pro_setup(); + remote_callback = j6pro_cb; + break; +#endif +#if defined(WK2x01_CYRF6936_INO) + case MODE_WK2x01: + next_callback=wk_setup(); + remote_callback = wk_cb; + break; +#endif +#if defined(FY326_NRF24L01_INO) + case MODE_FY326: + next_callback=FY326_setup(); + remote_callback = fy326_callback; + break; +#endif + #if defined(FLYSKY_A7105_INO) case MODE_FLYSKY: CTRL1_off; //antenna RF1 diff --git a/Multiprotocol/NRF24l01_SPI.ino b/Multiprotocol/NRF24l01_SPI.ino index c14f5d5..cec1439 100644 --- a/Multiprotocol/NRF24l01_SPI.ino +++ b/Multiprotocol/NRF24l01_SPI.ino @@ -257,6 +257,7 @@ uint8_t NRF24L01_packet_ack() /////////////// // XN297 emulation layer +uint8_t xn297_scramble_enabled; uint8_t xn297_addr_len; uint8_t xn297_tx_addr[5]; uint8_t xn297_rx_addr[5]; @@ -269,9 +270,16 @@ static const uint8_t xn297_scramble[] = { 0x1b, 0x5d, 0x19, 0x10, 0x24, 0xd3, 0xdc, 0x3f, 0x8e, 0xc5, 0x2f}; -static const uint16_t xn297_crc_xorout[] = { - 0x0000, 0x3448, 0x9BA7, 0x8BBB, 0x85E1, 0x3E8C, // 1st entry is missing, probably never needed - 0x451E, 0x18E6, 0x6B24, 0xE7AB, 0x3828, 0x814B, // it's used for 3-byte address w/ 0 byte payload only +const uint16_t PROGMEM xn297_crc_xorout[] = { + 0x0000, 0x3d5f, 0xa6f1, 0x3a23, 0xaa16, 0x1caf, + 0x62b2, 0xe0eb, 0x0821, 0xbe07, 0x5f1a, 0xaf15, + 0x4f0a, 0xad24, 0x5e48, 0xed34, 0x068c, 0xf2c9, + 0x1852, 0xdf36, 0x129d, 0xb17c, 0xd5f5, 0x70d7, + 0xb798, 0x5133, 0x67db, 0xd94e}; + +const uint16_t PROGMEM xn297_crc_xorout_scrambled[] = { + 0x0000, 0x3448, 0x9BA7, 0x8BBB, 0x85E1, 0x3E8C, + 0x451E, 0x18E6, 0x6B24, 0xE7AB, 0x3828, 0x814B, 0xD461, 0xF494, 0x2503, 0x691D, 0xFE8B, 0x9BA7, 0x8B17, 0x2920, 0x8B5F, 0x61B1, 0xD391, 0x7401, 0x2138, 0x129F, 0xB3A0, 0x2988}; @@ -327,16 +335,21 @@ void XN297_SetRXAddr(const uint8_t* addr, uint8_t len) memcpy(buf, addr, len); memcpy(xn297_rx_addr, addr, len); for (uint8_t i = 0; i < xn297_addr_len; ++i) - buf[i] = xn297_rx_addr[i] ^ xn297_scramble[xn297_addr_len-i-1]; + { + buf[i] = xn297_rx_addr[i]; + if(xn297_scramble_enabled) + buf[i] ^= xn297_scramble[xn297_addr_len-i-1]; + } NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, len-2); NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, buf, 5); } -void XN297_Configure(uint8_t flags) +void XN297_Configure(uint16_t flags) { + xn297_scramble_enabled = !(flags & BV(XN297_UNSCRAMBLED)); xn297_crc = !!(flags & BV(NRF24L01_00_EN_CRC)); flags &= ~(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO)); - NRF24L01_WriteReg(NRF24L01_00_CONFIG, flags); + NRF24L01_WriteReg(NRF24L01_00_CONFIG, flags & 0xFF); } void XN297_WritePayload(uint8_t* msg, uint8_t len) @@ -352,12 +365,20 @@ void XN297_WritePayload(uint8_t* msg, uint8_t len) buf[last++] = 0x55; } for (uint8_t i = 0; i < xn297_addr_len; ++i) - buf[last++] = xn297_tx_addr[xn297_addr_len-i-1] ^ xn297_scramble[i]; - - for (uint8_t i = 0; i < len; ++i) { + { + buf[last] = xn297_tx_addr[xn297_addr_len-i-1]; + if(xn297_scramble_enabled) + buf[last] ^= xn297_scramble[i]; + last++; + } + for (uint8_t i = 0; i < len; ++i) + { // bit-reverse bytes in packet uint8_t b_out = bit_reverse(msg[i]); - buf[last++] = b_out ^ xn297_scramble[xn297_addr_len+i]; + buf[last] = b_out; + if(xn297_scramble_enabled) + buf[last] ^= xn297_scramble[xn297_addr_len+i]; + last++; } if (xn297_crc) { @@ -365,7 +386,10 @@ void XN297_WritePayload(uint8_t* msg, uint8_t len) uint16_t crc = 0xb5d2; for (uint8_t i = offset; i < last; ++i) crc = crc16_update(crc, buf[i]); - crc ^= xn297_crc_xorout[xn297_addr_len - 3 + len]; + if(xn297_scramble_enabled) + crc ^= pgm_read_word(&xn297_crc_xorout_scrambled[xn297_addr_len - 3 + len]); + else + crc ^= pgm_read_word(&xn297_crc_xorout[xn297_addr_len - 3 + len]); buf[last++] = crc >> 8; buf[last++] = crc & 0xff; } @@ -374,9 +398,14 @@ void XN297_WritePayload(uint8_t* msg, uint8_t len) void XN297_ReadPayload(uint8_t* msg, uint8_t len) { + // TODO: if xn297_crc==1, check CRC before filling *msg NRF24L01_ReadPayload(msg, len); for(uint8_t i=0; i. + */ + +/* NB: Not implemented + Uncomment define below to enable telemetry. Also add CFlie protocol to TELEMETRY_SetTypeByProtocol to set type to DSM. +#define CFLIE_TELEMETRY + */ + + +#if defined(CFlie_NRF24L01_INO) +#include "iface_nrf24l01.h" + +#define BIND_COUNT 60 + +// Address size +#define TX_ADDR_SIZE 5 + +// Timeout for callback in uSec, 10ms=10000us for Crazyflie +#define PACKET_PERIOD 10000 + + +// For code readability +enum { + CHANNEL1 = 0, + CHANNEL2, + CHANNEL3, + CHANNEL4, + CHANNEL5, + CHANNEL6, + CHANNEL7, + CHANNEL8, + CHANNEL9, + CHANNEL10 +}; + +#define PAYLOADSIZE 8 // receive data pipes set to this size, but unused +#define MAX_PACKET_SIZE 9 // YD717 packets have 8-byte payload, Syma X4 is 9 + +//static uint8_t packet[MAX_PACKET_SIZE]; + +static uint8_t data_rate, rf_channel; + +enum { + CFLIE_INIT_SEARCH = 0, + CFLIE_INIT_DATA, + CFLIE_SEARCH, + CFLIE_DATA +}; + +#ifdef CFLIE_TELEMETRY +static const char * const cflie_opts[] = { + _tr_noop("Telemetry"), _tr_noop("Off"), _tr_noop("On"), NULL, + NULL +}; +enum { + PROTOOPTS_TELEMETRY = 0, + LAST_PROTO_OPT, +}; +ctassert(LAST_PROTO_OPT <= NUM_PROTO_OPTS, too_many_protocol_opts); + +#define TELEM_OFF 0 +#define TELEM_ON 1 +#endif + +#define PACKET_CHKTIME 500 // time to wait if packet not yet acknowledged or timed out + +static uint16_t dbg_cnt = 0; +static uint8_t packet_ack() { + if (++dbg_cnt > 50) { dbg_cnt = 0; } + switch (NRF24L01_ReadReg(NRF24L01_07_STATUS) & (BV(NRF24L01_07_TX_DS) | BV(NRF24L01_07_MAX_RT))) { + case BV(NRF24L01_07_TX_DS): + return PKT_ACKED; + case BV(NRF24L01_07_MAX_RT): + return PKT_TIMEOUT; + } + return PKT_PENDING; +} + +static void set_rate_channel(uint8_t rate, uint8_t channel) { + NRF24L01_WriteReg(NRF24L01_05_RF_CH, channel); // Defined by model id + NRF24L01_SetBitrate(rate); // Defined by model id +} + +static void send_search_packet() { + uint8_t buf[1]; + buf[0] = 0xff; + // clear packet status bits and TX FIFO + NRF24L01_WriteReg(NRF24L01_07_STATUS, (BV(NRF24L01_07_TX_DS) | BV(NRF24L01_07_MAX_RT))); + NRF24L01_FlushTx(); + + if (rf_channel++ > 125) { + rf_channel = 0; + switch(data_rate) { + case NRF24L01_BR_250K: + data_rate = NRF24L01_BR_1M; + break; + case NRF24L01_BR_1M: + data_rate = NRF24L01_BR_2M; + break; + case NRF24L01_BR_2M: + data_rate = NRF24L01_BR_250K; + break; + } + } + + set_rate_channel(data_rate, rf_channel); + + NRF24L01_WritePayload(buf, sizeof(buf)); + + ++packet_counter; +} + +// Frac 16.16 +#define FRAC_MANTISSA 16 +#define FRAC_SCALE (1 << FRAC_MANTISSA) + +// Convert fractional 16.16 to float32 +static void frac2float(uint32_t n, float* res) { + if (n == 0) { + *res = 0.0; + return; + } + uint32_t m = n < 0 ? -n : n; + int i; + for (i = (31-FRAC_MANTISSA); (m & 0x80000000) == 0; i--, m <<= 1) ; + m <<= 1; // Clear implicit leftmost 1 + m >>= 9; + uint32_t e = 127 + i; + if (n < 0) m |= 0x80000000; + m |= e << 23; + *((uint32_t *) res) = m; +} + +static void send_cmd_packet() { + // Commander packet, 15 bytes + uint8_t buf[15]; + float x_roll, x_pitch, yaw; + + // Channels in AETR order + + // Roll, aka aileron, float +- 50.0 in degrees + // float roll = -(float) Servo_data[AILERON]*50.0/10000; + uint32_t f_roll = -Servo_data[AILERON] * FRAC_SCALE / (10000 / 50); + + // Pitch, aka elevator, float +- 50.0 degrees + //float pitch = -(float) Servo_data[ELEVATOR]*50.0/10000; + uint32_t f_pitch = -Servo_data[ELEVATOR] * FRAC_SCALE / (10000 / 50); + + // Thrust, aka throttle 0..65535, working range 5535..65535 + // No space for overshoot here, hard limit Channel3 by -10000..10000 + uint32_t ch = Servo_data[THROTTLE]; + if (ch < PPM_MIN) { + ch = PPM_MIN; + } else if (ch > PPM_MAX) { + ch = PPM_MAX; + } + uint16_t thrust = ch*3L + 35535L; + + // Yaw, aka rudder, float +- 400.0 deg/s + // float yaw = -(float) Servo_data[RUDDER]*400.0/10000; + uint32_t f_yaw = - Servo_data[RUDDER] * FRAC_SCALE / (10000 / 400); + frac2float(f_yaw, &yaw); + + // Convert + to X. 181 / 256 = 0.70703125 ~= sqrt(2) / 2 + uint32_t f_x_roll = (f_roll + f_pitch) * 181 / 256; + frac2float(f_x_roll, &x_roll); + uint32_t f_x_pitch = (f_pitch - f_roll) * 181 / 256; + frac2float(f_x_pitch, &x_pitch); + + int bufptr = 0; + buf[bufptr++] = 0x30; // Commander packet to channel 0 + memcpy(&buf[bufptr], (char*) &x_roll, 4); bufptr += 4; + memcpy(&buf[bufptr], (char*) &x_pitch, 4); bufptr += 4; + memcpy(&buf[bufptr], (char*) &yaw, 4); bufptr += 4; + memcpy(&buf[bufptr], (char*) &thrust, 2); bufptr += 2; + + + // clear packet status bits and TX FIFO + NRF24L01_WriteReg(NRF24L01_07_STATUS, (BV(NRF24L01_07_TX_DS) | BV(NRF24L01_07_MAX_RT))); + NRF24L01_FlushTx(); + + NRF24L01_WritePayload(buf, sizeof(buf)); + + ++packet_counter; + + NRF24L01_SetPower(); +} + +static int cflie_init() { + NRF24L01_Initialize(); + + // CRC, radio on + NRF24L01_SetTxRxMode(TX_EN); + NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP)); + // NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowledgement + NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x01); // Auto Acknowledgement for data pipe 0 + NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 + NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, TX_ADDR_SIZE-2); // 5-byte RX/TX address + NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x13); // 3 retransmits, 500us delay + + NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_channel); // Defined by model id + NRF24L01_SetBitrate(data_rate); // Defined by model id + + NRF24L01_SetPower(); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit + + NRF24L01_WriteReg(NRF24L01_17_FIFO_STATUS, 0x00); // Just in case, no real bits to write here + + // this sequence necessary for module from stock tx + NRF24L01_ReadReg(NRF24L01_1D_FEATURE); + NRF24L01_Activate(0x73); // Activate feature register + NRF24L01_ReadReg(NRF24L01_1D_FEATURE); + + NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x01); // Enable Dynamic Payload Length on pipe 0 + NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x06); // Enable Dynamic Payload Length, enable Payload with ACK + + + // NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, TX_ADDR_SIZE); + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, TX_ADDR_SIZE); + + NRF24L01_Activate(0x53); // switch bank back + + // 50ms delay in callback + return 50000; +} + + +#ifdef CFLIE_TELEMETRY +static void update_telemetry() { + static uint8_t frameloss = 0; + + frameloss += NRF24L01_ReadReg(NRF24L01_08_OBSERVE_TX) >> 4; + NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_channel); // reset packet loss counter + + Telemetry.p.dsm.flog.frameloss = frameloss; +// Telemetry.p.dsm.flog.volt[0] = read battery voltage from ack payload + TELEMETRY_SetUpdated(TELEM_DSM_FLOG_FRAMELOSS); +} +#endif + + +static uint16_t cflie_callback() { + switch (phase) { + case CFLIE_INIT_SEARCH: + send_search_packet(); + phase = CFLIE_SEARCH; + break; + case CFLIE_INIT_DATA: + send_cmd_packet(); + phase = CFLIE_DATA; + break; + case CFLIE_SEARCH: + switch (packet_ack()) { + case PKT_PENDING: + return PACKET_CHKTIME; // packet send not yet complete + case PKT_ACKED: + phase = CFLIE_DATA; + BIND_DONE; + break; + case PKT_TIMEOUT: + send_search_packet(); + counter = BIND_COUNT; + } + break; + case CFLIE_DATA: + #ifdef CFLIE_TELEMETRY + update_telemetry(); + #endif + if (packet_ack() == PKT_PENDING) + return PACKET_CHKTIME; // packet send not yet complete + send_cmd_packet(); + break; + } + return PACKET_PERIOD; // Packet at standard protocol interval +} + + +// Generate address to use from TX id and manufacturer id (STM32 unique id) +static uint8_t initialize_rx_tx_addr() { + rx_tx_addr[0] = + rx_tx_addr[1] = + rx_tx_addr[2] = + rx_tx_addr[3] = + rx_tx_addr[4] = 0xE7; // CFlie uses fixed address + + data_rate = NRF24L01_BR_250K; + rf_channel = 0; + return CFLIE_INIT_SEARCH; + // return CFLIE_INIT_DATA; +} + +static uint16_t Cflie_setup() { + phase = initialize_rx_tx_addr(); + packet_counter = 0; + + int delay = cflie_init(); + + #ifdef CFLIE_TELEMETRY + memset(&Telemetry, 0, sizeof(Telemetry)); + TELEMETRY_SetType(TELEM_DSM); + #endif + if (phase == CFLIE_INIT_SEARCH) { BIND_IN_PROGRESS; } + return delay; +} + +#endif diff --git a/Multiprotocol/Nrf24l01_fy326.ino b/Multiprotocol/Nrf24l01_fy326.ino new file mode 100644 index 0000000..5fe0a92 --- /dev/null +++ b/Multiprotocol/Nrf24l01_fy326.ino @@ -0,0 +1,234 @@ +/* + This project is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Deviation is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with Deviation. If not, see . + */ + + +#if defined(FY326_NRF24L01_INO) +#include "iface_nrf24l01.h" + +#define INITIAL_WAIT 500 +#define FY326_PERIOD 1500 // Timeout for callback in uSec +#define FY326_CHKTIME 300 // Time to wait if packet not yet received or sent +#define FY326_SIZE 15 +#define FY326_BIND_COUNT 16 + + +static const char * const fy326_opts[] = { + _tr_noop("Expert"), _tr_noop("On"), _tr_noop("Off"), NULL, + NULL +}; +#define EXPERT_ON 0 +#define EXPERT_OFF 1 + +#define CHANNEL_FLIP AUX1 +#define CHANNEL_HEADLESS AUX2 +#define CHANNEL_RTH AUX3 +#define CHANNEL_CALIBRATE AUX4 + +static uint8_t tx_power; +static uint8_t packet[FY326_SIZE]; + +// frequency channel management +#define RF_BIND_CHANNEL 0x17 +#define NUM_RF_CHANNELS 5 +static uint8_t current_chan; +static uint8_t rf_chans[NUM_RF_CHANNELS]; +static uint8_t txid[5]; +static uint8_t rxid; + +enum { + FY326_INIT1 = 0, + FY326_BIND1, + FY326_BIND2, + FY326_DATA +}; + +// Bit vector from bit position +#define BV(bit) (1 << bit) + +#define CHAN_RANGE (CHAN_MAX_VALUE - CHAN_MIN_VALUE) +static uint8_t scale_channel(uint8_t ch, uint8_t destMin, uint8_t destMax) +{ + uint32_t chanval = Channels[ch]; + uint32_t range = destMax - destMin; + + if (chanval < CHAN_MIN_VALUE) chanval = CHAN_MIN_VALUE; + else if (chanval > CHAN_MAX_VALUE) chanval = CHAN_MAX_VALUE; + return (range * (chanval - CHAN_MIN_VALUE)) / CHAN_RANGE + destMin; +} + +#define GET_FLAG(ch, mask) (Channels[ch] > 0 ? mask : 0) +#define CHAN_TO_TRIM(chanval) ((uint8_t)(((uint16_t)chanval/10)-10)) // scale to [-10,10]. [-20,20] caused problems. +static void send_packet(uint8_t bind) +{ + packet[0] = txid[3]; + if (bind) { + packet[1] = 0x55; + } else { + packet[1] = GET_FLAG(CHANNEL_HEADLESS, 0x80) + | GET_FLAG(CHANNEL_RTH, 0x40) + | GET_FLAG(CHANNEL_FLIP, 0x02) + | GET_FLAG(CHANNEL_CALIBRATE, 0x01) + | (Model.proto_opts[PROTOOPTS_EXPERT] == EXPERT_ON ? 4 : 0); + } + packet[2] = 200 - scale_channel(AILERON, 0, 200); // aileron + packet[3] = scale_channel(ELEVATOR, 0, 200); // elevator + packet[4] = 200 - scale_channel(RUDDER, 0, 200); // rudder + packet[5] = scale_channel(THROTTLE, 0, 200); // throttle + packet[6] = txid[0]; + packet[7] = txid[1]; + packet[8] = txid[2]; + packet[9] = CHAN_TO_TRIM(packet[2]); // aileron_trim; + packet[10] = CHAN_TO_TRIM(packet[3]); // elevator_trim; + packet[11] = CHAN_TO_TRIM(packet[4]); // rudder_trim; + packet[12] = 0; // throttle_trim; + packet[13] = rxid; + packet[14] = txid[4]; + + if (bind) { + NRF24L01_WriteReg(NRF24L01_05_RF_CH, RF_BIND_CHANNEL); + } else { + NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_chans[current_chan++]); + current_chan %= NUM_RF_CHANNELS; + } + + // clear packet status bits and TX FIFO + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); + NRF24L01_FlushTx(); + + NRF24L01_WritePayload(packet, FY326_SIZE); + + // Check and adjust transmission power. We do this after + // transmission to not bother with timeout after power + // settings change - we have plenty of time until next + // packet. + if (tx_power != Model.tx_power) { + //Keep transmit power updated + tx_power = Model.tx_power; + NRF24L01_SetPower(tx_power); + } +} + +static void fy326_init() +{ + const uint8_t rx_tx_addr[] = {0x15, 0x59, 0x23, 0xc6, 0x29}; + + NRF24L01_Initialize(); + NRF24L01_SetTxRxMode(TX_EN); + NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x01); // Three-byte rx/tx address + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, sizeof(rx_tx_addr)); + NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, sizeof(rx_tx_addr)); + NRF24L01_FlushTx(); + NRF24L01_FlushRx(); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit + NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowldgement on all data pipes + NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only + NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, FY326_SIZE); + NRF24L01_WriteReg(NRF24L01_05_RF_CH, RF_BIND_CHANNEL); + NRF24L01_SetBitrate(NRF24L01_BR_250K); + NRF24L01_SetPower(Model.tx_power); + + NRF24L01_Activate(0x73); + NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x3f); + NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x07); +} + +static uint16_t fy326_callback() +{ + switch (phase) { + case FY326_INIT1: + MUSIC_Play(MUSIC_TELEMALARM1); + bind_counter = FY326_BIND_COUNT; + phase = FY326_BIND2; + send_packet(1); + return FY326_CHKTIME; + break; + + case FY326_BIND1: +#ifdef EMULATOR + if (1) { + packet[13] = 0x7e; +#else + if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_RX_DR)) { // RX fifo data ready + NRF24L01_ReadPayload(packet, FY326_SIZE); +#endif + rxid = packet[13]; + txid[0] = 0xaa; + NRF24L01_SetTxRxMode(TXRX_OFF); + NRF24L01_SetTxRxMode(TX_EN); + PROTOCOL_SetBindState(0); + MUSIC_Play(MUSIC_DONE_BINDING); + phase = FY326_DATA; + } else if (bind_counter-- == 0) { + bind_counter = FY326_BIND_COUNT; + NRF24L01_SetTxRxMode(TXRX_OFF); + NRF24L01_SetTxRxMode(TX_EN); + send_packet(1); + phase = FY326_BIND2; + return FY326_CHKTIME; + } + break; + + case FY326_BIND2: +#ifdef EMULATOR + if (1) { +#else + if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_TX_DS)) { // TX data sent +#endif + // switch to RX mode + NRF24L01_SetTxRxMode(TXRX_OFF); + NRF24L01_FlushRx(); + NRF24L01_SetTxRxMode(RX_EN); + phase = FY326_BIND1; + } else { + return FY326_CHKTIME; + } + break; + + case FY326_DATA: + send_packet(0); + break; + } + return FY326_PERIOD; +} + +// Generate address to use from TX id and manufacturer id (STM32 unique id) +static void fy_txid() +{ + txid[0] = (MProtocol_id_master >> 24) & 0xFF; + txid[1] = ((MProtocol_id_master >> 16) & 0xFF); + txid[2] = (MProtocol_id_master >> 8) & 0xFF; + txid[3] = MProtocol_id_master & 0xFF; + for (uint8_t i = 0; i < sizeof(MProtocol_id_master); ++i) rand32_r(&MProtocol_id_master, 0); + txid[4] = MProtocol_id_master & 0xFF; + + rf_chans[0] = txid[0] & 0x0F; + rf_chans[1] = 0x10 + (txid[0] >> 4); + rf_chans[2] = 0x20 + (txid[1] & 0x0F); + rf_chans[3] = 0x30 + (txid[1] >> 4); + rf_chans[4] = 0x40 + (txid[2] >> 4); +} + +static uint16_t FY326_setup() +{ + BIND_IN_PROGRESS; + tx_power = Model.tx_power; + rxid = 0xaa; + phase = FY326_INIT1; + bind_counter = FY326_BIND_COUNT; + fy_txid(); + fy326_init(); + return INITIAL_WAIT; +} +#endif diff --git a/Multiprotocol/Nrf24l01_h377.ino b/Multiprotocol/Nrf24l01_h377.ino new file mode 100644 index 0000000..e8feaf3 --- /dev/null +++ b/Multiprotocol/Nrf24l01_h377.ino @@ -0,0 +1,210 @@ +/* +This project is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +Deviation is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with Deviation. If not, see . +*/ + +#if defined (H377_NRF24L01_INO) +#include "iface_nrf24l01.h" + +#define BIND_COUNT 800 + + +#define TXID_H377_SIZE 5 + +#define FREQUENCE_NUM_H377 20 +#define SET_NUM_H377 9 +// available frequency must be in between 2402 and 2477 + +static uint8_t binding_ch=0x50; +static uint8_t hopping_frequency_data[SET_NUM_H377] = {0x1c,0x1b,0x1d,0x11,0x0e,0x0d,0x01,0x1d,0x15}; + +static const uint8_t binding_adr_rf[5]={0x32,0xaa,0x45,0x45,0x78}; + +static uint8_t rf_adr_buf[5]; +static uint8_t rf_adr_buf_data[SET_NUM_H377][5] = { + {0xad,0x9a,0xa6,0x69,0xb2},//ansheng + {0x92,0x9a,0x9d,0x69,0x99},//dc59 + {0x92,0xb2,0x9d,0x69,0x9a},//small two + {0xad,0x9a,0x5a,0x69,0x96},//james_1 + {0x95,0x9a,0x52,0x69,0x99},//james_2 + {0x52,0x52,0x52,0x69,0xb9},//james_3 + {0x52,0x52,0x52,0x52,0x55},//small two_1 + {0x92,0xB2,0x9D,0x69,0x9A},//small two_2 + {0x96,0x9A,0x45,0x69,0xB2}//small two_3 +}; + +static uint8_t bind_buf_array[10]; +static uint8_t bind_buf_array_data[SET_NUM_H377][4] = { + {0xcf,0x1c,0x19,0x1a}, + {0xff,0x48,0x19,0x19}, + {0xf3,0x4d,0x19,0x19}, + {0x9e,0x1f,0x19,0x19}, + {0x8d,0x3d,0x19,0x19}, + {0xbd,0x23,0x19,0x19}, + {0xF3,0x28,0x19,0x19}, + {0xF3,0x4D,0x19,0x19}, + {0x82,0x8D,0x19,0x19} +}; + + +static unsigned int ch_data[8]; +static uint8_t payload[10]; +static uint8_t counter1ms; + +static int select_ch_id = 0; + +static void h377_binding_packet(void) { //bind_buf_array + uint8_t i; + counter1ms = 0; + hopping_frequency_no = 0; + + for(i=0;i<5;i++) + bind_buf_array[i] = rf_adr_buf[i]; + + bind_buf_array[5] = hopping_frequency[0]; + + for(i=0;i<4;i++) + bind_buf_array[i+6] = bind_buf_array_data[select_ch_id][i]; +} + +static void h377_init() { + NRF24L01_Initialize(); + + NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable p0 rx + NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknoledgement + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rf_adr_buf, 5); + NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rf_adr_buf, 5); + NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, 10); // payload size = 10 + //NRF24L01_WriteReg(NRF24L01_05_RF_CH, 81); // binding packet must be set in channel 81 + NRF24L01_WriteReg(NRF24L01_05_RF_CH, binding_ch); // binding packet must be set in channel 81 + + // 2-bytes CRC, radio off + NRF24L01_SetTxRxMode(TX_EN); + NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP)); + NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5-byte RX/TX address (byte -2) + NRF24L01_SetBitrate(0); // 1Mbps + NRF24L01_SetPower(); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit +} + +// H377 channel sequence: AILE ELEV THRO RUDD GEAR PITH, channel data value is from 0 to 1000 +static void h377_ch_data() { + uint32_t temp; + uint8_t i; + for (i = 0; i< 8; i++) { + temp = (uint32_t)Servo_data[i] * 450/PPM_MAX + 500; // max/min servo range is +-125% + if (i == 2) // It is clear that h377's thro stick is made reversely, so I adjust it here on purpose + temp = 1000 -temp; + //if (i == 0) // It is clear that h377's thro stick is made reversely, so I adjust it here on purpose + // temp = 1000 -temp; + //if (i == 1) // It is clear that h377's thro stick is made reversely, so I adjust it here on purpose + // temp = 1000 -temp; + if (temp < 0) + ch_data[i] = 0; + else if (temp > 1000) + ch_data[i] = 1000; + else + ch_data[i] = (unsigned int)temp; + payload[i] = (uint8_t)ch_data[i]; + } + payload[8] = (uint8_t)((ch_data[0]>>8)&0x0003); + payload[8] |= (uint8_t)((ch_data[1]>>6)&0x000c); + payload[8] |= (uint8_t)((ch_data[2]>>4)&0x0030); + payload[8] |= (uint8_t)((ch_data[3]>>2)&0x00c0); + + payload[9] = (uint8_t)((ch_data[4]>>8)&0x0003); + payload[9] |= (uint8_t)((ch_data[5]>>6)&0x000c); + payload[9] |= (uint8_t)((ch_data[6]>>4)&0x0030); + payload[9] |= (uint8_t)((ch_data[7]>>2)&0x00c0); +} + +static uint16_t h377_cb() { + counter1ms++; + if(counter1ms==1) { NRF24L01_FlushTx(); } + //------------------------- + else if(counter1ms==2) { + if (counter>0) { + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t *)binding_adr_rf, 5); + NRF24L01_WriteReg(NRF24L01_05_RF_CH, binding_ch); + } + } + else if(counter1ms==3) { + if (counter >0) { + counter--; + if (! counter) { BIND_DONE; } // binding finished, change tx add + NRF24L01_WritePayload(bind_buf_array,10); + } + } + else if (counter1ms==4) { if (counter > 0) { NRF24L01_FlushTx(); }} + //------------------------- + else if(counter1ms==5) { NRF24L01_SetPower(); } + //------------------------- + else if (counter1ms == 6) { + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rf_adr_buf, 5); + NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no]); + hopping_frequency_no++; + if (hopping_frequency_no >= FREQUENCE_NUM_H377) { hopping_frequency_no = 0; } + } + else if (counter1ms == 7) { h377_ch_data(); } + else if(counter1ms>8) { + counter1ms = 0; + NRF24L01_WritePayload(payload,10); + } + return 1000; // send 1 binding packet and 1 data packet per 9ms +} + +// Linear feedback shift register with 32-bit Xilinx polinomial x^32 + x^22 + x^2 + x + 1 +static const uint32_t LFSR_FEEDBACK = 0x80200003ul; +static const uint32_t LFSR_INTAP = 32-1; + +static void update_lfsr(uint32_t *lfsr, uint8_t b) { + for (int i = 0; i < 8; ++i) { + *lfsr = (*lfsr >> 1) ^ ((-(*lfsr & 1u) & LFSR_FEEDBACK) ^ ~((uint32_t)(b & 1) << LFSR_INTAP)); + b >>= 1; + } +} + +// Generate internal id from TX id and manufacturer id (STM32 unique id) + + +static void H377_tx_id() { + for(int i=0;i<5;i++) + rf_adr_buf[i] = rf_adr_buf_data[select_ch_id][i]; + + hopping_frequency[0] = hopping_frequency_data[select_ch_id]; + + for (int i = 1; i < FREQUENCE_NUM_H377; i++) { + hopping_frequency[i] = hopping_frequency[i-1] + 3; + } +} + + + +static uint16_t h377_setup() { + select_ch_id = MProtocol_id_master%SET_NUM_H377; + + H377_tx_id();//rf_adr_buf hopping_frequency + + h377_binding_packet();//bind_buf_array (rf_adr_buf hopping_frequency) + + h377_init(); + + if(IS_AUTOBIND_FLAG_on) { + counter = BIND_COUNT; + BIND_IN_PROGRESS; + } + else { counter = 0; } + + return 1000; +} +#endif diff --git a/Multiprotocol/Nrf24l01_hm830.ino b/Multiprotocol/Nrf24l01_hm830.ino new file mode 100644 index 0000000..bb30d3a --- /dev/null +++ b/Multiprotocol/Nrf24l01_hm830.ino @@ -0,0 +1,267 @@ +/* + This project is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. + Deviation is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. + You should have received a copy of the GNU General Public License along with Deviation. If not, see . + */ + +/* This protocol is for the HM Hobby HM830 RC Paper Airplane + Protocol spec: + Channel data: + AA BB CC DD EE FF GG + AA : Throttle Min=0x00 max =0x64 + BB : + bit 0,1,2: Left/Right magnitude, bit 5 Polarity (set = right) + bit 6: Accelerate + bit 7: Right button (also the ABC Button) + CC : bit 0 seems to be impacted by the Right button + DD + EE + FF : Trim (bit 0-5: Magnitude, bit 6 polarity (set = right) + GG : Checksum (CRC8 on bytes AA-FF), init = 0xa5, poly = 0x01 +*/ + +#ifdef HM830_NRF24L01_INO + +#include "iface_nrf24l01.h" + +enum { + HM830_BIND1A = 0, + HM830_BIND2A, + HM830_BIND3A, + HM830_BIND4A, + HM830_BIND5A, + HM830_BIND6A, + HM830_BIND7A, + HM830_DATA1, + HM830_DATA2, + HM830_DATA3, + HM830_DATA4, + HM830_DATA5, + HM830_DATA6, + HM830_DATA7, + HM830_BIND1B = 0x80, + HM830_BIND2B, + HM830_BIND3B, + HM830_BIND4B, + HM830_BIND5B, + HM830_BIND6B, + HM830_BIND7B, +}; + +static uint8_t init_vals_hm830[][2] = { + {NRF24L01_17_FIFO_STATUS, 0x00}, + {NRF24L01_16_RX_PW_P5, 0x07}, + {NRF24L01_15_RX_PW_P4, 0x07}, + {NRF24L01_14_RX_PW_P3, 0x07}, + {NRF24L01_13_RX_PW_P2, 0x07}, + {NRF24L01_12_RX_PW_P1, 0x07}, + {NRF24L01_11_RX_PW_P0, 0x07}, + {NRF24L01_0F_RX_ADDR_P5, 0xC6}, + {NRF24L01_0E_RX_ADDR_P4, 0xC5}, + {NRF24L01_0D_RX_ADDR_P3, 0xC4}, + {NRF24L01_0C_RX_ADDR_P2, 0xC3}, + {NRF24L01_09_CD, 0x00}, + {NRF24L01_08_OBSERVE_TX, 0x00}, + {NRF24L01_07_STATUS, 0x07}, +// {NRF24L01_06_RF_SETUP, 0x07}, + {NRF24L01_05_RF_CH, 0x18}, + {NRF24L01_04_SETUP_RETR, 0x3F}, + {NRF24L01_03_SETUP_AW, 0x03}, + {NRF24L01_02_EN_RXADDR, 0x3F}, + {NRF24L01_01_EN_AA, 0x3F}, + {NRF24L01_00_CONFIG, 0x0E}, +}; + +static uint8_t count; +static uint8_t rf_ch[] = {0x08, 0x35, 0x12, 0x3f, 0x1c, 0x49, 0x26}; +static uint8_t bind_addr[] = {0xaa, 0xbb, 0xcc, 0xdd, 0xee, 0xc2}; + +static uint8_t crc8(uint32_t result, uint8_t *data, int len) { + int polynomial = 0x01; + for(int i = 0; i < len; i++) { + result = result ^ data[i]; + for(int j = 0; j < 8; j++) { + if(result & 0x80) { result = (result << 1) ^ polynomial; } + else { result = result << 1; } + } + } + return result & 0xff; +} + +static void HM830_init() { + NRF24L01_Initialize(); + for (uint32_t i = 0; i < sizeof(init_vals_hm830) / sizeof(init_vals_hm830[0]); i++) { NRF24L01_WriteReg(init_vals_hm830[i][0], init_vals_hm830[i][1]); } + + NRF24L01_SetTxRxMode(TX_EN); + NRF24L01_SetBitrate(0); + NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, bind_addr, 5); + NRF24L01_WriteRegisterMulti(NRF24L01_0B_RX_ADDR_P1, bind_addr+1, 5); + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, bind_addr, 5); + NRF24L01_Activate(0x73); //Enable FEATURE + NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x07); + NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x3F); + //NRF24L01_ReadReg(NRF24L01_07_STATUS) ==> 0x07 + + NRF24L01_Activate(0x53); // switch bank back + + NRF24L01_FlushTx(); + //NRF24L01_ReadReg(NRF24L01_07_STATUS) ==> 0x0e + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x0e); + //NRF24L01_ReadReg(NRF24L01_00_CONFIG); ==> 0x0e + NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x0e); + NRF24L01_ReadReg(NRF24L01_01_EN_AA); // No Auto Acknoledgement +} + +static void build_bind_packet_hm830() { + for(int i = 0; i < 6; i++) { packet[i] = rx_tx_addr[i]; } + packet[6] = crc8(0xa5, packet, 6); +} + +static void build_data_packet() { + uint8_t ail_sign = 0, trim_sign = 0; + + throttle = (uint32_t)Servo_data[THROTTLE] * 50 / PPM_MAX + 50; + if (throttle < 0) { throttle = 0; } + + aileron = (uint32_t)Servo_data[AILERON] * 8 / PPM_MAX; + if (aileron < 0) { aileron = -aileron; ail_sign = 1; } + if (aileron > 7) { aileron = 7; } + + uint8_t turbo = (uint32_t)Servo_data[ELEVATOR] > 0 ? 1 : 0; + + uint8_t trim = ((uint32_t)Servo_data[RUDDER] * 0x1f / PPM_MAX); + if (trim < 0) { trim = -trim; trim_sign = 1; } + if (trim > 0x1f) { trim = 0x1f; } + + uint8_t rbutton = (uint32_t)Servo_data[4] > 0 ? 1 : 0; + packet[0] = throttle; + packet[1] = aileron; + if (ail_sign) { packet[1] |= 0x20; } + if (turbo) { packet[1] |= 0x40; } + if (rbutton) { packet[1] |= 0x80; } + packet[5] = trim; + if (trim_sign) { packet[5] |= 0x20;} + packet[6] = crc8(0xa5, packet, 6); +} + +static void send_packet_hm830() { + NRF24L01_ReadReg(NRF24L01_17_FIFO_STATUS); + NRF24L01_WritePayload(packet, 7); +} + +static uint16_t handle_binding() { + uint8_t status = NRF24L01_ReadReg(NRF24L01_07_STATUS); + if (status & 0x20) { + //Binding complete + phase = HM830_DATA1 + ((phase&0x7F)-HM830_BIND1A); + count = 0; + NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, 5); + NRF24L01_WriteRegisterMulti(NRF24L01_0B_RX_ADDR_P1, rx_tx_addr+1, 5); + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5); + NRF24L01_FlushTx(); + build_data_packet(); + uint8_t rb = NRF24L01_ReadReg(NRF24L01_07_STATUS); //==> 0x0E + NRF24L01_WriteReg(NRF24L01_07_STATUS, rb); + rb = NRF24L01_ReadReg(NRF24L01_00_CONFIG); //==> 0x0E + NRF24L01_WriteReg(NRF24L01_00_CONFIG, rb); + send_packet_hm830(); + return 14000; + } + switch (phase) { + case HM830_BIND1A: + //Look for a Rx that is already bound + NRF24L01_SetPower(); + NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, 5); + NRF24L01_WriteRegisterMulti(NRF24L01_0B_RX_ADDR_P1, rx_tx_addr+1, 5); + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5); + NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_ch[0]); + build_bind_packet_hm830(); + break; + case HM830_BIND1B: + //Look for a Rx that is not yet bound + NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, bind_addr, 5); + NRF24L01_WriteRegisterMulti(NRF24L01_0B_RX_ADDR_P1, bind_addr+1, 5); + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, bind_addr, 5); + NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_ch[0]); + break; + case HM830_BIND2A: + case HM830_BIND3A: + case HM830_BIND4A: + case HM830_BIND5A: + case HM830_BIND6A: + case HM830_BIND7A: + case HM830_BIND2B: + case HM830_BIND3B: + case HM830_BIND4B: + case HM830_BIND5B: + case HM830_BIND6B: + case HM830_BIND7B: + NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_ch[(phase&0x7F)-HM830_BIND1A]); + break; + } + NRF24L01_FlushTx(); + uint8_t rb = NRF24L01_ReadReg(NRF24L01_07_STATUS); //==> 0x0E + NRF24L01_WriteReg(NRF24L01_07_STATUS, rb); + rb = NRF24L01_ReadReg(NRF24L01_00_CONFIG); //==> 0x0E + NRF24L01_WriteReg(NRF24L01_00_CONFIG, rb); + send_packet_hm830(); + phase++; + if (phase == HM830_BIND7B+1) { phase = HM830_BIND1A; } + else if (phase == HM830_BIND7A+1) { phase = HM830_BIND1B; } + return 20000; +} + +static uint16_t handle_data() { + uint8_t status = NRF24L01_ReadReg(NRF24L01_07_STATUS); + if (count <= 0 || !(status & 0x20)) { + if(count < 0 || ! (status & 0x20)) { + count = 0; + //We didn't get a response on this channel, try the next one + phase++; + if (phase-HM830_DATA1 > 6) { phase = HM830_DATA1; } + + NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_ch[0]); + NRF24L01_FlushTx(); + build_data_packet(); + uint8_t rb = NRF24L01_ReadReg(NRF24L01_07_STATUS); //==> 0x0E + NRF24L01_WriteReg(NRF24L01_07_STATUS, rb); + rb = NRF24L01_ReadReg(NRF24L01_00_CONFIG); //==> 0x0E + NRF24L01_WriteReg(NRF24L01_00_CONFIG, rb); + send_packet_hm830(); + return 14000; + } + } + build_data_packet(); + count++; + if(count == 98) { + count = -1; + NRF24L01_SetPower(); + } + uint8_t rb = NRF24L01_ReadReg(NRF24L01_07_STATUS); //==> 0x0E + NRF24L01_WriteReg(NRF24L01_07_STATUS, rb); + rb = NRF24L01_ReadReg(NRF24L01_00_CONFIG); //==> 0x0E + NRF24L01_WriteReg(NRF24L01_00_CONFIG, rb); + send_packet_hm830(); + return 20000; +} + + + +static uint16_t HM830_callback() { + if ((phase & 0x7F) < HM830_DATA1) { return handle_binding(); } + else { return handle_data(); } +} + + +static uint32_t HM830_setup(){ + count = 0; + // initialize_tx_id + + rx_tx_addr[4] = 0xee; + rx_tx_addr[5] = 0xc2; + HM830_init(); + phase = HM830_BIND1A; + + return 500; +} +#endif \ No newline at end of file diff --git a/Multiprotocol/Telemetry.ino b/Multiprotocol/Telemetry.ino index 39555d7..50553b4 100644 --- a/Multiprotocol/Telemetry.ino +++ b/Multiprotocol/Telemetry.ino @@ -1,166 +1,337 @@ //************************************* // FrSky Telemetry serial code * -// By Midelic on RCG * +// By Midelic on RCGroups * //************************************* #if defined TELEMETRY - -#define USER_MAX_BYTES 6 -#define MAX_PKTX 10 -uint8_t frame[18]; -uint8_t pass = 0; -uint8_t index; -uint8_t prev_index; -uint8_t pktx[MAX_PKTX]; - -void frskySendStuffed() -{ - Serial_write(0x7E); - for (uint8_t i = 0; i < 9; i++) + #if defined FRSKYX_CC2500_INO + #define SPORT_TELEMETRY + #endif + #if defined FRSKY_CC2500_INO + #define HUB_TELEMETRY + #endif + #if defined SPORT_TELEMETRY + #define SPORT_TELEMETRY + #define SPORT_TIME 12000 + uint32_t last=0; + uint8_t sport_counter=0; + uint8_t RxBt=0; + uint8_t rssi; + uint8_t ADC2; + #endif + #if defined HUB_TELEMETRY + #define MAX_PKTX 10 + uint8_t pktx[MAX_PKTX]; + uint8_t index; + uint8_t prev_index; + uint8_t pass = 0; + #endif + #define USER_MAX_BYTES 6 + uint8_t frame[18]; + + void frskySendStuffed() { - - if ((frame[i] == 0x7e) || (frame[i] == 0x7d)) + Serial_write(0x7E); + for (uint8_t i = 0; i < 9; i++) { - Serial_write(0x7D); - frame[i] ^= 0x20; + if ((frame[i] == 0x7e) || (frame[i] == 0x7d)) + { + Serial_write(0x7D); + frame[i] ^= 0x20; + } + Serial_write(frame[i]); } - Serial_write(frame[i]); + Serial_write(0x7E); } - Serial_write(0x7E); -} - -void compute_RSSIdbm(){ - RSSI_dBm = (((uint16_t)(pktt[len-2])*18)>>5); - if(pktt[len-2] >=128) - RSSI_dBm -= 82; - else - RSSI_dBm += 65; -} - -void frsky_check_telemetry(uint8_t *pkt,uint8_t len) -{ - if(pkt[1] != rx_tx_addr[3] || pkt[2] != rx_tx_addr[2] || len != pkt[0] + 3) - {//only packets with the required id and packet length - for(uint8_t i=3;i<6;i++) - pktt[i]=0; - return; - } - else - { - for (uint8_t i=3;i0) - telemetry_counter=(telemetry_counter+1)%32; - } -} - -void frsky_link_frame() -{ - frame[0] = 0xFE; - if ((cur_protocol[0]&0x1F)==MODE_FRSKY) - { - compute_RSSIdbm(); - frame[1] = pktt[3]; - frame[2] = pktt[4]; - frame[3] = (uint8_t)RSSI_dBm; - frame[4] = pktt[5]*2; - } - else - if ((cur_protocol[0]&0x1F)==MODE_HUBSAN) - { - frame[1] = v_lipo*2; //v_lipo; common 0x2A=42/10=4.2V - frame[2] = frame[1]; - frame[3] = 0x00; - frame[4] = (uint8_t)RSSI_dBm; - } - frame[5] = frame[6] = frame[7] = frame[8] = 0; - frskySendStuffed(); -} - -#if defined HUB_TELEMETRY -void frsky_user_frame() -{ - uint8_t indexx = 0, c=0, j=8, n=0, i; - - if(pktt[6]>0 && pktt[6]<=MAX_PKTX) - {//only valid hub frames - frame[0] = 0xFD; - frame[1] = 0; - frame[2] = pktt[7]; + + void compute_RSSIdbm(){ - switch(pass) - { - case 0: - indexx=pktt[6]; - for(i=0;i>5); + if(pktt[len-2] >=128) + RSSI_dBm -= 82; + else + RSSI_dBm += 65; + } + + void frsky_check_telemetry(uint8_t *pkt,uint8_t len) + { + if(pkt[1] != rx_tx_addr[3] || pkt[2] != rx_tx_addr[2] || len != pkt[0] + 3) + {//only packets with the required id and packet length + for(uint8_t i=3;i<6;i++) + pktt[i]=0; return; - frame[1] = index; + } + else + { + for (uint8_t i=3;i0) + telemetry_counter=(telemetry_counter+1)%32; + } + } + + void frsky_link_frame() + { + frame[0] = 0xFE; + if ((cur_protocol[0]&0x1F)==MODE_FRSKY) + { + compute_RSSIdbm(); + frame[1] = pktt[3]; + frame[2] = pktt[4]; + frame[3] = (uint8_t)RSSI_dBm; + frame[4] = pktt[5]*2; + } + else + if ((cur_protocol[0]&0x1F)==MODE_HUBSAN) + { + frame[1] = v_lipo*2; //v_lipo; common 0x2A=42/10=4.2V + frame[2] = frame[1]; + frame[3] = 0x00; + frame[4] = (uint8_t)RSSI_dBm; + } + frame[5] = frame[6] = frame[7] = frame[8] = 0; frskySendStuffed(); } - else - pass=0; -} -#endif - -void frskyUpdate() -{ - if(telemetry_link) - { - frsky_link_frame(); - telemetry_link=0; - return; - } + #if defined HUB_TELEMETRY - if(!telemetry_link && (cur_protocol[0]&0x1F) != MODE_HUBSAN ) - frsky_user_frame(); + void frsky_user_frame() + { + uint8_t indexx = 0, c=0, j=8, n=0, i; + + if(pktt[6]>0 && pktt[6]<=MAX_PKTX) + {//only valid hub frames + frame[0] = 0xFD; + frame[1] = 0; + frame[2] = pktt[7]; + + switch(pass) + { + case 0: + indexx=pktt[6]; + for(i=0;i0) + { + crc_s += p[i]; //0-1FF + crc_s += crc_s >> 8; //0-100 + crc_s &= 0x00ff; + } + } + } + + void sportIdle() + { + Serial_write(0x7e); + } + void sportSendFrame() + { + //at the moment only SWR RSSI,RxBt and A2. + sport_counter = (sport_counter + 1) %9; + + for (uint8_t i=5;i<8;i++) + frame[i]=0; + + switch (sport_counter) + { + case 0: // SWR + frame[0] = 0x98; + frame[1] = 0x10; + frame[2] = 0x05; + frame[3] = 0xf1; + frame[4] = 0x20;//dummy values if swr 20230f00 + frame[5] = 0x23; + frame[6] = 0x0F; + frame[7] = 0x00; + break; + case 1: // RSSI + frame[0] = 0x98; + frame[1] = 0x10; + frame[2] = 0x01; + frame[3] = 0xf1; + frame[4] = rssi; + break; + case 2: //BATT + frame[0] = 0x98; + frame[1] = 0x10; + frame[2] = 0x04; + frame[3] = 0xf1; + frame[4] = RxBt;//a1; + break; + case 3: //ADC2(A2) + frame[0] = 0x1A; + frame[1] = 0x10; + frame[2] = 0x03; + frame[3] = 0xf1; + frame[4] = ADC2;//a2;; + break; + default: + sportIdle(); + return; + } + sportSend(frame); + } + + void process_sport_data()//only for ADC2 + { + uint8_t j=7; + if(pktt[6]>0 && pktt[6]<=USER_MAX_BYTES) + { + for(uint8_t i=0;i<6;i++) + if(pktt[j++]==0x03) + if(pktt[j]==0xF1) + { + ADC2=pktt[j+1]; + break; + } + pktt[6]=0;//new frame + } + } + #endif + + + void frskyUpdate() + { + if(telemetry_link && (cur_protocol[0]&0x1F) != MODE_FRSKYX ) + { + frsky_link_frame(); + telemetry_link=0; + return; + } + #if defined HUB_TELEMETRY + if(!telemetry_link && (cur_protocol[0]&0x1F) != MODE_HUBSAN && (cur_protocol[0]&0x1F) != MODE_FRSKYX) + { + frsky_user_frame(); + return; + } + #endif + #if defined SPORT_TELEMETRY + if ((cur_protocol[0]&0x1F)==MODE_FRSKYX) + { + if(telemetry_link) + { + process_sport_data(); + if(pktt[4]>0x36) + rssi=pktt[4]/2; + else + RxBt=pktt[4]; + telemetry_link=0; + } + uint32_t now = micros(); + if ((now - last) > SPORT_TIME) + { + sportSendFrame(); + last = now; + } + } + #endif + } + #endif \ No newline at end of file diff --git a/Multiprotocol/_Config.h b/Multiprotocol/_Config.h index f0b4e61..6c28b62 100644 --- a/Multiprotocol/_Config.h +++ b/Multiprotocol/_Config.h @@ -24,7 +24,6 @@ //Uncomment to enable telemetry #define TELEMETRY -#define HUB_TELEMETRY //Uncomment to enable potar select @@ -34,29 +33,48 @@ #define POTAR_SELECT_M AILERON +//Comment if a module is not installed +#define A7105_INSTALLED +#define CYRF6936_INSTALLED +//#define CC2500_INSTALLED +#define NFR24L01_INSTALLED + //Comment a protocol to exclude it from compilation -//A7105 protocols -#define FLYSKY_A7105_INO -#define HUBSAN_A7105_INO -//CYRF6936 protocols -#define DEVO_CYRF6936_INO -#define DSM2_CYRF6936_INO -//CC2500 protocols -#define FRSKY_CC2500_INO -//#define FRSKYX_CC2500_INO -//NFR24L01 protocols -#define BAYANG_NRF24L01_INO -#define CG023_NRF24L01_INO -#define CX10_NRF24L01_INO -#define ESKY_NRF24L01_INO -#define HISKY_NRF24L01_INO -#define KN_NRF24L01_INO -#define SLT_NRF24L01_INO -#define SYMAX_NRF24L01_INO -#define V2X2_NRF24L01_INO -#define YD717_NRF24L01_INO -#define MT99XX_NRF24L01_INO -#define MJXQ_NRF24L01_INO +#ifdef A7105_INSTALLED + #define JOYSWAY_A7105_INO + + #define FLYSKY_A7105_INO + #define HUBSAN_A7105_INO +#endif +#ifdef CYRF6936_INSTALLED + #define J6PRO_CYRF6936_INO +// #define WK2x01_CYRF6936_INO + + #define DEVO_CYRF6936_INO + #define DSM2_CYRF6936_INO +#endif +#ifdef CC2500_INSTALLED + #define FRSKY_CC2500_INO + #define FRSKYX_CC2500_INO +#endif +#ifdef NFR24L01_INSTALLED + #define HM830_NRF24L01_INO + #define CFlie_NRF24L01_INO + #define H377_NRF24L01_INO + + #define BAYANG_NRF24L01_INO + #define CG023_NRF24L01_INO + #define CX10_NRF24L01_INO + #define ESKY_NRF24L01_INO + #define HISKY_NRF24L01_INO + #define KN_NRF24L01_INO + #define SLT_NRF24L01_INO + #define SYMAX_NRF24L01_INO + #define V2X2_NRF24L01_INO + #define YD717_NRF24L01_INO + #define MT99XX_NRF24L01_INO + #define MJXQ_NRF24L01_INO +#endif //Update this table to set which protocol and all associated settings are called for the corresponding dial number static const PPM_Parameters PPM_prot[15]= @@ -215,7 +233,7 @@ Option value between 0 and 255. 0xD7 or 0x00 for Frsky fine tuning. RUDDER, }; #endif -enum chan_order{ +enum chan_orders{ AUX1 =4, AUX2, AUX3, diff --git a/Multiprotocol/iface_nrf24l01.h b/Multiprotocol/iface_nrf24l01.h index 1acf438..92ff9e1 100644 --- a/Multiprotocol/iface_nrf24l01.h +++ b/Multiprotocol/iface_nrf24l01.h @@ -102,18 +102,7 @@ enum { #define REUSE_TX_PL 0xE3 //#define NOP 0xFF -/* -void NRF24L01_Initialize(); -byte NRF24L01_WriteReg(byte reg, byte data); -byte NRF24L01_WriteRegisterMulti(byte reg, byte data[], byte length); -byte NRF24L01_WritePayload(byte *data, byte len); -byte NRF24L01_ReadReg(byte reg); -byte NRF24L01_ReadRegisterMulti(byte reg, byte data[], byte length); -byte NRF24L01_ReadPayload(byte *data, byte len); +// XN297 emulation layer +#define XN297_UNSCRAMBLED 8 -byte NRF24L01_FlushTx(); -byte NRF24L01_FlushRx(); -byte NRF24L01_Activate(byte code); - -*/ #endif \ No newline at end of file diff --git a/Multiprotocol/multiprotocol.h b/Multiprotocol/multiprotocol.h index dcbbfbd..42ab887 100644 --- a/Multiprotocol/multiprotocol.h +++ b/Multiprotocol/multiprotocol.h @@ -15,7 +15,7 @@ // Check selected board type #ifndef ARDUINO_AVR_PRO - #error You must select the board type "Arduino Pro or Pro Mini" +// #error You must select the board type "Arduino Pro or Pro Mini" #endif #if F_CPU != 16000000L || not defined(__AVR_ATmega328P__) #error You must select the processor type "ATmega328(5V, 16MHz)" @@ -26,6 +26,14 @@ //****************** enum PROTOCOLS { + MODE_HM830=40, // =>NRF24L01 + MODE_CFLIE=41, // =>NRF24L01 + MODE_JOYSWAY = 42, // =>A7105 + MODE_J6PRO = 43, // =>CYRF6936 + MODE_H377=44, // =>NRF24L01 + MODE_WK2x01 = 45, // =>CYRF6936 + MODE_FY326=46, // =>NRF24L01 + MODE_SERIAL = 0, // Serial commands MODE_FLYSKY = 1, // =>A7105 MODE_HUBSAN = 2, // =>A7105 @@ -110,6 +118,12 @@ enum MJXQ X800 = 2, H26D = 3 }; +enum WK2X01 +{ + WK2801 = 0, + WK2601 = 1, + WK2401 = 2 +}; #define NONE 0 #define P_HIGH 1 diff --git a/README.md b/README.md index a4686c6..169902f 100644 --- a/README.md +++ b/README.md @@ -26,3 +26,45 @@ Notes: - For serial, the dial switch is not needed and the bind button optionnal - Ajout d'un switch + transistor sur le TX ![Alt text](telemetryFRSKY.jpg) + + +#Protocoles ajoutés mais non testés (Issue de Deviation) +##CYRF6936 RF Module +###J6PRO +CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12 +---|---|---|---|---|---|---|---|---|---|---|--- +CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12 + +###WK2x01 +En cours ... + +##A7105 RF Module +###Joysway +CH1|CH2|CH3|CH4 +---|---|---|--- +A|E|T|R + +##NRF24L01 RF Module +###CFLIE +Modele: CrazyFlie Nano quad +CH1|CH2|CH3|CH4 +---|---|---|--- +A|E|T|R + +###Fy326 +Autobind +CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8 +---|---|---|---|---|---|---|--- +A|E|T|R|FLIP|HEADLESS|RTH|Calibrate + +###H377 +CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8 +---|---|---|---|---|---|---|--- +A|E|T|R|CH5|CH6|CH7|CH8 + +###HM830 +Modele: HM Hobby HM830 RC Paper Airplane +CH1|CH2|CH3|CH4|CH5 +---|---|---|--- +A|Turbo|T|Trim|Bouton ??? + diff --git a/sync.ffs_db b/sync.ffs_db index b007d3936fd7b12599fc328514befd5900170180..af956efba1caefc43b1e5aae5b1d3d108e8e4579 100644 GIT binary patch delta 818 zcmV-21I_$}3b+fflmdTki40I!;!5q43sZ>s{-NLy0{{R500000Q~>}000000zMNIr zvLm4Apm%x;rZr?}c?9ljh5>pegoRtV06_Q$XHyhwy=wXYDZ#m#MOdBe__}kngpao= z4zpmHx`7!ygu}%%6of`okd;T#TyYFd6pZnAXS384PX{T+-!gxEj=VqV6vSH>sQWB2 z+wub}1YrONz2g)B)!OU*X9dsiis3Th? z#5Etvx!n1sOFB09oD!fT9kw@`VcHf>7(a5uoifZwM%9F|bS+DgGKO-kmL_4aNMJVE{Co%!We=?|B?m-dv2CENYv@hC$A|4GEmu9+ledXe!D^SGOgUz>LeA+V~MSK%jT$S;Q|7H~Ns34H}&J5_{tid30BZh$UsQzkc1c{3> zCSE}mzny;z63<~wH{Xw9zS}C0xCSG-J9mKH6VE8ewiQLaK^RDV7z4WcU10SA80PE- zi|=GWH^&%kjx>Wjn)x|kaW@R}uYt{(&Uo$$YB>J_hqDZ0AJb$McOC$%k6@I0vkXQ2 zAXq#TBm578#akKC-LpCXzgT&hzUL2c&;{FHVaA;$U-i#{#5G-zlkxtHm w#TzOy#Lt7pl`!IE5!l{PCiHy40QPShM*6u3Hiw_d3Ozi*;o!~y0HDSHR`+~)$p8QV delta 612 zcmV-q0-OD~3xx`>lmdVAS&PyEw?k!=r4FK0Mz%j)0ssI4000002>}2A00000-)|KL zfN%pp6Fb1BO>giY3Bf`>VRLvmu!HLozCI@$@9Xt!#})7~KF&`Ph&Lio$Rl(qA1%<# z!4yBce-ppTK#EUdEI-q{cG{A8+X}%GynJsEyGlHY@u72v0JwkF+U~xUIxpvmfb_LG z_4;TeQ9cRhF}#mhEB??%&#Sw+s1(TZuB4j3vBKTgV3GWl{e0>6o{>hrm^yETa7YYK z+#nv6(`(91)v9GyDQiqQ^a4=cozkNBuBaK(_;@=-5N&g}BW?Fr;U zz_WK;-|f3`lw>ifI~UImgZEjNN%OxfQa9!wG-_H+VoV4I{I&Ej=y^wE;4vPhaQ*>K z=+m}C0RR9gWqliZZ zF#^S%8PLU9gF)g(4Cv-;2b+`6h;Hu=uy{O%_)f6+E(Ub<^2><|~$^a!n007L}=iU4Vn71BTY2ftR7rv{M zmaD3RxvPhfvl&3l)WO({OvcX0!VF|)Wa{NKY$o`|MPa3;<*KD1&u`*j$87Wu4YQ}6 z;~O^sASmMLXk=nz=1OL4W?^M7L~;6~i-OF`RER>8OMz9vQNqm93h3=@rs}PzX5wvQ z!e>e$B1|Ue$^Rz6&dk+_%+t=+-i6;&h~i&z`QPsU>1LrI`xl9;jS$8EG)hZBnM}gL z*^G>fnU%?em79%>o0FN1la-H?kCBX>m5r5!jh%&+hl!1qpNof|m5uDbE{Zp8&Zg%4 zAW7-}()HF7qOf#zb>wGZ@$m3q_TXT4aJFD!k&U~=)YcQx{4vUj2U zw**Nu7ZYbIM^`Hcd$NBd8W}sdxe8IdS^7VRVCVSXV(nf2Ynt9BjK$N)k%f(!^`9aA zn@~aF|4nLV_utemt{}7jW$*u0u#1|PqZtdx%*DaY+2n2E%qjm-<;XALY-Z%@;H>80 zVEgY`RJL?*b#SqCa3qsZA}?QH=l%d1I^jg3)IP!JIj0ipr6i;Ei@8?OMs z%F4>?D_~?~q-Jlgr>E!m_!uxd``Ql}7#K)TPd_|7tgWqm2@3k-=ok_bGG_z8#KgR~ zxB!E}larI)-roD}fc^db+uPgJ)YQGbJ^RGOxVShO85tE76#yL_0}cQQ32F58)!p6w z?CdNuG7?}4$jZtR6cm(~mmeA$T3cIlc6PS1vU+@c1iS(=GBT*;3L`--~H#_NM?=p@6>E z*B~)502Y9pfdPk*=;0dx1`!1r1`z%FN=i!l5g8yXEKEg3)${mB$IAY8iHJ!NpZEfj()n{X5larHUq-R)KT3TFOtgEY2 z1F0=9FYoT|K0Q5gaB^BsPAV!YYH4Yysi|H20v!JQk&yagVQF1iS!rWqqpYk;OC__4nWZ=myW?5>;&=~!4v%D6k!-{qP|*Zhgyv;rm4W?fvV`tI6x_A9n22nh-Ng zDcqBwnh>fOHLYGuX?jK@L`s~u{{LSaj3oDe(EnfC&ZLly;@A*}m9=m3s%|LaBWWAi z+|HC0j`3}GnL)5`^)raj{z)KJ z7#L}E7F@a?GJ8A)mgRkzG~>4QF|*ZvZ4OBeXnA5HZ}hj7^2Euz{mWqcYY{jn@>JFS zp2g3`_I_C^>gmz}30jL|MBI%%q{;7N$Lo{HxVnzb>%PT3?_OXi7>Sb0={)ZV`!E8yXfHb-{?>sbeIQ08f(_Hw z2UYh%z>QASbmM1}LerPvP5sxyz=Wvqm5=aNjZz<_>0{LJpokXKPl{cnQWBMHw7a|g z0SO>wM`H@se;%=dutcMtTHZA}4T;P;7a{NDX@>kuh4oh;-^cQ}j8-ImX|hJ;gb4%Y zAK}XXFc?98+7)KK41sDraKYd|&Nt)eC@v+lSxhQs+vAG1kWy@0z)Z!cTOh9A0~ zbHCQXoH=H4=M^)T`s5vEDh~pOe~=l4u@Ij^a$L8{3^Wf*36AHJcK&a(uu?cYdI=PA`J8izkw^kf8j`iJJynF%rU~74^kcNDo9_E1 z$e=9y-rHF7C;e4vX-zsIBdgETD2G&#;*j3B$Yez`zr_Gom`l*|nx6|LoGoQVK+@0+ zf|P8UaCU;Yzk;bR!e{rj&zLS$55F)Xazt z#F#aAir~1lWaULRaND?$Yb#wbO;g7`)9~&x2}NpM=}#6@oVBC+9@OiXW z5sr9Qw_f>!Lk$)lp8#t4RwfYG>;7V_{?GjF4fc<1X`csK1X-@Tfm1Q0XcAUL4_x5s zG$j}gs#XVC!bO3lsxhU_lfGo9pT9DxKJzUK2+b?1P;%w-0BdJ60b^rYAN7}nA>PJ5 zc+g0SYbK&ZBwU@%=I6N`o-Pfl2Uk|rz>&g(R?cu{!wCoVWy`uU`r2gss{)4jzXOPs z`-Tux^dRivJH(qKTv<`xtF?{sx}eZg?|#2)OR z(e3wp*!tBJSEO)gEov!nc5Li0&ICf^(D>PqST#qghqiZ8i^7uRy+8$Q=&&w})UVk& zy0~P7xfGA&h531saUspl5)honbzzQ$sahH1MbuJiQ1ZnR+S4wsv!WlR8CZxG^!FO1 zica@DtMqUWF6XqAmd42Y!juG+K=g0Xp@N;bP?Nv*;xUFSz4^f}2v8`70;;XG;*0Zi zO0WbE_9(2^*7=h=jUgPf(P~Sz@iu!gL}s!WP=+1nAyUR zS!`BS@+QO?myFQ+j~4aK_F5R3?OHV!2tsL%CB`VfXTTdIzIGua&aBi%V$Z*hh8hZ7 zc}REBQ{;Uk3Yq|n;zke>DoCd`2NiP*-UP!YuZOq4{U<6&U$ zhJ*qckujc>a!Qh{q}JT6!3K=5qrMy7TaDt+8re$=KG}p{FNH~tZ_xckc)D(_Wdf}2 zp&pAQ2kt3jros!$<2ARfO@Yom4nYjY5Pp@n*+QmM3)A(u&0LQ>YAuOxUsh-4iKTa@ zH*IFMmHLI#*cw@Wq2qEQz3{6dZo~u5-0fO=f(*2o5GZ#B`)7cbMOtm5B2saDgtz7Z zDCSk9EmoN)8^_Wk`4U52)arF!J}_of{1&SzxwgSk<*>>%!B#;s^~&Dppf#2>K*2ff zv3}|7+0QOx3j#0hXX9IPr_fP9mbwtJpALXB1opR(RxAi|J>MQ1{xT9QsHtvfrK?;? zq8@c|S<}3rZD-1(H$1#QHqz#Pe89u9P-SMeeRbo`L&WvRy8c^2iN4SS)kx~Cer4U-K06D=QrQyl6t85tb>G)guYW$z!;rzm}%@<@mQHsVC$ z=Vxa5N7XDUC1f!1v{SfR+eAg%{!U7YJ7kN^ihr_Q4>mUvu(Ere{cjvTLF?W&9%)^4 zkPT42M(_qV4ut%9i`)&~l?#OHhYeBAmRgid#B;Gb37;vVLqaq7sl#9^n!}bbopdfX zC2VC-{$)6F@$V>)81;j6f)2vu*%?lgxh=$-lBBJnx5;BL^(Vs0APaMpgbGv3^UE-D zPYV5azudl@26JAii47nZK8d&=LuZ2`9FykhyX7ginM=j~lR!aEzK-C>{$04c-cVna zaRe#rf3{MFYj4i-_wDa-vy7n?ggV;NQrT}m&GjBlk7u?A?XBgqT#ks?zbxq(Ge4QYiO}jQ(@uRR51miMacHu6f?*Pl%#c3dB>=(2vx6k%7Kv~;yBbcY zS_JqqVntMQf$l!U>TrlaDg72PL50^osi?0b7KVDUf+l**QRM^UuMo0rSN_NKInAbb z$(=D0WrzW$Tdv{6l@AG${(J8Bmvj*qGlyhK3ho1*!caARB1SR{06(rt9f^vW+S@Bb=pS!O+ zot6)#=pvA3>1m$3MUd|N{Yyl80wxbUNRejg^J2l!1l_k}1mZM_D?IpMt-5+~DWZ&+ z&hxygKn^X@Qj)|Pd`+s;-{V$=@wHC*VDJ8rmBw{}G@%3$?@u@V_cRDlSYEDFZ_h~; z-8_ODa!RTfTx9C)#o~eddbXsXiOYohLb^_?sZK z6S9JuHiIR;lMGv<08f2Q^S#x;y{|m9ju4@UWYTN&?@(#6SZYM5J*UP?#e04sRU|q! zI2=X-WV(SZvQTSyqT{r6bLFE0PBl?G>^Co2tcoHv&w^7)F&a7zf0{)KJ&s+5$r)-? zIrz}Y4C+A;+n;hv*hR?6MFRd^Gt)mR=a*o@OqYjbk?gj118!vNvxryhf5sOKn_Jb- zd}M0A3I}J90Le|_(A>Mu;j_?WKRiy+d2%?WDg0VsK_`ZT_5{#wV+bfeadIU%7c{QB z#klt*g=0ry%*$;qaDOL#3T($uZAZ&%;fPfPexNLxU`ANHxVsd{ZCXJjAx&x8aSL4j zdU<`hN14!zzV2W$p|PL>)rZ~vu9AQ`!SNL4-Mx=~Q65IIy+AnfSJW-vHB_okgIEy_ zv<34i*mZK`N2+sQ-tBR}UeosdZkp{oONNU#i>ZP6_W*%Eo+P7~i-ijU2&xKvfr%>~ z`P^uJFhH-E2k-m!PNO#RxLsvPjlYqdpD~>XzYUy`VR@7kyXg~kg7pF%`yOGw zFe{Fa(`OXy`YW%wrBCJk6lIEa^#pyx{v3&457ink8t zD?st|qv_z1>!v`~g}&{)cFEcm!M*0zlLSUW5(`BF9nb1}UleyCl%Yt+sejy?`~E7| zY3D`d8SrD$W&8jhHV44$DuNDY(wM4v5JQu(8hywm%3c3PyE2NPM6P_MluGq<4rc_x zzhOI6Fqi}1`YUzK9_OxRH4JO?Sm*=3UQR#1S@+G(8GpzgFKZ|0t7HZ*Vzr*o$%D>7(g&rlVseqLZ8_`k+ktoI{nW2G^99 z^A~uVAk`{kwfUeVf&9N)>N}3xIqoEVlVZXSzR*VR+)naIDf!xQ7ds=s{cL zig93Lib4y`;lE3I`ETJT;ibWh`t;0Cb;FQCZF@Q`R&qpDc?v12DrXP)Gah`9%8rl} zhAkcqLF{&m)hH67P2`7BQl-2;pXr6)^11?V>?n~Mo%rZxmrzwdyX}#R_jJjbALtpy z_q^sY!iBj7C1ZK@SKg!STXAt)TCq(L17}5a!&hg z{?S80L+vw3dse)0xNR*zEL1n4J020c+^HVr)P)LK-(_BXW6B4UxX+O zx9?Pim{@(;ryl=V9h;0W0GtV^<{Z5bR60ML;_}SEXuL$_b$*Rq;tDST3zMM6s-19J ziy!!%e9^nL{#+kL7saz)W5HT@H2Cg56U1I-^PWUex&7}I`W6z4#PEF90GxTs_jX+R zvMT+q#wGH&hlRgdmJCt{E8MYx$$dSuxy(R8yvi-DqKm-1>C(`FLh^xh%zX~{wGQ3O zdW|{R1^c9CH9enJ#lKvz?Yn`SKGfenxmRt+0hma-vRt{IRb*ha2A@w{0=?o*RIw(rm!WhS${aHyg5iyaQ9e}DC$_mB;N zq3BR01-C&@sGczwxhecwStMig6Eer3_{c!B&M@vlk+!wQzPBhuBQ)ngDnirk{w?ny zp>lKW_Y9YkIEGoF-oX{hp6k-0K;rSOReq$b6B+00B=sq;?XtKkmVhgm)&OoE)x>|Y zVQIX`#T9abE99Dvpi4rk>%M|Ox2a#((~O+2;Z*F8NHi}X6r8@IKg{CgGPKU#RKSaX z+4*vl22yBcEOa7VoWt3s4^G9%|ne)h8=+xs9S|mcW7Iq30A!+m?R;=`Hs%0E&YFBpZ zK-y?WG>53G14t#lTuA#J+_q;q!eHIK@Lzy(%HKse_zQ~4NDF4C8cCgI;vH{ zb%VO|*$K{g{Km=`>pB>Yp8(2erB^=|`()zdU0_rwau=$?!O}dwN_o;-!I3gC7SU0- z6W&SQ&4j->(Yrkb*5Nkqjjv>G^cq7TsB2FsJXc@`$tDuv8T$prU}$o3G+nz#XIh5=`%>vhSVtlEQ128(DZ&Swi|ACkLOXPJJ$oy0dN%JM#y6Yb#*F0){fGm~LK)pKX1_(Y^kR4A94t!j7^^&26( z{b}^1)Te@GT_)}fY1rcug{F{-2R$U2TZkPrKlu)!5F2BRZjgtNOCO@qr!Eb3tqB8f zBG4rl#2Uv*Uyn2KL>J?=?*vsGMO^W6l0Z5WjOVUXf!GZIPKCVuW5NWAi{Em@)H{b{ z*PfnAS6%QRFwzQ&ZWBa4)LjSEBt<_7z6yIx!V~FYcmu+7-xx~zGkSud@`A@M70E@^ z$M#AyCwT?aPIt$SFjBs2v6PjVqs6DpO7+O?BJ)?29~H5h=!&i=`bGNU5F$GfZV*G-Ey&0Ec~g>p#Q3^QjXvo~dE~hL_qmx>RgW$4 zO~O8R&PGf3pK_asVTOdbsdEkLoq=R1RgGZIJLFHW-)E}TBJr;@2QI5%R!P$2P7cQh zJ(k}SCP^nLR$8J{at(m#DbeJLyvcG2$P9^T;Cpg!%f7U4) zZRQW~DsQ!A>TeP!*_~lW`I2j_$4v5C>_n@5!ThLw{iXr-gh^wP-wym77vd&+0$;oPQ8Un!) zRsP^?yZH75<5X$$Y^#ZljEHD?L;C?fS2vyjwgT$<)EtKo?wNeejnvlH-O#X@vViwM zz6P`Nsj0N;ubsYBvWLoT#Ec$t>YimA6;;mUyS(^*+erQ=BW#uBe}4rn>Y}7&Cn%S; zhOS|DeLY;)9Q61C_rt%Ca{EiBp?O{a?^s7fUDhm!g_vLMqA&fr&ea|$yMo2~`za5~&OvZzYR-`39!JRKlb z5{TM^uUA`fbWS`!dY)!u59KP*kdpmDRk_xovm}8v6P`7gMx{y24bDo-D+LO=-EJRH zAeT^CF{F>PIrK*0hqp0Yvu&wP}qmqB;4o}0p!y-{b_(V#MU81&Nk(%jx zwSExQPLR&72pTCk2r0uol9gFY4!a`WemJMtc0Wg5>~$wD`XWANBa~9Z$iPwDM(tNz z-4@f6Q8FT|Gn-?uTE#Rd>j_GyHEqFTatYVkmRB>mX6E5d-jqC`9>Um786VUj;$KNo zuU6c>4lF1ewF|eTkXB!EKCbtTwQw|!#KwVpc)0t0XcsQ2YHy$7C8@eC`H(6)m}sVPgamBCbSR|G~jH$Sg5E*eWX>IS_|_k8-47yoPKG1^_JAW?fJ^$b_SB$s9%P$Ba?{?{5#+&SSMV9 z+%=MuNL4tDszz(ibrU7kQ!q3ybeEJ#xKO>;VyDYtt6iu2iOp9mRwSCWG2#soaNq){ z@aZp%*0apJNV{r3gi)Jnzl+P**hQmZF@yoNQ#sQ=A1mV&$mb+0e>-7@Nq}&iI(@(k zyKWhlITSn`M&-Zq)ywJ)PR8UIixdmgRhHO!I2f9Q#fQ%pO-%4Q^*o64XY}n?fKHrH zTlREp57btz0aY|L^+1 zifJ6Pky5vRkTk`k`@@+5hn|1ThJQiHqMEB+z)p3Z{$uOX0Gru?tNA)*a4`zAzT$w| zJ{k$7;&q^Cv-Bayc?p%><26n7RMo2~rTy#@#y}l%ME>dwiL~_yxm$S5LQ0)79Q*a; zRsAW-h>eH=dcv5FRn;wyTzEd~M~2ukrV-JkZpHWj)^BkxvfPwi zXXfg%bk`@a*_Cxn#nb{I_o;BVq+Qt+sF$ocH35%5zkC;B=2QqT=PtsQnTqDapmTjK4`r{G$dbSI&eY&<0dw$6=MD-dOW@E?ADCh+W zeT8%qy;NzjcQ?^Wj4cxIGm5+_*0gJ&DF4l6qW0kt4+n@_`~GmTJov6qK0G2<*=?W0 zW9H-_ZY$n9mZRR9Or>WfrmJ*uEihMCC`qUtJI_{tp`@*{{-r+DMA-dfq9^{WU{r4MmIYUGvQmFL=V#I?vQv={CEH_Wp@uIX+IGAr%7!S15Vj(jegJJt zBwRFL^G0OABVj?9Vq) z+#7wOadNAW;FAk+TV}hpskXg};7A;9VyE#f7u_TW*IP9lwM6Wg`9H`4iO)oQ)x=14a}9} zog#cZlwQ2aR?2W2QJ8*oJqGHijt?K4lF+j1im8Ja8(S(5N0;Gxnz2*#Jk?}_~ zAf_70Pp%IrBo7I>QxTp}rt@Xr^EEt$`BNyegxO7zHX6Y4!ITibkX@iyR#BGp*KS)G z`wkQ6o7$R2Z6k2hk`>5^KN!ATIF*WV@hRkkt5UO(FR-?*qq34}R2zl<$9i)Y4L0pj&No=Me3_)xraHNU{V@EJ~E*SPOwT zW7U~*y3%kg}P5g`gH)rWpiTS^8 zSz)O`i^M5SfO^l^d(Yk4!5p|lrt$4*WAusRnYe&UgigXZ@}IaO!Vq8KvU;?FUI=3( zKJ3EZymx3aV|>X3PXfW!Vae21$q*F8=*`ZQy>NvdAkKahMYA8yF2OCkZ+QHX{GQ7X zymZu@=NFTJkTNgRj}dtXcNYh-9F-7TxfIXP^!#tD0r8Jlw_B{9OZy@=VYflv28$*{ zmFwJ;F|&PABPYc47o(P(kb|1sPiGJQIj{q>IQI~|FED@~$L@*q-6u(W)#TO^8k$9L zwyj=lT;OAr$F7&V=iMBi6K&wEyzf9_G&DTzqeUCHK4e7;K7hE6XzK5Log^m#)4VN6 z{gA}-dU7Gox=3DZz{fJl5f>U7gGk0D%Jcf#ZPN9$&C-SbTHRB^oRxb`6*ioanU+9| z|5}8q){okF+H{H=5xPd(_WRK2xf((I_r~hUl>LudyG15-Aqt?K_nju5011SDGi-$R z(EjO)weuE27^RR*_7dmdy1f+9(=m#!L0Q#?h2F?i!d;Z~UVVP-OK<)6(%nw<$!;Yg zx+b(laBZO->%cY<7F4AoI2ez@;Nc*mO?U3&0X}osR9niXlW;hNIuu=;9$BMMJmN1= z9OCkT= zcC0_+zV_K$t+pg&yq@9Q{9FV|aiHrNcb;JO8v*t5en&1yVo{-e7isS1ij#k*o4a&7 zt19w@PB#N+6QPj2H~;#zW}d7+>*)R6UzV5sbb}|M@9oM7llJSi7Tbxl>g8jhgKsD)IsMQT z>?tirLBtJ7DR~$aqQW*IWh4^=gho2r-1XJ$eNWbRufO)T7jvrF zDeo6SShFaPZVCJatm~%}=3&eRt~OAA%f=HhB2shM4qq$59kJl!=o=JK$~4gG#p{p$TO1;@+2Ahk#q2*Q+(wX4W74x;w_6x7`q?diA@_`iV}Mcp>;d z(e~H1>A$7y!&KV7ifQz38!o#3u1g=JnBmHr-zG#+;@l6nj$IraL8s@=dK(>+N5dfe zWPtNu!+gUm7M~oXBX#RI^*CZARJW%f@bp6Jp-K*!N$^qp=wSUw!_m=E1U|C{{)%)n zOgwc)v>V5%BpvZ9a_1{!`{iPNUKCP0p-+ChfKXWtvyTMa)B5qL|7|*{_<6|A(+!>BJIISu2M$nSGh5HnQ<-~IpXq}Vcr3~R6urjTnRX`UX>De+k zp>ISc+ry?~BcLwD?H_P<({zzBYwNfo;#TSMy@?035e83DrR550+S4d8gphVTuQqo* z``8f3+Ng_41?4Zn6N-R$mAPNk=6On$=Gg( zc?DsTM^1E;4}`YGFQ|ERP;dytcJ8^bQ-ZryYw+1P%YY*i8C_%;hkBi8P-e&>2W}F1 z86UJYGI_S2zo9Ddd+sS_Tmie*qi9@i-{25t59eBNf@_Vg;Tq0`l7%+H_d~o}E#=s_ z8EGqg-FiV18fq{`YbvhZ_xAa`ginPm@6$|AJwT7I2P`95*-g( z4TO;yl-kdFv$Pp%^}VX)pzLYUkrn-=dKqrUmxxdE=HF5ae|;1Ax!o;afxG&alFH0< z2+ce?OL9e6XYaHPX8iLk3d9j(0ZB0MDC?KH?II>LY)of;(&uHfp(D|fAAPSxpKdEJ ze?Foe@N>-I<6cZ~g+NWiE3HNbB;~F$a~B(VG17mB4kW46I>ot|ccV3SitrSy^hX!{ zCK^3RErCK={lkQu5FW^(z0+hcm1pmqP%h^W`ABL!O%(RUp1@y=L&?1P;NzWQ#nP5> zBRC#=CV-TDu;R<{+S5+1!dM#fSVq0M$UNcD2M9iq{9}MJ*TV~GlDS?Rr^Uj{Cylpa zrne$9py_CS3*UZ!mG)Mp%?>uq*2rQvV8UU5mnkGB5Keqk8tE}9iAjwGwSVdiA!x{Gi%8xxNUzj}@r1E zJf{KgMBJeF*}1}BKv-~b-zJ7|alX}D^uLU`FpudVy)HPst<%~eHX(aus$iK0a=n`4 z*?i}!GNV`{s`t+>I#&R+`Ol&_wpfAX@S##t!0}rFm=gqI)-nzMB{2eFMg9XFO%sn+yAm+I^AnH>Y~va08&D$Y$rzZO7J z0{)0FAchc-h@6^Flo<|W;3UjOm?Z3M$l1(S*ao@4Xp3pUQ$;kpE3C-Ut=dv2GpJ00 z$r3Mji57Qyf>EO1s)bbOX+p4_LOyk~t6?QeSSX6kOmqE6#a)KNAjt7l0~}yc>A0*p zuqS#pQO+YX_x3LEwB|r9P*+yCNnfki$drLuqo=>iUH7{IFf#+ZT=NhOojlG$WHqjX zf%g@!_;FBwG-9HR(iCsGvXuP7{lRL45qgrhoRJFT&$m^F_Urk?Rab!lrtehrq)LnD zSZQRqUCo_{wwkAQ?8wp4d(Q{&rQ&0@&CD%BN^*M4k%YZpS>9t$ECoP^{XuF3;fXRB z>%_lil>)+ZUw{a)atps?-iPWOURWh>*Eo;m)>=KR_vQNDkz=gtF2VY6VS+NEn_7po zwC%Gjy?g(f-}D+w3o`siRJJC=rgp8D zygu@Dc@^W_?pUF2j=q3uZW7{dz7&fZhdg}4$>8o>D2>kQroO@i>8|fnIdp`o^rl+T zkmwo&JXH=FtTE-dz7^_G06P@5mLi8KEQAapB!ZD~Ckb|-qkssDEcLuR`_4LqJo;P{ zy{{r+r7E|S?CBR9SW1HT!t>x~h8|y)I!ZZkNyVoto)_(YrGlK6u10idWYrz9>Op8k1$y6_ctM2mEc)?&g0~mHi!^?$ zR;l_r9kr11#gYs=UW`cMTMO%wUsO!cu;Rc`jTV1C0 zTV{^wBXL&=DK;H8kM6gn?{(4s$p&Z$oLkCuc!ZxdE*ayrqttpUxCYMFUY~B7)pLzI zyf&J}r?bWe93^HwI&laKjCH?$>dV*93M;s=W7#vdN~Nb9W)>>xqJd+kA5Q!YyH#u0uQQ^^E8!{wGEJ72di&CQ{=U=U{ zXfphhNySf@VD!Q?n=b&LVW5Z_`N(JIhtQes2=-jm3<_~rv~4Vn;^%jW6rJb+h7)!z}X<@6ymi z&9)WDlGWFWETT$!$lc^7ZK*$HWF7 zS3Nf_i}`*K*xeJb)2IgD>mZ&6NPYL#n9W}61yuw>1!oZIYrwtm2b%9VuFKIgUVRHb z7HE4@B=;%5m)fH>Rb)*ycFy-E+u(%;sS!MSX#}QJVJJ?(Ml8t5QG=Il1V-9uLezvh z2jMS`tX^VbYpCsV%6w@$7%~5d&ax0r7}K9I!F( z`LeZ7Ba-qu!=cpkg=HFTlr=)QNK6CJmeeoRfp{?oQTZ||#?!KVbjR*5*ObuOMO@u= z{iG{U`d;vbGnL8Vt>)_uGr0ja!-u;4pVx2~J3>bi5y`j39_Y{JlMJ5NQiWQe<4Gxw zkPO=dd3QHQ28N8CU$swg%Q*p0H!S|F-M?OpE6ze%SPbc?PljnKyB=Ry0v-mdOAjqr zem-dY)z?~Tx4~rtN&K3f=8{PupV#DV!D|UciF!XFnc&PZtQ@r0BSg|~A!?Qm-oUbg z)&%T-4l*stm!sPOJm0zd_sIW}y%xtdc6BKd8u4_R{lE=cl;_I*4ijLQE-ASF*^i#T zy^B(gU)b+LCT3Z7=x;=%h(ts^F#Bef#oyG%{{qnl^Cacfbj3IwtGtpfymfIw!i?XG zoG(1$K9QA+9Ky;cr$5;2J9DevAL!c1ujfdTZX7Y;y(F7`BnLA4)UQ%@}=qoS3}&d5ngm%T_fYh zyVW6B&r&|hfL<8IncV_|+eMePR}-vaWWq+d8s0c9sF!Cq zIN~j#@cN|mDjf#7HJYy~7GXkxU^TYykbPJJ?4|{#6{j6s@=RIb+uA14(9_U*ZJp%lR=Nf;6x`S;e?dl16;FUlqc1A(|M4* znj6%Nbm9RXE%_%6xB=ND5Zw7uiXpJ%XI-ZoF|Cr}j9LDqW^tjVRw9Lu{1D&_cG z{Vlmef5^-`zhCCo&#gdG5Brb+U(w2}w+9To2mf3ORYsSTjU!EycgX;;@~*!cLF8}o zyrz-sGhQfkpdS7-1p5<+pjT#Xs2nCpsrU8nowAQqf^}I-De7!)3o%-!5RT5pM|x~) zFLt^-Hi^hTr$jU$QW4b8w%*9)-GiUMduOm-pA!na6=&hmC7v(W!M$GdXQyGlRr_C` zYbxD6JJD^qvI?#+C`7p@=1wwg23Zdb|9s&j^Ug(U$n7oZ!uj%be{%>-SItuJ$z>JaT3~YI;=%_Jcf}_97@1qP}8H z0;ZaOT)znqaUCZ4q7E9DPamf=_li?UCn#urrCUd1s5COEMd!YD$bI5{eG90MX zq8_g84(a>3v(!LAm%~hsG@w3$e3}vRJ3=L^$_7J6C0K7xbrtb`uK=2rZ$Zi%%T!hX zUjEf`Pai=Ph|O&s&2&FBW1M=F5!^+EZ6e|^Grl(4-9<7G&P@xw{NVXASNIemIR@av*_YsRtbVW)_r*XuxWSuD8= z2(#5fRcil~ z=|qTD@C28s7d*+tT$viA1Wl*Yk+7@qQ(3_Q1G$`m*XN5cp+m@eY-}52gHdx0p?>Q4 z2=H6wubPRT!X6FaHOj;tIC(H1Nn}HIl-RhjW3+j4#n)J|Fxdc~wFxgJQ*ceRe*YAK z=k>B!J2U#2Jxtn$ds^K9PUKlwVX|FtrDTo(w_81=f%+7sE|S_LD62=P?lkw@hrw~v ziW;xHNB6H66hVSM`G`ma)UkN%Vw_^roa*B58;t8x^*04xK3kNU!%Yc|e!!qq_jmaccD9bO{bo^*;@#ZSdl+OT2x5VpfSX}3MW8Gi&m3n9^r$eCgJ)C?+8 z+;z05z}6^KIQP&0m8Wq(P7R{Z<5KbuIiAjvw#i_@Xs_1dDA&F_CR34dsR7IG=m~4K zIwB(I!N`NfNuG3ULa^^tCraV-3&m4-oAG0?Ny=un5?tbK`*>>jlXtJR+kDxg9aYk7 zKI7x2YknlwHn2{~OluDM7O*xeHkLG#OEV-1!E-?R)bKOe*VH?Byv@pR&X^T6WjfjZ z!N&{AKx7MH-k0FS+*X=i~u1Uj~<>ZC5qhB?e8P|a_nLgVIgE@z0qum3O zZN><_Ov_S5D&+>5J>iKc)3zDEEk5E-#-T%@0R_I!FA`~9NrA~9r4W(AXjQlxz>(Qf z^FEXwo2qr8;+KplVb6Y;D1!IP)kC0u;~@;yUubK+B1X?`vmXMyz=F>ky9tu|da_aK z_ufGZNErSXn+DIT)&5UO=!S4~JY#cs$pw%$(yI7bfsFfto zeB!M=aKQL2TYtcuTR9b&F!OGbun~%l*?&!91tZY>XPyh2gzzb=5;fgfd4=HnBceD` zeru{L4ZqxuHO#W&nZdfs*2KVB&+Xaz8G|6}2Zq~CFgYq^ksVJ@(X(8p)8(+^<%T9? zfT0$QIaZT;+&eTT6ErdK=l(;6qXk!bl=O*7`If`R-+@yR`vDbf`$ykJ6Vap~weh#w z`>a}U2IfU0_~KEh6xA4m&$&{T%*@;=rLhxZhR0qQp?vs7P6m+c|B?b2W8iVne@7?F zhIpjR{#*RA=(%14uqXVw^1jA+{G}*}K9d|S=qo(-tJfIlX&znp4v^=xy`yKU(rA^PJ%*64WntRJs7v+s(J@>H)Zs)v(R!Tx&su*WvUr zv$Ejd%|@W~BJ2qbWbvqRW4g-9JN^SFM&1@#;SOw#s^5)u=?#U5dEcw9fa_Kl8xUfi z+=|Ku-xt1bZ+WKgwAC4?^5PY#o6R{|Q?R|7xdBL~X1^-TOO1%gxqW1@ZYY-UFVFSF zj_JQgQV*PGQn15=xbG!C&6$#g`sxeNaf{mPBC7~gRxzlR{Vp-<`Ua7E4{ZrN055LxbAH(HZXNKC`~ z>2NAff|K*U&EJ**uQi?0!W_L8RG_(I(7`PXtXga6j{xrPw}v{6_@=jY{6yY%$zM^k zhAP0Wj=85Z=8}A`l`X+hP$E~;6T!M-L$z|EEsbNwg9?hplD4AIr04w)0Ea+$zjN%d z3%UYd{mKcnM(@8xfKv56yZZ6t49 zvj$tV{|Y&U?Ncfe$+h~diL~Vf&^kFtO#y|qJ=!PA2WB);Bvi(cU}O_ETg8vre7a2B@9LPh@ zinCVsEJRnKU2JOv#18u$9IE+)kvd!|F6dQ5Cwb%=oMnTPB5AddwDiRO{iGQf9}s%k z!1ihU6)SE&et7e)&1+u3%`eRk+VaA|RF~qn?pm{E;H}AQsPZWMSc=(5F1F3yPU@1% zAjR`HlAd@(kRtV@i|`Mle-Snj_@6ke;X<#WWsD7ff~Mk?mo8mex}q7Z8Oot4X+9G7 z3${Y!Y3$^6o*g(J&7on=2j038dq1`;84!)?3Yz2eg zitRi=`Eny0y1<@aq+>|kY&I!q@uPN~$vr8t)Pjevu=D>$km`XPdh0AbRK>2t+R%$2 z*!Hq^Wp|%+6pN`RZN$DqT-?d7-Sqk0wtvZX4_TkIHF;mHxVf@WIa@Z&wRE$KtTaQS z7INtbodeZlH+?2#i&xKjzgP~PGwaSqL`0-jUpHCW=?Jguu1kxGh=@wd&V#k}5Gewa zZfzZV;&g^Ck)qs+%^4{K>g#YQgD=&k3M7368ai;#TLoReS3g zZrEI!hAI3%w%zotyT4qZj3}ECdM8|NuR!zWo(eOmXyMF45ei$WX@yi5%`l-F+#)9q zi*Lg6khfZ+Yyp#+%Q$CR+t4_dBs)&`!RX_nT zbNZ`bOF4Z2Td5skyXVG~zT#ScNs;czg9!WOf) z)hh3CoCDow{E!rmMz$fQ-)cVBeyp$Ju4Y(*$HDULU2^M}U&?d8V6v_7W$2;H5Fg07*Yjdx#|Tvd*eqX5D{`+5l8x?zTH}%bIW+dyNnyL>|Dzh z;8$Evh)>RKpL>0X^Qdvx0+^MYth6vg7Nfg10xABA5Jk0GTdIp9cH$bzca4Em8Z9;_ z2NlW-5HpYL|BCGf`KvEZk1h~+t;x>9*|-aRvJuS+{((rIC7?D?`QJ?%&4XW@&> z4tah7cLk1-v&GRFpeI9i(qhIiQqw0r5myOk$t}CBbI=D;b?ur^`;Kc;0K96xx3uMK zb!t}1;F%Z$o5p^IdnLELydl||a;R|oIb31JO!M!pg&%8Lz3Sg5lBT^6A z`ik26m@E|E8j11m4;i#FYe}uFpKK#YkFi^ff1of@(*Y?lIgNdFQmT!dxh7h)YCLRW z;|x@|AmKg7aGNtweoR!`)$W$Xav7%)YYG3mZo)+ zGZD4iDga#+!`3B79l3zMoJR_t9HJjZ#pS-Iil&HoP!*URej_Thq;R8FxB2zF{0k&* z)lwx61z5_ww#>qF0-3>*pUjc#assbzG4tZQ)LPg&dT;8{OiRBW%V{{wI7ucDWefGp zz(qR5^|vmz`+BywW^b38BPVL_*fT_ES8?e%buk^i z8QRuZgnP>>Gx9-wEcUuVzgz-eCS(y`_y9%9KZYM1Mrz6+B@Wn!AdMKSj!LSdyvcH~ zr-VprNk%f3yLa*b@z>X4uTHpDlb|}}%}D9qnwwcyElHG&O3`O{WbW&#JaqM@%3QgL zRZ>YO$Gx*r_^I1G%d9T1P02QtB z+Bm54j93!I)l}qmt~HgOR=P1brN`-JX6Z^v(p@*?9l7_e;1-+Cs>QB3EA>=ecD-CK zKV71;*^<|0l5OMHM#pw1-%Y0doPm3sNKY#C(yMK^ln|s^2~r55Fj7+=DeU50y>@M$ zjUr{JJV$ku>#8_ZO2zE8DHL7>{@-fXSxG9(ZUt-u1f7K(Ya&<#a(w&1ShC1CQ;0LDmpsK$^QDKseOHk1&0oIb}m{~MWlc6!B$B!a(cZ-M5WQAY&(Go8B5?U z@`sM6h>vEI((E!zzu)Q6qe5$GL){IpxzBrSF(|Atb!C0{1Dtvfx{7U+Xpl`E#?gTC zAU+X0TzYiN3(0}qYWrbdZ%>AFk(rD8`{{M(ovSP;I9#5Rm}(;R7quN&O65|66;>5F z)`QNI=>|#$XkU@D?sWp_aNK9N2rANZxL@ryuUA3-*c4_n?fA+)H>mwp>hciXpz~bL z)vI?|6h><5$5M_8@rILqhKv>E;`kpIXQUDr$4kPv9a;ttszNp!5fzn|hW|@Dx!^pN z>(MzEsLUp#t|@PEUS9v=s=1x1M2@7kloRP7%2P_F&&}pTHl0ePvtrQ=EmXN6m5Y-J zU#kom5z`^e9Mw*tJFr0tFct|izuw7K3TGlW?15vq%g=U0t5^Uq;{L@4 zY0W0TVT}6;E3V?HCUQ8K;xNA-ln>c6U0XaENip>}{AjD14KJ?YrD%a>c0(S?zr2h0NU3QfJ;Oh7AAU+UR)=xeKRq1!ay)vn)@FrV3J= z8CI@YvqnV9KiBFWu4O^`M-JQC5OC>32-4%YLO#mY_@}W$=(}%g2G5hfSV=ZK@}o4B zA{*&L`F_}{?lJM=Hyb-tO2n#aBV$ZLFILpKkuM9asLX0@t?P$E#2xm|AhSH!ms_Qq zF{<};%wFN9D;afVC{RRu{|&z)@L(}}lv!i!1FssjyND#?K3z7V`N7lK@gh=}_HV{_ zseja2g)mZ6#qo=J?uW^-6v@^^uw@O%OYl_(5_O4^!;ejN2HX{xFuBK5xt-d?D(D- z%&Bz*DHN%I^2Kl&<-p70wqxk1HFuOPygVqvs!GFOSOai1@P%Vutkf8P0f4wNX2|38 zt*fw^${*`fh~-ZWo+tcbocB%B8NJ0Dt_ta7sw)LgFlSa6h~?U ztl0d*3!7JvJBQHf6wA=yMyIoSy{5{Fj&prSQt-cPuU)v--QC?#Uvm-%14kK#!3yeh zI^zrmJsC?ul}?LL6po=9w!-r3^<8Aqa^z(u|0F5d@pwUoa5PzGSC{bsBV6U zWQWs4})S!R(&JVzGKnibEBp=9I*e1x0$K7N{j6(>t2{v)P-X6LPYs#LjQP+Mc3EYTHB~~IWD1pLYgtrxnSpLZSWp`kOIE_-z#}qY`Pouyos>c6 z6qSZizF*U6!9Esp^nvae(xY)9C0QCA5Othfa7Aiu_nDf{B8zP3 z`5}yr$z~TUmcdT6(u&8@L**$c1)ZsL`}+^hn}Z{`oJ*O)J!;H?3#~JY-f>n{5*Bu#0vNEywa}5`lC(k8MrNlPWZz#*gJ*dvlZ%SU@-&CH6eSymXOCK7ck8@o5Q)8z^a9+3O5R67ve6xKhs3D6rB z0hHe(+FfRsSBKoj*k6S?qV*MelvV*HKDs;?-GN1_aw9FoFvf$ojD8z_JW6QcP{>S& zyOuHXpjwjEz*!v4<`PV9S!RWycsuF}B7NFA$`5=ies=pGTE#z$rsTDPUU5&^#4> zEUo7d2?|VQY8S_|ZmrJ|yuA`vg;}d(+^m-2l(LyI*w^tMiDt%30MaL-@n@bRd2JLa zw?q?mhq-|UrIjtZM z1ZW#0+@q-&jBkCF35QSf>LV617$hyf7GG!9uyxRGt%l*WMH@&Bg(@Y1oJHp$P__38 zLLL{?7P2Pq{CzSv38IynMXzpDq;`z02yXzKdiV;vcN%QxG7cFPDYr^OO4mMi46ear za;<+Lmhjh@EUj83`dp5hBLY;CDvTIC>vK3p?Ek06V|5=n@&!Lb6pgFPNwI?ILYjVb z^%XODZRFxvQcj^Rg=jq*j+Ec1&lBqash5Y+GgY8i6?-QwU!5JDR|@tcg@IwgiEde1 z;{2ZB6Fc~c)n-c!{>6|%ifxZ0ghodSKcP-Y0bx(iOfAPSZimw4Ap7oN_fE-s8sJrlj6|AeOedn<0$q%`3k&7X3=7Nuf;+diZGg&FF zr`hJ=swAcdI5*$!wOAq7NOI`D6zK5`55cg8@|BQ{=-e4~41L{u0{IY2Y1Rz-Sp+u^ zYB%ZB$T>X2fj_y(OcEQ!5ZiUaoj3<|W=C9--$~yau}A>hY#GbZ^~{nf=CX#haBvd| zrWyxYRqlpz9CX$2#H!;)oB<0t$4fl&6p?MX3K7G`q0#CYQG+)@F@G4TUk)lhs=}4;XgZ_JB=Bv6&C!|~{VvQuV zwU-OM6c`(@(sb?65nRJ7vllC%;-)f${*u&NO`plDsP$UrnxWtxJw>An5|0kwfCB&P zc!#x~=EX!?g!C69Po9aryrKG@K~!7Of<>5BBTf|bW4G10R^=siKHNUArdoBi_*+wM z9v`8(v@@870#GfgSh}xBBh(*7Dk&u zmCU2zm1~&fTF~W|^j8X?NWkE+)FQ@!t#IgTY1#Tw8`< zsMCjSghEC#6a8SnOiW2?>uE2s!Or23qqq%nuwQHE8AjfE|{?4jE0LN=e@fSW&$ z$6+K}UqK8O;T&{ABxS9EL6~DYrlh6S|0Rtz@N|Q%23|6iy#?%+!ZQ>Jbn> zQd%V|^?No{A`E5Q>2HMfkR4l?D6(Lj88%G2sE}b= z7i!_X!{z2@G}MBr+kk>&bCO>yh1MeGqR)4-1rFw$p+iQep|;vASx(7f1W{E~3z`uM?lz`0P^`W*mUjDD_+%16ujdZNoii+1B$y5d`RDx zCq}x2qv4Zl=n`P9qXPqTl)R1em8F7ho{yybjlEDBCEBUDF5J6|*@bLGD-^gx*4=*w z#cQaQ`d5VfkCYBRa!6@a)JmO5`bREQjSg3;t4Z%Jmv`WJKv0RR)?Ws51Tj(RSpsxs zGYri}a3%N!Wqe@Gyu;zvuq2nv^L!jxFy3ZhiR0(?4L>u(%`0Q%P+RB;-klQp`=Og% zkg6y>RdlZwmK9aPp|dn}i>iQAY+!PCFzvSxkNN6hs0EJ<$~>ruLdKzPA2Crg`k)QN zh>j1SF{Rv9F4rC6f{?-%GQSN}CGEV{r5v`4B~9+J3?6h$3*$Ix*LF6@ z&E-hBG1 zwd(_ONTeE|hhGG$J$MLK%_av;lZ8y>E@VXLjtx3)G18FD=HpoFu-5HxImnq~jDd3< zS4R}q#OCDWB$L!={JnN1&*2f??N$!;nH*YfVU``buwutK12da5p_7jRONSW_rO8xg z=W#ixjv)^=jr>8VEE-lxf!T201R;wT(;AYol73)rj4!K*6&pIMMUxrJRd5;md`NZ( zRCiE6lpSvYTZIZzHM0kHsG#{6LyiD#`5ZfBZa_SK3lAHdW5$eqxRq@;b9!^SYqF!% z`RNSDu^N^f;KSa-om1h{i0KMm8*PIW_5aV_+rG51u6@HMFo*M|d?)5CP40oT05ECfnF4vP{j13eMjH2Bi zY-x9-b@f#dNiBHSc+7JiGm{uK?P~Y+++6L(vu|mV8Rwiif9LW3J23kz$S@wEbE)2? zY(W}NvTwEMOres|437+{|G0qEw+|^%@%zUg|Es@*!qo3lj$Go$M^wa=GMQt3V)QhF zlfqqn0~}AybRHeLJuH;cAw!Z;ca&=EXkAl=`C@}K?7wa3XtZtX$Oe9f8zrGPwjF|^ zQYfT<3)k3Zv#i0_oowI->kf&^xncpfMU3YjH}Xv5X^#eGq6?}yQ0#9PB55Zgi>_V+ z$HX}w2r686Ly;*F!3+f2gtF*u>IK{>>#pd7<`qS(U&0_BX1xujO=FrmqqwFubbrqJ za{l3@B62FV8N;W2`96fS36s^5X?xH8mj3K>5vzdTSQDb$7 z?Um=aaK%v}LW(@63rKzYkP_ok|NM{t*;ztJC8LKLm*U8X&duBDUGN-N!2wc>k7Z!} z=!7?@j&cyShiuHoa$of$%qn0Ua~tzLuN$VPQ={m_Z{8RTU{$zs{FQ3ksM93!+$bWZ zC{2H*62>VMB)DKY9WL`YZ_iy{rXR8umDpZMvw^`>Vf8W*Eiu?A7sXGZGXQpuzuc&R z@Tf|2Y7WM-j|zyi(negoV~$Na*ke!qwX-8l#U?k z?*OpPdYU@ngTiaq8+B&&&VpOqFCIMFMP819;Mitm%YOSciz^Z(lD&1`nk3??f+%(d z+0cw9D7v3p0|PQ(a2cKxrlJ*72*|zuSs1Ee21`PU|LHHB=ogUsMj&PUAOC@n`tc8E z$=Qb9u7nMATLu#VDrR7M9`4hEu-yu-&AK9Cqr>usk2+OjlL8>nJ8+e&C>L2=C@P^R zOD$6oH=DQ1tP@p_$QKmrjWzvry4Z|QBngdQe$&w7g99fOT5TZ(pru zz|4%w>7s$pT{s4ObHY(^-ZHp5*TGu^u7$bXx;Y}A;c4Ri!SqX-Q zXo{lZ6xD4ukN7594&5PgJp<1$&nfCL=GieRiq=<0*}Fu2E^~)&PBAMzKrpqoJ(981 z-Buiz0L?Iq3i@w9AWQoNq`qlL)hqx0BPtaC@&A_ke1z{vE8H3kMM8kAZUZ!tm26kQ zAw}m-mROqJB0Kc}!A{imcmjEXwvUo4<;f#5s4=qA4im}cSFl1I7mka`E0@CsS`n-Pf29wRf7V0FO8bwMP$JMqb( zo|b4aWQtTUX08^~fzL=_{9;)vtchuj>e~?7CqLCV8RB;-MQnTJXxr@aCl*2@l3(H- z8~#XZsKO2qN1u6I)e``S9aawG)=_@6a0L_6md?ljlKmEYSZ0A$98qcq|-WKJsK!=%WHk9da(|`oLXApK4E?*5%$!68SV>9i|d1;#|eeqXENjap^zFB>p}k zw`03(rd5J>4PE4ziPMQ%P!i>@oaoGZR1BGuOoK2r1$(8QghnYs>Q9Nf{sL0p@;E?9 z-TI*vq{z~1fscAA@yb=hu`p;9>PNxkGZt$>IT`~`aM1V+w`&PVh0%>lQQs4UMz!Jn;Kk)yzP^yY39`To9t_>UvuUOF6r)h$@ zq>hq-fMzw2MDDC0LIusl^lxS?JwC+Y7A!{Z}4L*lfhBwHiL!m0En(M%)fxZVL_ z^mGWq2M0uZ>WQpd5(c1B@W9+rje(7ZAB~JCnFRSpjUPsd(w9yboDwv3Nde4bb&d$$ z_%P6j~^w>xfv+Hz$twa~ZyINvO!cU5yt(x2Bl@L#Zsk zrOS>#BuMRCK)cblnhvQh#^RQGoIsU00R_4u&Y0Zdiec&bUfFC$jjRWQ+yG*y$#5u0bB^LTX; zK1do|`8B{aZc!F3FOX%L5QHyWWfJnt_lPhs;|aEjLgw&Dc~>JLQ~lEMYlx}nBlVFc z<>0*pQEeIik}h{L+XQVKBOAfT3Sumt0Zw`Oc0!GbetODWVz!AlqHle{Tzoo8Gh%{! zNNo$_RNVp5CEKHc?vf>vOaJTt`G;62KYIbGZ+%Q*^4P5(`T3HN>J*SP0{Fi12>5G+ zq#LSon!NiPMbyZAH2gk7^ulC*4G|M!Ww|>}Ef3eIt=1kM;EBhsE*n0ga@{NV@pArq z%hX7V8`h@ug-(EYM)d>4l%R6J;BNKDz6cCy$l^{$oR_7Ry`7CpVA_dcze?;ntpWT4 zM?xW)?^961aum^(G2EPiRx#Je*rI@NdrqudS{0gs!>Cvf8-3DK-P0Nhdx>6{Vw4|5 zI&{e^5!ch6_n_RZh_9STqU6!?@^&J=Jv`Fp^AKB)t+sLMvXNyfN0k%#l>g#(8@WmT zK~OYy(em%Q2@ZI2>9@WY<^$SRS>!Y0gudtBycZSv7%8RlFd5sC4;?@8gCk7D2BD9*j+m9j1*c zU(y_>%8L}E@9mIpnRq)$~@9_ zF96IF6RJqD#f@TEU43YYMR<9-=!sA`o0?}ww)KgEG^5Bxvr}3J1nj!>iI+k{@4_T4 zyab5iZOW9NZ=Wi9k%a&G$8Y2@{rBhDuP*hXq+eBljkk(GQIX>d8T@UcU`)?m?ENqZP_F!PXuh+1KUgE%d z?bJw)DpHD;6Y336R_8PcDQ--ZD@~#mdXN;8uFzVOQr5$gP{YjWq*m9RL^xRhOkGmG z$7NeDM8~I$pVt3mZkFz+2J*!$^3HUAAV73I@05j`AT07WLFON%R3B7nF&QfqP}3*P ze)RNI47NTbR`PBKBA?8;7480pi=Z&#w)7s3HV06->)3ecR1kpp59Tkm#VMi#E-x>e zt>jzlnwl4pa4l7&>+0z@@JL5YIfIIrV#HJ`IXZ>g(qroROv9}UNPQcTsro~*)Or4s zJReBi=sfP_XN2KQsG%sd5;xwAz@w1_HG_px39`bHMb{HCZa0u$kQUZ& zBqGdY(}_VUL4CkOpt@TmpjbLb-XNB?8-498gs+L-wAG4rB8cwmPrQX@)*$mH9Ty^3 zHzCj_w;{$#6pg+I*dB^nPKwu^BtW5-J+Ga}Kk=}3Oy%=rty9y)(Bqq}oJXbNUL7LT zn8#BilxSvBMB3wqxi(|G;4{_JwXm-19EX9~ z^ri}xA3oI}2CI3edWc?_41m`dKk*}^?*lVq-d;x1tgz2~v=TQz+jS6uHGhdyTdVs9 z9g!%Dnh^OD3P&7+Tl|2H*2c5nU_O06)gJGg zNdU#6T~DnXQC=i%OB_+xYk{fO=?h_qw6PryJ1<)x+enTsUDX%SAu0=dQOxbGcxREY<7FrUncdU`+#R-2azW zUf~Wf&K22SOUIWdUAjWrxg^%qVZWL#_+fH%$_)#{vVWZDd}edDIR?!7p4R$u=m9aK zSjD8}$;SQ1*q_9-ZgP;@8g)GC8S^|}hynY4hKRJ~+nAZPo!q7>6|h^bDR|TM)FIqE z-dCd%f*LCuPowSRu)W!3Op9x(y z1AFCWvc%#r57M2(Iw^b;8Eaekzvw{+^p1N2lY zOp6Pm~z=1(YYw_io@x)={_Qu8_k+( zIlCemuNeo^HeHBCXy^?X70ScP!B02(s3LM(*dtHFdI70#dSI&!N54>~3~!hIf(0FR z?qOj8_I0^JlAG~egn3PrndDJ7#$qhj_Z8s2Yxlff4}BirDCn+>xjQ=AAvmi(h|d2vQ5 zrch|S@57kheyK*@yvt|z`z$dfi_Os(#qHLtHR*JI`SA}}{IOteqOFeaFom*;usvjS%0b>>zgm8aMY*^W9s6+avm1d0(Gfm}f9 z8y;C+WIF9;leCF;xEu3H-WN8Z95DD@9LTL*twKe zOHh=3Pd#SBM@}JdKT$N>4iAZtWnXqPYw$cQH_5(*P`7w7qWCzh|wVc(HYBaGB zY4&)og)4VHRRpHL_Igic{m?Bj3&sc(27Df2dV z#8K)?LJFJjMW+NG%oS=mh+$C$4v#rm$ZLy+*k+Z@5Cvsl7bmVTGRT&Vq>wI;y8x+_ z{65z;#6X~@VrC8kGgRJBQC{8*&TgU&$(aTHGtk<3s>CVH9Gpth&WD?5_5LKf1u_r% z_NP})cMYxY=3Xz%`Eh3myx`EucX{b7q;|nmT&0gBV2?F<8AY_dA?O|6PUb~aa1I$L z8i<+rr20da3yQNXKuWQx1c(K>p!B{r$XR#V6%grAZEgUIsj;Z-64^|>uWum?lRcYu4v`~`pa*G1cU6uPNQrN!v^LK3Zi4~m(`R=W7%h|C6v-9y z+t9&qT|)E;;LjO{y`?-|gouK}P{nCoP$rQTurtP@J1Rz5V_WZsc589GSlF<*MFM3$ z(AvX^?0iedOQ+K;mWYUcP+xcpGbyHd({f!xz6yl9!ygCfMoc1BnUaLL! zU`n1=0aAV+l6mfB^S6O~!{!+qRe+^2JJ;}+O)Q8YLtaFZ3QBxSBi8elj#XQ zbG;yy6aDj0Ei4C0wyKhvwwdasMwA~eAocA!CvFqXj6A0eDGGG%a}6>gP(lj~86|%* z?xtPrWSd!DVmS=+j@u02-`%vQY$w|_8QG8Ivuhr%1f*=_n^x|*fmilC+hvrE)N)cR zuv#(C^M-DDITJCZV%*y&t!uE|U?g240S-l#+|9R>-mb|`KW`ks(Na0VRg|ZtW^L!h zQ$b7_n3F#3*r#|QG-J$3!h?#__h3VoQAAmrc0-e=G6t?jj!T`IZ2?j?`vam(zq1y- zOB7zt?mcAL`yTRH*khI;m881DF3iu6#G&5o3Reiv2q2x8OF^n81DwR8Z8*Mw)VDfp zA~_#X|DrW#I|GWVuTk7GRp3nM^Lwe0V>4=5Mh#OOv80%e478@Qw$!=hMMT6?Ybi)c zxU%{h88E14Be1(In<~rt$1tvuN-1*bgz+l8m%13p%c>DlpGnC1`Va7vZnpQtIYHFE zm+(S1afo21Yl-nAU0iZG(Guc6j`TsOowJ^}B+fu8n5`mP$)V@WCn?Tz)di+zqMRNi zC09o>slNnHDku9W5;Vs;XzbA?y7bRp^ODdGLu6aQUfaokTS#3FelOz_;lW2_&!n)o zs7Y$navD;?5*B9Af`#`OW%YzIR%Do2b3T|fgPasB9~s~{?O82|yGrb^2UgoBAw`T0 zt9Kpz4cr_&lFk3*%E}?k_ooZx!o6S>iXc@63!iDCSSlI)FFKi$4{Bko7^dlne_Kz< zX&lBKn5&WVe9KqbK`~()1lKzPs82(R3zB_CIm?}ytX6AH-GML~r;`<;lusTd&9z{O z%PGTgO4kDWLNY8ehM&9UPQlJ+%t#0F$zI#_-^+5W`4ps<9p4QFb*#D6BUmO%#(hCp zl`<7h`=$xP>ap2*l`sMA#zLI`Xb`I7dBdVBES}t1X~z|&J>Bvoiyq?vd&;Va%-Txz zL?H)gIqpuBeWfyhp{!f-cbJEr{8QN#lAttYN|Uk3?N`6WP{LnzdOPtnd`Z&wWmllS z$dbA|4li}_e6pchp|qRDlKG4Yy(ms?^MAUB44^1tdD@R@u^nRokJT?))>PpRI{<~R^>?Bnh zQbXT+n*q!*R||qU95$aWe#O_C&D&U$k)s$_x=_zSlNBIqeM$2kA10WL_WGXLvswF@ z;RzC@-(mH5o-G=D)^i`@Aa7uDQviN!7fIR2}t&W6a`re!2^pjof0TLd;WW7+JXB7+e;?JLC#1zmWp&53J`I5Q*33#}?BH01C8F2Sv zM(mo)?Q*%?XND_=G2%5hesb=^lW)0PPCxMX)uS+1-YsD&;e|nsUUp%p<1T{tr9yt| zh!~aqG?rG+bp$25{nF3klR?mlqxx(Y0Cm-A+z^l*d^Fxj~z7!?3p zB_{Om&j#R(3dawpx#1rK34}l6hobz zg_v2V!r586wMCxq@|b#7Ip4eGaywi5sS~mOotRd6IN;*J zU8U9)f&}DGlFj4gQlb3MiKYzRR>0h^g z`>8afkn2DrKBA(!wz_Hq1K|!^PS7xT*j%_RALP~3bFe8U5G9W&E*!D$W1hKPTWWAG z$xc1TX}@4t*TYU|En9$bO2(Ag0Gm45Ll8GEK&nVE-H%ejrwR?pU&H$kFz3%{*jQZO za*)*<7@xW<5!04Frqj7r*icX{oxeZlZN49{%AebpQ^%dSL%SNCu} z|A~IaKP(hBp)u7}%8icIzQS?YJPXS8s?-XtGa7Y9y}Gi4Z1$!pqg0w$>h7h(uZx0G zci?%U;FcQX8z?#a_8bDXm%L)y6-aSkFeM*0C~fzZ`Y5HsW#fF-0gKBk!%|MyB%{{I zQdv(qGW8Alg;mybn+L@}8&+Ckdn*&zacdyzLxe63sn0Eg-){ZzJ#>`+E+AD}N;Q++ zvJ9WlL%`;MOZ}c+%*mUIi+MX@HSdG^NmgAak=P~Zil}>dTT06@Z^3JoQf#{FNtN)D za#I9uZjSpBk1B!G1UCn}6)y1RWK31VP<_52kzOF{pa7}5@RO1);jv@zArXwT-L%oD zNl@`PMdge-I@flWg_!n}ZE#b(??eW+!8)BM0?_S1hny;FR%gQ8rI3Hh69{N+Uoa(Z z8mDh7^;NA;Z1HRvUW8iBu;k~lvunAWtmx`m;MHY6z~GW_8GEh{zedLE_TkH`i?{iLdaM|edqzG@Ikdf)KFQ|nRh;mjwKFDI`SUnaoCa5)69La z`0POPdt^&N%0uu9^PVpXQg~X~tM=&_`*hl$2}%aW@`{P&WT!}??z-}}uHbd(bUJh; z92A|Gg&ie4u_cV@1kv26c!I*VJY?_J7|Y%;aF{&Zld9m_9Ac>x=f*ugD3eVj>M9gU zm9&9$*SN#4#uVXdyEXP@kP3QwiCy#BUK&!OXRgEQX1ip!A9W8Zjj{!&r%X&56$FpS z+)l2z-}BZ54$ZOX@)KG7M8DGN1*E<;DYYZEvqng*K?Oc2HQX)o+hQS=qVom#jCsD{ zHdcAPTrO-6ho8L`b5!9;DM;Bk7tu{_a$g3ihwKdJse-lZ^Kge67Tp2q9_X#l$(}de zK{R<>2v$F0(j_3ZB$S0=-Kaw>rD@t&-%lGa_tX0FL?W$Ot>&SxWJBv?;ULnVf4y`$ zrd-kIYfD;SA$^42&1BjOTPsa)U{8H9q^y<1lsw4VN1#MpX31i7AAWKqFRl0jY0HN-fPvDbFIL+9XI_6-)D^b;qGC zr1Lw>`6?;n0#r-3&Pw+_}7DM;C0^P-jY#Zrn(SzF<*N}11fS{_+r$~5^D zifWPAub{6U3Fnh_gsBL-x2z!szDAc;Rn`uTA0CcYX_pDAFyA*g2@AAv9#TSoY;viP z>0ZH)=EJV~#BIhWiOlWfgYe8H*5M6mzZgW@y0&xgZUoTPlLHS5U! zPbW5@iAK`NGrf9q;X|40nM{3y8LpG!VF}$73?)Rbev(>%9*=^3ZP$JUq_RC2)bo^t z)Y=q-WJitKNJb@50-9AJ6P=S&R5XUra2YQ>oxCS=F{8mp)eIk{xf8vTNqhoQHTz{7*xO0Ht0rpz-{^&|p;yTiJ8LZ9n_HR^o(>k-%&@~sZl z(4mtzkhIw?yJC(KWBg#51qLu!@a2%=w0;2p2d)&PT&gG7(~k94LaVI$nTZNu%scO& zu^YIyGWw#t2?Z&@#sOi9rzA+$#ww4>nDF^M!h! zD5Y$vl$IQI=u>7?X4#Prt$AYGbdoViSshr_&cBtpm`_F}Y*CsxMIQ~3S*0{OqmfRh za~dN}Ctvu%ZPldXx&D3FN}n^O?8M*~&$YBF+y&V=5sw=`!t1n@EL-DZy#rveVou+e zLn`ROdgvZcNl5t`h~lQ;O%(xVq!?H|Z>|Kl&>>!1F-bpffbh18FKmzufaox1}3m0y1)K>FLQPf00sE(Fg)sSewPG!LNYtv{XZxif#ifXyr5xjeUm>M}!BmhNgjWq< z5EGtOl4eV&O(U-|<9&Wusy;ausL%odK&Or_3?s+7hc$_K|E3ZiwrQkGmhuu4db+zI z49yw@+&(;_jVFiEm&q9?Fpexisy`4g%Z#^ay*pASxngoJ;4a51#yCto{|ZQ1XIKD} zwIrmnS)!XVlQ8O2I%*_7n|Kdg&5KB4JMOHy0SXPtmxP0irr13pJwIy+NZq>iC%`Yi zlJN)p@x!fu`~rW!BECkMbpffbhLkL&M1ghV#*YQLbzVy0E*HCe8d4QxTg*cWy|}(y zq%R-$tV>2L%d(Jq$WOFDlZDtTmA;aY@}NWN&=>p~DTUP!TqV0!Vc|N-g#Ex&>s<26l{}ClMsf=B2C|X>{f<<9G4XFg#^B$F!QUJgHCwcsTBRlGiAAX0w zk^lVpySTevKR-GQRdXT*$U8m0_Ffc_FsdO(iZPz90%q|#Q z?Cr&4ddHRG#@{1l%b{~(kU7%GNTghhka{Qb-8+@rb<(b_ zKVsb5%TgWQZ8r57Y9Enrv{q7-xXT-jiSFd}BZ@ZGA*d)#T`lw)(-b`g zhxIg#hiN){BM7N`(ek|SFWRKZm#}E_i4$g3)KvC>@3IEJ8d4%`GUwD^5mG@9b`%(W z2s_QNE9H1~tD+C{wxh-h1Hu~s-uG!pAyty$)H5AFky8Ks@y8#C5%t5Z-^ky;T>10I z8#gZ86aN)kieTz@a%sQ+BAZeurOuD>{NoZVQuf3Nq%h3u*O^0$`BVa;2)&JC=|wVe z6UJ3a|2s@w;({e1<-uqBF&q3!DTRze)_HhgW49zX*mhZDtxn>ANYE;1munn^`2dnR zjY1&iz~PKA6&i{z%P8AWZ%f4K?TLlSNI1*{)?Zg>^b~g1)-1wnIv%GxqE5GTn44$N zS+T*?$+uw|T6D5=LU%_p9LaQ>p>c*ku*y6WUjwP22TR`DJtZNE93Z!AE{AZ3o7K#CKqd1s)@m`^2Wib@&_Y!-0ys2(@-5Un>FiB&mS5s$zO*&C`lnE`2-oYd9jegV-y~?7L z{bs8cRxXrEXv!G3Ow>HAbg50yz{yqdUj->{g6uoDIa?`61%0^hR2g{fTlgrs7O6^j zDTjOGx(+@mR`*^%4XMQwDJ8Uj0#ZL9q{z!(Boy8H0KGs$zv0R+WGVdq=Y=ixUy)Kj z{CMluZ~y%BC&|xKT1tgAMUV=fh7^W*&8wDhnbfU0u2F?8qTZL>o`GJw(j^96X1S7( z^1Q$dwl8*0h*D}MC|Ax~??dxg*t9Kr{meJv&`8OPY!o;dQkO6z>4Z#UQaM7*r7GA( z^u=ka5Bx7wb^SV>&X{blfNM;o%A-B(peCL$4iz<*UR@IU-R@55E?now<)4)>4#2Cp zI9+NF8lFO{RjWlLeU%d(C)R|Wx$Gq&B{Fl&HL&B>jH5;jp|2zz2ehnc)6e)Fk?42# zG^Cn}xZ6|wC#BS{|NP-68B$~^-1zy&zx@HfTu7;Z-Ilub!ykV~WAs1&hT60&r2@NW z23PPV2@k=Rhm>d!SMXTPn}kJOKE1D2797LWH5luGT675B_t>neJ$P~^6WxaOK+FX9 z6_9!u-r?+4?4r9K6~rN75Mu zeAd_lRmONCmp1moT{>TTM2slC&aPxqKBa@oB`8;hE}DBc*76-A{ZL1!Lgo*w zD+_N)c_L;l^jX7hhA`Z_7aadOLnvuU%{165P@>JUIv3*58v>(Wo7#$Y$^ z^V5yl`^$@zWs zGzN>rWX4^noQGyioUj>q9@cDM1*xD1TMl%1&K7s@$bKnGbG9MlYFlIEsB%Tbq?cJf zbdB&qsCS87RdCL3NB>_!swggnlIa)V|3r`9?_??b0vB3O^;QA;HxTCFD2XL+*d+M z>=ICkWPmnT$TrHhiIfj3Wf5mSeWSk$vJ#}qSZ%R&e#e-geK3#E(+sn*1QBcLlR;MJ z9=y~^p7B~;f|!N*10!)1kS{ zR}CWE1eLxRoh0K6E3cFE_L z80R@Uk<*dU>C1PtFh^ez+h;dwAFip{ZYO$QT(=L?G!aF{QSj;rj`T$%r=cwo(a%D~ zlt=oUS?L-X9vK-)u4AY-3)9j`8^F7SKSoc*HIrLnU@S>BK&=<9Wr>N$SsPmohJE|j zNh#T{mpu)sgGj5z(nHKCa-;pPqpiNon#ekpqWSm?+!IBRx+Fp>EJErki1$4O zZ~7%jrH3OXiNu9^1^YA5(MKdo&qQVAjCXS%n(W1p;(`uhQ%`YU38@+D#HFj=%C4PM z&^Eztsg$l{xkSSR`*g1SU02uBooaS+dWwv(hNz{#Q`il?n%=oOW??Go61rZNZ0`wu z8N<8Xv9rVNhibG6`+LAf$2D7-=iZqa@0baxY+9gpOg!lz|JqwwS=msQ)~G_Y@!@3& z&>!ZZiqi(kM_zB`3}WH@^)MMsm^q{PeIg6zui{eE_t_AOCmiB}oGapM zii(SDrCS|d*U@F?I3H&PVOM_XD9mm!}%3R~% z?SU>)D6ee0{oCR_C#GW`diz(xV$;Jsq&g?R1XAZ|TrNrw|3yfBEkjblmO2F~s~F}L zj$0$$GP#`YDO8%JuFq>3pEHBX%$)#PDq$p>mFQe#My-@}5VL7H?H7-fWJ|fkCQvN6 zZCdLgboIzi`=e!tBTkovHnd}#o3pdCo12?sW7<|&s}qi_B44e;L3Fxp)6MXlru!tJaa68m4t$wb zD-uayIU_(=vZYdAK0P~T5RZFOC$mLcif36oVJp_|KH=|rVKgUdnz`}NGueJ6+e3qZ zWD{7`mWR};^L%;y7eMNws`vkYNd5FzklHzc)DvR2Q-V+*bIMhwapNuo#T?R=ipbU! zSg=rPtT&48KJr_#rSj~3m&mqi`U*tJkecWq@Z@>m$E{lKCI5a0nkBBJxFK9-tl(?= zHTjARji!DN|ybqV7h6doZR zgBV4b3q$WEQc5$a7%3NHaPQER8px)s11#_egVt>9D4&Rb{ei$zIypw zY)a~nZL$VRT4e2D)s;bWfn1N68T28W2^giT?+>hLa+)O5s3Z8V8)qD@;g!=;DoO1} zT;UOoxJt(fq#EH_e(p~J0?8Bftt8$-rLJ7*q@>h|_xw~}sEce6)_2t}8?L^qv?8Q} zVh`RgouF!-ERtrG_}Ypc?T9Vq_EuLnynH#6^GsMW`f z-FHOTF#d{)L@M$xGQ@wR-)!OilV2?37}r|uMDbgLOu*%KIpAIvd&%5vh6$0L$jtHk zL`t24lx94Vo6EdVMj}jv;hl9k{c`37c4?$XA>uSsr-zyT$Yx@7s7t9}mq2O&$YBf< zi5M2at5lqURAs$Y4)k`b!-j0c$))TApm34>!yjeGh%IHcjk+`8QnO*DiRPy)|3WKF zz7rW&4~JAYydvgu-*&*F$AxV?cD;NxB{GhdWehT;;>KPE(>$bbuQ6g0;~O!)=HDMu zoB#b+*Z^1l^Tw@PpZIj2a~4uvmv^92gcOy9g<1X)M~u5LUK@diJLnE@vx9i8B__i#a+_e5Ahzgz zY5HNb7J+}HMFM9QZ(cN1tHKmxSmfAoNieR&VzPT8(Lcm*OB*J@*iuB?=X8$HUqR}| zt5=fF;w%zh-UkcMJz~E!#3@mDk8PUj1#%r-K zlspxpH&}F;_g@C7-~VDI5Rv!azhE7oht&7nUn&o&TFI88GYdDRFfVzt2Yj-7!Z;iC zhz-@v9)2N(OZIKn*1R=0IB0nP{s6AMCx~+PysECQuAC$5x4EHO9 zQI&==j)EOoF>_l``7E3D6pyUu**b7&^lMr}6?O648sLEe2Lo&U>2r{(y!?=reCXyz zsBVFttkyPjZH`>smgS(z?sj2V%kkpeOsby}-BrmD{6tx0hIgOL^(h|FTZu1saWM_F z`VX6$4lILnt*@+EZ2PySc1WS^qxfT%k>L_aNolyU?8OH!itV<^+hNzs+8T7(p(g%=apOKg^V9*z=AhA22ZKd2N* zD6CeiXO_Hli!a5Yy32+$yz*e^aj!ed_(Ko0S?lS+Ww~{tDaIlbgT%lgXJo*k4F;#! z16BAya=RtQ9rSs{PcKx2GM2fyxh)qo7%Afndddh11}sCOD?$cM zJUtxA5a`a$Sz<&s=gvb)=TKZ1D?6w+F!KWTtSKUw!sOy2O32K*6gbCOA9rRZR?p*T zhT#LP3mxkLp2_g{Jy!WU*-bpej<-eSB`=-CmWp7cHv(=gH-oKvd=Hd0;?GRH2Cq?O z`*?}XAIOtP5?Q|PUzZ{E87cK$wQPG_8d78Y_cMis&p_%mw2P2ZU^lTI>FuWQu)KN=mNI+cW39-c$~}*=et#sAAvzz!LrfbaKuCGeU%Z>mx2EMP*)S6tpZKu3IXhM5 z5BZ^qJJa4asO2_^=EFxOwm@oj#w*8cL9Oz^Go`6q@+;qARz^xlsd|@GJD7`1rgQoc zW{bxBbG?PHHd1jp6J2bhs4=_4Wg03Mr}yBhF=3p_mos-nM@m5IQl0X4x8&cP=g00q zwbf=bLB>xmj|f`rB$29-ch=O|d05{f7z&O@FL9jpl4Wg@T$_8Y%7^WXTYcwf)-ZpbVF$Dm z6F6IK3mb{Xf?{M>q_-h*#^Mp_HLRE>qFnO_+>m$4Ma;rO3hab*rsg^Ug;=}n%xp>%#AjdnbOI*r@45YE@^?j zx-@3^yn`V+Uf0IAu8NRSL#QdGnsdEauqVGptLxQXepvCZkJsp&DTT|~sSb0h#- zZlCu@7YL$owiDjjUT{FWRfd$!`haXz?=aCXg=FzC=bIv@9GlfnU!BorC&~N`kd;#X zJ+LoB%BY1dnPJfMg^>DQ$G;ta3UwX5S#Brire^Mp+gO zsz|Kmk zyx%_~3S^w^R0E@oS~zV!FStkK6~Hf|o(CCMM!J0r8+J5e+#(#3*mBI)Vkwm;|D6`y zOG_7!`hFmF35M{WVQh&czpGO^6Lskrb1g4fK0U!3+Cgxx3I6noCHQMmK+*0 zCUR^ENR6=f^+^d*tk06^1*O~J@GG!Ue2AS|D+#G!YAwvqZBFDNXVC z>^J0l*;dh#PzGXTrV4+|0fwyDW4-{X<`YPLlp)nm_BuCe?zs$OzJS#C0I3=wVVO4c<6PQdP(6QaDK7?(ax5xuU}s81uEQ{AiuqfrVjptops6ByHRbDlJ zEmrp;Q++0V0jci+QdbdDMAysHq>Fhle#w?1I@O^hrH;(_WJA^Vi8u439YgnVbZq1y z#c8pnY*F(U>yv2Mb#pqu%x;d&^Gx{ax!OdLqKuj0S~?!j?~e9$EcEp?YY+S9=K#+j`DG-$C0vbk=%qR{ZXR7kllAC$_5k) z1*Xj+q_~tVOAZfTJt<$+S_i-%I+X2;31YElGNE4UCp>-=ChV!92n0fIjBz<8)qbax zQcmr%BiGqhVDlX}lzj9c+Krbz=%-WK6I-SrY4bWPn%Oxa!TDcoe92+B6v5b~B zCyWjJLA`j$Qs-KrUWAmw1%+lF3|OM?;+Y3xO>Z*25Yi6um0XIm0GTVfyl7?<6~7IS zR(pCLDQgGsXZJQ`!*OEvMJNE*tS8^fH(J$tM6H=u;LTHDs24S4OdmYJjHDzr1&w)+ z-$cIM7nxy}9KMKA-wQ~6ACUThE?RtQgC}nfL5-Y{q-zO_M3ISVvKY4Du@5T^`7o9z zxExX>+?ujJWlys}YJ(F>CK9eDn3~3YTT9kusL`rD7nf=m-4k;V4o4hrSJb~5OpQh6 zo-uRXBBXK)N~(rkhbp7kgd?7)n~xeKNOeS)1&QTu7w&3ulqNk6{+k+FLR7xVR2@As z1OclqLD4?OZ(fy9I1;^v{~)BC6eXRSo(&&_F3}3NR34IOhpAm?B-@1(Vs1x<34>BA z+ETu=kP31W5hfa#7@H7n$EgVi%Y>hDC*QKkF*~itBpRUToNzn9og%tm@PVJ$eo-xo zDf3mR%tPvuXg*0#sEpj*@UU=nA*H^Pp+!d@(MaH7zVRk@g;nR{QZpe{dGcu4JV#bV zBP@C_H{#6$k>kPTLR-pWwTT%5RYh3^TCKGiG9iDXcFa35{b8($&xCFV&ty-KrOBB@ zNL}493}OM6=~Yl`^M)R(!s~h|$8XVPL`XFXI&t)`)`nzARfAe23|m_5d<3s`bqT$` zG7JxF8Y7J)mlT!Lr)k}Aa~Kwe=|n>3QG!;GA>~Ei20GFGE>nNMbn4YCOCZ&6%9Ke7 zNmbA_0Q*)gcl99VcHcIw_f}iifCtA1k%jEkJnYxN&s%0T$B3poJ9WS-iF#Q41##zS z&vM=jhI&n6ZJ6sJ5rG7b4mZYv7vt!19Dtj0_JppHSbN2gf)~Ot8|c4))b{}?gY?kW zPkPz5fR)b29C@u7xloCEvSni}=nJ+@^}M*-{ARyply|Ve_Nb@C)&jv(Svs~gUcpC( z8of8Wnjb(W68d;Hkw=?SeT+gV67g~^J#U(un|JrPl$LwNAErWmIVls}GN>bv3NKOOXL zR>+WA^CQKkc;?3hQqSuTdApQ}-UTfUu$v`#sV0}!T-#IiA?wCkjUkoo%-)dVyb4yq z2Oc*}Of-zTi5955%Gqou_d}#NjB!4)aVZ09ulD!v-fiCfXv20OA0kell58s~Gnws1 zNR>~U9mtm(VmCc3gHh^6z`c3_sqbNYAdnix6zaL-0+;Din9xb7aF9ZT zcLUQwCL7aqBBwXn8NO2JT#_NR5EcVG1X50j76xkwbzOc9UbD>J{9+9HtSPRY4MnlS ziJ!ANV#rGa32<#G}zStzPxsWsRk2rEOQ6{78 z+9hJjyp~y!V;8!4xL$BiWce7`(4HTGyYm84--nc1r_oL8isd17Ox~+DN~v<18m2Fv zG<&d=E~Z+G%n~{BG#YWo6iS7ItdKpdmcj}SljY1XO!9nKnPDOkWrl^!!?T}T2Hkk< z+xM*ZHUu2RzzBqxF+Iz2s5Ew+VM9nP&eJI#9LrLN$ffe1LfuNQLLhK=tQjho#i(nP~Zj=|QQSn2XKj~MPNGTXWr=;*8 z-*W1BwNqGq0pW%^4D8nFjC6vc%277yu(_y)_F3R|IkBUT<=CmJE4s!ysPj*>XxY%&<{B4Ukvivn7f=y7e%P z{gwKFyvE3Jh#f+$@-6IDvWwV2KEACAFUqYQ(i)4hzM%M}fP0C0KOHM zRj1=b@uT=58B%f014Rv0MmFaMjj)duL|W|!?bV%~OE0URHWM@4y667as$B3WMGJ>) zv!1D)ot<~jyS!NNu@*^X0>h#w+q?&3D5XMkJ@aV8+1)HR(I_@pYbAnS@sd!9A$jSlDV89 z(nw}VN>j19<+78p$^@{NyK_3|v6!n}QU&?Vv%JEI?{W&}AOh#S?OM2kX7x!pk0Lw0^KXH<(O=PM5PbOCS~G zv{ilU4@*t9wN;$0q2!%tWr)_NwQ7Bq%oEcbxqX&uY_2$~RM=fEF^qndu7pc+!*Ts` z_?l1zsR=<$jT#g#AoYDf3dCyO$s)zC)9I#UwpqFg#=5bUbIpjtZDV5C0Mr`}VT3dy zcJ8p_dU&Ju_|A_)y}GaDhdw(eQDZtG!VrrK0@_rz2kyLrk0NDI()=Kkq!Chzf>9D+ z@{mFw!^y6VjS&+aWZjyot!3MB4P8ea`Me9{4X0WVIy;YxAf?Ilifa=g#mXn%vbYGO zp40R}qyjOOEVuIaZTzSwXnO(?CAq#3vl$~7m9?B^!yD>>Q@iCiAAi=8_nnGBh% zlMAM-)iBQS@9V6@8eP{k11I;>qOg)$eC~E;mf9aU&0KvPkh0 z#@UgyB&FyvsKx^M(Rkt^>*>YLwcJDmP-2kv`Y3C|78IG;uWBuDwsXfIdi)|0aD1>? z4|r_{q%dJ4xm=@k(siPg%BMJFSmq%}<>DP-s<_({CMOBG*>SS;*i67R8B?OwZ~9n< z{4~W16Vhx*jin_i70G8$5J+7z(l5Yvm8~Q zfK=soRO^5E8A#P&Y<~L;q^jYaRLK|DtJ(1;44iD|?!u+l&~DdiZOzWLHIr#>jYuhb zmB{-Y{4YStTiI$cnVgf(9!@)^bf_nlQrE?8Rj5OPl;7lZKEPp8%8)uP0jW;>pP49T zt%GZ8PRsk|ow6lKDf~2~*ay;yADGs(ky3U8uU!DGnYu~#wfFwXI+;9C(;C*FffVk1rq4i1 zYQn)Wj_A!T{$6b!67^3tV&%yXtbB)!H{` zm?TolI!Bhuj`hC;sg?tSWx!6(spYESkc+O1WG+XEeVCy&2&rg+EiWoVYDu`qQs;UC z9_M`!ot>-s37%brXQWh~bdO;}#FnDd-OBN_Sl*HAfyzc0wQI?Bc^VH42kqIfYuR?D zbuX4cU(0$7kpqjR%F5Y^DaB1OE_F;}t|(x; zSyd$wa$EM`e+5z#4UXVn34D&wr@wSr$tC94z{+4y+i);7a-MF3Q}hf zbo`f)3Zof?w$%T}-us5Mm2HjxNiK(wNkAh=V#Gf+!m05#dem>pRWuCf3zKLCX|S2Z z21^kt3Wqwc+WX?Zp8Mi5P@X&dAS82rAu)MorciiN)T9B)kwnqHX-i9_4O9C^idcJ* zNwUsw?{iN6YGQ5YK5gf5b*9z)J^Sqa*=y~!*IsMi&LKtgZMryjW0IN=v<;JbzWB8p zU7>&MV~`pi#w7=4aB9o|Sh?))RTmauXOiwg69^YVNw(MV#&(^Eewa7ERdVrD_;hbg zX{7!LNyji!Z#17=cHsN3%gYaC^Y{_MX&lz33TBZ?v&&vnosbg6h#IQLOLn3aUcG?> zWcjUD85_8ykB=(2(gJ%Qh13Mj=jR{8(MS_MvE0oc%}*w#z4z4wXZUd&LwLAXsAn#4_4LJ3py*bR%H0)dHjIRd^SyLk>M9qJcn0&#%e+vcrf67 z#nn5#$6evaAT{qC#d}NbxR^1B-*FW{<{c_$5B-kds+c0+gjnUEZZel?8C`kqrt^{30X@UGg4?|DJM)&+GLdy7* z*0#qTNqjUc*nvl1RQS|<$%edR4(J8;Y2cLMT!m;M^idIlozJ8+r{;WEWDI7iF7|KLX0Le>$i=IG8r3kT5swDA*9B8-tXK?;7qtofUVEibg z=J5eU?>X(1-03uONI3_gbpjr8rGX7{bn&)2ZuuHh?#C6mrXi$6eC$2Ie!47Dx5|x! z8{eK*?s#9M&VB?^xHhkZOKH%f%HKLws_cA57xiQ8(c@O^CZZNQL!cdXIRxc}~JM#9M@PN~*e9hhCX1)F%e-hn>e%jycA1D3yamL_0r0(Kf z;v$cq&lljd6rp@T-^EuDVGLE|U1MB4GynS_HE(gCdu?COAZ2_AO|!7crSL;WHI7H$ z#7GgkN|?^STmdPZMl_RY@f4}g7AYt0CRg|nQrIb5s}2WKx_4-vcV&v_Hg?0Ccd&2a zHfAtVBu?>Sng3WV#UJwB`xRDX;`oSx51m-|CmX|@;YZ)Sd2RAKP7YIbpIqS*&9c|g zLN@DmNUzm9Hq7J~Ybop4wd+W(O^)sQu$IC{>)m8U zf-m&D55^W4-K*k{BY!MXT&9hH?E=5GH9Y2bRXhSCwsIMU=mgYHzIFvR{PyFzBaj-$ zVUc9=6sgY}sr#rK1CpbV()sm`sCRX5k!4ru-6TxB#qV3M(0dz<8KiK=ALH;xYbid_ z(4H1%8{lWI7<43Jp*QjIc#IS@v3-5@^?iMPY^_&7YL^>l*|1rqMDJaQ?L*s}-Tpjz zGY(7CPQc+SNGf>^E%Sv_y|$rxEPZ{UX_7}OtgC?<&OyP1D`D}1U%Wd1`yge+B?lmb zlye7Kt_AKzqMVju#P(T4%#J!0M5gX?!8V70R4>eV@#)@Eq&{b)MsQsSD;dEZ*P{v- zgrP2bMarP!2`(G2aQih}`Hl$H3%fO-HLm86diGIvUq(xN#W&M3h0@Yn;3}?{aHE#v6V=?`LbPoFes^A~lK@ycVmMLu!-O6m+Bo8q`7c9rTKs zp?P@2JGK*=xTK;Dx^ZR}9;x`4asGGEQaGW*61mq6-6;ltQ?;Bi(xqgg6l?v+k=H!Y;iUbxg5AGX*`- z4|pq{-G`>C{M2x#NPUJ#;iQXNwJX3O)yw5a$%P>d*`|UD6E2Aqt7}~M%M1(-&<;O? z{&}CL3R!zqd$+kHT=Tz=mO?9y1GzXZOJJm!R0~Yt@EnAccYJYqQ;_B5&Snm&nCdN? ze;^Mdr4j2hIwvQ|OXN%uQaF!a5^wo>T+i@lb(-vKvP5)$8HS5I)&9 zbc)pHixe(tUNt1)4Zq!dr10|O4a{`mgHl*oy@4h^@+~2P%H(a0kOEq%EfY&vx>=Ub@Y%b{jPfst|zXbvN_>AO~d6n1Am z=He059+x4nRJQUW@JNMq8!#*wWD}s5uhZL>-v_C^ej3LZqYrx^CMO%9Gt4)Z=mEJR zsBS?f!9?h1n9jP;1*D=pQvF;t<(X5YK3k;lHm{?8%|nkIfmAv@66jGl0IUXOu+bFv zh@$);8>9Ezw_w*qzZ z9XN()fK5dzsAyLKv;`&hp->T0kqlD7O!(L-QlBMKI5eb*P22f+mm;LtP{FJ_V}YnADyvk9b2Md;iV4z) zkh;uvv76Suf|Cv>K`Mk^y(J(O$q6nj%B`h>LG{n{48Pr*7!j+c`@uXvy!tyJHP4;b zti51q_1=5ZlUbl9BMy~G8H}aWn*gf2u$^zx3R(*NpvQ`NwA6O*DN>&SQrvL?C7X6+ zywVj#=Zc1Lk$9B|&7a{|-5e?72bp2ouX^_@%vq`=T;<;RkJnOY*6s&=`z2`N&Aw#a z9hgvaQP~-!a+Ny{fMU~xf2S}E{X|+S%^u)VS{zb^wR-v74=JULoZ=k^N#b2#OE!+I zwW@c&15(Bb9CzfL@cHGt(36PpD!BpfaM53A8HINx3MPvzQbX(5GjSPN2EC_9eWpm^ zLv7F4(3*n}Av=UrI*kiW9H{ZM9oALCra>5FmEdk4ht68`{(a}_@1UjTjkA*Yg9dPO zn>5G}dgrqdd>+AYqlVtmr3#QTurNjrtVo-sU$dq()g(+V8S(puCFg5g&`$2t4(`CsZ3sm~Ls zO8~wo+tsyxwBd&XcTo3T5CYN__hCX9WQJw9D>DO*pn0^n`te$7_QKc_U0D_P4GX>r zsm*Iq5Q4%G9fj0>_9V)OA*GP$)9E9$l#ui*r4UKtGGTK{&$QYK{8UBU~Cx7huK=R#Rg zUovR5yf4h#VMTku&YxpSMxz7JI?Wx-{vD87A+KH7f>GHzyb{J(@GN7$EH6XDV%!(2b7PD3kh|R zN|uv0LP+!xBkTZHb&=us5*Uos9EVgFuCb!~<05ta(_dlDha%O&Ep+i7FO1<6<}+w| zMC<;%bFeRQm?l>P7YCjxs$r0d@T1^@hius7kaA{XNr4wdAy_gPd+ z8f92ej_p3Utt+U4h}Ke1(dY_&u*Z+jr~B(6q+SDkQ75RWy6`}tlFQE-Nd|xQI*hG> zrR#H^oAdJ@-e5fYOl$FplV{y@kBN^&l8(4la$yOVN@1jgDp>p(<@6BSW#(c()JuGE zgbDPD#~+H+xlcb}UzbPfsqT|Y^#>wVCjl^X2@ZNVq}J4P&^?rY)*Kf`1YbpFc@a}< zVKOL8+|zy^7ogfBH(EYMjK(LANDqvgHsK*(D=itN++Y+&b~vo=g(59A4q>&+qxdMK zLPK3{M^|4FQs-z`Zxk}BgzF+Mzlh?W3O@%&ML&4rOZbXEqOnG!e1$v01#YQeRw_H- zw+zR@K5Y1bK9@HG=O^5NP8^S<6yrc)zFX`=ABa@brysC2<&g@IpIp2jh!ifpdy`X1 zZ}F+#P>2<|!97ur##%&2-~^LEgz(%y3k~Qt*a0z;uY<{CEbHUrvG0- z%NLG|M5zw2O?T4}$B8e?GzUFd_I_wrn#J52)WILgLX*>La-HH+CZ>XQChPtpG9I`s zx6m3c-4lH7frnhSBn~Ou=<2+x$|ptYGZ?Ue@<@3DpIqnx+liz)PeVMaVD3OA%#mIsFrQ36Jw{vEu zOnc`mJ)jlg)44u5*WQF_02%~OOpH)e1oT7fa^_G}-$k<*JhKWe9Sx_Ys(5R66wT$b z4>bHf{eW%ya@-TQ&YnGcBX|GK-YSPw+RSb9a$2eyN9Ux4e639D77gYa4S$r%fHQzT z!-t4CouRxu1y8XjJwj}vjwdAz(_64L>ogjNhm9wd;o)J6<(ZG%e$oR2B4Ll$U~jp3TZJ?J{zeylp`{Ol*ZVxxVYHK$>L(i{74C;(rg8(^@xj*8e8jubGl5; z5`{eO;fH=CVju=VKRh9Z!PN`%N4Iu(*r}D2ZtwiCv)Ti_@= zin95fEc?WZR*&qEyw(A#%?SmYDJ)O;GdW)HcJJNNNZmjK;Z}A?WPkZW+!LRV6aChW zudbds^Yvc@sBV3I=BpcJkiy%%xA_$?y9>JlQrvPlBuI@;5C)m9 z-RCzFNyZ>Y7R){xs@oOKplUT5t4^MOwW{jEgJzJNce>$`iPurd1T_eE`eOW+R5+}@ z4;R>E5mLPXJ#1GAq%Ip>5|2xq6^A8J0x2%zkf#W#>nx#i5&RfWg$eaJFbkK)L=8WK z_`$Rr>=VZMqgsnI-0ZtbyU#7g9U!YkcfdZ4BPTCMlab&{&<8WECHk6>xe#J;CGz;S z0WU0Vr`T+IjWlaeWz!}#qxmdR0;wCfzCCm1%(pktk3W8OhLf*u-8$WuIx$kWez}5+ zss;Z2H3!m-uf6b(Uv8B~ir?ntH4|_637yBOD#{g?V3W6kpUrJaA!TDKs2KK3ECiFP z#a6FkcnZeltzuZ2wN&w^^xkuKW|hlWTN{VBd#@zk+N6Qskdhh>pf_BHqhpbdA`~?^ z4Q_&drmoAH4GQ%js4CdC(9uXmUVtsHUfMd{Nt8e;gfsVB6NW@q8fUT9F-wms_{a_P zm$I84&(A$N%Az1*pE~ zhQcXQCqwEAz)x4c4}jz=eD}_Nk1p=a*^)@%ZQkWfU(G^q(cWUcq^AOzANzQhY7Lo| z_-mGQ#t0QldGw1B@M7!_i{ksV}C zHD+{_;z__mV5Al`?d@52gXS&2^g9wMePn_3`+O>ukNczYt9p+{iZiE1!Q;%6_HCRf zneBw9x^TwyRFA^jWI|A5!Fe%g+mZ3-`PE`PsAX}D5P%v@=rw2m7f5<|MAu@evn+b zas`3)6K3iZsgode>nk53=)3Q(dO478e5+D@5C8Mytx`y}a4JaXs~Ob7LZsA^}y&@{ziX?M@U&BkSv75CICdP&v%-nC{D zHsn=P;E)U9*hy*ZC76l2urO=K40}yR$cbJoE2wk>z*x4E+0B5_lu<2&C{f z??5KG5PKaqi^iMUHQ>Oh#uzTCILj>goPsAE$DyHtj}NEHDNeDR^MHBAxJ-h%dIrzk zrB_urV=;Fi-njP~4Kc^|lUhHTxrxkqC8CAP;W?jaeBrLWKV;| z$hD>%Qe4c0bL{03h;Pdp?4Xs0Bm9{&fGvq?EVD=q61wv+KExm9oxnD?m2NG%VhzN@ z*$z6q-OD3&<0_C}pFR7RU%p4i9!BcykAL~`$A7@Temq6$gh-*g=DTwB+goR`X1evu zzYt(Q!4+Oji3^*6WIHeSbeg>emx__{s8F}AaHj~;p&`}@dRlDk-Bc*tx7-`V54w4$t zIV*s<(sIGLS{|w43zo533Ha_->}`OzhM@Sw8eE|cl~EmxWt=V|U%Zh|Pt)g-yahgb zwh$>go=fwDyP&GzX&H|cnn{1Sef6tbXK(z4N9r%!4D0{u)+tgaTT9*e_FuS@{>l0I zkoG6P{q76|c&8uE59cTlw1BnOX9v-0K_LYWDJ#y?k{YMERC%bMf2GHXSWu|t(TEd~ z@mUivQ_{o(H;A9jPmX(N(za7+MB}WA_dxI&G=%^+^efU&#`8OR5^TGcS8brGMJkH7 zsTgYH60~WQnGLC+;+!@DPKgqNv70UWkiCSICV;OST$TlUe* zMncMPE=DGWH)p!*1)_q4Qe;&bxl0Lk9l#_L5X|n9NQM0X{(?Rg3+{=lI8f||pU$A^ zG=tQQGe~vaI7RA&PV}?CT>a^v_-5jJ_dU9m-=W3n8BR@!k19vz{dk0=*Lp$pd_~|z>A>09tGOEFa_>jvcS4g0zc3R1Um2uu zp0&eBrP1oK-Ujc~M8@{3Q`ds4Di#rze2EzI!VA_0nFZ(Jw01llGhV>OqR^~yVP7I3 zHILM_Wun!L)`9kO?bFKu_bkDTiOWz@d?4B#=FQ7kur92J8DaLC#<3I4MJ+JyBlXK)&ffUt>)Ry!8!3MkT)BGn>i@t$e<_L7^_;0= zIaC8y?E)Z8_#}NT_D>+B6a%oUNbvxuKv%yrw;H=Hd@zb8Y+;EJB}A=aQ0cp;jje4o zkgkEnH`lVkq8429%y_MJ(JT%Cxv_2B+eLQI_^Mz9A)unfsuf-Y8wJlqkWh#m=-#fa zrB8}fWGCQp54bbp`VgejYiRWtU(HS-;YQ_anrsbId~+j=lyG*C;JP#H{B_(9UWxvo zdlu@c0l&yEkPu`vEXdCIz6FBomf%ht23=oxrS8%WVzf02aj* zIl`hYDb9hJMvEnTI@gHWQb=K&@2jidV~<3>;rHz+QYS;|#@9c5f9uw*8#k`N4__gZ zFC$mamO!dGl zR6+|i*!{&G#(+br%vy>RTdh_PCswOOb@w==4ojNbjPq!+Iy0D3UlYSll*(=kQ!(eF z3w#F+)6Ujr2WnctGtf4^_-t{!yJd8-XMYOWWnS^X!eqrv?HqXBl?0W!RS_vQ@s>%_qjJW|h~iS5FN;_Nqvsd7sKmPJh_~GAJeDM7Z9x3;eLMez4n+A8$aC?TD=EULJNfH?w zIEc23HHib0+}Tsbo)=(Ho$3YuWGXXKB9WvrDesm5NJb~+a^ty$b(f0H_BE}Ntar{D zpU5ZCv<|LXSS8NF zEXtm_2ot)?ZkT$KiexXEB1X>Jk+OdDSl;fu)@>H60@>DjeR2EXc%8gT`PU!Lbu)Tti<7O>bq!Cb}C}Zb8*-dg|o9S6E%c2*B2aUsMrpw zC#EYb@2*{ZT#4l3%)7mI`Al`M4VgRkg-K1&kQtf`BTZF`VRIz6j3SiDeb@U=}K6>^7*nDI&`hBMm0U`UkK&?&*Hz ztZ=SgpQvo8e0=`tl!xPNiSs8(ynu1?bs+_jLz_c!`#_6fvsDr_nvKyLp z*x9$X#*QpWG~5-aQK#9~3S5yDU<;M$MG^1u`}+Tb|GE10)qey1HP%x9{`%_IXMO?r&6(`GTsrxEr38c87 z5vxX#(^E0UgbP+IM0Pg7ZiXQ7?%9?Y*>I}$w%(5J)|%(fn|5E`eY=IT2>90z8Z;^4 zGz@=xf~GhAKqrA~{80FG4bfPqegkHl5(#~)+GvF_c8I$KycusPxL6}-%M_H)L{Hqf z`U78O>&y-8p5Wz&t2a&ql1}WNxbe%?@Bi_SD_3uziR!1TLLl;)pT4?r98x$>WFb;r zb6hfeezqQJ@YC8Ed@d2$esjoT>BA{%E7dqxr9wGj1@~AZl^bPACQ1;5$T-`5V75!V zg4svL9p>?uvqlktS5QoL5fu$H9e!BUC{p}6N1Xdoq1lJlG+x1lvI!#bQI1UXXlM%O zW+)duF_o2dkE-mx)TL~$A+Ff3Q0sTC3#*JYI}?ZxtA(g^tgaNvYM}4Sl!n}dz%T?6 zzPvZ_W^lzWAq7J>5VyKFYaibf83;mZ%CFVN0$~;TXa`>|mIzuj>V^f?Zqd zV!K)$;JC@I@zItty0F*q(SB{YagYt0{p!q5|MUh zS4ZyBFz6%;c<=c=5VL^w*gMqd5^r2cY?uh+}>KQFgVGbDWoQXg1Y6#Msl z;(`JzxM9saQfR&GrXfHB*M@fBGuEO&L9v|RG{U=q6V9PnGqC;pjA9}I7bpx z7@16A!hm6tMsn(jVItC?VZsAs6Qv+hxkJ3_ClY97ySli|uux5$oAwhYH{{J4O7w$qnI3VlAY!Yi2_HK!KWhS&(AQIs-JXd($G3<(D7FDCzaq`MK0^qq(zMWi^SV!9r@4ujEpL@=9ZMqlg& za#P3gmFAqTuuzCp+j}APg=a|m3@XY$|7fJ5BwxBV(?o2pJrdS2l`2@AG(M=Y!G09m zB*deF6fZbC1aWNx{NoS8gfyCbPhpaVMop^?{4FxPD9fs-Sl?rnZ-S?JjYVrJ$L>wz ze{P@lhh)Zhwvj21YEPOF_=> zU66Hq{D`ey{!PS9GX$(?))tUrWpUMnqGH}C3NFABk?~P5Q!p4&k{2oAb)-^ z5)%sMlx`}+pR=MWTIYa#1sbmHcdA=Urs2kdTnq&^GzXrz3uJjWNI0vK?ua6>N~S2+nB93y$&HweGt%m@8g zOI_2|g~Pdx*`Ok}cb^88yGewok|vU-BgYwbOhk}vM2VX0Xg$`-DC#oVmoQN&9rYIW z3083Ru}0`oPvE>~W>IpyecV&I(alcrSr=>Vh zIe^siX7tb~qqOrGQqnk=E4gZDL-U2IR{aJCjR>z+bb>>q3uar39Tht2;uLDYVuc|^ zP^GmM6NySGDmcS@j*HmV7VN)iAz><`kBJemCU# zjY90J(xtE8AF0no${^);eR5HKG*ZF1DzB358vuIJs^vn!A48K=3-`CXJ%QIzyFbh) zR`M*-cT9?4-nu;;Rw$--2UMWiYPsIdprv^}&NaY!_L{|-cRp2Z(*eE2yuw8*u(dYr;6kZVlLzQSHk)L1YlocZuFO&ji6n0= zCAjkxn)3%@@U=Ba(QhLj)kKJc_yTk)n_;7M*A7jD-5+5ydTOXi6>mx@3tAi05mgII zbU;7)>WPU67dayM)|b$J^nkHhx=W5p)KC)DBmnL8L%=o%Tzq91@R>9E3B~6;>bkJJAAOd0si&s>G8M#ISB8Xv z!h${}9F~eE2HiMRY4f^Cp^F7mdG8L_sk?E7&;@iYBK+MIW3X&U#V9Q;e}EI|Vx*et zaq`mKLHSnLVbkf4bx(Zy0ek-cfX5FZl`91?!9~JwNU>{Ej>JJgP9;r^Eihb#)9c_c zniSi$?SoN5oytwS*t-yn=@iWC4m}=6_O{;I*7MhHUfA1n?!CMIc)PZ@&5ld!m^&_x z=oCfo3@iIq?O@jAR!3=e9ww$?F@+OzSzV0YgVs`}9$25|PDS!BlTM84eaKw0ZyaJnq!8yHcmcD&`chRHF@9+Ik=i%l;(oA2S-#dfzrhFV*o zj>8BjSu?B~c~4LW%U)7l?uK_1gG;wPmC?1_S_*#Sh^xpVRShj4kJR~3KVZ-OA3&-x z4=FB*y}F)9s%yy>-cZR5QHH32nQ63^zl^9D#amReDbQP#%2+B32SO?wZfryoGBZ26 z;ZS*t%xBtX)s8+LQ7ZCW62dAfsEBq4yxl`=D4j!U3~m~6nbAn3amzQNm8`KA6Nz%vtQIQhy0gsf*k|g@Ngq^K|?C7XZ9iSx^$&n`ddN3l5 zb;ETT+%BlG%Cf{A@I51RjYX{uqSoqkbwPv1IPaW|l;LFP2WD4xO06R6H0#cm=MoXA|mZ@-J-cZ$^i22%A_7|Hy6 ziR(nQu$Jne^{;ua z05&zo*(_4S(5vVNm~w%gGOARHS-#0aur^y|2l7osp$K9#sDKshuLy@@jeOZ^{1-O% z`1;j(-soVXx>0Th@6UBvzeIKvBaL`1rH42^t*Cp3)+IIU;p~06SJ!2n=ss~Kn+p=F zOK_s&ax$T#-;E8(F+5l3T4`{2z%LV#bA1KbiTI51Z&YBPp^zn4+zd2Z5JWH*Cin*8 zM#qZK<8DYwt!Q6Foxz1X@gI##2FNaeIW^-0hZR&4CXb3pXOQZ$afTs})B=}=>=dal z0jVJm(o%e1b@0WNGlpONBK)j)a4@ja&B(0~r_2CibzVqM-`EQHJBO8u%v^mE2?t|p zQ3FsVm@(e(fw)E5w9OXU|hy>p|QM3aZX#HjfU2{O<#$_)hVU9Y8wfNd3CbYr z0QwGJWQ6S+8tM{cs4pivoz$OAI_AnGaCW&o*>o-=I-T&^`uh65?1v!9+(#8WYNsed z`pyNrY*+dSq|ofMZ3VJrI)%eWg2B}LfF-DDg(C9Q2J|Bl4(iY2bs0d?L`%RnPf_7m zl?^YLa!BFiVsk^MTI$O}3iZ-d##P%SZ0BdRRGL+G0_||y{NR%B__dju5;=PajWYQl z(p?KOg<7c$5{H)$M@-n*X|5n9v?O?5Q7n7(KtaZj6OCV+e$EHr-QPEx&0AYrQ*(Af z3E8c2NyfsH_;A&tOopVa;V1ED^7zq#fS1fzgMNv`no(p9yG_XTyyC~+aJ}9I{?{xU zI$D{bHQN|c)%GTXLZ=84@1d+vYl)OnT{pJr2j3g!(Ah zNU``N%_{%h2XOHesV@mB+*kDufTj9;q`KIU@$Qs(NxMt29W+^ZJebdsg$AGO#S#Rx z)fPslQ>J2#WhE9%)#-GaiA5{;?h7$RB}}?5wz27vRXjB=A=e#NPL>=Fn{W&s{j+~R zBR!krWae;(f62Bkh+Wv~C4szuX*2WUw_5XnTlf^cV+jfO(d#bN!9B5O{{>U*1u1ke zb`5uWK(hR6d!1StJEpa0G1;h7B;U0l1!b;DVhvUF*+X_@Ytu$nKB^ac20ALZ2*(^! zVHNOaI@0W=Q>4Ba!;iHgq_A~y6Sb&@%^@ZD4C-~<`U&UBqE`an4S%w5IyJpiA!@(FcZYlC6Y zyHPO>t~(kwcLXh8o`X=-uuG?2%hr0xAjNhf%Rs~VC6{6L6sa!-seLfw?h6e7`0EOg z%5A-3!vk^9b=1hm@!@m)(WXEymP=ehBwXGT+GStjQdoMd`UqPBDgNPEcz4`QNVBiJ z60ynZ(8zk@{yaI5Nms}RwBBbt{!SVKqxoNZgdgX=)#KqVd2WesM7&fZbGL!y?u%=% ztHcL4#`6kZv)Q|yK}v+a=#GHYF?QW`eH#3nbGUCTCMC-I=hF5GvQ{tFcOA8Hm9s>}B!AIcX0sNz);v(uIPR}| zwtIRve;c;8%==pH%1RsQ=qttQ!^0&5@{mHE12|qe&9)(3c8b&&f>ayc*<`UAB1a05 z$``aOSA|O{2@A}s3(7|}#@bvGiP+=vh|wPp&Zdn1#N!h2xjtoG-V5tn=#g?m1u4;Z z-?2){2%Y0`M&_bh_C)#O+?J4XIdpf!wenwr^}yS>vg|9mTy9-KBX!eOmn6wRO zguhE9cA28En&zBisMPnj(*T`^YBXk%GNNI&%in+FDN7#~*^ zu_RKjbcJyOF|q1Vv)C)44b305Jb3SOw|D2r5xr2>oWar$KjYPy>JrYK?h&Fs#Xt!M3o zVGkDA4wydnR?eb9TOO%W=WyHSwrpav&E|32_3L6C`;wkk7EUnbkiz@9 z7fT|=Rth02dYrBF6sa!-DRie563FIWJOU}4F7sacL`b=ny7BlOgp}FkK}hN2_sRCY znG++m2Q|m)mj-y(hmlHBM2aYsM3O>CtxdegXp-X~pkt7V6(LolZd`IZ>~5QDYii2l zcIfBCL|;oWQf0LiPJ`)QD~S~Dn0sq@hoj>E0#Xk?{S`LAmG91$m1Fm%4v?1OjZhmG98yUpnSa8TJH$>oVPR;R ztM*;~Qw(Hp*>5@;shEJ&!1}rvA!R=?Qpn)s!oW%(#n}f=R=osIjzy~MIQZ_XTn~Rj znJAA`i}91oApCT-y!>z+Qls#k?OM-^-#d&{$PJ(}dClCbT029<&k;;yXbI+@}3`ye%qZmvIA5-GfWK}MAlQgj?rUyPJM%KV2x>KVM@T;x<~r0(E3 zQ1K~{NuRq3oOtTNlFOL6{NI`39r0{&!5+nmz#>}`sTAJg7k?6@rqL4aIHZQ`Q;mv8ai#=P(+DYr)}=TWDH+}W zX^=w9IEG3hh37k$+#k@CLrUlPg2rRj(MZ)F*uE4Q)RY}bt+3ky5D=9{ss@*c`VcK8 zdB`D^@%UBrT|X&Om0&5ql)}cLYhS5&>l--=DTYbRL#aqja z9{Ep*)PQ>Eu4F+q?$^3Jj-TW1_$H}2;l31le8FpCL&r3rQMIX1S3|cl5;+2?x^9@& zsXKumEg@_Jl~$IDOfp(n!@?(Q1m85XUVl zzexE*BGrm3$HHo9r1p?u@_6tVq!eN9bbKZRJLR%Y%$QYL((SXWBrdILNp&x_~klX3uunL6>PIac??pi{A)*s-{8!w zYsn>cSmO?{N8%7$#qrl;&E9EcK_lzRBL&w+5i^mJNO1?*Kti1&^`#(%%UOecs5DZ` z04l|Jd88(~bUH;&bP9YB$Q$qm0wnrBKn4O{Zva13xt9Mr#aeCItzJTwV@ z*1hujYOm)?*z>Y_^Cd~1R|a*}AU{@1vA5}DIi$n`Lj`Rda*}8n6!4O`fnFqBGjSGT zSzmq|b?T||NL|;^*~BeJAypSYMe2(}3U9s@?5h_c74_jHFPr6&8n4;jZraXC>!!91 z%SKyU_TP<_ww0BR{8w!^J>U11LuwdamACt_jKOwaFs!uf(?=|YX{|*O4C@-ecsx=w z&`=gBPffwaZ+Ew$My|Bw3u@=eN^^gH6VV@uy)04}S$E#H;9;b2QV{ScPLcYOkdi1$ zBZW%~$jc+OM}N5cM^(;~)dUsqqh>GaaJ2))Uh5&*wkVb1R7~-dOQwE|NCRc68mH?& z!l`CcmqY3m7p5~)8mSQyA*Eygi1LR-3g;5rVM`*_=K@&oDvwm%w7jAQ>{Z2f*Ksnu zKtFC*he{)LHLI(d}vG6I1Qi=!1hm7J|p(09t9WFVb_P3n8jkUD0 z++ktP@Wb`419_4D#Yi~|7F&N*q;$j=BW2xOI3MP6fmwo(%KaAF;sPhiBbDX~LYdk8 zW3ulf>~m-@Z4sqeoonDd77(>ip*$v8k?#GF+67T*z;VW?c*hA_h~u0f%%+b+O5?-n z=Cg9S2r0aeQDB@O;mP@8L|p=@5i$M6NZCURJKRC3{0`T-;``a8C98bd3ta!A$rYXyzP zRgf#)Ouq07f8{TZLyESV2exp%YjZXejUK0K&VNxi;PN@8W$4+LGaRkDqmk17F#?j% z#Ea&?Si!&@azidEB4f6?)th5&KI(cGy1J}mD@=8g5^*RZ&=};xW{)Yil^gRw#%| z^$o3crF-IKkz&&#n}iz`ZJkX{LRTh8wM(tg%(nDQ;g@^YnRFS$uf{7n7Aba(-3Ewf zYhGtFqURp+`vF?hq2rNKsM^XkGOfFWQzQBBH7{J01$9HEPfiZ0l@*nv&Fi@4AE{NA zZG;8Rg}OpITr6*hyXk9b_C8K>lmDWZct61S2SIA3G*YDMlM4y-f0Y-yEK>D$9Aus< zL@MQqXL_$v$Uw`ElT_K!77BF{(@$@2uH$VJCh#^<=A6>fmbzP~xRv)lCe^+XkJ;;?ae;`O=h>SvwH`%_}BB)omI zw&4QRRer4{1i-)Hjv8k6EtZQkQg`uCJOZg>M#6u8CIhzYd8t?GPcCoZ&wnp3e=Um? zE)@!e5t(T0S$yO)cZ3KRkFauf&L}A@i&W;hdUf)8|Kf&iiBH&fXy?_3XghdzPNuAX zkA2Ja9-N;1SQOUynV|4O*up%Nq4)Tl(0lBI@p^V-qIPh@X2q514sXeMRbrd=pmt(J zJygp6%|~jC4+f)rTsB|)NDbJEgM2#xJsr@LMe48R2f{Z1HJ^UKJ}-~dd+Z+mr=grRg`})+nFhPXFN{hFNBRs^GNw3Fp-hjdqYsEmNOFOX(^^k>LX?T6^ z+_|UcD`%%GIFXz1wV?lFe5C?3EcoICp+0q=lDI5$PS20s#PZ<5a7FtF)2Qw`(VZIO zvdwaFUp{_PIDOKLPQh0~KemLz_O3$2F&qz?%R`>&XKZsty>|3lF@ zIoob1F|jDgS2nzW*T)G-W)^E=?ou5NyB=AU``Z1Lp1Xrs7CWE4sBLL!+1YvV=FOXG zEH#ynE3urL8RKMTUOvr>Ov8&wxeNS;lpOU%KfAW-hD{~A#ug*>0`-NT_z0xFIn9vt zzk$>uni-8AxKM}`i>BeBCZNZS{%mr;J!sxpMAF&Y^R^j@S+Bo$Pp{{48ha!ve$??! zQqCAEAEHEJ@ww*gNY>jhS)1c6&(Lse>F2`enqJM$&Q7=k$nth9zEl4v_qqjJPQJ5F z1KsIbl8Izkv*B9|7XHWIa2*=f0S144tHaW3E%DgEgtif3I<+18b z)H>_I`3QT-r#x{Vbk)}nb#)C5^(pygDH2SQ!R;KW;2SMB3c*QZPkE(P*~H(W>fN1| zHt6K8hGk!KA&)zWBg$>D8!&;ldtK^NE%kXLh5bm*ArH(P_VVK2jcE1l?UyxjLvI2G z!dwF5Ivrn^mgnJjH^B0l~UWc3;t-r!Mu4UM){a@+8`g;;iNp*!U;I#7+1Fn*I7^xK)i%7NA_J}+G4EugegG`oXOlLz8c%P(dtQUxHV zLu<$GT@`uI(?dba^JhKletf!Vec_@=8RFN6EFl43ToSh;dvtwk-@L!Sae$=vZs#+! zL~3byCLG&nYC1nN_U`7*ckgCq^3t#ebM4mULMuX<(!A-z5CgOiJ`)rU^C)aQ&8_P)HviA;}=X>tK7M- z7YBfhuWJul-c(*UB0Dl%*SGc_s;X;9r!gYBoKGb0i-zEKLC+Z<2zUT{N#REqPo^zK_{8 z5Aao|JRXmGMa#>0FOtE*!G${yA3nVE^XTZpLPrPs??v~E?(XhqJDjw1?CdPuuI=8f z?(XR9@#K5uNR?l_G+G(p9}1!etLwJytQ-8uB9}3A`?wex>Cmh0V?o8dQ?H zqmV+=9vXWLS+XxrwbW;URHo3%KKlD8q;B(hlZ0o6)Cz@c(Fb|c?}^3X;Qw}T1wAuG zJ#*s830FSnka#@SB}d-J;Sb{8R`9BV?Rp8vFkhC`;mEs|C9CJiZ^%@&;Y7Hu%mrpH z+aY{b{s(@D%t=7iug+S9GjQavPqS((jkkHxYAcXD)l#1?Qjd`7j`LwQ!|kJx!lt{s z!22X}!M;=3cZ}56_kCJX*Tr&C=#9F*&sWsy@Pq@*3YK?cB67Hz0*8@mbdgE)q9@3B zZaLLbpDj|FOg_v77(EK9+5D21_yv@ho>^m0<#%@Z^~1hmO$h(!Mi%K&d1r{Y9|u<8 zV3(r{%bjYe&jG0gWXN+3s)pVpkP6+)PcedHDh9n5k2zx)V%1eG8`_mmD_U*-&swea z(_Kj0VkN=eDN%l^r9MNXg8ocs^8|XqVWghW z059{6k7;Ccbfwv{L{a-_8g;oOpHy6V7r^aGf4U2icp*NiGo|TlP%OaI-j1OctHtdn9w}u!a<0fAGla8UKfc30A=-cX!L2nVMRv z&%{?XareDgE}&VDPi3)KTr=^HrKQF`{T2TDp-8!NDR)FPvMP#@!j;S&^=#;}(Zb7x zVX^yyqWBlWgdU>^DI*MFA{Y$D2nIb9YYZEh zXq1RX&`@U*;Z!U}B~8+BILZ(~1H&Y6%03DW;204OCK!ea*QHWXCQ8I2rZB|_qdOG~ z64GRZVGJqsScEZz8)J>=)d_+!F(xWZQA8G~V8RfTq6dlSW%MYM3=+{W`pN`qN3b!1 zE<1=m3|#`cbo9XnrWB>bJ7F&(9nz&@IA2q71}DXohY}uaRP+D@MhC8ZLJcF;lZFNIIHd1Txp(;M&--3rbse6y?m2bb`14WyWFF_ z)K1LYZ)?-Op`_E}4-EM6G4x^kZw%50%`K6UJ3XsZw26C!(2TcTYS#Wr5x=3|@5-r> zou8A5g$}MNHY07>*l1haiz48Rk7}gJBsKG>ZKYG5NJcx}7#OL%*KX?bbp|h`n(H^Vx%OFPcHEfLn_MU!xW^>MHZ(? zPI`s?5wmB(=X+E743VMJYi$M|scGmAmPAS;@$}felLYY^W{5`7Db6shk>Zv zaCx=Mq6pCgo)Kx1cm+3wIX|(pPfAwCMaqY;(X4GEQVlSMX(Kx0n{C<}iWmngG3oUo zD5l~)kJ`=?vSmHYwOynP_V|4>+@WGUpqYVI4)v%^wbZi@mk3jmYKAtXQ5y%z4Ks`r zQW1GKm5_-gi&HQ`@VezdQriaSsaOr1XH**rV$46@0t1Bfb(_`K)>BdUoL*^etBnv% zKpPnkG?bi8q9QWG!xVt;(c<{>c#+(_i~n9;9v`%Ek+?2hkt_ALT#9X+4n(5+FfH{N z3|Pq@HTOhq-Y$K*&qEjI3F+n*!T3;tjcs=WIm%T(TFXDghfRAlq+wYx!y%PMYv}4! zsc~i4qiYlfS4)iQ^_!>)@{UqH(jbb&_Qwe(p&Xb)CKR!%x~FQFCc_8f%Zy+^5*lBJ zl1du(9V42NL^9Pv%8-_lhRt^k8dD<4*sb=)MajC?o(r}99W+lZC&0@x+LH|DVyW|rd--VJ|Dk>v8h1vvoD~(V1YmTVOr|krysDd|DYZ}oDb72c=OV0U3MtS8>x12Cvz}T zQ)#xoY6VTM=SK=ply*rcHc9WMGlUHNS?agC^l^#5|h*Bax9M(&6bvOBU^tNg9b5WRkeU(?TRF{BP|S zRvd2)1|u0?LXSiuM6IuaicqVx?LfaSr=&8MZy>_^6_7&Fj=SB{(TK@YyC~5lqZ-fi zaKvUy27iV5)G*zeVhq+=!o;opdQ_5qq%E1~zDnYxlEk(@ZhL{SHkrh=L`2H0lMbs{ zlccupSYq=kg`wJZ;Qb^kz$2}8f<2I!V^^EIX&EyU&NUP2GWH{b>_uP=)^|^ z0-o+m{q9Kp{hL4i`On|{jhl`B%*mg=DUHlxSTlD>Whi*rkJeh5V9fBdoU=~dS?c^QH0}GQhxkjfp z%xyM9C5_$TYxi?pNIPo8GS^Yzj$>Ycq(Nd4^_ z)c4rWU{tMr}KWA2ffBJg~q=xW8slFUi=3H$fUd)1rokxmu z{u*W$&`Q7?ci3#UIebdU(>t5wY{B=^QiNGApYT62B#clUCOW;dkxJDYD%^ooN)j1o z6IArFRcxMu)*w*{)$gv$BOFt)yDE*;6z(P`hO6XBV%Yoh>dX@LRI1ZAhF%egL>W&r!9)y>eT918DorLBYn!mji5S-PilDeHNEyBB`&O@!3U{mK zhaZXM22Ff0MohpCWARLJuJWj~P0NJeB03}CUOzHJiN~%7$_cs#U2Q+TXJDu?=(bc@ zlEj#5*b|?$J}kM4EJliDsTwl`?me6pWmZIeQDgr;3AP#vb;d>LR|)aVS%ZMxfSb8r zDb?XF%^>y7e{o&^S7CDHN5!8`wbY4``um^Jef!g&{tEy7P3C9x3w%=osa16C+j(Zi zeRy6Fk%Uu`J>xsmW8*ed*6>W4)>JMuyXVAK+y34DX}ps%)P38$%68RG5b>iT$!%^$6Ct+t4asP@nN<16 zogh(7`g~+lih4x)RAfID8`s|qj9!d8rHLN&0Qr(gQbyG)A}N(gcETnHGAENV{|jNX zN0G(WC=++o5xruKZX$3kO!Sa(mB&a?Mqf=hGSWti{WdwpYqW0KYW2($k!W;a3$4)- z@BHy8)nYUfO&wU7C=;x~m$Wa9-Coj&2Q=0yeksKqk5mYUtT=nc=pKt7E!4hv(Xu>+ zmQSk9st~&0YY3^~Wq|ywx9kw>#`_f6-+Pf7(;SJ^-~J2!iu#_0zy6(@XK8LA@JyX* zsgoe}xBmuw*S_KY`7>_;@V^|16g~i--(`caBkaxdGK$m@zcn%x-x5rZ403BjLzx^d zX+9?4IHVG|D0M`>wyR=2tmm%pdT(9A{FT0Jq2j#GqPM(;>Er367S&dWq% zx;-3@Fis66RK<=unXuF;q7qJ-A#wSFhBBbfnNEf&0>7LH6RYQqi5T}{iby#hPiRu; z7pg*rKOi`A@%(fuOi+mmc{ECdHTWuJ5vu)3a$3g7BMI(ZiIH+h4O#6%nogvdG&8kR zKD=)71|&V_o+yRo6++4~T^Mhk#swJjbEM-buj5FhzJdS7`sq&qf5QXezd57tufl*h zMd~C-{TGMN-@p0u-#9Jx|8kgNq&5rRqd}McF#mxLA!H`wyzpl?@P{PY{9u}pPyr^C z&ZcQS7AdN-d84hZ`F>9i`WOAVkIVKpU%J%Xys^=C|NaK|B>KDgep}l{PjlNw^Zn+x zZ#OphD!*@=aRFTP!2KTd-sT?k1N!$Z`WL;V?a}6=p636bz4HxeW9u4yl5^(?LBUv% zXr#3yLa;V!G;eN*kM)aEOllh_2Ah+p1TKP7Av9kK=TOdv(l3X@{dT^bHy9|qCB}zR zC|pHrDwIq~^|j@N9uv*zwSlRq%qQDs?P{jOL$z`0m0Xv3FFP4y9Xhqo zX)9i`!_AtxFMZxYNRfNHkVzSN$|W!Zn+rve@~JsZN$q<^BQ;2uzPZA>KxPfM6ww*< z{tD-sK4Fl;8SpRuz&Io_cp?4tqoAcqcTZgW7fw+^yLv7Hlk@fGA2S}m{j!=jxpkja z*hN2{3x?i@RQASsXrvap{55Oq@7Eg)Ywy?b&-(g%{3|P*C+U~ozt4Xm??L_s_>o%LCTEi(6xnX_ti&kzh4D@7>BEx8CCQW-Q_>kgOMhFJ; zkfL@0WB-UblQ>R8*UeOJO5b!42e#!w?s# zZZ|(tztT3}FF&}^wa+1S@dsfnRVq?HGIuEKnZR1=_y0(buYO67r5@$Um3((m#F#}2 z*E!0DJy%Yv(?|tVRBc@gu2kj~E0ASqGE+e&Kl!1M(yA0NQ=^ry89Z9l3k|Na7kqn& zdZG>TXw(L<9nT@96K&!$p_-kzF+_&QeMr$NN&i>-IFnb<+u5MQ)qmMYEwykGf2iPL z-n#4Oc~^9ZLF(eaE~c&hi?q+`S4KU#e-X4)X-MH}Tt6^KF2AP9>P0c6G&Nd-T-8?-l^f(k zugYA8&`B6J`Zmz*A#MY=DT@?Iv^hZB)%^M4U{fZy?xUw@`&sRS)m>QwK)F4D8R zKVXLbg{OKiLe}tWJOHUmajtk&tq;JSEv8Ye7|J*yx)t!DN@-S#l;|JXR_BF}={Pkm zQlTP9#n%RQz+o_W`k?Hk%VnsuLGJ)UYMzZ$Om-jYtuJb;jTOsKM+}E@NWGY*=O)nY z>3IM;C#uM#*=#07*P6X>gDIDsMG7ZTR0nfIr{)8Y%1!k$bN;{oLWA}D#dH9GpruOp z__?#8C)t3cpMN|gQhG;DFAbs{8>l>_P$wX#r`OHO>`F2b+1-M#P>O@p_KUp`Nl2wH z2qH{`bcB&e>Z;jVN}jNTxIt@>ls{4ubWQ;8kEe-J!= zNA&nz{Nb=+vs|R`+TCu}c}XhwA(f)~AZq3;&s4Vgyp?%K)fm6rlx=l)o9b&Sv~mTLqQ88902J~#I;U}D%W{wk$s!IySJ@2`9kDk6?F0*{>gge- zaJ_i?idn>N%j6LJMCsW`Dc#vXzZBKTUt5I-DeUpfManY0Lh$$<4XLA5K}_@V3SF{v zWQChk5jKMq6;`xZMcgINWD{J?LrNurcUstP_s(tpG_(Gt-WAY?kIBMd1{R9&27>lCzO&ii6Z= z^d0NWeyQaH3*DcV^-@25`y*`lDo8cK7IPQG`FYrB;$oUKQWY>|&g%uk2|RVeMXIgW zX`kC_T5fhde>OM0YElP>9u`FEpZ`^+^3TFrYC(4kwyM{iK6hZgmo$4Pli~eH^|&XL z`Hk7GF*3o)8Kf?W(|)29b#5M%e;=t|*eUM6nH-QIX=?DB%kEb}Y73eeq#8KBTZ#&4 z{!I4sht+vwrOf|%r#+=O~3UxN0+}m^q)?o__b8*FZas@bL=PZ zS%-~(`Jd=m9zP;5L^q}fRGj;hNF*b7oaeY&Dm$Bj8Xwo~_!?Sj?%Q|Rj#HZwwPU zDIM3mA&3#Dn$#_HfSip~a^@k8h*7a@W#69=QCpzmx+j=9_b2J?BYR&(OP%}-NsiWU zF7sanDHl3Rj1(>{uubtIb-@B%ZCN*!NU2l>rYo300JaldM;OD>FrgztMpCCs5_<$^ zs`u1usYQ}l^V?;MQnOjQu%@w)$)q%kR7g`#7c-`|VW`bYv&6LKuuBmkxK4D6F3^Uo zL7ZxSMqK?>w3PGPcUWg}q&}aPvD8(t&`9Bn7~>+fnc1dx2bMi;!)DSfWA5WA9uPSy?*k&$G@_=RR3rI(rQ!uX)lJS@UDC$m{r z51KRFsoqTd@)wMh44k#!$yn;tc>F409LK;C3htT$Hd1=3Ql$a!v#I8Wjrx}kKXip~ zU`;78e&2xTBGw(9Gh#KicP3fJVw*|oMsJWDl_h%tRuLXTYU3F9&LAOVX zLxBLrgB60dI0V-K#e%yOm*S;Rph$6-P_$S=8;ZL-rNxSu;x3`MYhS+ezVqJhKXcB^ z&g{;ebN4rQ?!CXnM;Q#i6BAI8_h78zQ2B`=bk2xq<5p_c8-kl!(FJz}3*G8bnP_m1 z+;*mN!x5gPyUHLChwtJA6vUmWOxUz#dzH7e?f3O}`Oeoz>o`0l%GW?zq8*-z{udZR z_Db1sB31MQ40vj&tkS=|fOXY_OFBp+^Z{%Q2n%qe>ClT+9RK9ZNI>0X%3@R5Z`2!G zfn6oO~5@C)!dTPfz5rtw`Kyd`=HarC%kt1egjqAq5r7W(fp` z%6<<2fUq^37^I|;t%`V~`aujDKO4w&2mLFR$s#i1&^o;0C?KU*LOoS&8EaHuXB=uD zsqey|;<<C8vF}c3in3#A`1rkt zsr~Xr>OU=de_lUd_`2WR28}d~sSD?=c7HN1$Q<@VmV4RAKyDn$X^E!1)zi#92oOAN zs0SQ|Oxo(s^-wD1KK+5QbZf#Hxy zg?32dcHZuvOFPGtrDXjs>^5}}T0+^B`DyDi%N_qNcue3>B(O5 z1#K482rzvLjcU*+)9QF2y*`=Sc!6=l_%H|2Wz^)_Q_(Q|El8)Mwg<9EYBg;PMXBU$RgMSyp_o--G^) zd1`_WnhxCDEuE*WIhr-lFI`BZK}I@D`pc`2L$@NQeH@%glh=0C@B&ewAr8!HZFl#t zGL28F##b0rX2e~yVWGVNcC7z?^%%lN>Eh7~%y?=1g;DiEHhEfUr4 zA%;;Wgi2?SI>t<8eP@C^$41nvGnp#m#pNKn`swebzeM?%#E{Jdd42}z<2hf`4BW(R z^k~-Q<4lXkWG-DTXM#f5(i;-{tH3s$^c}_+$lRE*+p3Mv;+PswRpZ%aOwLA?HGezs zJ?~=1LV99EU!5%CS8yDEUSO`UG zP`{I~72)wJGeN)r6+DGWg#0J0ut_jxKMiTv^w9vgS2+~sv0`I149p*9*_4C7aw@5L zfFPbi+4k;S0B>7BkP(uQiZvMs?Ytlr#z1*p-vE;aZB?@w4V>lg37efIp0gc`2!4UH_Qw#?Ql%ktZ-$9u z?5glr`$7CrkR;7<&n<#*s9v@<1;tmQXDqQAI2|{kqT6{>CVw5@QZ*~dN)^zu^FyUe zL{>3v`sJP;2Z#1p{9o!p{U&#N$8yQ&>Ddz4{u{CS#a%E7WVBPMgyBlZH9gw>ntb8# z_eX#lFSSe?L6fhVD3r}t(WJ+A+aZ@@<1i4#APWV7ZyUehB_QU92#{JK@W$a?fF)yS zMm#9t*`^|jPRL{ON%9rqyIc1FMGGXGZ*6Io=`Of#k7eTWHnZbUW5JSt&$y3U>N4Dc z%Nk4)RiJmKg_+8d#b8mIpG^#n7jtV}Yf&3E8{V8X;hW|?RE#So4hXnU`8d<4q0tVR zXwbJ-F}$a^)XvoX;I^R}2bJchF{zTWF1_ND`IUShwIcHU0F1S8)6so9|KKPCWl`Nh z?OvzM%~V23JL13&(Qi7tA+(!OEUI6M)H=X`y#t*BLcW;^$t(4#*0!_px|T(Vks>@b zP^8nkaYEYhYv9vY?>Euk8BjZ_h3gBDh1NKC(H9P|I=b5v`R=9oX5LR-&)>PVc=&#K|2ic2%eu=9(Y*9TVKCJVoH2!Gk&YzG z{7X;lAvEm!5g9rK!pj`k zNzeV>Pw)K=`f^%ciR~m4PDhh4N~WJCln-pkp!0Se4H$Utwv1}8nWk}0hC%wT?4Iw> z4i~)}I6NHZ(z9}Lw`TZD5YfI&kjigxuCJtBE;}3guCiw}8&_2-B14PR3`d@qmzN)P zDf#d_!2}+@`(z*i!Mzw9AVQxZ#-UBv%=uMZ%FinU)HOErz71*olS3n!HchKm!VgN^gG0mLkw3qE2LC&rmNKkr)=e#z zm$VzZ+luuUTesy4S*8$#{N+Ub?=qoi#iGq+jK36aoPkmYe_MnlgjDW0Cxs{kQw62h*M(VOXd+4=jCf$)<~DE|;qoyi8rTAvkSv(gGh!d-?vjv_audn5 zk4R=8H`1WOhoJm>sU*pcc`%WJskv{u$ByZ%+kVNWDiTVQLTM`TFt8|cjlAw636{CmI<9Or=y^ld)%U2Rj!P;|5%lwD$7 zzKr6Tdv_c001ZfMBY6Slt^#vdmG{@Nz?r@Zr|d%_-xz2mCBA7~gnm)vsRVpdGh66z zt|D73Q&OO3Pxd$sJJbvdY7hLB!r?KP`eNEoXFuXbuj4uJEOlsDjK>Mt$2LRkE(O_Y zaA1P6y>X}kC=gBm=YghBldPz8c2F9q@)sE!)g$+wIS$`I{kA+K7a6EE!J9K;1rVwN z0{We9(aLS|26wnJmfNw>N@&3!cVz#Wl%5v+^AYB=KTYRgjoc6@A%@Pz_Pu4V5dKc4 zlN$kWPwbgHqHFDd)ZX;{h*haULE3H$7NB1-hxpGNSz;*6*5Cg#Wrt$Pup+n5)<0^f zci%>37fWz5xHDYp@D4n9JO>n@MeZ-w=#LdxVu13C>n&y+g1D) z9JDC7V39pxqN;>Ciutm?pY^5<+q-W?B55+!cBycD4pNV7OkUt)q@v+^eAbmgXP9YB zvnk*^E`pYUaSR6dA7$ru@+!eVoca(;qyfO7O*-jWy+l5_u=qc{*u$D0j|hF{S7w1e zg0cTJ*YVOlI44$`_I|Idi!GPc{Qb(eYjp%yuJ~>StWhc)KD$aPv4cBM#S;T}FYB8+ zhzqMFb~rHBql?WY|Dstc)UYv4o;L_lOS}BL(Lj%Hq#uC5J=dqd=C8>Mk*7v)y@p8B zSOOv^B^O1-w?adu+#iC8;0z_Y*lea1j?+RpDTAtm-_5bTKDoNN38TE6DL;q3Q}~uB z`s?k*=;*;EQgR!$9{c&vzAj%!!SLgeYMDSHAn@JPlQd4I?3uERM8A;;+0XM$mV{u= z=PgFWRn)lRH^!)aib8 zmaDVAx4pe*|1eJIJrfPoPS8PEz3;o7c)4QoX+7ZeH7-*8T~k?9b{@Za-47vxw%hy2 zQ{*b8@Z{Er^GV6oBDR?OTt~B2h zjlOgSF_;66{i40yL3P~z)&Q{}QqcL=z(A{>c2W!mO)vFSR@sdB=Iha;vEc0T>R-wE zV*<(*5bkVK%4vS~X4rTwny>`Uug_FRj7jJ2IXE&>{>-SgxANmgC)1B=c*eej z>4+g3P_>Ov`g5+jMMQP4R2hL zTHUu#XI&=xWtR^uIJ`5LXjRyx4LRA(5sk`oMTX9L--$V5N_sjx~%qV|~TVIvmE$))e$I=<@bs&d&ndi754RQx4 zksGZ)gtfZGBT+qVDzl{fdQ-J5k7E0DTghW+7_MQZO!IRONtEayfvEnWi|j+cAtkHbnv>*uLt7P+-`$!7mEmR`_qRGNz%?wrZ zm8!dkEb%Rqhwwym$8Z)K9!;e5Hu{G&sQX@AvU^76o5PiZSPo9U)pzT_B=m4}?F>X+ z+iQaf@@N#-bOe=l=GD{KW6wqpFK)boK@3XuL&m1w2baweR)@dD8>!wLjVE|ye~8HU z<5NLB8i$kr${AP|{4;6W)Fc(`qS{p>rTnX)ac*CAPxJd@hHpY(j(a2Dr*9U2gN}Lx zNE4(Hsc|9IG~yXvk#L#S%eP!^R{<;jWh-A8*%^1I^J1nkr7{)70PMRXihB;$ZJd)3 z+&iPSmv2UVT}gSwuu||7>Bm2vBTPJNV9nv;_=|1U4F>CbtQb6xCm z-ChLA?Xmwm^J}(%PM3O)aW_HtbLUsMqMjr#s!H_YUzth8q8$cV40tJmq0rpf8=~~p z_|BU3+Cc||w+>0FYrq60h=C(_RlbbgPYM<~9joZV(!GJFWK`7^SsDCOLA`(k(h4x@ z_Vp-GYmjbWeew>XqY;e{Q9twx8t+W}WdL>|6Cy38Am@0|~v){PdA zM(x@GZy*=o({M{1xE2o7FNjUv_aZZ}g%dUbeFd-oGfi*fK+O3$|#{C!(d ze2t~^+PbJo(o-*Y)F}Me!>x|$AE|&3m+cA*8QpNZs38D(^QvEBozod*KZ%Qz`LDf2 zmO@$?*JxF~XnaHn4Wx)cw_5&5c%TRN1S$pYnBXRX5d$_cSgXcYqg^ssH*F$U#!7rl z6k_jWN**$ygZnFYB|)Ey0PcMbVuJG?=lNrXh3~`>LV{nzE3JRi4kSkIw zUoCH~2$H-@E0!P69OawK>pw#D_!vcle559Y%6n;~Bmx{aj_8m&t&40HdoR_rU6?-tW@Kfx8S{D*50tKsJq9Rm z(v(r8_g*)b?){VYt$OBT7X+Bd$rN>0#PE5+!nKycGo&fAoJPu3pkchk8M;>iu`ulh z09oH?{3k&$13lC(#+u+E?d5|~v>%q5?9@vExT8T|Hi^O?$9P{IK*%%osNIT*Oz17+ zx#BZLRT(KCL6tNmE^0k>MPtnY+am0gvLx}^&(fb~Wu>4r?RV=!b&#dklKs*nG(Dm9U0kbCG=8sdboE*NH@0YWgLB+j4&X*b; z+Le7Y^Ql0I##ABDGs!3!jal<4Uc%^N5i=22JMq%4KMOHs9{6?%+K$4H0r$MjEz}gF*J?G%O03;6h3`awBf@+gL z+F(1S^*#N1ud9JN_@`Ov;|C&FYXx(QT7-K;ZZJcjb?y$|?U%mNaA??Q3V8ujp-E4~2 z?$E}WlBqy#JMadlw9TBAI{H%-9sVW+Eud*6d&o=Zim!uWzr5Xsg7;HVB(F zW9(yz_sW$iwTfSLI^&K+5#>hp`<*v?;6IqMji}iY*F?5jGLs9w{nb4pl21yqZ)4fg zoCGQl)S{VoXIB?{sD>fwPmroo$%F1~!^wa)@^ponNgEPI>uVc$xHw;dF5+^X;0#u@ zuj!NDVe2b3%xqUb>4@+#>Dk}BsiO3#7I?j4Q7Uk~1g2d%VpMS_fH0y@EH1a+`_~=j zW2eN?+_rNT+OqhOx+2T?L-V6>E7J*Ok(M4|auydaTR2A~i@h-b+)|q?BX()xLK{(X zFv=!yDmyLQj>wKvrR)uvpD)N#ybvW1@#8JDAypWPPw`Gh*&2~UKkWHxJHum`5~dr@ zSixva)I6cj<-_@!V+TH=Q{iDc%%L5Gh5fXr~7@);V#vfHx4!4n!MCx z1Ei7q%?F9RYUu3N@6DOC{l#YwyfhO?)07qp_hMsMVuAb%5sTlQ_jg!Gu9rT-FC$bR30bn& zxjlF@Ytci8=8fG}YhK++^z;^>n39QZD>1f2$3IY4GpAEZD?RhnJ{gaXP@GgdR($OT zwp6nr`I1^o@sT*WWs~T~VP9DMRPmehMOnx=#6+crFjsPARAH#KI_$AIT7@T#NGXe* z%!mDBkmPuAf(f7R@5CR=FJo0*=2`#pOIva9#p&}N$K3`ovrE?kn^as)58{_`?=6TZ zUzK(O?Xljw%YS+=coa7aPi-A7%y^7fne+cZS!p?BJg=6@5qJtzt-{a}qt+7zUMqUR;TX;= zQD~GOEVhuOORk9yDH`eYF)^cNbPNzv>+haF5lL#toslt=(t>mX?_*XW9dO$zG5xKy zJAPLggazt%HkQsiUG`2ZMW*t`W&C)!)NY#7hx6aBYjpW!s&K`2jJHnT%E7#R6@?C;ENFNN5bjwYXTe0Ct>+v!hlqIuP znK4sW+tuMB!lR-YT&R_rq)C|~nKLM`vD=c@Aq$HF%p824weNK}f7r;xyB?hgs({gTkLgAYMShkP(EUD|POL0f~Al2^9O zr~k^g(|k33;>i}z!Qm&{8B9(?8`ROXuwkR!3$pDZs}de_we+g z?E6XR!!Um6GYIHNzSKke_}L7`AmHG%>=*Z>?SbkJ?Ml*o`># zx53IefKIIYz`XOrhd*mq+NR5sLgipE%HESJQA?bX=b6(>!PneRKW31(B~w~vObY1I zuPzWVk$`Nx27fAWzgx~MSd@_t@O}zKs;g=2?$d=#@IqU2=W2|MDsl&+80hK|se}V| zSu8h}KN7MRSjIS=1oD&zpM|_vDUOuq2G3}KCwgwCB1`+8g%pjaI79=>au8RPmK%iz@ypj{>6aP}m7?pKWuJ9L_y&`7Px!u%js>d^9Ju#!{OY(i4 zKzv5TBoLX7dr6wV6q-DczXlpwoA&vv$KUk+{Fqx^4yD8vsq%dY|8Hq}L$#&Vyskb| z{TBj5NI0-_cF3oMl)$Ec|8Jj4cnBBlJN`L@hIHR|*Bx}*qaoG1_AEqh*VYCJI6?@0 zKW35y1qP>*vI%~-Z9QL!tWzQ$wCj&K`;JY0qA|s@ioiwe9`>&BZP{0HZ-q&QlGi(sZ|5tHrToSo!#B-=es>Y zhflh>C4^)IV0I*1J}YT@)+Q2Wm+&X~4~_J%jtEf)%c7M$Iqf%ziHS^2?2V>9prI~l zFEdST_u9UHCpeij&jsM&)BZ8jb4{|nt*_-=VsGVWd^U6%lsKqRA>3Kqb6_ZvLmB}M z1-hNA0Kamew=3cD>Se|b9HRu#kBkhG>K}+9%3Zf$|O(K8-28mYhCm6VGBWc7Y)E+=rH7h%dj;kQ8*LNBZbt zR5UT=Nu1pfcL4$)z?t8a>9>4>@Pz$nNtj>h!j3Q))ZIukpW7Q)p=f2HV0%;6{qe?? z+`Cn#)@)s~k@%iC39Ie{{%2pdpESJ)9CA%#O^kfRV>lRkr9c>0=GGYIP*F z^d)CZn#p{rwvdF*UAwB%Ja7aL^_b7DX~a7U$GtJ3ui_$sG*G=edJiyJ2sWlU>EhV` zsF~_rC7b^fSL6Wq6J__TrtYovPsl~nCvAU#(J7mpYlI_NZYeJ-m1@Mhy)NmOvqyxBHTzZcU6}yI$Ymn?b%hM3kpk_S2U#2{^y1Yu{HE?__$w^O z2P~K=_Y#W7kv!O{$vDV)R8OXrS}%UjFVes$Kuw#^iIwKMqgNOj?y&BHB$xRh9-)7R z7=SymKTbw*o?&%Vn#SE$dfqans@wdU`Xgrb`K82#@Ra4reS4n(C_JOt=2%4a%@8Sz zyZSn=D!zSgIl#H?w6%~pDdW! zXh`C7!Ie{_g=MN%766cPtJSP-we16Ig_}4ZdB!oSn`ld`IKz?sjY`Sb1%we!)Lu?<$br^NINfAYVPPoXq9aY&%71ADlS$U) zLtN{Jg$b(jj^Omy-ArAsk+((RhW(h^S*hmF=RVDK!*;!fw!VDi<^huxnl*KaRgzaZ^^ru&#iU_r?EfEWz_)}&P*D6NCZ5lsm53T z?OIW2#<;=9=TA*_oaiw@@;Kxv6iQG3uON?p8*(K%^{4+^`2ULk nw#bqDZ_WQTNlDxKNAv>2`g??S@S-9y2KrJ{)>5ieunzwp%J@5b literal 0 HcmV?d00001 From 37bfd96bb849802ddb56294e058649ab3705b1df Mon Sep 17 00:00:00 2001 From: tipouic Date: Sat, 13 Feb 2016 16:17:48 +0100 Subject: [PATCH 6/9] Correction readme --- README.md | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/README.md b/README.md index 169902f..24bcc82 100644 --- a/README.md +++ b/README.md @@ -36,6 +36,8 @@ CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12 CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12 ###WK2x01 +Autobind + En cours ... ##A7105 RF Module @@ -47,12 +49,16 @@ A|E|T|R ##NRF24L01 RF Module ###CFLIE Modele: CrazyFlie Nano quad + +Autobind + CH1|CH2|CH3|CH4 ---|---|---|--- A|E|T|R ###Fy326 Autobind + CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8 ---|---|---|---|---|---|---|--- A|E|T|R|FLIP|HEADLESS|RTH|Calibrate @@ -64,6 +70,9 @@ A|E|T|R|CH5|CH6|CH7|CH8 ###HM830 Modele: HM Hobby HM830 RC Paper Airplane + +Autobind + CH1|CH2|CH3|CH4|CH5 ---|---|---|--- A|Turbo|T|Trim|Bouton ??? From bdb8eec3ea9da48ef7ad9616818a84d643d80d90 Mon Sep 17 00:00:00 2001 From: tipouic Date: Sun, 14 Feb 2016 09:21:52 +0100 Subject: [PATCH 7/9] Fin d'ajout du WK2X01 --- Multiprotocol/Cyrf6936_wk2x01.ino | 12 +-- Multiprotocol/Multiprotocol.ino | 2 +- Multiprotocol/Nrf24l01_fy326.ino | 132 +++++++++++++++++++----------- Multiprotocol/_Config.h | 3 +- Multiprotocol/liste.txt | 65 --------------- Multiprotocol/multiprotocol.h | 9 +- README.md | 41 +++++++++- sync.ffs_db | Bin 1464 -> 1450 bytes 8 files changed, 134 insertions(+), 130 deletions(-) delete mode 100644 Multiprotocol/liste.txt diff --git a/Multiprotocol/Cyrf6936_wk2x01.ino b/Multiprotocol/Cyrf6936_wk2x01.ino index 363dd61..58e866a 100644 --- a/Multiprotocol/Cyrf6936_wk2x01.ino +++ b/Multiprotocol/Cyrf6936_wk2x01.ino @@ -31,7 +31,7 @@ static const uint8_t sopcode[8] = { static const uint8_t fail_map[8] = {2, 1, 0, 3, 4, 5, 6, 7}; static uint8_t wk_pkt_num; -static u8 *radio_ch_ptr; +static uint8_t *radio_ch_ptr; static uint16_t WK_BIND_COUNTer; static uint8_t last_beacon; /* @@ -41,11 +41,11 @@ static const char * const wk2601_opts[] = { _tr_noop("COL Limit"), "-100", "100", NULL, NULL }; -*/ #define WK2601_OPT_CHANMODE 0 #define WK2601_OPT_PIT_INV 1 #define WK2601_OPT_PIT_LIMIT 2 #define LAST_PROTO_OPT 3 +*/ static void add_pkt_crc(uint8_t init) { uint8_t add = init; @@ -177,14 +177,14 @@ static void channels_heli_2601(int frame, int *v1, int *v2) { //pitch is controlled by rx //we can only control fmode, pit-reverse and pit/thr rate int pit_rev = 0; - if (Model.proto_opts[WK2601_OPT_PIT_INV]) { pit_rev = 1; } + if ((option/10)%10) { pit_rev = 1; } uint16_t pit_rate = get_channel(5, 0x400, 0, 0x400); int fmode = 1; if (pit_rate < 0) { pit_rate = -pit_rate; fmode = 0; } if (frame == 1) { //Pitch curve and range *v1 = pit_rate; - *v2 = Model.proto_opts[WK2601_OPT_PIT_LIMIT] * 0x400 / 100 + 0x400; + *v2 = ((option/100) ? -100 : 100) * 0x400 / 100 + 0x400; } packet[7] = (pit_rev << 2); //reverse bits packet[8] = fmode ? 0x02 : 0x00; @@ -207,8 +207,8 @@ static void build_data_pkt_2601() { v1 = get_channel(6, 0x200, 0x200, 0x200); v2 = 0; } - if (Model.proto_opts[WK2601_OPT_CHANMODE] == 1) { channels_heli_2601(frame, &v1, &v2); } - else if (Model.proto_opts[WK2601_OPT_CHANMODE] == 2) { channels_6plus1_2601(frame, &v1, &v2); } + if (option%10 == 1) { channels_heli_2601(frame, &v1, &v2); } + else if (option%10 == 2) { channels_6plus1_2601(frame, &v1, &v2); } else { channels_5plus1_2601(frame, &v1, &v2); } if (v1 > 1023) { v1 = 1023; } if (v2 > 1023) { v2 = 1023; } diff --git a/Multiprotocol/Multiprotocol.ino b/Multiprotocol/Multiprotocol.ino index 46f6697..b16107e 100644 --- a/Multiprotocol/Multiprotocol.ino +++ b/Multiprotocol/Multiprotocol.ino @@ -24,7 +24,7 @@ #include #include #include -#include "multiprotocol.h" +#include "Multiprotocol.h" //Multiprotocol module configuration file #include "_Config.h" diff --git a/Multiprotocol/Nrf24l01_fy326.ino b/Multiprotocol/Nrf24l01_fy326.ino index 5fe0a92..2c8f943 100644 --- a/Multiprotocol/Nrf24l01_fy326.ino +++ b/Multiprotocol/Nrf24l01_fy326.ino @@ -23,21 +23,11 @@ #define FY326_SIZE 15 #define FY326_BIND_COUNT 16 - -static const char * const fy326_opts[] = { - _tr_noop("Expert"), _tr_noop("On"), _tr_noop("Off"), NULL, - NULL -}; -#define EXPERT_ON 0 -#define EXPERT_OFF 1 - #define CHANNEL_FLIP AUX1 #define CHANNEL_HEADLESS AUX2 #define CHANNEL_RTH AUX3 #define CHANNEL_CALIBRATE AUX4 - -static uint8_t tx_power; -static uint8_t packet[FY326_SIZE]; +#define CHANNEL_EXPERT AUX5 // frequency channel management #define RF_BIND_CHANNEL 0x17 @@ -51,24 +41,27 @@ enum { FY326_INIT1 = 0, FY326_BIND1, FY326_BIND2, - FY326_DATA + FY326_DATA, + FY319_INIT1, + FY319_BIND1, + FY319_BIND2, }; // Bit vector from bit position #define BV(bit) (1 << bit) -#define CHAN_RANGE (CHAN_MAX_VALUE - CHAN_MIN_VALUE) +#define CHAN_RANGE (PPM_MAX - PPM_MIN) static uint8_t scale_channel(uint8_t ch, uint8_t destMin, uint8_t destMax) { - uint32_t chanval = Channels[ch]; + uint32_t chanval = Servo_data[ch]; uint32_t range = destMax - destMin; - if (chanval < CHAN_MIN_VALUE) chanval = CHAN_MIN_VALUE; - else if (chanval > CHAN_MAX_VALUE) chanval = CHAN_MAX_VALUE; - return (range * (chanval - CHAN_MIN_VALUE)) / CHAN_RANGE + destMin; + if (chanval < PPM_MIN) chanval = PPM_MIN; + else if (chanval > PPM_MAX) chanval = PPM_MAX; + return (range * (chanval - PPM_MIN)) / CHAN_RANGE + destMin; } -#define GET_FLAG(ch, mask) (Channels[ch] > 0 ? mask : 0) +#define GET_FLAG(ch, mask) (Servo_data[ch] > PPM_MIN_COMMAND ? mask : 0) #define CHAN_TO_TRIM(chanval) ((uint8_t)(((uint16_t)chanval/10)-10)) // scale to [-10,10]. [-20,20] caused problems. static void send_packet(uint8_t bind) { @@ -80,15 +73,22 @@ static void send_packet(uint8_t bind) | GET_FLAG(CHANNEL_RTH, 0x40) | GET_FLAG(CHANNEL_FLIP, 0x02) | GET_FLAG(CHANNEL_CALIBRATE, 0x01) - | (Model.proto_opts[PROTOOPTS_EXPERT] == EXPERT_ON ? 4 : 0); + | GET_FLAG(CHANNEL_EXPERT, 4); } packet[2] = 200 - scale_channel(AILERON, 0, 200); // aileron packet[3] = scale_channel(ELEVATOR, 0, 200); // elevator packet[4] = 200 - scale_channel(RUDDER, 0, 200); // rudder packet[5] = scale_channel(THROTTLE, 0, 200); // throttle - packet[6] = txid[0]; - packet[7] = txid[1]; - packet[8] = txid[2]; + if(sub_protocol == FY319) { + packet[6] = 255 - scale_channel(CHANNEL1, 0, 255); + packet[7] = scale_channel(CHANNEL2, 0, 255); + packet[8] = 255 - scale_channel(CHANNEL4, 0, 255); + } + else { + packet[6] = txid[0]; + packet[7] = txid[1]; + packet[8] = txid[2]; + } packet[9] = CHAN_TO_TRIM(packet[2]); // aileron_trim; packet[10] = CHAN_TO_TRIM(packet[3]); // elevator_trim; packet[11] = CHAN_TO_TRIM(packet[4]); // rudder_trim; @@ -108,25 +108,18 @@ static void send_packet(uint8_t bind) NRF24L01_FlushTx(); NRF24L01_WritePayload(packet, FY326_SIZE); - - // Check and adjust transmission power. We do this after - // transmission to not bother with timeout after power - // settings change - we have plenty of time until next - // packet. - if (tx_power != Model.tx_power) { - //Keep transmit power updated - tx_power = Model.tx_power; - NRF24L01_SetPower(tx_power); - } } static void fy326_init() { - const uint8_t rx_tx_addr[] = {0x15, 0x59, 0x23, 0xc6, 0x29}; + uint8_t rx_tx_addr[] = {0x15, 0x59, 0x23, 0xc6, 0x29}; NRF24L01_Initialize(); NRF24L01_SetTxRxMode(TX_EN); - NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x01); // Three-byte rx/tx address + if(sub_protocol == FY319) + NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // Five-byte rx/tx address + else + NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x01); // Three-byte rx/tx address NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, sizeof(rx_tx_addr)); NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, sizeof(rx_tx_addr)); NRF24L01_FlushTx(); @@ -137,7 +130,7 @@ static void fy326_init() NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, FY326_SIZE); NRF24L01_WriteReg(NRF24L01_05_RF_CH, RF_BIND_CHANNEL); NRF24L01_SetBitrate(NRF24L01_BR_250K); - NRF24L01_SetPower(Model.tx_power); + NRF24L01_SetPower(); NRF24L01_Activate(0x73); NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x3f); @@ -146,9 +139,51 @@ static void fy326_init() static uint16_t fy326_callback() { + uint8_t i; switch (phase) { + case FY319_INIT1: + NRF24L01_SetTxRxMode(TXRX_OFF); + NRF24L01_FlushRx(); + NRF24L01_SetTxRxMode(RX_EN); + NRF24L01_WriteReg(NRF24L01_05_RF_CH, RF_BIND_CHANNEL); + phase = FY319_BIND1; + BIND_IN_PROGRESS; + return PACKET_CHKTIME; + break; + + case FY319_BIND1: + if(NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_RX_DR)) { + NRF24L01_ReadPayload(packet, FY326_SIZE); + rxid = packet[13]; + packet[0] = txid[3]; + packet[1] = 0x80; + packet[14]= txid[4]; + bind_counter = BIND_COUNT; + NRF24L01_SetTxRxMode(TXRX_OFF); + NRF24L01_SetTxRxMode(TX_EN); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); + NRF24L01_FlushTx(); + bind_counter = 255; + for(i=2; i<6; i++) + packet[i] = rf_chans[0]; + phase = FY319_BIND2; + } + return PACKET_CHKTIME; + break; + + case FY319_BIND2: + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); + NRF24L01_FlushTx(); + NRF24L01_WritePayload(packet, FY326_SIZE); + if(bind_counter == 250) + packet[1] = 0x40; + if(--bind_counter == 0) { + BIND_DONE; + phase = FY326_DATA; + } + break; + case FY326_INIT1: - MUSIC_Play(MUSIC_TELEMALARM1); bind_counter = FY326_BIND_COUNT; phase = FY326_BIND2; send_packet(1); @@ -156,19 +191,13 @@ static uint16_t fy326_callback() break; case FY326_BIND1: -#ifdef EMULATOR - if (1) { - packet[13] = 0x7e; -#else if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_RX_DR)) { // RX fifo data ready NRF24L01_ReadPayload(packet, FY326_SIZE); -#endif rxid = packet[13]; txid[0] = 0xaa; NRF24L01_SetTxRxMode(TXRX_OFF); NRF24L01_SetTxRxMode(TX_EN); - PROTOCOL_SetBindState(0); - MUSIC_Play(MUSIC_DONE_BINDING); + BIND_DONE; phase = FY326_DATA; } else if (bind_counter-- == 0) { bind_counter = FY326_BIND_COUNT; @@ -181,11 +210,7 @@ static uint16_t fy326_callback() break; case FY326_BIND2: -#ifdef EMULATOR - if (1) { -#else if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_TX_DS)) { // TX data sent -#endif // switch to RX mode NRF24L01_SetTxRxMode(TXRX_OFF); NRF24L01_FlushRx(); @@ -210,7 +235,7 @@ static void fy_txid() txid[1] = ((MProtocol_id_master >> 16) & 0xFF); txid[2] = (MProtocol_id_master >> 8) & 0xFF; txid[3] = MProtocol_id_master & 0xFF; - for (uint8_t i = 0; i < sizeof(MProtocol_id_master); ++i) rand32_r(&MProtocol_id_master, 0); +// for (uint8_t i = 0; i < sizeof(MProtocol_id_master); ++i) rand32_r(&MProtocol_id_master, 0); txid[4] = MProtocol_id_master & 0xFF; rf_chans[0] = txid[0] & 0x0F; @@ -218,14 +243,21 @@ static void fy_txid() rf_chans[2] = 0x20 + (txid[1] & 0x0F); rf_chans[3] = 0x30 + (txid[1] >> 4); rf_chans[4] = 0x40 + (txid[2] >> 4); + + if(sub_protocol == FY319) { + for(uint8_t i=0; i<5; i++) + rf_chans[i] = txid[0] & ~0x80; + } } static uint16_t FY326_setup() { BIND_IN_PROGRESS; - tx_power = Model.tx_power; rxid = 0xaa; - phase = FY326_INIT1; + if(sub_protocol == FY319) + phase = FY319_INIT1; + else + phase = FY326_INIT1; bind_counter = FY326_BIND_COUNT; fy_txid(); fy326_init(); diff --git a/Multiprotocol/_Config.h b/Multiprotocol/_Config.h index 6c28b62..d39c787 100644 --- a/Multiprotocol/_Config.h +++ b/Multiprotocol/_Config.h @@ -48,7 +48,7 @@ #endif #ifdef CYRF6936_INSTALLED #define J6PRO_CYRF6936_INO -// #define WK2x01_CYRF6936_INO + #define WK2x01_CYRF6936_INO #define DEVO_CYRF6936_INO #define DSM2_CYRF6936_INO @@ -61,6 +61,7 @@ #define HM830_NRF24L01_INO #define CFlie_NRF24L01_INO #define H377_NRF24L01_INO + #define FY326_NRF24L01_INO #define BAYANG_NRF24L01_INO #define CG023_NRF24L01_INO diff --git a/Multiprotocol/liste.txt b/Multiprotocol/liste.txt deleted file mode 100644 index 3b9583e..0000000 --- a/Multiprotocol/liste.txt +++ /dev/null @@ -1,65 +0,0 @@ - MODE_SERIAL = 0, // Serial / Manche commands - MODE_FLYSKY = 1, // =>A7105 { Flysky=0, V9X9=1, V6X6=2, V912=3 }; - MODE_HUBSAN = 2, // =>A7105 - MODE_CG023 = 3, // =>NRF24L01 { CG023 = 0, YD829 = 1, H8_3D = 2 }; - MODE_CX10 = 4, // =>NRF24L01 { CX10_GREEN = 0, DM007=2, CX10_BLUE=1, // also compatible with CX10-A, CX12 }; - MODE_HISKY = 6, // =>NRF24L01 { Hisky=0, HK310=1 }; - MODE_DSM2 = 6, // =>CYRF6936 { DSM2=0, DSMX=1}; - MODE_DEVO =7, // =>CYRF6936 - MODE_YD717 = 8, // =>NRF24L01 { YD717=0, SKYWLKR=1, SYMAX2=2, XINXUN=3, NIHUI=4 }; - MODE_KN = 9, // =>NRF24L01 - MODE_SYMAX = 10, // =>NRF24L01 { SYMAX=0, SYMAX5C=1, }; - MODE_SLT = 11, // =>NRF24L01 - MODE_V2X2 = 12, // =>NRF24L01 - MODE_BAYANG = 13, // =>NRF24L01 - MODE_FRSKY = 14, // =>CC2500 - = 15, // => - - BAYANG -AUX1 FLIP -AUX2 HEADLESS -AUX3 RTH -AUX4 SNAPSHOT -AUX5 VIDEO - - CG023 -AUX1 FLIP -AUX2 LED -AUX3 STILL -AUX4 VIDEO -AUX5 EASY - - CX10 -AUX1 FLIP -AUX2 mode 1-2-3 (headless on CX-10A) -AUX3 SNAPSHOT -AUX4 VIDEO -AUX5 HEADLESS - - HUBSAN -AUX1 FLIP -AUX2 LED -AUX3 VIDEO - - KN -AUX1 Dual rate -AUX2 Throttle Hold -AUX3 Idle up -AUX4 Gyro - - V2X2 -AUX1 FLIP -AUX2 LED -AUX3 CAMERA -AUX4 VIDEO -AUX5 HEADLESS -AUX6 MAG_CAL_X -AUX7 MAG_CAL_Y - - YD717 -AUX1 FLIP -AUX2 LED -AUX3 PICTURE -AUX4 VIDEO -AUX5 HEADLESS - diff --git a/Multiprotocol/multiprotocol.h b/Multiprotocol/multiprotocol.h index 42ab887..d731f27 100644 --- a/Multiprotocol/multiprotocol.h +++ b/Multiprotocol/multiprotocol.h @@ -14,9 +14,6 @@ */ // Check selected board type -#ifndef ARDUINO_AVR_PRO -// #error You must select the board type "Arduino Pro or Pro Mini" -#endif #if F_CPU != 16000000L || not defined(__AVR_ATmega328P__) #error You must select the processor type "ATmega328(5V, 16MHz)" #endif @@ -118,12 +115,18 @@ enum MJXQ X800 = 2, H26D = 3 }; + enum WK2X01 { WK2801 = 0, WK2601 = 1, WK2401 = 2 }; +enum FY326 +{ + FY326 = 0, + FY319 = 1 +}; #define NONE 0 #define P_HIGH 1 diff --git a/README.md b/README.md index 24bcc82..dc4bccd 100644 --- a/README.md +++ b/README.md @@ -38,7 +38,36 @@ CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12 ###WK2x01 Autobind -En cours ... +####Sub_protocol WK2401 +CH1|CH2|CH3|CH4 +---|---|---|--- +CH1|CH2|CH3|CH4 + + +####Sub_protocol WK2601 +Option: + + 0 = 5+1 + 2 = 6+1 + ..1 = Hélicoptère (. = autres options pour ce mode) + .01 = Hélicoptère normal + .11 = Hélicoptère avec pit inversé + 0.1 = Pitch curve -100 + 1.1 = Pitch curve 100 + +CH1|CH2|CH3|CH4|CH5|CH6|CH7 +---|---|---|---|---|---|--- +CH1|CH2|CH3|CH4|???|CONF|Gyro & Rudder mix + +CONF: Option 1 = Rate Throtle + Option 2 = Pitch + + +####Sub_protocol WK2801 +CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8 +---|---|---|---|---|---|---|--- +CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8 + ##A7105 RF Module ###Joysway @@ -59,9 +88,12 @@ A|E|T|R ###Fy326 Autobind -CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8 ----|---|---|---|---|---|---|--- -A|E|T|R|FLIP|HEADLESS|RTH|Calibrate +CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9 +---|---|---|---|---|---|---|---|--- +A|E|T|R|FLIP|HEADLESS|RTH|Calibrate|Expert + +####Sub_protocol FY319 +Same channels assignement as above. ###H377 CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8 @@ -77,3 +109,4 @@ CH1|CH2|CH3|CH4|CH5 ---|---|---|--- A|Turbo|T|Trim|Bouton ??? +###D'autres à venir \ No newline at end of file diff --git a/sync.ffs_db b/sync.ffs_db index af956efba1caefc43b1e5aae5b1d3d108e8e4579..357e3b141bb85277f93895d22856f5869a835bfe 100644 GIT binary patch delta 605 zcmV-j0;2u63#tpSlmdU()3II3ZbFrdW1gdBZlVnf3@snaea$ey&lFg?Q3wFQKRUfdiP!6P@ShUg%Xx(L z$!?&#vn71ENp!diwxt^;m515w%bpRZ|BO{mp;rJT=j?i9roNmLH0uKnc)$V(%#91 z+{M{S8?*3?0APHFj)!Jgj%}vI_re{{2rHIRH6>z7K=(6ZDA#IP5?cLClHq7o&hE$I zwcO%Px0Ot3aTb3U?+_iF^2VkcMtouek3^}$qcSfcVb^v6d46y-K~H9Asx)5CB?`=% zy47P${zGp$l&Queoo&Ob6;cLVvYzRfBQx}~f1_ixjbOtz>LVup`zyKEJB^xDV~BZ5 zK$|tib1i#7`uGd}NDI$j-8vCfqX7T_2m}BC00000cwUni1brpUSg{|~{8W&*E(5wd zcYxg!&nU;X6-B*47)X5>hWcG#^#P3Nlez>^e++SUaJ*D9)cK-@n~5t(yqYmKe+!Cx zPJ{g`$mp{YHD2zOfyC!9nl3>V=ja2ub1#Fo9;)~fu)R(U*=XuH!RpU49AZaRA3F)8 zelJ78c2sx%S^*M|$B37naFBRA!;51xP~86j9Byrl(VJ1lAA-e=Fw(<0uy`Ye_<69n rClW^ZF9O>e%7mW&8NmKc!$>C=!RGKYT?|I`FE2P84l@7%e`flxLL(Qw delta 613 zcmV-r0-F7*3%CoglmdTki40I!;!5q43sZ>s{-NLy0{{R500000Q~>}000000zMNIr zvLm4Apm%x;rZr?}c?9ljh5>pegoRtV06_Q$XHyhwy=wXYDZ#m#MOdBe__}kngpao= z4zpmHx`7!ygu}%%6of`okd;T#TyYFd6pZnAXS384PX{T+-!gxEj=VqV6vSH>sQWB2 z+wub}1YrONz2g)B)!OU*X9dsiis3Th? z#5Etvx!n1sOFB09oD!fT9kw@`VcHf>7(a5uoifZwM%9F|bS+DgGKO-kmL_43leu>nBs^kF1QYoPPFw<#g~BXbz+!?rv4mQ zy%WPBc2xDTlR)Bo849+ey7Sixka#>seD#Eb#M>EO9GijS{s-W2Xk(1tj4J*REN+C6 zPA<-Y#Tzli&x6I4Fydtq*xpbk^nAep_HP Date: Tue, 1 Mar 2016 22:12:10 +0100 Subject: [PATCH 8/9] Ajout de 5 protocoles --- Multiprotocol/A7105_SPI.ino | 6 + Multiprotocol/DSM2_cyrf6936.ino | 8 - Multiprotocol/ESky_nrf24l01.ino | 1 - Multiprotocol/FlySky_a7105.ino | 275 +++++++------- Multiprotocol/FrSkyX_cc2500.ino | 272 +++++++------- Multiprotocol/FrSky_cc2500.ino | 52 +-- Multiprotocol/Multiprotocol.ino | 175 ++++----- Multiprotocol/NRF24l01_SPI.ino | 195 +++++++++- Multiprotocol/Nrf24l01_bluefly.ino | 183 +++++++++ Multiprotocol/Nrf24l01_esky150.ino | 172 +++++++++ Multiprotocol/Nrf24l01_fy326.ino | 25 +- Multiprotocol/Nrf24l01_hontai.ino | 272 ++++++++++++++ Multiprotocol/Nrf24l01_ne260.ino | 274 ++++++++++++++ Multiprotocol/Nrf24l01_udi.ino | 583 +++++++++++++++++++++++++++++ Multiprotocol/SHENQI_nrf24l01.ino | 108 ++++++ Multiprotocol/_Config.h | 66 ++-- Multiprotocol/iface_cc2500.h | 39 ++ Multiprotocol/multiprotocol.h | 19 +- README.md | 63 +++- 19 files changed, 2321 insertions(+), 467 deletions(-) create mode 100644 Multiprotocol/Nrf24l01_bluefly.ino create mode 100644 Multiprotocol/Nrf24l01_esky150.ino create mode 100644 Multiprotocol/Nrf24l01_hontai.ino create mode 100644 Multiprotocol/Nrf24l01_ne260.ino create mode 100644 Multiprotocol/Nrf24l01_udi.ino create mode 100644 Multiprotocol/SHENQI_nrf24l01.ino diff --git a/Multiprotocol/A7105_SPI.ino b/Multiprotocol/A7105_SPI.ino index 1698725..ad8f7be 100644 --- a/Multiprotocol/A7105_SPI.ino +++ b/Multiprotocol/A7105_SPI.ino @@ -191,10 +191,16 @@ const uint8_t PROGMEM HUBSAN_A7105_regs[] = { 0xFF, 0xFF, 0xFF }; const uint8_t PROGMEM FLYSKY_A7105_regs[] = { +/* 0xff, 0x42, 0x00, 0x14, 0x00, 0xff, 0xff ,0x00, 0x00, 0x00, 0x00, 0x01, 0x21, 0x05, 0x00, 0x50, 0x9e, 0x4b, 0x00, 0x02, 0x16, 0x2b, 0x12, 0x00, 0x62, 0x80, 0x80, 0x00, 0x0a, 0x32, 0xc3, 0x0f, 0x13, 0xc3, 0x00, 0xff, 0x00, 0x00, 0x3b, 0x00, 0x17, 0x47, 0x80, 0x03, 0x01, 0x45, 0x18, 0x00, 0x01, 0x0f, 0xff +*/ + -1, 0x42, 0x00, 0x14, 0x00, -1 , -1 , 0x00, 0x00, 0x00, 0x00, 0x01, 0x21, 0x05, 0x00, 0x50, + 0x9e, 0x4b, 0x00, 0x02, 0x16, 0x2b, 0x12, 0x00, 0x62, 0x80, 0x80, 0x00, 0x0a, 0x32, 0xc3, 0x0f, + 0x13, 0xc3, 0x00, -1, 0x00, 0x00, 0x3b, 0x00, 0x17, 0x47, 0x80, 0x03, 0x01, 0x45, 0x18, 0x00, + 0x01, 0x0f, -1 }; #define ID_NORMAL 0x55201041 #define ID_PLUS 0xAA201041 diff --git a/Multiprotocol/DSM2_cyrf6936.ino b/Multiprotocol/DSM2_cyrf6936.ino index 928d24e..0882d77 100644 --- a/Multiprotocol/DSM2_cyrf6936.ino +++ b/Multiprotocol/DSM2_cyrf6936.ino @@ -114,14 +114,6 @@ uint8_t data_col; uint16_t cyrf_state; uint8_t crcidx; uint8_t binding; -/* -#ifdef USE_FIXED_MFGID -const uint8_t cyrfmfg_id[6] = {0x5e, 0x28, 0xa3, 0x1b, 0x00, 0x00}; //dx8 -const uint8_t cyrfmfg_id[6] = {0xd4, 0x62, 0xd6, 0xad, 0xd3, 0xff}; //dx6i -#else -//uint8_t cyrfmfg_id[6]; -#endif -*/ static void __attribute__((unused)) build_bind_packet() { diff --git a/Multiprotocol/ESky_nrf24l01.ino b/Multiprotocol/ESky_nrf24l01.ino index 1ed7d3d..7641a9d 100644 --- a/Multiprotocol/ESky_nrf24l01.ino +++ b/Multiprotocol/ESky_nrf24l01.ino @@ -117,7 +117,6 @@ static void __attribute__((unused)) ESKY_send_packet(uint8_t bind) // For arithmetic simplicity, channels are repeated in rf_channels array if (hopping_frequency_no == 0) { - const uint8_t ch[]={AILERON, ELEVATOR, THROTTLE, RUDDER, AUX1, AUX2}; for (uint8_t i = 0; i < 6; i++) { packet[i*2] = Servo_data[ch[i]]>>8; //high byte of servo timing(1000-2000us) diff --git a/Multiprotocol/FlySky_a7105.ino b/Multiprotocol/FlySky_a7105.ino index 8c5f956..f32ae11 100644 --- a/Multiprotocol/FlySky_a7105.ino +++ b/Multiprotocol/FlySky_a7105.ino @@ -22,51 +22,51 @@ #define FLYSKY_BIND_COUNT 2500 const uint8_t PROGMEM tx_channels[] = { - 0x0a, 0x5a, 0x14, 0x64, 0x1e, 0x6e, 0x28, 0x78, 0x32, 0x82, 0x3c, 0x8c, 0x46, 0x96, 0x50, 0xa0, - 0xa0, 0x50, 0x96, 0x46, 0x8c, 0x3c, 0x82, 0x32, 0x78, 0x28, 0x6e, 0x1e, 0x64, 0x14, 0x5a, 0x0a, - 0x0a, 0x5a, 0x50, 0xa0, 0x14, 0x64, 0x46, 0x96, 0x1e, 0x6e, 0x3c, 0x8c, 0x28, 0x78, 0x32, 0x82, - 0x82, 0x32, 0x78, 0x28, 0x8c, 0x3c, 0x6e, 0x1e, 0x96, 0x46, 0x64, 0x14, 0xa0, 0x50, 0x5a, 0x0a, - 0x28, 0x78, 0x0a, 0x5a, 0x50, 0xa0, 0x14, 0x64, 0x1e, 0x6e, 0x3c, 0x8c, 0x32, 0x82, 0x46, 0x96, - 0x96, 0x46, 0x82, 0x32, 0x8c, 0x3c, 0x6e, 0x1e, 0x64, 0x14, 0xa0, 0x50, 0x5a, 0x0a, 0x78, 0x28, - 0x50, 0xa0, 0x28, 0x78, 0x0a, 0x5a, 0x1e, 0x6e, 0x3c, 0x8c, 0x32, 0x82, 0x46, 0x96, 0x14, 0x64, - 0x64, 0x14, 0x96, 0x46, 0x82, 0x32, 0x8c, 0x3c, 0x6e, 0x1e, 0x5a, 0x0a, 0x78, 0x28, 0xa0, 0x50, - 0x50, 0xa0, 0x46, 0x96, 0x3c, 0x8c, 0x28, 0x78, 0x0a, 0x5a, 0x32, 0x82, 0x1e, 0x6e, 0x14, 0x64, - 0x64, 0x14, 0x6e, 0x1e, 0x82, 0x32, 0x5a, 0x0a, 0x78, 0x28, 0x8c, 0x3c, 0x96, 0x46, 0xa0, 0x50, - 0x46, 0x96, 0x3c, 0x8c, 0x50, 0xa0, 0x28, 0x78, 0x0a, 0x5a, 0x1e, 0x6e, 0x32, 0x82, 0x14, 0x64, - 0x64, 0x14, 0x82, 0x32, 0x6e, 0x1e, 0x5a, 0x0a, 0x78, 0x28, 0xa0, 0x50, 0x8c, 0x3c, 0x96, 0x46, - 0x46, 0x96, 0x0a, 0x5a, 0x3c, 0x8c, 0x14, 0x64, 0x50, 0xa0, 0x28, 0x78, 0x1e, 0x6e, 0x32, 0x82, - 0x82, 0x32, 0x6e, 0x1e, 0x78, 0x28, 0xa0, 0x50, 0x64, 0x14, 0x8c, 0x3c, 0x5a, 0x0a, 0x96, 0x46, - 0x46, 0x96, 0x0a, 0x5a, 0x50, 0xa0, 0x3c, 0x8c, 0x28, 0x78, 0x1e, 0x6e, 0x32, 0x82, 0x14, 0x64, - 0x64, 0x14, 0x82, 0x32, 0x6e, 0x1e, 0x78, 0x28, 0x8c, 0x3c, 0xa0, 0x50, 0x5a, 0x0a, 0x96, 0x46 + 0x0a, 0x5a, 0x14, 0x64, 0x1e, 0x6e, 0x28, 0x78, 0x32, 0x82, 0x3c, 0x8c, 0x46, 0x96, 0x50, 0xa0, + 0xa0, 0x50, 0x96, 0x46, 0x8c, 0x3c, 0x82, 0x32, 0x78, 0x28, 0x6e, 0x1e, 0x64, 0x14, 0x5a, 0x0a, + 0x0a, 0x5a, 0x50, 0xa0, 0x14, 0x64, 0x46, 0x96, 0x1e, 0x6e, 0x3c, 0x8c, 0x28, 0x78, 0x32, 0x82, + 0x82, 0x32, 0x78, 0x28, 0x8c, 0x3c, 0x6e, 0x1e, 0x96, 0x46, 0x64, 0x14, 0xa0, 0x50, 0x5a, 0x0a, + 0x28, 0x78, 0x0a, 0x5a, 0x50, 0xa0, 0x14, 0x64, 0x1e, 0x6e, 0x3c, 0x8c, 0x32, 0x82, 0x46, 0x96, + 0x96, 0x46, 0x82, 0x32, 0x8c, 0x3c, 0x6e, 0x1e, 0x64, 0x14, 0xa0, 0x50, 0x5a, 0x0a, 0x78, 0x28, + 0x50, 0xa0, 0x28, 0x78, 0x0a, 0x5a, 0x1e, 0x6e, 0x3c, 0x8c, 0x32, 0x82, 0x46, 0x96, 0x14, 0x64, + 0x64, 0x14, 0x96, 0x46, 0x82, 0x32, 0x8c, 0x3c, 0x6e, 0x1e, 0x5a, 0x0a, 0x78, 0x28, 0xa0, 0x50, + 0x50, 0xa0, 0x46, 0x96, 0x3c, 0x8c, 0x28, 0x78, 0x0a, 0x5a, 0x32, 0x82, 0x1e, 0x6e, 0x14, 0x64, + 0x64, 0x14, 0x6e, 0x1e, 0x82, 0x32, 0x5a, 0x0a, 0x78, 0x28, 0x8c, 0x3c, 0x96, 0x46, 0xa0, 0x50, + 0x46, 0x96, 0x3c, 0x8c, 0x50, 0xa0, 0x28, 0x78, 0x0a, 0x5a, 0x1e, 0x6e, 0x32, 0x82, 0x14, 0x64, + 0x64, 0x14, 0x82, 0x32, 0x6e, 0x1e, 0x5a, 0x0a, 0x78, 0x28, 0xa0, 0x50, 0x8c, 0x3c, 0x96, 0x46, + 0x46, 0x96, 0x0a, 0x5a, 0x3c, 0x8c, 0x14, 0x64, 0x50, 0xa0, 0x28, 0x78, 0x1e, 0x6e, 0x32, 0x82, + 0x82, 0x32, 0x6e, 0x1e, 0x78, 0x28, 0xa0, 0x50, 0x64, 0x14, 0x8c, 0x3c, 0x5a, 0x0a, 0x96, 0x46, + 0x46, 0x96, 0x0a, 0x5a, 0x50, 0xa0, 0x3c, 0x8c, 0x28, 0x78, 0x1e, 0x6e, 0x32, 0x82, 0x14, 0x64, + 0x64, 0x14, 0x82, 0x32, 0x6e, 0x1e, 0x78, 0x28, 0x8c, 0x3c, 0xa0, 0x50, 0x5a, 0x0a, 0x96, 0x46 }; enum { - // flags going to byte 10 - FLAG_V9X9_VIDEO = 0x40, - FLAG_V9X9_CAMERA= 0x80, - // flags going to byte 12 - FLAG_V9X9_UNK = 0x10, // undocumented ? - FLAG_V9X9_LED = 0x20, + // flags going to byte 10 + FLAG_V9X9_VIDEO = 0x40, + FLAG_V9X9_CAMERA= 0x80, + // flags going to byte 12 + FLAG_V9X9_FLIP = 0x10, + FLAG_V9X9_LED = 0x20, }; enum { - // flags going to byte 13 - FLAG_V6X6_HLESS1= 0x80, - // flags going to byte 14 - FLAG_V6X6_VIDEO = 0x01, - FLAG_V6X6_YCAL = 0x02, - FLAG_V6X6_XCAL = 0x04, - FLAG_V6X6_RTH = 0x08, - FLAG_V6X6_CAMERA= 0x10, - FLAG_V6X6_HLESS2= 0x20, - FLAG_V6X6_LED = 0x40, - FLAG_V6X6_FLIP = 0x80, + // flags going to byte 13 + FLAG_V6X6_HLESS1= 0x80, + // flags going to byte 14 + FLAG_V6X6_VIDEO = 0x01, + FLAG_V6X6_YCAL = 0x02, + FLAG_V6X6_XCAL = 0x04, + FLAG_V6X6_RTH = 0x08, + FLAG_V6X6_CAMERA= 0x10, + FLAG_V6X6_HLESS2= 0x20, + FLAG_V6X6_LED = 0x40, + FLAG_V6X6_FLIP = 0x80, }; enum { - // flags going to byte 14 - FLAG_V912_TOPBTN= 0x40, - FLAG_V912_BTMBTN= 0x80, + // flags going to byte 14 + FLAG_V912_TOPBTN= 0x40, + FLAG_V912_BTMBTN= 0x80, }; uint8_t chanrow; @@ -75,138 +75,139 @@ uint8_t chanoffset; static void __attribute__((unused)) flysky_apply_extension_flags() { - const uint8_t V912_X17_SEQ[10] = { 0x14, 0x31, 0x40, 0x49, 0x49, // sometime first byte is 0x15 ? - 0x49, 0x49, 0x49, 0x49, 0x49, }; - static uint8_t seq_counter; - switch(sub_protocol) - { - case V9X9: - if(Servo_AUX1) - packet[12] |= FLAG_V9X9_UNK; - if(Servo_AUX2) - packet[12] |= FLAG_V9X9_LED; - if(Servo_AUX3) - packet[10] |= FLAG_V9X9_CAMERA; - if(Servo_AUX4) - packet[10] |= FLAG_V9X9_VIDEO; - break; - - case V6X6: - packet[13] = 0x03; // 3 = 100% rate (0=40%, 1=60%, 2=80%) - packet[14] = 0x00; - if(Servo_AUX1) - packet[14] |= FLAG_V6X6_FLIP; - if(Servo_AUX2) - packet[14] |= FLAG_V6X6_LED; - if(Servo_AUX3) - packet[14] |= FLAG_V6X6_CAMERA; - if(Servo_AUX4) - packet[14] |= FLAG_V6X6_VIDEO; - if(Servo_AUX5) - { - packet[13] |= FLAG_V6X6_HLESS1; - packet[14] |= FLAG_V6X6_HLESS2; - } - if(Servo_AUX6) //use option to manipulate these bytes - packet[14] |= FLAG_V6X6_RTH; - if(Servo_AUX7) - packet[14] |= FLAG_V6X6_XCAL; - if(Servo_AUX8) - packet[14] |= FLAG_V6X6_YCAL; - packet[15] = 0x10; // unknown - packet[16] = 0x10; // unknown - packet[17] = 0xAA; // unknown - packet[18] = 0xAA; // unknown - packet[19] = 0x60; // unknown, changes at irregular interval in stock TX - packet[20] = 0x02; // unknown - break; - - case V912: - seq_counter++; - if( seq_counter > 9) - seq_counter = 0; - packet[12] |= 0x20; // bit 6 is always set ? - packet[13] = 0x00; // unknown - packet[14] = 0x00; - if(Servo_AUX1) - packet[14] = FLAG_V912_BTMBTN; - if(Servo_AUX2) - packet[14] |= FLAG_V912_TOPBTN; - packet[15] = 0x27; // [15] and [16] apparently hold an analog channel with a value lower than 1000 - packet[16] = 0x03; // maybe it's there for a pitch channel for a CP copter ? - packet[17] = V912_X17_SEQ[seq_counter]; // not sure what [17] & [18] are for - if(seq_counter == 0) // V912 Rx does not even read those bytes... [17-20] - packet[18] = 0x02; - else - packet[18] = 0x00; - packet[19] = 0x00; // unknown - packet[20] = 0x00; // unknown - break; - - default: - break; - } + const uint8_t V912_X17_SEQ[10] = { 0x14, 0x31, 0x40, 0x49, 0x49, // sometime first byte is 0x15 ? + 0x49, 0x49, 0x49, 0x49, 0x49, }; + static uint8_t seq_counter; + switch(sub_protocol) + { + case V9X9: + if(Servo_AUX1) + packet[12] |= FLAG_V9X9_FLIP; + if(Servo_AUX2) + packet[12] |= FLAG_V9X9_LED; + if(Servo_AUX3) + packet[10] |= FLAG_V9X9_CAMERA; + if(Servo_AUX4) + packet[10] |= FLAG_V9X9_VIDEO; + break; + + case V6X6: + packet[13] = 0x03; // 3 = 100% rate (0=40%, 1=60%, 2=80%) + packet[14] = 0x00; + if(Servo_AUX1) + packet[14] |= FLAG_V6X6_FLIP; + if(Servo_AUX2) + packet[14] |= FLAG_V6X6_LED; + if(Servo_AUX3) + packet[14] |= FLAG_V6X6_CAMERA; + if(Servo_AUX4) + packet[14] |= FLAG_V6X6_VIDEO; + if(Servo_AUX5) + { + packet[13] |= FLAG_V6X6_HLESS1; + packet[14] |= FLAG_V6X6_HLESS2; + } + if(Servo_AUX6) //use option to manipulate these bytes + packet[14] |= FLAG_V6X6_RTH; + if(Servo_AUX7) + packet[14] |= FLAG_V6X6_XCAL; + if(Servo_AUX8) + packet[14] |= FLAG_V6X6_YCAL; + packet[15] = 0x10; // unknown + packet[16] = 0x10; // unknown + packet[17] = 0xAA; // unknown + packet[18] = 0xAA; // unknown + packet[19] = 0x60; // unknown, changes at irregular interval in stock TX + packet[20] = 0x02; // unknown + break; + + case V912: + seq_counter++; + if( seq_counter > 9) + seq_counter = 0; + packet[12] |= 0x20; // bit 6 is always set ? + packet[13] = 0x00; // unknown + packet[14] = 0x00; + if(Servo_AUX1) + packet[14] = FLAG_V912_BTMBTN; + if(Servo_AUX2) + packet[14] |= FLAG_V912_TOPBTN; + packet[15] = 0x27; // [15] and [16] apparently hold an analog channel with a value lower than 1000 + packet[16] = 0x03; // maybe it's there for a pitch channel for a CP copter ? + packet[17] = V912_X17_SEQ[seq_counter]; // not sure what [17] & [18] are for + if(seq_counter == 0) // V912 Rx does not even read those bytes... [17-20] + packet[18] = 0x02; + else + packet[18] = 0x00; + packet[19] = 0x00; // unknown + packet[20] = 0x00; // unknown + break; + + default: + break; + } } static void __attribute__((unused)) flysky_build_packet(uint8_t init) { uint8_t i; - //servodata timing range for flysky. - ////-100% =~ 0x03e8//=1000us(min) - //+100% =~ 0x07ca//=1994us(max) - //Center = 0x5d9//=1497us(center) - //channel order AIL;ELE;THR;RUD;AUX1;AUX2;AUX3;AUX4 + //servodata timing range for flysky. + ////-100% =~ 0x03e8//=1000us(min) + //+100% =~ 0x07ca//=1994us(max) + //Center = 0x5d9//=1497us(center) + //channel order AIL;ELE;THR;RUD;AUX1;AUX2;AUX3;AUX4 packet[0] = init ? 0xaa : 0x55; packet[1] = rx_tx_addr[3]; packet[2] = rx_tx_addr[2]; packet[3] = rx_tx_addr[1]; packet[4] = rx_tx_addr[0]; - const uint8_t ch[]={AILERON, ELEVATOR, THROTTLE, RUDDER, AUX1, AUX2, AUX3, AUX4}; - for(i = 0; i < 8; i++) - { - packet[5+2*i]=lowByte(Servo_data[ch[i]]); //low byte of servo timing(1000-2000us) - packet[6+2*i]=highByte(Servo_data[ch[i]]); //high byte of servo timing(1000-2000us) - } + const uint8_t ch[]={AILERON, ELEVATOR, THROTTLE, RUDDER, AUX1, AUX2, AUX3, AUX4}; + for(i = 0; i < 8; i++) + { + packet[5+2*i]=lowByte(Servo_data[ch[i]]); //low byte of servo timing(1000-2000us) + packet[6+2*i]=highByte(Servo_data[ch[i]]); //high byte of servo timing(1000-2000us) + } flysky_apply_extension_flags(); } uint16_t ReadFlySky() { if (bind_counter) - { + { flysky_build_packet(1); A7105_WriteData(21, 1); bind_counter--; if (! bind_counter) BIND_DONE; } - else - { + else + { flysky_build_packet(0); A7105_WriteData(21, pgm_read_byte_near(&tx_channels[chanrow*16+chancol])-chanoffset); chancol = (chancol + 1) % 16; if (! chancol) //Keep transmit power updated - A7105_SetPower(); + A7105_SetPower(); } - return 1460; + return 1460; } uint16_t initFlySky() { - //A7105_Reset(); - A7105_Init(INIT_FLYSKY); //flysky_init(); - - if (rx_tx_addr[3] > 0x90) // limit offset to 9 as higher values don't work with some RX (ie V912) - rx_tx_addr[3] = rx_tx_addr[3] - 0x70; - chanrow=rx_tx_addr[3] % 16; - chancol=0; - chanoffset=rx_tx_addr[3] / 16; - + //A7105_Reset(); + A7105_Init(INIT_FLYSKY); //flysky_init(); + + if (rx_tx_addr[3] > 0x90) // limit offset to 9 as higher values don't work with some RX (ie V912) + rx_tx_addr[3] = rx_tx_addr[3] - 0x70; + chanrow=rx_tx_addr[3] % 16; + chancol=0; + chanoffset=rx_tx_addr[3] / 16; + - if(IS_AUTOBIND_FLAG_on) - bind_counter = FLYSKY_BIND_COUNT; - else - bind_counter = 0; - return 2400; + if(IS_AUTOBIND_FLAG_on) + bind_counter = FLYSKY_BIND_COUNT; + else + bind_counter = 0; + return 2400; } #endif + diff --git a/Multiprotocol/FrSkyX_cc2500.ino b/Multiprotocol/FrSkyX_cc2500.ino index 19044ef..dc6e2f2 100644 --- a/Multiprotocol/FrSkyX_cc2500.ino +++ b/Multiprotocol/FrSkyX_cc2500.ino @@ -43,101 +43,12 @@ 0x34, 0x1B, 0x00, 0x1D, 0x03 }; - uint8_t hop(uint8_t byte) + static uint8_t __attribute__((unused)) hop(uint8_t byte) { return pgm_read_byte_near(&hop_data[byte]); } - uint16_t initFrSkyX() - { - while(!chanskip) - { - randomSeed((uint32_t)analogRead(A6) << 10 | analogRead(A7)); - chanskip=random(0xfefefefe)%47; - } - while((chanskip-ctr)%4) - ctr=(ctr+1)%4; - - counter_rst=(chanskip-ctr)>>2; - //for test*************** - //rx_tx_addr[3]=0xB3; - //rx_tx_addr[2]=0xFD; - //************************ - frskyX_init(); - // - if(IS_AUTOBIND_FLAG_on) - { - state = FRSKY_BIND; - initialize_data(1); - } - else - { - state = FRSKY_DATA1; - initialize_data(0); - } - return 10000; - } - - uint16_t ReadFrSkyX() - { - switch(state) - { - default: - set_start(47); - CC2500_SetPower(); - cc2500_strobe(CC2500_SFRX); - // - frskyX_build_bind_packet(); - cc2500_strobe(CC2500_SIDLE); - cc2500_writeFifo(packet, packet[0]+1); - state++; - return 9000; - case FRSKY_BIND_DONE: - initialize_data(0); - channr=0; - BIND_DONE; - state++; - break; - case FRSKY_DATA1: - LED_ON; - CC2500_SetTxRxMode(TX_EN); - set_start(channr); - CC2500_SetPower(); - cc2500_strobe(CC2500_SFRX); - channr = (channr+chanskip)%47; - cc2500_strobe(CC2500_SIDLE); - cc2500_writeFifo(packet, packet[0]+1); - // - frskyX_data_frame(); - state++; - return 5500; - case FRSKY_DATA2: - CC2500_SetTxRxMode(RX_EN); - cc2500_strobe(CC2500_SIDLE); - state++; - return 200; - case FRSKY_DATA3: - cc2500_strobe(CC2500_SRX); - state++; - return 3000; - case FRSKY_DATA4: - len = cc2500_readReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F; - if (len &&(len>8) ^ byte) & 0xFF]); + return byte; + } + + static uint16_t __attribute__((unused)) scaleForPXX( uint8_t i ) + { //mapped 860,2140(125%) range to 64,1984(PXX values); + return (uint16_t)(((Servo_data[i]-PPM_MIN)*3)>>1)+64; + } + + static void __attribute__((unused)) frskyX_build_bind_packet() { crc=0; packet[0] = 0x1D; @@ -243,7 +159,7 @@ // } - void frskyX_data_frame() + static void __attribute__((unused)) frskyX_data_frame() { //0x1D 0xB3 0xFD 0x02 0x56 0x07 0x15 0x00 0x00 0x00 0x04 0x40 0x00 0x04 0x40 0x00 0x04 0x40 0x00 0x04 0x40 0x08 0x00 0x00 0x00 0x00 0x00 0x00 0x96 0x12 // @@ -302,14 +218,92 @@ packet[29]=lowByte(crc); } - uint16_t scaleForPXX( uint8_t i ) - { //mapped 860,2140(125%) range to 64,1984(PXX values); - return (uint16_t)(((Servo_data[i]-PPM_MIN)*3)>>1)+64; - } - - uint8_t crc_Byte( uint8_t byte ) + uint16_t ReadFrSkyX() { - crc = (crc<<8) ^ pgm_read_word(&CRCTable[((uint8_t)(crc>>8) ^ byte) & 0xFF]); - return byte; + switch(state) + { + default: + set_start(47); + CC2500_SetPower(); + cc2500_strobe(CC2500_SFRX); + // + frskyX_build_bind_packet(); + cc2500_strobe(CC2500_SIDLE); + cc2500_writeFifo(packet, packet[0]+1); + state++; + return 9000; + case FRSKY_BIND_DONE: + initialize_data(0); + channr=0; + BIND_DONE; + state++; + break; + case FRSKY_DATA1: + LED_ON; + CC2500_SetTxRxMode(TX_EN); + set_start(channr); + CC2500_SetPower(); + cc2500_strobe(CC2500_SFRX); + channr = (channr+chanskip)%47; + cc2500_strobe(CC2500_SIDLE); + cc2500_writeFifo(packet, packet[0]+1); + // + frskyX_data_frame(); + state++; + return 5500; + case FRSKY_DATA2: + CC2500_SetTxRxMode(RX_EN); + cc2500_strobe(CC2500_SIDLE); + state++; + return 200; + case FRSKY_DATA3: + cc2500_strobe(CC2500_SRX); + state++; + return 3000; + case FRSKY_DATA4: + len = cc2500_readReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F; + if (len &&(len>2; + //for test*************** + //rx_tx_addr[3]=0xB3; + //rx_tx_addr[2]=0xFD; + //************************ + frskyX_init(); + // + if(IS_AUTOBIND_FLAG_on) + { + state = FRSKY_BIND; + initialize_data(1); + } + else + { + state = FRSKY_DATA1; + initialize_data(0); + } + return 10000; + } #endif \ No newline at end of file diff --git a/Multiprotocol/FrSky_cc2500.ino b/Multiprotocol/FrSky_cc2500.ino index f3c6d3c..ec17450 100644 --- a/Multiprotocol/FrSky_cc2500.ino +++ b/Multiprotocol/FrSky_cc2500.ino @@ -38,45 +38,19 @@ static void __attribute__((unused)) frsky2way_init(uint8_t bind) // Configure cc2500 for tx mode CC2500_Reset(); // - cc2500_writeReg(CC2500_02_IOCFG0, 0x06); - cc2500_writeReg(CC2500_00_IOCFG2, 0x06); - cc2500_writeReg(CC2500_17_MCSM1, 0x0c); - cc2500_writeReg(CC2500_18_MCSM0, 0x18); - cc2500_writeReg(CC2500_06_PKTLEN, 0x19); - cc2500_writeReg(CC2500_07_PKTCTRL1, 0x04); - cc2500_writeReg(CC2500_08_PKTCTRL0, 0x05); - cc2500_writeReg(CC2500_3E_PATABLE, 0xff); - cc2500_writeReg(CC2500_0B_FSCTRL1, 0x08); - cc2500_writeReg(CC2500_0C_FSCTRL0, option); - //base freq FREQ = 0x5C7627 (F = 2404MHz) - cc2500_writeReg(CC2500_0D_FREQ2, 0x5c); - cc2500_writeReg(CC2500_0E_FREQ1, 0x76); - cc2500_writeReg(CC2500_0F_FREQ0, 0x27); - // - cc2500_writeReg(CC2500_10_MDMCFG4, 0xAA); - cc2500_writeReg(CC2500_11_MDMCFG3, 0x39); - cc2500_writeReg(CC2500_12_MDMCFG2, 0x11); - cc2500_writeReg(CC2500_13_MDMCFG1, 0x23); - cc2500_writeReg(CC2500_14_MDMCFG0, 0x7a); - cc2500_writeReg(CC2500_15_DEVIATN, 0x42); - cc2500_writeReg(CC2500_19_FOCCFG, 0x16); - cc2500_writeReg(CC2500_1A_BSCFG, 0x6c); - cc2500_writeReg(CC2500_1B_AGCCTRL2, bind ? 0x43 : 0x03); - cc2500_writeReg(CC2500_1C_AGCCTRL1,0x40); - cc2500_writeReg(CC2500_1D_AGCCTRL0,0x91); - cc2500_writeReg(CC2500_21_FREND1, 0x56); - cc2500_writeReg(CC2500_22_FREND0, 0x10); - cc2500_writeReg(CC2500_23_FSCAL3, 0xa9); - cc2500_writeReg(CC2500_24_FSCAL2, 0x0A); - cc2500_writeReg(CC2500_25_FSCAL1, 0x00); - cc2500_writeReg(CC2500_26_FSCAL0, 0x11); - cc2500_writeReg(CC2500_29_FSTEST, 0x59); - cc2500_writeReg(CC2500_2C_TEST2, 0x88); - cc2500_writeReg(CC2500_2D_TEST1, 0x31); - cc2500_writeReg(CC2500_2E_TEST0, 0x0B); - cc2500_writeReg(CC2500_03_FIFOTHR, 0x07); - cc2500_writeReg(CC2500_09_ADDR, 0x00); - // + for(uint8_t i=0;i<36;i++) + { + uint8_t reg=pgm_read_byte_near(&cc2500_conf[i][0]); + uint8_t val=pgm_read_byte_near(&cc2500_conf[i][1]); + + if(reg==CC2500_0C_FSCTRL0) + val=option; + else + if(reg==CC2500_1B_AGCCTRL2) + val=bind ? 0x43 : 0x03; + cc2500_writeReg(reg,val); + } + CC2500_SetTxRxMode(TX_EN); CC2500_SetPower(); diff --git a/Multiprotocol/Multiprotocol.ino b/Multiprotocol/Multiprotocol.ino index b16107e..109586c 100644 --- a/Multiprotocol/Multiprotocol.ino +++ b/Multiprotocol/Multiprotocol.ino @@ -45,8 +45,7 @@ uint8_t packet[40]; // Servo data uint16_t Servo_data[NUM_CHN]; uint8_t Servo_AUX; -// PPM variable -volatile uint16_t PPM_data[NUM_CHN]; +const uint8_t ch[]={AILERON, ELEVATOR, THROTTLE, RUDDER, AUX1, AUX2, AUX3, AUX4}; // Protocol variables uint8_t rx_tx_addr[5]; @@ -73,9 +72,11 @@ uint8_t RX_num; // Mode_select variables uint8_t mode_select; -uint8_t ppm_select=0, flag_decal=0; uint8_t protocol_flags=0,protocol_flags2=0; +// PPM variable +volatile uint16_t PPM_data[NUM_CHN]; + // Serial variables #define RXBUFFER_SIZE 25 #define TXBUFFER_SIZE 12 @@ -158,25 +159,24 @@ void setup() MProtocol_id_master=random_id(10,false); //Init RF modules - CC2500_Reset(); + #ifdef CC2500_INSTALLED + CC2500_Reset(); + #endif //Protocol and interrupts initialization - #if !defined(POTAR_SELECT) - if(mode_select == MODE_SERIAL) - { // Serial - cur_protocol[0]=0; - cur_protocol[1]=0; - prev_protocol=0; - Mprotocol_serial_init(); // Configure serial and enable RX interrupt - } - else - #else - if(mode_select==MODE_SERIAL) { flag_decal=1; } else { flag_decal=0;} - #endif + if(mode_select != MODE_SERIAL) { // PPM - prev_protocol=0; - CHANGE_PROTOCOL_FLAG_on; - update_ppm_data(); + mode_select--; + cur_protocol[0] = PPM_prot[mode_select].protocol; + sub_protocol = PPM_prot[mode_select].sub_proto; + RX_num = PPM_prot[mode_select].rx_num; + MProtocol_id = RX_num + MProtocol_id_master; + option = PPM_prot[mode_select].option; + if(PPM_prot[mode_select].power) POWER_FLAG_on; + if(PPM_prot[mode_select].autobind) AUTOBIND_FLAG_on; + mode_select++; + + protocol_init(); //Configure PPM interrupt EICRA |=(1<PPM_SWITCH) + if(Servo_data[AUX1+i]>PPM_SWITCH) Servo_AUX|=1<PPM_SWITCH) { - CHANGE_PROTOCOL_FLAG_on; - tone(BUZZER, BUZZER_HTZ); - delay(BUZZER_TPS); - noTone(BUZZER); - } - #endif - if(IS_CHANGE_PROTOCOL_FLAG_on) { - ppm_select = 10; - - if(mode_select == 0) { - while(ppm_select) { - while(!IS_PPM_FLAG_on) {} // wait - update_PPM_servo(); - if(Servo_data[AUX1] < PPM_MAX_100) { ppm_select--; } - } // attente de la d�activation du rebind - } - prev_protocol = ppm_select; - - // protocol selection - ppm_select = 0; - if(Servo_data[POTAR_SELECT_M] > PPM_MAX_COMMAND) { ppm_select += 18; } // THROTTLE up - else if(Servo_data[POTAR_SELECT_M] < PPM_MIN_COMMAND) { ppm_select += 9; } // THROTTLE down - else { ppm_select += 0; } // THROTTLE middle - - - if(Servo_data[POTAR_SELECT_V] > PPM_MAX_COMMAND) { ppm_select += 7; } // Elevator up - else if(Servo_data[POTAR_SELECT_V] < PPM_MIN_COMMAND) { ppm_select += 1; } // Elevator down - else { ppm_select += 4; } // Elevator middle - - if(Servo_data[POTAR_SELECT_H] > PPM_MAX_COMMAND) { ppm_select += 2; } // Aileron right - else if(Servo_data[POTAR_SELECT_H] < PPM_MIN_COMMAND) { ppm_select += 0; } // Aileron left - else { ppm_select += 1; } // Aileron middle - -// if(ppm_select == 5) { ppm_select = eeprom_read_byte(30); } else { eeprom_update_byte(30, ppm_select); } - - if(ppm_select != 5) { - if(ppm_select > 5) { ppm_select--; } - ppm_select--; - cur_protocol[0] = PPM_prot[ppm_select].protocol; - sub_protocol = PPM_prot[ppm_select].sub_proto; - MProtocol_id = PPM_prot[ppm_select].rx_num + MProtocol_id_master; - option = PPM_prot[ppm_select].option; - if(PPM_prot[ppm_select].power) POWER_FLAG_on; - if(PPM_prot[ppm_select].autobind) AUTOBIND_FLAG_on; - ppm_select++; - } - - while(Servo_data[THROTTLE] > PPM_MIN_100) { delay(100); update_PPM_servo(); } // attente de la remise des gaz � z�ro (pouss� � fond avec le script lua) - } -} static void update_serial_data() { if(rx_ok_buff[0]&0x20) //check range @@ -610,7 +594,7 @@ static void module_reset() case MODE_DEVO: CYRF_Reset(); break; - default: // MODE_HISKY, MODE_V2X2, MODE_YD717, MODE_KN, MODE_SYMAX, MODE_SLT, MODE_CX10, MODE_CG023, MODE_BAYANG, MODE_ESKY, MODE_MT99XX, MODE_MJXQ + default: // MODE_HISKY, MODE_V2X2, MODE_YD717, MODE_KN, MODE_SYMAX, MODE_SLT, MODE_CX10, MODE_CG023, MODE_BAYANG, MODE_ESKY, MODE_MT99XX, MODE_MJXQ, MODE_SHENQI NRF24L01_Reset(); break; } @@ -682,7 +666,6 @@ void Serial_write(uint8_t data) static void Mprotocol_serial_init() { - #define BAUD 100000 #include UBRR0H = UBRRH_VALUE; UBRR0L = UBRRL_VALUE; @@ -778,7 +761,6 @@ ISR(INT1_vect) } //Serial RX -#if !defined(POTAR_SELECT) ISR(USART_RX_vect) { // RX interrupt if((UCSR0A&0x1C)==0) // Check frame error, data overrun and parity error @@ -815,7 +797,6 @@ ISR(USART_RX_vect) idx=0; // Error encountered discard full frame... } } -#endif //Serial timer ISR(TIMER1_COMPB_vect) diff --git a/Multiprotocol/NRF24l01_SPI.ino b/Multiprotocol/NRF24l01_SPI.ino index cec1439..f95e86f 100644 --- a/Multiprotocol/NRF24l01_SPI.ino +++ b/Multiprotocol/NRF24l01_SPI.ino @@ -154,7 +154,7 @@ void NRF24L01_SetBitrate(uint8_t bitrate) // Note that bitrate 250kbps (and bit RF_DR_LOW) is valid only // for nRF24L01+. There is no way to programmatically tell it from // older version, nRF24L01, but the older is practically phased out - // by Nordic, so we assume that we deal with with modern version. + // by Nordic, so we assume that we deal with modern version. // Bit 0 goes to RF_DR_HIGH, bit 1 - to RF_DR_LOW rf_setup = (rf_setup & 0xD7) | ((bitrate & 0x02) << 4) | ((bitrate & 0x01) << 3); @@ -409,3 +409,196 @@ void XN297_ReadPayload(uint8_t* msg, uint8_t len) } // End of XN297 emulation + +/////////////// +// LT8910 emulation layer +uint8_t LT8910_buffer[64]; +uint8_t LT8910_buffer_start; +uint16_t LT8910_buffer_overhead_bits; +uint8_t LT8910_addr[8]; +uint8_t LT8910_addr_size; +uint8_t LT8910_Preamble_Len; +uint8_t LT8910_Tailer_Len; +uint8_t LT8910_CRC_Initial_Data; +uint8_t LT8910_Flags; +#define LT8910_CRC_ON 6 +#define LT8910_SCRAMBLE_ON 5 +#define LT8910_PACKET_LENGTH_EN 4 +#define LT8910_DATA_PACKET_TYPE_1 3 +#define LT8910_DATA_PACKET_TYPE_0 2 +#define LT8910_FEC_TYPE_1 1 +#define LT8910_FEC_TYPE_0 0 + +void LT8910_Config(uint8_t preamble_len, uint8_t trailer_len, uint8_t flags, uint8_t crc_init) +{ + //Preamble 1 to 8 bytes + LT8910_Preamble_Len=preamble_len; + //Trailer 4 to 18 bits + LT8910_Tailer_Len=trailer_len; + //Flags + // CRC_ON: 1 on, 0 off + // SCRAMBLE_ON: 1 on, 0 off + // PACKET_LENGTH_EN: 1 1st byte of payload is payload size + // DATA_PACKET_TYPE: 00 NRZ, 01 Manchester, 10 8bit/10bit line code, 11 interleave data type + // FEC_TYPE: 00 No FEC, 01 FEC13, 10 FEC23, 11 reserved + LT8910_Flags=flags; + //CRC init constant + LT8910_CRC_Initial_Data=crc_init; +} + +void LT8910_SetChannel(uint8_t channel) +{ + NRF24L01_WriteReg(NRF24L01_05_RF_CH, channel +2); //NRF24L01 is 2400+channel but LT8900 is 2402+channel +} + +void LT8910_SetTxRxMode(enum TXRX_State mode) +{ + if(mode == TX_EN) + { + //Switch to TX + NRF24L01_SetTxRxMode(TXRX_OFF); + NRF24L01_SetTxRxMode(TX_EN); + //Disable CRC + NRF24L01_WriteReg(NRF24L01_00_CONFIG, (1 << NRF24L01_00_PWR_UP)); + } + else + if (mode == RX_EN) + { + NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only + NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, 32); + //Switch to RX + NRF24L01_SetTxRxMode(TXRX_OFF); + NRF24L01_FlushRx(); + NRF24L01_SetTxRxMode(RX_EN); + // Disable CRC + NRF24L01_WriteReg(NRF24L01_00_CONFIG, (1 << NRF24L01_00_PWR_UP) | (1 << NRF24L01_00_PRIM_RX) ); + } + else + NRF24L01_SetTxRxMode(TXRX_OFF); +} + +void LT8910_BuildOverhead() +{ + uint8_t pos; + + //Build overhead + //preamble + memset(LT8910_buffer,LT8910_addr[0]&0x01?0xAA:0x55,LT8910_Preamble_Len-1); + pos=LT8910_Preamble_Len-1; + //address + for(uint8_t i=0;i5?5:pos; +} + +void LT8910_SetAddress(uint8_t *address,uint8_t addr_size) +{ + uint8_t addr[5]; + + //Address size (SyncWord) 2 to 8 bytes, 16/32/48/64 bits + LT8910_addr_size=addr_size; + memcpy(LT8910_addr,address,LT8910_addr_size); + + //Build overhead + LT8910_BuildOverhead(); + + //Set NRF RX&TX address based on overhead content + NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, LT8910_buffer_start-2); + for(uint8_t i=0;i>8)&0xFF; + } + //Check len + if(LT8910_Flags&_BV(LT8910_PACKET_LENGTH_EN)) + { + crc=crc16_update(crc,buffer[pos]); + if(bit_reverse(len)!=buffer[pos++]) + return 0; // wrong len... + } + //Decode message + for(i=0;i>8)&0xFF)) return 0; // wrong CRC... + if(buffer[pos]!=(crc&0xFF)) return 0; // wrong CRC... + } + //Everything ok + return 1; +} + +void LT8910_WritePayload(uint8_t* msg, uint8_t len) +{ + unsigned int crc=LT8910_CRC_Initial_Data,a,mask; + uint8_t i, pos=0,tmp, buffer[64], pos_final,shift; + //Add packet len + if(LT8910_Flags&_BV(LT8910_PACKET_LENGTH_EN)) + { + tmp=bit_reverse(len); + buffer[pos++]=tmp; + crc=crc16_update(crc,tmp); + } + //Add payload + for(i=0;i>8; + buffer[pos++]=crc; + } + //Shift everything to fit behind the trailer (4 to 18 bits) + shift=LT8910_buffer_overhead_bits&0x7; + pos_final=LT8910_buffer_overhead_bits/8; + mask=~(0xFF<<(8-shift)); + LT8910_buffer[pos_final+pos]=0xFF; + for(i=pos-1;i!=0xFF;i--) + { + a=buffer[i]<<(8-shift); + LT8910_buffer[pos_final+i]=(LT8910_buffer[pos_final+i]&mask>>8)|a>>8; + LT8910_buffer[pos_final+i+1]=(LT8910_buffer[pos_final+i+1]&mask)|a; + } + if(shift) + pos++; + //Send everything + NRF24L01_WritePayload(LT8910_buffer+LT8910_buffer_start,pos_final+pos-LT8910_buffer_start); +} +// End of LT8910 emulation diff --git a/Multiprotocol/Nrf24l01_bluefly.ino b/Multiprotocol/Nrf24l01_bluefly.ino new file mode 100644 index 0000000..9e7364b --- /dev/null +++ b/Multiprotocol/Nrf24l01_bluefly.ino @@ -0,0 +1,183 @@ +/* + This project is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Deviation is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with Deviation. If not, see . + */ + +#if defined(BlueFly_NRF24L01_INO) +#include "iface_nrf24l01.h" + +#define BIND_BlueFly_COUNT 800 + +#define TXID_BlueFly_SIZE 5 + +#define PAYLOAD_BlueFly_SIZE 12 +// available frequency must be in between 2402 and 2477 +static uint8_t hopping_frequency_start; + +static uint8_t bluefly_binding_adr_rf[TXID_BlueFly_SIZE]={0x32,0xaa,0x45,0x45,0x78}; // fixed binding ids for all planes +// bluefly_rf_adr_buf can be used for fixed id +static uint8_t bluefly_rf_adr_buf[TXID_BlueFly_SIZE]; // ={0x13,0x88,0x46,0x57,0x76}; + +static uint8_t bind_payload[PAYLOAD_BlueFly_SIZE]; + +static unsigned int ch_data_bluefly[8]; + + +static void bluefly_binding_packet(void) +{ + int i; + for (i = 0; i < TXID_BlueFly_SIZE; ++i) + bind_payload[i] = bluefly_rf_adr_buf[i]; + bind_payload[i++] = hopping_frequency_start; + for (; i < PAYLOAD_BlueFly_SIZE; ++i) bind_payload[i] = 0x55; +} + +static void bluefly_init() { + NRF24L01_Initialize(); + + NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable p0 rx + NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknoledgement + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, bluefly_rf_adr_buf, 5); + NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, bluefly_rf_adr_buf, 5); + NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, PAYLOAD_BlueFly_SIZE); // payload size = 12 + NRF24L01_WriteReg(NRF24L01_05_RF_CH, 81); // binding packet must be set in channel 81 + + // 2-bytes CRC, radio on + NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP)); + NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5-byte RX/TX address (byte -2) + NRF24L01_SetBitrate(NRF24L01_BR_250K); // BlueFly - 250kbps + NRF24L01_SetPower(); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit +} + +// HiSky channel sequence: AILE ELEV THRO RUDD GEAR PITCH, channel data value is from 0 to 1000 +static void bluefly_ch_data() { + uint32_t temp; + int i; + for (i = 0; i< 8; ++i) { + temp = (uint32_t)Servo_data[ch[i]] * 300/PPM_MAX + 500; // 200-800 range + if (temp < 0) + ch_data_bluefly[i] = 0; + else if (temp > 1000) + ch_data_bluefly[i] = 1000; + else + ch_data_bluefly[i] = (unsigned int)temp; + + packet[i] = (uint8_t)ch_data_bluefly[i]; + } + + packet[8] = (uint8_t)((ch_data_bluefly[0]>>8)&0x0003); + packet[8] |= (uint8_t)((ch_data_bluefly[1]>>6)&0x000c); + packet[8] |= (uint8_t)((ch_data_bluefly[2]>>4)&0x0030); + packet[8] |= (uint8_t)((ch_data_bluefly[3]>>2)&0x00c0); + + packet[9] = (uint8_t)((ch_data_bluefly[4]>>8)&0x0003); + packet[9] |= (uint8_t)((ch_data_bluefly[5]>>6)&0x000c); + packet[9] |= (uint8_t)((ch_data_bluefly[6]>>4)&0x0030); + packet[9] |= (uint8_t)((ch_data_bluefly[7]>>2)&0x00c0); + + unsigned char l, h, t; + l = h = 0xff; + for (int i=0; i<10; ++i) { + h ^= packet[i]; + h ^= h >> 4; + t = h; + h = l; + l = t; + t = (l<<4) | (l>>4); + h ^= ((t<<2) | (t>>6)) & 0x1f; + h ^= t & 0xf0; + l ^= ((t<<1) | (t>>7)) & 0xe0; + } + // Checksum + packet[10] = h; + packet[11] = l; +} + +static uint16_t bluefly_cb() { + switch(phase++) { + case 0: + bluefly_ch_data(); + break; + case 1: + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, bluefly_rf_adr_buf, 5); + NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency_start + hopping_frequency_no*2); + hopping_frequency_no++; + hopping_frequency_no %= 15; + NRF24L01_FlushTx(); + NRF24L01_WritePayload(packet, PAYLOAD_BlueFly_SIZE); + break; + case 2: + break; + case 3: + if (counter>0) { + counter--; + if (! counter) { BIND_DONE; } + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, bluefly_binding_adr_rf, 5); + NRF24L01_WriteReg(NRF24L01_05_RF_CH, 81); + NRF24L01_FlushTx(); + NRF24L01_WritePayload(bind_payload, PAYLOAD_BlueFly_SIZE); + } + break; + case 4: + break; + case 5: + NRF24L01_SetPower(); + /* FALLTHROUGH */ + default: + phase = 0; + break; + } + return 1000; // send 1 binding packet and 1 data packet per 9ms +} + +// Generate internal id from TX id and manufacturer id (STM32 unique id) +static void initialize_tx_id() { + uint32_t lfsr = 0x7649eca9ul; + + if (Model.fixed_id) { + for (uint8_t i = 0, j = 0; i < sizeof(Model.fixed_id); ++i, j += 8) + rand32_r(&lfsr, (Model.fixed_id >> j) & 0xff); + } + // Pump zero bytes for LFSR to diverge more + for (int i = 0; i < TXID_BlueFly_SIZE; ++i) rand32_r(&lfsr, 0); + + for (uint8_t i = 0; i < TXID_BlueFly_SIZE; ++i) { + bluefly_rf_adr_buf[i] = lfsr & 0xff; + rand32_r(&lfsr, i); + } + + printf("Effective id: %02X%02X%02X%02X%02X\r\n", bluefly_rf_adr_buf[0], bluefly_rf_adr_buf[1], bluefly_rf_adr_buf[2], bluefly_rf_adr_buf[3], bluefly_rf_adr_buf[4]); + + // Use LFSR to seed frequency hopping sequence after another + // divergence round + for (uint8_t i = 0; i < sizeof(lfsr); ++i) rand32_r(&lfsr, 0); + hopping_frequency_start = ((lfsr >> 8) % 47) + 2; + bluefly_binding_packet(); +} + +static uint16_t BlueFly_setup() { + initialize_tx_id(); + + bluefly_init(); + + if(IS_AUTOBIND_FLAG_on) { + counter = BIND_BlueFly_COUNT; +// PROTOCOL_SetBindState(BIND_BlueFly_COUNT * 10); //8 seconds binding time + } else { + counter = 0; + } + + return 1000; +} +#endif diff --git a/Multiprotocol/Nrf24l01_esky150.ino b/Multiprotocol/Nrf24l01_esky150.ino new file mode 100644 index 0000000..b3d9c43 --- /dev/null +++ b/Multiprotocol/Nrf24l01_esky150.ino @@ -0,0 +1,172 @@ +/* + This project is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Deviation is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with Deviation. If not, see . + */ + +#if defined(ESKY150_NRF24L01_INO) +#include "iface_nrf24l01.h" + + +// Timeout for callback in uSec, 4.8ms=4800us for ESky150 +#define ESKY150_PERIOD 4800 +#define ESKY150_CHKTIME 100 // Time to wait for packet to be sent (no ACK, so very short) + +#define esky150_PAYLOADSIZE 15 +#define ADDR_esky150_SIZE 4 + +static uint32_t total_packets; +enum { + ESKY150_INIT2 = 0, + ESKY150_DATA +}; + + +static uint8_t esky150_packet_ack() { + switch (NRF24L01_ReadReg(NRF24L01_07_STATUS) & (BV(NRF24L01_07_TX_DS) | BV(NRF24L01_07_MAX_RT))) { + case BV(NRF24L01_07_TX_DS): return PKT_ACKED; + case BV(NRF24L01_07_MAX_RT): return PKT_TIMEOUT; + } + return PKT_PENDING; +} + +// 2-bytes CRC +#define CRC_CONFIG (BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO)) +static uint16_t esky150_init() { + uint8_t rx_addr[ADDR_esky150_SIZE] = { 0x73, 0x73, 0x74, 0x63 }; + uint8_t tx_addr[ADDR_esky150_SIZE] = { 0x71, 0x0A, 0x31, 0xF4 }; + NRF24L01_Initialize(); + + NRF24L01_WriteReg(NRF24L01_00_CONFIG, CRC_CONFIG); + NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknoledgement + NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 + NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, ADDR_esky150_SIZE-2); // 4-byte RX/TX address + NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0); // Disable retransmit + NRF24L01_SetPower(); + NRF24L01_SetBitrate(NRF24L01_BR_2M); + NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_addr, ADDR_esky150_SIZE); + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, tx_addr, ADDR_esky150_SIZE); + + + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit + NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, esky150_PAYLOADSIZE); // bytes of data payload for pipe 0 + + + NRF24L01_Activate(0x73); + NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 1); // Dynamic payload for data pipe 0 + // Enable: Dynamic Payload Length, Payload with ACK , W_TX_PAYLOAD_NOACK + NRF24L01_WriteReg(NRF24L01_1D_FEATURE, BV(NRF2401_1D_EN_DPL) | BV(NRF2401_1D_EN_ACK_PAY) | BV(NRF2401_1D_EN_DYN_ACK)); + + // Delay 50 ms + return 50000; +} + + +static uint16_t esky150_init2() { + NRF24L01_FlushTx(); + NRF24L01_FlushRx(); + packet_sent = 0; + packet_count = 0; + rf_ch_num = 0; + + // Turn radio power on + NRF24L01_SetTxRxMode(TX_EN); + NRF24L01_WriteReg(NRF24L01_00_CONFIG, CRC_CONFIG | BV(NRF24L01_00_PWR_UP)); + // delayMicroseconds(150); + return 150; +} + + +static void calc_fh_channels(uint32_t seed) { + // Use channels 2..79 + uint8_t first = seed % 37 + 2; + uint8_t second = first + 40; + hopping_frequency[0] = first; // 0x22; + hopping_frequency[1] = second; // 0x4a; +} + + +static uint8_t convert_channel(uint8_t num) { + uint32_t ch = Servo_data[num]; + if (ch < PPM_MIN) { ch = PPM_MIN; } + else if (ch > PPM_MAX) { ch = PPM_MAX; } + return (uint8_t) ((ch * 500 / PPM_MAX) + 1500); +} +static void read_controls(uint8_t* throttle, uint8_t* aileron, uint8_t* elevator, uint8_t* rudder) { + *throttle = convert_channel(THROTTLE); + *aileron = convert_channel(AILERON); + *elevator = convert_channel(ELEVATOR); + *rudder = convert_channel(RUDDER); +} + + +static void esky150_send_packet() { + uint8_t rf_ch = hopping_frequency[rf_ch_num]; + rf_ch_num = 1 - rf_ch_num; + + read_controls(&throttle, &aileron, &elevator, &rudder); + + packet[0] = hopping_frequency[0]; + packet[1] = hopping_frequency[1]; + packet[2] = (throttle >> 8) & 0xFF; + packet[3] = throttle & 0xFF; + packet[4] = (aileron >> 8) & 0xFF; + packet[5] = aileron & 0xFF; + packet[6] = (elevator >> 8) & 0xFF; + packet[7] = elevator & 0xFF; + packet[8] = (rudder >> 8) & 0xFF; + packet[9] = rudder & 0xFF; + // Constant values 00 d8 18 f8 + packet[10] = 0x00; + packet[11] = 0xd8; + packet[12] = 0x18; + packet[13] = 0xf8; + uint8_t sum = 0; + for (int i = 0; i < 14; ++i) sum += packet[i]; + packet[14] = sum; + + packet_sent = 0; + NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_ch); + NRF24L01_FlushTx(); + NRF24L01_WritePayload(packet, sizeof(packet)); + ++total_packets; + packet_sent = 1; +} + +static uint16_t esky150_callback() { + uint16_t timeout = ESKY150_PERIOD; + switch (phase) { + case ESKY150_INIT2: + timeout = esky150_init2(); + phase = ESKY150_DATA; + break; + case ESKY150_DATA: + if (packet_count == 4) + packet_count = 0; + else { + if (packet_sent && esky150_packet_ack() != PKT_ACKED) { + return ESKY150_CHKTIME; + } + esky150_send_packet(); + } + break; + } + return timeout; +} + +static uint16_t esky150_setup() { + total_packets = 0; + uint16_t timeout = esky150_init(); + + return timeout; +} +#endif diff --git a/Multiprotocol/Nrf24l01_fy326.ino b/Multiprotocol/Nrf24l01_fy326.ino index 2c8f943..68234db 100644 --- a/Multiprotocol/Nrf24l01_fy326.ino +++ b/Multiprotocol/Nrf24l01_fy326.ino @@ -75,14 +75,14 @@ static void send_packet(uint8_t bind) | GET_FLAG(CHANNEL_CALIBRATE, 0x01) | GET_FLAG(CHANNEL_EXPERT, 4); } - packet[2] = 200 - scale_channel(AILERON, 0, 200); // aileron - packet[3] = scale_channel(ELEVATOR, 0, 200); // elevator - packet[4] = 200 - scale_channel(RUDDER, 0, 200); // rudder - packet[5] = scale_channel(THROTTLE, 0, 200); // throttle + packet[2] = 200 - scale_channel(AILERON, 0, 200); // aileron 1 + packet[3] = scale_channel(ELEVATOR, 0, 200); // elevator 2 + packet[4] = 200 - scale_channel(RUDDER, 0, 200); // rudder 4 + packet[5] = scale_channel(THROTTLE, 0, 200); // throttle 3 if(sub_protocol == FY319) { - packet[6] = 255 - scale_channel(CHANNEL1, 0, 255); - packet[7] = scale_channel(CHANNEL2, 0, 255); - packet[8] = 255 - scale_channel(CHANNEL4, 0, 255); + packet[6] = 255 - scale_channel(AILERON, 0, 255); + packet[7] = scale_channel(ELEVATOR, 0, 255); + packet[8] = 255 - scale_channel(RUDDER, 0, 255); } else { packet[6] = txid[0]; @@ -112,7 +112,7 @@ static void send_packet(uint8_t bind) static void fy326_init() { - uint8_t rx_tx_addr[] = {0x15, 0x59, 0x23, 0xc6, 0x29}; + uint8_t rx_tx_addr[] = {0x15, 0x59, 0x23, 0xc6, 0x29}; NRF24L01_Initialize(); NRF24L01_SetTxRxMode(TX_EN); @@ -148,7 +148,7 @@ static uint16_t fy326_callback() NRF24L01_WriteReg(NRF24L01_05_RF_CH, RF_BIND_CHANNEL); phase = FY319_BIND1; BIND_IN_PROGRESS; - return PACKET_CHKTIME; + return FY326_CHKTIME; break; case FY319_BIND1: @@ -158,7 +158,7 @@ static uint16_t fy326_callback() packet[0] = txid[3]; packet[1] = 0x80; packet[14]= txid[4]; - bind_counter = BIND_COUNT; + bind_counter = FY326_BIND_COUNT; NRF24L01_SetTxRxMode(TXRX_OFF); NRF24L01_SetTxRxMode(TX_EN); NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); @@ -168,7 +168,7 @@ static uint16_t fy326_callback() packet[i] = rf_chans[0]; phase = FY319_BIND2; } - return PACKET_CHKTIME; + return FY326_CHKTIME; break; case FY319_BIND2: @@ -243,7 +243,7 @@ static void fy_txid() rf_chans[2] = 0x20 + (txid[1] & 0x0F); rf_chans[3] = 0x30 + (txid[1] >> 4); rf_chans[4] = 0x40 + (txid[2] >> 4); - + if(sub_protocol == FY319) { for(uint8_t i=0; i<5; i++) rf_chans[i] = txid[0] & ~0x80; @@ -264,3 +264,4 @@ static uint16_t FY326_setup() return INITIAL_WAIT; } #endif + diff --git a/Multiprotocol/Nrf24l01_hontai.ino b/Multiprotocol/Nrf24l01_hontai.ino new file mode 100644 index 0000000..4408014 --- /dev/null +++ b/Multiprotocol/Nrf24l01_hontai.ino @@ -0,0 +1,272 @@ +/* + This project is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Deviation is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with Deviation. If not, see . + */ + + +#if defined(HonTai_NRF24L01_INO) +#include "iface_nrf24l01.h" + +#define BIND_HT_COUNT 80 +#define PACKET_HT_PERIOD 13500 // Timeout for callback in uSec +//printf inside an interrupt handler is really dangerous +//this shouldn't be enabled even in debug builds without explicitly +//turning it on +#define dbgprintf if(0) printf + +#define INITIAL_HT_WAIT 500 +#define BIND_HT_PACKET_SIZE 10 +#define PACKET_HT_SIZE 12 +#define RF_BIND_HT_CHANNEL 0 + +enum { + FORMAT_HONTAI = 0, + FORMAT_JJRCX1, +}; + + +#define CHANNEL_LED AUX1 +#define CHANNEL_ARM AUX1 // for JJRC X1 +#define CHANNEL_FLIP AUX2 +#define CHANNEL_PICTURE AUX3 +#define CHANNEL_VIDEO AUX4 +#define CHANNEL_HEADLESS AUX5 +#define CHANNEL_RTH AUX6 +#define CHANNEL_CALIBRATE AUX7 + +enum { + HonTai_INIT1 = 0, + HonTai_BIND2, + HonTai_DATA +}; + +static uint8_t ht_txid[5]; + +static uint8_t rf_chan = 0; +static uint8_t rf_channels[][3] = {{0x05, 0x19, 0x28}, // Hontai + {0x0a, 0x1e, 0x2d}}; // JJRC X1 +static uint8_t rx_tx_ht_addr[] = {0xd2, 0xb5, 0x99, 0xb3, 0x4a}; +static uint8_t addr_vals[4][16] = { + {0x24, 0x26, 0x2a, 0x2c, 0x32, 0x34, 0x36, 0x4a, 0x4c, 0x4e, 0x54, 0x56, 0x5a, 0x64, 0x66, 0x6a}, + {0x92, 0x94, 0x96, 0x9a, 0xa4, 0xa6, 0xac, 0xb2, 0xb4, 0xb6, 0xca, 0xcc, 0xd2, 0xd4, 0xd6, 0xda}, + {0x93, 0x95, 0x99, 0x9b, 0xa5, 0xa9, 0xab, 0xad, 0xb3, 0xb5, 0xc9, 0xcb, 0xcd, 0xd3, 0xd5, 0xd9}, + {0x25, 0x29, 0x2b, 0x2d, 0x33, 0x35, 0x49, 0x4b, 0x4d, 0x59, 0x5b, 0x65, 0x69, 0x6b, 0x6d, 0x6e}}; + +// proudly swiped from http://www.drdobbs.com/implementing-the-ccitt-cyclical-redundan/199904926 +#define POLY 0x8408 +static uint16_t crc16(uint8_t *data_p, uint32_t length) +{ + uint8_t i; + uint32_t data; + uint32_t crc; + + crc = 0xffff; + + if (length == 0) return (~crc); + + length -= 2; + do { + for (i = 0, data = (uint8_t)0xff & *data_p++; + i < 8; + i++, data >>= 1) { + if ((crc & 0x0001) ^ (data & 0x0001)) + crc = (crc >> 1) ^ POLY; + else + crc >>= 1; + } + } while (--length); + + crc = ~crc; + data = crc; + crc = (crc << 8) | (data >> 8 & 0xFF); + *data_p++ = crc >> 8; + *data_p = crc & 0xff; + return crc; +} + +#define CHAN_RANGE (PPM_MAX - PPM_MIN) +static uint8_t scale_HT_channel(uint8_t ch, uint8_t start, uint8_t end) +{ + uint32_t range = end - start; + uint32_t chanval = Servo_data[ch]; + + if (chanval < PPM_MIN) chanval = PPM_MIN; + else if (chanval > PPM_MAX) chanval = PPM_MAX; + + uint32_t round = range < 0 ? 0 : CHAN_RANGE / range; // channels round up + if (start < 0) round = CHAN_RANGE / range / 2; // trims zero centered around zero + return (range * (chanval - PPM_MIN + round)) / CHAN_RANGE + start; +} + +#define GET_FLAG(ch, mask) (Servo_data[ch] > 0 ? mask : 0) +static void send_HT_packet(uint8_t bind) +{ + if (bind) { + memcpy(packet, ht_txid, 5); + memset(&packet[5], 0, 3); + } else { + if (sub_protocol == FORMAT_HONTAI) { + packet[0] = 0x0b; + } else { + packet[0] = GET_FLAG(CHANNEL_ARM, 0x02); + } + packet[1] = 0x00; + packet[2] = 0x00; + packet[3] = (scale_HT_channel(THROTTLE, 0, 127) << 1) // throttle + | GET_FLAG(CHANNEL_PICTURE, 0x01); + packet[4] = scale_HT_channel(AILERON, 63, 0); // aileron + if (sub_protocol == FORMAT_HONTAI) { + packet[4] |= GET_FLAG(CHANNEL_RTH, 0x80) + | GET_FLAG(CHANNEL_HEADLESS, 0x40); + } else { + packet[4] |= 0x80; // not sure what this bit does + } + packet[5] = scale_channel(CHANNEL2, 0, 63) // elevator + | GET_FLAG(CHANNEL_CALIBRATE, 0x80) + | GET_FLAG(CHANNEL_FLIP, 0x40); + packet[6] = scale_HT_channel(RUDDER, 0, 63) // rudder + | GET_FLAG(CHANNEL_VIDEO, 0x80); + packet[7] = scale_HT_channel(AILERON, -16, 16); // aileron trim + if (sub_protocol == FORMAT_HONTAI) { + packet[8] = scale_HT_channel(RUDDER, -16, 16); // rudder trim + } else { + packet[8] = 0xc0 // always in expert mode + | GET_FLAG(CHANNEL_RTH, 0x02) + | GET_FLAG(CHANNEL_HEADLESS, 0x01); + } + packet[9] = scale_HT_channel(ELEVATOR, -16, 16); // elevator trim + } + crc16(packet, bind ? BIND_HT_PACKET_SIZE : PACKET_HT_SIZE); + + // Power on, TX mode, 2byte CRC + if (sub_protocol == FORMAT_HONTAI) { + XN297_Configure(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP)); + } else { + NRF24L01_SetTxRxMode(TX_EN); + } + + NRF24L01_WriteReg(NRF24L01_05_RF_CH, bind ? RF_BIND_HT_CHANNEL : rf_channels[sub_protocol][rf_chan++]); + rf_chan %= sizeof(rf_channels); + + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); + NRF24L01_FlushTx(); + + if (sub_protocol == FORMAT_HONTAI) { + XN297_WritePayload(packet, bind ? BIND_HT_PACKET_SIZE : PACKET_HT_SIZE); + } else { + NRF24L01_WritePayload(packet, bind ? BIND_HT_PACKET_SIZE : PACKET_HT_SIZE); + } + + NRF24L01_SetPower(); +} + +static void ht_init() +{ + NRF24L01_Initialize(); + + NRF24L01_SetTxRxMode(TX_EN); + + // SPI trace of stock TX has these writes to registers that don't appear in + // nRF24L01 or Beken 2421 datasheets. Uncomment if you have an XN297 chip? + // NRF24L01_WriteRegisterMulti(0x3f, "\x4c\x84\x67,\x9c,\x20", 5); + // NRF24L01_WriteRegisterMulti(0x3e, "\xc9\x9a\xb0,\x61,\xbb,\xab,\x9c", 7); + // NRF24L01_WriteRegisterMulti(0x39, "\x0b\xdf\xc4,\xa7,\x03,\xab,\x9c", 7); + + if (sub_protocol == FORMAT_HONTAI) { + XN297_SetTXAddr(rx_tx_ht_addr, sizeof(rx_tx_ht_addr)); + } else { + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_ht_addr, sizeof(rx_tx_ht_addr)); + } + + NRF24L01_FlushTx(); + NRF24L01_FlushRx(); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit + NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowldgement on all data pipes + NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps + NRF24L01_SetPower(); + NRF24L01_Activate(0x73); // Activate feature register + if (sub_protocol == FORMAT_HONTAI) { + NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x00); // no retransmits + NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x00); // Disable dynamic payload length on all pipes + NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x00); + NRF24L01_Activate(0x73); // Deactivate feature register + } else { + NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0xff); // JJRC uses dynamic payload length + NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x3f); // match other stock settings even though AA disabled... + NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x07); + } +} + +static void ht_init2() +{ + uint8_t data_tx_addr[] = {0x2a, 0xda, 0xa5, 0x25, 0x24}; + + data_tx_addr[0] = addr_vals[0][ ht_txid[3] & 0x0f]; + data_tx_addr[1] = addr_vals[1][(ht_txid[3] >> 4) & 0x0f]; + data_tx_addr[2] = addr_vals[2][ ht_txid[4] & 0x0f]; + data_tx_addr[3] = addr_vals[3][(ht_txid[4] >> 4) & 0x0f]; + + if (sub_protocol == FORMAT_HONTAI) { + XN297_SetTXAddr(data_tx_addr, sizeof(data_tx_addr)); + } else { + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, data_tx_addr, sizeof(data_tx_addr)); + } +} + +static uint16_t ht_callback() +{ + switch (phase) { + case HonTai_INIT1: + phase = HonTai_BIND2; + break; + case HonTai_BIND2: + if (counter == 0) { + ht_init2(); + phase = HonTai_DATA; + BIND_DONE; + } else { + send_HT_packet(1); + counter -= 1; + } + break; + + case HonTai_DATA: + send_HT_packet(0); + break; + } + return PACKET_HT_PERIOD; +} + +static uint16_t ht_setup() +{ + counter = BIND_HT_COUNT; + + if (sub_protocol == FORMAT_HONTAI) { + ht_txid[0] = 0x4c; // first three bytes some kind of model id? - set same as stock tx + ht_txid[1] = 0x4b; + ht_txid[2] = 0x3a; + } else { + ht_txid[0] = 0x4b; // JJRC X1 + ht_txid[1] = 0x59; + ht_txid[2] = 0x3a; + } + ht_txid[3] = (MProtocol_id >> 8 ) & 0xff; + ht_txid[4] = MProtocol_id & 0xff; + + ht_init(); + phase = HonTai_INIT1; + + return INITIAL_HT_WAIT; +} +#endif + diff --git a/Multiprotocol/Nrf24l01_ne260.ino b/Multiprotocol/Nrf24l01_ne260.ino new file mode 100644 index 0000000..32b5345 --- /dev/null +++ b/Multiprotocol/Nrf24l01_ne260.ino @@ -0,0 +1,274 @@ +/* + This project is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Deviation is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with Deviation. If not, see . + */ +/* This code is based upon code from: + http://www.rcgroups.com/forums/showthread.php?t=1564343 + Author : Ferenc Szili (kile at the rcgroups.net forum) +*/ + + +#if defined(NE260_NRF24L01_INO) +#include "iface_nrf24l01.h" + +//////////////////////////////////////////////////////////// +/////////////////////// +// register bits +/////////////////////// + +// CONFIG +#define MASK_RX_DR 6 +#define MASK_TX_DS 5 +#define MASK_MAX_RT 4 +#define EN_CRC 3 +#define CRCO 2 +#define PWR_UP 1 +#define PRIM_RX 0 + +// EN_AA +#define ENAA_P5 5 +#define ENAA_P4 4 +#define ENAA_P3 3 +#define ENAA_P2 2 +#define ENAA_P1 1 +#define ENAA_P0 0 + +// EN_RXADDR +#define ERX_P5 5 +#define ERX_P4 4 +#define ERX_P3 3 +#define ERX_P2 2 +#define ERX_P1 1 +#define ERX_P0 0 + +// RF_SETUP +#define CONT_WAVE 7 +#define RF_DR_LOW 5 +#define PLL_LOCK 4 +#define RF_DR_HIGH 3 +#define RF_PWR_HIGH 2 +#define RF_PWR_LOW 1 +#define LNA_HCURR 0 // obsolete in nRF24L01+ + +// STATUS +#define RX_DR 6 +#define TX_DS 5 +#define MAX_RT 4 +#define TX_FULL 0 + +// FIFO_STATUS +#define TX_REUSE 6 +#define FIFO_TX_FULL 5 +#define TX_EMPTY 4 +#define RX_FULL 1 +#define RX_EMPTY 0 + +/////////////////////// +// register bit values +/////////////////////// + +// CONFIG +#define vMASK_RX_DR (1<<(MASK_RX_DR)) +#define vMASK_TX_DS (1<<(MASK_TX_DS)) +#define vMASK_MAX_RT (1<<(MASK_MAX_RT)) +#define vEN_CRC (1<<(EN_CRC)) +#define vCRCO (1<<(CRCO)) +#define vPWR_UP (1<<(PWR_UP)) +#define vPRIM_RX (1<<(PRIM_RX)) + +// EN_AA +#define vENAA_P5 (1<<(ENAA_P5)) +#define vENAA_P4 (1<<(ENAA_P4)) +#define vENAA_P3 (1<<(ENAA_P3)) +#define vENAA_P2 (1<<(ENAA_P2)) +#define vENAA_P1 (1<<(ENAA_P1)) +#define vENAA_P0 (1<<(ENAA_P0)) + +// EN_RXADDR +#define vERX_P5 (1<<(ERX_P5)) +#define vERX_P4 (1<<(ERX_P4)) +#define vERX_P3 (1<<(ERX_P3)) +#define vERX_P2 (1<<(ERX_P2)) +#define vERX_P1 (1<<(ERX_P1)) +#define vERX_P0 (1<<(ERX_P0)) + +// SETUP_AW -- address widths in bytes +#define vAW_3 1 +#define vAW_4 2 +#define vAW_5 3 + +// RF_SETUP +#define vCONT_WAVE (1<<(CONT_WAVE)) +#define vRF_DR_LOW (1<<(RF_DR_LOW)) +#define vPLL_LOCK (1<<(PLL_LOCK)) +#define vRF_DR_HIGH (1<<(RF_DR_HIGH)) +#define vRF_PWR_HIGH (1<<(RF_PWR_HIGH)) +#define vRF_PWR_LOW (1<<(RF_PWR_LOW)) +#define vLNA_HCURR (1<<(LNA_HCURR)) // obsolete in nRF24L01+ + +#define vRF_DR_1MBPS 0 +#define vRF_DR_2MBPS (1<<(RF_DR_HIGH)) +#define vRF_DR_250KBPS (1<<(RF_DR_LOW)) + +#define vRF_PWR_M18DBM 0x00 +#define vRF_PWR_M12DBM 0x02 +#define vRF_PWR_M6DBM 0x04 +#define vRF_PWR_0DBM 0x06 + +#define vARD_250us 0x00 +#define vARD_500us 0x10 +#define vARD_750us 0x20 +#define vARD_1000us 0x30 +#define vARD_1250us 0x40 +#define vARD_1500us 0x50 +#define vARD_1750us 0x60 +#define vARD_2000us 0x70 +#define vARD_2250us 0x80 +#define vARD_2500us 0x90 +#define vARD_2750us 0xA0 +#define vARD_3000us 0xB0 +#define vARD_3250us 0xC0 +#define vARD_3500us 0xD0 +#define vARD_3750us 0xE0 +#define vARD_4000us 0xF0 + +// STATUS +#define vRX_DR (1<<(RX_DR)) +#define vTX_DS (1<<(TX_DS)) +#define vMAX_RT (1<<(MAX_RT)) +#define vTX_FULL (1<<(TX_FULL)) + +#define RX_P_NO(stat) ((stat >> 1) & 7) +#define HAS_RX_PAYLOAD(stat) ((stat & 0b1110) < 0b1100) + +// FIFO_STATUS +#define vTX_REUSE (1<<(TX_REUSE)) +#define vTX_FULL (1<<(TX_FULL)) +#define vTX_EMPTY (1<<(TX_EMPTY)) +#define vRX_FULL (1<<(RX_FULL)) +#define vRX_EMPTY (1<<(RX_EMPTY)) +//////////////////////////////////////////////////////////// +uint8_t neChannel = 10; +uint8_t neChannelOffset = 0; +#define PACKET_NE_LENGTH 7 + +static u32 bind_count; +static uint16_t model_id = 0xA04A; + +uint8_t NE_ch[]={THROTTLE, RUDDER, ELEVATOR, AILERON, AUX1}; +uint8_t NEAddr[] = {0x34, 0x43, 0x10, 0x10, 0x01}; +enum { + NE260_BINDTX, + NE260_BINDRX, + NE260_DATA1, + NE260_DATA2, + NE260_DATA3, +}; + + +static void ne260_init() { + NRF24L01_Initialize(); + + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, NEAddr, 5); // write the address + NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, NEAddr, 5); + + NRF24L01_WriteReg(NRF24L01_01_EN_AA, vENAA_P0); // enable auto acknoledge + NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, vARD_500us); // ARD=500us, ARC=disabled + NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, vRF_DR_250KBPS | vLNA_HCURR | vRF_PWR_0DBM); // data rate, output power and noise cancel + NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, PACKET_NE_LENGTH); // RX payload length + NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, vERX_P0); // enable RX address + NRF24L01_WriteReg(NRF24L01_07_STATUS, vRX_DR | vTX_DS | vMAX_RT); // reset the IRQ flags +} + +static void send_data_packet() { + for(int i = 0; i < 4; i++) { + uint32_t value = (uint32_t)Servo_data[NE_ch[i]] * 0x40 / PPM_MAX + 0x40; + if (value > 0x7f) + value = 0x7f; + else if(value < 0) + value = 0; + packet[i] = value; + } + packet[4] = 0x55; + packet[5] = model_id & 0xff; + packet[6] = (model_id >> 8) & 0xff; + + NRF24L01_FlushTx(); + NRF24L01_WriteReg(NRF24L01_07_STATUS, vMAX_RT); + NRF24L01_WriteReg(NRF24L01_05_RF_CH, neChannel + neChannelOffset); + NRF24L01_WriteReg(NRF24L01_00_CONFIG, vEN_CRC | vCRCO | vPWR_UP); + // send a fresh packet to the nRF + NRF24L01_WritePayload((uint8_t*) packet, PACKET_NE_LENGTH); +} + +static void send_bind_packet() { + packet[0] = 0xAA; //throttle + packet[1] = 0xAA; //rudder + packet[2] = 0xAA; //elevator + packet[3] = 0xAA; //aileron + packet[4] = 0xAA; //command + packet[5] = model_id & 0xff; + packet[6] = (model_id >> 8) & 0xff; + + NRF24L01_WriteReg(NRF24L01_07_STATUS, vRX_DR | vTX_DS | vMAX_RT); // reset the status flags + NRF24L01_WriteReg(NRF24L01_05_RF_CH, neChannel + neChannelOffset); + NRF24L01_FlushTx(); + NRF24L01_WritePayload((uint8_t*) &packet, PACKET_NE_LENGTH); // send the bind packet +} + +static uint16_t ne260_cb() { + if (state == NE260_BINDTX) { + // do we have a packet? + if ((NRF24L01_ReadReg(NRF24L01_07_STATUS) & vRX_DR) != 0) { + // read the packet contents + NRF24L01_ReadPayload(packet, PACKET_NE_LENGTH); + + // is this the bind response packet? + if (strncmp("\x55\x55\x55\x55\x55", (char*) (packet + 1), 5) == 0 && *((uint16_t*)(packet + 6)) == model_id) { + // exit the bind loop + state = NE260_DATA1; + NRF24L01_FlushTx(); + NRF24L01_FlushRx(); + NRF24L01_SetTxRxMode(TX_EN); + return 2000; + } + } + NRF24L01_SetTxRxMode(TX_EN); + send_bind_packet(); + state = NE260_BINDRX; + return 500; + } else if (state == NE260_BINDRX) { + // switch to RX mode + while (!(NRF24L01_ReadReg(NRF24L01_07_STATUS) & (vMAX_RT | vTX_DS))) ; + NRF24L01_WriteReg(NRF24L01_07_STATUS, vTX_DS); + + NRF24L01_SetTxRxMode(RX_EN); + NRF24L01_FlushRx(); + state = NE260_BINDTX; + return 2000; + } + else if (state == NE260_DATA1) { neChannel = 10; state = NE260_DATA2; } + else if (state == NE260_DATA2) { neChannel = 30; state = NE260_DATA3; } + else if (state == NE260_DATA3) { neChannel = 50; state = NE260_DATA1; } + send_data_packet(); + return 2500; +} + +static uint16_t NE260_setup() { + ne260_init(); + bind_count = 10000; + state = NE260_BINDTX; + + return 10000; +} +#endif diff --git a/Multiprotocol/Nrf24l01_udi.ino b/Multiprotocol/Nrf24l01_udi.ino new file mode 100644 index 0000000..ab8afa8 --- /dev/null +++ b/Multiprotocol/Nrf24l01_udi.ino @@ -0,0 +1,583 @@ +/* + This project is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Deviation is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with Deviation. If not, see . + */ + +// Known UDI 2.4GHz protocol variants, all using BK2421 +// * UDI U819 coaxial 3ch helicoper +// * UDI U816/817/818 quadcopters +// - "V1" with orange LED on TX, U816 RX labeled '' , U817/U818 RX labeled 'UD-U817B' +// - "V2" with red LEDs on TX, U816 RX labeled '', U817/U818 RX labeled 'UD-U817OG' +// - "V3" with green LEDs on TX. Did not get my hands on yet. +// * U830 mini quadcopter with tilt steering ("Protocol 2014") +// * U839 nano quadcopter ("Protocol 2014") + +#if defined(UDI_NRF24L01_INO) +#include "iface_nrf24l01.h" + +#define BIND_UDI_COUNT 1000 + +// Timeout for callback in uSec, 4ms=4000us for UDI +// ??? +//#define PACKET_UDI_PERIOD 4000 + +#define BIND_PACKET_UDI_PERIOD 5000 +#define PACKET_UDI_PERIOD 15000 + +#define BIND_PACKETS_UDI_PER_CHANNEL 11 +#define PACKETS_UDI_PER_CHANNEL 11 + +#define NUM_UDI_RF_CHANNELS 16 + + +#define INITIAL_UDI_WAIT 50000 + +#define PACKET_UDI_CHKTIME 100 + +// For readability +enum { + UDI_CAMERA = 1, + UDI_VIDEO = 2, + UDI_MODE2 = 4, + UDI_FLIP360 = 8, + UDI_FLIP =16, + UDI_LIGHTS =32 +}; + +// This is maximum payload size used in UDI protocols +#define UDI_PAYLOADSIZE 16 + + + +static uint8_t payload_size; // Bytes in payload for selected variant +static uint8_t bind_channel; +static uint8_t packets_to_hop; +static uint8_t packets_to_check; // BIND_RX phase needs to receive/auto-ack more than one packet for RX to switch to next phase, it seems +static uint8_t packets_to_send; // Number of packets to send / check for in current bind phase +static uint8_t bind_step_success; // Indicates successfull transmission / receive of bind reply during current bind phase +static uint8_t tx_id[3]; +static uint8_t rx_id[3]; +static uint8_t randoms[3]; // 3 random bytes choosen by TX, sent in BIND packets. Lower nibble of first byte sets index in RF CH table to use for BIND2 + + +// +enum { + UDI_INIT2 = 0, + UDI_INIT2_NO_BIND, + UDI_BIND1_TX, + UDI_BIND1_RX, + UDI_BIND2_TX, + UDI_BIND2_RX, + UDI_DATA +}; + +enum { + PROTOOPTS_FORMAT = 0, + PROTOOPTS_STARTBIND, +}; +enum { + STARTBIND_NO = 0, + STARTBIND_YES = 1, +}; + +// This are frequency hopping tables for UDI protocols + +// uint8_t16 V1 (Orange LED) Bind CH 0x07 +// TX ID 0x57, 0x5A, 0x2D +static const uint8_t freq_hopping_uint8_t16_v1[NUM_UDI_RF_CHANNELS] = { + 0x07, 0x21, 0x49, 0x0B, 0x39, 0x10, 0x25, 0x42, + 0x1D, 0x31, 0x35, 0x14, 0x28, 0x3D, 0x18, 0x2D +}; + +// Protocol 2014 (uint8_t30,uint8_t39,...) BIND CH 0x23 (second entry) +// DATA: hops ~ every 0.361s (0.350 ... 0.372) +static const uint8_t freq_hopping_uint8_t39[NUM_UDI_RF_CHANNELS] = { + 0x08, 0x23, 0x48, 0x0D, 0x3B, 0x12, 0x27, 0x44, + 0x1F, 0x33, 0x37, 0x16, 0x2A, 0x3F, 0x1A, 0x2F +}; + +// Points to proper table +static const uint8_t * rf_udi_channels = NULL; + + +static uint8_t packet_udi_ack() +{ + switch (NRF24L01_ReadReg(NRF24L01_07_STATUS) & (BV(NRF24L01_07_TX_DS) | BV(NRF24L01_07_MAX_RT))) { + case BV(NRF24L01_07_TX_DS): return PKT_ACKED; + case BV(NRF24L01_07_MAX_RT): return PKT_TIMEOUT; + } + return PKT_PENDING; +} + +static void UDI_init() +{ + NRF24L01_Initialize(); + //NRF24L01_SetTxRxMode(TX_EN); + + switch (sub_protocol) { + case U816_V1: + rf_udi_channels = freq_hopping_uint8_t16_v1; + payload_size = 8; + break; + + case U816_V2: + rf_udi_channels = NULL; // NO HOPPING ! + payload_size = 7; + break; + + case U839_2014: + // UDI 2014 Protocol (uint8_t30, uint8_t39, all other new products ?) + rf_udi_channels = freq_hopping_uint8_t39; + payload_size = 8; + break; + } + + NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, payload_size); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x07); // Clear status bits + + if ((sub_protocol == U816_V1) || (sub_protocol == U816_V2)) { + NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, 0x27); // + NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x3A); // + NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x01); // 3 byte address + NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 + NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x3F); // Auto-acknowledge on all data pipers, same as YD + if (sub_protocol == U816_V1) { + NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x7F); // + } else { + NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x7A); // + } + } else + if (sub_protocol == U839_2014) { + NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, 0x0F); // 2Mbps air rate, 5dBm RF output power, high LNA gain + NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x1A); // 500uS retransmit t/o, 10 tries (same as YD) + NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x01); // 3 byte address + NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 + NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x3F); // Auto-acknowledge on all data pipers, same as YD + NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x0F); // Enable CRC, 2 byte CRC, PWR UP, PRIMARY RX + } + + NRF24L01_FlushTx(); + NRF24L01_FlushRx(); + uint8_t status = NRF24L01_ReadReg(NRF24L01_07_STATUS); + NRF24L01_WriteReg(NRF24L01_07_STATUS, status); + + status = NRF24L01_ReadReg(NRF24L01_07_STATUS); + NRF24L01_FlushTx(); + status = NRF24L01_ReadReg(NRF24L01_07_STATUS); + NRF24L01_WriteReg(NRF24L01_07_STATUS, status); + + // Implicit delay in callback + // delayMicroseconds(120) +} + +static void UDI_init2() +{ + NRF24L01_FlushTx(); + bind_step_success = 0; + packet_sent = 0; + + switch (sub_protocol) { + case U816_V1: + rf_ch_num = 0; + bind_channel = rf_udi_channels[rf_ch_num++]; + break; + case U816_V2: + rf_ch_num = 0x07; // This is actual channel. No hopping here + bind_channel = 0; + break; + case U839_2014: + rf_ch_num = 1; + bind_channel = rf_udi_channels[rf_ch_num++]; + break; + } + NRF24L01_WriteReg(NRF24L01_05_RF_CH, bind_channel); + + NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, (uint8_t *) "\xe7\x7e\xe7", 3); + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t *) "\xe7\x7e\xe7", 3); + + // Turn radio power on + NRF24L01_SetTxRxMode(TX_EN); + uint8_t config = BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP); + NRF24L01_WriteReg(NRF24L01_00_CONFIG, config); + // Implicit delay in callback + // delayMicroseconds(150); +} + +static void set_tx_id(uint32_t id) +{ + tx_id[0] = (id >> 16) & 0xFF; + tx_id[1] = (id >> 8) & 0xFF; + tx_id[2] = (id >> 0) & 0xFF; + +/* + uint32_t val = rand32(); randoms[0] = val & 0xff; randoms[1] = (val >> 8 ) & 0xff; randoms[2] = (val >> 16 ) & 0xff; +*/ + // FIXME + // This one has been observed, leads to RF CH 0x1F (#08) used for BIND2 + randoms[0] = 0x98; randoms[1] = 0x80; randoms[2] = 0x5B; +} + +static void add_pkt_checksum() +{ + // CHECKSUM was introduced with 2014 protocol + if (sub_protocol < U839_2014) return; + uint8_t sum = 0; + for (uint8_t i = 0; i < payload_size-1; ++i) sum += packet[i]; + packet[payload_size-1] = sum & 0x3f; // *sick* +} + + +static uint8_t convert_channel(uint8_t num, uint8_t chn_max, uint8_t sign_ofs) +{ + uint32_t ch = Servo_data[num]; + if (ch < PPM_MIN) { + ch = PPM_MIN; + } else if (ch > PPM_MAX) { + ch = PPM_MAX; + } + uint32_t chn_val; + if (sign_ofs) chn_val = (((ch * chn_max / PPM_MAX) + sign_ofs) >> 1); + else chn_val = (ch * chn_max / PPM_MAX); + if (chn_val < 0) chn_val = 0; + else if (chn_val > chn_max) chn_val = chn_max; + return (uint8_t) chn_val; +} + + +static void read_controls(uint8_t* throttle, uint8_t* rudder, uint8_t* elevator, uint8_t* aileron, + uint8_t* flags) +{ + // Protocol is registered AETRG, that is + // Aileron is channel 0, Elevator - 1, Throttle - 2, Rudder - 3 + // Sometimes due to imperfect calibration or mixer settings + // throttle can be less than PPM_MIN or larger than + // PPM_MAX. As we have no space here, we hard-limit + // channels values by min..max range + + // Channel 3: throttle is 0-100 + *throttle = convert_channel(THROTTLE, 0x64, 0); + + // Channel 4 + *rudder = convert_channel(RUDDER, 0x3f, 0x20); + + // Channel 2 + *elevator = convert_channel(ELEVATOR, 0x3f, 0x20); + + // Channel 1 + *aileron = convert_channel(AILERON, 0x3f, 0x20); + + // Channel 5 + if (Servo_data[AUX1] <= 0) *flags &= ~UDI_FLIP360; + else *flags |= UDI_FLIP360; + + // Channel 6 + if (Servo_data[AUX2] <= 0) *flags &= ~UDI_FLIP; + else *flags |= UDI_FLIP; + + // Channel 7 + if (Servo_data[AUX3] <= 0) *flags &= ~UDI_CAMERA; + else *flags |= UDI_CAMERA; + + // Channel 8 + if (Servo_data[AUX4] <= 0) *flags &= ~UDI_VIDEO; + else *flags |= UDI_VIDEO; + + // Channel 9 + if (Servo_data[AUX5] <= 0) *flags &= ~UDI_LIGHTS; + else *flags |= UDI_LIGHTS; + + // Channel 10 + if (Servo_data[AUX6] <= 0) *flags &= ~UDI_MODE2; + else *flags |= UDI_MODE2; +} + +static void send_udi_packet(uint8_t bind) +{ + packet[7] = 0x4A; + if (bind == 1) { + // Bind phase 1 + // MAGIC + packet[0] = 0x5A; // NOTE: Also 0xF3, when RX does not ACK packets (uint8_t39, only TX on) ... + // Current Address / TX ID + if (sub_protocol == U839_2014) { + // uint8_t39: Current RX/TX Addr + packet[1] = 0xE7; + packet[2] = 0x7E; + packet[3] = 0xE7; + } else { + // uint8_t16: ID Fixed per TX + packet[1] = tx_id[0]; + packet[2] = tx_id[1]; + packet[3] = tx_id[2]; + } + // Pseudo random values (lower nibble of packet[4] determines index of RF CH used in BIND2) + packet[4] = randoms[0]; + packet[5] = randoms[1]; + packet[6] = randoms[2]; + if (sub_protocol == U839_2014) { + packet[7] = (packet_counter < 4) ? 0x3f : 0x04; // first four packets use 0x3f here, then 0x04 + } + } else if (bind == 2) { + // Bind phase 2 + // MAGIC + packet[0] = 0xAA; + // Current Address (RX "ID", pseudorandom again) + packet[1] = rx_id[0]; + packet[2] = rx_id[1]; + packet[3] = rx_id[2]; + // Pseudo random values + packet[4] = randoms[0]; + packet[5] = randoms[1]; + packet[6] = randoms[2]; + if (sub_protocol == U839_2014) { + packet[7] = 0x04; + } + } else { + // regular packet + // Read channels (converts to required ranges) + read_controls(&throttle, &rudder, &elevator, &aileron, &flags); + // MAGIC + packet[0] = 0x55; + packet[1] = throttle; // throttle is 0-0x64 + // 3 Channels packed into 2 bytes (5bit per channel) + uint16_t encoded = (rudder << 11) | (elevator << 6) | (aileron << 1); + packet[2] = (encoded >> 8) & 0xff; + packet[3] = encoded & 0xff; + // Trims and flags (0x20 = center) + packet[4] = 0x20; // rudder trim 6bit + packet[5] = 0x20; // elev trim 6bit + packet[6] = 0x20; // ail trim 6bit + + if (flags & UDI_FLIP) packet[4] |= 0x80; // "Directional" flip + if (flags & UDI_LIGHTS) packet[4] |= 0x40; // Light on/off + + if (flags & UDI_MODE2) packet[5] |= 0x80; // High rate ("Mode2") + if (flags & UDI_FLIP360) packet[5] |= 0x40; // 360 degree flip + + if (flags & UDI_VIDEO) packet[6] |= 0x80; // Video recording on/off + if (flags & UDI_CAMERA) packet[6] |= 0x40; // Take picture + + // NOTE: Only newer protocols have this (handled by routine) + add_pkt_checksum(); + } + + uint8_t status = NRF24L01_ReadReg(NRF24L01_07_STATUS); + NRF24L01_WriteReg(NRF24L01_07_STATUS,status); + + if (packet_sent && bind && (status & BV(NRF24L01_07_TX_DS))) { + bind_step_success = 1; + } + + packet_sent = 0; + + // Check if its time to change channel + // This seems to be done by measuring time, + // not by counting packets, on UDI transmitters + // NOTE: Seems even in bind phase channels are changed + + // NOTE: Only hop in TX mode ??? + if (rf_udi_channels && (bind == 0) && (packets_to_hop-- == 0)) { + uint8_t rf_ch = rf_udi_channels[rf_ch_num]; + rf_ch_num++; + rf_ch_num %= NUM_UDI_RF_CHANNELS; + NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_ch); + + packets_to_hop = bind ? BIND_PACKETS_UDI_PER_CHANNEL : PACKETS_UDI_PER_CHANNEL; + } + NRF24L01_FlushTx(); + NRF24L01_WritePayload(packet, payload_size); + ++packet_counter; + packet_sent = 1; +} + + +static uint16_t UDI_callback() { + switch (phase) { + case UDI_INIT2: + UDI_init2(); + phase = UDI_BIND1_TX; + return 120; + break; + case UDI_INIT2_NO_BIND: + // Do nothing (stay forever) + // Cannot re-bind on UDI protocol since IDs are random + return 10000; // 10ms + break; + case UDI_BIND1_TX: + if (packet_sent && packet_udi_ack() == PKT_ACKED) { bind_step_success = 1; } + if (bind_step_success) { + // All fine, wait for reply of receiver + phase = UDI_BIND1_RX; + + NRF24L01_SetTxRxMode(RX_EN); + NRF24L01_FlushRx(); + + NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x0F); + bind_step_success = 0; + //packets_to_check = 12; // according to SPI traces on uint8_t17B RX it receives 12 packets (and answers with 5) + packets_to_check = 3; + } else { + send_udi_packet(1); + } + return BIND_PACKET_UDI_PERIOD; + break; + case UDI_BIND1_RX: + // Check if data has been received + if (NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_RX_DR) ) { + uint8_t data[UDI_PAYLOADSIZE]; + NRF24L01_ReadPayload(data, payload_size); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x4E); // On original TX this is done on LAST packet check only ! + NRF24L01_FlushRx(); + + // Verify MAGIC and Random ID + // (may be reply to bind packet from other TX) + if ((data[0] == 0xA5) && + (data[4] == randoms[0]) && + (data[5] == randoms[1]) && + (data[6] == randoms[2]) && + (data[7] == randoms[2])) { + rx_id[0] = data[1]; + rx_id[1] = data[2]; + rx_id[2] = data[3]; + if (sub_protocol != U816_V2) { + rf_ch_num = randoms[0] & 0x0f; + } + bind_step_success = 1; + } + } + // RX seems to need more than one ACK + if (packets_to_check) packets_to_check--; + //NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x0F); + if (bind_step_success && !packets_to_check) { + // All fine, switch address and RF channel, + // send bind packets with channel hopping now + phase = UDI_BIND2_TX; + + packet_sent = 0; + packets_to_send = 4; + bind_step_success = 0; + + NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_id, 3); + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_id, 3); + + if (sub_protocol != U816_V2) { + // Switch RF channel + NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_udi_channels[rf_ch_num++]); + rf_ch_num %= NUM_UDI_RF_CHANNELS; + } + + NRF24L01_FlushTx(); + NRF24L01_FlushRx(); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x7E); + + NRF24L01_SetTxRxMode(TX_EN); + //NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x0E) + + return 10; // 10 µs (start sending immediately) + } + return BIND_PACKET_UDI_PERIOD; + break; + + case UDI_BIND2_TX: + if (packet_sent && packet_udi_ack() == PKT_ACKED) { + bind_step_success = 1; + } + send_udi_packet(2); + if (packets_to_send) --packets_to_send; + if (bind_step_success || !packets_to_send) { + // Seems the original TX ignores AACK, too ! + // U816 V1: 3 packets send, U839: 4 packets send + // All fine, wait for reply of receiver + phase = UDI_BIND2_RX; + + NRF24L01_SetTxRxMode(RX_EN); + NRF24L01_FlushRx(); + + NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x0F); + bind_step_success = 0; + packets_to_check = 14; // ??? + } + return bind_step_success ? 4000 : 12000; // 4ms if no packed acked yet, 12ms afterwards + // return 120; // FIXME: Varies for first three packets !!! + + break; + + case UDI_BIND2_RX: + // Check if data has been received + if (NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_RX_DR) ) { + uint8_t data[UDI_PAYLOADSIZE]; + NRF24L01_ReadPayload(data, payload_size); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x4E); + NRF24L01_FlushRx(); + + // Verify MAGIC, RX Addr, Random ID + // (may be reply to bind packet from other TX) + if ((data[0] == 0xDD) && + (data[1] == rx_id[0]) && + (data[2] == rx_id[1]) && + (data[3] == rx_id[2]) && + (data[4] == randoms[0]) && + (data[5] == randoms[1]) && + (data[6] == randoms[2]) && + (data[7] == randoms[2])) { + bind_step_success = 1; + } + } + // RX seems to need more than one ACK + if (packets_to_check) packets_to_check--; + //NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x0F); + if (bind_step_success && !packets_to_check) { + phase = UDI_DATA; + NRF24L01_SetTxRxMode(TX_EN); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x7E); + NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x0E); + NRF24L01_FlushTx(); + + // Switch RF channel + if (sub_protocol == U816_V2) { + // FIXED RF Channel + NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_ch_num); + } else { + NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_udi_channels[rf_ch_num++]); + rf_ch_num %= NUM_UDI_RF_CHANNELS; + } + + flags = 0; + BIND_DONE; + } + return BIND_PACKET_UDI_PERIOD; + break; + case UDI_DATA: + if (packet_sent && packet_udi_ack() != PKT_ACKED) { + return PACKET_UDI_CHKTIME; + } + send_udi_packet(0); + break; + } + // Packet every 15ms + return PACKET_UDI_PERIOD; +} + +static uint16_t UDI_setup() +{ + packet_counter = 0; + UDI_init(); + phase = UDI_INIT2; + counter = BIND_UDI_COUNT; + + // observed on U839 TX + set_tx_id(0x457C27); + + return INITIAL_UDI_WAIT; +} +#endif diff --git a/Multiprotocol/SHENQI_nrf24l01.ino b/Multiprotocol/SHENQI_nrf24l01.ino new file mode 100644 index 0000000..18d5037 --- /dev/null +++ b/Multiprotocol/SHENQI_nrf24l01.ino @@ -0,0 +1,108 @@ +#if defined(SHENQI_NRF24L01_INO) + +#include "iface_nrf24l01.h" + +const uint8_t PROGMEM SHENQI_Freq[] = { + 50,50,20,60,30,40, + 10,30,40,20,60,10, + 50,20,50,40,10,60, + 30,30,60,10,40,50, + 20,10,60,20,50,30, + 40,40,30,50,20,60, + 10,10,20,30,40,50, + 60,60,50,40,30,20, + 10,60,10,50,30,40, + 20,10,40,30,60,20 }; + +void SHENQI_init() +{ + NRF24L01_Initialize(); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit + NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowldgement on all data pipes + NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps + NRF24L01_SetPower(); + + NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5 bytes rx/tx address + + LT8910_Config(4, 8, _BV(LT8910_CRC_ON)|_BV(LT8910_PACKET_LENGTH_EN), 0xAA); + LT8910_SetChannel(2); + LT8910_SetAddress((uint8_t *)"\x9A\x9A\x9A\x9A",4); + LT8910_SetTxRxMode(RX_EN); +} + +void SHENQI_send_packet() +{ + packet[0]=0x00; + if(packet_count==0) + { + uint8_t bind_addr[4]; + bind_addr[0]=0x9A; + bind_addr[1]=0x9A; + bind_addr[2]=rx_tx_addr[2]; + bind_addr[3]=rx_tx_addr[3]; + LT8910_SetAddress(bind_addr,4); + LT8910_SetChannel(2); + packet[1]=rx_tx_addr[1]; + packet[2]=rx_tx_addr[0]; + packet_period=2508; + } + else + { + LT8910_SetAddress(rx_tx_addr,4); + packet[1]=255-convert_channel_8b(RUDDER); + packet[2]=255-convert_channel_8b_scale(THROTTLE,0x60,0xA0); + uint8_t freq=pgm_read_byte_near(&SHENQI_Freq[hopping_frequency_no])+(rx_tx_addr[1]&0x0F); + LT8910_SetChannel(freq); + hopping_frequency_no++; + if(hopping_frequency_no==60) + hopping_frequency_no=0; + packet_period=1750; + } + // Send packet + 1 retransmit - not sure why but needed (not present on original TX...) + LT8910_WritePayload(packet,3); + while(NRF24L01_packet_ack()!=PKT_ACKED); + LT8910_WritePayload(packet,3); + + packet_count++; + if(packet_count==7) + { + packet_count=0; + packet_period=3000; + } + // Set power + NRF24L01_SetPower(); +} + +uint16_t SHENQI_callback() +{ + if(IS_BIND_DONE_on) + SHENQI_send_packet(); + else + { + if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_RX_DR)) + { + if(LT8910_ReadPayload(packet, 3)) + { + BIND_DONE; + rx_tx_addr[3]=packet[1]; + rx_tx_addr[2]=packet[2]; + LT8910_SetTxRxMode(TX_EN); + packet_period=14000; + } + NRF24L01_FlushRx(); + } + } + return packet_period; +} + +uint16_t initSHENQI() +{ + BIND_IN_PROGRESS; // autobind protocol + SHENQI_init(); + hopping_frequency_no = 0; + packet_count=0; + packet_period=100; + return 1000; +} + +#endif \ No newline at end of file diff --git a/Multiprotocol/_Config.h b/Multiprotocol/_Config.h index d39c787..5df7e3b 100644 --- a/Multiprotocol/_Config.h +++ b/Multiprotocol/_Config.h @@ -25,14 +25,6 @@ //Uncomment to enable telemetry #define TELEMETRY - -//Uncomment to enable potar select -#define POTAR_SELECT -#define POTAR_SELECT_V ELEVATOR -#define POTAR_SELECT_H RUDDER -#define POTAR_SELECT_M AILERON - - //Comment if a module is not installed #define A7105_INSTALLED #define CYRF6936_INSTALLED @@ -62,6 +54,11 @@ #define CFlie_NRF24L01_INO #define H377_NRF24L01_INO #define FY326_NRF24L01_INO + #define ESKY150_NRF24L01_INO +// #define BlueFly_NRF24L01_INO //probleme gene id + #define HonTai_NRF24L01_INO + #define UDI_NRF24L01_INO + #define NE260_NRF24L01_INO #define BAYANG_NRF24L01_INO #define CG023_NRF24L01_INO @@ -75,27 +72,27 @@ #define YD717_NRF24L01_INO #define MT99XX_NRF24L01_INO #define MJXQ_NRF24L01_INO +// #define SHENQI_NRF24L01_INO #endif //Update this table to set which protocol and all associated settings are called for the corresponding dial number -static const PPM_Parameters PPM_prot[15]= -{ -// Protocol Sub protocol RX_Num Power Auto Bind Option - {MODE_FLYSKY, Flysky , 0 , P_HIGH , AUTOBIND , 0 }, //Dial=1 - {MODE_HUBSAN, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=2 - {MODE_FRSKY , 0 , 0 , P_HIGH , NO_AUTOBIND , 0xD7 }, //Dial=3 - {MODE_HISKY , Hisky , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=4 - {MODE_V2X2 , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=5 - {MODE_DSM2 , DSM2 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=6 - {MODE_DEVO , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=7 - {MODE_YD717 , YD717 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=8 - {MODE_KN , WLTOYS , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=9 - {MODE_SYMAX , SYMAX , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=10 - {MODE_SLT , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=11 - {MODE_CX10 , CX10_BLUE , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=12 - {MODE_CG023 , CG023 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=13 - {MODE_BAYANG, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=14 - {MODE_SYMAX , SYMAX5C , 0 , P_HIGH , NO_AUTOBIND , 0 } //Dial=15 +const PPM_Parameters PPM_prot[15]= { +// Dial Protocol Sub protocol RX_Num Power Auto Bind Option +/* 1 */ {MODE_FLYSKY, Flysky , 0 , P_HIGH , AUTOBIND , 0 }, +/* 2 */ {MODE_HUBSAN, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, +/* 3 */ {MODE_FRSKY , 0 , 0 , P_HIGH , NO_AUTOBIND , 0xD7 }, +/* 4 */ {MODE_HISKY , Hisky , 0 , P_HIGH , NO_AUTOBIND , 0 }, +/* 5 */ {MODE_V2X2 , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, +/* 6 */ {MODE_DSM2 , DSM2 , 0 , P_HIGH , NO_AUTOBIND , 0 }, +/* 7 */ {MODE_DEVO , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, +/* 8 */ {MODE_YD717 , YD717 , 0 , P_HIGH , NO_AUTOBIND , 0 }, +/* 9 */ {MODE_KN , FEILUN , 0 , P_HIGH , AUTOBIND , 0 }, +/* 10 */ {MODE_SYMAX , SYMAX , 0 , P_HIGH , NO_AUTOBIND , 0 }, +/* 11 */ {MODE_SLT , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, +/* 12 */ {MODE_CX10 , CX10_BLUE , 0 , P_HIGH , NO_AUTOBIND , 0 }, +/* 13 */ {MODE_CG023 , CG023 , 0 , P_HIGH , NO_AUTOBIND , 0 }, +/* 14 */ {MODE_BAYANG, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, +/* 15 */ {MODE_SYMAX , SYMAX5C , 0 , P_HIGH , NO_AUTOBIND , 0 } }; /* Available protocols and associated sub protocols: MODE_FLYSKY @@ -159,6 +156,8 @@ static const PPM_Parameters PPM_prot[15]= X600 X800 H26D + MODE_SHENQI + NONE RX_Num value between 0 and 15 @@ -191,7 +190,7 @@ Option value between 0 and 255. 0xD7 or 0x00 for Frsky fine tuning. #endif // SPEKTRUM PPM and channels -#if defined(TX_SPEKTRUM) | defined(TARANIS) +#if defined(TX_SPEKTRUM) #define PPM_MAX 2000 #define PPM_MIN 1000 #define PPM_MAX_100 1900 @@ -199,6 +198,15 @@ Option value between 0 and 255. 0xD7 or 0x00 for Frsky fine tuning. #define TAER #endif +// TARANIS PPM and channels +#if defined(TARANIS) + #define PPM_MAX 2000 + #define PPM_MIN 1000 + #define PPM_MAX_100 1900 + #define PPM_MIN_100 1100 + #define EATR +#endif + // HISKY #if defined(TX_HISKY) #define PPM_MAX 2000 @@ -249,3 +257,7 @@ enum chan_orders{ #define PPM_MIN_COMMAND 1250 #define PPM_SWITCH 1550 #define PPM_MAX_COMMAND 1750 + +//Uncoment the desired serial speed +#define BAUD 100000 +//#define BAUD 125000 diff --git a/Multiprotocol/iface_cc2500.h b/Multiprotocol/iface_cc2500.h index cb7b623..ee5242f 100644 --- a/Multiprotocol/iface_cc2500.h +++ b/Multiprotocol/iface_cc2500.h @@ -156,4 +156,43 @@ enum { //void CC2500_WriteData(u8 *packet, u8 length); //void CC2500_ReadData(u8 *dpbuffer, int len); //void CC2500_SetTxRxMode(enum TXRX_State); + +const PROGMEM uint8_t cc2500_conf[][2]={ + { CC2500_02_IOCFG0, 0x06 }, + { CC2500_00_IOCFG2, 0x06 }, + { CC2500_17_MCSM1, 0x0c }, + { CC2500_18_MCSM0, 0x18 }, + { CC2500_06_PKTLEN, 0x19 }, + { CC2500_07_PKTCTRL1, 0x04 }, + { CC2500_08_PKTCTRL0, 0x05 }, + { CC2500_3E_PATABLE, 0xff }, + { CC2500_0B_FSCTRL1, 0x08 }, + { CC2500_0C_FSCTRL0, 0x00 }, // option + { CC2500_0D_FREQ2, 0x5c }, + { CC2500_0E_FREQ1, 0x76 }, + { CC2500_0F_FREQ0, 0x27 }, + { CC2500_10_MDMCFG4, 0xAA }, + { CC2500_11_MDMCFG3, 0x39 }, + { CC2500_12_MDMCFG2, 0x11 }, + { CC2500_13_MDMCFG1, 0x23 }, + { CC2500_14_MDMCFG0, 0x7a }, + { CC2500_15_DEVIATN, 0x42 }, + { CC2500_19_FOCCFG, 0x16 }, + { CC2500_1A_BSCFG, 0x6c }, + { CC2500_1B_AGCCTRL2, 0x43 }, // bind ? 0x43 : 0x03 + { CC2500_1C_AGCCTRL1,0x40 }, + { CC2500_1D_AGCCTRL0,0x91 }, + { CC2500_21_FREND1, 0x56 }, + { CC2500_22_FREND0, 0x10 }, + { CC2500_23_FSCAL3, 0xa9 }, + { CC2500_24_FSCAL2, 0x0A }, + { CC2500_25_FSCAL1, 0x00 }, + { CC2500_26_FSCAL0, 0x11 }, + { CC2500_29_FSTEST, 0x59 }, + { CC2500_2C_TEST2, 0x88 }, + { CC2500_2D_TEST1, 0x31 }, + { CC2500_2E_TEST0, 0x0B }, + { CC2500_03_FIFOTHR, 0x07 }, + { CC2500_09_ADDR, 0x00 } +}; #endif diff --git a/Multiprotocol/multiprotocol.h b/Multiprotocol/multiprotocol.h index d731f27..b2b9e81 100644 --- a/Multiprotocol/multiprotocol.h +++ b/Multiprotocol/multiprotocol.h @@ -30,6 +30,11 @@ enum PROTOCOLS MODE_H377=44, // =>NRF24L01 MODE_WK2x01 = 45, // =>CYRF6936 MODE_FY326=46, // =>NRF24L01 + MODE_ESKY150=47, // =>NRF24L01 + MODE_BlueFly=48, // =>NRF24L01 + MODE_HonTai=49, // =>NRF24L01 + MODE_UDI=50, // =>NRF24L01 + MODE_NE260=51, // =>NRF24L01 MODE_SERIAL = 0, // Serial commands MODE_FLYSKY = 1, // =>A7105 @@ -49,7 +54,8 @@ enum PROTOCOLS MODE_FRSKYX = 15, // =>CC2500 MODE_ESKY = 16, // =>NRF24L01 MODE_MT99XX=17, // =>NRF24L01 - MODE_MJXQ=18 // =>NRF24L01 + MODE_MJXQ=18, // =>NRF24L01 + MODE_SHENQI=19 // =>NRF24L01 }; enum Flysky { @@ -127,6 +133,12 @@ enum FY326 FY326 = 0, FY319 = 1 }; +enum UDI +{ + U816_V1 = 0, + U816_V2, + U839_2014 +}; #define NONE 0 #define P_HIGH 1 @@ -147,10 +159,6 @@ struct PPM_Parameters //******************* //*** Pinouts *** //******************* -#define BUZZER 19 //A5 -#define BUZZER_HTZ 440 // La clé de sol -#define BUZZER_TPS 300 - //#define BIND_pin 13 #define LED_pin 13 //Promini original led on B5 // @@ -440,6 +448,7 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p -- ESky 16 MT99XX 17 MJXQ 18 + SHENQI 19 BindBit=> 0x80 1=Bind/0=No AutoBindBit=> 0x40 1=Yes /0=No RangeCheck=> 0x20 1=Yes /0=No diff --git a/README.md b/README.md index dc4bccd..3c27e54 100644 --- a/README.md +++ b/README.md @@ -60,6 +60,7 @@ CH1|CH2|CH3|CH4|CH5|CH6|CH7 CH1|CH2|CH3|CH4|???|CONF|Gyro & Rudder mix CONF: Option 1 = Rate Throtle + Option 2 = Pitch @@ -76,6 +77,13 @@ CH1|CH2|CH3|CH4 A|E|T|R ##NRF24L01 RF Module +###BLUEFLY +Autobind + +CH1|CH2|CH3|CH4|CH5|CH6 +---|---|---|---|---|--- +A|E|T|R|GEAR|PITCH + ###CFLIE Modele: CrazyFlie Nano quad @@ -85,6 +93,14 @@ CH1|CH2|CH3|CH4 ---|---|---|--- A|E|T|R +###ESKY150 + +Autobind + +CH1|CH2|CH3|CH4 +---|---|---|--- +A|E|T|R + ###Fy326 Autobind @@ -107,6 +123,51 @@ Autobind CH1|CH2|CH3|CH4|CH5 ---|---|---|--- -A|Turbo|T|Trim|Bouton ??? +A|Turbo|T|Trim|Bouton + +###HONTAI +Autobind + +CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11 +---|---|---|---|---|---|---|---|---|---|--- +A|E|T|R|LED|FLIP|PICTURE|VIDEO|HEADLESS|RTH|Calibrate + +####Sub_protocol JJRCX1 +Modele: JJRC X1 + +CH5|CH6|CH7|CH8|CH9|CH10|CH11 +---|---|---|---|---|---|---|---|---|---|--- +ARM|FLIP|PICTURE|VIDEO|HEADLESS|RTH|Calibrate + +###NE260 +Modele: Nine Eagles SoloPro + +Autobind + +CH1|CH2|CH3|CH4 +---|---|---|--- +A|E|T|R + +###UDI +Modele: Known UDI 2.4GHz protocol variants, all using BK2421 +* UDI U819 coaxial 3ch helicoper +* UDI U816/817/818 quadcopters + - "V1" with orange LED on TX, U816 RX labeled '' , U817/U818 RX labeled 'UD-U817B' + - "V2" with red LEDs on TX, U816 RX labeled '', U817/U818 RX labeled 'UD-U817OG' + - "V3" with green LEDs on TX. Did not get my hands on yet. +* U830 mini quadcopter with tilt steering ("Protocol 2014") +* U839 nano quadcopter ("Protocol 2014") + +Autobind + +CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10 +---|---|---|---|---|---|---|---|---|--- +A|E|T|R|FLIP 360|FLIP|VIDEO|LED|MODE 2 + +####Sub_protocol U816 V1 (orange) +####Sub_protocol U816 V2 (red) +####Sub_protocol U816 (2014) +Same channels assignement as above. + ###D'autres à venir \ No newline at end of file From 8da823e9fc6f45f2891343ae856ef02f9eeb7613 Mon Sep 17 00:00:00 2001 From: tipouic Date: Sat, 19 Mar 2016 11:03:24 +0100 Subject: [PATCH 9/9] =?UTF-8?q?Mis=20=C3=A0=20jours=20protocole=20FY326?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Multiprotocol/A7105_SPI.ino | 6 - Multiprotocol/A7105_joysway.ino | 18 +- Multiprotocol/Cc2500_skyartec.ino | 183 ++++++++++++ Multiprotocol/DSM2_cyrf6936.ino | 75 ++--- ...{Nrf24l01_fy326.ino => FY326_nrf24l01.ino} | 188 +++++------- Multiprotocol/Multiprotocol.ino | 43 ++- Multiprotocol/Nrf24l01_bluefly.ino | 53 +--- Multiprotocol/Nrf24l01_fbl100.ino | 282 ++++++++++++++++++ Multiprotocol/Nrf24l01_h377.ino | 14 +- Multiprotocol/Nrf24l01_ne260.ino | 2 - Multiprotocol/Nrf24l01_udi.ino | 3 +- Multiprotocol/_Config.h | 16 +- Multiprotocol/multiprotocol.h | 33 +- README.md | 22 +- sync.ffs_db | Bin 1450 -> 2385 bytes 15 files changed, 698 insertions(+), 240 deletions(-) create mode 100644 Multiprotocol/Cc2500_skyartec.ino rename Multiprotocol/{Nrf24l01_fy326.ino => FY326_nrf24l01.ino} (51%) create mode 100644 Multiprotocol/Nrf24l01_fbl100.ino diff --git a/Multiprotocol/A7105_SPI.ino b/Multiprotocol/A7105_SPI.ino index ad8f7be..1698725 100644 --- a/Multiprotocol/A7105_SPI.ino +++ b/Multiprotocol/A7105_SPI.ino @@ -191,16 +191,10 @@ const uint8_t PROGMEM HUBSAN_A7105_regs[] = { 0xFF, 0xFF, 0xFF }; const uint8_t PROGMEM FLYSKY_A7105_regs[] = { -/* 0xff, 0x42, 0x00, 0x14, 0x00, 0xff, 0xff ,0x00, 0x00, 0x00, 0x00, 0x01, 0x21, 0x05, 0x00, 0x50, 0x9e, 0x4b, 0x00, 0x02, 0x16, 0x2b, 0x12, 0x00, 0x62, 0x80, 0x80, 0x00, 0x0a, 0x32, 0xc3, 0x0f, 0x13, 0xc3, 0x00, 0xff, 0x00, 0x00, 0x3b, 0x00, 0x17, 0x47, 0x80, 0x03, 0x01, 0x45, 0x18, 0x00, 0x01, 0x0f, 0xff -*/ - -1, 0x42, 0x00, 0x14, 0x00, -1 , -1 , 0x00, 0x00, 0x00, 0x00, 0x01, 0x21, 0x05, 0x00, 0x50, - 0x9e, 0x4b, 0x00, 0x02, 0x16, 0x2b, 0x12, 0x00, 0x62, 0x80, 0x80, 0x00, 0x0a, 0x32, 0xc3, 0x0f, - 0x13, 0xc3, 0x00, -1, 0x00, 0x00, 0x3b, 0x00, 0x17, 0x47, 0x80, 0x03, 0x01, 0x45, 0x18, 0x00, - 0x01, 0x0f, -1 }; #define ID_NORMAL 0x55201041 #define ID_PLUS 0xAA201041 diff --git a/Multiprotocol/A7105_joysway.ino b/Multiprotocol/A7105_joysway.ino index b153c79..1aed90d 100644 --- a/Multiprotocol/A7105_joysway.ino +++ b/Multiprotocol/A7105_joysway.ino @@ -35,7 +35,7 @@ static int joysway_init() //uint8_t vco_calibration0; //uint8_t vco_calibration1; - counter = 0; + phase = 0; next_ch = 0x30; for (i = 0; i < 0x33; i++) @@ -100,7 +100,7 @@ static void joysway_build_packet() //Calculate: //Center = 0x5d9 //1 % = 5 - packet[0] = counter == 0 ? 0xdd : 0xff; + packet[0] = phase == 0 ? 0xdd : 0xff; packet[1] = (MProtocol_id_master >> 24) & 0xff; packet[2] = (MProtocol_id_master >> 16) & 0xff; packet[3] = (MProtocol_id_master >> 8) & 0xff; @@ -118,7 +118,7 @@ static void joysway_build_packet() packet[9] = 0x64; packet[12] = 0x64; packet[13] = 0x64; - packet[14] = counter == 0 ? 0x30 : 0xaa; + packet[14] = phase == 0 ? 0x30 : 0xaa; uint8_t value = 0; for (int i = 0; i < 15; i++) { value += packet[i]; } packet[15] = value; @@ -127,21 +127,21 @@ static void joysway_build_packet() static uint16_t joysway_cb() { uint8_t ch; - if (counter == 254) { - counter = 0; + if (phase == 254) { + phase = 0; A7105_WriteID(0x5475c52a); ch = 0x0a; - } else if (counter == 2) { + } else if (phase == 2) { A7105_WriteID(MProtocol_id_master); ch = 0x30; } else { - if ((counter & 0x01) ^ EVEN_ODD) { + if ((phase & 0x01) ^ EVEN_ODD) { ch = 0x30; } else { ch = next_ch; } } - if (! ((counter & 0x01) ^ EVEN_ODD)) { + if (! ((phase & 0x01) ^ EVEN_ODD)) { next_ch++; if (next_ch == 0x45) next_ch = 0x30; @@ -149,7 +149,7 @@ static uint16_t joysway_cb() joysway_build_packet(); A7105_Strobe(A7105_STANDBY); A7105_WriteData(16, ch); - counter++; + phase++; return 6000; } diff --git a/Multiprotocol/Cc2500_skyartec.ino b/Multiprotocol/Cc2500_skyartec.ino new file mode 100644 index 0000000..7f3a932 --- /dev/null +++ b/Multiprotocol/Cc2500_skyartec.ino @@ -0,0 +1,183 @@ +/* + This project is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Deviation is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with Deviation. If not, see . + */ + +#if defined(SKYARTEC_CC2500_INO) +#include "iface_cc2500.h" + +#define TX_ADDR ((binding_idx >> 16) & 0xff) +#define TX_CHANNEL ((binding_idx >> 24) & 0xff) + +enum { + SKYARTEC_PKT1 = 0, + SKYARTEC_SLEEP1, + SKYARTEC_PKT2, + SKYARTEC_SLEEP2, + SKYARTEC_PKT3, + SKYARTEC_SLEEP3, + SKYARTEC_PKT4, + SKYARTEC_SLEEP4, + SKYARTEC_PKT5, + SKYARTEC_SLEEP5, + SKYARTEC_PKT6, + SKYARTEC_LAST, +}; + +static void skyartec_init() { + CC2500_Reset(); + + cc2500_writeReg(CC2500_16_MCSM2, 0x07); + cc2500_writeReg(CC2500_17_MCSM1, 0x30); + cc2500_writeReg(CC2500_1E_WOREVT1, 0x87); + cc2500_writeReg(CC2500_1F_WOREVT0, 0x6b); + cc2500_writeReg(CC2500_20_WORCTRL, 0xf8); + cc2500_writeReg(CC2500_2A_PTEST, 0x7f); + cc2500_writeReg(CC2500_2B_AGCTEST, 0x3f); + cc2500_writeReg(CC2500_0B_FSCTRL1, 0x09); + cc2500_writeReg(CC2500_0C_FSCTRL0, 0x00); + cc2500_writeReg(CC2500_0D_FREQ2, 0x5d); + cc2500_writeReg(CC2500_0E_FREQ1, 0x93); + cc2500_writeReg(CC2500_0F_FREQ0, 0xb1); + cc2500_writeReg(CC2500_10_MDMCFG4, 0x2d); + cc2500_writeReg(CC2500_11_MDMCFG3, 0x20); + cc2500_writeReg(CC2500_12_MDMCFG2, 0x73); + cc2500_writeReg(CC2500_13_MDMCFG1, 0x22); + cc2500_writeReg(CC2500_14_MDMCFG0, 0xf8); + cc2500_writeReg(CC2500_0A_CHANNR, 0xcd); + cc2500_writeReg(CC2500_15_DEVIATN, 0x50); + cc2500_writeReg(CC2500_21_FREND1, 0xb6); + cc2500_writeReg(CC2500_22_FREND0, 0x10); + cc2500_writeReg(CC2500_18_MCSM0, 0x18); + cc2500_writeReg(CC2500_19_FOCCFG, 0x1d); + cc2500_writeReg(CC2500_1A_BSCFG, 0x1c); + cc2500_writeReg(CC2500_1B_AGCCTRL2, 0xc7); + cc2500_writeReg(CC2500_1C_AGCCTRL1, 0x00); + cc2500_writeReg(CC2500_1D_AGCCTRL0, 0xb2); + cc2500_writeReg(CC2500_23_FSCAL3, 0xea); + cc2500_writeReg(CC2500_24_FSCAL2, 0x0a); + cc2500_writeReg(CC2500_25_FSCAL1, 0x00); + cc2500_writeReg(CC2500_26_FSCAL0, 0x11); + cc2500_writeReg(CC2500_29_FSTEST, 0x59); + cc2500_writeReg(CC2500_2C_TEST2, 0x88); + cc2500_writeReg(CC2500_2D_TEST1, 0x31); + cc2500_writeReg(CC2500_2E_TEST0, 0x0b); + cc2500_writeReg(CC2500_07_PKTCTRL1, 0x05); + cc2500_writeReg(CC2500_08_PKTCTRL0, 0x05); + cc2500_writeReg(CC2500_09_ADDR, 0x43); + cc2500_writeReg(CC2500_06_PKTLEN, 0xff); + cc2500_writeReg(CC2500_04_SYNC1, 0x13); + cc2500_writeReg(CC2500_05_SYNC0, 0x18); + CC2500_SetTxRxMode(TX_EN); + CC2500_SetPower(); + cc2500_strobe(CC2500_SFTX); + cc2500_strobe(CC2500_SFRX); + cc2500_strobe(CC2500_SXOFF); + cc2500_strobe(CC2500_SIDLE); +} + +static void add_pkt_suffix() { + int xor1 = 0; + int xor2 = 0; + for(int i = 3; i <= 16; i++) { xor1 ^= packet[i]; } + for(int i = 3; i <= 14; i++) { xor2 ^= packet[i]; } + + int sum = packet[3] + packet[5] + packet[7] + packet[9] + packet[11] + packet[13]; + packet[17] = xor1; + packet[18] = xor2; + packet[19] = sum & 0xff; +} + +static void send_data_packet() { + //13 c5 01 0259 0168 0000 0259 030c 021a 0489 f3 7e 0a + packet[0] = 0x13; //Length + packet[1] = TX_ADDR; //Tx Addr? + packet[2] = 0x01; //??? + for(int i = 0; i < 7; i++) { + uint32_t value = (uint32_t)Servo_data[i] * 0x280 / PPM_MAX + 0x280; + if(value < 0) { value = 0; } + if(value > 0x500) { value = 0x500; } + packet[3+2*i] = value >> 8; + packet[4+2*i] = value & 0xff; + } + add_pkt_suffix(); + //for(int i = 0; i < 20; i++) printf("%02x ", packet[i]); printf("\n"); + cc2500_writeReg(CC2500_04_SYNC1, ((binding_idx >> 0) & 0xff)); + cc2500_writeReg(CC2500_05_SYNC0, ((binding_idx >> 8) & 0xff)); + cc2500_writeReg(CC2500_09_ADDR, TX_ADDR); + cc2500_writeReg(CC2500_0A_CHANNR, TX_CHANNEL); + cc2500_writeFifo(packet, 20); +} + +static void send_bind_packet() { + //0b 7d 01 01 b2 c5 4a 2f 00 00 c5 d6 + packet[0] = 0x0b; //Length + packet[1] = 0x7d; + packet[2] = 0x01; + packet[3] = 0x01; + packet[4] = (binding_idx >> 24) & 0xff; + packet[5] = (binding_idx >> 16) & 0xff; + packet[6] = (binding_idx >> 8) & 0xff; + packet[7] = (binding_idx >> 0) & 0xff; + packet[8] = 0x00; + packet[9] = 0x00; + packet[10] = TX_ADDR; + uint8_t xore = 0; + for(int i = 3; i < 11; i++) { xore ^= packet[i]; } + packet[11] = xore; + cc2500_writeReg(CC2500_04_SYNC1, 0x7d); + cc2500_writeReg(CC2500_05_SYNC0, 0x7d); + cc2500_writeReg(CC2500_09_ADDR, 0x7d); + cc2500_writeReg(CC2500_0A_CHANNR, 0x7d); + cc2500_writeFifo(packet, 12); +} + +static uint16_t skyartec_cb() { + if (state & 0x01) { + cc2500_strobe(CC2500_SIDLE); + if (state == SKYARTEC_LAST) { CC2500_SetPower(); state = SKYARTEC_PKT1; } + else { state++; } + return 3000; + } + if (state == SKYARTEC_PKT1 && bind_phase) { + send_bind_packet(); + bind_phase--; + if(bind_phase == 0) { printf("Done binding\n"); } + } else { send_data_packet(); } + state++; + return 3000; +} + +static uint8_t skyartec_setup() { + skyartec_init(); +/* binding_idx = 0xb2c54a2f; + if (Model.fixed_id) { + binding_idx ^= Model.binding_idx + (Model.fixed_id << 16); + } else { + int partnum = CC2500_ReadReg(0xF0); + int vernum = CC2500_ReadReg(0xF1); + binding_idx ^= partnum << 24; + binding_idx ^= vernum << 16; + binding_idx ^= (vernum << 4 | partnum >> 4) << 8; + binding_idx ^= (partnum << 4 | vernum >> 4) << 8; + } +*/ + binding_idx = MProtocol_id; + if (0 == (binding_idx & 0xff000000)) { binding_idx |= 0xb2; } + if (0 == (binding_idx & 0x00ff0000)) { binding_idx |= 0xc5; } + if (0 == (binding_idx & 0x0000ff00)) { binding_idx |= 0x4a; } + if (0 == (binding_idx & 0x000000ff)) { binding_idx |= 0x2f; } + bind_phase = 10000; + state = SKYARTEC_PKT1; +} +#endif \ No newline at end of file diff --git a/Multiprotocol/DSM2_cyrf6936.ino b/Multiprotocol/DSM2_cyrf6936.ino index 0882d77..19a969e 100644 --- a/Multiprotocol/DSM2_cyrf6936.ino +++ b/Multiprotocol/DSM2_cyrf6936.ino @@ -17,7 +17,6 @@ #include "iface_cyrf6936.h" -#define DSM2_NUM_CHANNELS 7 #define RANDOM_CHANNELS 0 // disabled //#define RANDOM_CHANNELS 1 // enabled #define BIND_CHANNEL 0x0d //13 This can be any odd channel @@ -132,15 +131,11 @@ static void __attribute__((unused)) build_bind_packet() packet[8] = sum >> 8; packet[9] = sum & 0xff; packet[10] = 0x01; //??? - packet[11] = DSM2_NUM_CHANNELS; + packet[11] = option>3?option:option+4; if(sub_protocol==DSMX) //DSMX type packet[12] = 0xb2; // Telemetry off: packet[12] = num_channels < 8 && Model.proto_opts[PROTOOPTS_TELEMETRY] == TELEM_OFF ? 0xa2 : 0xb2; else -#if DSM2_NUM_CHANNELS < 8 - packet[12] = 0x01; -#else - packet[12] = 0x02; -#endif + packet[12] = option<8?0x01:0x02; packet[13] = 0x00; //??? for(i = 8; i < 14; i++) sum += packet[i]; @@ -166,34 +161,38 @@ static uint8_t __attribute__((unused)) PROTOCOL_SticksMoved(uint8_t init) static void __attribute__((unused)) build_data_packet(uint8_t upper)// { -#if DSM2_NUM_CHANNELS==4 - const uint8_t ch_map[] = {0, 1, 2, 3, 0xff, 0xff, 0xff}; //Guess -#elif DSM2_NUM_CHANNELS==5 - const uint8_t ch_map[] = {0, 1, 2, 3, 4, 0xff, 0xff}; //Guess -#elif DSM2_NUM_CHANNELS==6 - const uint8_t ch_map[] = {1, 5, 2, 3, 0, 4, 0xff}; //HP6DSM -#elif DSM2_NUM_CHANNELS==7 - const uint8_t ch_map[] = {1, 5, 2, 4, 3, 6, 0}; //DX6i -#elif DSM2_NUM_CHANNELS==8 - const uint8_t ch_map[] = {1, 5, 2, 3, 6, 0xff, 0xff, 4, 0, 7, 0xff, 0xff, 0xff, 0xff}; //DX8 -#elif DSM2_NUM_CHANNELS==9 - const uint8_t ch_map[] = {3, 2, 1, 5, 0, 4, 6, 7, 8, 0xff, 0xff, 0xff, 0xff, 0xff}; //DM9 -#elif DSM2_NUM_CHANNELS==10 - const uint8_t ch_map[] = {3, 2, 1, 5, 0, 4, 6, 7, 8, 9, 0xff, 0xff, 0xff, 0xff}; -#elif DSM2_NUM_CHANNELS==11 - const uint8_t ch_map[] = {3, 2, 1, 5, 0, 4, 6, 7, 8, 9, 10, 0xff, 0xff, 0xff}; -#elif DSM2_NUM_CHANNELS==12 - const uint8_t ch_map[] = {3, 2, 1, 5, 0, 4, 6, 7, 8, 9, 10, 11, 0xff, 0xff}; -#endif - uint8_t i; uint8_t bits; + + uint8_t ch_map[] = {3, 2, 1, 5, 0, 4, 6, 7, 8, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}; //9 Channels - DM9 TX + switch(option>3?option:option+4) // Create channel map based on number of channels + { + case 12: + ch_map[11]=11; // 12 channels + case 11: + ch_map[10]=10; // 11 channels + case 10: + ch_map[9]=9; // 10 channels + break; + case 8: + memcpy(ch_map,"\x01\x05\x02\x03\x06\xFF\xFF\x04\x00\x07",10); // 8 channels - DX8 TX + break; + case 7: + memcpy(ch_map,"\x01\x05\x02\x04\x03\x06\x00",7); // 7 channels - DX6i TX + break; + case 6: + memcpy(ch_map,"\x01\x05\x02\x03\x00\x04\xFF",7); // 6 channels - HP6DSM TX + break; + case 4: + case 5: + memcpy(ch_map,"\x00\x01\x02\x03\xFF\xFF\xFF",7); // 4 channels - Guess + if(option&0x01) + ch_map[4]=4; // 5 channels - Guess + break; + } // if( binding && PROTOCOL_SticksMoved(0) ) - { - //BIND_DONE; binding = 0; - } if (sub_protocol==DSMX) { packet[0] = cyrfmfg_id[2]; @@ -463,12 +462,16 @@ uint16_t ReadDsm2() set_sop_data_crc(); if (cyrf_state == DSM2_CH2_CHECK_A) { - #if DSM2_NUM_CHANNELS < 8 - cyrf_state = DSM2_CH1_WRITE_A; // change from CH2_CHECK_A to CH1_WRITE_A (ie no upper) - return 11000 - CH1_CH2_DELAY - WRITE_DELAY ; // Original is 22000 from deviation but it works better this way - #else - cyrf_state = DSM2_CH1_WRITE_B; // change from CH2_CHECK_A to CH1_WRITE_A (to transmit upper) - #endif + if(option < 8) + { + cyrf_state = DSM2_CH1_WRITE_A; // change from CH2_CHECK_A to CH1_WRITE_A (ie no upper) + if(option>3) + return 11000 - CH1_CH2_DELAY - WRITE_DELAY ; // force 11ms if option>3 ie 4,5,6,7 channels @11ms + else + return 22000 - CH1_CH2_DELAY - WRITE_DELAY ; // normal 22ms mode if option<=3 ie 4,5,6,7 channels @22ms + } + else + cyrf_state = DSM2_CH1_WRITE_B; // change from CH2_CHECK_A to CH1_WRITE_A (to transmit upper) } else cyrf_state = DSM2_CH1_WRITE_A; // change from CH2_CHECK_B to CH1_WRITE_A (upper already transmitted so transmit lower) diff --git a/Multiprotocol/Nrf24l01_fy326.ino b/Multiprotocol/FY326_nrf24l01.ino similarity index 51% rename from Multiprotocol/Nrf24l01_fy326.ino rename to Multiprotocol/FY326_nrf24l01.ino index 68234db..6417bfb 100644 --- a/Multiprotocol/Nrf24l01_fy326.ino +++ b/Multiprotocol/FY326_nrf24l01.ino @@ -4,38 +4,26 @@ the Free Software Foundation, either version 3 of the License, or (at your option) any later version. - Deviation is distributed in the hope that it will be useful, + Multiprotocol is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License - along with Deviation. If not, see . + along with Multiprotocol. If not, see . */ - +// Last sync with hexfet new_protocols/fy326_nrf24l01.c dated 2015-07-29 #if defined(FY326_NRF24L01_INO) #include "iface_nrf24l01.h" -#define INITIAL_WAIT 500 -#define FY326_PERIOD 1500 // Timeout for callback in uSec -#define FY326_CHKTIME 300 // Time to wait if packet not yet received or sent -#define FY326_SIZE 15 +#define FY326_INITIAL_WAIT 500 +#define FY326_PACKET_PERIOD 1500 +#define FY326_PACKET_CHKTIME 300 +#define FY326_PACKET_SIZE 15 #define FY326_BIND_COUNT 16 - -#define CHANNEL_FLIP AUX1 -#define CHANNEL_HEADLESS AUX2 -#define CHANNEL_RTH AUX3 -#define CHANNEL_CALIBRATE AUX4 -#define CHANNEL_EXPERT AUX5 - -// frequency channel management -#define RF_BIND_CHANNEL 0x17 -#define NUM_RF_CHANNELS 5 -static uint8_t current_chan; -static uint8_t rf_chans[NUM_RF_CHANNELS]; -static uint8_t txid[5]; -static uint8_t rxid; +#define FY326_RF_BIND_CHANNEL 0x17 +#define FY326_NUM_RF_CHANNELS 5 enum { FY326_INIT1 = 0, @@ -47,97 +35,86 @@ enum { FY319_BIND2, }; -// Bit vector from bit position -#define BV(bit) (1 << bit) +#define rxid channel -#define CHAN_RANGE (PPM_MAX - PPM_MIN) -static uint8_t scale_channel(uint8_t ch, uint8_t destMin, uint8_t destMax) +#define CHAN_TO_TRIM(chanval) ((chanval/10)-10) +static void __attribute__((unused)) FY326_send_packet(uint8_t bind) { - uint32_t chanval = Servo_data[ch]; - uint32_t range = destMax - destMin; - - if (chanval < PPM_MIN) chanval = PPM_MIN; - else if (chanval > PPM_MAX) chanval = PPM_MAX; - return (range * (chanval - PPM_MIN)) / CHAN_RANGE + destMin; -} - -#define GET_FLAG(ch, mask) (Servo_data[ch] > PPM_MIN_COMMAND ? mask : 0) -#define CHAN_TO_TRIM(chanval) ((uint8_t)(((uint16_t)chanval/10)-10)) // scale to [-10,10]. [-20,20] caused problems. -static void send_packet(uint8_t bind) -{ - packet[0] = txid[3]; - if (bind) { + packet[0] = rx_tx_addr[3]; + if(bind) packet[1] = 0x55; - } else { - packet[1] = GET_FLAG(CHANNEL_HEADLESS, 0x80) - | GET_FLAG(CHANNEL_RTH, 0x40) - | GET_FLAG(CHANNEL_FLIP, 0x02) - | GET_FLAG(CHANNEL_CALIBRATE, 0x01) - | GET_FLAG(CHANNEL_EXPERT, 4); - } - packet[2] = 200 - scale_channel(AILERON, 0, 200); // aileron 1 - packet[3] = scale_channel(ELEVATOR, 0, 200); // elevator 2 - packet[4] = 200 - scale_channel(RUDDER, 0, 200); // rudder 4 - packet[5] = scale_channel(THROTTLE, 0, 200); // throttle 3 + else + packet[1] = GET_FLAG(Servo_AUX3, 0x80) // Headless + | GET_FLAG(Servo_AUX2, 0x40) // RTH + | GET_FLAG(Servo_AUX1, 0x02) // Flip + | GET_FLAG(Servo_AUX5, 0x01) // Calibrate + | GET_FLAG(Servo_AUX4, 0x04); // Expert + packet[2] = 200 - convert_channel_8b_scale(AILERON, 0, 200); // aileron + packet[3] = convert_channel_8b_scale(ELEVATOR, 0, 200); // elevator + packet[4] = 200 - convert_channel_8b_scale(RUDDER, 0, 200); // rudder + packet[5] = convert_channel_8b_scale(THROTTLE, 0, 200); // throttle if(sub_protocol == FY319) { packet[6] = 255 - scale_channel(AILERON, 0, 255); packet[7] = scale_channel(ELEVATOR, 0, 255); packet[8] = 255 - scale_channel(RUDDER, 0, 255); } else { - packet[6] = txid[0]; - packet[7] = txid[1]; - packet[8] = txid[2]; - } + packet[6] = rx_tx_addr[0]; + packet[7] = rx_tx_addr[1]; + packet[8] = rx_tx_addr[2]; + } packet[9] = CHAN_TO_TRIM(packet[2]); // aileron_trim; packet[10] = CHAN_TO_TRIM(packet[3]); // elevator_trim; packet[11] = CHAN_TO_TRIM(packet[4]); // rudder_trim; packet[12] = 0; // throttle_trim; packet[13] = rxid; - packet[14] = txid[4]; + packet[14] = rx_tx_addr[4]; + + if (bind) + NRF24L01_WriteReg(NRF24L01_05_RF_CH, FY326_RF_BIND_CHANNEL); + else + { + NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no++]); + hopping_frequency_no %= FY326_NUM_RF_CHANNELS; - if (bind) { - NRF24L01_WriteReg(NRF24L01_05_RF_CH, RF_BIND_CHANNEL); - } else { - NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_chans[current_chan++]); - current_chan %= NUM_RF_CHANNELS; } // clear packet status bits and TX FIFO NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); NRF24L01_FlushTx(); - NRF24L01_WritePayload(packet, FY326_SIZE); + NRF24L01_WritePayload(packet, FY326_PACKET_SIZE); + + NRF24L01_SetPower(); // Set tx_power } -static void fy326_init() +static void __attribute__((unused)) FY326_init() { - uint8_t rx_tx_addr[] = {0x15, 0x59, 0x23, 0xc6, 0x29}; - NRF24L01_Initialize(); NRF24L01_SetTxRxMode(TX_EN); if(sub_protocol == FY319) NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // Five-byte rx/tx address else NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x01); // Three-byte rx/tx address - NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, sizeof(rx_tx_addr)); - NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, sizeof(rx_tx_addr)); + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t *)"\x15\x59\x23\xc6\x29", 5); + NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, (uint8_t *)"\x15\x59\x23\xc6\x29", 5); NRF24L01_FlushTx(); NRF24L01_FlushRx(); NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit - NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowldgement on all data pipes + NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowledgement on all data pipes NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only - NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, FY326_SIZE); - NRF24L01_WriteReg(NRF24L01_05_RF_CH, RF_BIND_CHANNEL); + NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, FY326_PACKET_SIZE); + NRF24L01_WriteReg(NRF24L01_05_RF_CH, FY326_RF_BIND_CHANNEL); NRF24L01_SetBitrate(NRF24L01_BR_250K); NRF24L01_SetPower(); NRF24L01_Activate(0x73); NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x3f); NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x07); + NRF24L01_Activate(0x73); } -static uint16_t fy326_callback() +uint16_t fy326_callback() { uint8_t i; switch (phase) { @@ -191,77 +168,76 @@ static uint16_t fy326_callback() break; case FY326_BIND1: - if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_RX_DR)) { // RX fifo data ready - NRF24L01_ReadPayload(packet, FY326_SIZE); + if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_RX_DR)) + { // RX fifo data ready + NRF24L01_ReadPayload(packet, FY326_PACKET_SIZE); rxid = packet[13]; - txid[0] = 0xaa; + rx_tx_addr[0] = 0xAA; NRF24L01_SetTxRxMode(TXRX_OFF); NRF24L01_SetTxRxMode(TX_EN); BIND_DONE; phase = FY326_DATA; - } else if (bind_counter-- == 0) { + } + else + if (bind_counter-- == 0) + { bind_counter = FY326_BIND_COUNT; NRF24L01_SetTxRxMode(TXRX_OFF); NRF24L01_SetTxRxMode(TX_EN); - send_packet(1); + FY326_send_packet(1); phase = FY326_BIND2; - return FY326_CHKTIME; + return FY326_PACKET_CHKTIME; } break; case FY326_BIND2: - if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_TX_DS)) { // TX data sent - // switch to RX mode + if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_TX_DS)) + { // TX data sent -> switch to RX mode NRF24L01_SetTxRxMode(TXRX_OFF); NRF24L01_FlushRx(); NRF24L01_SetTxRxMode(RX_EN); phase = FY326_BIND1; - } else { - return FY326_CHKTIME; } + else + return FY326_PACKET_CHKTIME; break; case FY326_DATA: - send_packet(0); + FY326_send_packet(0); break; } - return FY326_PERIOD; + return FY326_PACKET_PERIOD; } -// Generate address to use from TX id and manufacturer id (STM32 unique id) -static void fy_txid() +static void __attribute__((unused)) FY326_initialize_txid() { - txid[0] = (MProtocol_id_master >> 24) & 0xFF; - txid[1] = ((MProtocol_id_master >> 16) & 0xFF); - txid[2] = (MProtocol_id_master >> 8) & 0xFF; - txid[3] = MProtocol_id_master & 0xFF; -// for (uint8_t i = 0; i < sizeof(MProtocol_id_master); ++i) rand32_r(&MProtocol_id_master, 0); - txid[4] = MProtocol_id_master & 0xFF; - - rf_chans[0] = txid[0] & 0x0F; - rf_chans[1] = 0x10 + (txid[0] >> 4); - rf_chans[2] = 0x20 + (txid[1] & 0x0F); - rf_chans[3] = 0x30 + (txid[1] >> 4); - rf_chans[4] = 0x40 + (txid[2] >> 4); - if(sub_protocol == FY319) { - for(uint8_t i=0; i<5; i++) - rf_chans[i] = txid[0] & ~0x80; + hopping_frequency[0] = (rx_tx_addr[0]&0x0f) & ~0x80; + hopping_frequency[1] = (rx_tx_addr[0] >> 4) & ~0x80; + hopping_frequency[2] = (rx_tx_addr[1]&0x0f) & ~0x80; + hopping_frequency[3] = (rx_tx_addr[1] >> 4) & ~0x80; + hopping_frequency[4] = (rx_tx_addr[2] >> 4) & ~0x80; + } else { + hopping_frequency[0] = (rx_tx_addr[0]&0x0f); + hopping_frequency[1] = 0x10 + (rx_tx_addr[0] >> 4); + hopping_frequency[2] = 0x20 + (rx_tx_addr[1]&0x0f); + hopping_frequency[3] = 0x30 + (rx_tx_addr[1] >> 4); + hopping_frequency[4] = 0x40 + (rx_tx_addr[2] >> 4); } } -static uint16_t FY326_setup() +uint16_t initFY326(void) { - BIND_IN_PROGRESS; + BIND_IN_PROGRESS; // autobind protocol rxid = 0xaa; + bind_counter = 0; + FY326_initialize_txid(); + fy326_init(); if(sub_protocol == FY319) phase = FY319_INIT1; else phase = FY326_INIT1; - bind_counter = FY326_BIND_COUNT; - fy_txid(); - fy326_init(); - return INITIAL_WAIT; + return FY326_INITIAL_WAIT; } -#endif +#endif diff --git a/Multiprotocol/Multiprotocol.ino b/Multiprotocol/Multiprotocol.ino index 109586c..77036de 100644 --- a/Multiprotocol/Multiprotocol.ino +++ b/Multiprotocol/Multiprotocol.ino @@ -140,6 +140,9 @@ void setup() Servo_data[THROTTLE]=PPM_MIN_100; memcpy((void *)PPM_data,Servo_data, sizeof(Servo_data)); + //Wait for every component to start + delay(100); + // Read status of bind button if( (PINB & _BV(5)) == 0x00 ) BIND_BUTTON_FLAG_on; // If bind button pressed save the status for protocol id reset under hubsan @@ -148,7 +151,7 @@ void setup() // after this mode_select will be one of {0000, 0001, ..., 1111} mode_select=0x0F - ( ( (PINB>>2)&0x07 ) | ( (PINC<<3)&0x08) );//encoder dip switches 1,2,4,8=>B2,B3,B4,C0 //********************************** - //mode_select=14; // here to test PPM +//mode_select=1; // here to test PPM //********************************** // Update LED @@ -352,12 +355,6 @@ static void protocol_init() remote_callback = wk_cb; break; #endif -#if defined(FY326_NRF24L01_INO) - case MODE_FY326: - next_callback=FY326_setup(); - remote_callback = fy326_callback; - break; -#endif #if defined(ESKY150_NRF24L01_INO) case MODE_ESKY150: next_callback=esky150_setup(); @@ -371,7 +368,7 @@ static void protocol_init() break; #endif #if defined(HonTai_NRF24L01_INO) - case MODE_BlueFly: + case MODE_HonTai: next_callback=ht_setup(); remote_callback = ht_callback; break; @@ -388,6 +385,18 @@ static void protocol_init() remote_callback = ne260_cb; break; #endif +#if defined(SKYARTEC_CC2500_INO) + case MODE_SKYARTEC: + next_callback=skyartec_setup(); + remote_callback = skyartec_cb; + break; +#endif +#if defined(FBL100_NRF24L01_INO) + case MODE_FBL100: + next_callback=fbl_setup(); + remote_callback = ne260_cb; + break; +#endif #if defined(FLYSKY_A7105_INO) case MODE_FLYSKY: @@ -512,6 +521,12 @@ static void protocol_init() next_callback=initSHENQI(); remote_callback = SHENQI_callback; break; +#endif +#if defined(FY326_NRF24L01_INO) + case MODE_FY326: + next_callback=initFY326(); + remote_callback = FY326_callback; + break; #endif } @@ -594,7 +609,7 @@ static void module_reset() case MODE_DEVO: CYRF_Reset(); break; - default: // MODE_HISKY, MODE_V2X2, MODE_YD717, MODE_KN, MODE_SYMAX, MODE_SLT, MODE_CX10, MODE_CG023, MODE_BAYANG, MODE_ESKY, MODE_MT99XX, MODE_MJXQ, MODE_SHENQI + default: // MODE_HISKY, MODE_V2X2, MODE_YD717, MODE_KN, MODE_SYMAX, MODE_SLT, MODE_CX10, MODE_CG023, MODE_BAYANG, MODE_ESKY, MODE_MT99XX, MODE_MJXQ, MODE_SHENQI, MODE_FY326 NRF24L01_Reset(); break; } @@ -669,12 +684,13 @@ static void Mprotocol_serial_init() #include UBRR0H = UBRRH_VALUE; UBRR0L = UBRRL_VALUE; + UCSR0A = 0 ; // Clear X2 bit //Set frame format to 8 data bits, even parity, 2 stop bits - UCSR0C |= (1<0) { - counter--; - if (! counter) { BIND_DONE; } + if (bind_phase>0) { + bind_phase--; + if (! bind_phase) { BIND_DONE; } NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, bluefly_binding_adr_rf, 5); NRF24L01_WriteReg(NRF24L01_05_RF_CH, 81); NRF24L01_FlushTx(); @@ -141,42 +139,11 @@ static uint16_t bluefly_cb() { return 1000; // send 1 binding packet and 1 data packet per 9ms } -// Generate internal id from TX id and manufacturer id (STM32 unique id) -static void initialize_tx_id() { - uint32_t lfsr = 0x7649eca9ul; - - if (Model.fixed_id) { - for (uint8_t i = 0, j = 0; i < sizeof(Model.fixed_id); ++i, j += 8) - rand32_r(&lfsr, (Model.fixed_id >> j) & 0xff); - } - // Pump zero bytes for LFSR to diverge more - for (int i = 0; i < TXID_BlueFly_SIZE; ++i) rand32_r(&lfsr, 0); - - for (uint8_t i = 0; i < TXID_BlueFly_SIZE; ++i) { - bluefly_rf_adr_buf[i] = lfsr & 0xff; - rand32_r(&lfsr, i); - } - - printf("Effective id: %02X%02X%02X%02X%02X\r\n", bluefly_rf_adr_buf[0], bluefly_rf_adr_buf[1], bluefly_rf_adr_buf[2], bluefly_rf_adr_buf[3], bluefly_rf_adr_buf[4]); - - // Use LFSR to seed frequency hopping sequence after another - // divergence round - for (uint8_t i = 0; i < sizeof(lfsr); ++i) rand32_r(&lfsr, 0); - hopping_frequency_start = ((lfsr >> 8) % 47) + 2; - bluefly_binding_packet(); -} - static uint16_t BlueFly_setup() { - initialize_tx_id(); - + hopping_frequency_start = ((MProtocol_id >> 8) % 47) + 2; + bluefly_binding_packet(); bluefly_init(); - - if(IS_AUTOBIND_FLAG_on) { - counter = BIND_BlueFly_COUNT; -// PROTOCOL_SetBindState(BIND_BlueFly_COUNT * 10); //8 seconds binding time - } else { - counter = 0; - } + if(IS_AUTOBIND_FLAG_on) { bind_phase = BIND_BlueFly_COUNT; } else { bind_phase = 0; } return 1000; } diff --git a/Multiprotocol/Nrf24l01_fbl100.ino b/Multiprotocol/Nrf24l01_fbl100.ino new file mode 100644 index 0000000..f25e368 --- /dev/null +++ b/Multiprotocol/Nrf24l01_fbl100.ino @@ -0,0 +1,282 @@ +/* + This project is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or (at your option) any later version. + + Deviation is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. + + You should have received a copy of the GNU General Public License along with Deviation. If not, see . + + rewrite v977/v966 protocol to improve reliability + */ + +#if defined(FBL100_NRF24L01_INO) +#include "iface_nrf24l01.h" + +#define BIND_FBL_COUNT 800 +#define FBL_SIZE 5 +#define FREQUENCE_FBL_NUM 20 + +static uint8_t binding_fbl_adr_rf[5]; // fixed binding ids for all planes + +static uint8_t bind_fbl_buf_array[4][10]; + +static unsigned int fbl_data[8]; + + +// HiSky protocol uses TX id as an address for nRF24L01, and uses frequency hopping sequence +// which does not depend on this id and is passed explicitly in binding sequence. So we are free +// to generate this sequence as we wish. It should be in the range [02..77] +static void calc_fbl_channels() { + int idx = 0; + uint32_t rnd = MProtocol_id; + while (idx < FREQUENCE_FBL_NUM) { + int i; + int count_2_26 = 0, count_27_50 = 0, count_51_74 = 0; + rnd = rnd * 0x0019660D + 0x3C6EF35F; // Randomization + + // Use least-significant byte. 73 is prime, so channels 76..77 are unused + uint8_t next_ch = ((rnd >> 8) % 73) + 2; + // Keep the distance 2 between the channels - either odd or even + if (((next_ch ^ MProtocol_id) & 0x01 )== 0) { continue; } + // Check that it's not duplicate and spread uniformly + for (i = 0; i < idx; i++) { + if(hopping_frequency[i] == next_ch) { break; } + if(hopping_frequency[i] <= 26) { count_2_26++; } + else if (hopping_frequency[i] <= 50) { count_27_50++; } + else { count_51_74++; } + } + if (i != idx) { continue; } + if ((next_ch <= 26 && count_2_26 < 8) ||(next_ch >= 27 && next_ch <= 50 && count_27_50 < 8) ||(next_ch >= 51 && count_51_74 < 8)) { + hopping_frequency[idx++] = next_ch; + } + } +} + +static void fbl100_build_binding_packet(void) { + uint8_t i; + unsigned int sum; + uint8_t sum_l,sum_h; + + sum = 0; + for(i=0;i<5;i++) { sum += rx_tx_addr[i]; } + sum_l = (uint8_t)sum; + sum >>= 8; + sum_h = (uint8_t)sum; + bind_fbl_buf_array[0][0] = 0xff; + bind_fbl_buf_array[0][1] = 0xaa; + bind_fbl_buf_array[0][2] = 0x55; + for(i=3;i<8;i++) { bind_fbl_buf_array[0][i] = rx_tx_addr[i-3]; } + + for(i=1;i<4;i++) { + bind_fbl_buf_array[i][0] = sum_l; + bind_fbl_buf_array[i][1] = sum_h; + bind_fbl_buf_array[i][2] = i-1; + } + for(i=0;i<7;i++) { bind_fbl_buf_array[1][i+3] = hopping_frequency[i]; } + for(i=0;i<7;i++) { bind_fbl_buf_array[2][i+3] = hopping_frequency[i+7]; } + for(i=0;i<6;i++) { bind_fbl_buf_array[3][i+3] = hopping_frequency[i+14]; } + + binding_idx = 0; +} + +static void hp100_build_binding_packet(void) { + memcpy(packet, rx_tx_addr, 5); + packet[5] = hopping_frequency[0]; // start address + for (uint8_t i = 6; i < 12; i++) { packet[i] = 0x55; } +} + +static void config_nrf24l01() { + NRF24L01_Initialize(); + + NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable p0 rx + NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // 0:No Auto Acknoledgement; 1:Auto Acknoledgement + NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, packet_length); // fbl100/v922's packet size = 10, hp100 = 12 + // 2-bytes CRC, radio off + NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP)); + NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5-byte RX/TX address (byte -2) + NRF24L01_SetBitrate(sub_protocol == HP100? NRF24L01_BR_250K:NRF24L01_BR_1M); //hp100:250kbps; fbl100: 1Mbps + NRF24L01_SetPower(); + + NRF24L01_FlushTx(); + NRF24L01_FlushRx(); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); +} + +// FBL100 channel sequence: AILE ELEV THRO RUDD GEAR PITH, channel data value is from 0 to 1000 +static void fbl100_build_ch_data() { + uint32_t temp; + uint8_t i; + for (i = 0; i< 8; i++) { + temp = (uint32_t)Servo_data[i] * 500/PPM_MAX + 500; + if (i == 2) { temp = 1000 -temp; } // It is clear that fbl100's thro stick is made reversely,so I adjust it here on purposely + if (temp < 0) { fbl_data[i] = 0; } + else if (temp > 1000) { fbl_data[i] = 1000; } + else { fbl_data[i] = (unsigned int)temp; } + packet[i] = (uint8_t)fbl_data[i]; + } + + packet[8] = (uint8_t)((fbl_data[0]>>8)&0x0003); + packet[8] |= (uint8_t)((fbl_data[1]>>6)&0x000c); + packet[8] |= (uint8_t)((fbl_data[2]>>4)&0x0030); + packet[8] |= (uint8_t)((fbl_data[3]>>2)&0x00c0); + + packet[9] = (uint8_t)((fbl_data[4]>>8)&0x0003); + packet[9] |= (uint8_t)((fbl_data[5]>>6)&0x000c); + packet[9] |= (uint8_t)((fbl_data[6]>>4)&0x0030); + packet[9] |= (uint8_t)((fbl_data[7]>>2)&0x00c0); +} + +static void hp100_build_ch_data() { + uint32_t temp; + uint8_t i; + for (i = 0; i< 8; i++) { + temp = (uint32_t)Servo_data[i] * 300/PPM_MAX + 500; + if (temp < 0) { temp = 0; } + else if (temp > 1000) { temp = 1000; } + if (i == 3 || i == 5) { temp = 1000 -temp; } // hp100's rudd and pit channel are made reversely,so I adjust them on purposely + + fbl_data[i] = (unsigned int)temp; + packet[i] = (uint8_t)fbl_data[i]; + } + + packet[8] = (uint8_t)((fbl_data[0]>>8)&0x0003); + packet[8] |= (uint8_t)((fbl_data[1]>>6)&0x000c); + packet[8] |= (uint8_t)((fbl_data[2]>>4)&0x0030); + packet[8] |= (uint8_t)((fbl_data[3]>>2)&0x00c0); + + packet[9] = (uint8_t)((fbl_data[4]>>8)&0x0003); + packet[9] |= (uint8_t)((fbl_data[5]>>6)&0x000c); + packet[9] |= (uint8_t)((fbl_data[6]>>4)&0x0030); + packet[9] |= (uint8_t)((fbl_data[7]>>2)&0x00c0); + + unsigned char l, h, t; + l=h=0xff; + for(i=0; i<10; i++ ) { + h ^= packet[i]; + h ^= h>>4; + t = h; + h = l; + l = t; + t = (l<<4) | (l>>4); + h^=((t<<2) | (t>>6)) & 0x1f; + h^=t&0xf0; + l^=((t<<1) | (t>>7)) & 0xe0; + } + packet[10] = h; + packet[11] = l; +} + + +static uint16_t fbl100_cb() { + switch(phase) { + case 0: + fbl100_build_ch_data(); + break; + case 1: + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5); + NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no]); + hopping_frequency_no++; + if (hopping_frequency_no >= FREQUENCE_FBL_NUM) { hopping_frequency_no = 0; } + break; + case 2: + NRF24L01_FlushTx(); + NRF24L01_WritePayload(packet, packet_length); + break; + case 3: + break; + case 4: + if (bind_phase>0) { + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, binding_fbl_adr_rf, 5); + NRF24L01_WriteReg(NRF24L01_05_RF_CH, 81); + } + break; + case 5: + if (bind_phase >0) { + bind_phase--; + if (! bind_phase) { BIND_DONE; } // binding finished, change tx add + NRF24L01_FlushTx(); // must be invoked before NRF24L01_WritePayload() + NRF24L01_WritePayload(bind_fbl_buf_array[binding_idx], packet_length); + binding_idx++; + if (binding_idx >= 4) + binding_idx = 0; + } + break; + case 6: + break; + case 7: + NRF24L01_SetPower(); + break; + default: + break; + } + phase++; + if (phase >=9) { phase = 0; } // send 1 binding packet and 1 data packet per 9ms + return 1000; +} + +static uint16_t hp100_cb() { + switch(phase) { + case 0: + hp100_build_ch_data(); + break; + case 1: + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5); + NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[0] + hopping_frequency_no*2); + hopping_frequency_no++; + hopping_frequency_no %= 15; + NRF24L01_FlushTx(); + NRF24L01_WritePayload(packet, packet_length); + break; + case 2: + if(bind_phase>0) { hp100_build_binding_packet(); } + break; + case 3: + if (bind_phase>0) { + bind_phase--; + if (! bind_phase) { BIND_DONE; } + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, binding_fbl_adr_rf, 5); + NRF24L01_WriteReg(NRF24L01_05_RF_CH, 81); + NRF24L01_FlushTx(); + NRF24L01_WritePayload(packet, packet_length); + } + break; + case 4: + break; + case 5: + NRF24L01_SetPower(); + break; + default: + break; + } + phase++; + if (phase >= 6) { phase = 0; } // send 1 binding packet and 1 data packet per 10ms + return 1000; +} + +static uint8_t fbl_setup() { + calc_fbl_channels(); + + printf("FH Seq: "); + for (int i = 0; i < FREQUENCE_FBL_NUM; ++i) { printf("%d, ", hopping_frequency[i]); } + printf("\r\n"); + + // debut init + if (sub_protocol == HP100) { + packet_length = 12; + binding_fbl_adr_rf[0] = 0x32; binding_fbl_adr_rf[1] = 0xaa; binding_fbl_adr_rf[2] = 0x45; + binding_fbl_adr_rf[3] = 0x45; binding_fbl_adr_rf[4] = 0x78; + } else { + packet_length = 10; + binding_fbl_adr_rf[0] = 0x12; binding_fbl_adr_rf[1] = 0x23; binding_fbl_adr_rf[2] = 0x23; + binding_fbl_adr_rf[3] = 0x45; binding_fbl_adr_rf[4] = 0x78; + fbl100_build_binding_packet(); + } + config_nrf24l01(); + + if(IS_AUTOBIND_FLAG_on) { bind_phase = BIND_FBL_COUNT; } + else { bind_phase = 0; } + +// CLOCK_StartTimer(1000, sub_protocol == HP100?hp100_cb:fbl100_cb); +} +#endif \ No newline at end of file diff --git a/Multiprotocol/Nrf24l01_h377.ino b/Multiprotocol/Nrf24l01_h377.ino index e8feaf3..439178d 100644 --- a/Multiprotocol/Nrf24l01_h377.ino +++ b/Multiprotocol/Nrf24l01_h377.ino @@ -133,19 +133,19 @@ static uint16_t h377_cb() { if(counter1ms==1) { NRF24L01_FlushTx(); } //------------------------- else if(counter1ms==2) { - if (counter>0) { + if (bind_phase>0) { NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t *)binding_adr_rf, 5); NRF24L01_WriteReg(NRF24L01_05_RF_CH, binding_ch); } } else if(counter1ms==3) { - if (counter >0) { - counter--; - if (! counter) { BIND_DONE; } // binding finished, change tx add + if (bind_phase >0) { + bind_phase--; + if (! bind_phase) { BIND_DONE; } // binding finished, change tx add NRF24L01_WritePayload(bind_buf_array,10); } } - else if (counter1ms==4) { if (counter > 0) { NRF24L01_FlushTx(); }} + else if (counter1ms==4) { if (bind_phase > 0) { NRF24L01_FlushTx(); }} //------------------------- else if(counter1ms==5) { NRF24L01_SetPower(); } //------------------------- @@ -200,10 +200,10 @@ static uint16_t h377_setup() { h377_init(); if(IS_AUTOBIND_FLAG_on) { - counter = BIND_COUNT; + bind_phase = BIND_COUNT; BIND_IN_PROGRESS; } - else { counter = 0; } + else { bind_phase = 0; } return 1000; } diff --git a/Multiprotocol/Nrf24l01_ne260.ino b/Multiprotocol/Nrf24l01_ne260.ino index 32b5345..598c15b 100644 --- a/Multiprotocol/Nrf24l01_ne260.ino +++ b/Multiprotocol/Nrf24l01_ne260.ino @@ -162,7 +162,6 @@ uint8_t neChannel = 10; uint8_t neChannelOffset = 0; #define PACKET_NE_LENGTH 7 -static u32 bind_count; static uint16_t model_id = 0xA04A; uint8_t NE_ch[]={THROTTLE, RUDDER, ELEVATOR, AILERON, AUX1}; @@ -266,7 +265,6 @@ static uint16_t ne260_cb() { static uint16_t NE260_setup() { ne260_init(); - bind_count = 10000; state = NE260_BINDTX; return 10000; diff --git a/Multiprotocol/Nrf24l01_udi.ino b/Multiprotocol/Nrf24l01_udi.ino index ab8afa8..a8eac63 100644 --- a/Multiprotocol/Nrf24l01_udi.ino +++ b/Multiprotocol/Nrf24l01_udi.ino @@ -573,8 +573,7 @@ static uint16_t UDI_setup() packet_counter = 0; UDI_init(); phase = UDI_INIT2; - counter = BIND_UDI_COUNT; - + // observed on U839 TX set_tx_id(0x457C27); diff --git a/Multiprotocol/_Config.h b/Multiprotocol/_Config.h index 5df7e3b..e0d4da0 100644 --- a/Multiprotocol/_Config.h +++ b/Multiprotocol/_Config.h @@ -46,6 +46,8 @@ #define DSM2_CYRF6936_INO #endif #ifdef CC2500_INSTALLED + #define SKYARTEC_CC2500_INO + #define FRSKY_CC2500_INO #define FRSKYX_CC2500_INO #endif @@ -53,12 +55,12 @@ #define HM830_NRF24L01_INO #define CFlie_NRF24L01_INO #define H377_NRF24L01_INO - #define FY326_NRF24L01_INO #define ESKY150_NRF24L01_INO -// #define BlueFly_NRF24L01_INO //probleme gene id #define HonTai_NRF24L01_INO #define UDI_NRF24L01_INO #define NE260_NRF24L01_INO + #define BlueFly_NRF24L01_INO //probleme gene id + #define FBL100_NRF24L01_INO // finir id #define BAYANG_NRF24L01_INO #define CG023_NRF24L01_INO @@ -72,7 +74,8 @@ #define YD717_NRF24L01_INO #define MT99XX_NRF24L01_INO #define MJXQ_NRF24L01_INO -// #define SHENQI_NRF24L01_INO + #define SHENQI_NRF24L01_INO + #define FY326_NRF24L01_INO #endif //Update this table to set which protocol and all associated settings are called for the corresponding dial number @@ -80,10 +83,10 @@ const PPM_Parameters PPM_prot[15]= { // Dial Protocol Sub protocol RX_Num Power Auto Bind Option /* 1 */ {MODE_FLYSKY, Flysky , 0 , P_HIGH , AUTOBIND , 0 }, /* 2 */ {MODE_HUBSAN, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, -/* 3 */ {MODE_FRSKY , 0 , 0 , P_HIGH , NO_AUTOBIND , 0xD7 }, +/* 3 */ {MODE_FRSKY , 0 , 0 , P_HIGH , NO_AUTOBIND , 0xD7 }, // D7 fine tuning /* 4 */ {MODE_HISKY , Hisky , 0 , P_HIGH , NO_AUTOBIND , 0 }, /* 5 */ {MODE_V2X2 , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, -/* 6 */ {MODE_DSM2 , DSM2 , 0 , P_HIGH , NO_AUTOBIND , 0 }, +/* 6 */ {MODE_DSM2 , DSM2 , 0 , P_HIGH , NO_AUTOBIND , 6 }, // 6 channels @ 11ms /* 7 */ {MODE_DEVO , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, /* 8 */ {MODE_YD717 , YD717 , 0 , P_HIGH , NO_AUTOBIND , 0 }, /* 9 */ {MODE_KN , FEILUN , 0 , P_HIGH , AUTOBIND , 0 }, @@ -158,6 +161,9 @@ const PPM_Parameters PPM_prot[15]= { H26D MODE_SHENQI NONE + MODE_FY326 + FY326 + FY319 RX_Num value between 0 and 15 diff --git a/Multiprotocol/multiprotocol.h b/Multiprotocol/multiprotocol.h index b2b9e81..12883c3 100644 --- a/Multiprotocol/multiprotocol.h +++ b/Multiprotocol/multiprotocol.h @@ -29,12 +29,13 @@ enum PROTOCOLS MODE_J6PRO = 43, // =>CYRF6936 MODE_H377=44, // =>NRF24L01 MODE_WK2x01 = 45, // =>CYRF6936 - MODE_FY326=46, // =>NRF24L01 - MODE_ESKY150=47, // =>NRF24L01 - MODE_BlueFly=48, // =>NRF24L01 - MODE_HonTai=49, // =>NRF24L01 - MODE_UDI=50, // =>NRF24L01 - MODE_NE260=51, // =>NRF24L01 + MODE_ESKY150=46, // =>NRF24L01 + MODE_BlueFly=47, // =>NRF24L01 + MODE_HonTai=48, // =>NRF24L01 + MODE_UDI=49, // =>NRF24L01 + MODE_NE260=50, // =>NRF24L01 + MODE_FBL100=51, // =>NRF24L01 + MODE_SKYARTEC=52, // =>CC2500 MODE_SERIAL = 0, // Serial commands MODE_FLYSKY = 1, // =>A7105 @@ -55,7 +56,8 @@ enum PROTOCOLS MODE_ESKY = 16, // =>NRF24L01 MODE_MT99XX=17, // =>NRF24L01 MODE_MJXQ=18, // =>NRF24L01 - MODE_SHENQI=19 // =>NRF24L01 + MODE_SHENQI=19, // =>NRF24L01 + MODE_FY326=20 // =>NRF24L01 }; enum Flysky { @@ -133,12 +135,22 @@ enum FY326 FY326 = 0, FY319 = 1 }; +enum HONTAI +{ + HONTAI = 0, + JJRCX1 = 1 +}; enum UDI { U816_V1 = 0, U816_V2, U839_2014 }; +enum FBL100 +{ + FBL100 = 0, + HP100 +}; #define NONE 0 #define P_HIGH 1 @@ -332,7 +344,8 @@ enum NRF_POWER // CC2500 power enum CC2500_POWER { - CC2500_POWER_0 = 0xC5, // -12dbm + CC2500_POWER_0 = 0x50, // -30dbm + //CC2500_POWER_0 = 0xC5, // -12dbm CC2500_POWER_1 = 0x97, // -10dbm CC2500_POWER_2 = 0x6E, // -8dbm CC2500_POWER_3 = 0x7F, // -6dbm @@ -449,6 +462,7 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p -- MT99XX 17 MJXQ 18 SHENQI 19 + FY326 20 BindBit=> 0x80 1=Bind/0=No AutoBindBit=> 0x40 1=Yes /0=No RangeCheck=> 0x20 1=Yes /0=No @@ -500,6 +514,9 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p -- X600 1 X800 2 H26D 3 + sub_protocol==FY326 + FY326 0 + FY319 1 Power value => 0x80 0=High/1=Low Stream[3] = option_protocol; option_protocol value is -127..127 diff --git a/README.md b/README.md index 3c27e54..d223102 100644 --- a/README.md +++ b/README.md @@ -76,6 +76,12 @@ CH1|CH2|CH3|CH4 ---|---|---|--- A|E|T|R +##CC2500 RF Module +###SKYARTEC +CH1|CH2|CH3|CH4|CH5|CH6|CH7 +---|---|---|---|---|---|--- + ? | ? | ? | ? | ? | ? | ? + ##NRF24L01 RF Module ###BLUEFLY Autobind @@ -101,6 +107,16 @@ CH1|CH2|CH3|CH4 ---|---|---|--- A|E|T|R +###FBL100 +Autobind + +CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8 +---|---|---|---|---|---|---|--- + ? | ? | ? | ? | ? | ? | ? | ? + +####Sub_protocol HP100 +Same channels assignement as above. + ###Fy326 Autobind @@ -164,9 +180,9 @@ CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10 ---|---|---|---|---|---|---|---|---|--- A|E|T|R|FLIP 360|FLIP|VIDEO|LED|MODE 2 -####Sub_protocol U816 V1 (orange) -####Sub_protocol U816 V2 (red) -####Sub_protocol U816 (2014) +####Sub_protocol U816_V1 (orange) +####Sub_protocol U816_V2 (red) +####Sub_protocol U839_2014 Same channels assignement as above. diff --git a/sync.ffs_db b/sync.ffs_db index 357e3b141bb85277f93895d22856f5869a835bfe..e2cbf558cfcd9446cc3d759a2706394a8d36550a 100644 GIT binary patch delta 972 zcmV;-12g=p3(*pPMsj6kMrmwiQ+aM<00{s900RI301yBG06vV9iBd>QE{N*lXs%s- z){g@K00IC2004mj00000004||Z#W|Wgai0<@DlB{x>k@&TnT?}ri@t&Pm*IeH_{xl zVawN@{vzLx5FD&%nYw`}+=hokCkY5vARs+JjJ_OAr76mPdK}}gPaVV)H^%rYil4>z zkLq0I^FrFb+I(|~BYdO%1sBv-CMJ44j`E#u#2}`0V9^9S)IoOgI1z{3eH$pmrOgyG zxw8w(M)&XuA;5&{bjP%o9U{|CcJ&1mhA&u^gkzYtg_z1d-Gn|BgvTfq6O$}b6M$Hv zVzz84_0bQ1Dg#zdDD6VI%<_!THuP1}?u-|bEW5*`*1jxl*9mkhaVvF7pNNCxQX;ZP z-3V)2UsmG}PxjlfKS`3rIBQzCo@Dr_5*+60c99eG^6}8}vM3ev@>pJyg_h+2Wqs#J zOg)iM8B%#RkesA3Tdgn6ajy6RcA#}M7FIa?FI{YZIB6s5=)A9(^|-}x3@@s&|j;Rr837DqzoujQ(VWiHi$99E96yn{Rf;fONspf0077Y00000 z004MiWs_Y1Zy zgMvThd@KH~mpO6vBe4HyM)=RzKaGE`g#~YaZ>D+bLFGj)#4X@R%JV+(5kHQdTatgh zOWciJ!M8I1Ht} zDPEHM;~;<3(8~|*>y&{X~>Ezfh2A9WHh#~!o1hYa7t1cnrzWp36^ zjAum78t+>i&YqXOKjwLC;JYgODqkdiAFBK^Cso*6Q1*F)c?|Bokmt&A?;SApO6IR~ z{v4R>^1Fy~&L;S)r0-fLe+=7{_r?lC=lb?>TAX)>`x?fZVae0XEvV*y|3vu#!~Q4O u_Zjvr$=qz%huQ0t)26B4DeyhtG32jvPMPLWdOYMFSMWb$cQ_2O6_o|<_}tq7 delta 31 lcmca8w2E8Qttd6sEi)%IxH2!9fs=uOfeDB=?_r+G3ILc&2xI^N
  • Kddb?%DF2WIu|>igldK7L#GRX@9R*?}0aeMq;1D{2pCQnTzd znAJaMV1$&M#{AWgO;q~u5-VS&=;dW^1UQ#p=d@RPi;w@#D{|K-I#JOe1DYTlViI;O zVIAx;t=A#fip2oU9aWnJI|aCG*@tnLPX@v@A~HLJx_IS^W{=7p6i@3-#I!f(@M;=N z@obO}-M1U&4wsRC1!bFWtYkKwERBN$f5eWXkMF=?SU6&Gb1#46Dk^fA?vf=IEd302WEV|T82?hgQ# zHN@+aev%1IH`b&r`5R&AH4s;RM&jNobL-N7rY}DvGNw?*$k!g zFR-w0FHdv*eDx&3`Oh&l5OBD~qFik~kC#vR~#H@C*OkiBCR&fsaD;8sPKy zLaE4IFNuYFSFgYuDJIzqWjwaDriR#h>W0s#r{Onk?D*04=vs&Bj{q%SuEP>dqIc8; zF)S>=v3IlNFPi22kwh>dh?gkp?`UF0P&St@;FqH8?8TX{e;o)Z_Eyc~|0m`W64Nk{ zN`=Cn2biIDXIA)-IGjMd%ad?0=luV5&G6ea%;qEt^-6jpZs5VvVk&s zcgrIpnAvdpxxTiB7+0ReE`sweFz5(bHh8BITCbCNP1}@Rn3|V(d{bescb|?3VVSM_ zSSo&;T~N~2lzck)S7`?%#o=>IdL8$h@u{EmzRvWod8l zcg#}SfQ$!Zq$QIU7M>gH6!|@M=Jyq`zELiw7IYVC|8KRFff_#=4qUrb2H{=Yz_=cn zWztdJc-;+iWqhc6D)}rPB{%6YT zv@~X85kny52)0hzGefLrd>8*|C;QWd0yD9#3ao&1*V!8(YtlVADn``V^SPr%oPV^T z+4j#I_!ky$8xc_e>xRa}j0?<$odR{$DP-*!m!)NLVH}})X752%^gzy^QPZ6bI1>6N zScJFBfE@S_AY6(=m-MSV1looZ_f6i3XScjyORlv`&FQHEoaSIOZLu#7VtmO%cU-1V z#?JO=sZIZF;PWt|XWP%;O-c4ErA@uyzbQl&>ll;mZbMn5C+QVjqPH}f+{#o3yQ#R? zm9Kd?3RD7VIKKu_CozplFD4=Qygc)b<+LMxU=*qO5 zF)T-xik5~~vpXfV0zu$?cGKJz*`dlTj=mTKoo0Ot}Q6Bx#oj|s);b4)n8!xX{| zI#Bo@%6zvDEz*4)6!7d0mcXxj1MuE572s?9jYb9%*-nhTER(iTyWU!4ql6qOKb#A&$-4fkMt#F%`;rY4URFI z>XUJ3M5!24P;2KJU>5LDQ&FRyTWXe!%PkHmX3^gDk=JOT^CIBT_+TBQXb}fykV4N& z+XbQh3cI1S<+5*Z%!Pq!Zsol}Jhm_6yl1n?;fB!i+FFgv=@BIXUT0oU0gKvoWnHV} z3Bk3vV@Gk5$@A-PAYjAkZR>1Cy1RlFV%dF%->F%)Oo6M~=U+SV1= z^GMO_pB|-y<_v~m{dn*{TPsa4X=_`hS2RVhx{iqXywvnK7NwSoFEDo>+Z92Gp&sJ> z{s@#b1wGcfmBB-8oUH}b^WLoUxL(1)vf3-urjO5nboRN0yTkhNJ#ho(I19iX-he!V zkw;{_yfNHz=&6qft;CUr+GXK2Pa0}2kgJ~_w@q4Ac&lV1#xwP@MZsjM& zx1Mz;_?dDN5tdC}wHcqWBw3%xYQ%{NhtVKWQ~D)M(?&bycW)gSU+2!QUQ&ZvGNBb$2Htf&qYkh8l>i?s1Gy&*Bv;Ut0=F!dWx zT)!qpYpObGL>#)UuYI0zJk=wb9%s2zv$l%^#eXP|BEcyZ2Tsw@PE8s^nhn#oi#5y4>g7l)Zf1hMM zNsyqr=f2s;BT_=8YOw6l zm!5Vk=vOl1Tu&!N8KK-h$RZl?DM2O@-gsf9%siQ{VlTGGKNyz`!Lo=a$`MkF4VmT& zOF;cn)a~tvQ{Dz_n(;9Z!P-EZFVHn)X>e5%_Vu*7Pm@Hxn57 zZWY@QhPVbVVy^;m`U-Qf!ldG=k7UnxZ)Z-dFcKdK^eVZeVl%n-=gu{4$N5OXTc-dU z1>2Ug)5&`ljosl%+1djzti-rT_Rb$!>hO7wr_1XLTB4r*Mubp7u*711`r7 zNav`V#~r^I!1a2oFYn4NAq8)A2brA5++ z58KiE$FUyg3bKz<<-#t@P< z_2;6@An?;~o)C1AYe^(g+mH_R@3=G~wy}=G@w%*t3#X zS*}^dUkj|w03`hZBCUfK9UUN^i4djD6PpaMBe>vpUQBm+V8 zC?3$60oLHpysX1?MUGV1#>K^UKD$Dz`Jk7y0ram5EzH$Dq2bxl@@%G@@{{W`Kn2=C)3GW0r-s+OCnR%Jo%}g%vr%XWoKFyBCw#3x$rBOF9+- zk0b&1{~z!wu%it)AnGoWPet@J1FfzWN!YunO}z3bOumzFrdko*_DKxP?7|e+3(mK1 zVbjRahNB1H&yE70C!h}@Y@DvUPWB)-W-7|N3affQ)D#6F z>GsW7iYBDopAIv4paBkxEQ$netg*G^nGRxpQKiulVC)F?vlw-S&muoK*!^xJUQ8!b zVmZ1LrYj4^2ExcS0@2->P389G%{!av0FOT0t=(-GjE2Dzl0bV6)zrF1M91bHjQ9fp zC&=apS@98(CUXlt`|~UEvW>s^$n{l~{A5Gl2s6FjH}=I201$ZVh)g#x2$>L7zbb&NQGl}KUNUGIdd;PH`4Vk11?x+=bRA%ii#%lMjJVDd2veQe|`> z{;cbmv1oO$y*bA=F1Loz%TCZN1_QI!u+|$UUa|<7%trf}PH%&nUFk5t$B*y9O zQ>8u~#R#AKKo$lB{sv-;pm^2%ti8y6Jrq@1bHIbGUc+rXx?vxr>migqnFwG5V~WRR zh%+ziFLd6M4W_umw{r;UhL-t!BS^1qX!ir;{)lr6SUPX%H<}d(wPIf{*5|!%pzpu6 zFvTHRGE}gC0E>sIw<&v?@Qz3aljiZ744*9&1G2d9wHg$0`FqA~LeSD%X0H6hjLvld zm4@E@+@HO#;ToBTBTF|JmXwb}kJ-AOv;gnHGNmTf${F?%c9YG?J(aa8bU}}-wtg&w zUaVdVVniW;ns_9_sZOa~va5j>Yk~$^{%C5^#C--v){nxuf6-h(n+kOHU# zeSo>3X@(x8J)FeAKvxxwx5R`-lB@6GtoM!J&FeeBiTvl1v3u({j(%V5RX4|&*U5uD zSNJL@<_pGzRs4ymyas_k1Ck4{QNd22bOQ%Ox*A%Cz{iHNN}ngEx;69{xtG|aeQwI1 zt$f5uN#^As>KFHxQ9+Xa@2g9}t*h4)u? z{=p6+4@+4KunFFqw)HFF-ISXx_wet8VvnN!cJE%RB8gr)ux?#P-*jtUQ&PTTbQUqh zgwmn}W@XAjICbvusQ1W%k`mPjcgH!&d8zxn$dCx$Btx#$M0iY^(QKV?EO8FHR!k8@JX7YUSTW|N! z9_gMY*X1D&u06wlt^U{%2!gCKl&wSez+>?%?ljlz(l7^(wTz^NBgj0P`-bey)n0-! zr`U8prZ>DYg!Ut&>>M8$dZMR#-SF#pwG~b3p$KVEndn*1BP@g3ETN;vOugz-^O1Il4QHC8mF9Ay;h8J){oGc}fRN=&67VC&9k zt#CiVvNR`D!E;$d#c^RIv;Gfl#)XCy7i4+PWO%H{d{b@}Z@1NCLX51d#?5_g5K&%U zyC*&Egd^md=Xq4liEXHK|Bj-1)5gXYE5UoE0kbR9|^^x*=}GZLiWoNC$;E_fN46LMM|e* zW;;1PvtQiOxm+&5s=--!Z2jyd&Q8eCZ{vML$J1kDXB^VIPt=eft=ILCK;=Q*>*5=z z0F7LM0LQ$Z5i;5)t55?m+MWv|h$fJ_E=ODfwzY*G!d#O-jyo3_UvD0xg3C2s5zYe*Hmojq--ey7ILwQrHWp5S6jiH zkk{5e4kSU#cxfjI;u|*kGyCGE=0WZGD|GxQ7wx(O_SijJg1K^Tx*qa`ugh!K=S^Y` z#_ey^4#{DtR#47#Cf}aQ%Mg2hBA>)}^s#H|D<#F1U>>%_BG&0-j*8O^%HKPrz~CzI zPM*)9?zw4^eiFd=ekmrPYoOmy+Z20#mv5y8Dxk13Dqi z@@w{{C^!Q^sr)<*G@x>2T%OX9Mly5#8*lNoQt4Eao95J91N_e=8W) zIIxIi2BDq{59ixI7l5$>dov;}F*}W=J$+GI@ji;g?|U`S-nBi;7)mG5tjELUxCdRT z+f(_kF3N{`8MO91(Ax`J-CyBPMPq!8zwWB&Xp1BY9UQ9zOnCplDfks36#cEvr#yZL zfO3i01EIuoJ|x3I=kaK85S>w=IT#l}q*eG)T>S9V<4!tFki%6P|JT(FCpl zz+S+D^GXhp>+SfL`@zi0iLC;boV3!f%(Bww0<8)6s+-{4sV6rv)wd;sE48&Ui8~Q% zqc+V`f73%VXMOO1pA_!g-P%(Mn(HXhGT#w-S_Z>k+J5x0PLs1NW3PVIjjEg?&>qWy zRFamjZr*AA*2f7m&Njx9&PKTy8sa-TM_SkX21ig!1bE$MHO!BQy4KHBEdD`xz!|OX zg}Vp?2>vSL2!%Wa^O*_B6Ivg3tCUFjU{IvZGZ8VmsAhK%NQ`}9Q2VOt*q`ODZfjY@ z2EWF9jsI8W(#4!9hP~U8%GXCJiDa4g3s19qLOqAA3s_PBRY;1+q@1g(pc zqK^oieK3*ztXldRd-hxzBV=;R_w0_-cNv@wo84x+7vPwn{B|@yor0#mA}QaxuRa&f zoj|KKC3mwQ=zJqwKaNu)N|fI3Sf^CitP?7a{ao?3*5rlH`|H=IC5xdyyU9MdY!;Q7 zx~mQ@Cu{!yA?;}q8!e`=tA^YfsxLf@CWdR++eGx}4c^Pj;^#wkIXg!@A1Z3->AS|_KA6tW1ade@07@eUqdLPW99EoH|@M}jM<2QK0?7xspG7b za_GLM;MxtOSQW^oQq zHEsjrez(e&r=`LL3_6ZG1HZkTt0+Dn75=faxZovygK}yMxhp%>$ zZ|l3xTVGk_r9JyD*5Mag(TV}f7a|=MyNdmc3gblN52(A_wqHPNzYIVnQPkHvCOM^{ zwH~R%#I-T8mPT51!-7ie{>hxA;}`b=`_XE~d|Hnm;94gZ^oOhB__@zRJ8{4?oCpw}YMVbHe`pzG9b z%Dqb3AVOuX`|UN9^lHeup0EbirAIr1tW>;qA%Gb|q5DF_Bj@nKZyQ{|I7mkopfzZK zXWk4Y;wGoYo=(jc>Za#pe-!>mQ?2e)oGSxP($=0n!0XMztZ;kHwpx&RUS4ybAQ6_E zAW{6r=^_)y{f09?sQ757JyRqoy8|59CLhAVJ=;eb59`=24KhTfh91rbM{=n`sWFx(6er33yv)_vK{EiGIKtj zAJ#}lk!m43BGx4#T(D4sCUW?3Ef}i2eEmazuLK?x7ghrR;N|73p{i{hxl0`0@K_@>nKr)o|UA7@V6%zXTdr)euHs@Qq!$}r<9`%FMk?`+D+R`xx? zH589iKn^{c*3)u;8x2V@a4rlqbmYaclD=$8!8ut?<(N?m6uDmU)*UCE?LcVbl1ryL z_t0ow(5Cq_CRTKs9539pL#_yGR$Y{Hrx_-KtRtO5YArj^7Mz03C5S2pPf(cr-msyY zDbvTh5PqJ;R;yP1sB!~4C z0|VRzR~;IdabN0E4N>5Lr00@iXimnJ*>nc+%BFwqas|h~sLu_EN)D~AV=A|(IX~x* z@^v-LS#@c}+Zm_>e077H3HmhP!Vx{NdAns<)GF}YHLgAs?5Tltzt0$Sz3uy`DXlv7NZPiEA5KgP`Hvg*fw@(TA*7$+-u5WEXyaUt;ldf^~ z^N|5dCQRBP(9g0jRH_$`h|DzoLsWA;5O(f4VOo^Oq+(p@0^jm1MhOkGdM!8m=qCt- zl1wCN6SVoJTxU=ORzhsE*oWoa)VO$etf{LjU>+y79cQ!!vLcH@1&)Ny>~2**U=u#& zW*~{%s}4ip!o|CUX-v)<59=1AIjWh?ewg)8!ki!4_4kdgSY!pN){IYNo~@oNt(Bii z02JK~Ns8U{1_NUMxa7aj=-4Sh(S~87b{h|zt+dA|_9aslPJzM|r#7)6r>E4JE-n)X z9D}3*9~I2{GSp(@et|LpqLBH@UHxy_u_~^~se&w!!+W)aBGLg1Q$K~Vz=A_- zvJPy8NB}%jdpjIfPjIZRw4@CwDJD8HQ07^fSvKDeB+aoeD7qcO?nAu7rcwYzvT!=5 z36K>GjL83hp`vyPt)slt7c$|QIMy^5!~%y9s_^(Qu_qIeCyx^QlT0zLz-ANG0UNE2lCa!1naf%GH2R#XN-kBia{`SK=~9>Hi2?H_ zXLqtzf#SARNEXy*@$z7gx2b(g;X!~gkn zkxqHHf2Iy?p?rf$>lT3m>B#u(u11ncMtViLF$ng3YYFxt_>i>m;Fz?&Zn~-V^e!Cm zEsUR>;Pl>!bM?h&@o;*Q^Rd&7M42O_g!oW?vSpnEstlIOW;8n?X(q&_$+3Y$JDaJi zM=u!<7#IjRa^*zWr88`b@^4ozG(+&e9fq`A$-D|a7ZI z>JrabE)c1iJ9HlK+a}l(JB)izqV)pT+Hajw+GAOiCzg(9OYNsnOcr|*^ly$oaFXdY z8umTUsgX^guVfZDz+(cDDoZ;rE>RJ(yd&f#&m9CQVEw7K*hWOzPn;IZ20N^4o)rI1 z*BIaM9(jVI)|Si1mC)>kt+*z*&*AH`94F1%7A(ph-l36hSl*+t39Y4||B?Dmwomp_ zK@)mtuIcAjgA^;Ferog}aYPq0Ow~meyePXL5MuN%jGyJB+)OwJi@nd{p)8Fa2*(e< zN(b5N-if>s>cIz#$Ui&r1}2rStBKZTmRx3y+Q6;4+O)YKu?iTHdzC~s&<Tc!v59Rf?q4ysu9O@4LE{_je!r=IO;e4oaUR zNsPO}YYQv>=v(~paXy@a^QS7O5s%ZM?D>CMW1CUX(KF^*du~jAzR&yiBJkB#eP6Vm z2@w2yn{t`Xbr#&PC!3a5pUGOCotD1M$~EOvilaP;*q=f8M1YK6dT(dcgQyWfN$sU2 zqN^D(tXQ~O?vIyhsa}2!=x6Z;+fotLwNo^knQ&oZE&|~1?2?xGQLZz5HswkUV}5{S z$?oK3#~bXDJlrlqte$Xc5rVv47G-;gEV9ybGIly^bdNR* zYnc@KpyBoIyStGIUPb%$^S%1?8cZMn@hz<~KPXc}0Gn#$v3Qpr*KswB z_*5yDs~q|}OoY1IkNhvO9Ps6Pb>8cZx;wS;A2aulcz6(l7=2v~H&8<;0fCY;4efdn zd3RhbdAvt_SBio+I~a$h9sDTF>6QeN{A9Ei(CNByscG>8sb_on$gLAUB0YZwu(B8~ z+*23FD&y%avVbRbt{T(Xk(~AtW2}G=E>}Iv9NMHvduUrMmj3i^Nfk`pwA=RL-%|bi z%639|+(isZbE(LamMPF_o5`4sGi-D@QPI1t{>Q^kWR|OXu&~A*E1;i6(&GhbB+One zqoh)GdY>!Bs|2j7i~s^5p~{qGZQ8asr9{Pj9U4)Em;k~Dr-3z7#M;m6#7apA@3Hp( ze}&h3!o=-N;{P=%+V2!h0c<2F@3i}YJTIsx91O8B>hkQk9d0!{0#@Mm;u zi@T3|T!u)78X#ORn(n{J24)qT<_aW|rk+6PS(EN7zg_Q=olR)ek`&KW$}g!|#zAmp zyn{vpZRR)(ybMp%x91C1^98CoM}7dqV1nE18e0PrBln0fqKWeGq?+y^?^=gX67!!E zr)~gIt@~ApJj#XY=w`hFrAUTN=2;TBp=r!v043(W|0rHlX(qr%iVN%9Dp}e`HK4yg2T9ii`?!(r3W>KNvyn8=e=+JGA-2OO`(7LsF}a z{#FHptfENjql_4_lg0Vzt0X$xYKOgN`=O3K;L!gZO7zT#oW>93J#+WLK?SiC6Mi?J zJAsKcKc~VtFyUseGVW`C#yCd)d*KC3%o9z*ZQ|CGZfBxqW9UtN8r#btj)yw60=zG#IB3G!XPXs=HfC|%)3@D+A#OFS!5y^0NDl5DchtUG5 zOT!Ok5HW~YHCh3}DQSq@F?e~{+@=X8r1BM(yB0fr1ux zlJ#2@muBy#KG#-@2h7rwzXTIha`$YI@sEy!%IbR6FAwS5?pd4Nc3PPp(~(n09+z=e z<@;aor!LH6y?U8u_DebX3#vrhbDVG>y9Sk5%S&2CTideS(uBHMH<_Au3J z9IoMyo1gN=9>l*Avk=_*HDB0Ej^(7UQ-yZf)Lc8)3?i9ct9KvO3c<&RXMHhY-k&;qc9Ba_WM|$?M??XLgI(o zS%<>8B^Md?c7dr7+}*OW;ELEQ6|S=!U|2K<SU=%23k~@2#y(Bi+Y5N@UlFO zNXzMJO-p!lG?44pdanX7)8!5lcH{@F7RT%fUr8Ga$&t#>--`3t=%$Wt(!%#GJD+$S z_lr`T;@Ak9u4|2418nS6G+gIcigoO^wIP$PC2a6prQJWLcz>WxLchf;%AcBVP7fO= z>;UTdQ({8%TiQjC3{9yBuwo~Z?^N2tW#L@m&k3Z1<}BW!L?K;TKZ|x|M@%fOu>_DY z4EoqmXMxJqUJ9vLuqY0XzvWZES( z_42|JsbXJ?jnKgh`ouMn@Ew*%NwFgTrJ&@qFN+p=m^tHn$r-|K7=8Q_D3X0PBK4qD z?W?7h5&DCFhrR>Q{e>)lG#e8E<+)tpaf34Ph?LCwxWUg5^PthUww731UC=fxICi&w zWdkfujRU+{=acWrk*`RHK+l4PO{fREYYb+yXi%xntB;0QBC=w9IBwW~R10>lY|&h^ zjD*}SFrM!?6+KHQzTQG4ZpwimD4uT&hedL6rW5?yJ!)MQ~Nwc>`dD9e8te4QDVD8`nFepMaF?#@+Th(h)9oGO$ zYI85T!sy7eQ;HPk&S(T`+-H1N(I#G6AF~`;HAJ@5WTSfY_H_AzZwMYlm}&M=*GknF zSn6|RZ&7Y_`z4c>| z!Zo3nD(g63KBc@OG1|@@O6RG3Te}Iz%AH@A8iP}(2eI~XBPlu zk9H!=kC2iU4%SN0UWk`^V&H5zHgN$dhg)kFfSm(PQgEv_+9nL9eRFDFrHJ`PUyxSZ6^e4e~{IUmfViY(vRkp*?o z{tzY1Kl<~}^(BSABab4Cqrn!k)%Jlw03*38WCCu7wOvVUia}yiI`qRR7_%m?X8HD{ z-kHO{mj77wf0&3PjT8N0so4318?kwdSe5kXZlVce8!cuOtY1iw!*d;Hwq;05Mdhu7I<_0cR@yiMy7f03~+sE(TVXcxE!ezz~1 zyCBzlk|R#BLDX)t$J~p;uLRokMiblLu>G9R&=akp+5IgKqH-F3@rXT)nzG@~u8(=W zlNC#FhvWedIQyL#(xYGUn@&{XyZWw4C5-XIMVJ}j`fj4Pa8R_k+GrmyVp9{0!^!EB zI>7QT_--^G1G1rF9qk^F5N~oW1h z;w}pQ6-iZO{LtbHBT$SRi*^u7&*xA8-AD`0Qd4+AfOUs}4{W86mx=CD1HGE~A5rPP zek6q3cMz)&amU**R!L_4k`D>kkTLyGwt9`Ff&W}tfpWk3t^r0)aFXf;r|M_#43!oz zr7t`+P-6X8NdsJ+n3Ec#2)*hpPdQuNn80wz78@&rDZIgYX)pg3KTkLX-Gw5;6v`8# zPBk@#rsYacUBkIYvpdduIeyf?zymL-hw0wSqq}sxweCO!W_Yt5T&sLQ#uS2L=CfbR z$plQQlW61I80|J$h$k+$P>ifDxMO z_SY%ib()A87~Ht$&A|*KPR|iBV{Q(X9b+r2PwBg^=#-4MLCijML4fsnlh@bJ@v1?x zVo}4Z^&vfOHK)R=?vSC0$!usNGVc}pgOgw;NT67~AB&)aROM)CO2a5xTBK#o-N+id=CIH$i!qHdrhhwl9CZXm3fI}VaD8# zvdMYXm&g2S*g)r_A*MlG6p$DRO1&`>irCW8-Cmrqm&t7*o20gI(t?F5C9hVaPoSH` zp7=w@sfv@xbwt#fc8TP5xv3<#-mLpSP{=6f`EokT$#}&&o>YVmTX5cKh~rjMp8q*UAf#a5z3n^Lr?bZJN;$_KL-cbak8Sk0r{3qUkL|hgx1S zKh(vFY*L6a^}Sn&shPTOn1l!Rh-}kX?7|Dm6y)XYsR1b?otX;=Mwj^nCW;P5zyr&g zipYs1aT=Pa7gV=#(th+YqkUU`i2UodUdTtjf;#Jb^+4{1$Th7@wPMpDBA|X+4hUXb zGX1th+4}IPG!z<;U1fCVg=QxKNikLmXDu~Ca`=T2A+{_whvRVE30~(mZ!P)mzoAil zCfGc2lWa9v7CyzUrfDvw`!7)IBZd+tpThk>S@XhW48QQHb+_G#}IuytS2an1-|oN zyynL%SQh!QDm>$Jlc>-F{hHjmuOR zqpvQES^FzZUrPsNV!4U#y0d!c-KZDd8nfKNJS62&M>yodrmpR&wpdCtr6^T!J8$93 z@vY$R5|dTao5WBg?Pyv6S*LINmlS0>+qfrdlB(WFn@^hyYs=3q8@CE!9&mtt7ZrEr zpKHmS3MXo-1RA0z>}4o0OWZ|nb4pUX)PvOgVN-%-0pa3JWs#V=BeQm1FQ-U!l^>IF z$(`SF!{5EQSf~pF)1))hx>URM6J=SoA)ieVQU~>GczXB}m+=H?d^Z)f*7qk~l4a^S zDU&^S8g|gL`suI|_&?2e%|v9f)4o@DoXPF~Ar<2^gY#V5OL&A&()qMQZsi%L^bN=k z1!)vPB6h3=Zn8MNbFN_0F-n*wtW9Mog3`sD=NM-B$L71bTALTuP9=J~-R}pQ$#E<| zzj4RbIBPU<6+Koh%tgBVp7IaTDkU0|BtUBrEYp%+PZfL-%kefOteE(J^CnQltfsXq zl<1P;!Arp340b?apC1w~%(9(3eUdc#488 zsaZHLv1@S*{ad5%cT(6BUJS$!^ULc7Ovq}Z0*y<7sKg@Uss3ZC=*2=CA|d6{q{isJ zr5q)?AV$>P5spWu+Cfq#XSu?~ZU4%EonR|rC(dM4s20RYMAC%fT)RRLf zN@ZL6IvX0p<2WUKW0~%MJnyEK8O4pBa!OYe1|a3WXy`w?LGIYuIhv>u5knh@0i@)NTP=orZ=_Hd#aFXwh58-N8M`Fq|wF>Mv}UcbJ%hMYpSkI22h3zszDilGnd zJ&+Y{D^nyUTh3*DX0_;u@^{7-P0D_MOwpI&N|s<`9!zCI_uzeRlof0A7G`?Sy+C&L zXFbf!m{I>Tl@lx+ROeP}DO;Y_`2j)cH8Y28J0f)Lh8%3`7w+*`K`N@M+-!R^`?+4&Ag&y+ zVigj8#R9m{7KV0@;M;EZD}<;zykR8<1zxj=`8^SJRj^ta*E%PBa|soN-|FF)VDd={ zVG`QJI0om-Lsi>B2_7z-srEzP+H>@w` z3BX}VY%S_9P zgW0J+6@hoXQpuq-Ud3JC${?*T&K(!p_L`85RizT`M8su)Cl~!(HLB4 ztqkMmP_L$l$`M_N3~`5)LRSBgW0Hw5fA&plQqBG9w5D@AX4vxRmr0ISvmS91mM>=0 zb_bn_LI7EC=^W_8$~{jN4T6&|3Buxfdsevxpb0g7gt=NCnM+k(gT|si39VU7f%mzP zsrHIZ#=%_is(Gd->% zSFH$q9kxMkuMjABT{Q6VWWp2Jw3+oTxbscGZI_>H?3~D~=^X8Q-tdt9JBwgY!-l=4 zg8zlfII&o+gTa)9(Fpg#DhP4*B2DiskxEoiQk5R07Gi$}iJmQSKpeod=ChbLxuRAG zcxu=5x}W_)BYmXBIlfdsUB;H3^3b115gEX7b!G{1d>E4y?NFiloRiYR4ge2$*a+%d zlRQYUO38?NSIIf`MFn}edw7ohm2FW*(^2)E7uIw{#uF^u$h3GT9m-IU;PBAF-cm({ zwY1=>7-Vki6SBA9+FhSC5p-;lGvu0zBc@Q>OY~j{O;n7luI>~Eby>%*9ntU!c!J(M zw0O(~X1pyiVdwBSh=e}7pC{y&+C=+@tXe!qfsuqE$dHUWd6x#JQM4IXa*$lRN3vnp zaqxvvY)ozElqW!eL9S&|V0Ih?BHqf_tEW5_Mj}6zAY2Y-zL^X>!J0QeU6OJ@SZ&~A zviRda&c@L8;?%<)5JoML7y%TxHp+32)`avS-JxyAptUPcC#MPqVcO*^_U#%s=6J@Y zv@miZR-5325prjdb8q)>c}KedD+`B@yWEjv|HVw$g9Fka@$d)f?fi=? zN3e{3LU&MY!q5WN8B$P(#oVq`0B_QT*j!d^T>W+hQ*=R>tlQ8(4%u|qhBs@(7-al;b%Gt)`~2w_Xo<$@xgr%*)!7RWzKa)3XvY54J%K0p2WksC9;cG=U%O>{M)= zoS5fN2<$QSf-f{rWo&${f#6j|jLxOVP6z7$7iiJlWzrne=LOe}5O0U@m0{G9?DRtR z?6X3df`nY}ekPQooZl)Xmyd@IZhndgcijIq=-43v6>*K{8hjiljr2`}uiYRdtQXv! zIJS^Lf4!ymGepitPwl2eglA~Lw178NqkW8Y_fOHbSfgqvn~-fr7LDcexq?LblGXxH zC^+829lt+>pE>eDpOY=|>4@s!)NXCu|Z|y$Pv|^P9N4dW-YN!ST)j#{>U)cMCQ2R5i zL`@#GniK|vCRw-(bD${5H2NTo8yRhA4 z1`39vZCR#_&V|eLKu^9IOPORUsFb3*Ajns_z`tW$*tO&wSA0wrJ4-R5Fs^VlpHa~d zbePx`k7FFX+^l#^W}3IRCS8HJ09ChuxFH1}3eysoc)N}-G*AhqJVA%AU@qs;n%Ifvg5UzHQ?Fcf%Hv_x$eitie@3P&;zqh!2#d`ecqa-3 zYrEM=eU`Dv1s>|NqjCo|o81(~2Xx3hvS455E*yj>kCN)17t(2*bq;@?z-xITv#PU) zK|ZbBa2{OBxv#Pa#rW}o6-X#ReBpi#{gF8-Cv_65b|FHF#t1gOI06XM=RWgD7(HZ< z41a4Y@92<2gs#o!XBc@BctVK_~*qBn+ihIx-{^HBjWfM$%SS;JP?4x7iH*(+Uo z^H4|HaWF$hm;7Fz-nJAiB2D_6gstJC?Sv7aaUiBUoiCeUMzd7JvggYU=rqnNf7z|=_>1- zKz0A}wOyt&U9#z{2z!uNjMo@eMX9B}dqIHjjF$~e!p8!>RIsZ|7qU`$tO2ex?GQzc zLXD)uD=0w}qamoekp_** z`$~mVkaaB*kjGp=7y~t|n=wV9e1cJdsM9 z&6~FNRT@;y0N^22_8#4v0^o!)4>&JA6quId0U>hC3AWXZz?hZLGhBo*+E5YgBGdT2 zwWHvR&agnPgCc?cSOnfEX#Vj;!fU~ zU=X`&ie4?1B=4+e5;jL-M@PH?=wjFV%Y{D91%L3H9n5glWBK#bNffxw{CCk18SuvyoI|JYfqojI+H%t)sgqiC z-ZYZ2QneA8uQ>ZCIPUly0OR*30%w2`t&Ki&V!j<6q&jx!7`0Gv*Lw=NH946Yw;@f| zhFGD3XBW`UQP?XwI`SPtDXxMBzIHCX+H>>ty9ADiuDP;xVc9`?nMs-6(%w7Sk|GAA zz;CuldJJQmuWdBH{srkdt7^XW=QWAhW zDyu?kWRLNs?FcB zE^|rhhRRP>8Vk3s3GDL~?k`m(T0A@Wm@q>F?e`SQBUCZ}wS&A%o;W@Md}Hn-A^83% z<7csUladZ3v(W)1f&2RUfikN?SnFqL-`cX|s!Y4iors2!r?DI!^q$6%GN$cLM`D*P zb_E|4TZ%w9sJ4P0A;56vyUcJb$}=s*%FJmnl`f%YmScq^8cx4UpCc@0GF4V_s!6Nn zp*gBEq{p8! z0*67eQw7yUCF*5PbukpfLG$+4R;~_Qs+ymBHHK*1ve#H8!Ux7*Xc5uRk4@y9Z}~^<~WkO?$?27YGOyr46J`& z=tgJhqMUwJA+d4$p?J68%F#~r3r*C@J;IMa?O;S5V9Ezi;6-s|_ThX*LJB#@DisbM zi>ZxuPOl~^3xBYbT>WdS$|n#7YCAWs|8y1oGnedYtTqkQnpTh{X!{XK$ho z)0gR4F-=FB-=lz{GRN=$D)Gy&5d*$wzo5Ij@5-v-&R*J-d-m%1%#FO(B#vg0<+M!O zz(cEYXwnvqedwmFsD{u6M#R|sDeMInS(pCk-TZ-SG*TzLiP}*_A{}_T&eZ+EWJoP0 z%*<|5$E#CC)oNraZrY|MxQK{2v9D19O}c();^R{f*gbFBNlxCQ0#i>Dd~q?EubG6x z`CtR%@tP&K$^5RiM-=@O^-HYgWKj6|^k#{;VtmZmPc=B@i_O@5)yD^E#4U|>Rd{92 zo^rLZh0s+Bq#aTG;;QP)M14`VfHUM5>y02$rnd6FnBT1RRikEe!&IOCq)W*L3V!-Y z2s7=3{@f4zhp?HCSFWcKhd7^lDgmdNNMlO3oDfcmldjFs@y-87WknGi*@e0g-~^R$SA2vyYHL;F z@kC+8Taf(Sk@_c| znSV&f?85gk6|TuQ#}ecJ4pHWIN2&0bfcaF!k1}^gn5!KM;_g!b2+dFFXY|v=qLw?I z`MueXla}H}m!_NYCRSB%9C>q&8A*5F8K?QtH!Phy82Q~D$$Po$vikqy@Ag)+`$1;V z1dy`-(1Yb5I*>pp+&-p`IX_uBPd3qm*E!|n&Hs$(-(aP=!@;h&De68Rz6qT7?63;P zgMC1IR<-d5Nw`rI==NurL&;A}KI_=nh{`tCrYd~lgKBfDN+|@ET~UozW7MO)#FlF^ zx%cs+OFV(|fLLA2m+*;+RQ-S+I4ePu(oZ_dCi==!#?gaQ1EFId@qBlj+}B8^k1a&A z%rLrYirRGgPp~x>(R8ZQ0d6Z~LQIbtGwGQ|_vF!dQ|*k**D^HFYWP_kk6>zC`_2{( zfg-jHpVqtt4d6+?L16v;Nrk1Kww!WFsDfMXMY;L{mFa*sC|HuLwLp-EJb% zB2#Xg%f6s$_yBU^UhRI0-nn9z6__`@oM!ilEF7lIwj97_S}cx6@F&hkVuGq;GPx41 zQ}!uk9h0v<@`jd0i*rHA`AI=U& zve#kIZwj!X%{`7KS>)&QO*|4QvS<31w0GfNLVx;BqIp#2bI8#iV*Z{kNWU7x8w_mS zw+7l6b4Dk=y^T3*GJVe#;{4?l4J+m%ZeY-dJ|Y1sjd}NvScrAOp?F>?`XHyRNlcrM zHmy3A8&IuMXRj9~wFMtc(|7xBe`{#_O04(DP}kD2z6AuWcI5@?J%ajtLTrgt&%5&@ zTTK>mxZWGXtX(;=6jXhkhTWX+s#9ww(XYd78}b-`%0WV885Ns* z$`4nl*xK3zkfl#4^AFTml~%gIz5Jh{t|HH;gD32!bG5jK3V#bwIB#pji^*zXAb)6PLrCa}CK@qZP)dGu%vq z%JXTuU%yA#AjrpK4EP7_sauCnP1Bgd4mbWE)YvflWW8QxDky|2K8MjsCOFoerDHg= zFWhwVe(?bU^VE2Trx!u`%;N4DbJk7O($y_JK6fTHf``Th(_Xll2A94lr_V4$I+?8w zY13+kQK+5U2Jki1p7&eCQf+5B8DrWP1?v6~RuwEL;KQJVcbhP7s2r^%3X}XLa+eMr zZD!RL1-MAyeJtvy&qM+h_v|Pz^g|v>%pWQ61ko5HTX-S_^4>Ju>7cW_9w*aa9_K^)+#NKL#$U8^>b|=tJB#lv`Cu?N_Rrm#`Y3fagK|^=FnG<_T;s>EDr+B>a`~F0Ku6_H%y7B)KFAC zezR+VU4jpggT2Ji=X(|%WCXwSJZe!-b1Hs8{*P!@&@A)NTm$_k;anzka%YR3g}$`| zr{QBk8^?j8ZS$HelllDeZ0ysHgBgt*13ja4j~Cn!c+(?{jTPd(@uMfvfq_;%C0XC4 zJE?OAL|l&AvF#F0(K(@7?poH3guGPC2s#36ZsTnNPX+t=OK9u| z3C4%5jx-j7j027zPBV4F$dzhK0z08^bu@Mut7aHB;7N^aICUq%yk@O82ooZe@W<38l#F$^w?z(GDKpEU4T1{L z^B2X#s&TOV9`NN|{Kp~Hy=ifP*Ggl*KkUBAK`OiRANeJ=fl105;5{B zX%kk()a^D#(#uvZ^~=#;9elQ7lFqyB!fp%lD)cfAFxi8pxh7x+0ki{E9xJY)?pz$))g?U zC{j1n8?xPP-|~>3;#HM%U`KcCMSw6Bx2xQr{o8TAnrt*3XKuAdn7F3h>_?y2z}`A{ z6!_udD(%ZLtnC&JB<$^eneF!^l(_8&}R4d6#65r>}jd1JM68v7SK8d^+j02)p=tv9iz z*dBDJqI;TdeMh?XfY+c?u^%Dnj-K?E8PmCt-6JDD%NTfY(Y%1w@bZ{ExuxaSkwC76 z;_zzy%cCc`R}i|@MR~^L@gmIJSDY4%^nVrROmJ6JhSkj&{6p} zTYFu9ucpY+$)<8O2wHEiTKpDp&i-w#$PWgf`u{VKSpRE4yL0I`v%;%gw34Q38sLX z2KL+&+sR(HiW0n*I?Xx_K>r;@%~9pRev;wl$9AT4J#KB}talhkR1<+A!i?=QIS&0$dINl;m_URQB=$H2SeMmX#^-7&n+g$@A z)%lhH>7%({6N) zxOSqoLv3W0mW;@HuqObcf{oZQN3>1rAx2}nTpE|pAsnUYpVcD110fh10mERPo{8RW z_J&A6JbZp@AZpP#3KK|X!(hKNG$|e1mFzeS)Gbpw!_U|cnxa3hIkk<`3!FmWt_}Ui z^xQ^kth#zl-7fQgtP?%>05}mAJoFv=G&(57t6A;w4wmQq$XfVyD7*#JiGTGJgHW7i zv2A1ngK@-)aEO>@k(}I=rpQgMsz3~i$~Tr%r@|0y8>{x z>dB6e+hV_E%NujicUziQRuP+OeEhNW;G@39C)YwOn9zlaKIg31#>|(JeHJ;jG;}nb zHc4H*NG6uuzmbL+rB^QPEY(g~%f~T{+jm$^uno>Qw)~v|I}zNTPGJ43azuhY-)^iV`_yr%*dRKR@xlrfvpGqy1&LaID@>duqll=yV) zEi3PS_B}W`Dw%vSR_yv3+8=@aZ1jY+eSue3EsNm(MWV~K`#w8Or(lTB(lCM6lA3r& z?Db#I2-xG~k_$AL*y;?G%QpHuWRi(iD2s~g-~%z|In@r~an`L$zm;;t?rFFVhv29$ z++23Sj{$R^n8*VLbZc!|d<)J^leZ9#?Ay04cnO03g=1JH{gQ#+WYG)$X!{F!bwH&r zJzs@VacW~BrAVJ39&7a-M;L#6hxRwZ!wOj(;`(tz56LxXLRpKrH2ILenj9Ufy??6 z3t;HNH#GFvfh}t^S~o7>5-nMa<7#MdOB_<~4o6bZeQd@(r4&P(@J&#`3{d7j`NMF5FIArYM#{3u2JC$d)4NT$iEOOS;HxQTPZjyKBNyObrHoxqD z2CG!4TTr!)7Z`HOFYW7NmL!RE)yk1wEL)XVoo%h3-NQGLZ<@5D;mv{AtP{2bnZ3rj zJb~%+`rECR9jKc%-zrmK3d>ZXT(&@})hyNc#~?`tWC+C*+H*xy_4%jrfk|i4=5tdi zipIx=GE#a1Txl9ZX90ss4j$w*`e~2)@#0VzB;QRzXSUP)oNDm1{x>)T=6~vx-XP;K zKIcGw7IcCd8`edrI=*non{T}qRg`0Yrbz3)@ZN{(Nr*-7@T^E|l&Y30Q|^;E%FTlZ zy31X1Eok1OQTK9bnsF6_o*>OLPVFO`JR9o~I^xiCiS(~QnzI#$u6k=!Qliacc-AHg zAUo`)I-4C@^4;-x6B@rGQ{y`V{I@@%e#I>#@U$KA54rIZ7O2n|ZMa2cwYSK#7ho@! zOiU&MwkIGxM%xV%2Q}L8f|d)PAI^RN=fE>`;}hL^mCr*sX3tjl1iMcn#6!$mZr}|6 zO$pm4{P!{KP|cTteZM$GN~;*Ng56I}DK_viy|0dUF#-=K=*VzW#+dg& zV7yJ%=1IgtfSS=#d}nr#a*3q5#+r5C*Y-E8V{K+sFKpt|s$35iPUQi$hdEJ{I6#6j zHiWYk!ms*AWtBrwl6l_1sGd)F>~>%RER#68E^93&Eb}ayyyqk|)3GR&;W)3d_Njy{ z5+l33x8jglXiatn@Qj~JeOWK#Q2j+qXK87#xV}^hr?op>`>Ys-;E-T=$-syJooW<6 zU@-~0%|rB$JRhRJ8+fHTj-KCp&TBoLMI430$!?UuNUIZ~AR7Iu60Qlj7qCS_TO%x#7JF^$?6#3W zd8cg0Poj16(!(}f1I@)J3MWEH<8J8}fo3)yar2)*n8e5cx{dw zBM<^T52f;W5Mnj30+Es#LDqGxfICIL|0V|n39((%I(26SEyp0bkPEL^x!xU;ILvMFIoWh?yg}J>dAF0 z2c?}&jGbkOHr4L%_Yo*uLGlP5tWvlGA^zt`WqXT0d&a!Z81QJ#I)x}?gX-_~``4Nf z;$Ub(1Xi=If>@^RX_N*k_SQr!o05q#sHkC?E6808OXE|s$x^G5j@GqqX`b&ALRUJy zAAyS}D3Ye{;A4X^L`O7;rGY(O^vO_qatFdm^tn4Acz_}#KR8psB9j7q6+kBan^Z&J zgbR!LaM@gEY^odz&i+w)L{mqoA!BQ?vz!!adDl=qdJo0TC)AV%hi(gg(=ewRj^E&U*f{*%KR{fnkwu2BXrh)sLYQEKc$tXzens^cNwN5vY zM;t_ynKL=c=g|~cgB@-oMv$R(cxsxtR}gh6ot?kIH52~;4HWB z;Q8H4yHgGF*yH$lT5$h@hAs-98D81t5C1N!?4e;dfTJW5D+(IupoFCdgRCony-_+6 zt&<~!$S^nIJSz?j#9ohmTuo9-bA*gSwb=Ed_Rl$Q74?y*wg3jTQkFdGMYTXMg|au* z65<`6N_*zd)4bCa+@F-l=wm0!aH6PR0jGlLax~i}6esE`YlqXG-j&rozqGC;a;sG*Ex=)SZCgXXayi&;8k@pX zocnA~RduPP>}7hn0ihMp#l-#4ATgk!LpVZ{Kkb7ghImtlSF?F=FEcJPS7%NMJpFl% z5lZr1RB(@W^t&j*W)-8-P|$?ZI`KB_Kyv-W5s^=ZX;QjHYbiKwD^kHlgmK)D%L~S~t4a_)EU6E=xTx zof>CB;i9RKn?O#>d7BR!jFrzrSahEGha4QQlq$H4QdvAa^8whTF)Oj%S5{`_u(nYr zCtj2VdK533fvG1anFz(yg4n5`PP)yEN34n;h~}IUFc@3r=}LX+NTqv*5VLSf3|Z<0 zc`gGpDaTYsREdR^J^>ld(fLENAcXZ8ChOZl;0cv%RhcDPjQC~1kfz_6hN=g%uVOZLNFz{xUaV+UYkVX}D#%u#L z#vNi1hWO}9AaSws7X?HT9Pvz^Ipxckbgv2Qad8iLivfxnCz0RuX9OyZ@+f2*q$K+P z!yy#cUcz&u)4sRJ1CD*YZ?9I~!@nR(g7Mw?n6d1qi_w~EW^eodPZa%XsYisKP7~Kd z!nfX!;unhv;NM3=IMb&HGCbzI%d6I?zAz=#l0iFm#Us%&p}ivs-K&^=3H;esZ<dfOHdKk_~hLD_Y<3|Gtnfwg)m%E-@{I;pP`(COL4*Fc~KKHk_N z5!PARfNHgbk%I1wq!V>-AwI?t(;OSbN@k1^`yc~I@-Xl%_=)wE?ps?7Q~tC8s-v{S zX#b3gVU@)I9l7HXpBdgBKO-};nTCrpO03tViZt-L(|)&xbjS_A7IB;ctP-J>m{287J8>wo1^!9U zj^kW{UQ@ly4)Jf^Qv+RdM4Tzt+U1Cn1B`wK`Qzga*IZ1MNMr*Mnb4oi^M_srD^Ad5 zbIk1cj7Z2G^DhRC&5mqX&5eb_e`wvRa7- zGf1y&Bu(NHE_0H#-k!;`gIw}}h~)eDTO`D3T`}F|?Drzb$ZIow5J;@mdTN>^!*nXPD|K@x)1 zHCq)W0bIkl$SGpuA4)BGY;=5=A35^pFt_4&nuy~*HOpS>GA2bMv6k6zb*H8wO^(a zJ+?>)-3@q*Bq^M0aT63e3y=cTMpeLoHKqB!qr8d^(3RGVfc9VY#WN}_Lnkv)ylMG* zFl4{C`A{d7pZ&;tJ~PjMD<7BZ5HQGajsJR7zH?R?5|d~p`wK~^TodKed{ddsd#6tX zS!-c&M!F}R;5>1DQgkgVmPVKWLMbw17c@8JN(t&AUUu1Q*Dam;6fUIoFqlp2HvYeX zWBkfO%KJSIoBh#G_55p(1(0QerKCO^J0R6LbUc#ps{nFUprp&L(IC-HaF*Nx1cz#n)WSWZ;dt-!arqbw_hX08HBn|&4xA{q7aj&w&L(=ePku_KyzS}S3fx39 z1hAc#6BHdqLpw3kJ|~%aa)0npQkqcEa*W2XbS)+ZcK%fPXAU>%Q1T3_k-~qAkt#>X z^eF!1Zz|SakU=;W%^lL4*HxMp_(=D`s6r^(?Kv`p9KPvvX%coO1dM339908ES3}H( zNG?IpI4{4n$%V|h{}aPhao);oZ+(Ck;@bVr0h80H%78aJrSfQKd4YAe2ju4OoJ>+a zv}hDMiK}9i6@7p4xY;}MFGx6l$)3c0o#ohdccd$2FWJ~rLqU)dt(brlbPgJajk5;# zHut1z2*Y~}^q7>E9sq+Cp|zW6Zt;12Zjs&#hk6QvgJfE{+j~zMr&V2bnuN60F)F!< z^v&iBFY0}Ph3gbMmviYF3s{YXbDL+H+HxFV+P)^4(h%IO&zmW4HWFbby)FXo`C0@I zeHKR=Si{1OLjfu#iMMfO@?d4IIesCfb1*0D_G8*KB03jm;`fJGfNz684i$JE)}?dG zqNpUe3&{lA9N} zDWB2Qj`GDX5n`OQ7h;w>MkRRA z3(Q0NdBe;g8h%p=Gr4F8a_?HE+L? z&(jFp-)@`{s`JAoo_zYq?Z7B7O{|CqYCh5X@f`i}1K!n`1PFAlH{nE*5@Sckua$&s za4}J=>DDQIk8c&{%)$Xpq2%Gy+Zf^bEhuk#RA;-|V2E=f zDcE#hSIRDG`Ai=*Akk0?JB}sK|u~e6Ho}08I`)!q_3k zT{Y}iZ2{$MT-R^xd#k0kD?1V~$Jx$!yHK`ofUsi93G7;voY+VRW4z1sK9p1nJ`6SCoJQ9n8Kf^L2rSuiaq?$956#2V-_{swjVB8$L2}H+&qvG zCMjZ@iz$GWAP)sVLFU8e$bi8;G$+TLB&}^|8Yg*hpGg=9%>M}(@F0a96qHL^p&!wE z*?(vmPLL6Zg_=TrJTs1O*1m`f4=N9iR<2v2HWt>lJgpCrpA!jDi|1eM8}ErDF7B!J`^2CN}BFLU< zjYsOE^AO`_s1dZ)Rj@~a&p!PC+G)9Bx)`qjyRxdMeWkx&$SV~ic|+PmG_8OW5f#~iUCkp82xD`-iu#7rq zr|dn7es{pwYANp*w=VTJo5%bZ*P1Lj2L2<3OVcz~*4jUVPX) zEwcs>qF{H+^KxGcoh$mPfevzv^Bd2-M(*=`zIMa^#mxhE0e0vicyr*22%u=W5778= zZ#31)aL*H@t|gDm%tkp|!iU9c-MZj40fygt1QF*~7j>VGRbVx7Z9eSeABqfrU)G|I;bt%tsg9&ui5cJXvG7YLXFV~n zZO?s@#2onyY+Ge^j=3#U$?Gt$4h?8Mt7Z+0$>q4Zf9$5BIxvQN7W367%qrFkCLz>U zV|L?zX&H*%Hk0LbR;XIw04hsYN1w{h->}~iYEAIi7~j89a6OQ)o@}}2_L$d76|ebF zP#5@nq$cUhl?Fo^6;SDcT3RzbXE|4$=zyiHsxqg`S;wyUk~P$!AKSGAtJ|p zok@%fP(cu^uNCTG6<<3juLgS)T1f`#dvp@br3g|U0c+UFl`X7X4~Dj+zD~^AmVK{r zrAAknt<_(ZF))p{r8SHcDeU|R-{}&pC-9?gqxPqv1?VIle*-RTO6P}(EZ%iTOnZ)Hz_DcU@RniL<&SR6dgYym%a*ttH%H zi!ExgP<9CwT&db4)Vsg3LZ;&8@m)lCjup-Od#j($2gqwGp)vm9+xW4mSWZK}FXTlR z$EU+~CaaV|+sz~}CEcs()DJI{5W@A0xVFM{mQ||Va6pCged<;U{bPs9M7%GR(D7L5icD9%@3%VrfvrvcwE(i`;n zicTH;!|!)rNtaGKwr9DGj~|G$B+*2}p+0Rdl@m~D-Ry!P^aSEZ+B%#hkl6~M&9gL_ z{B4mxd!^AGODx-eP#N*f^lqKb@f|zB0#tn;He%#wNnL{(u$xY~ zPhgiLQPpfb`im6z&h_l~s*bN1Ug&i4L&Z5x6seVI;rp&xB;lOmjxtq1iZbkOKozRI z%J8$t5I!<1n;x)~5YbDeVoJsF-p9vp%esz{#r1F`V+0$?8nc1a0A9b?*+J$VUdT3_ z5vcau!HPTxvACu;GSAp&Cu+7Sp*E;b8wPnqyW{DQ3gx|tyd!)IL;JGwf8O_mNp`Zm z@}wMk(FywRYENo(c`QBpAvcA_6s)Rqj=BFCP%vHMS&B^x?(1e-X}E+NC8FFlYx(xi z`r6eH!38$?Y9CF$aV<0>Z~+gM=EOHK++jl7 zR|sC_1}C+?kHp2;?Ws^N0_AZF$Uev7F0UU+YLwIQs5|d-dDpeQRnc4iCt*hi3BQeinen!;sY+Kzhv5|t>3MZ_HFT$qAoQ5AL%R9e2u8Top1Mi*Qh@1ATo?0E8$_Z_hDYY=3DWDC>-|eBeeL#c^;MRnS(ru z=WZ9FZG}vwd*SA4IE!EON_Iy5C{CwC$W^-n>3c3d@(lP{FUaPn-!y~EYv*C0-V4eG zw}Vhz(L%jm+`da86sUNyZj*}S5l{+$qbRI0KkSt7NGO6=xL8?`>lm+TX};OI(yEFX zZy?^%8|JHeF=(mWIWcX^Miecd?z4@DKh5pdFJ3RJSvtw>=~)On13R2L`JQKHz5%$A z1_&(vp;L*SWgZN+>jHh{)rJGgh!rmvgZ;4(D56#M2uqaiDaFX2Qi;fsb zJ3031lQ2icC-Q2WB&*Rsb$(hj!E36*v)f7(+Nt@d39nlbF87241?vdA;o0J4;8HcU++E#ILff>J**5Tg{gHHgpu&&6H^3L-A@NR3Z z5=HaI@)6Hh?9HTTG~K$fiH(}LjTG{kUYBg3x)8Sr#*_IBS%#KiUL5;>5-TQ=fX|rE zafz=FbiJ&;0G)uJ=NcnBk*K1czKb*i+kPUlKL+OA#G`DWfa_0&G5A0e3d#+0K5OSp zLn~t4kZQ`{;GV=7T!nd=)m4Lj)wV#AMd&MKw6YG_c)sfDulf?y>|7&fn zRTTasgcTI@b5*cP-TGc5a9|{XsC=p9N7E>%R`lt+yy78_$*2>a^I*r#@{nvn*Hiv; z$O@lD+Fx)n?*BY^#0`JL(Wr7BilH@I&SV5+srf>1-^?CYy!fY7uPu6sBdr zBv7AN9fRSgsWEe<#2|Js=BN6Jx3V2{pCmAJsq(L9-lM=zY4QVU_Uvh*m}doBPr_$88s@waHk zQkA#vBEE4r+G0=rPaG6B%vHkqcjNC^Q_)ueoy^qC=U|lx#8m4LJY<{_A2QDA{|l`D z`e4AdNK1cw29HlH8Zgs_Q00O~)EXr90fwG&cnh?T(I-JfIr}8j}q=?gOnCu zbfW8;_^oiO?f9&`F4W-u`c?_|I@l;bUc0Js1q04hR(-|zTFrT~y`K1u7F=Y~gnw_^ zyhI{zp;pyo@6;jBA1q5wrNnwzWbi1VTHkID6uBt{pPXhnxHR?2XFu3oYuEZG`@b@F zGj$~#{KBX#qQeP$Aw3IrG$u9!x!xBd%T~2<#q^2<;g9hLG}di@ZBG7dFdpj$%?(vk zYThn26E?07J5Mf*95B|qG1Wy-uuBn&5nS5x0^h#3f^-|u%Qfh3I05v!VmYZIR*jik zqXXx7R$ZmT`}90Tao4FNH<|4+QoWEzq~E7iEEXmyfA;*{_Jw6up{(sbEStIh&U{;R zVU{Tt4z&VLMfEz|9`K@8hY69KJNMYsl5+V*kFM+}O--~g28w2OMi#}WPbt$}SqfZ_ zV`IO$D`ryWLDU-M_c!9H1@MD{`dV3viCex~Hmx3HC9%r`m&4@*6)k^Ez0YgUe1Fh9 zc1Ki1h1*83nVTG{9|hCiawK6?cwgb`e&E>KYNOaSx0D zdKghC!>GIM4RLTuC(53Et}^}E0P_}$z7fU0(CwS4Xi7~XD><@ZlOKxwF++3t#XTRU zADfEPz0y+l0fq!FeG7{FMYLt@a$PwGDzFBCIsE~FwTvmhXCR6+;BtH|G4M9j6W;js z#&?aM!1(&kU*esR%jzXdxzQ+R*Kt_7iF;6gLvKG?9Sfy&nlyHKM>DxkO_>UlT9<8~ z7jVDFAaPlugW3I&wik)!O6#oYV}!7KvLSCyycsPZQ{Zr$W+i-Y-i>G)g5EUzB6zJT za})Tn{sV6?*e6kU6er;ox!tPt7V5Pfc;GVwkcb<6u8qnW0@sA|Qe{~|1q!y5FVxFi zWec*;(UK$Y*#Q_<$-Yx|8iG|tLnL(b#@lPY$L}QIL89%T(v;huGPdvhh~JULfhFSA ztZE({50T}3Gqxf)!)mmVaDlZ6ZL`1L%kLsymQrF9kv#m&Y{@G{5To+qC(&`i>=w8Et6-S3bQ)M$hCUQ^r0i9e7%zkh!+7`13yfd_aC&Ltq;@k+F|{T$-kj3sSe}wPQq+H zh4TSCFeJZ6#Rb-rKY^lv->gHR#&2ZV^?)t*)MBs)o`i~AtnSAW_Ll@w7MYx9X=6|m zyT!aiDbAX&dF~Tdb+5Q>d_M4U);>%T_2P!YjM>k*uL7n-6JVBGSpzzJB!O_a>RaqTVqliBM-B)yRbO@ zen+=6s9jyWF2nuzu$H#b{6w27{WuPF5gbjjyG8*tb8`;5St-Z#UlpJN7|?7>i-TCz zj|s;MkLI6mjW%*$kQDZuuc+Cy=A~1nNwA>Ku13nCjjgs>EC`vLW_BeKJ%Rae0&2KB z#u7`Nd9T8T$B()s#s{IT*iq#^5tK^pJzj^CmQJQLD=E^iowYOaaP?DZN|P(gJ2t3S z%Xy+uo3VwFXuGNoJ z5EJ;dK=NbayCrL85|hI$FwY5|V&`EDpCcEO9;#yRwJN+b9BSpiP0E15b;!HZ=fR?& zcKqFA?*z85YJuNUa7znh$=|cMYW~*RkvEkLYD?`)1Wlpmbv}>SE~~0a`-*D~GLqUP z*kW^2QlNfYZK1M`ogOzv6zmwv^L(KnsCt^iqCF|r4@&UL^^vm#8F0x$JbFO+HxsnB zEE&k?6}IRG^}`}rQ4y?z<$(xZ+kjGcKzdc$T)L3N(5HD|uR5$UNud!~&1zs9&kjhK z>-DDt+oDq=kln~Fqo4Z;NK*$brj&Brb4R8Wk(uweRN`UL_^?Nn31EKATFm4l$=V(T z%lgYLam7HJN{!<=9p^)hs7B@uqZs{5gl>bPbpIIuWPmOm==!QiBXX%mnod@&3oIzG zU4}?z=>0xU+D2zv;|HtS)h6)5aK0_?l-^H;ljLg@($8GBHp_u9@W$uFc5Z#2aY?QX ziO1Am8m@YmN)^}Ic_K9pO-Z^Qc=#57*7!rp7>!_9{NC?`;>g`(foEfALgtDF?s)38 zIYlJ!rM<45n6;xO3fDaZ>_#(|idN_1Ri{QBZim^grDQKk_K_PZ8+KdivOAGe^&cC{ zjx&Iv2$0PnX7Wngk#44NL5w7%xy<8aa*luYirhMrxXAV&&K@-Z=Q{}rtitwh{Mqj7 zpLIGOyv=@tPlPQtd%u~0S)6^7e+{Uylm)D^O~uVs(1CuDV^}T{)k1`q2eJK$94R~$ zr6Ex+I53pq$u6V~DbbO;V>H_ZxPRkGyenb6g`Wr;C5?Zd^TSgmo6;?h#D3K3_9LNG zCxyZ+Yq{YgAnUR|5>%aY>LpDq7$+WH(5e7YTf;zKO0j~Pi`JY7p6}WjBgou#BM4nw zlsYXEcUg1IWU-yqh2R1sT2(Ali?2?Th2_-1fSg6I9trf1DXC!w%zUwvZ>HPXiVpqK zS$=y|kt>~)>x;5cs(6%rdbGEm@s)8ddXJq-r|O?e^E9;JfL=xMfOcMI3>7io+#1&( zAagV(>5RvWgc(!-51ZJCu2FKsU`i;zYt)o6nNSS1jT|LYlii<6T7Yl+6#q#6)VFxx z{&q+X%_0X9RaQr%PtX{3D8K}bOfiE2PcbWZ0L7PZq=tu3^dQh}9O;#5Z z-MR7yYSuD_ibNh5tdNn;)J}5O=$(1nb{A=qe~k#2$?y)=1X@)xCrMgOKFBC$)^ts# z&@^@pfkuH?rf<7+Fa@>gpwl|CnFl$e*yv=$7s{06dW#Qj{14^zelmuiHzz^7CB>C`Qu`E-2k#zxx#wIUS5B^0BFnu*Zdjo z9j{lh&D_DD^)}8fgb(~+YDO<}S#$}d(8B?cx^+0y^CixvEwfIz5vX!vjg}t-R-jyo z4u>6P@B4=Bkz>O2){Rld%mvl|I3pl(U z5>#VCDAkXu;u9iUVEhYR31rnb$JeL3Cw8UDXaa_ z(G%B*s%VpCSfkr&mwW*hQ>i@#1_K)3;q zUSC{O0H&^m!(wU3jKdq!RVrza#l73?ID2_kJ`SUJ`N6qx$}UC!6DJ=C`n{=TSEWyv zlZ#LK;pF!m=GxdZ^XhfP-s$YILdFXMoz3)Gn7?#2tl0_hie`Yt+^mwezI8Dwev?x8 zW;S8dD;&2}Y`!=zJ=73#n>!P9ZbXk>D)2rFsRoG3YvHUHbgV$Bm8jG#4RjCLsj_s!d-A5m`X$T>>K z7J_?ol-|3oU>fP;O%Nlhll%8n(8p~X5b(ZQZ39F!xzX5EVub9t7p`XVZ@n%{xOh<_ zHiMhxnTcrybV=OnRMjo!>~zi#`lI*?xIS;ZG7`v%LR6LOK-6Y#76{ko?4NA;0AHoW z4zV`aaWwAew4F@cJs!jwv2avCQKIzBoOYawGTfJs3Z^in;`z2(z0DvSBY!f`1)m;# ztS)+P@~gT?DBq`T)wuqX4{ks8$Rr@|Cu7M03O(h&$(%d&!hSx)HP{Q8Le*TXIY==> zhytPa1?Iwg_2V_m!)<7dS#?uF;SE`EN`JVz-;p(|hn9M%Pw%Tljyw3We&=5|w1dsL z{pWTqytP4lp;_Ct%xDUQNNHaQN5JZ*H-TO!M91;Rm2Q3OrwS<2IcY;V#2 zXl$v_ACMdF=l(YU{@`i^i-KQ`Gl&lzaZD6>>0*(t{>(P+16kZ&R4E~0&FDsDJ(Ze1 zbjMQ52cHWR+6(JuMto0IE{3!yB9PL)FX~V{IF?TOtbnGN^<1%*GL#)V&r?PP+rXMX z^O}PT<(JxT@!_r6>|i}x%U%!kL#wm7HN#DVG<>qhLdJd}g}PQ15TAAoF^Rnz<_vx^ z9)F>(0n>{uO^&=pMJ$eW^HZdc;%rL?I_^vhiy_JU;`=6H%+u} ze_O(Y*|^_i^2)FvCtIC`?+o6}kiTRdeR)BGz?wqx!plkt=97^!-yC>WZeEBf&=WMy zb^y2%6&MnK2Elo!PRV%GuHx)Y4ETa>2_^dwy1hZOR3HKq>f6u(a_>@{m)>AzGj>X^ zyL^bYVvJ>)fZ{9k8{M~pZXH017AmV;;W4nY;-WvE3+vF){_NkqKZH`kOB3wwgfwT2n%;Vz}M1U#%+opaFrYX+0!{vc|U}i`b^8jANVV#ZXs~8F^m&%FJ zvN%IoM}(&>opHT-$FqIqSl+#N=O&1CHY6*9kI>3vE4|m_!@8g^KYok7aU3nalJ4{`AXrbDaB~5~3zv$Q^ zLXnQ9Lk5TWkW7N*Q)PZ7G=&;XO!8%~I>n80GixckkO)fURawjmB-wPV``Z&5+aKEk zZ892;x6g4n5;us;5fv|DDjHjeI2PJ02#H$V9M4j_UH<=*uoN=s1-Npoo1C#=*Ituu z{&Jfu1To{raNTW_wOU$vMzc~J!CSnjswYC4myqxbUWxZwk(|)0flO%u%B&~ZEZbha zE7Af>W>H~xe)Pf%f{w%lU=OD;Z41oo;v|zKku|~s z+E9jhu^rm!I-vj=srShCb$kV3&m~p7Lk_uLR3j{QpswP@L@6-(1{#f_5LJ}0rcJL!!! z%8}(|%q{T!tQ*_p(@^O`(zmkxyYFz&t+0QS+CkPz2Tz+sq^ROsy&=Ac@kU@`QKWxq z4{?{BQgDWiVUQdtqz_diBdwc}eA&{0j?aNIhcn&jgJ-WMt2PLX^<=Hvw-nI-PMTiUQlcAs67}q7#?X$Bp!k8Tv?xr9_@qk^>&6!2n2)djlt{VU6jh@4|Um3k4uORadY*r zYC8<_t+4Wb_Tn{$*Ry!C=SSsd?eqK@OHMmRcp}Qs9;P}N(XD2)0{((oXyyk~Ofa<3 zhf^02!DQyDAo2YaQzmzIEUPo1d)F49D>SM-w}sGtXkg2)f@nx*Xxq$C`Xh1yfyS&n zDGP6i@wFmuU5!@v{3`yE6}6zjOregzp|}7?z;&l?m?9^*>u~dK#VK(t*OGY@!z$wz z&l6a#Veo?6>eyYvA}JVm$Ti@ot4ng7Pncl3w&?(!h@K4lEhxfoH7W_k^b>SPwc_MT z`PD^uxu;Yv4r09S0%;DUJJBjdTji2c_N>?wYHP65-2(_bOjImO-*2!3U=KCZVn_Wo zWv)7Xyw{X=w_`N%t}1x*)-2ROmpoqvI4ngRnOJG{(8S;tA^!hzGuR(VhH)!Fgh!dMfX&Bb$#s!_y|7`sn0O=8P8OaE;*M_6+@fFxl^$0JZuX^V5 zEWXhJf?)4a0Jq+rsA{$e^MbQ<^;dbbnxf$a*Qu^kd`3C|nOeEPd^frrms@qsT|b5aWv4oaJYY&5-Q;5v z1;671dZ5uf({4r*_ki1~mp(I?RO#@DY=gfr)1p6a6nTod_ZfyyzrEYxkT5Zpi{~&~ z62DSKFzZJxWX{r2X$#KjQdNpXaV0h!qS!dhQT z=Q{=y!Gn8#i&AcZrfSf41Cu7Z~XYxNoi zSjM)!hTk5$>#FC%*b-C^i%sT9{hx9$l-)jTf%5Z#9uLTG4Aq=S%kHXL#)G`yz>du3 zO^@tJR=f0UhS-_n4#*l~Kg2#6tZ@-^14;6+2O!XgvBt_1wKQgFe|R&RcqJ5HbWCpgR_%2_ZFoCZHiDuTqJyjW@SQ?zLDmKv=$WbZ~ zMRoPrgqpp(-Z~%Ib;1vw`(p-95y^c9TPw=>?=prcPc0gn_({b#GlVSa_>j*+mU(_v z1lM!fnvF3bbDY=ddyPUH!2U1vK3wP~778&K65oY{sBV||UqDBt0z z=c;8KQXz*0KTu1!K08`SDP$o_g?!U{e-wNj!YGD9-Kz>}T%rq_9i9U)Lr?iYl)cDY zLVe?*_fR~r@s&NgJCEMldW)&-e#aW522ZCu{#S^*nrMQzf?6}@jMCYW02-xNF8RTR z!V{ZAL3rrCkn^nECvQ;5=pl)zTa<2NrO_pZzJ31~Wl@Sx*SqlCgkubP6l*b<_ra>o zeo}twm^b$ukYc}IkyTUupoZvwr>FuiP8qar=6h7syOE}rK&ZNDk+U?=>(MpLCM=ZOgEp@6c}sp$dcWTr3bl1k50{P z69P5>P{57I?~YJSFMC^~c2N>{iA_&ts4`hsO}ZR22dd_Kuq~jpQC>Y`VN2NdKuv6} zegktyYmrN$+8Y)c;S>jU3vG>B>(46~JTllk73?<9@d2-Vd;oqT7b%GF*b$E$`voWt zB6T=acWjxV+l%8``m_n1DzY!%?cp((A49QEHi1?dVr}90x8C*|TmwJQFw{D^p*b)q zMKf}3P&PPICR#hMl6K!*8${7sBWG3uewtgl!M5(LX4$O`KvFeEI@M<&Qe0P0N^iUW zFf%jWt^vr+(qib0NZD5_$4wNy6+f;tqQ6AU8}E?dm+e;)DQ23Gm$#FR$bDlY|oyfWcB%t_lH?J4#3lEo4P?NV9z`tiM z+Hv?pUS*c;t;3W8w$?=m~gb3u>HJM6A*c#C3E{auGG_JQDpiCoYzE>r?t?P48aA z`B(V2nC?cid_PBJpm`BF~$;0$dmYjBtpzM1ui?^}i$ zf0Gev^Cb+3UMzd~R}3ii0VOw=jmN=MljO)M`BQqr@s1Rb5N8rkz!-DUZk8-JVnkqE zy}k)Xhwn$JMc^*m6()O>RJFB$cWU|c$24?%#PCAk_7-*bAo(u+wBgRVo4^r33N*+6 zz3MT%LC<%~t>22aGUzm?sOwIP)7bzFW&S)?l2q34XWjbNrD2sbPhjowFc~bnZx-7V z9onFg9u>P^HYs^( zE0CcD#qwfR9Mx`6v-b16tp+&cus)0^dg6<{Ry8b*4^b?YLddM3f37-Cat-pZ+2+O) zQjjKs(ed<>DC4ZD#ZsPIvi1e(i0n&@N4V{(_17Vn)fF~+Gk7S5;#Pzu&HC-OwUD?M z_T3WMT?7_~oI$_ep|MIAlYq1j7Pi_qd9`R&L6*3mWWtQJa5-w^MoR+w$@@o3(Vt~q z5=R+|E*3-*$Ik}{_ zb~Rg6yX3nJqtUO(W`WYH!R(xUBI-Y)i!7J;ek~@!lUfbOONr|x+R^Jz zmLiK>=4^iZwP2Z`+4@ZAjv?nzP%mjRIgI(0rDw>L4l;`?B`^L7)2fDey$taqTw6Ok zyZuz!BYi%VBi%Wx{f@r0k+oY$#Te!emSJhzP*29=swyylEK4t{OyTCyb3D-|ilFzm?aoIXNo zqj{OI0osXA7RU%MKMYZCG@wujalEiW$W~c*- zaU=`-`u4v^s4nAdp^I3T)JAE#Qbfx|Al*vL#ncE_8VX*yMSEiLcq*;8WOZ<_?4eXNqx$Q<`MxcQ(7qs%s2p#Ujcp*rBjToFE2_K}s9<}ROcyK~5w!+% zbTZ+1zRQcJ@;0cAmmX3~@8utpXgrN*gv7$-86*rzJJ^pewNjha0@t)6ZYbJbZY=l` z{?-;R>fobl-r8*J+t}o22|>l`+D$}4%?1bSMA=}vno6>0wB9CL^ZYf_{O%S-eg-VR z*Km&A>TMUi#6lk;2PQ+)iy3C&2>@RZMK{fvgNuS{?HWYwB(9xo`GtDt2Fif9d4{WB zT=f(y4oED^AaM?7EnzxZ`^|{F&5j6Zi;U5Q5}+%}e&<|dYI+7~Q--_GO>xi=)w}%{ zJ<2oKrXkIy(^RPX_AB=MoVo*Ngm`5>(rkb?`d2A4#DWVuaOCK0jIjd)heT6URWzLT z8Eb=_{k|{h)$LkxuK~Lh1`;vA5LH%@YkVq~hs2Z&5oeqWR5$Lud^BRnt4;)(J!On1@z9v&#k}1gtJ5qB2P{GyqfmsUy@;s;eeRVVJW-J|aE7JPNHL}afgoZ-)k`9(rM@DQZ`NPMpw~-+n6;c->@kN!mj45p++un5;L3lKj z$q8EmAG9QJ1K)e~xUJW!c(s?=$IY$-ed5=z z1d-uN;&)X0HOKU<+^Q!_SVOj-G!N}axF(M}Spls+_v`4O_Vt-09VluS!mc+MDJqdG z!gn9N%_fEHWUh$!!m{dP)P7;Ivi`_n3{HW!VlK$Yg`SsK<8HMD&Si@Wi{BgeO~hLH z3~SB?x+vAjO1^%jraoQa@k`BQx0?$TJm-%1lIHJzIR;Vgk~ZX7tU_6;b&O5VVNN%_ z;!sIo>=a>jvDwtwL&Y-b`hEDGL>)uVRD~cwrCb5RxlfJFYcP#=jg2cUxm_MKf0B2s z#ZtfLP6=-Q0AA>i8uV1o?+oZ`!)6S{hb)d1qa~Bdw>GD068V;#1_bTeZGpEkrq>S% zVn>grWb9smVrQpgeH&I1QoLiJI^t~j7D)8_y(Khkc<}D@t8?)jg{3UmG}jZpjh`H> zN6V{%=Mhvxs%bk3EdUb2dtfS&YI=xGGa--Fo4(2W&}1k0ya{v*GiDj5bQR?NUN`Zw zah2`{fRI}yxn|tcK4ipjhqjbbbU&1NM*I8e#^r?xDEW(Plw1MuhtgXs{u_Y4X~bHe zQI=&Ki4#sJd4t%5Y_ZOq%rmkCtV72h1(IgzH#+y2g9jd48=S4%xk) zqPd2qSp5n-*EFaekkoE2T<+PRW~S4wr+wR-@|4LX*8qfMQkDnMB^n1>R}6@wtb&0jX+?Y2Mjni+>4m!S-^!oBB{h9 z-Y*7t^g5bwI5}0L2+ExlHlcg%lPjC=(~|O!a5u(Xm+^|2zRd%Tsq@=(G#m-xO)c#_4wwfNe0pp}z=dJ2*$e&26EjZGsWCC!GHuD-LOt={(A$1X%@4oB1=+V<1Nae^6v zT+CcQFtjnG#i_VYQDiB=RD8@YSO$t*LM;-1c7kXoUe>_}67hMUuFhJKG>Y+f7-DT7slO`LFrZ$khP>CuH4yAjlD5KK~#>Z%FO%P~rWRnNPBx>$#BIyk3- zuY$QB_{ifO<*$aZ2NK?9*X1$Bl4LtanMj93s@Xambb(74ZQU1{{%~6?{8n24-R}bO z!ato8@n!6SvwQS=16F+&ued^5*D#FM2<}nT^wpj^fLXB#+Z(O`H$ce0(;62)5YHW& zM`HujvnagsFYh=NqZvF!Q>`zU6+D0yjtNi1V^_nU>|0HRdYM7gj0e{0*I3;%x{0*q z&6JPi2z|b@7c17d+Sk22mLo;-eKSeEyh(j*V<2rQ?y{;izh^vCl!u;LyO!j0?yKfE zH1!EMCfVwNJcs#rlyRFypvFx7m2K4K1JvF0b1e1p2Sm_cl zn)=_iQ(}IEWn_5Mh%txYYbQ|{lqLZ^FEmJtmEkR zM>oo&9&|PhQ+O)SS%MQT)S_~ULYEkP)(zzICNHsYG(ZJGwZ*zzA=UwR&q~Ys#~pVm z0b)4Ru=w^xON^vs8_BfQhglOxtPGYxmE<_qiLvBlG8!8?Y~>r5I}_~I!%|xZ9|cDa z*b|lP;j!Exroa3Yw;(Pq9y6RYei?8&n1APMsYJil&JJ|AauH_Kp=-N&35Z`Se7A%l zM;&B09mv@f)C>e$|E1A^c_BZ8&x=`$b~spXG^-lGeB`f&cU!JwON@DvD-q)3q#tSq zu7&vnq5HHq5G3uMYQ~xs41jrairM`!=n0d}u>eAF0cD-gf_~N&^5CIJ75%`Qalv3t zBBKEyLSWgUy<2OW1k6%F@PW~sAI$S#oPfoa%VH=P$^5=9&mo<} zq-uy&MR|>5_{Q8XbX*Aw4Q;+7vzn`lWj?0cSZrCKMyrGo|tprU$0SFeiH7}5JmmwM27~ctUNScpEd08&o=m$WYOLd_iJ+VRBwj=>mw@axxeG|7&R zWAuRrVc8U8zk5g7)hcir-Rc#{{bHg(mq>js)T!9 z{%Ecvc4s=Ub9s(iveandvFuKt+#-J&I38|#5DZx6I<`MMO7I?VikFG(RQsK)!%yN3 zn?O~jQm_tYTi_R^wNEV`bXxv8x*%`V>2%*_6(;qA@<^}-w|A!zkOiW7dms0+?=at| z463#AlS-ep)tSl~Oj~)%feXS{^eM2{E%JI`mjW_Sigkt>7Ng`Z2Gl`9({iS>k9uMK zFlo%cdMtTj|Id5R$kH|Z+cY9fBIQeXT=Z(uXKxz|(63itq2RXNVNy@?YFtN_tk5P` z-{FFlKIn)`QMm?QzJu^{Ova$v`VO;rc+eBjB0ddIr+l`F>!SB}w}KPw7&N24MkpAw z8K`Q_Q!k@*!nov$S!;XT5X8?E%}E%nUUws*Es4i4>2f#lszJDQ=QFt&LJ>F6;p->& zYYRvH{(>Q$O~7CK1i(eV_T#XMH5V1L58p2;AbIcBYmvPJ!9bO@;;eZhzluhEu6^re z_2LP{@G)1S%meFWk$7H;jRE|1$=b6qU26o9d>CY|uqbAkz8Rh|!J_2N#60;`vsZ-S z!xR!=xw*t=+fg)bG}R8b(18-@HeC%u?LF2?x(N;!sNphYKpKY5GP$p)=2Po*$D?|d ze)rdsW@&_lHyj4rBU?c@AE%Jz2{XW^_L=1DMUkt|DbW@m* zOzwv!*wgmKBh>{p=3smr?hNNCZpJW|aQ$?*5RWig!9}c^n2mKU(3AFiVz%UC12c$K z55P3VAV(wW!xl5rswsKpX8t;3y!%&bTN-ksR5K!V_Ur;UCQEsia?n;qWOTMNC;-r(HMF_ba52Iw!v;}XP5zH(tX75pS*(VXCA-mw-~Q@W z!OUYG^(@BsUc~RHJEZn+6iS2=cYXOIS+_&;+qTB%ixG*=BD?>L3@BkeOQ-2WOd#kj zA`)4t7q%B9(N_C(Fw!7Ank(NVEa1YZw! z1(@!1H5ePZHi6UYiiicDXpWj#zJEV?r<)0*Idp{yP>7CYK@fpeu0q{wHgGLG3{SYC z+x*iuQ%6YrLvX2YSuIp_#Jk^I`vNySgGgbZ+)ju83!mIl+PMP1Ykg!JBwJ%3{YpCw zy@0W?N=vj8$=>K7%D^`zpAOx#myz2adyH3_0>h8l4nL~h62lEd68(UWRjTdsj120a zS-wa+sz#8F6u3k_L#+QqtN5PfK<<~l!v8fp2yp0F*6Z^UzU}?gRMp}Wf^!YC9Q}s8 z><+dmwpw1hTi5^tiL#J-6#w)2a^u>m;UJqZ3In!nU)KAsB2;dZMnm8kE^YJXCgV3P?AJBGw)1Xus<(K6Gn2dxijF(r;N2?%1R#t6z&gyy0e#=NeF)ZIBu1+2hgSGcyg91Fu9B8I;-v z2lVEXB4HaCLs2Ev!0JL}dSi@nO#Of2;a=Gvne%gn&1=URb5h{_yG@$8KNcy453B#(uo*lgWt%57Y8P4X(3T1=X?J-l zF;t}5a8yST<>*p_x!`qi9+S<=R_rU>-D(X;j_#Py3A=Gz~Z?A>w zJnz14s7t$BR-OUJoV1!@bVd1c1%$hZjnn!(QX;eBj+fYRc;0F~vzU(Rj;e2}Kj1&Z zlS^>8Ya2R0=YB3)vo5N^3EJLA6xEUtTA`q92+jEA7jh-oC|`B&`^LWa33NWy(+6OY z;~@G?HVae5+K?{N8|B%^OA%pyFh)!k04YKXp1dHJt7F=(#DiEBkO%NI7}WZ4ulaSs zN9MvSctgWM((x^NwP}HDb-DWn)L$7J=`1Zx6{MbJ-jiOVRbM`#)_3r)a^Zet;jmX{k^%vCL-m6KM6bOuR;1GxJN0G|iH? zXw04Tx`TqLxjEnkbyDcJ3T|Ou)^ku+QqX9;B2_k!mCN1np^$B4`EffreOqW@+}4d~ z84RyT1<3?NxG#&fuGj{l%>DB>dx#Ijx|f^8Hoekw6xft z?wGS256}VAuE(8lLT7k?vz++aGCNCvW>IQauKR^Br@KbIx4vUhFGZC9S7Tn7!F%rY zrtwZ@!dTNh%@5iOem%aizYKx@^uwTx`fs9BFw}uOsBy9vYj1iy8Gfv)A80LJL>+4W9Hje$v+A6yQxcxqHhvYsK2%7kESvlhx z?)1S}BrPM^y}dfMfMX)QD@Na51dM=z+-r#dtib^-yvQT!Ff!ImH6hBFOkc*nQpzWT z&oHJ#%|_T_w0d-xQnvG1=5kG8!HbAT1<6Xe-$GjwUZ)r}min(Pu9W&QQLs<4n3t5V zz-=G;wY_a$mP=$_sHM;?GekiVRDPM-=*3n~56(Rz3+hx$^n7yDeYxThT9yrfl&5`D^ICJElJoJYN)<4R8T|cv%#D z4=HBXT}RT~>3eaT&YqmnIprXYLI%wvg>H$k(>#W4);5Z-o0jvQ|8Oi8U`|-viL0f_ z!>VI_cLu^6!vAN5Z^d@w*-WNdhk)`p^FN^nxrxp+pCb#1V5$@8upCSRg0pJ zDC`ES2v>(a5wFYO^66N#_GwSx^j=VMVUSfIU)dN5Y^tOu$yR>ATF0KVA?Nf=-hE?Y z6qrQG3qS%Id(c5XUbBQA1)V+eK$dp%|6r*m7O0by#mw<`g1YHtv-`EA{zW(-=h^2L`^AVMLlBO?ZYBCPe%7Z>hC6M+LYx%>ljM6x(5ixAl*lYRl%l24hG8d$`-ebd!XWBy0WH(6^?x3^xRifAF1(9ER0BcL!-S z;EY_UKoS5c=fA#zpxoW%gU2_X`abF8!=U<-f2w>{SQ*m+Cnv21Urm)U(9bKELF3NCe^EQ@wSIvKWSFzNtH=Mr0 zcUD(*adfR^t}qe4T42VSZ+Gu8#7S5Wc*}Xfbn6)m)4{Twm%ro1&54~A7AP;%*b_L` zoN2SQR=+M`D4ZI`SZ*gkD24;$%dr~-Rze!a;vc&Nfg+a`Bby}@t_qlqYkU$#9mHM3 zmzNW044;QDvIA`^U-i?yF7v!y@v@d?>ZBYKPItNz0F?6DX9UEk)oJ@FNQn53k_?=t zlbokLZQ#b!h}BohYoTEKdz3D9dCHFO^9yhhe2osbQJmO6N5^DHVSX1fzd9(<4(5-x zvn05UPV8N?oym&DAyZF^Vsh?MP$?@NGe+*wml^nY*+f}y16o$7X%7$QLi4ov&$FwG znCx8uF~Itf*>*^K3Up3c89J-%sc2E{K0sOQ;v_WDmty9O}7HBbgckPGdeQM8$f zcORfgt{G7RBX}(ZmZaV48ek-C#RD3-+X%$Va|1?{PedBM_bnjlhmO*j2gJ`ZD0jveSeaossh4xCAgJXpEbFT3C0FDz)(T-i01YQSTZ@2X3=|xu{?LoUi`+&o_^!uiE8`7rBOQ*+FI|p`Wk`#ZWa6)pDYGg;bOO&A#GH?uN-zE zXm)3<0f+2_;M6MeLDqWpe1B^qg>b4Lb90-s><0ncmi}pI^qC$GNS~1mK|Md7@}&aO zv`YdUnI8SP9*rl^kKED5`<_%aokOz*XUENy&nP?H5&+vzby18I@S>JE+5YdSK1R^- zvzqQbp3z^+V4CS9@$u*I7HGMriRY`fY{H^iA0dY#Q*TE4GMm{U!yqbLsPgn%bFjvs zs{sgi`>i3xJs$6;)I2<{9x9fBZ+^4RP(Gml3itGj8xmt}rJ_p|QVbF=07=o*6Mvay z!n(i+;7n=AViJ{8Ajkx0N<3Z*u(lO+_GEZ%?PeT78wcF53?vKroO(FH3&%OB&9Vwo z)YX{^3|}?mXu!45W%Xrye2k656h-$*KL})Dkg-T6k+qK0xMRR_3%|sxs2_R$A*FMggkPLL8 z0-tI6LZN_{#bi1Hfj?jh64|FZV@gO{)Lo~ERw(0ELqN()O1@i4hnJ>jvSqT?QEHkgtw6KP5S)yV;LgUO<}#!ITsS$GN3wC< z1;rl|)8cN8ziFDgPqLqSc?TLz+V2~F)7nwU8t-j8BPj55>QlQ{Av#3O>yaRD4|O1I z(AMMMh#T(4WwD~w!gyw%huO!e6|Ad~i!&O1Q8TzEfj0&)bq0s86^m^0Qz?SvoDVpIGVfJbWHqoop>vry>3ijr+;+Pv$!cG8^! zT%^%As|c6VpOHbM!=W1)OCDApX;EPtt696WS)N|}ssolEtq!7&3#uP1ZRYaT;i!70 zaRCd5VyHXj5Zl)T1FgKpx?%r$?yAYgH<0tsrBhW~;!9{z<2FZ4f-b(XWI-UNjI%Ut z#s*9GY)(N4-4uq{dsntvRgUa9!WG}xRAY==uxNWxdzoRIGl<*j@CEI~x?DrwFtaH2;u zLe7V8v*wI_e}}Pc1cPU|tL6-_3*JS04;Ppaq~${2jfxweH%TZT#R<%&dENkJLX#Mk zEh}dzXpsN*p80aNEX`W`7IExkI{MpS5Wv13oVHFrmtD&^UyV?N`H7DoRomDX8&Nk= zo)Ozy_guNjQWpNp0ta(q-*x25Q1KOj#SVlW$Kwch2-BLm!-nHfzogxqL% zzb+5q%on=adzsSPOVy1Tmm&|OW#B_HN(bcA)X1#S<|2Y8rCuDd6wN$L z2cGu(5^=dFWj9bH5qU=>h{)ucXTPXo9P6KcQ@N7Xfmf=b!WVB?hAhbsSK~Xw*4fWR z3>Gny*VC5@tva@lZ*0uG;PitI!su6hUl^0}xd`sCIQhz&5WvKf0$ObQe(X+Hmxy-` zhA!^4kuG_zjYo4MT3`}vIHLzu>tidOn*UT;T9%$GMDx8rL+SU%HsG1)!}Rw=XxXQo zE~J zac1j+<4yyeD74lFe5!p{q2yh8nBxy7LPe{oFE(uBnN`Yhv_3otyTU=!aUiZV7ss&X z>`g8B0vxj^L^FcJ;#oMxFz*eRSFD396n-EB$!7mxfhDFHm}zJZvo#n$5yg zJP6V2-bF&72fddk2DMnc=jyM(C8VoB>i*F#SvsFVGabEFKwf-%dfUem6HEh$3K$F3 zIill3jQ-P~lhieZ{c&X0z!CfED%l(+g2tBb0GwR2zc}LW5+G<%I(~P@c%X85hTWht zClpei_sYRxOJxQI#bZ|CP!i7a*)puCko>8ECJDJRn}? ze3oX}PXi_eG4CnL72iBBMrs?*Tk-5xS4@Q`bW9{J=t=dE<9jWuNdZN?HG^TtZ2hpmfd1dSD-G5h^Ek$^;0*%&>r~@*G}Fh< z#XaQ&g{M4&83uC+hHfQ&OpG*3!exviNA@aj%XtSAW)r6aF`zY*qi^lT_}Lk=v5iEsDP!LkvJhTIs@?Gd#EVFDK0%o$B43x6TMCdOLkOO zx_wLNhtiH(I!7P~S)osUD{s>TA6gxWAR2vcm|2q-#j9z4toODvzPu3;`RtZqO3u<*lyT+vMox zvjd;9{!^>1uzMBNCfih8+W?cKZSgA?=2vv+->6b*_8~=Ar}>aft4;(a0}`koqtO-C zvv!(A@Qv;C>~IZsi9}2NRsi_KLoDGZWqAFvD(Q#h{TAOtO#ZzQl0!;EF+Ft6h0;ev z0f5iuP*esirjEOD4x_B9?Oj42oJ7AU7s)C(>8QQ9zGB^VL~^P6QLYoyS^-cbEvCc3@)bPdH=+xWSDADtxt{Pryz1y_U`ws86hhwSBNv zO8!>Mp~xS4VA}%x9}t=MSE>gcq4E?F~3SZe8v z_CLF*)u}6M0dm60!_-gst)y^@5Vjohggy7*RH?pwPGzN%(he3L-P{nnqy^=}ddR@U z?u%#2WF1x@@;?`tDW=ZrgtNZmMIJK^MD3tKZ5C69cM=}daNd*F)YW6qbsox+&E3@d zM2cfsWBgy+DTNXw*BEQc=CHplqN#Jqlh#DeR`vS+?DM=_j9-wxutBf;3F^sfT#p-sDIf=KAPp0?V!uz!g*j;W?#<<57F@d8d@P82~l2FMGuWG$(sS^m@Bo7WS2K zstnOJJ}9N%cZQA_h#Eoa#40oP9lXvRTa5*Wn7qgK ze;C-*2WSgo6&HyDxF*xlN=G@lT1w_iN;g2|5*AU=(yICrdX-q+IZD`d5aHJ$821HjOM&QRRbS8gM3)R7wV>%Z_%)o27Xzubs z{Mj{6t#Kal#z-fvqbU)5{lVEr^A7W)IoP5KCCjlIsjw*qPpvA2~UwO<Wwj}$ux-j97ix4?^WzHkklxqghsz+O=jl_tD^m4 z{svz<@i?r3{}MbE?3$oGB-P3;Y>tN=D5x3;Exo{Q49^gFhZIJJ=I~VYNT4?>gLx&# zxDj1e#7SmXM3C{+KV93+aG0d$X2s{aIietN>LHTv_V?wn?!I76CVU#l*GO;y$vx<6 z{GpYpEtrmk=}p;Aq2nUDBu?LL>MS|91FY}Fvx}sU*M_FU-EFIk`LdmK_+$?3W!8WV zN}1z5u1rrwAmL_6)FGlXrX3h0faBJ|JC;3H&)Mi59w3Y!=GF`=%CK1VDb@o!5)eNG zr8?&!=M4DetdTX(SV5i0T*89_>BCk!X;)oShSLXqB~4nSDrIAIsXH+{^j}Bx!HByO zZB|sZ)}Hxv-I57KJFws_c@WqAJke_Xm52;VtZ+&E(Xbc4Y4^_PX=v*NX*9$Iw8)kV zv>9lnJu?AjDR{6#>COG=RQjczV>K;|QA`CyHSrRi2$+u4(+exio-NM@wR)CYgLp2T zj6Lp!g9->;HpxSy7HiG{vA~$+vG$e$u-kCC*`;_q?Ce~*C62jlBpZs42pgbs zGeN{;Nio0+(1P}8JZ7R`Mv>nFHhO_v8%ymgPGS|AbCw)1qb|wUN)f+*1_glYV`Uu7 zn>}!Bk#s#LpL`e`<-UA90}t|Rj>d4(-jNxkwHYf_Eq#f$Ho?^J?Q{#Sp{uolDNg-K zRMp{12pJmFTG7_$cu4jV3N7H1K&Nof3JJYFyRz@j1dzm{Xn^FKMEE%Fsagj=mv0ns zK-syy;GOp%1a26%@|02I5yPXwgAT?*ouUi~hVj0-Ynes#r_}doHQc&80&NG&qH{?T zL~W~oOvzmrQr~WW)p5@DnQ=hdEq3suQ7cR{9x$4CVkhWXFX)j;966E-p*seMD>Xyt zGBpEB5v+%iKS+Bci0e%VN>vN^q_HWiZ!v#?!|ZOUd0UmP5~Y&pk&Th4PXs%BGq*&w zHjzcH#!^WGbea~@IHb_ifha8tl(6GpTJIPxEpL3K;#zzZl`0a>;{$ZHMfwD~W+_9P z3IAyGo0VyzDz5j$NM4(SQhTl*x|Q4 z=hJu_;b7;MRKJ65QWX|<8g6>}X|#$jAx4-d-0*PyBw1Pv@DSOaYp#+^GC(rQ3MPz{ zQggR)h;}qWj>x0l;F-L7z!Ky@^Y&~)x4r(Iq~TvbiK*?acIpntYw7hSAw$D? z~LM5;I^+KL$M1vdABn3hs=c4f?&$*zWq1Rkbs-4eP4yYOL2)A=EWiK@b zbaw%Aw3)0GRf#{Jb`l+RntFR=l){G8zRP#RyN465%Z%4|w@X)LMBe)>k1-gC+BK6EEcyJSc;LN!6gaJjU;0wu6D7})~>E? zy1FS{PaTnqKM7aIovcH5KyE0Bs7&O% z-5_f7rh(m%dI4?T&oO(obwro1tJfJdHkTGWFJ-=>0>yEtw3b#Q~e`#Y|M~ zn}Jc{=WMsiZ8}e3K?Jj|f%ATzU;<7vt-9 zXBBvlruC5~VT27Q0zWDY#^J<{9nb|%rav*~2cpqteaiMKama57Fww0ybCy42Mk9}g zv5co`hOaY@t!*sDHZQ;*2_byy#!7cVz<)O*R@HTxgT1&%jvXlcRGWmEp_$RA$2Kr4 z2!MQ?`#J;ChP2J!)$6Z#3u<74uwd0a$j>5wi69=cL{D=u9^)etvF-%UV1Ku)Pe$v=B?0$fv z7caUkpnOjO2C8#`KQvfhWm@Z(?!RawEadB!@`U+bU1NI%+xL_|SPa)<>rvfXI;)YS zGYnc_3r+p|;I};*6DAINx9{L*cVh$fj`gQNJ>1bjr$w%OhwTCGIPfL^-)PcAPI+%-{3Typp<0E09!>l&)1PPw}(yw3l| zI*!SV!~yGAc=TX@Z4W>SU=~a0M-}jzM*aD9<9kl41e&VW#3v(i23M#Fm2w@`3-xtY zhI>s7US+43wWl7C@o42kpYNB9HCJl)^QnBX;Jt90F2g1lbnYy1i}>4%^A#Qv$?k=+ z9F?-8cps(1KiZLwpj}ZVU{N*X$>h_*vu=E{Gupe;Lic8ukH;4~h}MIhKGa^|Dg8K= z`^mS!U`!i$dh-T(M%1LwtI)!6{&$;%rFkk0?$fL!1{SB6V;=Ip>w`^9dY``m2Ht z2KfkN@Xn?Tsg#&4V!fWjxt)r2-bI5g$`^Stx}9C}OIOI%Z>R;AfqM%L5|WE=mu=p6 zY{oC~*O-B?7Md<|9=G`qKgG~>C_L%m<|xvQZ_xBQ-2z^D*(fK778d>Evd{ zo5K9OouN@|wM7Wbj~_YE5OYfJg;RrGW=qYW4hBK7>inkF$)}PCoI3Yk#4a1vOaq#U z3Rs>wQN(Z8yZ=i{^V=>5HZR#opS%FuQnrxh|87tr`a3`F1KBS=;Ab=hVtL>yghx_e zFN89tm-*M}+@0w2vS}^p?)5_w{c;2jIw}ZZGMRy^ zJof;KSCv6UYN&&;XHOM+t4iK3u31spT>N2`F2g$|)3F!Z+hsU(OKUymRM#K{H>tq5 z-MhoU45py2|9PZ+K`mEkB;;=y{p{G8c`^CIs_~Zm+eE4FM`o_HJQ~ND?5Y*WKet_M zcgvN+!hUM=I_>?Y5B=63IejXl%l`HF%Ro!ns>J!gsLBX)nnAWGu-=-@dqdy!nUPLG z=o7B}as|bySVyhZr&Xx2)@K95g8y4a`HQt5+zm` z9znMxUOPGZ$@IS(efHQJ1F#RK` zX(nxYvj=6m{5@B2B}<$=^vGmMe}RcpWu%VUMZ~))|FBRDR>~F z&Dz`hlBpSvMP%4FlB*FU<$v%mCLm zXjh{UZ{_x$PlBcr=9Kz|v@29W$keo>0r3oXfa>AoR~D|eWFqy=B0pTOlv-2BE$CBh zg==)%cUdtTVxIz{s0UFpqH@oc`Q@i+yznn@UP+ZB+py^%LsPPh1WJnefAYfO-@dnm&qdyg*iUV1No&-V%^(XRWsqvGo69`@6o11e<-0P#D zjZkA)+>3P_Tt+M6cL$d(_9BM-q4kac;l)!|p_6!^OCRLR>)vQ0Wq@WM0P7;H0)N(N zsX|z8>W7}5yU(vFNZW(n3UvBi#SCqE7h=;cD~Gj92D$XMQ( z&s|le&xA`w*!F^e7THe{->LZ`j)U`|?h`6~C5hS^Xl)mGLSbL@FxLs{_brI(_W;@v zAcAbjo#z8uvl8t0=bZ*e-4gfot@PyMWj=ZEm{`oX5-&_CJRrya4%HO(e+I*Gr81Ik z*V+650K_8ZiQqxMq}a7S;eO?7(mWaTNVdQ%2n#-;Ha^whtX330aesM!Y1_P#G*zF! zZuX;@WvsR=NkZanxjo}(HCuBHL>bU=AIesXf-aoG)Xxk*zdWVvcJo<$)`g1}WRmu- znaL6;RHag>EKl5fpl)NLw&&K)U5QH9#~DO$A+ghozN4Be=f;5vXlI7b-*98){tI?I z_0g?L@T@RTX6BHf;=4>&x+qy$qDE3H>~c--VNOIXG@!4TU%Ohotj z96aE9@L6B%NPN_4l4>Z9!{gs9sYBSp*In#*wMroX&S=nT zZhsi9js{1l4*zSlP+R{$!9cnOI7p7z=2Bfi;KVY3D6dd&A3(VnRB%aWkW;o+Op=C~ zPGX#=3PpEd$(^D&dA8&~&9w(A@)w7o0#RUr^Ek^NKG-M}&v;p)?_O|QC4Db^*A?pzQoES{o3o9p8R)AZ&(kZ}z&^rR^ZU4BA-ukfoWs)(g|QZLpD zhrjtUrs435BGnrqVmn;nzj^L>R`~l&@;}dSa>SR z`iQRwswiio^)rb|T~548@pmKRH9e4ZMe zb3NFA!z0k(r+$q*Y@)WGkQ%Dvn3`d07xv_oP3*?@o|`so#aInHs^}zyEj!y3oONS7Bpnvh z_sT0+j*ECI@*}0z-z(UZ6Y$<*CnQYbI1056rd%mVD_M`juQdRLfCaqBB*SWx^nV8 zh(>jk0&1vl85L@T6XP>A)UCIyuaV>ikiRuz`zs9*Eec7-<@nPGPFd)G5LQ_&mGPXw zs-?tT$YTsX8}t2S4xKZPf#ls%8lIQ(9$pJpu&KLKar~7$NcNuC6Qh0<2hTCfz1?+7 zZ$=EY1U+u{3XQ!p>niN~Qu~tmR@hk16UVY?UOMLcZgo4aqqt#ZGP~+LqCCiUlS*i> z@b3U`NYDy5c_kb;P*Nqtl9|GO;~+}|cWCXBD6hZz{Bv;m|BB#gfabT5el*D8Rlpbp z`9dWtl^Lx}w=Q9-aKRI_Z$wWAxISKybZLYLPwbg^if5HTZCeacBeTsS*VLD9> z3{=}z2a}#I~l&-ckl{Xg%oXS758{sI7)uS0s>Y-%0gzodQHZU81FUqTKcFfc20N1n- zv0`g?FkM(Yquk?U3O%%}m+ppDDa{hnVPB{U7%k#M-YJKnm*KrgLKxzzvrS3cZka)` z!w$NqqnB`As4Y`TTSJ|!CTstu-g%GrK5wT26e`Nwb)yO5?8gB7doAf9OM3UXk&i6VqzX4o-eq`SYtEOANWNz9Dm67Z4H8q}mggwZ-pc%LRU?D6nDwMrU-&~Z{ zU`_)=A?f16>udn%3!aOg`Ccp;FCsw%_XVjRf-|p|<40o4+Y|zE0omw)c;XfKipk=# z=XsorlWKsPy8IMiU49MgRTmf>V1idtW{m-4lOo23raV=^@>f5~AlQTB)I-is3diBO zg+r7*r>=cPuK9_(XCC+}p8ja|X>gVJ_tpt`v+YT{|DT3cx%7m(z63unShqMa;=-vR zdv<4*RpVw>%7hLys-r%kGw%SsZ)4oXz&Dn&nck+QWD)O}hcL_&ej@n*(e7_Nv3 z;)_9GH&2ub0M$1({iVn zOc`F>{}^HaKDb6QX*9y3r4K85f|y-(Fr1tUFbJ{K-ZF#!ZUG2sEJ>k&xsN$XMHGy$ zJ2h%MWP>wsWu@Tt3m`)*0m#4@bDzj3D2$eba|zmZ$R|-AH?P-@QgqYUFdDg}Z5T(I z{oGf_6i2>plm{$R>t~aU6VCLCr{Z_lq(oVyL!x<5&~`?e@fYnBFd_I$V%N-z36Is4LdQ{jjy ze>Db8lggQhazF|b_7CLTKCz%Chw|DHj<2QKP%{Qb0Wus;sCZmW8)_Ec{UT*L- zlx8^hsK+)0oyU&>xOn-1K1(&{l|B~`rp%n*vEAL$Nr(=_r&j|2gaoFXt%$*?XUlA3gtr}ytSWEhy!-8ha5z%?o9sf0!{uuAg@^1m5f4co72Qp>= zIY7q0fFr(_af$$9@R$2qou_{62aFri244ISJ~iFnhUS~M>DVe+^%V;0p*IJz;>WWk zzIEEWWu?d%n{zTsJw<~@lFtn7)o5%D)Oxl{#rdn63oM%DN-9TjyU%k$T;5IZ*G?qhjf5xodn70tZ^-^^!GCi-RlRVPy%iVQ3fqqQKN;0)WlJfzN8S z_$4GnHI}@Xks3KZ5VJ4r++CXA9y?JO2d=oCn$u4)(0;HaH(x>oKxsC;yM3kX|NYxS za<}2*%PB1AK*b|tQTs*Q{S*hl*NE%{9>JqzKaC zHH`8s@;OgBl(A2dknZ8!jaN$-PT}R|BI8&SAXkCnb$!Ei7|=f=<@CYy=7h%4!60!M zdNKNndFK{SRlPQ)pv9cEe3-rh+b5V&2NRL`^x7|-`srsD!!Vzq4)d}`c}HG54C9{B z7nyC&_>E*1xnR{A)TrT<9+@4k7}8ZfHp^^Oteuw;od{T^uZy%)uGUb)dRn6dAEZ0} zS5Inp7&Xf4P&*Vwu5MZ3Ia+2yn0!&WC#LlSNlz-9;e@VUr>SN@A=Kel-T_Gw_F@_) zUnw4auAYg2ru~XwOv2JbF)qsKEg^7rR7{|*XdfS}K%Wl(SZONmX@SA}|8^(pOHbgreXqson$TWPirb_-PHt~sHU~`9Xe0KiQ zS)bIF5ltpy_8LKM^Ex8&DXh;d%OG{)o38gyW&r5`Edhio1@Z9c<9XTAB!ev= zavD6QGL+?adOarMpCeEG6<6U_dItlE>!Au%(0*d`ous9-{Zw<5kI5stve!tLed5}G zC>}IrtHbFH5`eI?*0Ojp!3|!Nkd|#^(CEHxjve^kgXNNvXLqg@u*zi`P$sU5FM4_~IyS>IA!RAv(oF`xzBA#teqgWu9wcTWKuQ zZ4yZ8JS|C3#(S4_C3j|_^Yk8quu@3|ceE}Vex=E0=abaE6)s^LjaCBMBB`U$BNTx; zyO3&sp30)72WriAUX1D`iy1k_^rAVXFm|TLBk6b2fbfVBql{q4f5N4F-5Oh?R;1+l z<3ZDE0jeMVK__#?WEd(Xp*C^o9n1<4;F4aJuR6RaVNstb{U3bZ*}2)bZ6B%|;CMHy zkjrbR!3+O3q`TU_6q#?YG(6k?!U%G=y5A=9EiozEw~a&C%xA*|A>9|Jpmb7=2r%um zsknwEp>f2Z$R^`AoNMl$j$N#E0eGiFWq8BnMgZ53-tu)E$o}Ghu|{_o+A_W`<&|8q zb{>VTqq|c_ZW+pG3D+#f+z9JWT|JPrNHI>q|v3F8k;?A^BPY{bc63`-R zjqcHxJ4sDeCAtL4gB+b59i9SgPw73Ba1u&fmU+MQ$WSvRt+3#D?KKGMM0E0DN1QAh z4}mOi-jArAIo`uRinGUFDA=K!qG&adAHb;Lv8J`UN~rd{90Uw_&@I!A@9mcDnl5;) z%A>qSW89P8r`TbVV(!Pw2so1sQqfT{jg*9so1#(+8*@YW^4%-zJs3ktJ6EDP3lQrG z*aO;R#MqxtOHCAaud%U9(KMO1m_*5op3sx(8pnMcQNK;GtR5n zlo~`B_pC)kOjXppM4Sfb82t&w>FX`Q0|4B+)r$^yqoq)PGxIe+{y3}sUb-zI4Dn}q z&l@O>ERetBCZ$uQZYoA)h!yl1j1>zJxrJ%kAHg#1kouG_JGdx3skq?nCY#Oagv7@E zLx*o(99R89?^;v%RauIav2!tA^FLN_-h>6u?)^QWZb(GpRcI0oRE-b6qh2p{u1Zru z71}|;_ZslZdggjN7v{M2=FD#_uLJM({R?=CT8%&(iT*Z}8*a7l`QO)4hZ47m z5Dbf~Z^#m^8k-B0sK7d#558I{KB;wo7R>k*Yu4OF55vxdq3qQ_2$^>92ngxGmo<`cn(RJkh^LaJ9}imT%=mT=CvoLE6SvmG~dwL z#$PNuaa`5IP_dY6KLCKUgAs5;sOyRz={PN4Ti(q0#@Z1kD}`qi{d}hczEdkkmWw)W z=OLw=h*4jW$ZvOX$a-AcLth|Q<_ygh{_wnh*^EuFv?lPCfTgNg$oEWi9Jj2g2Itd8 zg+_@2xP9SWmp>M12|g$*e-g1n zz=>0V6hlsEz;n0f1j|V##;IdO}t0{E8idrmeG#1GVChL+4rFh>0-Ti$V z!L1kq%CmAci<-0;IicfsG88VMn@PJ-pof96#$XhG;*VfYEJ*%-zkzR?Wu+0?TrR%` zbtKdgo}%vBBCMsA{sSnH{fq3k@`*xRvR6@9=#FuvY71X)Bl`->| z-rujeX#J7JVd_uOdf(=Kojbd7PV=cs;(?tr89!a4>OQV+^<|9LKUMrhI2x~jLt_OH z5!Ky%pn|a{408B#X<(~X3EhO=*N%g5cG}Nnso$h~qjIouvrz#ve&V7AN{L1_WJN6O zd#pHpT5-8_LRHp7X>wwhgq+wyBX*wVwaF;vEEJ3&|+d}e& zs=f)RZ$mJi-nnecKTuH3yW_#mFWoQCX_TtG0~{`1UAW``Kbv1MMep5U zy(_{e#GA-2Hh0F{**2q(b}a!GWPpsC-_$`S_K+A!iHEGX3Bo7=B~XWr3=Vq9GL3MT@xXBal)G z7jV?!hD3*V-G(WvH;-#nDb~6jOM5F}1m0;vNlOe4>y`ZE47xg_MMf&`<(y-o!bpF$ z+lwG?49%vpzBWH?JQtIDCa~;CC1=Wi7YQ-Eus2x}@?at1dn+H{wnD#YOlPz2acHUN zXu5xv*mZLwvFi&ujQ0uPlw%w8*p68wyp#*^3OESMuF2BC#B zznqa#aSlUl@g?LFtnPKD`84Q#ZsOC~Hu9B| zan2>m!ZMcnh!HAwEJbvYYIsg9beRsFtD-_rp6xDmsa z4)kQL9RprZM79vzLDhd;I*LZyRTDN2f;d8}z`tlu06wJs5Slc=lNu*yHdMG=m@Yan zPg%Qs7OwfDpfAT5p<*=uly5xltTrzL@e87Ik)UgfX;%H!gw5nK7y96AKa*O0bd9!c zdJIa$&psiZkp%WY1(?D{;57;DpwZ*3_R1a5L5&MHp791K^F$!?0QI0y@G8%P0b{28 z4(ra9QEe%PaKUY@_Ss`lDOcqr_F)GE^Rm*u=4q^Pz;nLAca{VR1P98f z;&)W@)tUrcQnor&Z04371lo+xV3#}5VKYD7I~b%#g~|k2cHhhT6jk&&w4x8|psg5z zcUOvmr9!PMl?OJh^(a!aLxgo}Tv}eFOwTDUckQOV`XA*oC;e~cVkKiMXS0IFYLKHW z*bg5Ahxl*O3f#aPrOf#_8eMz_cl>QWS+n6Ne=NVv@qWYnN|iJgXrXE-8sUg|10WVz z*VZ^Hnc{w#$2*@z_!Y&hFyyHhd34e>#ODl}1D$^y24VeHifax}XnfwqkwL-MRVvu29Y| ztCgr&FR@^?kvZTLo^0UkZ|9PhG;wi+V_$9fP6u&UJCUc#h+4=x(jGA`r@Gxm-Riz3 zYNQ^-U1{{4im~8ofYorKFZoM{a74fQmdG9+cGY;Xega-L@c66-sxxG>sG~sl%sE^p z$~FLWxHo9-O3{Mr0{v9bI(?3NbGwhRofJ}9OGs6-^|QzNRA3wFG)-vM2T zHefyh&~Gr?LIOD(6x!km)OSy&%`qqxCkO%J_h9RMorV1&+7(Tg$1CRJdV!Uz9Z>s? zP7!o=+9&gq$SbEE$7c|q%^9sQ^jtcnT>?4h5=Uc9FN1Hd^bu_68!5Ic`}?3)0N1`= zW?dQWA*=v@kyOBps+VVtvr#xt#I_}^DVfi+pp3NyC6TJ=-d>KmsOj)t&&R3mUf1Fi zHY&hnERmTv%JW0^hM9@NbYM;pxts!3&tNv?lp>_^4FEve!(xH}O|kB5v5%|mI+;nA zhe}g*Dw5ueMWsumMtmq$2ha1#k8ei~LUDrr#BEA@Otw_SC5Gj*=NZSij~{Hs6yb(9 z9AkH9OP3$#_ZWa!FP9xZa4F96p>bXP3EYG(iK&jI!3mP}olZ$Ow)QuxI z&w9SK8r5zRiZi4(nB#>3p(Adak`;gDM_sxA7%=2pTvtf6Z+BGNEPS4S3|u}99|V$< zG(GFw*P@Ld^S3Zyqw%M(U% z;9@bXW>^Y%=<&Qsegu%g_yH?Vlm(WtCsnmK5eeicF!+?~6ax?@a5K zU6$N-v0tK2Xu8u(WT2VqKJ}xCpzDA83Q?Yv$aqHUA>LVazM2GgBka_DE|oZFgcOpc zP2&>mp^)V5&$`Q}``+pDSQaOfZ<9VnO241H<$9N!z3W(&?pwcgkofC1T_>RjFAa%G zqUO46ZqbQ>Hg!^Xno5HfLC*b9Z)c$Y%AJLYven=8&SL^G0&uQmjM!SsV}Ej&8nJ~P z1!3Q>yv3La9a!)Qt1biL<37xa8CLJ~bc{?jfr;n}z_TsSy>LT^cRL&Tnie}QILj!O`PB;0|knuu|vhqh>v#h_) z0xqj1K+vm<68!SUqq_((V$9Sypx;xgs5bv(~E9BT!Hqve<s<(cAKPHJ$yv zH3jja#kn`#oQV)}NgXNuCXd*#hz6F6i6#tKhg^}RS{gE6YkCx6RoC_#LpVxP7Ioe* zf~q!ykCin^rgE)pTNbTmT0EO7p?L2~1Ypwi_eDsdr-gYSNyDwZ0`Qnqe5z6$c=fD6 z`636zZ{RUreh{`aVDwww_zHCHFK^&?UA@THwzGQ&)@FSu)N|LWD>{mP^_*&;;(1U> z!~38<`S}fSN*w6ikbgO`LZsyv%&W-iAxYsEj#z&#HY}KO@xzg+ROl%i#Dxjv(tvTh z11&&}?yt)w=ysQ((VWKOPB>%>01Mnt85QKp*V%I*<_T?KSOk+}Btb(O|4dyc5FCJ} zs6Z!sFd{!B)c7;+V{^vzp|M<(Q_>=Y=7~MX!uJV)B+EW7vX#0~oD6Y1E~1n?dr-N) zoN5Ty5!GOXw@2c!^DMlVy-MrQ@Yu{(YTC|GC6g3(0z=vP5}T5o^?SzMBU`oB=gaK2 zv{RZGox{xnE$F-o$2^2@>Q>s2jWDEp&$hP(ortTf%vYTn1BW0CB|5#M)*EKwfR{uf z00JuhlrT-awT^-0wYsxRp;7Cfy+P?F3S>$nmx=ZS02Rj;_qtMa>?}_SVO;?LU@@pK zcRMwo8aBUqHBK&lIk3o=sZwFcsA+R4#(HwI?boE#_m=GgG2iNva`f5E@>X)}6%Je^R)WT+`YE(OuWZyV=n7ro3c$=I<0j0c$W>qOjICqd2&a z^CxySO*@sDnV+lBD(_HDPBP8qA9xED_{<6JqotJC6fx035@W#z&Z33WT(}%dQWj}Y zArpHGp94Ue)yeH{dEpbm9+o^TzSbH02x9&G;Y2obNS*?Hx?=KsIG}49ISlHX;~H5x zMEGjFb1XPYw1td10UB-2uV7RKrBabWaua+0&8Pzn*gO z3LW|xoaWeQCXsD~N&wK&L3s5Y1)5cwW<`8k^ z!Pq;SA+zp?!h8jP(%5d0;L*D$#f-#MLYl`qN&s6iGtVr175iKyr3m1<4+cX2L63Pv zbcL>}dsP3tR2KzX(X?Dm>j1T6Lr(ZH%AqHt1>4$aedVKJ3dnp!_^QNpbYZ!p_An=sYpCxG@2|1GYLA&cb58em@nb} z>I;wW`uTOElBW`Xi#R}wRTWhU{Y#}#IsEIk*r!{O{YC~KEd*u}ss{IyDQh6;GM%dUucb;U7|-P{ zN+w5g|AAij$WtwtgM#EFmI_*jv@-&8hH0L-8r9a1T1zO zmQ0#$8-+X^-i+=Qg4goKHe=09RZ919jg^lC3s8=Y=3ujW1LvB~J*Au38*D{cv(=7H z55v5r9&`10?5T4{Ip`Rg`}Q0969LeC{O>&dwK5(Br-jYQ8wqdk+^cS|XLzRCFY3G> zoZrnTq;isWj~LTc z6$73w)s37D!wH2<7DPfL0phvg%NR+wqY)X-0snCu$gAcc2FxA0l0-1`n8C?)z-5q~ zABlS?oXyLtzvQZQ9)4$ITZls++Ud@e6JH>l)mvty@ZGB!h;Ec6zw?&;oA@PK(>)m{ zbtIrh%CRc!`?lLgn6appNDJgQ47(e@OwAKG23i#>R4w52$xzOA!n{!0;%90&HSBzY>j#mJJXfO>BbY0tR!Tf zo0-^K?~9utl_h>g)B-z1p95$JhL~=cm%?O=8zJf*k}1QZ@{KJKnCtW)AjBB-Lgq_x zH7M%?a`eGGY9tqgwWFB=x7FJQdygD)T0!jqkOu@@?e}y zog|lW77Pg~>k)1Cz2VY;PFWb0&R|Gf)47v%8{7>v*2WgvKceE*zuLW@7NY7*%G^XF zEbPd*#&*p%*BJh-5T^(llotlt+`QiAOLei{p@3qMip9Y)fs5?ad7Dadbpo>0OHFgT z_Hr}zT4$m2Sku%@|KKFS-;YHfj)+ z|B8buVR8(}>L!-v591g7LHcRU)kgZ5A)4}*Xr)yX(J%xkrPror9Z2H)1%oI-SXAU9 zUe=$Rgtg!Gzw%c&xB-Q^mtu3u~!zfFv$py!y|)zky_I19&F| zk)l@NwsC@18S)&tr-g51U8?WJj}6!8)jb`3&t#jx#*e3tKOD9^bL}(_`d@>PH#4DC zYSmek_s6Pc-?9+C z_gZx8{H-8VnLTD1lUQrjH#NG9Hni$qVr~#siY$boic_+3hjrgFgje^8?QSkLEaP(* zP$KiKB9PnTkdcXF~-^JNWL|#Qk>#P-UL>m$yKt zIlt>k=BwDbaec5F)+cKE-A4#3?s5-0#@E!7gHK>;^cND9*_ZlGbibm&Izh*_7$?PO zlL25eATXepn0j{+qaZ)fe-iaSG3>wJFYyiy<}3=K5+F4Zh?{61EOb#W%Z43YA+UQl z;?F0QTwo)H?{Rw=j`c?ECjhX?dU&59aC7Q#D~-@u0bp5_=n*Jc&$az$BTkli$TY2V z_LapHPmVhMK`Ay%?>7I4Q0w)te zS;4VBPjwVlML1!1uo%y^tX>ow)P7^mQfKI^6-X{Z)rKggAPRE!WSRT8@s&T=E67{S z3o`ksMY4Aqhw{tNI)xoAVqCR|wq9z*lQ9KvJz5TSxbbiXDb@)jN5B0fC5&Q9)W_#= zV{*~#bxwNu8!3br3!g&(ovOEf0lY-txYM+aCeNxJC5>IZWP7+8@gQ9m8qN=}@pmYz z4%(_l8jqjClxMQ(-BH4qX;j^i#%_{j-Wc(U2bTFiK2nE1sQq`7c^j^QGL;68vcDr` zt!4+Vjc*B2na?rC4w87(*0I-p*UuR|)kB)I)_gXXRX1%RR&6A}rt>tr z_5`l3tQWl{rIxKiU)61zkk2 zZeW=|PJD;dGY}eJp5%Tf zoa0a&B98adxM-eUV2YWy<0?x4C@8Krkca>@T$ts^FgSnm+w2N|XVK{U;72a2tu7EI zlwx^dd5(4Vr9+ebD09y#=fS3(;KfX-3NlcD1#n1kwtlwJ0aO3YLjNY1qZ0G7L6Fjj zgN*w8POZbN8CM5lr@ZPUnZP(BQ`<& zu+|(rwLzdHJpa|+_nncVj#{#?R2e)1Rf>#Pf`!DYBeriBFg+>tjBHhB%p0P|xTk

    4^_e4aye=+s8u}A*csB;T5dk>_9M{+4spYYBs zdP}v=L%g9@pA$eA{TMzQSXmQ$@q1}~rJw9XW|;V$7S&W84rdrG-qX<&Gn0_zjjYi zg@6WBrIcorsEcLJ4^H~6vc`jgq8*$rdG`TLdzpK>;#+u2#D*ipZ?mc9Wg4{^O z?V-NbkTds!-RF6#zY6s6@PJ3+{~S(BOK$N&W4yI8s78z#M$oyd;rlDiRr{*Vq*e6a zT{y=B@T%}I2s|*-RIjAOdIK=-naFeRSYPFK58-8|#x_N;=LhI5`@G$bvY=OciqT#k z{(iyvb93&mES6h}jY+6jVD@HdCUmpAr@fXYN=T-{neN1 zh%gL2+q>2&Yv$Omdg$JPlAj{QRdtekqq1!izgQXVEK#gZoVW^WhjZm6-@ChSp5@Xl zYwOF)KMXDZme(V`3n2Ap!4Cv!I_36 zNEj)egdmcTcXA6`<+C=MLg=FtU#)#I8CGVNwXsll z5!%*jm)pmqPh{dPH=Sh`E`YkYN1gvUfT!~8zE`QIp5s-};K3?u2$B7k>ffeEo8Q=T z-y?THItxc71yM|OQe&rv z)sFCf_Q6ciqb{{Jy0@qdT5!O&lK@_Joz1kZNt&$;(!puFtcEr&E48jhY; z%>2i*A$sNQ&Flhh+dUpQS^7BqZSLNWi8~L4pVoRQ@K3KT_XH*d1O>MA*!KRp{hu)a zyB(&_F2=<4Y5zK4cli@nxayNYnU8?)trr5P?x{3W(XfX=+67Dm9+rIzcW1gKX-eNm z?Nv|l&xDxT4?~EqQ)eneGp2lSKB_)SgGX!YGktCZQo`*L3|egs8$ZC}=*#DML{Ni> zjzO-D`u_=!1|h!^d!G_~J6iO^g2;Ihh9s9s4|V{r-N2 z>z>|4t#N(R%G&5gw{5-HpVyM@*n+W$nu?lCr#a>%rYJU7j9!Z<_>nP z^lyP-P+{mvAkcuv^|F~danVo*N;duzjvzMW)B}=r&u@_EWELHO4d0N5osMn&d-T5m D^Xt5m literal 0 HcmV?d00001 From 8faf5abe383304c9bbf29931dce83d1975e2a163 Mon Sep 17 00:00:00 2001 From: tipouic Date: Thu, 28 Jan 2016 20:32:53 +0100 Subject: [PATCH 3/9] Correction script LUA + suivit --- Multiprotocol/A7105_SPI.ino | 11 ------- Multiprotocol/Hubsan_a7105.ino | 31 ++++++++++++------- Multiprotocol/Multiprotocol.ino | 13 ++++---- Multiprotocol/{telemetry.h => Telemetry.ino} | 29 +++++++++-------- Multiprotocol/multi.lua | 9 ++++-- Multiprotocol/multiprotocol.h | 8 +++++ sync.ffs_db | Bin 1274 -> 1276 bytes telemetryFRSKY.fzz | Bin 5198 -> 5691 bytes telemetryFRSKY.jpg | Bin 72125 -> 78564 bytes 9 files changed, 55 insertions(+), 46 deletions(-) rename Multiprotocol/{telemetry.h => Telemetry.ino} (86%) diff --git a/Multiprotocol/A7105_SPI.ino b/Multiprotocol/A7105_SPI.ino index e3b59d1..1698725 100644 --- a/Multiprotocol/A7105_SPI.ino +++ b/Multiprotocol/A7105_SPI.ino @@ -196,19 +196,8 @@ const uint8_t PROGMEM FLYSKY_A7105_regs[] = { 0x13, 0xc3, 0x00, 0xff, 0x00, 0x00, 0x3b, 0x00, 0x17, 0x47, 0x80, 0x03, 0x01, 0x45, 0x18, 0x00, 0x01, 0x0f, 0xff }; - #define ID_NORMAL 0x55201041 #define ID_PLUS 0xAA201041 - -/* -static const uint8_t a7105Regs[] = { - -1, 0x42, 0x00, 0x14, 0x00, -1 , -1 , 0x00, 0x00, 0x00, 0x00, 0x01, 0x21, 0x05, 0x00, 0x50, - 0x9e, 0x4b, 0x00, 0x02, 0x16, 0x2b, 0x12, 0x00, 0x62, 0x80, 0x80, 0x00, 0x0a, 0x32, 0xc3, 0x0f, - 0x13, 0xc3, 0x00, -1, 0x00, 0x00, 0x3b, 0x00, 0x17, 0x47, 0x80, 0x03, 0x01, 0x45, 0x18, 0x00, - 0x01, 0x0f, -1, -}; -*/ - void A7105_Init(uint8_t protocol) { void *A7105_Regs; diff --git a/Multiprotocol/Hubsan_a7105.ino b/Multiprotocol/Hubsan_a7105.ino index d13bdb7..760cb4e 100644 --- a/Multiprotocol/Hubsan_a7105.ino +++ b/Multiprotocol/Hubsan_a7105.ino @@ -181,14 +181,15 @@ static void __attribute__((unused)) hubsan_build_packet() } #if defined(TELEMETRY) -/*static uint8_t hubsan_check_integrity() +static uint8_t __attribute__((unused)) hubsan_check_integrity() { - int sum = 0; + if( (packet[0]&0xFE) != 0xE0 ) + return 0; + uint8_t sum = 0; for(uint8_t i = 0; i < 15; i++) sum += packet[i]; - return packet[15] == ((256 - (sum % 256)) & 0xFF); + return ( packet[15] == (uint8_t)(-sum) ); } -*/ #endif uint16_t ReadHubsan() @@ -295,7 +296,8 @@ uint16_t ReadHubsan() } else { #if defined(TELEMETRY) - if( rfMode == A7105_TX) {// switch to rx mode 3ms after packet sent + if( rfMode == A7105_TX) + {// switch to rx mode 3ms after packet sent for( i=0; i<10; i++) { if( !(A7105_ReadReg(A7105_00_MODE) & 0x01)) {// wait for tx completion @@ -306,15 +308,23 @@ uint16_t ReadHubsan() } } } - if( rfMode == A7105_RX) { // check for telemetry frame - for( i=0; i<10; i++) { - if( !(A7105_ReadReg(A7105_00_MODE) & 0x01)) { // data received + if( rfMode == A7105_RX) + { // check for telemetry frame + for( i=0; i<10; i++) + { + if( !(A7105_ReadReg(A7105_00_MODE) & 0x01)) + { // data received A7105_ReadData(); - if( !(A7105_ReadReg(A7105_00_MODE) & 0x01)){ // data received - v_lipo=packet[13];// hubsan lipo voltage 8bits the real value is h_lipo/10(0x2A=42-4.2V) + if( hubsan_check_integrity() ) + { + v_lipo=packet[13];// hubsan lipo voltage 8bits the real value is h_lipo/10(0x2A=42 -> 4.2V) telemetry_link=1; } A7105_Strobe(A7105_RX); + // Read TX RSSI + RSSI_dBm=256-(A7105_ReadReg(A7105_1D_RSSI_THOLD)*8)/5; // value from A7105 is between 8 for maximum signal strength to 160 or less + if(RSSI_dBm<0) RSSI_dBm=0; + else if(RSSI_dBm>255) RSSI_dBm=255; break; } } @@ -344,7 +354,6 @@ uint16_t initHubsan() { packet_count=0; id_data=ID_NORMAL; #if defined(TELEMETRY) - v_lipo=0; telemetry_link=0; #endif return 10000; diff --git a/Multiprotocol/Multiprotocol.ino b/Multiprotocol/Multiprotocol.ino index 469fbdd..d9a8430 100644 --- a/Multiprotocol/Multiprotocol.ino +++ b/Multiprotocol/Multiprotocol.ino @@ -100,7 +100,6 @@ uint8_t pktt[MAX_PKT];//telemetry receiving packets int16_t RSSI_dBm; //const uint8_t RSSI_offset=72;//69 71.72 values db uint8_t telemetry_link=0; - #include "telemetry.h" #endif // Callback @@ -623,11 +622,11 @@ uint16_t limit_channel_100(uint8_t ch) #if defined(TELEMETRY) void Serial_write(uint8_t data) { - uint8_t t=tx_head; - if(++t>=TXBUFFER_SIZE) - t=0; - tx_buff[t]=data; - tx_head=t; + cli(); // disable global int + if(++tx_head>=TXBUFFER_SIZE) + tx_head=0; + tx_buff[tx_head]=data; + sei(); // enable global int UCSR0B |= (1<-20 then tps = getTime() + 250 end + end sw = tpsact end diff --git a/Multiprotocol/multiprotocol.h b/Multiprotocol/multiprotocol.h index ab72a2f..793645e 100644 --- a/Multiprotocol/multiprotocol.h +++ b/Multiprotocol/multiprotocol.h @@ -13,6 +13,14 @@ along with Multiprotocol. If not, see . */ +// Check selected board type +#ifndef ARDUINO_AVR_PRO + #error You must select the board type "Arduino Pro or Pro Mini" +#endif +#if F_CPU != 16000000L || not defined(__AVR_ATmega328P__) + #error You must select the processor type "ATmega328(5V, 16MHz)" +#endif + //****************** // Protocols //****************** diff --git a/sync.ffs_db b/sync.ffs_db index 59c8138eb586a0496dd45c9b30047a55b7b6421d..f8a7ae005d708ebf4d1d02e67f56a37d87fff8cc 100644 GIT binary patch delta 599 zcmV-d0;v7^3H%ALlmdT<`HbX}UP}~&n}*o3#dj)H0ssI4000002>}2A00000Cb)W# zNdSU7ys^Y>sypF5C3w$yhI+ppn%?aaE?1C4f1QqL*(pAT&7}fD=n=xSJfyFA>Xb4E z6Miv$myc#3;RQ%b*9?tM4Z*x`65>f3t`kPK6b&NSXpVExgOPuf+`b80A0G0A31G7- zCHMUxh{5e!qs-j?^O>J#r5g1L!{6r-!%U9wac`qEYS;C9{^G`gmdty0I(2Fy|;(dzhH3}#^&&aDCXP-oA1xm z_IWXi_Vq|BZl~Su(%QJ|3Hk}JlmdT(5L(1h`bs{9rqVaF;z-z10ssI4000002>}2A00000Ur*H% zK=2PA3ZG%qAV~kyLUg0bFqrP8ZgjGR4|j=UzQNe_e1Q*ex!fd(84(oi5fx8iu%Obx zg12| z2Bw?&p+E7nBquG87Eq5Lc(lVtOnLkBCJB&zx7Rhgieg?UFgM4Hqj9iLxl{Zb)XrbO zsnSt6lfMHZe?BQJL=nFX7I$Pcs9u30z8)-Y!}zpkK8pAzu(&FQ`psbR91QWRVDT^v zbGC!U^D)%#0E@?Ci0=f8?_xlA=Ps~#0EYVAVDX&{eN2;4+`k9vFLZPEfyFmsn12l{ zJ{`mS{b2E<80H@Ui$^fZy;+80??JG5CPp|M28*{cf1Cke*GE;q6s-O>LvuK4I=Ky2@6Xisc`=GP z_o3m5?%%Uu@rMjAj?F+({{SrB#u&XBRs11X+z7+J=fL8P7~Ct#R!5iHKn^!_hu`hN-*-^&O9#*W&=1u`6{ diff --git a/telemetryFRSKY.fzz b/telemetryFRSKY.fzz index 7f3aed111bf21b0f44ae874241b38578ad07b63f..0a6f49a2e8747a66213e7e21ac55bc1f91a2b6ea 100644 GIT binary patch literal 5691 zcmV-B7R2dLO9KQH0000803ESANYl(4=eHFA03M7101*HH0CZ(+Wo>12a(PBlQ%hMc zW_s;iU6R{4l78Qay#qrN+tK?V2)`uJ?V1VO)$Mgmx7%B;?wNh6pd^-xVM)|VESJkq zdyP59Tw#y0Cs}|1DN3X$vGhYyLOD8GB0(~lN_;?mNMyeH%h$=+`r^+QK{&nYAOJg- zKOKa_U^=?${C@j$*X{h}&;R-_uO{K}aqL_7^C0>r&i#>G0RacN4-f)~19ymrj62X~ z?mg`LL&yiVjRxHJxW^FdvwI5fDIIjIU?49Bv+1ZK?rw>{SN+hN4;T8|@`$CL{C;@V zxqS+M@t*zpjX#LI>1gbKeEa5Cb@sYrML{(7uR8kVYfA{Mn$t>B%Ji+xy9u z_ZWrZ#*zO=;QdE9_SL;skKYJWy?qDSR%Hq#YN{qg(h(Eln7&mnflnt4)^A9{0t5kAhv zBYHD$9xZxB0eiUEv z$}d=SLEJ^s_AUi>=Fi!Bx#~~p^~?q|`tLtGwReyU&>RM~~- zf7GQ&*@goUWR&<_w8==So9j!Z?C#cos#@)_V$o&@7{Q>IR0%5Q(@{k{-5-MbCM5EKl0uV=GsFYeLy;nS(#WO}6&wYNozhC%K{8hM=&&k)Wm}W%&*C=twVf@#z?!#%MoM={N zU$2J2VkUI(SO3}i>_2DR6 z6#tkLgeC1JKM-{QqnLS~V64CE;{?fuL=LeNBF+({J`&k{^H@0AG7N4T>j@F>mAoPr zQwYg?2{qWMdz%jMIF=|K@R|H}k`ceKwWKJl>EopD&zm+?*lKX;JsUh(NMGW%aS&S| zWYaZWHeqP6rpXy-+Aipr&C@hJ15IZp4)thy>(t?Ry!^X(HG0!>5~EudU)5svE)@Bf za2$CfKV`}DKe?vHl|%) zt!Am1ER6_bV?@=B=we+tmT~2@1tAwO&TL~rl`QDu#&n6cn?`i0m(mgaNnBhK2qN!& z@DPxAc-W<9kPOLzv8{1cVy&Vrp4I=p;;Rml@dMA2#lSMMaqj;-_C^ay|Cb=JZ1>Yw zfi(+j5{wt}ApncNjxak#7Et64hoU=%Gj9+?&oL*`_k?zbWfp(L)$=ml<#pJQ-pPvG zh9RUt|!UH zn(<>rj}5o!Hls(I^jwA=$(m48faApz@Y}Lqq995k36x7`;6+%$HB#_Bkb(neb)o^~ zzuJLfH^t=@XrN+6-W{N#U79Wfi<4`*MqlfLAN}I>{qaVBi*NC_rhYV*H`r~vifEWJ zs2@N6YJGbDZtJF#VIa521mQHjavtwO*|gb2-L^LV6>0a53PfZYb>k2&!+LCAovS-C zxf$du*Mqj5T99KK1FC317fZZq>K+k*s5T!N)B>roplTLmh}Si}>`T1jnu%9O^$Z6B zx!F~%j54`f+$r*kx)=hi8pgq74uJ7DL&i4CN2-+~%nE#VY;1m2iZ|Fvs)vjv^E^!&=Tq7`|uA$m?>4mkYHfRJ_i_`$_ zU_c=^Z2wCw=wiuQO-UgRY^vjVgG3L)Nb8WnZ$E)JxWCV8vWgB$`;E45)0A zc^Ancnn{s<5|^J1RolS+TCh{Cp*~W(G>scYiZ_(1b?ZbFL)2b2p0r8NWoUA#k+cY} zGPS%g=-y2hc3i{H8muUk_w4xDGPE%K>{2Z*IvPKF`*-X6dtq3SKlWo&C`jD9A61)w zLVc{Q3UKRUF)2$~Tf@2ShJr6o-MPcl)`RI>T9oee@;G8Ob#NWP6OP!#^Hw(3N)+)9 z&nh$4i>0GootzG)bTkE&Gh?gOY_%d8y~ESWtkqE8Yrn$2)Hko0`c6`(xIiU?Mq;$s zz)~Ti2`m*K#DK{b(Kujm3p~4qdYe@;9tk7p&{?B#KFGjw4p)?iZ+~qbPX{Ao`l6o%dbYPfOQgl+T=)rU zxpW2U>v%Fwvj#V%*+L|R-7L^jrw za$pn8D~&%$k3Vp2{DFG-QR7f%{DFG#5#tcH*(u72QN)GsqzGOcKyD)^Q%;O#Mj|Z6 zDuiifFmix{WgLyEDOSe)G`;_qjb#n4zf{CcwN2BtFU4ntKIiIf*)i?nf*x-CMX(Uh z-4OWTLR6Jqo9jF75^oxXV}CA%O2b9}_n++Fwnmw%N32{&or2O?YnRP}skM-#|8%sx z4nnz1uqinx+pBGdcn}JN#o_^|rt3F^84f$)l{$$D>4vn6E-jnYY#m&%_3E11{Pa zgw>P*_xJ>+TG{E^HXunlW|sojIWC3C0H#SzYMCdH!BhB=UEvm#{0Z~c#&o(S#kOPR5wRC}iEJJCn zEUr*MZ7ISMkc7Wu$MFWuCbbGL%=k>z9vD6u{%m{O7l3DjS)CU0XJr6-ajedkO~WqS zR>6F)O~bEmu77|3;Wz91Yjlhq!`a){wp}AWKv=Y$qTSx#iw!6) zWStlgGdV)58qmc~ja7jFCQK$?h<%Q?*~EKlEAR*1ZEMi$OVEq~q}c;_0N%iubb(1< z++?L>-)*dyy$iF$nm67$x~~$THovE7-wL+A*gU&g&W$(K5wrQWas9PD6;xZUX*trJ z*=+G38*u9c6|)KVvLU6_dd>jKd3g_2cjEHIg;4H8VGVc5kh?ZU8aki=8JEYwr)E2D zqpZ3`=+SabXYj+gYHNJ^-mcog!|f`%YARD1qq3f&qm8Wy78#WV7pa0p1RTdE_MY|A zjHh;-WuUtKhpfa~#rcx||5uZ`yr z61f0vNJk0NVk)|c@z@&HOJ5uxw8PVKbdJ-CyhUyG5A*EV*>3&W&qu5Y!i;}-TmURTJqo1o7}$!>CR$Gt)XyGm~2I%#qfS-q?*PlL&BQh1fgZj$NG z%w#v&bbaHD@JwtlpH6HeS<{s9_5|5YRGE)1f_RzVggNJ$--PjHeiNH!^P8xF&ZIbL z*OZx=6enw992qFji%_Xtb(+b%emcbo!2n^tPlgl308ciBijUmRrZ}-z^T!j4R#M0# zTT{v=#YxiKq&Rsoc(#k)X}YG%0QBORoev*Bbfb{tuHPT5>jhU%S{qM1V_xTO5saqZ z_)gsa?)Ep1?|ypowj}=HKWj`7tCIl431XKi1ffHm#&amb_oJLE7KK27WHtNtd9dmM zF5nK{?toW#O5H4qU3Z3-tkB0}Q4j}rcv5KamC|d`LGkPcoYGeq~fCSGYd&P%+z$tka(+i zY?>cx*PA9REAknWcx|9cTUU0iY#h2&s#GORq%ulCuYAh&9hsY=!Z=hp;~jE=>m(~m zhsb%iwdPt}1pvh_h{b%+b~EIylNp9wId7D;!P9{V0~<0YK@R9ga2zBs#$5Jj-cuG5d}=ux4{wg%_H5#76Y$40bk{ z)Hw_K?1D+1vLs7%Te-Dek}UChlPqDiVUut>-Sy9b%@`^!IY5Ok7;o&1a{##5VKT+qvPVqiPN=ar9JaRM9qehQ)MAq zqDK;X%DG*bEv?IebQe(q9pW=_FvKPuZiC^&6fwD62&u zv{Qh|r4}zqz{7FUJh7Y?R+^0cGE4|1IOC`#2aKcERQxcG+Nm(aIBLrv{kzWardXj3y*uHkwjeRoY5GprH8K11Fz+rr{Q-Q}N`DE|r;p23;$t#m7aZ0_i zQGEF>J5;}f= z;Nhq9FE=8B$t#a8$v9WK5)Q-YX3mv33N*wF-|s@RSD|V4Y(ij)q`5fcsK+;R4zQt| z9K3Q(Mc<6&%g77li)TxPpqQOWIq^5+n>DSk$_!iW%yidEb)Rpk+5McfTA{@_X~zYY z_9Q@Sr>f7kENfL~&Ca8U17ZTFVEckb4_C+58E>soHl2ZwcI5zTr@Ak>Flm|J<{n^= zIiWTCZFyKE_U8SdT%K~$_(9puEUMMsV{@zEPSM6^#=Bo&AF9Dg%zTeFB3XksCYq&Y&)lX`PyH`HaT8&!A84(9+x)g^VP*xnkBuhebn3l#!=3mBFYZNM)Vmrms93?p4q;byqYPCX& zanz0rD8^Ac1(sZ_qo%O~r??@D?G)mMn{m;UhsO9`b-Ij)c4X)<9@?qkd>L6^C*$ej>bw7b45J?(qG8=c67LSlScK)OkxiSGNX;1XF!N{%CK)ulfwMpyfad5q&m(#pE1tlB>QOiU0nD z;E$FRW@H6J-6mE3db_xx{57omU_92X`(tnLSwAU}fG~aFSs&o~yS%t74Cg_>x;iuo zhQqP1Pp2Y`y}m!z2N%&i{OosE-a?;}wZOXzSqxkqKr1KiJu#Xj5?s&2U}$~vri(<@ z$@qtb7*CRGXTlKu`4@lr(%OXNOZTMUs|xFl((mzC`7!mMsqCu-0&*+KL4ZRw|ILAo*#<$1=X$3C>20~7_6OAA1cDMFeEX*JOh~K8)2HC0H*0#z;tRv?FH(}*-Q@!)Fj1en;{L4GLyW$ z36)L()UNPBb(PmHrVhZI915&6T- z0ssIM0000803ESANYl(4=eHFA03M7101*HH0000000961000000001VWo%__Wpr|R hMp9EtSuSRJP)h{{000000RRC2KL7v#<`n<{008FV70v(v delta 5179 zcmV-B6vXShEY2t!P)h>@6aWAK2mt1*J4lO~vbM?-002ad0RRz`5f&7G?OofFA~}+M zU$gxOjI}lEeL(0M5o)WNv97A_vbLGNYCO_EYvt zRthODfCvc4KnhUSLnUNf9LM9x&ymaZ=FeXqW}VORVmVFbZ@UP~7{qvvx^AV+mGY7-P`BnuY;F(aTAYLgZX3@ z|N8#jPwKB9x}DW@HH+VN^&g*RgGERDz0>R5#LMZ|!EhFLJJb1pQv7iw4ikSu-OlrL zy!!OE8vz;wK{$Hoc0R?^$*0xZE&~A-KjN)^W?+BK!Z)9%@$;Iw@{P`X@F1=}T*QNM zdidYOo88WEF#2P%NS@~7_sJ|-yzTzmefrbwOcvAeZ_}@_^d6edyPf5yrGI?5vTl60Xi`B9}N*1wrQ(xpx_~dT&oZQXiwU^+3{_A76WJ_w#<05&C7poWT zMRlb3@PpZtc!}5CZ8{;1=luAHf}r#h?mb-ve||m-04@J)pPxQ+f0EDAo4)#e2K=~ zXlBJh2Eg=x_Uhhn$DP+NZ#rb{0e$uRuU&ofJLzvBS3i3W_CFi%@=w;g`RxXhpWY#e zdpnj_m8qM@?lyS+i3{=OM_9=WZ@*3b1B}WKN*1ShdCNrCy^OZJ9J%jh z(t0lkTaTlAUZ$=0GG|u3Tsp!yVAdxhHPb1qlTZ@SVn~g`$|3c&N1Od7Z=3GkfKz;b zioZ`6Zat^c#IZScwD=h^RL(N@d^&jP+~%K0)$8BJcb_#NP-~zY=-) zZbCNM!^QRyPC~@z%040%gRWG%gbRXyl;DyQ>FnXuqMUUy`RXjR(|EL$COY${hhe;M zjj!$vw)~n7ClL9ExOFbiHyG)pV@hdoU$z|(=@!F12l^a4Cx${y@^dT;j7+;oym zl6FlV$?>&vYV}#1Y?Q@Qi~2{J^f8^S-enY{dyG<(-G`|4pOe{YFo|=)eme?(wMwrn zsy);7IvHKA*Q=~f=R7C^jI-c;@m<=XNIZa>j9LwXr{~{uG*?E}G#L*mt7z=7U z(sBxg@?W=;JPtJ=t;yb_D0d4!OET{1n)6kD~#!pKz@C(D8U~Gjg=a z&sDgQ)q1%C8fT|{#68-_+%qY(V$#p?>aT-gJlkp3zNvwEyqd`i9Jb0z9GI){zyA7D z=eHj}?p-T2p30S7(`251pSegEPwiSGr7mkt!^et`BLWa*YLt|v5|Ek~sH9i9TFq>G z+S&F5ze^gv3MEWA2z4Z(bfJZhqdIYP%>up#qaes5C=7f6)eImn-fMq2mNFf0QX$@B zyW)LT#;I4c;?P8=dzpGq0An~r>0(!}#LSrl8=e*mqh`8<62-qH1hIa%|NJdIrv=$(^|b!7pUVvUw~CBlMi7yJ*qOny(@sja%<4K$RT!kio*H9|HPcn{BW0LXhe|5gO z7vZ#uXK@+=hIZYjsmI%QuqGr^-98QGLNW!EGq2qo0DZ?d3Oe9!o27;kHLS_GTG3jC zZ4Zm2AQ!E@)!J_R8R_{K4|W4p~L(k@R|p@^R&&~pT~z{F1v zTsM@o$@1%V5&mOw#3Fei03cR_k{7r3#v3)FkNq?^8!H+O-0V;7774%j*NcA=O6O7v`T zq(9>NaFK21BEHKgEbs1ewmn6SNBhlPUVlW1tZ&ayHo6YaZJnpB&p4HhzT|CmqUcf= zq#U__ab_eDUv`8`M>R-AmVd^*E!wm5T@^Swyvd-6zPHZR)+aX0Mql(UrDb@$lsV)* zTRR)3XjJKBj|YI{8w%G-^`TDnH@9)@?b^ptr1*i(_W2p|{GLF4o#k^1REm$(h>)f8 z;$>hXySJ32w`BkCs!_<c-^=bfb#_~(=2JP75S zz^?M$8+)RkTF6N$FGN2Aq7b5riH^PcS`-xe8j=c{%r$a-tvvpcU{ha1)OCT)cw#Ak zSnAy{dG=b~{$mdv!mR5aWuq@i%i9{p(9RMkR|c}PDNK3qGDHQP$Qo8a0vL5(V-f}< zu9s;r3U?O}=V#C2$sytNm`vxZI>DNrHH^Pb*g~VVL%wMlkraM}H1py#gKl_M^#I;$mi~&rUmdj)s&EPpE$9tH7 z0P9c5k^Gbf-AoL0cBaL>aCYnv;;f|8I^nDeB(Fx&*|VNHg8NqboV1?$yPFTc|M>GS zoo_y%CKgkdFKHazkIc399>FAetZNG#)}AIzR7Ie2)dedrDC~l>JPV80H0t| zu>u%DyGww1mcOXnB{Hu84nY)Pq!-*k0E399Rp5Rduv?hXo(-H^?rFIi{vz|lqZb1+ z4I~7phEjRsJ_DWvyu5%fN*DTn5x*eVwIFX1oV482B{;bhy6`HCf^C9|Ul@GdkkV>D zmjK1HM=kz4#vYG1sl*;%xhC;Q_DJO}f1wV06E-s{w*jOIn-K`ZfCPT0V*9wUJxOMp z*OZOEI2yU-ZfLPjhI0%uum>idKsJpgEvt=drMscA%Fh)zvBMxOf{G`9kj+9$dupZH z>1w!L^W_SboSi-r_vqu%CY9(Tc7;A7q9-6jzzH%Tv^WMwp=>^!Z6%)`==q~tm~nLd z)B$(fQn|ubv?^*VTiq5FFMl;zP0AW>WtS)tSY~cp3iF*-^&y_FItyN}zeP$FczJTX zZcW4B<)>In1lbaVd2-x;EP%cCra4vc<%#&&pzCTTbN4l)K|wp3(V#yX=|%I(#JxsI zzuGg1%7q}h7Y)IJn)4G{(J&YQo~@o@fb)QL*A?7SCpbdUS~EBl=%L8>qsb2U{b=gp zEA#zm42Cq)R&A#i;>uWd&VDqiwxH9ccnu?nt8=ulc4lPN!;B!$^Dd9oM~F1(a7K z?fm@f&%IT`aW5W@HvNHX_ZUv`G8K02mea|6FuN1izq|c~9F zAvNw|ThIz@_tGjG-JGB$QY3=2DK#I2n}=CewA!Jnp1kjW8{&Y#DDXjOKFqeX?`74j zCrD4QXQWC7dNc&MR=?HyqACG2lT@+1*%<^?iU7@eCerktMm-fXm2P=Gb^VI2afQHc zKgY7k7p$kYLA7q(?s!$>(AB8c`w9{QF<{90mo7s zFcu_25Wq-(70zdG1t3ylh}#0T@kC#c=)@>i+DX@81@|Jfa+f+)=P86^St z1&O{Oar@XK(9B`!%oikHazUb3&hmmp!9ub^JtP}%Tw*n1z}1ap{tiO6OFQ$mh~_K0 zmZgbYi7*ZJx z;XyXx%XwgIT+!nIsvY28(q3Xxp$jp@z5}&mqfp2V)r*b}^zHKW<}6NVT8!(=V1MRL zUMK^Syb~b@0b|I#)d&?-KV7n$Vo8KUCQD{~J1=LE8HZ2|Y#BtM_CWK;aaT7o1h-0ysJJRK6Sk9`2+?eQzb4ojD%ju`|EKePs z#S%{)&ju!b(<03s?P7{&kIf>AXOHIqlWX69vWU4iReZcjCGN=Va>qcoKUT#>ayz1Z zla0NUG@_7Dx!;i|jV{SeX&Z4*8aJ(J1e#qI_RdWjao$8-C2nc;FimF)3~+)Vz{T`{ zXNwMlh-ZsuLlMswHCwazzECO6QM{B%E$rly&P7 zQ58fLL#YoXXIlHceoA+I5D`p@AQDu~2T|=H^6QqgKO9qjk2k5L{6=<_-*ByJh|!Au zQBR>&UgvFsSNY-~lQoU>xij>xaR!Qi&#m*43^M@L%_^B3*X4qAlQaVmByzR9#1KS4 z$O-aluWJGBYlDo|TpgC!5qqs7ikEzw#S<_2UMG~Cn<0kobt5?5q=F%mSKiU9E<;qE zNEwCsnm@U=L?Z4^ridav8|V3=Q*a^2*;aPoY^S@gU|;Z>%#m(m2?r{dGZq|wmh-$Y zedU>>Yf)YTm6kQaY^A#|cN6Nt`7 z+)=lc!KBnB-H6Khz7>))Mm)rR>d`Ss_M2)Mt!ZR6hwqJEkVd^^8gZbKwiHGvGgq1+ z0w9Mum}FU?XN*n-xZhRFY)!*h;u)i6j8-AV)5T^1#nZ)eV9CYM#o`Tl*qgp$XX4lY p2T)4^0ssIM000080OqR8EOX~BpU-=Jy1J>A7aj^v|#SyK^s3^c#|0q4eiCn!v9FF<$C!E#s~lGnW2aV%pK_1lHyA{eX6-d@m?s(q4U%hFvON3>1aJ1FNWw zP1?}c7GMii27YfP4+ViUt^V5qjv>_w{>ZLfp}t#1p{e`kZ%R@-%7AHhtSMKw#W0!E zAkI~&PU3d9!$tx+=XQ<$jyAQ_y38N~y;W{Ptd0>Y+6iR^=tVE~`X*DjkG8djc8guN zv`{uPkKPIQ;nhvl4OUUE{p`v}+1HM^ds7>&_7QHHwC9%b8Fy%a5^F!x$MYV`LT>0< zdx=faoN3ypin4$gl$aSDq`it-)Wj|pimc(`$sL%NLG5zk!iO&*N1fD}DK2}OodTOs z&PwhZQe?nY6b^J|^6+Cn#wvc%*R^A}7)1IK`!on@nsc;`-x)0X65J|E<}!Eu(w|%A zXene>15NNi8m)RstT5h=uUcN1FNOw%k5*B!_w5A_4dXG=R=X*FOt82W9eA<9}G#pi+NH5NHQW&x(%2@29G1VukOW z)60u%z*biYeHAtRG}lZ*_vJ08!n?`VZOgz$*qpLcLT}mwvD;uPC|cn77YIm%PxyUO z^HJuerPJd*X6^n;EY4sHYzPw1`4ZH=r&pXC_q{^ShGhaoe^Y`7+0$i+8HohT)9%Y{ z3}~O!!efvvi~utpgEP&!NBW!8Dbm@zjx<5$iRzd3md8uxU|j)_a4~^zOQTN`mtDMx z=FG&eg45tP4NU*1e!!S`5dBPQaa=IpiC4bNzPL2%Dhz|d1dbi6C@E|Z?$(qFj77F3 z9$H25m*RlUR*GB-5&RA3gXuh*ghWeyFnk7^25X8>3xX0@M)Y}(Pff1!fThLrZzFYC zxz%+4IqsAG=@qt6QBt{xy}XKw%RM46Ed*ygArk=*Fiq=VB(kfc7G=OFZ_Z^)U)@$* z>XfYRAUeqsTL5t!Y6gF?car^AQKvYpqkNhS)YR%cc!5JX%2z-1CFbzyCXqjl_`{@g zK~Llj_pxiF5&=TmXeOVuu!_>X*JMgr1FZuCgpVMc$c{|nZ*E#Iz$URTEp3^bRDys& zK{9U@m1?y!M3$c>H}7GkD%e=Y%K=){XbHddF>PEoHNUQ5V?XC!y??2>h;7EeooZ7H zkzhAJhtY<)XUbM-Itur%qG~X0ecXIu92A!i5yUDyeLVkbyUB<0NIAnd8e3@|f(^^@ ztaUt$EachJv=!{gDJ8CS6mAU*%4@1D@w2<}0vB|7&2n7&t%ZX0e-@4a9<`0tO$sKD zCu+Il=lTM#j#Rf_)nC%TXyoT}`a+caxp9Zh;crBN@qf9T^w?fzBK{X{F(0X3MXg6n zFLn{;U_j?IwYi2QY7YRqbkoCyd#P#V3$Yt0*SI)Xv#(_C0m1)Z zzqTk+@})8|0PN-kyaQ5!856=AZ23r_`+>IoB?sQOZE#ozPK2OC2c``5H>OnNf;qXXPLafRg6;PAUtns17hvl zKE8$b2o9WS%Adi=w`Ds27~_)fv~%N`<)gE=5{;AfMvY&)-5=@QKD2J`iQ(nE*L5#5 zzK`h5kAA-dR98RbYrTG*)Ym0CS2wc2C(P7}Y}j0Xt;jol2|apWiss$LETH)<2HmtD z?pqQm{}<4JAgDGJ$JZ4r0Q|)&iaVI|cyZ{uzmX)n$uOh=7tabWo@j{=TaS*`vXUFQ zav=2lV@o{&20!v!kD=Sr5bXo}r53b!7PN2&BpLeH%aA4Myvo926nG2>zB4l(yKR8O z!;5zZbq>yF{!{k4`B-Lxhdn8R?=;c4aG0=!;m!oVkz#8vK4nI!QKGI_;knkK;gJ_J z<&RC&HqM;We!8su?o06bhG@rvx{Q-BjlC_$OTlV>! zau1WdG&#RKFYK2*p_qv-!Cipy&xmtz9PbGCGcIbO;jh_Xk_; zNiUTh0zy5{lE!`t71;gQE5LZP>xZQ)`t;9&-1r9nVz8R``S(P@1D0Bf54E0`s$p8i zsvG*d78R%gqqTWylG~+feAo3n`aA{%>`Bm(Uf&pG+ujmJ^mm zhZ!VKv&S{x^biXOBPYIm_x29tMD|?hbF5;z?%WP77ml@P4v6J?qtew(M68BM;1w)rEpG_#?- zU7QuG+unCCE3Pw@a-(3hH}D}aQNxy&)Nbj~lu;|@yA7A)6Y zuNrHPj3S1b=3O1h*xDDScxcK`pS2ts8np91Bm8Pz2Gh)G^X^Z|!k_Qm>^7&=5&sOY zqVA-xqAszMCe0#k1qR47Y zT54EF_}<^(>6JxW;F*wdvu-1QH+dxN-9Pr%>t2h0hNO4xG`zaCt?KQA%q??rSuhSe zooq(cMOHQw*|yWGC=wph$KAVP^0rC(TWGXM7H;9%d}NMzn9*b?yGv$oP9=*kG+dqv zdSv~gw&D(7p0sbs_^midpvyPSHN`_7J#?Vl9JTj(5-PnziUsKX8TxO{uonS!il^j0 zYd5lFeHTIx3#*Vz28xfrl$14XBj0gm9u65GA8ui0IadmT{&L4>@mn|!;P-n1oiA-m z=ILTnr)?%i^JYff5+#nNU~NaYD~L(0nQ$23uA-cWEH(L#J4CXhdm0d9ecjLayP@WF zU5@{bWPtdu)!2GzNm1UjS<_{1Y=hka zrl!q6P4f1le^o>qQXe@`N}jJGOl!B~b(^|`U{&EX#tvC{L7idm1+7`E=fo&9X zsCt^DC^i>#+zG#}Oy}XZe`7XmtPf2v|$>7Qg=2`_jGbK(_l-8++Wb zm9{0a4>E3gH`O*Eb{hsrJ4o@l7-&k%UXsCndA~AZYNx>!t?HydCT%Yt8cB7G52B(? zAjcaFNZHH%Z%5lzl+z2?)zSvwIjJJW=2F^PBAqv{5QY&eZ2Wo72`@6;y$5Q+ZYzhYUlWem{}@a#zEP|Z{1b3oMXj^i46Or%5zt|d|oJaUn$q z3NMDZRK`PipH~-v74_G4BAks8tr_WnvW1CI8qzta1I_mA09-1d zVyRvdj5N-j;%#Zdo1j@6{$7JY{sx*@lO~V7LQ}3eW6jUrVIlKfpB@oPYR}zLEtt9+ zQ8x52M(-qK6J6{tjY}$y$1NRVKU#uJNG(3NII0HF?7Dl<(jw@YEe!-*r&4d4KCR`p9Rlzyhe2Dm*j9KQfsQP{KB=%(@5Gt=Zc%>kJ44t1|={z6F}D93`sNS z+F8qE#ApkOhNM9Mx1WcTi9wi3g5??k!wY;G#dK154g?Sz9>axsPrQBlTpM!d-WPUf z7Vfh(z4qwB(|pCxd)trNbB&x`lCGr>7&*Peo$A0Hceons9DY}^aJx-!SnQ)Oi_$i| zXI(s>PW}^n#pR~$p_`bdsh4RBsnfVoYvBoK15(plcm;m2lBHM;uuP)MZ7$cP@%vOh zs@BplWd8RJe7#lF4rt0%AeF?}jnQuGs1WvVh~NHzTKhcdd2G4?To35!iK0%fqMr3W zM#BCM9DK}sh;IA1kse}P&*)wZ87S-_;xoC!#XZEbACnx<+TkB%{&8FIB>y-K;tx^C zui&3PoX^7H(r}+SF>9ouv4T-%bE%Ua{NwEdn=(R`qh@(nr@Ex9OS67cVq#TB(52n( zZrj>!tZ9dcotGn#STylwR6=AY*vpPCoE-l)x!X||&_DByTkz6+bWXo$?qFX4 zpib|)?|u1ufYHa34CQZQcax_9d5RRj3>%k=g+D^oGc={_rS&1)h!y9?V#>i}oA@8X z$s<`pRf;Y+*rN84PS_oGnNixg{(;4gY|of@g98(_k1vIqW_1fP2sIqhF{dm7eX{3@ z=&9-qQM(7=hMHsqWD#lxSLlAOPR74)7BORx?5=>F=Ey!t6DxFg_;_8-x}GYsCC_mj zD(`LE;V5k&)}Ib_{$dfl$L&7020uCBce**M>p(&E))JK!N5)qLSnl?K)*vvQo2$*b z@z9-vU?DS}aZ27klSd**vfp%6Wq1>X{o1cKzXHzg6qNpXoC?@Q@~-YIG?0H=xX;0b zd@K-o1sY3Ph5O8YUjD<7)7}Rf$~jzn^y$a%8_q6IX-hAb_Puk7Zv523P7RH2^Wh^N zF=QqCB+{|@DuS{Zu(Xy>ToU<`FIw}vI__RsMa_Jgy}lNDPJUA7FMeWZGVw9#c)$0*C8+gBKO z>E*ix>j(UTxpj;}e`~%>&2U=F&5th$p2`o%nYa&;+8NQvof4UPyhh-r-ZO5wN^FO$ zeG?15f!%}@8eezZ19;<%qQeKWu2%}Oc@uTT0f+2N=nJMyv#iuA-1--S`dHz>Bwv@S zVV3s!?~1u81eK_A&WnBlcTZJ+DJ=PD9~Bb~M)4Nghu;^dYG>g#6UyITU0c$(De=XF zXKtzPN^Vp|pt%jR1*j#-0nJBP#Lc<8h9jM%oT1NPYnwj?x0RgMW@RwqF%az}+nUAl zRAbyTV2~E6V|+)6oky~>ymfqrb{6ny=EF8!?Z^E4 zeVe|oqW=Btnl125+V$0JL+cakGvV2>)WJw8v-Q7kmgtsoJOOI?M2KCo-EiT($)f>- zq)+!xjTSs;@Ok(4+nlvt8S34;<1TB~%X^SQo5q8pf`rLsxLWQ<-w&9Fm0$pSh-$YN}g$} zo+6rY%Nqi`TlshyKTGcRY^TA6C7)17Czc=9ZRlcM6BB`G6H?1P9t%h7Mii6>3FQX+ zin5(d;@fHlos0+Vi?Rp>gHAf^lbxn7kBnqH{au*~7;_2b8v4jPMOnxpPC8ix6UY#$ zsNRM|F>{q9^>JGPNf`v*bS?`_8bw8zr1}%zV+`~uE;k94)IZ2|- zJf9Yt1wP>qcp^t--1F}Wez*zt#7;jmTMh%7TUSw_^X{Fmozp?Uw_y;|o!C?SaX!ng zQ_jL8xA&5@2@7e&l&}A^bf#Bv_W*HzQJ%j%`S=8?xxh0;w{F-HXAHVd}G)85^|pW+G^*NtG)%NqRmb%&gyP!h)DN8art|B#p0J&-oR7bxMB0; zZY1)(#)FO-0xRYgI>Qc>a{utV(Ps0qehD#G7R0qT+IbD7_Ox9e_*mr02ro@nZ>tmj zJY1fs;Cu4oRztJIfk)RYcjoW2b+ml9xcA-JhmAqeNR#6EBlxr6f=j}dX>A#YZRhMB za?d=<)22A(6w25-%-a$4=<59v?|vJl<*&2N>GHy2K&CWiESB2K$B~4bAhfuo*}i@mo$}o!9Pbb8Iv_C%9f%Mov3h z-@q|>!}&QeuTs?&eQh~vv+p8l8}%(7v_tk=tdHGE!Gjp#Mv&2boKP?)H6wM;QV#^| ztRbHRCK87}+Yby}o1BXtUMAUz=s6T2(X+3IIX@!x9aeffdcHI?#3Fdw2XPcw##>(8 zja1!k!|*|B&njvgJA@>Q2b$OZ>QNr&Ww!Kz@RR5nIcL3Ny7sR|4lEb~COgiT+iJg&JcHLlUxiV~I;bIO;yC5_%+#$WO=u06 zJ(DI@{EDCjsv<1>R)y=4_JUkC-M8?2#&BF$c!Jq)h50Bx0>&&SS{|ET1Uh^=6DXcD zw$MJF#kj<UoP&Z8y{I{O*b3CB(v;$s*f+ieG+nV0anX*JIdnUuc=v?4;(v zVy(XU%-McJ-2}k3Di(g{o9&g~aJv996kde9*#9+>FKBWAaTPUICe(oFA~`V%3KSg> zpNG5!U)!gY;EjZ-st%?I2X*o>Nvw6H;sam|tvLhk5frh{gD=U%HY>db!73_+qF-P~ ziUfjq^A_1@Iz70rSn*aGKPZ8H-l7NZ0zC%GJ9)sENcc(elpTWM!h^m|Bu(27O-HEB zKutmiE*@WFlaYP-uC;I#wH5A37w>>>zj$}u9!XA{mi=C*Uo1VqyoLF2>5fPR*)}ap zR{^>MkY*W)EZ~-0O{fy&a~ztW1hDluh;L5C^D(y;YR7$j7q|WFpl%vmtN<+SdC`8C z-mSd*>F|nU+`YY4*0IAHl(U0D15_jG7y`}%q*!(xv)##He$V`g5jFwM9Tz?juw%taVG3!7Ch_qYsX&Az ztX`<9?z)^SeQNu&|n?(u??V!GC08RF3<=eITB9=GqM=`I5>cI;$tw5$)+FfIks=Dcv_n_F7Z=sG5 ziyE)Bs0Z+*^DRv4bF}J2(TC&%D8Q8*B z=>WXMdY}!g*qtYvQEmPa*gB%gQyJL6H7Om+^fCnq9(Q_wx|N8L#wPZz7{T_j1U$40 zCsyokV^@=!;~)jII}2hPUf+G}T9!9Rw1)Hr7Cgg6`8*<9&Mxs+Uy}d&0s6)ql{SPK z#KwKWDa|&-HxkQ(aRmrSpY&q~V7;NZA6u)^N|K@uV?a-YcL)#~Lp)xNLL0k^(TpDj z_*09FJh9ryuX#OMJfLWG>>EbW3PafnQZx>OcZEN`P3paboOp&xbCY^tU&8Mlo&%SE z>-$G{Cp*49&O~8Oiglp>;?+q>KAq)?UO@H&(&2Q*1hjCEeE~|#jw7&s5aZrTWM1Lsp*gZ5Vjw%ZWW=Xz)-v>&7mxPlj62Su0Akg&wUHR>rj{`2DsC|Mn7YL8eo< z$cUcvQ5Y6--KcqQG;NH%0NO@I`&Ic-`yR@e1aF=~eQHXc)`PcE5%#&tCSj31!yYqh z!N2Tm1ICI0VItC;7)_A@{?a`J@4ZXgY>5$sPj@!6cS7MUY7>2}Q;Af0f%_^dS&Rck zX9dc&ywvEH4D*cJg-Gj5$?z%cxt|%m(_>hu@njXHfm~$N+G76;Hue_|cG=q!3I;;`In_j<6v|9`b=gYKl($08QVdfZ!Dl(0XguN` zo7FZw@GxcQ;X@aKG2;@)BcQdApv*Kk`Tj(a{OT28z}I_Hu_tRXbU%ENJXVyUd;hP> zhEq>IzS`gJ^>uL*9D`KQNc{0XBuV&gJS8JWLpS*NRE-@Yzhy)5&3F`RH=*30xC)>) z?aJX!xzkS6e-NATy?+_r+QN8&*+RZ4a(;+eOD^igttIdMC_Xe?!8Ud~OoVt2sK zuqN^(%~W85Y64EOc{z@- zG(+S`-qYtX=re#<2&tyv>njIFqLaz~d@lobpp(WVPG2kPtU=z|jep^fd{5zf5m9JQ_?~ZvZlP{_GQ1goL zHb|dG$gpRJmwmN7(pK)d@#28ni~gML7p^`o^+<8!;bnoOGTU;Jb0lFX!JM^!pw#8@ zsiu(dr!ilDP`Ax!rv6tfe<|U#_Mveqw;9&*+ieRion?3UqW$-~z3|BQpqV$C4}}cp z`=E0l+qX^y0=w1N;__J@All=JS*aD<;5m)J5zZ>=C3{gj96@JB`>{kwym<wEd#Xc;H*uc+(KI-vXYuY_rQgN01>BmS2VNr@kHmaQURv|tR<*qQG4U;uD3$n@ zm>_wBE9a~*^CsV-Z~pjlu4b>uXQ1J8q2|g_;CYhXJo-)A8w_;R0zO+jgBI<@$gzK$ zff8yr+)Mj$!fG2Z8prFCm|5c!XyDbpHqv@>!Zh|S_Tn(@jKHuRNVeJo79+(EINqY% zQvvmz87QaVgErD$*gyADDCK&G_`n$v=q-N;`kbW5V)o!K-yOU>V)ZPIiK)H@gqX57 zu%zYw8VGN3=_Y{NHmI_O*mup$zd-p8qL!$T3gj+NL@T6uP^LN!mRn?gCoU zkKcAmsuh^#fq0z=mzELwZ7;Ra2Ec7@|HINAhwWkumr~ou`x)F$w6FYrrF^@OWqN+A zsDCt&w)Jm1Qo`En(0v4Kt^&XK4lF}af>H&z&PnY7%5EM;ntYAF>@C<>d#F7qNa^DT z!u6M}sye=lzGs`*wFAG@_YCOKt$jJ9h(%4OO7@T;y}Vc=dzil2%J*M@la(H~ldbL% zA|IZeYN@f`>4cuQJ-0t;#D$>83|h$z^WT0h-=uBGH3IzOAK(-6^xWK$fj0p`+S2+# zrkMx!)IKUyOb^wCFi4S&l#g#QLPVlbJp>`QUC<=Ym~~-4#Y1Kyho(VGZIKPRWw3Q} z_W(;%kcMa!l4p(qo95e;(Z!}ER~C(xX`X``9=Ync)1ph6CExJD0|pf}-%N5e&sFAr zHuxn_WcLqKJma9Z0Y@C}&Nwv6xV%4X?!NEB?(J?Vx%)WDk_m^Q&#D7$1CIio>8IxR znie}3?Edrh4jBr7FmgvewDF4VjC=RG=OqMSo|KI!v4r*KspJMbbJbSg<-Xa^Q#As)ccE#Jo?R56fCPM+CY}nR9pBE z@H<#$yr{cdD<)MTfMNeaQowRlJ03~o-@UEj_{**-KI&htwOq~1Fo^!I>zhyBQO9;V z-SF(Yy7MK_>f#=_{rsa!lR5jN&3ju?d{bN_^_+)FS_-{wpF)U_dv_ojcM;!d3?P|srNO7|M{ z_V^!8uC^~5D;RVXZVFHJiI{8td7^x`%eLxsA4;X&?v@XPfTdEG(mku~iyqi0x+|xL zi3$KJ;`z;1*o&uXC9<##K@^U`bP>&3NsyLd3u7#gx;;&{TtGAuJAn*D5F?OhU79pn zMcs|neHo*~LN%O#C}jWNk!xOL&(OVh><)?&G8dOcdu&AE@O!F`FsIuhT!W~YG7Rwx1(Nk zU`}nMoa>QLkI-7G4ObQNg;byYpP}mfYmUg_*GP%`7Ns% zMl<#v20VdHU@HOV8DqXe0|CC1w)G9-7iOJPiCCpTsFufGhxj$I2@3@Y@)42Kb`$J< zU`@p@FUv^FEUCCAJ&G~ZNf#Rll#6mTM=oR>GsAHhmd8qcYG75;2O1Q(#Px+AI*FWD zQM^1!90ItnC?KHz|GA_8b3?`~eUZi(gewSE^SnjbP)I&sYp5W$HNTQtM2?q*Oj3i|9uQY_2awKB ztkBoVuJKGjZWp*m6gfMAK|-PA(Q^))=S}6{rQofzbsF0nlRK^}XBoC(04YSA79;4p zPq}fP&yMrA?2lMHNX%V7)TG@wT+~>^oo~VjY*S7P6{4lYhn5%h|BL66VgURAx2&Qh zGDASCA$4Ht*FzFF3b9P|0s?P+$oUI%7?JATT1AD(p@kI#*iamIN!SD87L{fg3HWNy zcEhoyH%$siYYga*Q~UgP4vMh?%{Hp608zwQGyI(dW&9o?o8ARXA3L@yeo`HctG)l7 zcOfC91n?7lZIf8HR*zDSLD7X{2xyN^*5VjiVtJyjptKWUN1R4|G~tFofv^3!=t=~z zK6qKHb@RbTBb0#h=j4D^>1750hk4iGWLZKU(`n2RF7LHF-nzQy2Fw?}g#<%%2 zwUGXfzw2HPt2l%0b=gG-4cWPng^4$|AR2Cgu65-Oo~lgfX~_Nhv&r;bxaIZ3dTrAO z0h6$rZ|5r?>Fqz9uR56HQ?vj0tC3O%@X>kg_u0#jvwUffp}2=Zsu@___RmiuFSq1k zWd1#0)`@mSt34|AuT!I&?d6o&f{zGY;kGU{nR<@l-IhuqZ~}BH$G!0PBX@Ve`#3-y zD@GveeUix$pRXuNC>ifOkbJ32IhD5v?Eh$x!y`%0-p|sFk0AeDS(RiDb7F3+XznCz z(>lAyPBFN$b7zRW=E*f@^`OpsNwBf6dw+PRT#g5r&8w0=K_Alzs!k1ozInpTZZIMu_ANoMmDYwwS2HyX0IJ+kF!P02lr@%7~MyJG7)_laXgAGq5bQZoEE6&G_oCJUcXUoblipjY8X} z`&?r~yGmN*Q!YF$7_S3LkDu@qZO!J3=^Li1PzK}#8+;Z z^eF=KY89oSF9?|R5sRKUKPOa8Qu!E)7dSCcmDAb zA04dCiRR-LW9an8RF-MRKLyI*u2awdx|*-`&|dq=#Jw9@*ZMT8?KKZq8&&#~1kwEE zR@^N>&Jt0T&Zwl+04RzvxG_zqo{uD?`G*d5KA{i0<>)nAeSKQPOXj#8^pcNb-zGIc zVQNqb5!UAXmOI=EV+Ku*kz8NCtnWILr#9GTo4S|3-}YdspKC1ri0#LhIqphFZB0F# zo%Hk<9=060Y)tG^+IdWxAJSqxcR|x3i{bKAzguSHjJvk_ z>LC*ZYMoz+e}ZWE(6d>&%+gUWB>0=K(PCKv6PEocVA?^S1&q^z%w`g#jcX>U`hTQs zhb*~qy?2nNjqBOIBG&_aNkjVZts&;x-}b+2J=0GKoC!sreKpvmPT;8ZHDhDVhnLa} zsYaB5f$?d>H58;}jfKU;0jimpG(b5I2Ej6pU{Ht300IP>>HqFX;P-I@+OyQ#zoY_u zto+nB4oxWEZ%LSOQb5j1Ri9-dXEluV=~=$N)MP}tumQm*N^t4ZF%H1D0YXvw|E4_t z<2JJY<2H)2LXRON2l7@H0r~ZRzW)2UX3(ja#>1|Mtl!);&E!pOB$I5xjyrj?89qAq z@`E$B5>~DxKPP0=jhJ7#SKvMV{CH6?H}Y`~ogV-A;y+&Ai7Aq*XG{#}J_Tt$)tQ{&kGR5{wqzAtYgR11Y1}u~+3M=`2$}%_F6@-v?@kxx=PejD%Kx!1fElXWLF3PW5VO+#i{z_77XzM(yQOx0$GJ z1K+aR7ok|r+}`K4rkRyn))c1yGol5EE0O)n0-BvHbwx5{Tr0dD)J1YSFPu8cR&DCe zr=XxU`95<#2p@>N6u|2JEM)6;w9*k*R}mwq8TjBzzxXJxN1ZPA77*Jren5K7E~Bjh zGgwtf`u}-u;Q#;RvPg+D{R99{vy~~Tf}lj~74-O>HVjzLp3cLlHVv0U32o**BiR)M z_S%Sva3{Y*zy`=5#t7i4BXxBvEI*~&LIpGhn7ceCNW06@C8;z|-Kq2vn^tm6`tJQD zB~~zmWit7FcdQNwq!yb+SIKu^6*IA-=8PG)mbMj2@NO84>@k~mMlMlSghLABz9K`h zCL8=0XtDSN;o7L0;8Rmr0nEI+$cHSz>w1{@5%Vwg0zF|v(%yB=O;~sUz{p}RrEQqA zItDQq&AdK2g2yE!z`3%f)N|;so`mu}A82MpXOGWk_^RtV4u+C``}w+MaGYLNW_|xL zrUl<*>4TjJ|Di&gnJ8}WOH(7=gSP<9dhkZ_z%PmxWTZjYdCX^X9XouqGR@uLMt-zp z+j4}<-G|F|g5nfoAbU0fK~NfOzLbGM)6~imGRGBqEuc9|6p_7qPsX%P>Ps>W>=GA! z&kPoDSY|;tivKW`yTf*BXbvoe)=i9l^qy?~JSqL<@r8Q#r>$#`$QRr*n?eeCskmPZ zDe(p<;CXNz=sjBpD-OsNrWUeHubZ0A2d-BZBJ|zdOMvS=?%TZijPJ?yM*AP#-hIn% zJ$_AQP`!j|)%#sIKHy2AaNEMHblbjb@}Bx*w!8uiyY~jXbm!sZWNej6rZd!r1N_PFZS~}nO8+hQ zGam}(fuj__O6EhPt`Ebo5{ho+O5Kf+L$~BAe)t7!Ci}LkSv}z`$&rbz+`x?FXXNO= z`Y%5lj0iT1Cy9LjJd~_>y$ClsCZM zid3}dlvNay)@BIpr`{3C!0%`^2`%_BMzaSS#32X*5t(1YZpB`DBzbOfjM#2O?Z27X zJoZc0LK$L$Pimr7e`Pmno^@m|9{cNfSm8Nqq0E+IVe&5Y_&YtpVc~U2F*}rj%u=}= zLyUYJnOSj$)`^_P#HS^X#ek>iwAc*l0$q6qjo{%(U0&VcqWA%x$RDPg1_6KU|q zb|Cb}Ms`RjskO-r8sxpTG!tNjw**sf044Du@O$12exojA8)NGSGy@xcbqMYfrc+66 z=ArTV0%tk@uWcS98Cm-AS-L36+w|Lhj_LpStq0b9!KdJBInA`&O(p}>o#YO~6#w0V z-b!AOphjambXa5p_fOT>mYwGrl{w~FGsyAiTfn9!ZL}<5ncLntNh|E;+YQ_=3lE@X zg-poqs77Z4tu53IhwW8XT7-V5b2)#QLJc)L~4`@}l}oss(<;5>Nt> zmOjR?BTa>1rC2w}usr*M9KZwG7%8wR2hotoaYI&$?iEZBIa&VqB1r|lb2od_i~9g= zmSTCN*6(z6}mQ@1B+jI9xa*eUcv?{|zwrD>&NJtl$-L+Hz(fqHSQ}MJ-<2ag4{9X{)=&Tq z;d`7#Bw{A@B7Tin)~^F+(<}Z`2J{XKNB;W@+&A?y=pOqLW|KG+ui^xV+$cf)Fq-Tz z)6#J1NeKa#O>h~eSnwts`Dty*bewm8X9BED_H2Vq5paOw#NS~uOfr_>IyE%h1}b*v z@`(UO^7=oXQVm!@O&V~TwBR;;-PbnSU5!l%Z}8(-OcR>y3ruTNf=@%R@~q>}$kwe~ z?Z(bjAQ-;}>i>;{PFv#gAb-I{@S;ap2vcywEK~XTlH$6LNP6O7*CH)&4)r4dl`lbi z5ybpNI|c-4w}D^I>?>HYN0eAG2tgYzG+h^9#Y&odWD(b3+nl0d8H6a?U|u~?^Hp#c z-USS%-N9b$7@-_~2ASD>sO@Gb&L2$UE-g4do2%nC zdGQk~%bu=kl7rGj2Prs7RV`^WUHAoZ6`6_6CI3bug%r~P$`%}M!B_vzeIRgsW3Kb0 zm{_-hZuPRUUj$YgNR%#f@tN)jW zNlX6+As5f3Ezm_2h$+kycqY``0RF~~XHHAqVYyB(3vyEh(KCJVK+uFPkKRkukIOC0 zAB!pGO)V-2blZug)AWJ#*|2-5~ZErod9`O7zArJ`>`XIJaj8HzY1OH73;IN}iVI_ik9-$nC_K6OP zji5h-FeEWj!Or%ertCH&Xx%A}@vEh;%w!)0zj+N)KL=F*IlrnfrcLSJ$0d25pTgeZ~ zJ8DZPXC%1`um-)iuf}m^1N53#Hvjh5hd0&8fL+Umz?rBpWi7bRkq=zglKPB+js%>7 z24nu4a>PD^g4)bUciF*Zeb8PNU?IDJ47BGO59)A?(>99~{ zK$4dy}5EiHnTT5H)6zvjwOLBkB)5Bm* z1h*lI0Lu`KO#*h}qJgCmof~Wv?5~?OaHOX6fTgF^oihK|=8|Hkm#ivP;y>tiB;VTP zNfOx8Y{dPX`o^y`J7#Nzl_z5nlcZ{Y`u?E)jPl0MRM<+%MC-t(e755_^YF zr*7nWhJS(p9(`_CTzvy-B^llnCJKXrenh8nB@NOpUXT*)hB8lr%WZ6K-;8deB~dWr z#Re}{>O9HrO;Ym?fO`YG0l32 z$q(w7g7mCX5wC3rabg7$vKQbPHi|%#rtYKma;Fw^3ZQt>D1&!B4`4tRJTXSeY7g0Y zeEMt>piK8lEVnX*Nk@Z0koezAH!WMI#sV4M~c9yj?I^D7_OH=r2l$d8kI$vzc5wElp}^ae@b#^6?GoqMhPp2wW>rx&4>ft{LYvb z>06UVe>3i7angAtL_uEfv8$GuXr)PP+TQ;?Nk+rMx2wpj;Kw^mFA3T$wI~p|z@yj= zKycq3JX5JR{k$lG`VOmjnPMV1G&$JnqZ9vMtZ zld&&$%CQN|0McJr-rpr{ z6$x1*+jUm*^miI`gf?B=Id!{975WX%^9+&rg?N={H~irYB^)y2WAA1}P1RuHDn4f; zi0S=woth;gUp>gDuAijC@<(auJRwbNRu3X*h7!{>7kLaeMp{X$KmSR=-SP_=HH`Dq&AwrAg? z)46AN_+qQD)n6ATkk7aD|6Wq>6geOh0@xt5GCANJyGxQe{ES)K`1DYM!L^M}d_^D1(ioKk+PHY4DiMCLOu?W_E(XlVVf4d~p zaviv`#Gh=Oj-K#6`4Y<0O^v{Bb$kJ-^;#rL|2`s?4-Mp7AMO@9G89-_tIvHQ4+;Sx zV#<$^v#+8;FZ*y{TRsM>U()CJbUZsceL2545L#DFB^WS~o53T-1m!a};s?d-%AsTLdt9-yJA zTV{c^R)^r8+t&ujGfF0I2RYyM#%MWQH(auXTIGX|BV-dW8ePdwWJ7?jBZ9ULQQY}*?odn zcF@!95c2_%Qz<@#s7b(7ubpCwT1n}**(AzJBdhZJ5Q71v(w?xE>~nnMJMO)%U_sJ zrkl;F>Z7A0qQgqxekg#wBSH+|S@}9c5Q6prW+RG}#g|i`kOIX6u$V4N2MpNS7T0i_ zmm;X!l9;G(jTdCi1&bg-=94B%=B=f^oAZ_kmtXZg=Bh~(@7nyh|4V47#cesLw0sxWEgZ77ZKi3xIWn*`gM@5 zYx@eCR{?h?0I`7mgx#soC3G@#B{Lj7juUd(TvP~SAJPghhz}zUCDKz=UJaBg2tWP= zIV(LQvQKXz!c%Q>oe`;PY2^$>4^AKfw}#H;f*VaQvyM51kMFHfz`2Id?f_NVcq9)$ zKMMDGBiXS1X_4(ixvD6$9v&Cuv2m&T8bjn2qB!1Y2X})u)WpyOHVJF$a1AXOL4mP} z@kbK5XTn@OdGW=-l9H7qegHFSnoYH~gKX7T{CxHl0WyBaPp(V@EVNz7(hr3qX2`Ns zg52QYIPN@jI|eaG>1G0>h!Xhwe7Xb+9-Ib?Ii(WPDzO7TVNz2@l^z8FA&t6e(b#~+ zRAlTX`E@haf!PT8s3@xwSHJYOh3py#k9NdTa`+3{wj}|i2c9n)prHn5EL&16QsUEY zP!3VXxw;IL6#ve+#S45f8c^ohf{Fbq)@Yu^$RC9}VXq7ZM(Pi9)1q`Aw3>WjyVIM7 z7o8oKS>YL$;IYI*3MXdzb(}hZTQYhNq#(RdNN}F97JSn_yFRE!>-|fjt?*|_i>0F1bVqt*Q1*3 zh9s@##B>#)39@^Xjq-jS)!7qf_zm)Y^lBUtf1RmpV;b6AT17N`f5ikF$2Si2tEb2O z2?YH!%RwEHXOCW0?O+bz+X*)aYnj2&y0CyXh#60UT8#wzh?tp-owJ^v94MJq=^q|| zMeYkSoVtKqAfUdAl;}E4ulDm1p;M#dWOm|((?eH$5AOH$EaKuD>KhXOrgPsriS0!g zc2*`~EuEGat2f0aaPY#NP=i(%S1BW=bEFxc$@s-Em8>Du5`AR(AZe2kx*jh@UTmfk zc>6?lWC-U{`P0uoR241{UA|H_Wai0GSY&3mxl}>~*oB!uXbiqiR)JGGnOlD-T(Pzi zUq`$u-szS0K))8uOJEwy^0yi-73|A0XbknTqvuj93pQ+hJ~nPh>9Wy z;6k{o0aK!Jp$n%jHHVwJ(6=Z?B5^T1#m23bACShuEJU{hx4C66XtnH_ut{PSiQqIu z^o_st-92x4T=oFu?mXxjbuLS!+$W&UEx|5?l*uE5i+c8Kb6=*^m~dNe)Y$lr9`Yzz zf=@ptVs;QVBiG!#tD#4kN1!@Je^~8}P}41!mv0lEeV==vHCJCP@95?+lfFPf)J^XZ zw#x_wMVJidy0C+1it*GCGh!h8Dk!#U+?b97zjFjf2GBV|o3@2)g- zKO2<4UV)5)=lwOnH~g6CgxbC=#wPNKX2d~&8fOZElOQJVPjrKvR^nsbRUzPxC5qFS zqc(f|XLQaKebSElp`cI3rtq6OoR!)*|J-pfODYFzRP6Zd)&TSIf+ER+#of@N$H%2i zu6eikLt#D1sI5@vU5g%o1XM#0q(>OBC$-?NyzrtB9sLJa)@}3-wRFxXO?tTPjz()s zXm*ns^hw_W_>QcVIu6*Z4WZb;7b(VrKNNz|w*Zx=3BEX6xI^R&0#qVnr_}Uabk=&r zs7uK^&mSZ^dIs87w5C4f8>vR(pXHH#`g!Zfg(1vqf6R*o`~pU{i0is;6Db;%W@SU~ zZHO{Mc!>;2Je~P6JWEF@LF?2I)?NhRJ7PcNm$y%>Vr%U^FHA>kkYeASEJtn>&2rBV zr6iDXJd)YpIR0T#V{!1+M}{d&qp*HyDZ=_D(9DLXx+eQ1C&?a-NTguihV3|@+lAYN z4OEop!IC!5=9{r+^X0|i!TkG}CI7gycR9=4cDVxFVxc)Iw-9wM<;>|oyGlEgbBaR) z3`KpnTDI_L>Q}icWTo@GF*;Qn>F&(`83IWoMw^6LTQBHYzVVq}h&IpSL90H0BM_K3 zDO*U6PLf5KnKU3@p7E=k_v;KW8g6kG_H9PWJAFsLm2W(bO6|V7Te)%fVW{fUk%BD_ zUd1jA20rd7SoN9qGAR3s#o4-g=Y}z9dFMvfg>NP%J+<0@pQkkCe?qRkKAf)}KA043 zr$3-v8XIBy;OeKe+jm2ow01K9keJ{Lg04+8COP1U$YMTR;yf9O)`r5En|D{9KQG#S zes_5ZNzHL+TZ&USq+nBAI&B741M<%N~!7>`*##^{KBZ_74aC^uZ|b~89FyL#W5J%d*Y)|=_= z<$pfbPo3$ww!Z#K&Ly zS?4QWv68gy*0n-@MqdNv$`kN{TzOce#mBRCQOM5nZp=;GD*4V(xh1n1seK|n-QRNX z$pn(v?iO;_w%D6=;d>VV|Mro7@1BdDoGl33g0(*Xlxw#f7rH!8Z!Ih?o8eY1dX1u^ zAayPbx*0eYBSSCDy#R}b9|HrTN1w8gARv&jhP32a-+!`{+70Ix0I4UE@UBU!ktkQT z2D!QY7aIkDNyelwgV5aF?7iP#{S7rOI%?14GmseYo=-E zt>>eBsN3X`>@Em@qSg&o@#uDR6K<~iG2(uzzOJ@E>OlcU486$j8sQ9R=W9K0mfcx0 zO1*0N=Ji+Z*%zK?pG%%XRFPJB$HMY)rFpQUQb3fIsV+ht0aP{S^m;U1OTLu|#zBh~ zquKVm+uyxCc>f(h66dp`%>SXd1BShqVBl*px>eSt_#Q3AL!c9ZRfwu#cUcR zWzDZ=D<-#%-hNu1eCD^hPi4~s;xN|=WA%S#UYR!B_5*kv8v}t={>)s2m~~U~b+}+i zo|up01H6{ENLa>k#{iVDnpzJKv7^0)Qrl^fmHf|ki7UkK5}|%59FK?m3HA0}PJJA- zn2caVqo)y~kdXMDt7W5u92cl^Sqrxs?OjC7>tC?0#lB&60G!Ot&}g|cV;T72FTFB) zT_F@Qa%Ae+vwZvd#1U(DzAUo=!--?#>Xq7^SBd*Xl%ae=!hU0l8EKS1`Cvmf zZ($?SdFe$cE$V@8gcjTLq@cYjV(G{tcLND>XdUJ=TL+@74V|CU2j}HEz<=C4I0Ut!RCEK z>F2_yfrcWIr!>bEy=>#^LYIiikV5sG+)R2YuZ>v#lL@1Bo$gQca5i!{7{-Wir1So& zs_qz!FPwQjbM4P{t4~0#>Zg^yZ4U&C3o*dE{s}&rJ%F)pFm=Jo*Q3>-V9;~-0Sa5@ ze#SoXZdoGp;%8}46=Kkd+q{?zSQWHP{a-|^f0xInpO&d)>;w2=XY7^A692GflU#=K zV2iEbfidwj4lx;>^N^gAk6NPUv;+(9+3j2u7ATIyb}~8xEg!O=K)T3%p*I%AZ*?2w zcNR>RmrRfP-hOb!#CXY=!gYDZOkjBv-BuvLt4a0E+_~fv(1`M$RbQ#{wM>aBGAdv9LqW2dj0N^} zlnBge*<-A~pzjt{7YdQZ*$-_Wt~LWLI8_6}dc;+SYvDNW?A0wx@^Q(0xalU>Es0zy z;tw~ce~;XT22aCgW-tvg%54IbL=zk=Rj&u30Bol=Fycz$sxX5mh~mTVq`J|PpwEBk zd{38eaTYlVw9@7&htAGq!8PuD?xxB2B;L#_{vZkRNPBfz*#A-F(b-WK2DyTHKiCa| zm^nYd!iC;}4Nw6V*A=)=aOa%>%z$Si)j>SMSf3c%-$2+rM#`UMfk1@1et-9fnVxHe zYc`vc)zKQmrmPnweYzeTUXAgAHXE~ByxvvCcS|*A#VSY&_~44NIPIgq)N8m;*>nPJMGLs2^03L6{_y*`g&9x9ue^URBN-( z_J)f%n(1jJ9wgOF5$}=FaJ*tJ?2Jmpt&ytm`c{WR4S#~B{V-@hN_q44-8z>Z@NpZ$ z3N`x8oU&5$J<|m*ZjShNHf9J^eZ!4)ysr&cfzJJt^~!e1q=gcq+NGObYA;eux8CdqZ zy#)BLdqtg}DyzrHM;hT1`br7HZr>B5G1H~AG-jg|bM=COB)%&>dTZIFGB8Eq6%t@@ z>kz~4`3lJiK$n3}*26|ZbbH^pLC00{F$tmVtP2j++2d+9EEUVgTBubtL(B0Wd7$;JOO8_++Il;!+E(>vN}A9EjZ$ z{gTnx+BATfBkF+U=9-B^O#mD)u1g;!k;owxGl`n?HxLfC0!5}4qEt${A_sd=Nvd8c zJ|`>3LTi`;70h}7o$W&0i=_BxBLB%hzq>ZX=F-A3X$?`&-p#Y{q^yHU_kLx8DD?=H z2@$#P>-k^=Yal*}^htJ;eQy}R-#alXeZfUYhOxm*uqMLlgQI6)Ootw{Nv{~kDcmG7 zt0|~d2`XGmkJBbL=zfpKcrX))uQ7;4wtU@!@kFZD`E`FtI*azZuElt6H^F>$>Na zz(5z*&^-?c`;vfC5f*k@0_V`JWJ?h~!C1ao{+grzvOGN3v-#7@@?8tv)mQXlJR8%v zyouZ2p`qSL$}e!)9U*fqiPk3H=J3xuauB~Yk_F{|_@kaqf0J*2tKns}ftyp@J;my& zIICB=TZS~#j@2nR-uM-rMui;-<7htaCb&CE&_(5PiE~6ds=D2d0_|qdWc?$uQQfYxmxC>6 zm>`bxNAUx0@NdtEqLMCh7twVz}VV@5duUz8?R@ z(rT}QbT@cvuJ`d1VI%okXE0{tg%0lg38>Q$!&PJx|2-UYG6ZTF<*BZD!L>y~El+O; zCNV=0{4yS=8R%s2wm19o6^VT9#N&1zI*ki^qf%^+Wa{EL+EDu$8ym8ZsFP9LK%#mf zdqsJ6a0-|eg1T1Ib_z4@*QP^d2R$Fa>Tb*zo*JZEuj=GPWLJqt+ZnfI0QTbDCDdij z@kLG$zq=EqJVVu&{zh3H%Glk{yo667Y_Y*gk0O;YReW}UOelAH9NtJ+AypN$x_s?n zMOY+#%4TWmWLDsAnPsT4PLZvO!Yu#D?Y%O_*a*I{E#)m`gY1daUvl10>M45`4ct=; z55id;Tm}Cb#sOJ{d=F9%#OEralSncYfp2GM^wT3;NI<7UPzj^#Y#C+fA#tbj^$gk= z+ZqPw)ob34pB{`TKaE1kl7X=sL9YB0u2sB?(Ba|jAPZVSK@ttJfvAvP8j;Pm*(-Y@ z*9P*8q^XW^f6JMEy9bd1D5X$Y6vL*eN{=1H=8eRPiz7QtSa&b83%WUaKfeea#* z>#|`j`ML?E)TqAe0oJn8Xrc<~?g$CTUx~Czenlh#DtlqWBmqf~bXvZB$pbC;T`?Yo z_;m#A7&SAJ0d(}!oj~G~*(R+RwJ`UyPNsJ)J{M%KKs!JrbQf+6FZP!e(H5<}#0jzo zloitGVeBD5YD0)_NH;J$nd+DYGcNBiwd0Xc;NwZsIJ1 zYI3J5{m6z$Aa5bLG4@fzU4h@Fq03UWk`T|P0oL~z)vcqadw%)1G-h5|=?SQZ>tVDE zQn7^O_Q1qvc)~Rx=yLY%4v&Jcf9<>i=nhBDRQh4sJu2N?M(@p>VY@_T*S);=U@)?q z#%{r-Rl9FW{k!h6%Z`SJGo!SepruNW2X((!c-Cx=Hr#!;rSynJP{ncQfkl~q|Nf{R z@2Yu&oh1j?wC!AR_pQ%|B##WI`pc;Xspe3(&OUBY+Tz~9a=?XmEmuBM(Rr-E^0y4j zD85DrYvav8?Jgr*?arNz_7#pf`_wD?A3FjPJ)qV<8MwLEt=wf_f0AXCaP6^8zIF$1 zU&u{WRCo0Z(fCH2KPvH~^m1#7Y&3F~O1J1jt(B@HA#xz&+eH-6w9ii1M?4`FL%zw& zvre!)C#c+)Fw@MS#RQdxHK)A~&DDxIIGyiVQPI2g51r`wH)vb0UMk%SkX1|pKCF_* zYnu0g6WM4T$`)IJvr(5hLrZi#ELSu=xv$@NN!J?FVQE+KILy+esd#3jQHMb*OP|NM z)fYx!JcmttQu6RaMB_3ADYO8zr?$<$8Jej+m|UfJMj0BkA8wsPyNR?R{wTXeTBrB$JIt4F9G@{)<_8aypfcXB4FGd z$!`VTEE`0Gl!fXgXQhrwO_9m{@M;p&p|iU*?5ppLj$M7pBqz)=VyWTo(U{=K_3%sk z9ktU&f5G?!=`NVtUbq>F;h{H7+iZd{*INLI>rgvI?cHU;U;}173C~*guSw;Di3BIU zxk?kV^vo#n9-HPwKipUA=j(TTeb^?2n!^8C3H*Po>;LQoXP1`$JNl-Aj8c@gN8!J| z|;`F;^fyaV}37krP?{sAcjLf3JM3{}co>ITMvutFnI zcbk>|XwoeqazA9#8Y$P34^zOROziB&WVu!ZFPEoErG2Jt7vCQd ze#4&n?YU!Qxl8nvPWJ6!U-G@djD69D3-}4=qb1)%tqKFKKKyup&C0Ui2LgUV+dzd~ z!71C59uJ}ImfyrtMMArrutKS9XxKcv>5#(*`S2cEJARBPSJ8`!gLU~V`5;v_dIAzo zWG2b(i>x|uE2Ao%kMjw)$j8ejKD-B(+dVZi%a>?n-PP~ggP(@Q>h)4{9*1kiCf^B+ zfy&1?lYNUyQfsi!sIpBz6tZy0DFke{{4nTWDsrnu1E2-(6>z@K&{log6&lF z0Q71%$3UND)i=@%+I4`dCA3Sor#LdHE{MIT%jhrT^1rZhje#p$Ht)HZ!{NMU`!QRY z&8*8!4UG-Y^Fs?Xt>VhZ!*PFu0vG8m%hE4Oe^r;0l_DEEEqWRIC&79rnV4n2Ir6Ww7AR9bo% z^|OXMydEF5SMx*J(PK}mp82@$*u#63$BJ*G7m3+^LHo1M1QllQ{q2|Rd&F+=s)T0j z0M46>3#6)fhdJ=5pwMfO>LeFjX=(z_u;AmbyIdr(d_JL9KPJ66dh~w(#a-p}Ju7bw zt$8r7*|Mc9DCzY9?T0QE}N%IYL2#qv(GFr*Estmus z>&4)?+Dz}#OsDCG;%S&s8V|<^CH|!2{?A34w*z7E4ITT6 zvq*SHfLhL%jih_2d`n!K*%|K#%JnU3Q&Ia+fAd>hcw`S{QrfloJzYh4FWgl#lTNy5 z>~pJdDe>GKb_lo#I{xkmMP~3m1Rs9>N@{}Y!fZJBJj^@)tkbarPs(2G;~&!YD7TE> z*I(&arKwz$;pp+iv)oK4$DntO(CzBIV9fh8X$07{A3!ubNihH-Cr}4kqq=`6tRQdU zFQif%@EvHh$sI8L)HfJ3^N(?U345{eDx`E_F!&?QnOOZKs2Yj!dD$=B4&(XU+v`U` zr(7YuWdw4 zd37Fgr+rI}g=!w~Fi!3eUXAwHYPR-tw;kAf=0&CMiZ1zA`g~lBBBJfTD6zSENT49^ zIu<3eYPY->+m~o#K*F(Ytl&)A25bT3#n#94Uj|&@FxPX>zAiLW9~+oH@W%Z0fs>z@ zdQu-yZhDMJt-uc^jFGCjSfkh$=+)8Ov6*44lSpAYwu-V7jB6pmgi$wc3swo91cxuw z05yhYYBl98cRhU~4*$-N{i=G#QvR~MN5B3b+laD>S*U$;OK2PqILVB5bL)s5y->_; z91jqA^eN_)F1gXD+3a8Q`U}9hDkG@H9X`}GSlymASGaWuOlg=JWa|hUxvNIiyJ@Yr zMQa+L)9KRK=g3tdK9vbOa5+jq2LI@@)+n<;z{(M{OrAsfuOQr%|u2%g^^8J|Tp;c7G7&kQy=A95X`r_cHy zIytZ(W9IDc)_UJ~u0dvnZ@T+sdHIXLt+qWpG-7@I2WNwQw(3{D9IG%xzy@0l_D;eh z5>u{BgzLo_qTmjyN{IeyQ67uSQI_|#7pnI+KoNn*T3^WiV(bGqg`fdl!fZv72f>i> zRZTQa3sLK^csDWA7*QI!T$R5%5AbAD@&(Qq#AsoDlX)$;1Z${aVeDJSMlLcdR|Y+n zBA{+j$BI20gFQx;FymgQ2e7-=v<8}*7&cjYvGn4)7?ufNCPtjjykiU)(!KMcuc#d` zC@#1l8?;+NylUWwqjgh`_CcY@t7MIUF$hShfqNR>YZ%W($St6Dpk5|}fwcRm$+7M$ z(aw?LYoiPUl97Fi@@O5&Q9Gig;!iet#bT3GGf(^t0g&bDFR~=8pNPqeNg*E*;yDH# z%#9Rn=}ttE2Wf^tzI~}t7)_vc=wj??dNI5>+pEHEUPxZ5KH9L5Y^l|O+3af{SmnER z!PM&7!uou&*VU%ahHa?ZlWMXexuSF{BI7x1t8uilv>nqPS*LAHSrhLw2R6G8?x6=zc}~2q2+w4@y&-# z(#=i+Rq7l~av10Ok)h1=vqQ|LYgsuTJVBGyK!phI(yg4K_ zf{;YR6w@ag?DKfZ4Vm`Ihrg6`ZwkoOOuFoR?P=73#jw$8*9tS`Gw1i^>>fH(GPHf2 z!;>zzFq2m=4U>)3jw>a11RgZg0Ldo_6zi34cgv3@9T};1?b>vYlVlnB!1Z>?kne53 zI;chC6BsiCDg27hu1LCFf0Xf+w;a-iA!xsu-XA{{97pI@FK6d*F8xs`WgpIG-)cq$ zE&O{EEvURR{#qH!Y}5JB)Z!t-mO-5PJjAQTtz3wB)Y5=Bi{5@3nbH1YTw^S?=2!3v z*Zt|B{;m&|1`J(G>^9szv7lSA{`Q%~v#1OvuZ*kE5(#7)-Y)@>$Mtibd{dq~^t_+S zUM3_NpUeE_(U{p4e=OWd=H=Fq?bcMQWp1vM#>#6n_bsG_5-pED4d}K2k5z{)kG70H z&xGwjSo$jqKytTg`BO6W_ju{6v1@uG4|WoiX~CmHq2)8Y}v<+k-S9S}X1pu9#!= zZ!Gc{v=R>TH?b}^f+Jx+aTqv};D>@bqn4;B&k!B=MB?F;UmM@)^qjss>s~LyB$@SP zEN6&oHx%pVgcBe4@||s7e|r7>G&8%yJbOBqbER6+Dp8{hEi27eON^yE02*n=_YZ7a zj_FiIdlyczEI-cYnw7@^eL1Ue-)M`9p!FA3-!|Jd^x|=(oUQXWEPk;oGb670v(l;I zXbg%(bZu#V7sW$WdzMEjUlVPSQ-Jco&%Ftid#GZLSdiO5m3ZrYfZBu zaJ5IM=bvdQ*$02u1UKdXsmnt?&E1(yUa_Ug{g|g=%r(%3o_O=OW_QK$M&cZV|0K-S z@BZc^`dx1&Vqk?@-hBGsq$@Q7AbWP*u{ZT!PofN?OGX7d0P!~aT7 zG@{0i{)3taUB=$?AQ>KjCT*dm2V@N44EcbpXo;EDtU6g)oYEhifjX1@(@7qms+g2= z+Xjs^bKdrV(^8mei{lYHmPd5Ca}#){QPT)NC+08~BgCu=56}~FZ_pRiNLroxx}x3H zu-Ckrz?pa!Jk$w*_}s2PPcKWFWTD69agnP!rt2i)-v$kSJN1X=>I3G=CxiYxmr?4% zqXh34Vrgbw=bw4UZn?eh!oRH=UH~2 z`zkfjH81zl>s^X{{t%dtee6lDNIyHQxuZDCTF33T?`D5M_}r;4{_3uTv+;ks+Nvx3 z@0S-pW*!H!!e&_^E(D#)-7LqFEoG(52*UeuciE#We1@!?tST`eU&X1&x60pHCbW&j zOl}v^lD?3wYdC&L{n^@URdiXP^Fg24z1N-+xSzj;$4)j?h7p=g&%E7Op{4w1(n+fT zNMrlD_OXe8L$?KU17V^+Ld`B^yIMxgbh4@sd)%z<{rOjpy=LI&f0*VZ0&5-9e3*J2 zU2orx9!unnvbom@ie$wSk`q6LjY0vHta3=w#o?MFxBJK6F>;JOUHxI15(*-I8He+Vi zHiM3}B1%p)Ur!NhQH3P1PwO!9%HPiv8XONVpGlbcG+{7UV}>WzsGNe;%>yuy&Wz12 z5$4vCx9LQT?YsG<@^^uQQnO-GwnzU`e4z8dqj!sXnsLv+Txo%<9u@f`$y5GA^YabQ z&o?n{oef*_4OIbPlh3H1ZSP+M`K2TB$JYTTVk=6%>D&*6e{YY2gFN{0Zo_j6Qe4T| zafbvEJ*n=W+h6q$51e?NYxjPZVL=){__ET0zpy?eK%>rFN3$TJ{MWg+5a}t3{rBadIH&u*alb=FZ8s1y`SL;zwvU31*Kjvp+~`PlGHIVvcnJhS|IyL;EMn-f!Zhx19k(LxtOm~xSG z0A}LKeqd16u$X=RsWJ2n%pFueGYo4ZaDLAceX@h_@dp*bw>-a?nLJKt*`d0 znjUzy)1`m+#A~CicKXTtGR~Us%h+$H-=JqXWHgxMYj)n4?^bZ~ty=p0o>sT8-rdhS z&;R!RgZ1Uzhfv40k~-XT_92&@_eFp9EZ-G+ta{(G3YV+#XC4g?g!MwZUlbU%Gc@}z zpC4S5t#U}7+~~5VAc*0x^~>E*$F|3%ck138drDiUvoqvYGw!{wp=?D1O{(P!iSmbw zYD@Ei7DES%?N{6=b-ZWbQea8izjOQAqkFnG-u|t^?x5qVT@x=G$ES*Of=IDvo&a=n z#&pkM(mvDBAVk}}++~yNO=$aC-cTR_5byerzx@68*K$@r?z3ts#A_Y|ljh;{2n(0` zKYN1D2ZbAL&nRi6C#>7D&T~(|p5Zi2j|(Nd95=gPJ2^(){NJA4eR$w~h>MBn-huZd zM~r{qp7X*ztpT-nV_TzRINDgfBX&_R$uTm$B^bXh>84=G>o!06rU06oti2aN^Y;g? zXar=xRyt)j1(YcCsd*2W&FiiH$N)vU;+QO(vXRn9Q2r7z5U7rB#3jm2NNDjXkxent z_yvCMexBG{_IQz|-uv`ezkd$|k952`pgA(?i5tqhE?)s`mmmoi=;s0kO?AVWH}zE! zi$~J6b#U)LP)G#EMlZxhg$}RxHJiJ-+CFW8om=#FZX4l%(_UUE8$l^6>``|sqFAPAark!@j=(HN?_ zS#{U|aSo?XVvTljvgYO`tGUPO>}pjq(BdeO)-7xd|5Y(7v8?)?X3~XP8i$COSR`WY zsI{A9Pbm7+*)xD8z$>I~0T!K;lvVZge|Hb1rn<{>i#|Pk!zBGbZMY{VHy0sZF zGfPJkD7x5X^YW@mB=T3At#I$sWTAbMY5dyo&1W4d!i8ssb?50blV&h6nX&`1=wzZ= z!b|)BC5vGNzis7lA;yNys_7bC4~Gqm0-X5pU|0zQIRWkIp@o?6<|t%}Q`<>h4|3 zwLg>1Vs2~+fy>6Pm59;LcFhphT&8OP&2+*5rE{4m zRpW5Hdb4)Peb|8|TB=? zvxba9d?aRopc(_K@v?4Kx2%Kn`1VN+z|}*EW!{`wUuFB46ytEKGx!n*aQ=-0J9JvR zfmQTmWlb2TkXGT}WBsKRin)dzWSWV3#OHwW!C_LWF+?$!;_5`h-{Et@37hYEN<+AjDX@XQ|EsqSpy`$gs1Sd6+Z#NNBzV8=pc|mST!Rr}?zx!ZmOnV3BO7 z?#w8D+pLusrHW(cAA9p@M}TYjbfduT)dzm2OZbcb8bwB`HTssYXxR!r4$fBjq41^~ zGjssGxatPzEuj4X4?1|C@LwVuFg%BN^BAxANEcZCAo$61?fgm3;e-Q!{Qmco%68(; zs#CseRjVsGovZH@ON0=2y^(`j*cq$_8wDYq-aI}APys&5?#0SV&y zVpbOw!AzwzsD{hec}Z+%eBY)N&v3GCMrS2Zw!@|J@-iR7Boat?flR@(tUSx9l$x4H zx$#=w&*7$2sT03q$=cj0d@KsJaW>yHyRo2>Fn*T81mDqAS|IW7IYp`5p_=m!t zLRls5OENU;K-LEwvFvswTS)p=RvSf2Zw8T6vUi%Wq9uq&P2p-`Y?S0jT60zYvdtdTKy z-W7`A8T+}sBOkxYcQTrH8|^aZa{lbB={divaeh1V6a!2nUr8w)T(Lba0xi>(m}Z}X zen6O8HtMo68$(jJAHbSZu&TU;trG~9hq>*};sWVkwMEMAL8+JMkbE7U7b*?rQ!`?; zCbfqy?>FlqWI|gpSRWyp6U;AYELEGa+>i(cfRy!3bOyCUr=W^i2OK55%VlLa-W|Xu zPwH;>A(Br}4$496y9K~sDSM&t!1&M#q_De#s}x-wcYJ_9Kr?-*+DN~}LGe`l$p*tyLa%p|%ISDU;8`K^B@0L|=Qvf3gg2GTfLDa9_Jg!i2>x5aDx169bv=!4>MOkGdB7xzLfN|+U^g0VHuQ_ zvMqZqe`qv$Ps6qOvZkS(3EmeyzK}gcDeZ)3O5oTw@!!b55^uH;w}GrBtAW7R*FA}> z5CIQ@^CDe={Y_IG$o8YqmPJAudc_i?XU`wK+2RB7iCRd?Y0*?NWjhjibZGy)aZ9*j z=fLOhv4!+9J(HnTi%=IDc169XwLuD$&GI4nUcjK+R4#uD?8~EN25j7VIi^!q{{%7e z8=<%Ac3Li#mOXwNn(x7bpK{)lj5=MzV{A;aj?v*y)kOiHZMHo)HR>7#O)d3-+#^my zh`?mTqyY@wn{jBv8*~-fm2Uh40g6RSh1QWB$jusq<7dMTkkA4siM&hbT1vPqamje% z%ts!LMC?qP!XN75jeZqIz^eqNKNM=q=TPy&zC`%}cq&PL1g!Ai6kS<0Sr>NioZK*U z8SK3zLOqbeLL5UOu>+IBA!Ly?jPGQ(k0c&rJQH22e>D4>t$qqR&0vsxRHI-vVEP$! z?#zmRT_qc#b|0Iya!%ndvNH0n62wc;#J&j@7!r&oL`dyLD!i<2<|>lG8CZ#>cc^_8 zK}5T4vlC#5e8NqNj`Xl7aCXvQ1fYV6fL<02<#ou^*p|*sx6HWf-yb)d@m}tp`v%Ig zqq0CZZbsDdu_Xf%d1p$YUPRdg)^kkSUauz^a%-Er$$mkqsrm z(r8&Rj#tFgq@c)FBT_R#fg)ua*$Cmn<861zR-!96giaGW7{wkwgnsoDtn0(rBBA!5vXfL0^_K1f+fB8aI7JE)TEjCg>k&0t85U=Yp zlHct=cscMTjGRUdj^hy%FmlnKI`eLBN>&uDiasWyBvsEcQDB0T&THzXZjc%vPvtrT zcJ(wQn2+v^23n?UXMKabla~7B!GTZKVtTs@o*WGa{(1KN6MYgLu30d7Fp-mu)}InUiQCm073hvogu zl?-EYsO$xkM~BwSHKsXb*#cS?1lv(>5|kNRNy#V6`xjM%1rV_Jt^o(!O@le~UHn$x z%Q50na6WiYTx_0k+@on|`KH(XCc^f=m8N6bKwg99EP#B*Wq`5?3?W)8XKhSGSF!}$ zjnV_pN9CKO!LU{$<#34p%B)^MtO7~zglK^cJgHQKjSu)eS9dKfb+fWIAq`H&Y>Qi$ z6{k{)EvrfPb2P9Ma>0QeAqaFigWw5syYNYq>asi7a7eTiy`TZiV`5~b4SnEbdbF$% zYr&5obTP1_EzVU^odN72K2<-x72mPByiGUbf>7weNGb6pd?0PVa%HNXE`2DwPTmeY zTQ2=16|epP&I+WBm&=upS5tSeBb5(2ENgin?)?OU8-brt{HbgYpdr zWf?8b!GdZnaQH@WCm01Y=T&*k1fK$IKd#n%ZlY+56o+gKEHR1X05N5Q=#Ppb zQrYsTeI6hngyK0m3ywoA=Oq|QAH^IlXqx{hz>ReaaNW?t4V#rBY6AJZpl=N~6o*=h zFkt6$nmY83AG0)1;d9r8PaYXr#H?CJC+Lvkd|pt!Uozl{8k$K;{A$7$+T3Mo132`9 z%~zVE@_Rs`a(e+fj~)}?Zw^*J={Er~*lP$8?rsaP2J#C#hYQKVQ%soI`BRui^cpVc zfV2j5!q|rB&wM&*9PnkT-3Hs=;=p%G z@1i$K&T_0iq?1+`?fQ;OrGDLxJdn2oD*shgiZj%%u%F1}zsIe^63lW&avp==Rx9z8 zhQgY6t`Ut(njtnZ9Zkn{p>(A<(tMc*soIRD60Q@RT6Gk|=<`c}oTn&SOL>A|=`9K% zhCYMjAC3p$0Acd)L;xJr+Jpl4N$vV}0rlVAhqL4zTl(ZrMcpiY3nZw9(D#V!g}7cT zB|$=5N{d<9XK)NefDbT9?M~c3IpvN|B4`j!)eX^v?}W@Dy1zXijE7XM97nJ|uwQ3> zSET^AAruPO11O?4M$$bud%R?OId01`}H8<7Y1zr_HPq z8jrF!!G}71(OtUNmhdS+rS9Ly2Bw8jFy68Upoa}2`5nWX+%|@G13V<2G#mmpKFE@f zsh$cRej_3!e3FZ|mpUm9l!&190buHyU@7NP^pS;f@;W%B4X;hMA8K(ZvK2teB=)f^ z+d5dIE7d&fN%${g$V-8$yxB&Fq|~K@5xbN>3YTk(lrj@=Y5V#0FhrpVtx+8mB@sFu zXUVhlxm-zWMF_<@I&V9!7Ramf6+UGxZxD_gaRl-TGKH%~p*u@o8?D_R0^-S~e$d z2V(R=;S?LcMtT9Uf`rCsfQhMMq2lful6zCKi>|h0#(Xs2 z;uhJuYHWHL*jCVGICqeZZ<+QU@*Bj=8Mp3W=Fx8A;PAe=ZX!I`UMr15_#&<+(!s$- zN{=>!Cl8Y{sgHzeG9&ko9ttf~eI}x^&}vAT&>rePm#eB{9qBhzO(WxtZ%*z4=B>77 z7vZw>X|xEGX>;IZ8zW|deqO=@pY*V@EK2r9o`Q7{6sWQOFnSW6_s*w%XXW}GK97<< z{dp(n_6Mic-nLc+g=bv9J__7_$8KpcO9$~fTjwXU3K;l!<3Z1b(UB)^K_{;5*x6GH zag6zT{A=e;wzzq5oFSV#P`tU$FlZU%;u~o++iFTKYRgU+qiYbEX^r5L*t}jf`}$ zCXK948svU?>-0kG*RK7`hrhoTYD_}GUe6!!BFW>K@P}XF7r6Dj`cv66z>q|wJwsB` zVXzKmdwdKid3uI)-!YNBUp-LgfQS6qN6aNkVBu8ZE*?_kjZIAaDxFH9RIZDU)41>c z`a^hpz@dA^sf9bLo(_{dNi;!Wcl2SA$oPB_mE+I z|Dv9nbK~fBRn|QjZ>aNv1m$OC_~OaC7*mA@7HF~Ir7+~;U!AjH`J5BxkG}y@2ZuA#pd4E z`1H8gk6=?9TsG6Bd2qTZSlo9Dy=WH%A$I`${BgUCDaexPLed9d(8wW3-~0xx!10*S z2F6bEMd0KxE93&9SP%uEicGLh>eCDrS)Lp#@29LBSi~nY)q#5IaK5lTV53NJBawF2pFI*p3>EoIU~?sb+1@uAtf-L2WazWMq%RhxVAL)79(Jg8k9kuGX~(1?y=nPP86!Bg z{a6k0dU39>!0~C>=H$JBdsz=JXpw-vx+j-b!%w1I}ev%d%e$SjQKkU!0}$DUiqLr?t$|l;llMOOd7P> zW*13Uz-2>fN5vUR-RKQcd@=Hpt&^`%<~_fZvEhrjZ{D*?U^Hu(gV}GgYCND_v4gmI z*(27zM&n!geB2W-ki*Z_N>0o`b;&uUv($#ply>T^Cc=uvjEmFMvE`J`5VCOvGa=%m z^A*4N4WU$j%}cMx{h=3)?`mkat&Q~Ph|-=IEMz;{$D|WkXgz7HtiT2%-3E+uin|E) z%#N(Bh^534Mt5-)`mp+Y5TfAo#YESifpD&qKAhA$aoe&qht6m%9p_Ge3)e?KA2xkL zSJ7(qd;Tjfmv)o8#YQXa4%x8ZMi*4zU=gl>n^g?SmG9=$*jC()|AV;qjB09)`$SPh z6og2P(xM`w(kv9EB$lIyh$tu>asZJMF?s-r60&V{Ax9BV6e1!b0!E}skq7~D6cMEb zf{q0@xoc+4x*zUc_XBH%WF>niPy3f&A%i-|zY%~`EBi{qQ zwlHx8)7h62Vk)P#ZA5eqAa)zlgck0!m0wMk;c8PpHMHEHnx_~-C_-G{N~!B4QHBN$ zdZJ8Mho3mJTe_RXl^lTQK?Haa)FupND~FtuU~C#V)brN3Y|Gca-Bggx_3*ged>!tmC@ z)3o*1`qt;$=gfYrb*gVY_2$iA{l zU2aNwAIg_pJkY&s(&tg`#o$A~MOAa1a?c&7X~p1HKp>;X2tDSQj4Z_tG3siohV%$& zdl#CaO3^0oLVBvA48BkWh-o5!{Ses(h!iO{z-Glom0diB)_uaZ$-M^}nx4A5_lzY~ zPA@y%Ow85Fv#PbbxpVP4`el&A(=Ku~$-e~@+LnNfB^I?D0gMxacQRw%oO)F5_54*( zde!${Q@3Yz12b0Pi+~xSUFGiH{T`ckY;JvRRc0M%PfuV%w|S+vBbri!H{U2VVk%#I`MN5seDl#RJ|MLo z=4uwk&j-4VQ~by~#Pp2%VCXPX3+L_{!gn{v7ImdD>5Bu#SQVs1-f&71 zfTNF%1+li)u>sJoz$38%Zp`Lu2TVF9^!5P}kZs5bB)1b(?JAJ-wv7xesBXINX^j5g z*3@J|^TJT|{6TF&(59Y}*VtX$=c2eq_1qtJdOszq%-17_LITq(Xgyl)R^5NXXG-L` zY4@jEb>!naeNwl@W!~ubI&ykpES?fvK=Mz2Dg5i&@euR;%{kuG9{3#-3JcvbTie5( zt?1G6#CVOC+Hq1;C~0cF#z(e{7Q!B;q^&bETA7{RgmS3i{*3G9)Do* zH4@vK^IMEK-)npI`ZBD3xZqeOhMC3z8v2p_-)%%zrUA9@zBIKBmDabk6o2r)(4~81 zQAivd4k}n3G^&X*n}Q}25F(G7h0}EQJRM8k%_F8$R=t07LI>-D&ZGZk^sw%faJ*pwdKg?a7S)rUBQ1LYB#P?RX4g1tqTGGekrp03z{_mo%C zDZRLrcJfFT^bADh8CE^+`q}3-n_>k$qHTj$Hgf_=V1DbJvNA8;@qM*SkEk6SxPY6< z01LDWl0RxymjVor{1Q0R=(MNwPS4RafL(bZ)G+7MJ8(HTHQT^G14=Kb$@xAGVwF$Q z%O^&sLe^yM$&o}}8lYIlVUJLcB@!}`F^rq+?&(%Xf%X??hICsTbifW%UW=~={w)z zr~K|Wlt~Y2y`er%L1oVu9#gD&(IOUsRQOVrKPf>}hs4V_EcD=O1|GCrCdHz?npi~0aKEAG`jE;xG?IX7l|p{k`*zp&Ur?uAa!y{` zW=jV5aXD8pJYk7c3W6bTISt1vYcoPpqz5SNHH3iKN{6)Xj75|#uCa5VbQ1wGz@*r! zPdC~2V*Ft)(+2Uu=-J(TA8REXwyjJGj`-M`?IYnSFFd->0DTeOGsqaID(NVe4@mb; z$ZVPitrR=R;qU8kqmTqj`(tqSJEYwQ*Glfd`nScNFB2*HgH>ji7y3F)R<*%*C+uok zp5<9rv6>va0LmpH5kx{P?nsZoyvt@JPS{rVD0n=^ zAbXw)oy6;pBZh9n^&0L+@?-ZNYlVqSTO?WN_Ji=Vym@FnY#4(|AY1D%d{qANI8)&d z@md-6Y!*I+TQ@(G7b?X~Q!K79X;1YpJp_Z|$vBm)3K*ns>&qImuu9Q1V}*gD&%SNh zVD7%w`Yi8;;Z`l+!GP{G$WN)P?tLM-!grc}H1ou({{(T$=HQU+c%1t{Lbb^P+q>T` zOWno$;9%85_biva9)niGmYTM@=hy1uIOCjNUCFooZ*Fw0bG%Wdp@hGm`BU0Cu_0X+ z3)<1PHaJXBd*#^q3kBI^tAxs^8qx)JM`D0Ox>fuOm-wbw@1rl^$c$Fk4F%9c7BRs} zUR+Ru$9uTs-;ylg(=TE#0WEJ6h@O~82qnZNC!N(O%gbwJCnhFtTW>EJZh-69Xr11* zeuC6h*FWaFM*OkwWSG*1i>s((Vp1yB}7gX|;@(O5jt6$ihj)#OH7kC~c{(ubC0KfyKkV0|bRk#|L;#CHy@x*9Be^G* zlmYpm79qR6k6OIyeZ5LQXmIhqbkbC1ZvAz^J_p*~n-o+{koNiw@%!snTm4e%H?0{o z;Y_*zRr|n0$ASi(`47py-?9^^e=vxRuk3!3r0SPa^Xgwp)n?)g416W*s?bzMQUK)% zYTwr8Oj7T}?hsS12Uv@A}weTQg#|PhjF;-OF>=Zg93FHuO9k=Ly>4efx@5Pw=$}c9dMFe9WPi~jxQN+6G2?46pZ>%CIzclEs;LlwtHW{)5xOG3IhA-MP z=Qb=OR8Km@MNh0j?8JmlgZSZjPUwJ5^=uvP8f~?$(<5scgi2gm2GXCCWti?LS)>p* zIxS+1emT(JiW9S3-^Ckm_k3^bqU~>+ZMeVRvbt{E;y{1hSW=*i)1d*|=^Z7tPX}f! z`KiONUk|UUu8zH*xolm|#`mhdXSljwcIG7QwPN+C09}ivIGx_Kj<+cXj&(S%yWB!Q zesJ4DXH%{_-_D19{9hxp?(+&l=Ph#S_WWR9jr5-F&XHKOs<(!Z-kEJLA6Z9-S!~)5 z1r%(H4$KSmP2fYhK^3MDM={84Kr{PB4L!uEl|bBXUbI@+LtOn~`dov$)J5?Yw~7%( zC|dJ%Wi;C%7kS3!W3IOP;!-SUO$SR1A|_h%?H3;8&%-0HwvPlaYcmyNWM~V?1|(Zt z-i0#(y7LUqEbdaVCUQOj#s?sM)s${r-RTT*O`8d@%YMJj*{+IoXFohq##`p>AaJ+R zPCga0&>3PfXy?>}S@Ctk95%}5j$&62KLLl^L0mAlJlDR|9HRRomq7JU3y4>NT}{?gr0h`TaNP8N6?bZxj|{HdPGq^TkMm)X&^kl6(i zdFR93kG~#q`8Gjl_ISa4e|XZs_QtmR>uOtCRQ}kfa{KnJi;wSVzd4|^*zM&#R2qZ- ziTe~MH%@EMH7qxP8ss@pED?x%{6O53;1)?J+$S^tT^pY>Mr!$8vrjlarT2SPGo6iH z9#8r7g+6YNJ!eIXm%AQ-mu4h?lGA*}vyG+G`qw0l@K&S;C>&h|r%*dCa+oe6?-f8f z7!=4@WZrCwS|7|7sLn7zrW7eTh0h2vg3IPMF<%5S8!>gDiK_V-+4oSLXy6w_x)2=b z51+nszx|O)>h#gZuss)(ZE_zy*Z>8wMWDN?vR!@`7lFC9fSHjC$JHe%Fslm~5_rn2 zzqVS4)g`BZ>cj4kNt(KESHZ-xJKc^lXqjxS;8nbf$yjFt>fwj+n60~Yw+Bs5&0>z! z`oBQ&9YjB*<}$!+z?uSire$pw{v5XH^|eJ37PxiGz~G1Anx@=xnkD zkhu?8-*1ag2dXD+84pHZB|2PbJ<6{(#}}@ydSX>|vYzqm`CVmIg-Nhf88|tNkPX1@ z_ZXvaaFsc?NI-m3`V_GPRjy+=+36Si=Ybx*Rj71ruk^1VLi0U&5l>!(<3BzDZ$==W zSb{>AE3*iNp+5=X9rwA?GgFc6C-Bgp$+=Qr5gxX&7tGBk@VGhb%& z`WLD~3FC=kL}B=z>>0xD2AG7OwH(3s0Q*$*`W!o5^(a}dU)IU9xo+7LP_ zps2T@gil>&BU@kC>cctsD*mGJf4}Eky$2X5eqxEd8Dyr!-^nM6WitX8RJd&vQ01xZ zyXuSE+3E4sam;`hpQ-|UGf#b&gswcYpEM(e*hZ*-}NsuVAJ+* zfrLhQciGf18>@X5dKBar)T5cVCW$bgdLlx}#QZ-d3x2aJm@6N^j3oE{weX{X0e_z6 z8HH@bu6Qng_NTm{%>_3TOc1EBQK=?QG>*4olHKWW&Ue`NOj%dir=szeS1Lo*gW9exFFLiI zx9?d#x&HJ&uRE0m#N46s^^j*eLwuAt3XC~Yp;N$$v7p;vMuC!FRZWX!MB{X$01?^b z#XZEe(`4Pd_&HtF(x`>vqHw#$YtE5;xpE*l-h~)VQkchKX@|PNMRTB2J@gU2?EcTb zc06L?Fhc}hf{d$eD)u#S7LN)lQ|V8GgUDON7?Hcwk^Gk&x}AW_412xoG~J3~5QAAQ zQ{|&jB(C4(VSyn7aV6sb>@QQ$%aIJYJ+Dm_kS@Al{vS=<1`vPDjeV0GkyFWmVmyDI zMax`>OvSFFybHmJsZ1&;m7(ItjDgOd!XCD-6#|R(kmdae8RVV(X%E+<@11p2GwORS zT!)+!==&a$Jb}iny0LX~pwwsKb@!LS)@YFXY(x^_9w3_iP3RFL1!0yJ6lH8KSXwH+ zM68Q-Biji*T=}WAasp78$WF@)zw|v20>UJbM{>K)Vf7hJb%Q?`)*4?GrbF>jbPy;# zwS4L9pfE`U(f%Y@hkSWH1SAu%piC*!Q|txeJ<=1o_gwY?u~sGDpKMuBqx_~US$Y6$ zYhLwKWb<~#+XcF)00duSD8bxSfb|6+m^=YhxtG^BlI8Z!mcSUj;W_HG2ei=k7!wW; z*4>#~8FQ{5F;1Ww;yWgc2W@Plzp%3<<%&#DP3y*t07S|mc?sE*4;hk^>Daf?4g_PE{@=*B2TB4%a5 zvV+LB3AJnFjWC-fEuvsR^&2^FQVLOt?Tz6)B9#8=%A60Mag z#}^$_QmSf6Ry|nHuJ_b#Kjj@TT-S?s9eg5_rlJiJ)1D->yjZvBbbo!_hGAi60P}We z>dtcMk-!Wy_oRrdk85A*nHtoPfy0qb!kUuR?mBx5Z{FnNqCNAv;_T2K-@4D9xm$I! z=|r10E!8g6;C+Gd**sUD!mE+aCk>0Q<{gZa)HR(Ce=A(>Md`O&H#t~%^jgzNhMtTd z=tC^dh`XP>5=;3Wc_Xz=2IN;s0(Py#T=ZGvn*q=E3h&&exfM?GGbKAhqaQ#S*Us@i z)NQ7m5Yt7VVW5hNzMy-QWGdMtzblJWe@%IRR>06jC|&Uqf4Vw{vm25Ik`8||@PdQ> zF?pMa4ZZ#;@Vw=*UrO%rUayd)507@P>@(~9IT5+)oy1-B*1_#ZDX-)2h6dzs*y0!c z?eWl={`O;Wo!;gCVVj; zyJzxt3e&5v76%_6?D8rL+0pDp-6Z2fOn0cg2LiGrqu|_A$E!i#&%6gMFOYDk{!Thv z7$;CNEAl3ACNlBwMS2Ts7b^bu?}GjhZ_{1$zkkm#D62bxg$mU-wK}MFLZhk@NNnpp z=G`{@HPUIa z|KEaV2TqdimI)#cdZJUWK7Kv;X~X1T*@}?G3DG^b-Sc<6w%`nu?o2x19bb;T2nT^5 zVqrUcuAc*}Xadikf|sTeq+A`V!Rse}Lc~pY%>MNsE* zr_f7mpWCrNOeeXvb0RAJX&mM@__dXx{Gg?qipnmYI&qS5@+&=;iNuAZsM$tze+UdX zR^eT~xwezvH05~anz37yeDZmdQ^Sv;#&ZgcIv;C_N@emt32cnmd1|^*uU{O3PNFzI zd7IB%slX*j2hRSL_}7K$O-`>Awor#JI9NeJ{eGl43s`x`j{Z{WTUv^Mv}Vcd5E(DE z1|zT+yIRpdycLs96Cd@|Ci@O4tdZ1DB0IvE9n5ADaH+-GPy6X%mo4hwwdqF{p1esz zRn1!0t5+{Ibo$FKsn-t=g}jnF>`U6|u0_<1&08>_*h8*<`~Pj)Y-}tXq8tS zyN0$c!sV#%>pLmIURlFC*rXrnx{ZcDyZ_Xq0Xpi@XTQ77;)LJ}A+HWsZR$FFxB%W% z`QY*TiPr$T{HOc{#hmrq7rim-H&%%m*~J4*`O7gF%`9-pEQg3P`}^cQpar|he=C!w zL(_>xnm*0|dPAr*v_b3S$OTu?q*xsoUmS);f$6(Dke*g(C^|=)vV%Q?1>&6HBK0cJ+#%`n` zJDe&1K(tXefSd^9>gy=fJ7Ra;`3HoH18C-U>9!&#k%{k!$9s8MD-+5_Fg zhXfJ=PQAZw)m9Q3dsf}D#uQbH+lAZ4fKG+sqCx+`T&4p__FsHb%A<{50Y8j3gIA6* zjF)^Klj7UqAo3D9Em@8IB8K84dqS-Yvfe7|e=|uuGlN-VKbUC&na!Nlqr;6q=ifS=`0ANa!-aoBmG2 z+zXBZNUIw8D8v@krSmeAGUg}-ieaqk5OlI{b@bNJfPHpDQhJUI5A?EEjy>>x5Qlg< z(Kqj`=C?gl0s+OJxDfLYB;7iq=*HK0&U8s_ILl1F@wn}Pq88YNZkREFtRh*W zhpbAn8@%d_pA$k8EG+}xtgofC_~tt`iRR}OWUQs)4WzXe3`!(&|)a`o!LVA;ciB%?pv3;Cp$#69lKjC>bjkl zwY9xx%S*wTqg`QVJar(qe!r^qr7JuPpEqvyDm?2Iy<<9d{f}U>Y;2L`fOU6-xLfe= zWZ2hc3(!Vco5lRLqtQ{j@T_2Cc(JhJryl;B4?F7mV`d zN)K}31FkAXwWp%{25318Z-b=!A)iCRggS9UWt>-`;T1X-(4hK}OZ0R~$_m+J?C z*_X0|sQ5!RrdS&bE$lFg1y9_XWH@9 z;Z+>>)Ti2{*|QSrCL{9#oe$S?qZ_7QMPwU=_TiJ4?fif+fv}-2Ira%7qMrM6(KJq?HVA#c z5hJ?=zFNRaJBV{H_afGr^!3JtMUrZpTzv6o1t#oF@di>-q3boI_=Tn2p<`3LvpdpX zXCF_=i&4D2Tj5)-W(z-l%sd%GI_2KQtMFn%UHrSrm9knFaqa5M@Rg1?pRsG;oDDhJ zPwdN1HKH@Ge)aX+#O_Mk>{Xgxy28b>%O?l5&M>;zETvY?`^qa>v#Szz6 zpU&<0_TcDS@qRX9a{(-1S9cA0#rHo`gLphK{^%QGlf62zK z0qE82ib;bv#jB9y`%_qSQn31AqRtfOqk(hwdS?LB9rKpdBBoMbnSuN|z#wBZ70Lmg zQm;{@A2UjojPg)5()Qf);| zi?y>#>bx-ZiccR^Q`!jRh5zf%A`L0}rL=xbfCgPB%U?yAIuCas%2oE}naZnmbCEB7! z8NzaK7R0_6_jCZNDU?7T&22CDhaEZ@=^-jetRU96%OGMl7gpxYw~wO)%F{<}0i0tM zc5{C&zJAco3gtdPw`S~Ogkwf<9iSco0o*g+Ri^Vr@U{%3YgEb#F|qwcB#%X<+o9Ck zGWdNNCI+xB=U+lYL9u@GQ2nb@@p8{Y?8t%gy5unE-(4kTIiHMkdt?nr2Dsb*)G-`! z;D3?nGa|vf2gu%z9{#xMKJheXYL^KJq?Rn;QHo)V*xQDqu2924Qd`+h z%nC+WoYW>72c$@xlT_2ziuV^uiL&Ejb~hS0fJyft1g8D)u=X^B!s`#o-ORN=8<1JCcv@kRKWxtGAN(xC&Rw>MOJ5R|%V&AW(~7R;Gn#Plmz zGk@N6C`#TKIxz3?^zb+wA@5UxqAYpNzzuj!|- z5*93W0WrG&_``ew+ocK{Y>ZNn_gf)zASj(yl=UHA;Ao|Z3!x4)kik-yZonbFcyS8U z5&28$EEVwwZIn!?3%sU2uh5^Dpk*(7ze2y1WGmejCS||hA;imo?CLgE*~UI3NS_e{ zW=u7>O4=_avv9@A7wQTf9I}hScL%Wb&|gaHAen^?auDK!q&}0N*vCbDxiF|Prexvo zamDctX?5zfkpeJYv!EsjG*oRwK=KF`HDN|O^sE5iACJ-jYO~Ob3R1z|0lV94V)rv$ zVa-xLMh!n*7*YMkC!l^V)!8KhQt4cGhz7Lg+NiJ`0Ci6W1K-~0!`=KZ_&VddmHz^F^ec0DpgZ(~KGI6o|=d#0(|rl!sZ zDgVn-ID7%$-|x~drQW_$@Xvoe2AnV;GOhYQJ@dc3`jZ2rM5-X&GLLFjG?hj(o-$^R z3PetB!*(v)m|YYTIH9QFk|4=KeN+@n-di$8qD#8OtjyT&$uY}H2kZWEcIVSk1Q_xU zYB#AZnRLwjFcSFFrv%0+)Cd9`hJ_L_#dnyD#S}1Jp%br!3>~t@&{`VHr_en{D`3jL zAz(hGZJP`fDlGV8<7(~=uuUe}Y6)etcrGQi{1Jll6*p9xPz5fSg$wkeHVXiM{l>SE zs>I-4&oZpx$c_2Y%;)~D&}!f1mez4M>t_UCRy!h7xEEaJXW5Em@`|THyRW~tz8M584&R6e^P;-Kw#aU^Iz0Q_5oTCzU|mm% z(bL=as-5J+>HtzJGKYtxb$z=ATG8cE1}@aAV2Y@XO%4~MYs4=eLPbR4J%8l%z<~qb z?*uPqyXEw2m~ane+kTDz*qHN5e>ChUNCuYRKJKR~I-059QrpzpYTD$t=yW^z;-rdhZvLX;?uO#H$3CSIiJs)wZR2fs>04wFo))`o5c0C zB>(zq!+p|5p4s?As6;&5t>~DVkaSBVQ?sun{ZX^A)*@@K2?A&YrTg=rH$G44_dA&} z0n{jN*hl>7nbm>$*M|qq94&$-{X=Kz!&|1!jm5)%9`fDNv!vwk@YXlkhAF361S1nxA+l{u zvAkZookL+#w7{hjx*~=3@&fXv2MCe54e=nyLi$YrjZRAJK7vf(l@Vr_y_i`UGocH? z*fNwP@>+b)c}v625QFD!Vv&d?2`Nb?o|XE`)hKEpAXcr81-7<6(*}{OU>iaHb(?G` zA|nCVie1GR+PQ-Q<2#5~upDNv93McM->aLGZ#F|+axCcE^0*n!=gX!Yn%UW?_CV_8 za~fx3OG)nDS1B*R=f*-&5Z-_c$}X3aWPb0lD@RCKLGpWy=pIn++bb_7@8tC?dQ4*b zBPG&ZeR2Fv*3QP|^`DCiLd?X}ix7V&KsXz*hkYJ?>o}VHOwv8rdtQ};F@R3cuh5L0 z@xZNj7wmJp@+)O02$;=)($ZzDrP#hop*!4alYEvxHm8a}1s&QS{CB}z*-n_9V)Icv zpX01^7A3)@+xEonG|$;t*Rx#oqivJo4MUx>jf|JyZL>op?7$&sU#TUM%W4C^?nBoq z57n#H&Y`d>IJPx^pme7d##;4H7*C?G`a^atxMd;1&w&cWxi7&(cIvhc&)Qv{tA6_l zrgbB@ektWG4!GH_ru3K?%kvm9prj)?FR#KyP_HV?5iQ;vr~GA`npgwaL`x-W#HuOS zrLyBSV!eWk*mdOn?|!&B2TOl@^`c3I3)4pi>YcLj{Ld{(apfDIyNf*kl`=ydF_l3((w@Ss<1#14{jP+3}%%j22m&sER}~ zO_qauXLlPIk}bsMog!aBWQMa9e{SV82dIX>aB$r|I_4m`0#{1H5Px{On_J83gp2~F z&nb4u3n-SjZkwwVGx0>NecIz_?7A0XD8pGrV2t)EURCBuzXFl*e4JiPp=)NV!;Zk< z5WSl7>vIBEt;g%7DVD#GZUz+tQ}UnkbURPgn2B`&HMnE?ml9g$Eo7ibSMbe)cITb< z0dcIQHL!apXE=*~{tN&S6=w;@BV_Kp%CRktSiQmTB9m#)g1&)!H!fmb`oFgXqZFFU z#geSBNc#W?C)08awtn-W&#d=VJ?O8*W^4C<_z?6uATZ<2k@7pvRsHT8CXMpL2tu1I z{o#cIU^)#r#P`YQ-RJorA3@gJFh>|su@20Mph7aY{&WcsqWaJ@2mCL;y8|H}b6DkU z6Voq`2EX*HT>g-sVpX#M!FLounblO7NNqEK$UeggTgqsNDpD%$lU#VmIJpdK3Zmvm z3RAKP+?P$!{(9ki@kYgKgest>u^shm1oFN9u+GDJf${#?S^c3OPDuo5dK-I59I70O zAdavkvGOde@iYi(BJrt`wiWN3j|*G?*U)Lm&Ly%F>i~S2=!S&HS=C6N01tJdjAGi> z!sS$FkH?QK6Aj8Ue)JyntM+kHUrQ)wsyz4;b0cIUsF*>#VPMHA^n(onHAw^L2&lOZFo+hkqO+9&&S$) z|4FeNncy5Q+fd(92bO&lMB=F5Isf;+H<-3Wqs;TZUZ{f$562YClBB4>pfMyqi1L0w z@pia)E0xs%)p)Q)4shxhiFG}^9=jH6b9J8-+avH1w~#_m`qu@16cZ0ihGzJX);Z*m z|LIy{85G4u%;!3&oH$|QOFReD&Cp^*VbnnQ7~Rw|*oGQ~$XgLQ#G@@k2!TUY_0{Ok z;x$Cgfapeh_5v$YW<|%7ws#gd{N-j+&bP7oBg(XK`|X#wrC2+%5258HBu?`ZKrFFwf>FkW~3FeXHa6sL3s%yVm!nzyy#1R+fJEdzYlBA zZlW2~MeU?%A}FtC&j%(Zl1jb+oPr1yDm|v?1L4|V^P=t2P16R&^(Evec@852Z;a?1 z8BpmoSzrH-&iM0=6lWAQug^J^8!}1RE-tDr$ZEBtPi{Q`?0WU03iAuLTlL<&r6_MR zqP)ed0M&z&@=~lba**wpCQuc*SCh9xY=vbIKIU7e8>Xt@th%1Nzgj!^s zWg8Z(CBRZx@;z4&I_Q~sM*`TPsYBVq7!*IEe=)M?3qfps3wJRMR6>7xEB_H{rJB!r zQv$w&4uv`VuJJNtmB8gZW=kS+J7Wds0TXo@E@m!UUApQ+h}#o~OtbzCi2j6GtXV4> zmvOs(RAHjAkF4SXYxVFOYmV1qYA&3I@4vaKl7e4@(FqtF2EtSUnE_~d*Dt${zLxY z``nm=aK1})5??3{0>&+Pj+AxIpm(_3^z@Cuar1-kY;o#3mN!~`CNK?++N=22Y<|O} z;qN01-p%F{3$``8rMvdReUf$1=+dMO8O{W>Xgi4c0d(k$IElRDRP|RlQnoIQwOA;% z`~@jRK^^8`-`|<`NjrQDs{xMXZ37-aP2&Q1grnH+BLIDWqOh;qGaaXmUE;>$>IHud z*(qi)=^Vo#C=;WrP@g*I{xDxW18FL@c?z;!+e6Hr4%S~6;FcpDZw0U@K3_A=A?#K8y?})MO&CCUGEdlRqM3_@2sSpZej`-!V&N zL5Ld+HU2^UW9ZX+;D*a?$C*Siv}EdM~e)YYCpP4U5xOkwjd61!U@JvYinTDDr}QX5ozL&kgT^ZKh&0_pEdmr1vvH>J7C= z<9N5YHLhK9U!FM-KtE1O;=6Xe&^hp~e%!mgnR=08L%KXQ;09Y=1`5%_m=F|_EHKvI z$Edk(t-T{*r+G?XMCXxz)KG%~|Kc+6YKm2)ayNK?6YvNyQHD+G6h?!>WPFGiN~=#k zDr^|A)*dxHGH5%U1vR+GFIwZh)$gXtwT((gR6o8*lNntHi~P{wTvgo|W~{Np0nJGn zug|`#%=Z*6O--t7x-l`a@?Y}$1MgnhreAsxzt5^5;>ZEHv78RYQb!XdYKVUXh)^1l z#s@M3B%%Ugx{5W6K&|5sI5Is2NH^I{8{@tE>nyA=?E#Q#MuN1mGTUMIaQ*W2R}Ll- z+>N*WJ1a>_B8BWmHi2fw1DOR9Du58v$oAO8PKKtls=zo_VL`s&JDkwBjFjXv6dX%2 zCu}-Z{RltFMxSc<`uK0%oHMF%JaFyx zOWG@1Hdh?XMb@){MFkaHUkPik7=hY!5eQD?cY_#xSzoqnZG{Yn^pF&oVMT8&>C}@S z)fj$v8UNLuv5>$+Y@foeuEMI)gqNH7wQO2q5G!l&-hJMp z?noq0KF6YS=z^Tv;w(OvMvtPbqIF%!&lXU%&KIwN%{ucJtaHOlNZa?q<{1f2J>8c- zhnw6f4VLG>?w>!}YA?}G^xg7H$qo-N2`|vRzAT8>#t zOA~t--9ByT;Ur0f3q;WyYQ*e72b`v6hH?4T`lM{k{u-nbTbjh*csl;(ptD=m^xwS_ zjKO3;Dt!vX6vwG)9E?oQRiVa^u7TRk?at5IC>E2KAf|AVWK90#{s7cR(=}jawAxgW z4dt}>ibTiVv4Gf0nAn70S$+3s;WTpsmm?Xu*KmDMdEq?39(}i21>~&Y#FQU_E{RO+ z=J&P$HJ2DTP^L4v(4F$cuN{<%tFOIWWLI2LJ{~wec2G%s@3tLA>>iVqat0JWXF?gK ztz?Aa)nsSIpG&2XKiT3Px>KyQ+>%a_)>OqQMW<3>mjZ2=ODErzOXbS8-Ghup40jIS=&APMF|X z=`1#;;d#+;6(s{moxTZSRo4XoHG za3G8;CO~1y62Ra=we~WQ29sZ8L~&C&Dy1R41lW}~+a%qNlzPY?P_%#`*Ubw1$Hkk) zuBq{rBQqi&4{x9Tct{IzI&dupyQT4YgOcJaBO2lmc#$*b0ect-!Mlpggi>58gjw3E zVxATT6SL>OQ?;fW3T=xm;r-dXK9prM{wh%L4rx;K!w%{3$(uBC^5WOt_+f2*P5-Rt zS#+v`4di+HMsg*ncWnj;4Itix1aTUZfv*0ML`y3in!kkINGkPU3*PbGolelZG4~P( zQ2gO&36CLn_T_Wf_}I-~pd;?LbBZ*$5=yDWlZi*H%|&tIN{I+`pu(|slp)4aVi)^T z+m^4GXY=Xn2FjkN3cba&^grcQZEBOnHe&0xcVX*c^krx7h)M(>poOaKfy#R0PJHw0 zi*;uBLG3RuVi1RE$+Lg@Wd5EPRbfyw>=FkSD#;H34ge7cjT%ZGAj<_1CyPhx?n9BX zfX+ZLH^a)=7bbLG@Xc&nh2VDMRli;!W{{6oOgW}?xu~|ss;1SspnPfv?NBj+^bpqIqOkO05R>9F#lU;VQK;4 zUO?c74^u}2J?4PDTHjcbVi_pss;D9A5OCHeBRl!D(dj?f&TDxh(?8g_P`{5zmBgQ<-`npF!Y&dOrb~eUQXB0ch$B_&=snByJSvA(RQ-?(7 zCDSjqVxAZhuEN_xklYUYftdFfDP`mnU?b^Lyke-xl3=K#keUikd{C24H&K`0k?kh( zJvoV>W7UBI@hA(@h9bG6tj_M&%;Q7fZ89OPRvcmT!*ZSob9}&#n65ve-cJsjPF_ya?+VQm8mF7^wf z9~)brGM*Kyw>UwS=hvqSCj35Ua2$MqJcHQF=IVqK$X~-CPGZMz8sjyf0(OaFOmLHW zMsph)(`0M;z{H0;SLb_B+cxb6mn z*~SvjWK=3$=8~9nc3}}X>Hh^jSo11;w^2t9Y&e#!nXM| zRF6|eVo)lR2Iunl7DX{6enAKx73jYqmncw8)uD4Zd#jd(1->`9n4G;&_sCM8mS0M1 zTp|_i0aV2e4}3O5e7H|75D^}fKb4s$p0TP<=*uqNS^GS(AxAQCfWj^9F{}OoU85TX zq~0c9zhmWn_{IU@@0hgG;fCGa=kgnD=%Z>C$nY(W{%3s`C?gRBTs6QKHiAM^vFR?FkPm@QmCcDjgk+rZwD@ms|TGxjo~E}WUY8!P~Pcz8KdcZ91x6g zwZv{{wE0`NV`2)OOcc}kv$+CPh68S?4C3Kd2iFyE7kj3)9^#<0>&l+OCRq^?717Og zv}MpVrjb$#)}0kt94WwNqt!|Pjm`_vGc>U(P_?OQ+d}pib4APH(w7W9XJauF92Zyk zM5UOC#d4a$fV>!VGjRYDtC8SO#tXaP*-C+@9?6|`0evN+q5fUHrzYYx&1%kmQQgIw zQ-HOtvJPA+F@`M(2q};zL6j~|etAXkSoFfVqH@I`O_^@*rEH<}a?6Tq#;X=DTaokl^@U2MmzNjaL%p&A z9lEuoBHRwvL62#(fik7Ejbui6skMxc3NaYjTXsq|<~ zeKBa9*w_{AVIHVw3_Yx?e?B-DYq>UW_DN{QFQve*|C7n#f8V@uG}Kj0-4~fIz8fd@ z|BVa=X?L`ZIxyvn1A8hYT}v4>u}3_lTad)==EzQz{y5lQnve={IP-#US6_}|GxTo8 zmzl;2*-!%;eIrG_ROk=Y1IE-`T4cfDHbx6dE`b7kD9A3MT3Sai+7r@82K?ZHZkthMkaK3GwR10-EFSQ3A#~$cVmHb549@*9 z#xZ?7EqWgX;iot$6S;gy?sROh3Y&tIi0OjEAPG<@mEWLji=I${kAqsC8U-K^6E6We zx&GKb#+`N!>Ke#62t1Q&K0|$~d0|idv~gnafUR*1=*SF27Fp9{ZCifwvV{$K1^=SJ zZYt9;1mbjQ;B$4ru$MvrMz@TVD6mNdw%(&-LI-Fj8ZMV8KZnVjPt=!mYJS^N`L$MM zkX&%pW8dbhYha)8?VT`C&8bm&JXAc5ZD&FJOv5TUy*8Ob;q&SF=V?K{) zL9)bb&|uef4u^HTpNoGfWweH>urpbgt3{zhG6!t6S)M4htQ`RdXY}tBP82HD9*e;@ zsEQUz!xWu>IKX9zP!cDY1ttN(3g13~1%NqU$wlOP31NZJ4yEHXDVve-_TuG(KQK#? zQg2|p!)KsLkVR*MgTd*HWsW&{aY>J2IAllkHN_BAH`hf|QH< z85s+VnTjNFmgGLN8w~MiZfD|TxuTDTmc@|$ACY%9!3je{mw;)DhSV7-N+qJRLd8$Y z`O_fW-!H~zgcq{A3pap#$+5MqMtTacsh~VigJ}1J!ul>!w#YM}*lEV7yTlCv$;%hX zWt>r~mRR*DAXE}Fadi{5d=+34)-p{qU{*#i_+G{?rSu&E^T9leVu^76{c>z*wl#wP zQ?`@HH%zu+`kJg8RKneV{9mi(t_|X-tT=?`qvb_FRRH>NhzvpWuM)=p?gjAt|79vF zXg$uuph(?G?nNgpYVGcN?bhLpJFm`k)s9Wzd_DI(tm<*~x2It**Mtmbe(dIL@y|CQ z9b&5QU7hlXzljg)4juH$+Zi{In?>;Rh}$=AD-R(1=L8mf1|9WVMguCTEZ*bScOQqI zjn9kOp10}o&9aRShOh7T-!!-pJv~(Z5hH%!3|6-D54>y@O|d;hB>^0vbMm~?v!|_r z;fuCyZk)xNVUS?m$3@Z7+Kd|$cSa02W5iNHc}gqhe#eFSwyb-TVz;$P8R0iR`#;PT zy|zeO#B9<$9t;VdeJEXYsnhYV2h;qgaJlcON7q}U5C4*%ouO`X!{-H$`hDB>R+nE@ zpbg*Nzc268NaMkH6I0ccY=gJiuBu)%#|np64u_3inNf}>MnsCg$ec zSaepeBP3hr(`-@_b6WG>JjfjaLsrPMa1ppPeC-p4bUg{pb7jt{QF=o*4UmtQB3V43 zm1l@r479s^bJjlx6r%)1-ip`ewXntbxW>uxvVZBNO@L*3KmQM6G(rGcn|M{=FX6=Z z1*S()6dV&*vP*O+(O)f z$1mb;0#RH>hYg6X+f5j}=O$SBH6Z9iLZB?^F4=F+$U~X(9mz$pLpL>RPrEZ-z~J2B zP1FiRdszY2O>q&QCfQh1hS;Sq>xVq?c;m4b!`&rf1!rEw7Lu{vQbX{$PKRg4MRcr{@$} zeVQS=AEkduBFI(Uo3b4OMbLC0Fgs_94TU%=R+D@bDHm6^D|R4RQY5c?Ywk~%@;~N`AcquA`GD@q9>&B#uEa!s0~du$Zzgteul+948UfSbQs@Cti^F&P zx4ynS8p=NITX%a%vXyPREh$S%M98$+Ln_;d30a1akinR%l0D{*P{dUBb;>qbCwnD{ zVPvc`lx&%)j4QL;@2}^1-t#`sdEfK?F~>R182qm5`hCB@&-b%vA(`763lOk%pg;z@ zWX{%40RA1DtH*3Gz)2S=?gyHV+nMEl83S6W-Grq2ai9C<eqyWB#Iqxu7f)?J^(eN$s2>a;*3ro4muY!Ch z?Hp)v z60l*+ixmE~11Z#UbH@SJ8AyH)R*4dBq6J(zHnkandr2(?__(UG0Hsutw~gIj(nX1N zS7IwZCPxi)1}i!bc!dTs2|NAO*^?Mlj$JWksO6ux%6ZFyBJ6i_rVXR_kiNuwNYS># zJTyE#gN%2VU;#T}!VuOFor>6_8*?(S#gcu{E`e@Ci<<$|Q3uv7dJ5LpytSEHm;RpO zQ=f0qbME5y-@m{UbqfbHiLgp`CwQ))Wrc!oIl1^Z5bKHri_3Y;|Hq43<(+*R-pRG$ z>GGcmgyHeolJ;@z^DD8ItTxI_|F-!{L)R?Y`briq^0bHQhO+|fWEa7a(+0u18DCX| znP#0vK=k<0i^IRTa#db4>u)qf57K}9pwnV5{l;tIy&BID_wzzYcb4DZf+SFTt3sAuCwV2q81H| ze@$>A;Cf^Kw65X;9Ucf+V>L6TNGvf( zog4V);UPu-(hto`{iRETt8%(tw_sA`sLiCcz%TdF=6i6wBZ3?Z*;-(d+px@)oT1OKZtte~YgvL{Mr zTtO0qP4NQi47+r2%_7*VmVFg8*oE{l?7jA?@W4}=TJ)apQ|G5}+!-~VI9ISU3AnGG zp@NZ;2tUc>FOZvImU=r}Obn(WcZ%)7#&*iyr9<1EGi=UvM;I=*NewGIjESx%*ggs0 za?3`3Z%?*FR*9TQ zlBzTt@2c^?`MByu+SIAszt2BVCpi5#-t!;+^Y2=w({c%`gh^gOaCPv*(3FOqIJp}+ zreO=u7x7eMj9griVydJSQ3gmqLoyLS+kCS2Nqw1|IV(S1*W9%kx!m_W)JXW@(etyw zaq9Cl7%K*r;|Cydyowt(_6)msnamEhfvGGcbD)zV=?Xh_3q;wbb>=oBb&q*xX*sFI zMKh2rN;puv*Ifh}Ua9_tkREqlpf%M4sKk@Jb3ibS*arCl7BYIr_D%@63fDa%)=bBT z-(^a}U)VAo?&4&&Ob_6BSK<}gWK2Y14U+$85(60AtFyJbQhg)YI$U$MbS*<;k2ddc zadE@TDRAiw@{c^ZED)JvZSC$VPo&gFEHCN)?1v6GIH2idMsuHLO{37EP5G7zcZ8(9 z9snHs4O|QEi(5ectd5-qF_BvM1A<}7jutVl4V*mRJq@TYZ?x}1b%+#@Ot>AGuG?3P zjW6JjvbT33w)(M6o|pJj#OqwG1Lc_B^PQwU@LqJ{iDNDK8iqyu{>hczZ|m`uCXfsd z!J5C*CW-aHDX`W%-4#FS0xx`hmO|#o>}O-n*oe-k@P^c9Fi2w6u-UAamQg%LU*I@8 z?sSYMx%D4DV)hg zvn+|9S2>^g_XRTeQ6zbw(+0um;FklhIAnq&S^<9q7YY}Y1>_J@T8t@@Ub$U(8J2#B zFxSR&zlkU|n2``)ub|fHE=O%sux88;1^w!KQk74W2rT&w-GOX=IWd7%?tJgG)Dip+ z0S#HJ-))D0bD7J;muf33+%tk6aK_cdQZL2?^xzHPQ>?F}?I!AQpjvA9sOAPKrA7Z4 z_6KsOe}=`6eub>0BJ&Vq@?VaK`eC7W%9i%b%)J(cW@#347Z;Qa)W3auQ=xoV{r#Kx zE%$cl{boadX5>dGUPSuHuW503{*5f*$}Z`0m;1gP>!iZgPeFO_NT13z4u5)nsY-q1&`_Sg@l;Rc zLWjfQP@Mb6TPcrDHvM>qe%CN1(dki6D@ZI$cn)1^L*#yT%u^4oFeh4a)zf41OoCd{ zotmRgjPs6y4mU%v3!oiae*8A}eFob2DahMKP2dBd89F*%AO(ul`8EY?lt>8{>N^ZcG105jqoa@mFEB;AH~$3QroYVn;JU{?^jn=uPWu9_j&rZDVI2# z!Zm>2b@D(TQ8T~-Sn%c4U6d&^N_#U041zKeU~q!=CNd%fC9=R?D^*C+Atb^-D5vY{ zc9S84`aeNy_7)#XE5E-_EO&X5 z=-^PfnQpi%}j?g>ii-tyW3z^(f`#OGcXmMY4U{F<2T6A=7LG<`nh`GiUz` z@ASi7K56H@!#oT3Zqk!$K59HXzag8t5_@h)|LTFEo%k<|-XMeie2q&ZT^VEb;^j4`kNI_r>oWLIo zB;d~3lHLKtH-vDTIJ|A#rkS0P# z_XJY#2n*zqvt_y z?Tlq2IG_C2qug3oNC|5Tb<@{?WzrAr`$R>-ZX7l^X@LdixCw#-AR87+$v+BSBC^YBM(I+!WBxTdQ$?I3v=t74|zvgIQi}EAA z?(I;HEY9%-o>Pa0ThjZKGc9IQC7YXHUb*O!D3nuD=GW{ap!n=+n!Usd?pfWzJ3TsLY+!nWZ<;S<_;d>GFgx=sp#LM;jZ98qaN}z0Q{}MeW3Rx^Mz()QmMBi#x;MA7_mAii+8N;%#M*p8?@)Cw|)ITD*i~ zJ;aiNw46G%e-eNXJ`(IY*D2S<#?(03@Jw5 zK}+atK%Q$4pbZ_w4x!@&!lPg(AT#ocUsWtY+yB8xz||U8Ucr$}?LGdodd0*l%=9O| zOqCtx6H7PqOej97YFAqR zJlsdVQ*DNiR2_h!K~}dUwBzzOY7A~~70(>sbq4u;jNkkM z`s8Z`RxcIY>53$_HJ~2&yGei}Ps@JR^hMZVW?I%AUS%Th*2$s48TMTLNO-Uaguxb~ zdLah)_xEQR7xE8>*WP4zZz-HupgDQozIGsme;LVuM)LvwR`B|dj3}-ed^&J3e>FBQ zeX+;WZw9trdW>@L-nEakvMY?=suzTMnmT1XK3+Vz|Myq#uB*ZEy-XIod;5l9cWPv( zC_sq|%$IZvf>3QAZCPJ!n#1VyRCDF*xQgUD+2BeDj;&!Ygyb!kW|n*v$FJ+x5Q2 zDJnI{+&$H%^i-n6j%%iOWP-8ZdhF68e;ViFqeZUlrBu{Z-)HJ0|10;i6LLZbNw2R` zq!Qb)n6;-4>i$4nDJq|hZPtH?Ag$F1K zPtsMe3u0Kq&(aRpttL?Fi9F>E+qtVo#>#JU?qrAMetD2|>v|4z(I$PWwTc9Gjopd= z3RM!Jb~J^phvcE0Cgwg@-qu%#-gwq(B8HExv3@OjzRb$uNL|mHeRt_{neE~b$HCX| zQDbYKrPa+0sDLFne(ZzJRkB>}46^pPrtRL$t3KOCl-Ht$>~iEYeJ|B(RM>r{JzcV& z2S2C&XkKlDe>Ia#FqVrfy}IBiP#v7USm$e<;uR?wEZ1Y{VTs3>9>OFbcj|4Dr%rg(|1=M*6Mj$+xr!hDjN4FYp=hy!RyAo z%D;)e4e92VRgM~jrx0`EXR^)%v&(h~*ueQ=cDS#6SYyRm-2>&9?t841jg(jmYkM2M zCRTbrcYKg3R$+Fm%5g7RtykW>$34Y{pSneF{hMWV{ zCqT=|lGT&#QHs)~kuSSi(ME6oJbRs-<1AnN?RvUSC8Q6ay#MPl2Y2V6M+W*I&kTAk zAr-_D1LuY!?Vkq!3jHBweFGE1uReEwIq@W8IgJF42|tnIMYgw!^ZmRgof`^vUa%R2)hrA4b<=)KsRixs*XWfxW6R7_5s-wJ0N7was zf*se9GK*+KLhZ+)ndda(w;a1ScJyS#7;(0(fLM#+OxI?wyz}y9ML3S~Y;HZq)DeYn z-emYBGv$zvs#Z|WcjjO2mQ}%RDM}xXKgAu>Hh2fU`eGH9rHDkut1XE?g?tvRCuxcw z?eC3RhAyyb7hebK4*WFm{6YjRDo5no#|JkDH&%?%v;u=G;ojeYA&1q`v?e>EjpqPh z_}*jikl7qMkXm`#!75+#suyLYiCk}-D?7UzorY>i?^kKkUS8m;Vby1u($#tf&plKt zP1N9bl{~q@I@hvYNzj@R#-l+)^U~yJK0rse+<;e@M9@0flExNSnU^hPdML3dvt|%K z6iuxzKJMQX+(Q^6bVZf4+sU73a6asIxl6`fgv`EQ?x;f(s5E51i~aCJ8MI(yd&KAg zf?Zz#BEOekdHr7@JC^x!E(nuDvTVfe(I5GSXTZ6Z){q@thVv@RVEnLjnKwAE?86;r zIeZy5$id>|1A`EKhuxicsCMr={ z>p;F{2b$hzUYpl$8NLz?QoIHdawZ#c{Ry{6p*<^4R`OlBF2Sc}7YHAx$B*~okI<~!~ys|ib>&V zf-U5LABslN$oPnK|Gj6Vi6V5nwHU4)FPcSOZswiAtq^Tn`y?u|f6_r`iC9`~e^O`(`;=0!?pB&ai zpI*&X%Gb0KHn$r|PT)yc3wE9Y*H*x;?N{poN74e$Qx;|U3HLhe12Jz0;z!>A{F<K*(Ox#%h<2U3=OR3RYIyG}572Ec2k>$C8 z-`sZymfF624BS-vssFe@o!juE?%Oh$#TByi%jlZy74tbk|8$+o*-4?joyDEAh)r<+ z{l>aFMPb(k!AC8Li?4nV{(^;jr^(=m4#2yu;!xWs6Fr_8$gL0N`179`Be*AFrKJu< z)sebBw@~Kxgtpy(;veO1q!vbybHZ*0%d`Zdb=_jjcap)F+Lgo=mPq4C$r zkD&zHHpJ4+j_6(LkBTco?Pgogm)#=8^9IZalV~YyhD8HwAo0lG^)K1?KYgQTbTh1D ztk1Z#SSyY7*PczS&mDJDwJrZ#Gg&rq&hv$5P@(g=Q6f&Vkxb=jm%A--mi~CVCUnb^ z5_#q&)05aB+9!YdQ|YbQryD-4t@w}WLZT)gHBL#tXD%|wuMB?~`d%M%>Al?KS>NoR z(*lJ^=IVwK0dO8+)FQ<5C&1zJDU@&DO^iTA2>^EjyZkrtzn2V?b9@Y2Sdcm`@bN?Z z!59W)rw9?;ow&cLD|$x4%~W8YCCwT~O`Z!;r+2d=W``j$qsk+KtN0u2o=PsRM^kz7 z%RBPMg?rc|o-QlJ$xNBa8b1|F&zMU4hIev0Cq^9|+YP+cZ=R9jQK0rS$eH-*I`Ya+ zMsPxt(;u+Ko9ChyzqVq_bz}ARLi^w*ZIQ{M@5DLhC63d^2?Fy(iu)&*BXui=Ly(A@ zaFtOPv@us!{mtj?fHJTree$5J=meWXC2D>7Hc0JK72Xux%$3L?E-+#t`my0U+vyh zl<^O3Cq#;;%oHHVqwNrUki7hyEypQ=N3pe-HtBj<^Sdn)fziQWTy`1Gtr(w#z~pMF z(=7Z^3O{I(7LaFW?;22w(`Td_q1o=wgEoBPqVI?`2D|}b8w0=frs>v#w}>8XzEi#u ziJ2hSfdR}~!$lKK8YO_V1zhg)#vm3Ef8CMcGhXRk)a)j+|3JT2lt@(qYu7& z4AxV|&@-!djWtS^WFN`;#$T^zajIBkv*Dlvwcuf3cLUL|b&%%PmEM)$6;aTpw7Wt< z#5-tt+_|!a93*dVF2_0+RR6A4pWvPTmJG@RB6+mOPQ(S)Mzv*_vLVS&)(|U#<2J~1 zDk9YQpP=8E7H`wQ-U9OgOQ%p(hZXu1(-Q zMZO6J(kLNe%9_Ea3jUm*5U|DnA1@LCIrD6~Rt3?3UN-023qEYq&>t~52C4-akSm~5 z{Px9KnBZrnL4?ii`+eYf)I4gdG0R-4csgQpQW6qd#6m@9zR zV}T!%IvmQLID=eKn>~eQB6@@Ap^gNHm!s9;L;_GWN0N9}Y#u$Wwa7Z8Xeokz>LUfi zFdxzFtC%$TKHW+C;WE8=Lf{7R2f!ZBaz((ZlrBI#3x0s~I2FMN?GE$?;#5>br#8Jq zYV_Bt$U7$TvoF&;5x0L9N^LUjTF*GApLD%p6fcH7IBv=+%5ig>n!pn5AO3A)ytw?Y zP}`M@o4rz%&L^t?phVhWHubEE-yL-&r90)x&(zBS zE>8ItmjH^Rrm+r8UZf`SN4)dKav&%o7R+TVI}TrNA7F^; z+c(uTwKV8A;TEaB8p+xCY7Jh)yc;^zv%t_o0-YT%!~rTC8m$sv%}Dan7T7rYlM z(TNm0B2d8@!;xS_*M+2OizT<%RM3HxUsf1f(Vee$Z=f@cK9ZMORGjfVCcE?YKmA&1 z1yH#^`rD>z;Qk=y@*kGl{|XgmIL-C)_6`WnA?lI*Y=S&snL1{prSiRAJu;}h|1vB@ z591L+q$5zzccStjUz^v_7UNT2qR~NF6TF{^wVHUjR2Z=-p?kC-7Oc8IKU8$*kD)HE z?2#+{${WLtilb4OfFNimqDGr12aSUN=U*XyG7>|GMb<}jKx3p1J76y3n-)fr|JHN^ zS(ore7~5hW=(h@dFShuTb$A!*ox>1{SkHA=7L@3Gp?c#;BP6@$$9D8DI$Y0CfS80g zl%)L4bt!hAS}wCC82S%*%7ME}Vl+1#2_(3=eIqMX1QlOYGB#;*;s&u~(ePf;E17W zAA}`8c%qTI{W`qt&8|BA$F8uPHIZudB!?@Hywo#N)o(sHe5ndmWRaj)WwXGivl#E+w`Io4q0c$*D+~5JmhIBTbmZ+aNM0)+sW6}xnZ+x% z`q$#>7HowU)xAB5{jR-4U^I;L_2(Wg4lFZCIfsBZ0joSwfiL|DhuPaUTMbGWO4^@en$w-;y z;Z8*b{aPHXkTMKS@jo(@GS;JGW2N)Jd%x;vY>!8%$U!;8U6P$tY|q7_qz>j`ef98C z$9rW~g>v?|nm=z&x%8l5znMK@1hvY$vqt=5V6tJUhX?4dVVxWR^g!H?TEee>_t|r8 zBX~XR51N84Euatc3=)kl)E(5K<%N5fp;YIDRUeUa0>2a&V5B-HoUgV=Na~c(bEf~$ zhQx?wBhPF2U?z8+Z~G(g#D<0&(whIG4d9A#b3a_I9=g(9=x~qAe2)3G^3umwvmd7G zMWB=vH>Su?ePZ(dt@2bVX%m3S!H~pe5|n_8*zGZH;(be$zit|I*$PORJC)^{_nuhna@zRaUn3 z7Vjk;EW5k$4m~IHHw!a;;~yKF9h7{vFFV&P^`uz=aKQhVx$k2k#wu0Dy;9A3cLnVQ zTgt;QOzINq;UndZy9GQgnz8t=^Ro?GbzcC!W5*jyejKDrtn7}jbcr~TSK7o+3bSPRg48QcX%ocRt5&(!9 zE*~s2s|R09Z8QD#${b3xqofW@ew?1kUY6qS34nH*DEbSO`2@&&T4E`R5T~2cdJe@_ zdm|Pn`?V@MM63L`@%jew{`cy_%`YmfCMWwo{OD5y4M}G!W06hpEYRUi%meg_+|qw9(ug|HER_oQgEci>ZyeNedV~~M-G49)@XIK9Q?|#km?d z1V3+E6{1sY2OQk-(tjiMV^s)-K@|0ylCCj~`%>SUH#yM|rBGi~-`&M&$jVv`(KKT^ zSIt;A2E`Q|5^KoWo>E9@`)9+P^06>|m;IDBu5nQN0pl({bz3xA#@D zHO~QZc=n3#$@kWBolg|KbG#d;j5IqvYp)jMa*gC1u7n?*7z(vL=1^c(Q1a)k4&R)z zWGm;LL=C0XZ9_pPyJmMI!~W!(jE~#JA=0~PSR;5jjvIyljNBoRh0k$z^2zmLp9^~O zrP(Vq%4}Y!or%g&Zts*F@!ac|uLi%c(Xsk)frXpQrBGaxTb&LDwa~2NpDMp$mgCAo z2;{+iwjB(*ha!zF0seK4^Wa~hIYS`VY*e_#~{i^`zSy^I0AMV%ESh(pENok- zkb9qDCjQjbrlQBP#Ak#$LZ5GaWM7f+zUIRzKg00SYe&P%se$^t9%>5YubVwcrK5 z<`;koKB7H~uH6NtI-x=rA{32B_x||7&@PPkjqa;0!TcQaJBJ#6OEW&(CfaTqu948K~2TkMKI317LNG8GriWKGdnbU}T&>jN(3^v#-$o&0>@E>2o0TuYG zGy#T6c=DS-;02Ed5Vp?CTtL``ehQi`X)epx$xKNcYGpV<687nEbi&< z5+UMg8|W;wt4$4-nGNm~OF-|(?+f?@R{+5_VKdf_X$OE$30EK*Ji`>*3QwPX$<~h7 zE3K?I3ed8Br*}%`a!reLRBB!kpOiNTWM&h+nuj)Z;Xi<^&4WC&1wT(93^<9Rc%U7FoLrxGaO$TMt7v6?tg<*gMrY9}>3M5S&G7OM%{5mI z8>^|sDP%ZEy`qABUS8KUOgp$z&uHK;V2ZC6Cs4*3 zE?pWbI=+yT+8d8U7cI%^j&6j_^?P7BHX)e9ITU(J%L>3OfumKwHn=s@kOSGD)#T&d~%g7dOh zGB(LnWb6S73#s31E(Sk^NARV{mqwbmwA9vp1f+avZVN`sX$L*hxHXOUfq6u?9kuEuGyq`qg& zYD<5^?|)6`xQQ(uN7pByh69%o7wgiwZnQu(U?-avLCN1)shoz@Dl%_+b#~Mq|NYY@ zAeh@^3h7Q6vPGwRD6;qwXb*rIhnfaDv=KbHku?}Ej?)v2G*U(Td*WiM#}@<&thMyT z6UVDQgf1A~et1)WAZI%X28XY+4^|HK)WnoTdS=1*XIn*-5^ zp%s%Q+2JIYZ|;AOgt;9@HEz+c43GBk2nzcCS)$a<{6s-I+4GJ`?F)()G6*?74oy73$cN_<}P!SKCFqBB3Ai$tMdYj*hFEhEM3+y#4a+yY^Y#OFIU(egv}o$SDCX47`GNjQCEg0{MMuD907fMGH3CGzP*hC zjfi>HjKxpZYiOOt;H;VZ52jgOC$0-~)Zw^UbTU*c(*fAZXE7y5+3ppEi&>)^sUJM$ zQvF3`x=?Ki#R1vkaTg~1H+=GZV?qo}t>1l3=N$OEG3|~?(SO^(PC*|{G=Tn1tR1;^ z5wXWaHDC~q?v%YjYp9u$a~>69qK(+c18J z&GW?i`J8^)m#;5EP%-d-+lu=m+kOKaS_p{^PGmfyt+{4cIoqZ+#^^G&Udzxdec&SX z`-rN=cMmaLQ{Q`E>CS37`>W>6l_*cpDPYUJixcDC920!Z(Hl)HWJv*H`F$`@YF^?V z=2_@c6r5r8d6)2EC92l4>D(o3JnU>0Rx7_NtHUn{x)9_oB)CuUCDN@q-ta<&Ki#f9 zp!Fy=rIYTtDAQ!m3h#}pH>fjzeXnbZE|;n^q*1Zsdr3q6Yw3u+^_3a)st-r2`fIJ5 z*?pWkP+^P$@+DcT-3ak145}n$@O$NfmxHTo9$rP=VGWl83~OCX|E{IRy-Qc|cKKd% zV%-dyqB%4?E;-3H#CM~&LOxo-SJ~Q~Z(HnRm|D@6g7zkwu|w6FvPsu({gIf`s~FnF zg^i$xULyJt4bn3DI+hr{zEhb^h3qZ`#19RDFrXl*t}}Z154mD|8)NU&h*#+SAfS&l zHa&B&%=a1ZEPHtm9M7T4&3y_JMP6hdfyx3sLS*{_qsvSS#wX7eb%smy>ZLCpAGeFy zk`m%A+Wk7xsTL09n(^d;qLvECuQRLr#@%4C&YhL|No&zdVAKrl&f9EDaH2^#y&4V- zTn+5c%GT9iUfA-=EWXQaBgK@qWicTUwx-bhbPd0FxKte~bG0iCDG&ukOJDZ!RZ=w80;;F=t8 z;2F~!W=91y6^_zLiFS#<62la1NZKpuU9K`iS}V&{qt>x@X~SoaXbl9}cz)N^xrN{+y z)AFlJu5z&A6YpYrpX!_F=m3q#>*a1rh{yLKMZjnh0>-5V)Hc}(>KeN;g>(rt+~yH%}w; zgW*GjUSd3uC)FW)rbS^Y<91n01s1Y~yLIH?$-F5d2 zu-0wbM#KB!n{C5s#PAJQ!gTqY-7RMz#Yyp)PoDwj5&UQvp4 z1PrXLhWvl(Vo*y~X!(Gg*L8VS)0YQZ6iAbpOHC)I#bqTv% zm!u6%`&Uw*%Iba1C|%TVx}krwQ2+9T|Lygt2iq(?QY_NXCku(u#NyFXctzfIRuM53 zC{s&p*uDwc3eRPlqTfOpE>mU?-+?@3%({JhDaP=rc)v&nhMrkfH5Xzd(l3^&Ys()Q z8L3LG>R(y;Abs2MrcHQ6M7Zv4PD8_gq&@2EOX!$x*#o#ARI4R<`wF9)@^s{1$eC0+ zpNHOq*MYCPS@W}@naSlol1WhmD=H(p$vJ$KW%@N1B2jhO2nH2kN*|#I0k(eR|*J z&)dC>bl_zQZC)4<2d6qKKuz22KN@9(vuL4xsd=(8-^!YgGq$Y29CZF%k>Ymgl%bK9 z*&ee?t2Pjbz4!k8>~*GvUOf{5A3`rb2aor5AgZ2aS}jF6CDmKE9_;BmGg$B1iXWP{ zi64rwS!5q0m5*z8AZvYru8m>drG0N|CmhGt=*c(! z6A^5Dyck?6HZt_0tuVG+E_Qb9hrz zBX0!AY`h^U!F$S{7pxvqv|=kGcu!|U87$XrZ`LsHGPL58tWgob{aYo~qjEtzBye|8 zP?c(PN=iVpWxiad#T_JIQ^A3Vu~0#Zb{wR2`Cp;TVW%H|XDmX;O@*M4U-qU#lG#Nv zn@Erp?=yao_#?CRxS)@)3>Ki67+23%8=bWSiAyE3!4D`i&!!Y%#tRJU>a?&bd!U0L z?~hl_xH>qKZ65o^5Q+<2b5oi*UpULi{Y! zyqZ9GQ;c^gaN^!eqyL~W=WSujqV`hAwLL_#_Ol%_#n?4cME{?j71hdG)YUWLlA-0s zS=3I$&60`zd^x9|ZtNJG94mNsekBmYy@=b-Ms|_*;GCLAS53BI^JTEhfl4E*^^IXh zlZK0~;}$f@8VYM9sdZ>uRVkQ|@9uxrUEDM=@!}429xX&ymImWB&>XERgL;t_lSDi8ax|fS;>^T@D~`&kImR z?d~_tch~^&9)Zyuyw@*BKn$t&Ym(&bStO%QO{SHnFOfH5>L+t@UEh+F>T_ISE7v-* zw)iHWZQJ`Efr|~@0=96CWQTp5Y&QXzx3fU7ANs_tgl1ld32a|b+(4M=zhnOkFzbJJ delta 60833 zcmbTd2~ZPT)Giv20}28P3J5|JL_{VB24%`oL({+Fv=(p>8xb0()mh330O;suAd|P^D?|I7l4NGY?ZVOa;OWI}tB8(2+tk72 z4qp8bVHM$?E~sFNJqSi3j*zIMGRoL8JE_pfSsK?;v|@3yQ=?W9+Zr+h_(OM$qkV|0 z2nLy6u+S)Wm1shF(`0$#QOH1i0CM7!+1ZK^fc0&M#Nt~r&WzYdVh>eP=0;U#8)ciJ z-Jws2x=?!z^)=u1$U==RW*VtE0cjl{XmfZr9(>{U-Qg`0vs)s`pa=59;Z79YN1_Ui ziS3EU2T6aB#+h}E*)_J|Vmo5wuz9N#eNxsnY-VCYG9YR|<>f&fH6LmkLy33+0P7}# z{r7_NRvx`dWokvwxTu_#@~kT1VkT;;U==~jSVc4xEGUb;2scR`a@RzU_KSa6^Or&L%LMJtvJ87~!~@Gd?Ht!lRAVcw~l= zv|M&H7^%jbnp#Duk~q8#%dzWa>*49NV+O|hdO_+S6A%>%*+e^`TP8CR2yRDv3Y}gp zX0~AB+qO=dt@DxmkD`qiAa~ovk#-b(?(jEVyw9BK3K+t@KT0OSTS);-!z6 zSQKP1k=?P1;I8E-Rf;bG9Y<~PVxLC#qL$=1n4G$3uPBLxY{b4qMn zuj$2C)r+YZ&{KKLh!4!q@J)>PJ@K~TWkhRes}(yFIc=JVy_`dc_ZX3&1*-_9*UFul zDBm{D_osEEQTVNWf=B#*TU6QWCqU5XW#pgApW2h=w$X!=IBn@eNq%%3BD&Q(wCQq{In&BA|)p zPYKbE1C&q;JFHLp2>ozb$1*T)C=TF~##Rvuws=9TE5Dlx;siZF2Rak86}Z00Rh<&m z*M1<-Wtv1h>Q5PTrUdtxCKBtp(+#dKL^pvM3AWb?zW;5&+vt?%`J53+9Kf{Om3xbP7@>lw?M{B`sS;1ff%zbo7FPP~j9f1evjXdb)UN)uk6_t+DrP zk@ggU!lEKUf#t6bRwml+=4aY?a_F%xf+0nRP=DF1O}i(~=8SS%?tSH^+&_tXfcxciFhI2_?F;uzK#APA@u5F*bYFCNQ$I09N~6nU zNFOgzj}SG(D>H&Hety_XbOS!k^P3|#@aAKyanX%dmOenYwi`XuS5R;-bTO>>iJ#NC zbQfV(;z0(pZPaw0p+Pjc19(s+*C|KjmP_6~FaJC7{Q5_K-+TV}S`Heq=C#4SqZaFn zKUb9ELV+t$p|JsX)_GYL1}`4#g8Vo3M6WbseiL~dHMPId>FsvKl!l(i^Z;M^oou?>x2)*g{})V{-v(^_Vu&yfD%+J_Jqbo)36*M^Sjqg%_9Zxo0->YT zA0dE!yZ=>=g3T)n6VskoqnumE`x^PNqs;-jP6F|-7U_zV23*G|%Ep*=z=E9E2x|0f z8!$&_@#H1Gpm2F^(_UAma){4p(f)7tdWpO9^==b$=?d=wKQ9mb*iVrPa{v{VJsy3w ze=*F2@>y7t)Z$+WQu&{kC!RiN)6DQ8HS;rd4C>k%hC>%fmbjMUhH-eCQEx=Z>Yvlp z8=}wp`;Pl@KVAy{Sx%R1x#Va(YIVq$eMh_flSiu^?T62$@rgZW_n#8|+VcMS)w~@w zoF4(PlsO~-Is?#=?qK?Ymq(*C8#UEfs6*aP7gfiEo2E}O#|>Ula8H9px?jF~dk1os z+pqSy);BopG$z^3Sf2TP*XzC@>%-cW_s<)m8+@- z{+HNdrqHt&m11gdB5|iPh883arDNm9oU^k!YrwZUy29>%szSrpkG7Tu6&nA0Z8UTc z4I5XSm5kj;2GPopfz$kFu{j~_%a@-5%UpgDSzB_ssfm$$<^n8cm zl{c0wP->DM8yx*IQ<`8KH#vDHErtIe{~ch>1aATJ9HDOy<|XqUDij#&@f?Zd zab0Db9tZ#eDKYu^35ImA)iyeRgq%v=*X+J!s+gCk2I>&G8+Yl;SoKd5f({ zZAjRFPfs-Xv+J%`N}CzguU`MT-#4$^8Zvf#H)7@KCmToB_ZOX()-b0Y0b6dM zLU;*`T|=Q6D>Q}zNcoamL-g+7?xh%h1zS#tJ^|&0UyUwyW@u%qm>W_q^_VUBUdrxN z&@w^4B3TYa8M)%5HfO->RAcmrT+NGBde>3PSIM zjz(ptwftzOcYS~Gd{##VP$l$wSiRe+`DCWV6fz(!DwXo{(#FLo>K8eg;@1AqB{N8m znY1G^Z!pRPBT5FK&(Cr9DT>9PWlsu|;-8N5LgZ(5)_u%WcNsLkT6h^VuV(3C_~S{6 z^32M^z#aPgUb`G}?)C`r$O)P0_PCXi>r?S`$fsiTNk-X`?lTXu@EvasWt8osN9}uK z>haKL#N|*9?i_dcCpDcXPgD?c_+FjaaZFX(DO+c7PS6M3Z#xUl^=K--U+2@9NDO!~ z`Aze4{*Ri=`JvV_{^jP3O%&{p?^gl~_gs;MdI2h{h)^>n;!zH2YEWzhsJaTzo|m?T zGBgRmH1UCf$VbMq?iwQAY;MYVZ}f?y!aCK7)WV-$Gtc3hd|^&`Upar@L`!N}{rj{~ zJ<%MyiU8snwwr1jlWW{M0r0feyKoC&{zF2#Ac9KhWhI{z2c@XitRh%?df$-2hqRdU zdLl($z#j)J^J)iMJ-mYb-9>4wUSaQF`?cB_U~w4+_F<>oiGSre|2Q7;sZz=RZtkaq z--hgxoy!Kj?mGv*{Bx)5ozzUS89F?rJT^4d#{&B9G3A#c`|WoUwL#@Xk``p-?3t-g zO(yOx^9d>pZY$Qym<;h!6XBwshp1F?ElgZus>S&+>5u%{J<|+x08KLJwWu`*fG3op z{X7;1GETlHQKb+XMbT0!LyJ%*3YNZ*=|Fx9HAR=8mwd7ug9=t-oT=9v292YrfT|Ax z#VQarUN;QuBD1I|iC@(14?INwa*}9yi;W>M3suMLWJ3GU3u>9qNF!wM94b|_V8Lqo z-PIoxg0>-s+MH(A%POK?zwy;aUoEXoDOl*)i)%1 zYQ^~a29?E4ZhR1sv~SS-{CR|F&_vIph&@G_oI{?Wj!nErhDTmIHUUpRUds(NFEGFK z&$%a`a&priUV3q7Y-_($7Q=j+*(PpCjFN1?th~F~mU*R;-R(ovbp~B$*#^G~ zFmIwInvHxD0~S*mHC6T3Oo?`VzaAPgTV$GV-zT944?hn!FTcd2Y& zE7#*;p!#*e!oFrl_|&hcJ|nk2<6*>dsKIFtje>RPultf=*Pmn?Z~WLMd;MbUMO>!9Hnbs z;(Qj-gFU~{sl5v!Ltp44zwx+g?(FaL)Z@u!jnw1W7QbWZcg^oma6iN$!_AZ^l0VMR zpW`+1q&{GjcIVouCnK~m{Rg8*rn6)tpB{WnJaNL?^>F=`=g&7?{S%SvbM9=l%X1(s z&*%I(AJ53=L(iXZTik}KJob)OSr+*`9W8Zf*PLmwcsA-0>^wkmsY?%;aUQ5X??`{{ z86Fyv>yvl~)q`s-QjP~y@y1_bVv2wbxH<=O?B)#PK<$nT7d+1o#P3OYn^lwXCZteOmDYgw@gD=O#9$s=n{TQc_NViEHc#dqV|m_wV@~t>`P|W=%*gzhUkNTf7kU& zkG#Qh1W_rBwZijcRv*logb}@keQEE0#aV<}#~Sz#F*F>XuMe`h0-;`WE>2of@y>j7@p@zI`^`dn4)A5cvat8y zJ9BQZ^g?Y_Md97{v%ZY)tB6!Gh)aCiBirG`ne zcLR}=l=Bc$Pbxp^a_i3Bwn{^H^skZVho24YCVyPPbT_mMOu~VwS>*b+E#*^9Kyrb< zN=)hDSW4TW-NI|r$E^V2kI1$sY!S-pwOBJ@0}pFy%-(AN?-9IhN!76znd1+k@Dj0X|Es(p-OP#N)gZ-$}Cb7&vzU z1UM4a^zIkE0>!iE`Xd*!Fq>^1_)9{$6p4diAu!Z{*57utx-0xSjPOM=&O(Vkb2uu9 z_KDH{f}UBPKSE*B6f+B8bDgiMuum6T5H}4x&BMkT@V(+9dy2O`IW5vu%&T^J)|F;`m>|XUG`DW({t1Awm)f%omfR2d{b#9pl&<% zK1?C`P}1YCR_mk{vr1u`W|z;Py=rS^Qty`GY_;raSJk##Jr%syJ0HAs){CU)Js22H z^184l?_u22KQ`*tV0@$vZ+`SHs9zxC=uLF-`3xSmy+M2et@Qoexk>Wsw^t&}v1H~g9QrCk8!GB5(dw717fhhshv{ZJ3HdP#*H;nei`;Oh+FbcI zl|>FeX$$s)%N4`4@vfm|x8tt3IlMAN7E*UZWbixc4Gc>e|W;0tftipE$7~Z$ota0n=L#d7Ox-J8#b3_AW8ezvJTm zIw)^GKXn)NbA(KOEfB3P*@=P!X2I58+6+o=xs`HI(v-oCec$|)cyovzJpbj|Vc*`^ zz$;k%;m+A{lPAEw^PDKak)#hrPgA!OSTUhzJAXQXjGtYWB?irP{gNxwNO_22QbSxv zv{6o2_)avB9OL(Y65jHKxOZyWTq~U|KJ9%!`{w&3F0tTur?gI@Ezq`-DZo>>t{Ja7 zcXO7z1R$dPlzoTK^xfhnHBT|uNqmQ+GEaT{=oD&l@lD7t>qiGay5jMNtzU;*&`uuv z<0m20&`Gc3&7p_a>fhE5W|Z$R8jYsGkqWRk3!|pL@8!503 zvgo+9gb2h|%ldOA@?drrWAEI`FBY(#N2u;rxg#7!?}KC&GgSKs;+m*weL&ShI?_jF*>eQ!8|TOgccwWif$uk*LHcY|L=Y zQmFir})w6A)Y;{#E}Hn5Td(C=J>c0)pq8f#4u`F zLxS426{l`Z$=HSLH)Em4jAR=ZVV>snum$rz5?IT;tekn*GS^&vm( z*?f63JUy!* z7zfZ+5gDZ2Q1vTo7q z@Y~!Z+e?TMskV(Qo2B}^1xV^rGBXT4)+;KNQWq>*zx*%{RhUkmR~MfmUV{R~C%l6j z{yl-h3zg@`P#w$^&6>(<1x%0{HQsFLlG96ABi#^$dI?BW9J)|jBv>$=jjU(R8wybA zNF|fV>ctdbvpI6TL}Ns@8&c}^qth7!X13TViamF_vqYT^jNYKuP|d3|BTm0eKSOV$ zH_`5tHl zuCLGKClv{smoSii3sGaV?aZXyfXtLpEk10(*7oYIuK0*EnUY%dP@ZMW^9bdUF|O_B z+fbp;d#g>0aN)$z^))JQ7-h)$`|xP*74c64+I&b+ytWs#58X8NL8!{ZT_n^lPi}GNrUkCT=bepT#Qlf#m zf0$t3*Xh3#ng)%!$Qx*=IG!p)MK++R)(Q?2vQIUyV z>{Ll^mKMqS)?vNqk(n2GmXB#p~#q`5?W@n)ivv=9J- z?t}Pg?O(|%ixiKFmbF>KCWX!r-ffPYPO3Q;U1!YR+eo z`l(-eqHL&Z+Ux^q+6^SXT16z6=tBeicKn%!5y^H?fu&a1^@RyO*)#!Amc5sZij~OP*2BJkAg0xhT=CZ#}z7uqg`6d4Hr;uj5L2a#dpf zhWbyXC$lv1%IMh-jEiTV&kj8_5(Me*hi+JRIligg!6|o%@>+`U4;RMBoC`96`Snqf zLFOL-e;H`xNOw_1FfZ_`56+%TH(F#1P>`|u0%sbdI49cy3^S+FRuS~*IOF9|3yQwb zvf8RkT%>J+ZE8&Xt{*oiIybQJ>Bpc`l*;UuUDwwC+7*bZ#Et|w?0Glm=Gwkp$KU625-xoizDf5h+uj-zGJK)# zVcEtv9t$v00gM5^opgb*%TW9(qWlGC$qti*0*{#`%B&zG@ho5g#}idnxbF$$g=C{-4FCtExy;X+qyuo*?}KnY>@1+nnP<+=tRnX4 z@eQOY{ySF@Ly;EHomGU~X30s=DFx1$IEdW5mz7l{UQoTjOdiHQJjJ%%H@J%#%ZmGZ zxRrMb-BRC~bmY-4!lz?$e?RfweeuiRd+Kb1f0NGtJy0bm*m^n7_{6ok z8x}`6dFC&c_w&`1Ds=zZTk-XsyT%){!pN$jXVRxZ!<7B!&!f73T;e8Tc0g3KbKxF^ ze2MnHt5`>4laLSF?^Dvt-Jbwe`~Mj(&1Td0KMeMKF0Hw_{8FXV$2|5;9i8`k%^XT3 zKMXA8gp5$Nq^0)z39#g)1CzqrCW#gJ8L)J=g2~CIW>MrVxUpakyCX}t|pecjGad~^7co1+z4Iq!=_MOD}PvP|O*mbcEtjYb6DVi|e6 zcsN@Q0`T4nhEXN(2R>VDhfYVWxbih+c}Blsz#R|JsuvEkFf^|W6I(lhwh;>jZ|gyr z6vpBH+O}htSAd9+r0+w=f|p|teh%gjFZDG9-_1%CW$Mn(xyO4CTJ-Mt?zxEG>MGUt z>LOq=k`5<4b2qQ<&ogEpF89pW-I{pnwV;^5oEWCKdlVbH8J;{hJDgP)9}+ox99crJ z%1%Pv2Zu5@yK6>9oE9YdXgt4}c+qXzU)Su{`S5L(n+AZcfq$?r?H4EBt2_+xtag8d zdE2+}a}{AY3-6Laz?cOD>o1=F6qo>~M3cHP$nG-km~YrSnNJUlyUHQc#u9Cn919`_Iyrg7Uu$|d zTj*c#0FrjNs`@|8{YNEZUsqF?l_zb%C1d~jhrxaE-ERl;z1iMq8e1Sd)ERE--Md+P zyH9v!!rAVtA@8go4rbcg>hEKjp06IJZ?>}@`7CdNdMdx4lE@jqabxlJ9Sn}v*z)5S z{)cQp-nE`I%&R9&jH};1Opmx9!gNcR_S{k>N3c7Wu>aUtHS1=EV19mN`bevJVLKdw zGcQ*j8L4!yL7MMpZQpHV@lO7)#8WQs_EP2lx*cp01IOvxJRCi){BMqQBOoVOl&DUN zPNZY{nN#`X#)Cphem&6=euu{;`=y2I{1mXIPpux=2`hB^RuNmZxiKj4G=nP%31?rj~ zpQ84ll2Mwur!^G-D4sQUM5rf0VHD|KMV$tx{4UP2IG&bzZmmBt$;cPHZe#*V*;WoD z^BX1G4vWYjkIhV!Z3dZaCIX6L?2vWc9SYJ>052p5@Tm$xlo}kl?tLjGKG zt1E*#`>t5M$US&)JK!Wa^lJeI%+7nIl>pc;W5FP3)9{*~sE)o5s-nmJ%#Z~=(Xh03 z6>)>No;2WZ14W4~Bp%Wdi2@%5hrJVx^UM5p6dNW`ou>LU2=Seo%O81~BxBy(%EtoP z+M%3DEdtHXe$=KqFHPlnX?sKuS#?=isqYH-i~qde{A(vVr6B)N^MGV)*~i??2Uuslg;{l}{OrwolkHMj_Q%&^W7(i;&mMIo=!xXQ zRM`VTi5%o4R?>CboaTA4cuM;4$s@HB#u@#++n#Iu{mE%fvMcyiAL@7@?U-EO4i zYz+B5G;a7-_~9*8_1>$I?xE78?lU#d-eQ2dKK0|B|8TA zaoukW4a9!SU%zF9KRxx}MCwkDCp|mEpPk6uvi`)0Guu7Rtv`R}k9!D&yig03Xk7|0 z>I%+|c8=x`(cV8W-*EQtz4v}!iHteco`ZG77F`Q$8`?H`F;&`4o4Qe?mEU)?E1+%_ z@oc!~+^cS#p;_5v&CTKcCq0Ww4I9^6r{}#7ZHzUorGsC0y**UeEIWMg4YNMvi^Z*P z9U~XLQmLEwYSv))=dfMMZf4Au%XyZCT>{>7G6y`+>(mdLs~_kJS6JX}7CwDxKdRJP z_P|>U_q^`Y&O=EWyEOCD#J^7-azB*z@LJ)+YY)rzjKCk|JND9oyDDhG6y>3EjrWH# zrgwD1f`x|x``(y%cYEYK3{<0q!#^0PpdF5!K)MYKUR;_x*Wmq+?Ni&j*SkIFYh8iE zuMJPEZ*XE>RezA@aOyMd*^?)E`_CD6=V?ZM8;qkF4kiQ-rG++>ZQR%8*D#S!X&4Xt z5*akW9!%V6xBuL}A-Cgsnm5bcH#P1p+j#O|+O6EM-V5WQ4Iexlx0gQi`kXDHpC5|EHFL|FLO*xRdL8;oUJ1s-Nmh zw>>7lN&2X>YZZ|QBlPtf;l5L_o%Xv&!)Ox`ZjfrlTw%yeE=mr)M?S5?v4!_yMq#H4eB;DB`12Y~92`qzTe)@-%wk zm$3O0$M$SZNK1J`)l=fuA-bPkBrFO#-ezE$1VXm~wXVm16Ax11=qw2-2RX3S8sLXA zl#T^}U)@Ke7E@7lQA2~s66E?E|I7E)ecjYGtc)DzJ^9$%`kx;3+Gf4mlkxs-ch?r-G2{`mtP4lvpDh*b7l)F5QuXT$Rb?)3} zjWO?|<~5CVt{eF;2B@~@ZZ7GiR&N}tN&zzWhqSxgY&16TK6dV*USQB0HzSjU?W%%b zU5iO%giMnFYizsCb_B@~Q1FzZj$1?*$%wNj?*?sLKVQo?XjcP0>8r;GEJyWdt{-T# z<1c9To#9Aask55cWC^Mw*hgbeccnt>4NU|!`+zm%&9y8wZ1Jd zCL9cy`Wd2btqf0JFh>2Gl~tkL*Hq%MXWt4QR~sohI0_3gX?7>4-Jz(;OE}az*~U39 zhHX34CCqlk-)mbhq{DIex0BOuP&7=Gq1G`r;jAWY7;v-cuCh{Fcra^O)*F)fX!)SK zs3cnxekSrX_$vwCM;8wDI`-SzJq~I(6Wn5%T>6cBLydbow`|5bicU{@RB_SQckH6K zZwC&y?u_G3T$%HKX`3Opz5nHJ;J;A#+!D^~h=Kw0A^6(=mAHX(H~*z_f-B%_B|w5i zm9Mdw;4G`7>gue4JqaQu6tAibcIY^$@ z=cAM%)mJ6R|D1;Ss^q%ZG!tAqwILH%g)7W2gAch-^hwwP%<)Q%l06tO8J1o-wmQM| zlKJgMA-0RE=G!|(UGEy8n4KZPPU-z0o3{D?-L@Gr_xwqJ0D%NgGoihhbo^POSZKr_b!@~ zx&uFnw{JHH0vl8PPhj0QL)p?gz=moP@!LZ-RxisUo@+)<5$#r7DMa6Xj*H8*x{Do0 zXwh4p1a5m*KBlK@71=cT*!(Ma^fn^<@ar^GzMl0Z(mmN*9reLBB&g2MN_{fkfvp&a z&YrT&x6B8}K71IbJlyi%njC-54#tM!*Bv|-x@Ak}bI)~2Yj$oW0r_9sfMb~K`nSod zC*xk@6u9r} zgo-62+}udbZjVXabS zy?iG&n?0%1Z>#q>h_nr?NVYG70$7t8150oj29E8oGh|HjTg&EdNDtglR2FnsC$pj> zv@+P*KDW}>_adBvN~E{vCFZrMHN0?K=h5AoJL=?^E2%fnp=|>EF+!%#2&@|O75qw} z*^EU_;Qxd$(^8z%@a2uz7bE6W`4A2_c3$@c;cY|XO$XbnCnC)>K4vt_{k|&Av!M72 z@DkPDDe?kN7%x-Ola`X!5d($PSBlC4a>hK-SLh_#IYQbgK?&(!lX+fkb;ArbLhe*x zV}?bn`ssEc`$makyYRAbL#4ds--Yph?=$~IazeL5MdAapF(i0~nZ*O0(I3R3RM2dG zf)Atu4UG%i`I&1ShnL`T4k&4eFULZyV^>*an$$4iC7t@0s{)P(QliY@5*0RY%QX#tQ;B;EEvFwMYvM@q) zQrgH2L~WLhl<0%WailepOOO~G;`wfF2l^g*vFq)FHw`mSf^HjgdvTI^Y_?>MpPrpRO!aY~s1i}33iMjtu4Z2_f=1E{hZ66#|B}f!j5l^DT zFz+g;XHJ!&qzc;$#JK-%z%G6`+=Z-{OORO_q<{%Wn>wmTI6@u5rn-9C4v#B?Ek0jU3Jwwxrk22&WRDs?=26|o)8^RC|k z3x6(Bi`&rf`6(!quZ%zoRsCVC=>c@O*DO(vO0J+%%%`XN#tzcSo4?sB4n&&Vn(MND zt0!s|t9-MjG*F)%D{D`b%F0bRiNuoyEl~*vgCjzKwm#M(WK4}G>B-(ARpEe`;w#!C zZDwqf!Khe?d0iV2Q3e@%C8xoHc`5cO@f@g>S`o}$V8nx?%JQUv5|d##wJOm5W5o}D z{H5@GWx~?Y8|E;jyr8@#m}3-*zqMu=_@9SUCeu;PE&Wp!@X{9>lXyC&(r30_e5oez zK|%BxTJv9d9&{YNBM44SF>E2MD0Yycb?Jk10JbVv4HFE9>?b77LZ4ax-L&>JKV3aO zy6%PZ`sImK1?DHr8hEmmID)Jy&{yoxZOvn&GglE?h~ZOIg?B<5XEMuB0E^P)+y*WWSJWSLm|gdOJ488P z&1a;J`Gk`Xq%ACR8Z=Cl3ag^b!{K1_X!Yprh_YM;Koa zjrO1Xi8fE&7WDp26)(_v+x z7K^kF>f&c}eLJ|6!XE(l7fWr0mmP`RGIybe%~T~C2_0O8=FxZUs{kVREN;{~ zaD=(+hbd(2g$<>UXfOzSuL`6*To~Z5364^xl~YNFA&gK<;M9rKxj1`}3!(XroOoNS zQmF9+sJNnSxj=N7rfz|7enUjp>ThR4?z-{fiDm-iA9LIUz)Lh~Ii#1eb`)-w%tYFo zkp|#=LM7WQ1)v$c0<=l*$VihL-zDn8GQL3;QHx5jh{UAoY;Fow=qzO3f5O?db#4{0 z+15M!1}wRY71*hs;Y7wzl|n>!2^=%J+u?IR7&qab?;@H*sbIWp(|xhI#0H{HVbtN^ z<`ur8WnivlbRE2bXmSdId)lIng0)N{TGlA0~li+4k?c-4!| z+dQjo$wg-_E&efQZ-z%+{77KEGX}!UmDgShs)x99XGdV*xOx2BFaO<5Ni57UAz8Am zSKwb%Ci|DEOhS_2Bxf5NAT6+()i9}JzhCIogG?js zdf75a)XlfB}4UWIoC9zXs>`36yY@qjYW;SFHNQ6F-r z3l_?R^~Zz-ud2~w*lyAx$U*Ev)D)_Go797H!SQKcoCQUT?FGn1HiF;FtdiTpYYEIt zLR7o}!q$A_KD9Q;SfXk|Ufx#Lb`&XhhIa_cmdXDVdq_5bjR`W8j0@)*TrsJuh$R?rN)Vi_@xhZS@Xlf<@F#nSpVF zNx~yR;U+<3{*Hj#S*OPQcI4eZ+`qy$lXT;qwZnW!7~dlXPs3; zt%Kj^Eo^*aF(+WD)83{b>W#(HEdEnkOJi|Bo+?~Htl}iw^jd5~JOO5RkrOfXa`8)j zDNNHHBJ z7n6-7xcZFNEcktdiW!~b%X$KVPh6! z56;pOXk2Nij-tQ?;FvTEvmMY}*WLFo1&U4=M(KXoPLlq};fC{1(kr1cH$n1EhYkrbNerr^cPJKLWi|Pi<43J}F#a zc|&QFv0CR^gjhCJj*xz)5&X!tFQ}U3DjsVezF}H1Oux=REKzd_Uey2-bcdY_rU848 zs0tQzF||=)b|_IC4yc zu70k^V(ovrHO5~I^@ze%?QVXNv;&ooz6Z(%OZLER2g*8D5o>|q#hpY=5H2-egaKVW z=`e9OG%}3@l921=*x07FhF*GZKp zq6QWv3Xf+eHHIv-Mw>?QQAYtv-xyQ2DO$Wq_Ak5<*2wmg`Y`K0L$TA84 z_W4eu(iSK*JD+{K8AF2pHoQ>1lc94i-v|iO%fif4X+AZVecU$q+Lx-&+llu&ijC)h zmj@v;K8`$w?Yv-rU}%{f&-qm-Du3+n3;pbdbrspFO~X-&*S~h&<`k6Ja_H#oV<8s` zhc&a3DQ@e(#79-wC6PsEl)L*NQ?FNMDiabPX%;aSOc&^LSm-SzSfHzFYqAQ!nj>lD za;)y_?-pn^7}LKxQAo~rRJ!#H0CiVxRa?SGzC-bDr z1fvdy8Wc6PxJhCUS|(RQ0UiG9z|q91ML7uPoZuVmuLClZ%v=3b|Lk8Hzj-Q-?L2rR z)YzE6E`_o%eY&`rdO*ko<|jZW!G#B)gM;u_yq++OEIuM}1kJjb@dlTK>S=f?yn+n) z74bC$Y={2=>&}*$5s70>(27}#MUhicS2TD2ZcSlg*Y|q0Qj+IPY~Nkr4zO4%Ghg$Q zoW=Y^ERuEn1ZGgl)i5CD*5Q?BNn84Dx3pX@6`;~cdZV9!5qqU?IvUNc$~!MY)$Gw* zj;KyWb$_waQ(IL&Y&IRW$5s)WdNS!+HkoT|QMJr_%O+;s>f|jnasU($UvKM0pW2t;(-$t3OvS+3k@66J9`u(nR&OhIC{y2Xf z*X5e)nv0ovKl8lr=e}R}>-D;qG~7`eKR~Z%8DDcoh9wA|bUgcQ9gR=RFf1cq?$bAb z_8FCH*zi#qgww2^wfLe8*qwC@v97xe?(DGG*G~!LM|D(Q%G`?QZk`^#+T#%Qss>sO zBdzjQ#3F58SL+1~6F40h!fD}i+bwj5X$41OR0;OSlJ`4T9-xbT z5BxXv5vVc3o~nO*e3Vt z%Oa8wZ7??1Zq9Rgy2jMq9bUDhX=sfN^mXQuvf16XUe$ezxuArID*~_(C6)M!n- zl+^(>IDbd3r+sw*P;SMWKT^}=b7Tkd2wrjR(k6uuenNkju>Gk@M~|F*plx=s!2iP2 zGx?!YS6)s#AWq74Wbb*odl`C%_s<0f=1mmhyx?b>O~qPoUlaQRnVYZD^U0>FH_UZ( zFL`JpZf7XU+1qc~)4Jbo1{%X;A$cxeW#9N*#;)e@r8u?ajO@{2b33=FgS9c8Fg?YYrY2FVmYR{X` zjTiZcJogXWovM{t0<|ACQ(2)FVSV+N(lVvqNg`1kLx*JMVgiBz@ZC)&NzjVM)apZC zkQgvpS+le>Q{&D!ls|^S6yV@TtmL4%1?}FN7M|0|?4ZE4ZPSOmK=<)FFM7EvGVeyq zx@YgZR+nx+ga0;&tip)2OrCb)iePQQr1;??O2$9uwu`AjR!Fg=XZg@2#yHwi@#L}! zrplr?*g(hak(c{yu5MQ@GR#S`V-bSEWuLt)eo5nT@c{mNO3j2*2RPy4?XiMqf28Q? z9Hb;+<)`1*QB$>!LuRq%OP_<36BKHE98G1irSV6czS z!7;_ji=RHc{AN_0pM8<{F+j@_sVNbsD`{@Z2o@Qr?5!TKHvk|`E_pJWDxz)L- ztkpHcbxz%odZ(E{S@EpkW@P8v5KQH8ywD!hZkOS`Pl#g@Bc4N>10&0pcRHTjK~@(X z8@SR>(BvRh%SQB#1zFzMXZV2jt(T0`sU;Tq>>k9lYXik(xxqg1`ETsm@7KwTknh`Jk36}AI*WHh*~ zo2hG4+j0d&jp|_vh8wLqYq~gJJmu0*{H5vh`RGYZ90|zJQNDmY%yT45;aAgSi_#*p8ew~D^uaKKjZp4h(p@|2=^8SwFAZ`y%c8_Nfl4Bd>3uOQNvw+ z*qr4I9{_lQsyG|vm&xejTFnLXtUCJ$cJNan3NL$--_wrSj5l8_2w|5b8W=O>C-7Lw z=2QIi1hQ!W(W1{#-vy)Sw-Q7OE5Sqadc^^z|5@y;8mcijVJ(c>a_c)G+n(`B0qHMK z!#`7v_#faLE~kiA2@evC;ev4Cb-Z6PHV%EHdP@m37) zEMn|6oo=xP-XF~_*KYON(mU@iXc52oo?~ue**m|lMtJ@0+xzaN@9wWM{`Pg?%NJ|o z|N1|&kPS6im-TfZ!jkZk=r~y7YQYV7h`(BJ8+J75G|Zr?^40-WdoJ6|WH>Sa9_Z}B z2^{47>+5qz8p0^(i|W~J>KRorl24rI-5&)LpT28+xEv<2wU7nrDY^MComnKmOxOBb zj6;&o4N!YyIZ`5XfRmX~h=R$!LKAoVFF`g84GB+8L)B97xbS4BN*vfa`F1tDM7n#^ z?vJycy|tS5U57^MahaVd=xvgBU1r3v>LY9OHk{l zZkr;>Qn0t{r7!Wkviax%dL2rBU+C?O(E3XRH-EOFT+3_OB%SMaI|knSo&EPMB>j~< z--8qxgEnucVC~;ei|H1S<1iZudR!d5*LVH^+h4Vulo8q!Q)s|jpku~DS{VNwjq=3M z4~htUeP)K}1iKtP!L=Xmp-1mcr;tl1!+GehbwmJm#Kwu_Ucq_OMxz${p_UzBPomUqO*h-iF?X=9zuuU5svlLOrHx&4-)f}< z(SnLU3~=3A1j7KidMcSubB3=J6I5t$*0)a++HYaEXZR8qeqAmrnCacgn3CbPX93(s>8KtWB61D?BE=`C>YA?`e%^Lt+j|k9TUS_J1?7Vh6QJG44lRbx<>@_Ywx+Hs0A9s$Y+aZO@L4jIxlgN!<$_8cW z07%j32*eCZfv6}#fOX_bx-m5tC9F(Yv~AfJf;%s9&WFVuYqS-=s-dl)?v;}0z3cCQ zQaKtUZwBPLX3;%#vFq_Z$#}V?X1=5s#B>*$9~47UM6n()HRh=5_@Y*(I++$kx=Yl9 zrG?t~s1|i<0Y_sYgQR3(f%jT&!N{@T=)k}bnj6SZAeWIqiZ91@s?Hs6LZ46{7M@Sb;K}2nkJqiy4X!&9(5z&f-TzP3&O{Z62m2Y0)i|ymrcB$H0K+ zr7$7ZTx-GMEeT!dpa`e@x-f(bs=zI!+qw@fd7?SX7bu0(qTF_fcZLS<`XiNLp(5H1 z>vNc+ooqnUuV!6jZZ@!x$L|)5V@y$ZzQeD|rvX+GzdPw3G+X&u8&CG=51qHYC_J~k zszQIq{-pB<_e+nFsuSr=?rg-|FP;Yba8qeJd6pzA*+?*e!^^R~$E-Kim*RDrSC9#{ znqF#}&J+4Jzs}|TGzoLL_VCc2opdac-i>_{sFFQP#OSQ;XD+F@HgffAND8IMw@BgvwdJtP`l?x#TUY zRH4<)k^_>DP}Rb`67+P2R--aE&O>l3Ua|9!b))E!xgDrj8p1*c14q)&=V{~%H8=h0 zn9u~?UirsnQ==jl^vibECw%wYo^vfcS&e{|Xl4Rn2w)P=qlk1SoXlJW{k}_n>-Pka zNMnxz6vmFUVpTt94vy~v9)QN7hw7;R>G_B1!h{qlIO>0Vy`ul|+5eY!`G0;B=>OBZ z6j*E}zQ-W7O!7aC2kLGvY+)AQEx&u-cH)!CG)K9?d(5je8`K5R5(cv9sv#uWxHY~li{#cA2 zBg&Mc@871BTzH`#^0*-T^Ye-PLUW=fTjU(@FwOpS*41F8=aVi?gi^zDblI1zY@6Df zS+9;7Wq;fIp;6yPJt((iN|5aR0^RQGueNJ@(&1IxHs;*=^i{Vkz%&1v^;YXT=t!T7 zc#G>(`vOxVwoUqx3&r-jTc!s9!KP$=>6y)O+NvD~(0e-e?y54kx%ldQv3^ADThHO#(ttcqdRNJeNzQ;2F&yOkZKr@qB54JD z32`9phadfs`fnHL(ZnXvSgEJ(pm5;%h@GnnR5<9gtPD4b%ofCjvr@OtD*c7oSx}22 zYN|z|1+gRe)qkW41ONW#O^B8J+7dB}WKWz}`|L@T7F1d#l@1k306#ulxkyop3ELK;t|FAuN0h~?m9@ww+}hbbtIoZ^Mr2>mcQ zZMS}0pt0uR6^8Y;#_D$oc+aAHmlm`C!|SvV6<{2zX9EB&5s9Is^{`5_ms&4DjYZoq zbvW3cp^{*x!;Ur>IR!+lHGvjiTx2!%&h#tpyRkTL`bp_hdAa`61mpF0Tpf;QeYQeD zj;FUsIi7};Fv_&ROn6T?Kxi!mb?^sXs$dFE6v`8nfj{64L>g2{YevQ}*U@|(5;3X( zv%qs%nmKoaIml#M&FxC=eE6A%{)NWWkupUG-hN?pVSY*U3ynaTh{Y(eQ=5e7n|Jx( zjjjCOg}aY<>^eG7V)`rHy5mqeWMSjqk!_l_T=L_^lm4ihf*!*opKkpZyUOWMH~(hK zW&evs_Ahok*Zs7)AVO&B7+hpi>p&#V1ms(fKYIQH3aD{qmCV(H>@cIT36|rrA^)C) zh95NkkIs{l|KI`+@~)}#i>Ev?U`!1J{kUOIWBZJRMIUk<@E)GKTs>qAnQ!{u^Rc%! zwaM~qWg~51ZXV~mvRVRwSe}C<>5o(=Nwk{)woJD%p+|JeO9oU*0u2!PylKCa0G|L( z)zX6c?BYO^=0?{ase;K_PXb^WoFsn4RGZBEvI|fx%$mt&!#IqV$hgSM?&VaZYda(b zV>|eG$nkB)5hy4Oxv87%KT_|791Oagax5xetQ@7$nCc@m8ZcYaL0mOVW4(daU+E`L z4p8Mq!71Nm{l6nn@uB$%r&82*-L9*8GrX{X`|&1Ue_p@bV0WJH>5PeK0i)-qF-^4f zl~4-~KU+uYU~ZuKj|Kh6GpWlu&VyR>n|U75Pyh9l1@}ej1oGm26d>Hz*ZcV-KfC6? z-#70kbMq0`Bi+NcIoA!<(r#XO@QMwfjDc6CA*Bw83$^Hr53oZ;HpS@R^AEOO**Vj3 zJ9c0X-!i6J#J?%9%QqvM52Q`%9x=Oiv*z`uY@5ZKwZTeL=N;RI>3!v150s9cJYTX) zxA!GiS_s7oQ4+9n)wy%UEMcY;xb0V4C=u540_T4ZfsVIGmj~JaidV`4I(F4dMn+Ul zys66d7?OOtHx2~^{Pbdq^Y)ZW`o6Yr#ZH{y(b?VgZB15OecD}$o^*RTrp45O9_Y$B zhgN=EczBSA^g~aSb39dAT&X+VgG)W|-dk<>o0`h8k;GK}0e?Z>i}IHk%YQsPd$j*Z zp-5SGZ|=#ueX|hyHV(Cbs-RN2aqCUACRMU0#al)lM7#f^{ho-{2aBsBE(I+6B%$+yRo_GrMOf-6AcJ_}FAJET8o6vh#1Gv4J(w_d2o<9mo16&Gq;UbRV z20zzfwB1rgiGKW2Usa*n(5`b1@NU<6p9;x1^jBZZ(1AJ{&J?g|DPB6fj;HL*^ujIu z6Z-^}}Fgt`@ zR{%x5@~`(&sD|HhG!V-8PjUgAJr%onlL_-T<_sqveS0GS{yYmJZ=7h0yF?~gxakY@ z1n=Ehc#P*D+ET<)deDi8W+NCW9ngA7@9h;2ZF%&RL|Ocds);qR#RjdB@8-5Y*0l>c zh(}+-(=VJ5dH9T z7SdsVYkwJUNw+^fGQjx3#m`%@eNPYnzE&{k;q`j?92s2hUjo3Z*}ox`oPpsv0FeSw zrO!;SdHAQ{`ktqEUfdP4sSt z*f?~M?BzE1N6Hp;1HsTZDb7Oq;27G1M|=&p0z($2r6&ocNbDkbxX&pE)2nQdlESi z)QV$BSqsDPndj5c9=2=@tmjf%*O?9O zSXzG%ybo;n_}N#I79`L9*gnsa`4*ukZ0QO&6+KQ`p!qnAsRaVn7bv}WpKaa=%}hTP zv2h7h8M*z+^$r~V6~n@1N9dB5RJ1&Z5n19YN|Z26LdR^Bn24_RE`n?m8lYJ64cR91 zvMik3bYwUNf*nj1E^<@1} zHhO%d;KI91fg9MPwSbp{^6C0_*kZN#wP-Dm33!h@tZhBy?0%YW+}%_^CltDkH~%yW zb|}NZlP%1R1Zw~uEG)1|C*Lf?F14h>z+@?;@)86zB6;H6PfL$F2 zLp3$%%PSWf$cbUc3Un^GyC?GHC_?SV+U%2_42I_uDGzju!PH3Grz4p=-)pYT=T5T< zciHs{pa-)(4Bf!J+UJi9873bhw%@^JB6-uX`f?>GXZ2I@8vnPpFX`8@FXmdfDN~X!_31Bl?;Yo8!oBM|Il3DUsTOS+t-7 z+!bKR2ao{ym-nXktn7V5g6$qbzbN9UXS8*aeE_JqO_dex8xkFC=xoKMRZbUfmyAap zVfUGB4I-o~Ye>@qPZ;CWr=aQY&%=2=KAOez6fdlq%CdZGadf3M(LBr>Q5WC#IF?qP zUVQiQQ?pY%{9|Joeu9pCOo7Kf{^q#S3kiodB-3rYK0U~`IT)}>A?}-4(=n^!rormy z1A^)k!Qrd2bc44-hL|lV)--A?)4F%x527rw8>1| z;2Ch6xQqAV9iQe%9o|0Z-CrKKc$BiYWXxmCYewZKKA}JQ;JDooEu3~0#~>XS*V24w zahRIP1d3i69%&ChEt*yQ3|o0LRShl>%*n7*J9_!9F2VK1iPB5!pA6STL0e#NH!ZD^ zot1s$uqLVLyozG>g4~QrE_&1BRZHesEz+l4lzt-S<@sG)!@H8bgw3!%Pmj%{14+&# zcU?R`y!}2?gof{N$cYwPfFC$7*+Q%H)oIO1y0!Ai1A{%5TBwlZ{YFSf>H!0f5Cd6AbP_KMYO#T)k|lH!`~U^2jFruP|3CjcP}vvnPS7(b zP&wB)WQ>VLRr*l#ebqliS!4@sL^lVG_muyayfxF?H(I!RTHy3$523Z*HTXDEZqL0f zZ6dhLZl9KlVp`ePm+bvZmBt?4-MefNK&bw>vf+E~uA^?Ao?{;0J2+FU{dfv-`-dyM zOCDzo8sj3qzhu80B0G0%fJ*j8nL2$-ANrEr(}ew>X!YdR7OKR)NM^g|x&`Mx`cy+l z;%jSmj|N_+EvA*;fkcQr1ATp7et|LVk%4vhqOo!df}oP(*}TK$#mt#P6@G49EqN2X z(9Bp)rpR)@V1q0dSWl45-(6n;wLoZym3f;naB|@aV*Zbm`MbNE(6MOY5&wJOq?7$e zRb%bWgYWmB=`Xp7I+PP!=$gmfKf2F+V~5fK!bHalZCUkDjQ$3W()ZHtihzq>**^m2 z3MvRh2hKX%0`E5wL>0Mwr_zk?D@`8uGDbIlexqM(uLww$ckC=o-+Lq~uTcl;3RyNt z*+Z_d_zEx=ssHm=kJl(5fsM9-*n_M=bmEdRS{9nber6qc4);pZtMV_CI6z$|zDGS$ z-wKGRs2b%bZ#0fAY{rkYE`!@HP#=hFE>VWjlIj-^%a$HchHwju5w%S?_n}(k7j<3V z^%qm)&z^j)Nrq(pjbqLIAggr*19>kVh=8lDUly2#U1hsG)@^n9{`aqTUC#rL7h|if zOIyaC59QebYA<4}h?NVlSuA^@*)WFsPrunNP@g3xvUrnmizllBMjX*rMkC?5D;3qH z=HJW9XY)RlghiFjGQO8a{AIg#iv=Z6u<;NySY@;#oicCikSy5-2S>3M*6R5&%qQN7 zOW5{BFA6oC+WZ1T#pgXe#-B%qb-bEi zYVj}pC!wo-f$M42M%~5NDqZ)eVk%FQTD7tZEivwH+e z4Bg^R+x&Spub_#VyYcWypKSW^i7QKHNbxE*ikBq|aHLMu;C|%d>bszN*@py2PJU!! z9KrB4x(PH{6BkqS{r7tvepBahuh6nn{p_O)@5eR6I~Fvqn}qoTp-sAMYuy?8$$|2k zDa{<~c#312@1yhEa~##51>I2Ds}5PoG`{a^%OBO8(L3_(UFZSFPD{gPx|+3!^C?rE ziVm{&6#uUI6Bn&Z+lA%r4;)Y5F1+)w%RrG_yN_GvOn* zwerokOJQra9<2KJeT%1>+lj3eiM-_&s#f}dJx`KDHaJ!N;mWoC_a@3xarGIh@M!v1 zOO?FJlh=P~8DC*IdW8L)qbVj8rM9td;?rET6iY1SF|vu}=ycQcqpjICH36UGvs?r8 z1HP1Z8{km#55D0kUP#Txfs?kVPtJh@XdgQ{%9*+8+ZOfQ+7NTzVQa$b%N8BpUM7I%VP=_*8MFVFKwCC33lf9-)cY0uM17aiR*Oxa!rN44G7FM;#vc@|ITcEkIISM>Zt zyH9yeo74+TjyVi)}HN+JIUAXPZX#dUFDw1);)lG z)RC@x@#@!pdwZi-{i#{jIy%Y>Ym;mDe~N$xw8}JmqB&7O#(1ImDZP+?QEBZ3=l{ zkYL=v!p6}{oAaVsaDK!px563E-MIP9Qcra6Y?1o=qbjwkS?Z<~ONM8T5qQ9|WMY3I zLQGzQ647DH^O`JVeBpLLqC_V5&k(nHTAqe|Ipwzy3fMyR#8auRnXUE6fZ^>}KyCUW zGuftoLnW_*^dg`x@^*D88uA)@+9vq|AS#1w;WbGIRMRu}?zMgm#A}eq;h8O_O7oxA z0AecHC@PgC1^;_Z$&H}T#R7-=l(Cd-+jN87+wPnuZUWj2$uYP~B7+sW2GHuI+q!k! zsv5xtx&oZm-lV!?hqJ77z3MFRP}I&3ig3v>ameKD^P zSXW$cloXdXOQa-SOt6c68j&e^zReDab*N2q7RI7LI9_;$U|%z^gp&_=1Lt!M+pQOc znVN7LIjJ_?TZk0;FBTj=LO?x%eDLn4Ypd!jdyUKuJ{?#qMYIG-G0rT^a1KKz0vv|t z+you7Y8)y#jRLnodQK6rP#e6Hrp*c>z+dDW}XoZcW z0dM%0((ar0&y6%3F6OUuKs?N|%78vG&(^=G!&Nbwr9We8ATZ#?UGNUp;Vz5~2$Fc_ zv^FRfrMM`RGwjroZ5TGQVo%jJn(Mg_m|4GgJzFS0Y=lsl4jIKZ805ZUOiVF86-2Ea zdSIy8dgtRrdx`(B=^4_M=hL^}070Q=c11zSrSWYkj87dO*VNV2)~6Ezd!xQS<;c|& zt!Gk-?z#;YohffBS2vEpbfxtN%k12{RFrZ6LEv@d~mLD)ty%vuS>bwIx#KmH}~6J(mcFf zH}e+v=vJpZxc^`Pn-}QzDd_YTN6$oj7OxuVwh9J4uC*eb;BGn80(ixKO}1{mi_z|m zyo^e~r?J>V8(i$t6EZhqmr+|Kn)nNo9=xTYL4}@YvnpE3d{i>Q*rMdchrlR>is%Die{PFuR@*?vF=DRB^N&=PP@ICAOCd67D{ex=Ebo**5F&}FEPi3J8&3ylLTn;IjwkQ#Ao6iM++}l0#U~tKD>A zxMO9&iEo~nOx-k#79>T)>YU61j=x3~GGy+82%QDdPW91#9hhzZa zU1Ty+o0&X&+-NC>nF>OUfC&GM@XF#MqO?2S*9ATbq!B0J`ImrUP(|*$DbFUA+GTkxT-FEML-Cr-0D6#Ef0h zNz@P1!^sA?Quo8BdF*F{6cki6lXD2>&@r`0ImsX-*;Wa2h3lb~4ZvPecK`=Wea#`k z5?JihgcCJdT9xmHwEGAB=39dOE-o)JS>}<-S?x`9DB~x=cV+tbQ+5F3|Wb} zBassA62AgcfRlJ_2XTSq$n1($0#QwbNfr7!@?7dco5Lg}Y}VG!^5TF|X$#xA_6^T9 z<=OBLf~QtImfh`ss;L*)EkA-Po=x}6(xgy+qy#`b>1>^KNP}d#{GWJ@^R(f)(BIVU z1YJ0nm)n+G`qa}J8~n0`g-ezw0S-(;cJv#MsfM@-WQyGNPiHGaf0^CdOa9h6!a}qG zY~LF-s{Xg9CQb2XgDV2%cI>|t6CoNlVUbcPnlIgE0cekcd~vBzjY9`B34^GiX~DYg zyR%w`OP^vc;j7(x!(Q&lJek=pKg|%igunP@A1nOl3F2esC?t{j00{eo{M`9N|I3J9 ziMSPjPiaVHks=O^`arEAn!_5+D<$Aqi!;T=xO(yH(}=t9Ah2TMi0Yyv{2O@-Nwp*t z3tC7ac>3^Bmb_0{fNNN&_9g*4Sh++Ro0Q1h6)F-3X$p%yainz;z1hf;bTdbGcSr|D zj>CsqQE5zBFpsUMrBE&ElIS#OJKVK61V07rycWr3c#K`H`h{*TDCc#0@K0CyXXGsg z>Lh-zAG$6&&pVUJL1>8pjVU$`Lb39RYFTX-isEXjDX|aYIbu>V(h|*CqB{Rf3~e)L zkl{cN*b2DtFCgIlQgxq+5mjPd@)>FDgqBcVKSq9$0nLlW;jqlJxPWD>Ot8c&9w?y0E7fG#U2U9JYJAjtJ zL9Y9Cz+sh~n~*VZ^^@b1+fh8op1c`f+PVUDVq`~&Js4gva(=b&qR5%Vs*ky0X20B^uVy~5EbPnSj$<@Lyp-4+lshpTsO7+q zFgt~Qhyk!Dt6mD`DK>I}&P9h?Ny0nCvdu71J1GeJ3qhTL!mSGCfY(T&8 z*lr$#xKj%_4|sqZwAmB1pZhT~Q#hp4sWZs2Ou>@)A%rc4%cWbGK&y=0OxV~6yp0cl z(HTG(pMqQ^*&#Zd*v7E?PGbjR+Nofw0|@M^@QpUSh2%wj3!!VTnU%r6q2@OIo#!`W z^3#ugBOMZ!$!;O29u+|`BsXHfLO>K?i1p`zhfn8qP+uQ=D>kf zi^fWaq$Nrslaa3}(HbX)B|6{&7{XSD)?+hUvta*9=J;o9!|8Nr{-;OnkJu|OE%E1M zwq0Gd;>t6W$dH6`l0G2b2qndlHV_T5>Yb?+_ac0K8)l<{G1#XVb+ffBW`-7$w}lv< zwnPJs6b>?zs0Cwz#;}ID$vxR{p~7MdKC}H~KO{J^ z3iK`xQxBYGFQ}fRBCGmDmgL!njDHQH$ccqV`Y1@@QLySAs7iA3oXGi^q~Agx27H;d z?&7Cl=vx1Bv*eI1Q-iPt%(X&UgN8i8l9y4HCkx}e`Y5)$$(yoEEWM#J>(>sYEg?Qy zh2O5;KaUti$UrR~w96!onHBxScq(v%b?v3t@txRKAT5>^+0?^(`R&9_a6X6Gk>3rR zPmp(w3{(3FM;#K;8KuD$ez}Eee7VmS+NOrFW?llXO?=|3XZRN@BUZU1kiP>%eZh8+ z;w>~J_7D&A3TV(gmxCOmb4)rH?t1;hC&du1aA@n8{uWY0iY~f+5dWa1D+E7xiT^2M**h1)jVuktOr1aB>|_ zuDZ)19mQlq2%pjEeDL7$O2U!;@AuDKlKZb2`5GYC^UiG2c(~v!yg}%Ucd~g4@dPA( zezQ81v}7pj`To}z*remIs|wi4cUe)5$=hn9O37>R3upMqxF0yV+Iq(KzKO3VWIk$R zZvACd?Es9RIe>!IZyxzNBGLe-el)mtDs0J_E(=;LSLAfI;~3RktGh<|;}L<^D`6bp zTkry=b2FuEa(?MjT%ZPKd|1Juwz_S(2;cISZ6P$-l`j4v$tjc~G>QUaM7EQWNzm65 zh0rL;2-x;-bYt-yL|I#{{zzTj2#RE9JeQ5o5FH#bob0vG6YZh&Q&4;oAd(J*o)3FP z-X~Jyd$;7^LSB`$l2gbp+yY$rQ^Cv`bVU(3s5zkBUX0b+2S}jZ-p+hvq7iuu-m)F3 zB-ui^B)Rt2i?rn?RT^#-EQ&#P~(sDUQ!}mvg@C#7|zzgJhVryZg$E_<?Bx?Q;vYR zaukrJ04F(vNp?>X;ZR9|&k|FE0aBH-S*@mMon#3+)-Noqap_sCct0PpzJf;bpj|@~sAq zAKegn^4I;5@((92q7J(UJ%hX;$u5cAlsF1j=?Bbeqka9wHnTBCl%b(+*jxP z(ghTR2L|_C(ZbjlU+Rnd=DPmn(9Q3Ul_EdadTc-W!=pNEyM0;KMVc;eIKk0$)Z@%y zivRZ`Hx93J^VH2QI$2;n+-!wFpZ{K9oZNP6IFy~xn7i)_I<&Og*a{MBSZo$~0in+? zc1bMp06~+VlgS0FfkIRtcLdO^n>JaayDn7ugHB;g6!v9ct)|YU{xA(}w?>w%fmsKi`!6J97KTn*GZD%ti0xIU=R z7Z3!aRLr{^2>Ym}XWb~ihmA-UIRzI@y|G=FuJx{b#$|-6lhcY*s86Kq$g9FTonFj@ zuguHf zQQqWke5E(Pn?^cIV=+*p^gY%O1Taw)%1ML!Cn*Z?O{`y67OvA;A zn@&5{-gh~9&D#2(bqU;A6aWxf)F59?J`lfr5T`&#d=@CDHS}I z?}Ea8cYPM>v(nUpu0=S=EF3ERY{xrF4eZ1RZNqzz5^lP^uwKG<&EnI-%vPskuBd%@ z{gZsbS=a1b@d?F z+DFH>9(fn%0E$O(BHlQ+bu)e7Qf_KUE>wkbN7aWqtZbadzz0A=!yWpHLPGwAF#v=! zY#}8vkw6Z~Jjd&yqvDCGRB%Lw;UCpvN9Xj--ae`9uZiC8F@qj{R~Dc+HnjqLAjUlc z)IU{2S6*DA>koZ)tp6UKiehE|6^X}^7tb0S!k)RN_LZghsFS(v>O?ZcPByaBaN%Q; z_EGfNv*z|1`Qr|oZ5SEvUR^?~g?h@m#+{8m%vB|{H# z{NZyTu^_Gt6;^)#U0#YFjcJadQu^tRSyK~m&}8S$g6=#lsMnaM7W98EG$JJ zu@WOV3(Ucl=43Yaq(e%SRpGcYSVq`f_z&#H6T0$$WNpp+_GB=0HDA|31&w#_&7E# z`HApMEH^Wer~_I7>~uRRr+v3qIugU9d@Yn0Myp%pAFTPxB7y)SfcTCVUp1dZ5<`ql~xm>LWO@aSHyo zO(zoxw(RZ;ogTf$Vil*lj9+%cMuDEb=L%=-heDgq^!rtmg~@6>nm3p)&WMV5o;;MP z$m`@{S~2M;-Wxicd3wzZ6*3Iv z@sZ=0{xj8AwpLlc`20nju<(%@^L=77;(YFtEvt}OuSvIEGvxzN8&Lt6F&(bm0-c%LuwL6TQ<|tiI01K+PN^@qA%K8sLf+0D6drPBC=O1+ZJI%`SkKpeQETwP zC>2{^u5V}<_=8*n2Q}cbh)?yapFKJHk9K`5>IV4^$T28LwnL(1t@tr55FrB;7876s z5fYRivQt^&XR1({OXT&x0}cHJ%9X3OD%bH(-O-f^Po)JR6D8Wb3G&lv+8O|dg;58~ zi9I(MxpO8$7e7WM3Yc$FhQe_1%INE)px0^rp3E=f=+-BcfirjBh^3#sI{=@~Z06oP zm|wj0x}suSn6}bhr%QQCen($^DArl)`sj2`ao6>sAJE$nvn?U}>i2gQU%2S~@N)1& zHRrU8-)xRhj0uNcsan7MFyQ=d@LGRXrk?*Xau*^IP{t3JlBb!<#Djk7rSOPd_1iZ< z_igKrUozYzQtu@PYB)4TVIO`!oVVQWpfFtlj86EJ9k!l2_V3>D5O=R*Hj)(Zi5$cb z3b8w98R8r+h!Dt~>|firP#%s!*HWiXdf3Jv4Lxf0USnCa;x_vh@x?QmMKc`Xz9F?M zSn1I3t9yOk{-%#$Lv;|H8$u<3mtqC@_X5J|t4XgH!}6RV2&lk;hNA zTI{Og`zFo8W|5m)>#l_FDE|FW8 zO&B$|>%&9FQw=YHrnufG;ywZrbSJpYkqfO0=@3Z2`M&JV9=UIDqe96baCZW}|MX(Op4Gpt;dfyC+Z@43oF$5`_*?Pu zPG*j;?nG81+qytVt_@olE8(o8mB9-F4190bJO8VF0)#+JuF z|JA7#i;5}d*p@<8;(I7C){R!Hau)(jw>Z)plt}59Knb)x_DlL{DwHeFMaG~I?_{4z zjo>@@I-<87md3xyAAL+W+g<8T-CMr=}sHe|F9_#N9!ub|Fi%XUt${a=!+- z`r|1lapB3T-v{NlHXc4I({X2CpO+iY{lc&@E>YchqN#LZmhn2kLT}(lSo-OGMbtq> zYd)0FRE+MqoflRdAM+`2-xIgB1=+>aZx+rJ>o`qZIswpV6TLuuZ9}RD2&hP2_+7#w zGQP7tZ|T>=xf%yKythr`@X{AAe)BH<&@ToZGe6nQyRO8)msWkUDKAChfnvpxYL@4B zaghvPK`!{>0@9t@<^O6L=;j&{85$(qgSTvBd?%N6f;^w)n?ckAg~A$|Txbaph0V`B z<8{*0O$0&1`k{7em+J=>Ns8`WI}NwgEhARI`3qRw^;}va^9?4A3g&bTS1ckkX~6Ir z8P9yP&!Uy8G z4VB9C(KlAD44ftcb}W#?9m6+rdqj#Qf~W?#C>#prcd|ON$iyyE%|`S@Nq8AP2a!&y zMkXzxVhT+g`S!)ozU2|>HoiGCHc%889TBDXWdfl{j|i@EPfSPY&{&mF9j*h4qwyR8 zYM|GSk%1_7963W4LZs+KC$18|py5=F>_S{(=_~d0g>h{zEtcjZr*VSs67L5^KR!2dPYSvi>SXr*KcZjg&$@`h>)(Egni}gDK7Gk2 z29Ax_KjzRtZUt-8=JWX^PLF6yrl5|GX~#f{*cH;;A1Sbu`*_SY1j9kFDG@zl>`y@z z<5vp~0BJM$q?T^I6ul=*&kx1Z>OC0}HAFlZS02|F7+5rH^s>D6(axrH7r{-$Oh$@s z)91<)*bt*-Tkkc8f7u$(Qsj3%cI@ccHSpmUIZ%E4$)Q7^wU6JGwJBG*-9Kqp$0<66ZMA7WO6p|u=(XxpQ0aHTpO=_@A>17l(b8GVX|a{JR2H= z*dro^Oo3Jn?*=&0^hHX1It$qv?c0H_tB-i140rK+I3qDeVp~pI;h~11AHFy>fC+|Y z`tq-nICd&dZ-1w{`Az3g#9gOLQ_?bn$OcgVt;o$5HjsFu8TLBk0JeiDdYb z>6vXLbx9X$gTx$P-Ab$8UC$k>Ju{3GxfT<4QZmu~#I3XHh0nUfB7%8&+-BV@<-8C2 zyCZhqL;#`!>jBWf>GN|1p&*q5CQ=j1eDHE>B%KmD@I*ebAGrbL8;D`i+T>i>KcGr5 zJ^Zi2~B zvuHDk{Z|%nS0WEyI1hw+XLc!SoyY_Z1iL9nTq4qBkz_B~MTKCW!XcLM6`|SabRHo* zvS3J19N9bGMhz1bLs1bgy*^!QpfMDX7KRlxr6{C(z zsZEapm~M}HH#_};VQijGl8|z4ZSe;--;^ty@=Xiv;gOTcBd##10_Jv*Zj2ZN z22q?MuxlI0MWQw0JPTDx_XtYUK%#!4;)Kb(qVPC83kh=JjIbupTAzGQc$=M0E5jsd zvM>8dtWeJ~%23*`wd<_YLB_}WgBw17I(a90_5Zey0v1wusFMUj+HG+TLBAN!6+D2y z@rqbFv0-0`NEtt>F5JXrZWNjGB&8f|!LbWN^CDEq%*5Wonl6o|tI>K^L$#_kQ#w)5 zyL~m|v)M^>?4gn@f+kqV6k;=}MklR|s!5O$*8(DeLn?D~n9*Bce1HTV05n;OC)eEN z*x8*86!27CGAF7#Bu2hE4^$69 zn?$`y-_iQy!+^978hWMqj!XR+4S|^M5<9SQwNwKB%LHR4G@DG$2_L z!EG5l&Vf#a*E=Lu$?`}4xGC==C3IOUW;Upxx+xlC7LYoG_;)R0Z}HJ8qyiSZIG=Hc zly+dW=FV_KWQ_f2?D&^hAxI2rm@Oj6_IN#d`lOCo_vGr#=*2(t_pe`e>e}`@OMkzf zf|`5m5Zo#jvunQO26PSeT#Fo1HTfBw85rQdCF-wdrfyrdb%v^@r9U4Xd(F}OrSSeD zTp+v3Ktmtm@s{1U8Zld+muGkEz^oHJy`W{@s_zn=y+`ZOx1!`wMWgjC-7#CCT>O@v zpC7H#>Q;Z;fBufhW9N%UM@fa}t6g^W3QAL|tlalheAw<7Fc9!O=*OhxB-A+xLsBVd zJfQ}r+}Ed{Jtoy~6&u2@=~aNF1coz}o&9S`P?AG?^N?kty0^%z%rCVF3bmP-^m|vM z60KOYW}x+adgV>09j&`HN{mlYJK|o&_{;7v+CrWgD2!Tqpnx1kTy>w60Kh{kDnk2` zdy^oL=-g7|E>i5ECk1UBs%UB-T6-&z7!WDo;am^3sE2 z1*2PE7UGo}o9Tb^%=h$v3o>MV(AjpoZsy53N8ek5{qPg(e!ogGrAcT->sTDiG(?daOv+G<Y&P zD?mOrht0k4SPu$pnv0PTD6gR=dZ#}pi&KxvhIlyOo=%$Yrme-qT^MBOYn=r>?6lCw zvoS%%Tbb~fkWe{e?UZieI**xKWTwTnp-(o1F_;9^xSK>+1n_TJ7t?gKUPe#;-!}B0x*cWbG-MPc7WaNpB_a@CLwB zYTJ!_QhPWo>$}^w*RD@n^#K<;+*fUFpshg+Zu*hn}A z@^zeKkH8iMM$Dq0xq!n{Lf*t>8b}?Gxci^k4+}OU_Pu`EARM$DZ~{l>%}x!rdWBU^ z%Xhy4yhxnZzPsUa)o4~j3*|J?hg!_*h;io4K zp#4(yj|l~1wO}izTHzJ=qJwZ~uP|3}u1y54?WtM(I`b#wouYU0K^lA&m3HjxG32_w z0baNGFrsUGr7gFs8cdtIdYHkc#2SXHiJixhR>pAbq~qw6#ADbrYEw&HdtFP4xf#av zi*V|&d2Q64oc+Qt8*lImA#LX^7aYAeqSYZ*AM;OW(FT=-M^4!PQt0^%D9i18{u$f>5y&4B)kr zDoJ-pdz^;9&+62+1`BYg&$^s624+1H!%~ZgpIV1k{d^&`WTU^zA(@%>Yl;$RhkThK zP!?WOx)nBNP_N^cQ!rA8t1|*#8d$~vkTfJHnCk;X7pmVop4k6X7%;z8li>eA*C_#6NzquOnyK0~&< zK#8^}gTLdDw|ijk-(gF(|J(OqEo+!|M4^W+y{ot?q`$JXs(xF5DkPjFf~LS_>nq9&iS_1b{CH-WJGSk}oUCXZo;>{Uf&Ekbkxkh5vy$S1Fih+sl>mYM_o| zG;#b0bdHIVzlF5P#+9GZjZR%O4Uz$IC8f*H{mQ*b`O6&2bG91N-vQ5pvnc~{!CsBI z&jcq$45=A!^3XSjl1LIK0{UEvw{c6q3gPVI{d60f(=Cw8|Rj4YU$vrRq`J_~EU1UF?%B4-@UZ*0Y5_Voo3FIQj5 zw$aOPt}nIBeCBQ;+9^Jv>3;G>cyCT+$1ytrA>xK0?B^f#@9G-;H}vg%5$adIy5@q9 zC%|}RDJM>Js@=c6e@FRqZ!?0P@8lNfxBc#<0FM~2;LHWXE1|1?Cpca7Bs1>)-cG7M z8G1U#LvHagX*Xu9M2P$B(XW>CtDR$bh(#=;9=4Ocz7l3$&MhLMIK9|%LJYBLDlrk& zMMZXWk2c*$qBy*<&alyj#63=3^q283N3Dh+$0||F=9j8;4d{btrk$2 z=Zoc;c!sKjX6vzo%a5^^?P*9DD^eHiLDMy zI4&~P>b9&U92tmBbeZpe5*%Ggy7bAvWpJaG(8T{xWR$H#&HnuLA%zeF@Oq9nHJ)rg zv|)+ou4?V>cgL(el~iv&hAj41IlHTiZ~hGM*>fzGV;iQu`o(kCd{>?^65_2|s}nt@ zb388mzGF;J@YB!E$18CJ*MfZ8FFW&$gj+n#i=E5Y_vI6Q-j}tJ9V9_B_!Zy%Q4`9% zUY5QIFEXvm6{XosBq%3db@_ruQf13vA{T4OZQUX`6gv$##@ z?wj!Hc2vsph}6w{^tI!-7d`E+pXD^w~{cpge0|2OD+a zQ`&*njd>acDNA=FfTgmEDm7!K1?ht%Xywl(%Ms8Gf@S?Att$vz)|5=1zEy|!6k60I z-Gtrv^ywIR3n)(Z(yG8oTGa%2RDI^0YRh+iE7F##Pl#8DpetB?05gOEht`dxQeFZ0 z2Z$?^=Sj8}Y0nM8cz@Ukn8Tmc?J|Hii{_;!^i?xKN>2gCcNOC86|G=2w(#c>$5`1O zxtiOlDHRW2N#xwI*UUta`Q_kp^!)XEm0CCNeE>h3Rc+n=)Yze6@a8FYIA9jI-wxpI zt8!U;^!9P?;Oz~i+p9VlhLwt2_gU#|-Pir(xskSXL}~(vO6SSOq5$TSc1TzLn)9eY zs@^0(^-K~vu%^f{UjNk}L29yMI%OBBUK}lQ%o7zHgK6nx9Bk54`00APDOnGGzxRiA zST7Kv1(}5fWpc-|$QSRJ(=J8}++2?i{Zhc=cqZUewE490UaL}@+!*+ICy)@ezAX&cjR!c|#G zM3dcyW8L-zA|B5!up0^|ds4zLHLty**IV=7Ul&_SX@8Kf=6>dXY~5$O+(pT+98AU7ZYkXjRy8uVUyPq!8kXsQv5?*ClZ zc}V0snBo5kwzaHHUF1m5*g9!u^q%N(EYU67K6vlJQ1Vtc$3`O^WB2nQ3)YA2G~p8! zk+q&(B#l|Y(>F$Gxu+g_c2#(F#R)fmIMu`>-nxqZn&^I1eS`%v!lanKnzPkMH&8o?OUbc_o*+w`@6<`mDAX{33}L6NSj8vSQBCD; zrlYSrmEW3K>RZb@7uoZ!U;^mBc@TpO*4RXo!}$SGza%r=WPJa zZN30?nbE;oxh#tb*DL-~_!mtD8dv(-X=WYN)sJj7687?H&4*Y9YO;JR4v7K0p>9H@ z!&(|(nM2}0SsfWyCSBFiGO9bI3J7L!FaI?dSqBZC>)0#a?O@w@x*%s%QiceDBLm>_ ztf-OwjaBR|nok3!1GMpPd=FuhXoqTMt*$^o?A<>P0pfQ5p^*^1oQbZW^>8_}2TE_= z@x1Zmy_^@4Es6A7KPrVkCA;2I#%Yi7LdZsf2})O+6mXh%t0q%5Gi^|%-Vkh?&0>z={?|%SHp1Dci}l$Q}79iIIB1 z3)yu2u6V6)@#*<0 z`;zlRg)#3x-L83BY5d}a*p4o?*&;p-?jdlWbvQ9kUrZm8s!Kc(BCk@aF~QBh-RhS` z=-xF!UMj1(>GC#<{t@T{`k^%WuBVJNwTW&)a9rGa|NBuL2y<=(T<<_2 z+}gAw5IAHiJr|`30BJLgEq(Me=b*%hybgZ-ShAh+y1A{qo;*5sA(uq#VX9kH2@Cgu z+qr9$-In>>l;zbbfVhHUZ9#k|1~dcpG~siJ`Lthtsi+s?jaG^(#a7LXfndOFod;bx zk(#{7>6l*=(RAL|@mruP7sX!L$7Np3~;5uPZi2miQVt}DCAJmYa0 zSMQN*TLAxfMo-2nAb}zAYl1w)^@t72??NU-57@TM@<)1{o_|}+v0J@G(a`;Xe&gMT z-w%XA-18s-RDDdYGD_6e0+@GdKlK@SwwDiK^|jOFY8)ie;WuMv&CxoDjNC?wh~520 zVbUbjgvz7Ly{tiqh`&tH0aran{*nf};MgX-uf36=l{4(^L0v(sv~Qe+J45mX;-km} zu)PR0J#@0jdG&CO{4jC6fL|c}!vJ^sShp9k6@NCmV$Ad_7P|eb?)ET`G$+oDJv&&{#UtqG3KSjeJ%ob>f5er)O4D-7Foih zv+KoY5Q)T+^z4szePkNW>;*&ZIOV6OzGdH>+6|AE-t#3i&i=@U0Q+z;W%6ND<&l5# zr+z7TG?r|x>q%CikjWQh)wl?=7;z71a^@Hk)3X#MQB)gT#8YI^uc1}%jt&JJZnX>t zNvQ4CgROeuaaG|ZI|gbzB>^B-%Dg^2cx%It9KWLKq}YvFrZx5GZs6Yh^q3%*m)5y@ z%MD+{ta-BgXXrDxy0n^nV8@FWE_IJKUD{=7Owb7X@oDqmMNSGJr~SI;O1fba%;G|6=un<0E&M4@T_r+ae0_7=gIe)-Ep! zeZWV#>UZkMi=k~LY+25We^)u?MYdjCf8(Z_#-ptVH?CVvFJ?vnnF8$Dzl>}Lh|66n z%Xl0pWn=1MkKN{vHdHka-e_x%cxs9paSyE-5kDKZwfxdaGpu~Qwf?k|loz@`u9H1rs}A;jRc*Z+^Z8KAgicJ-3^_;c>o`3hf z69wWSI+eX{mHWRYV@BlTuL*urzygBW*4clK3Jl@kWswl{zO~ORLis7Jvn{ zaq-10tDYbfv|v_{O!(T#Ww2WrJZpUzmW|$%@6Y~eIeibHVs4hg376ZGrf;BVJdl*U zRU%F}9R|5|oD`;du#AQy5XU|EA5%n-_?+ynS7*Oq8CNpW+)#(4a50*s2u=Xp&B?^B zm!5!=V~~WN5;eSP_=V=O{6({o*`V?1AJ##4mhd2k_=aR9sJYefnODG8IR1CL`g zA2l)0Hxf>B(SQ$q=8=f+c|{NCRb5Am_S@9sVu7N_h> zN;rySR6kFwB_9$6R%8(Q7&XR=>D@u>&#M-X(CYB@%v8A@2ra^;HDK6b{50rF`z~on z!_zTz7ZCGoAX~K{t~~uyqo4elPv2}BA}c5I=Qq5Y-aUP3dGmz=$f9IxyKde>c~9Am z@$$j(XG??)|7EoGd&C9Z#z?jCa_xDkE#N3fG4#a(9M2Uv@sqs<_2l3~;#eZGEgGLQLh(RtDfWOFs;2tLYFB&ez@&59Y zRm*joUs8hIn|WYe=qTMoEG? z-hik-bLbTQ3NQ|S^F4tIX?$ifaA{<_Qc`~6?iYcO^BY?axPUJ%=Le#WjGn&2&{IKo zSyPkA#?Zs?{H9&L5o5sBdSOJWt^T?BTs~(2bGh9BQRMj~f2S=0To2I(>1Sf} zRp|;|v37@CeSpcZGwGCbiX$-W?jV{L<^RvKf<@ zVB!bAG%zzmjOpo8XalYZu<_PPS0i{?T7prw)D5;eo(k#vg`3@XAlzq<6Q+Js0u=pW zdKxj-*c?o{jo}7Wkf_nFrCU$mhLgYXZ{`@a-Snx!q> zx9|B@uH}Vp2n{fN^z^moSbgU0)3bv6UME5{{ixfvrPY6Ac}JCnH#6vtb-H_CTSm{R!>g^O4#L}n4nQ-yIEm5>?zJwmW3fjfKGohj_FdVg)=3;a9QDu=SmSwl zH06K!!F5=8*B^bK)ZfvZ*z9cA-)VE}eZHh8Xzk++kPoxx9fVYNj=tiZ8EuHv{=&Ij zaG@}b)uJa+u1=WHo0zC>F_~~KecI5{@YMBU?U&l9O<}+QgRkuzTxdl4kTrUEJnsq? zvkH3d56auej$rF94^6xBjQKU-15>=2kCtJ!*?E9ugTKum|5Es~&Hi`3I~{aRo57>U zn#9OgSwRwm8A$6BJlWJ)Y$HA?3jEPELDf;-3n!ydwU!?G9)kU?$D6OVC6UhK);d*T z8=LNrW>qNPJzu-}FX*qRKeK115`3@h3SgP4rP!S8-E9%2*`idL%rvG+%N_$#kcwO&x9sCt0z}vEQ>HDX!{g}K3oepT0+hxCYi(^c$*XJeCT_fB z*O1x!M?_Up1Yg2xYC?}+N&$QfVc2(L1oVf?4Hyk@rO>}7oTeYkyyo{uyQM6D>lluk zy^eft1T>mX2f+#*U<5`@8)j}uZ3Y{s#h%kZT=ZSy54u{4q3B~l&D3m=1qeQl!mfU6 z+1;4MGjms61X%V8hU_jm9M+bvo)?Auf!GK0L9KdKR*CtJ8b^sQ!k>~%S5^rE!Qv@g zX4juw_5{9AGFEsgkW|o#T>@5}PrZwO#Nd5_J>_Z#ao>cVm*so(S#r26r+qCs7I=hn zM9aGU&d~27pTr&rluuJ{Uxm~^W7i{IesJ4DZyK=`&Bw2DjSgMb3&EdygEW}Atf_sl zTNm!FeB+Q=!~2qbABRkhnnsaI$!@6`@*M1v=RsoML?H3F2tQZP_b@>EczbUdJhm`U zYY?S%p_d1dZH8^V=t!*NXtVt39mN0m=$v%Z#R~#Cq&iU?e|*^V%~aoVF&EwcNvg)- z2W3h2fvUl=HB@3siWhs!ssNw{G7}zwHd`GucTP#n2-;G_nN$BT?3d3V3h z*?;cO8)R=ZvhBxQHE7$iL`mX}Bewe0q)Z?!7tle9fJe5}j;}(QJv#DUq}@YH*X`}b zs1y9m+di-^-kZ6Ep~e-6Fjwj4I^Q8aUPBEDwOBk3a=+@Lfc$VB6vpC^eMT&{S;p=0 zvtSGRV>-5FPmFDW)wVGYS)+xkYfN;Ead?!`u0ti~zScXN7L}d%&7cFw&fk9qlu$GT z@FLC8b_8 z=&+XZc|VQDUhr`A5D`NV-a*Zp!UDkyNbMPrgp$yFDhoG0dr0=rMuZ9z#H9evOX$T~ zBCdC52T7$86Of{WMF)KL>&;wH3F~q%90Toe%M*W}VWE)zWwRte^(D4gmd6Z1k2i@; zk@y<&Zdox!kB#g(Ao59HfIM_b^T&sQPZGib535>h=3Q5 z5%J7NADYsHvAj*^l*bv*?+uKOJl;2a+qcf_*{e5Tj3ixJ$kga&0}4EBgsg+s`i`&li}YfRH*+)ZbXvwW@s&}&Ay$(~5u17}TWqf)j#J!7yz3CIn!~uhA zt0f`wXEZdJ+tRb}D_d=%z8(NE5OMQ@QnQxUk;lnvo{C8+`1;2%+qpXpJ=)v+#B zzCGw*BDpT;sn6f{Mf2lS`RZATnfzaa-LfhGHe;UEA!qOtDE>O6SX9dLxs*9GwWdvE zdt&tYJ|wSUh4+eHJgHaS795;CTtt*J)iFR`|tvedimUvRkhMtNXzdm|ll0 zg2xGxstc1!gWJ`r@`HQ`-v;7jgYbc@6n+fPCAT zu`q;WsR?WR=yJlOPIY^~q;yX=M-_uKdR;6vIJ7+6`b6HtqVnlWku_S@7m6xRcIemU zrKIH5MEgU&=zrzZt z9Bsxe3PBjd56glG^ZIWIR(`j$nw^QU#U=;dNKKE_xrqEp6!yErA*nl=C)+*?qhpVpZxG!)g~frXJ2)a@y(4k65|Ybx!g!Pn3ml&N#|vb&&N zph*osqHj7=&mjO0Uf$+_2AA~Lc;d(nb&Z{|48__ z+zOcJ+s0UhM+~gT$m&4(>hVl>EUk6x1Ej*nVU*r#QyRgZs;&xW+jY<7Yc(|uz3X23 z;zU81T)6_`Y0E$x73Pt(xc_VWCONPMIQmQBtry>e<)7}}H_i|e1V2*RHAqSJ*Zwdz zZNzSa6}za~pZ!Klwq4VAb#7~6G-H%Ca8Nk_4L|^2pZG2er2u_`- zsb;6{Q{dQ4?Zq#bUc4uDg3Y>Lz1;QhnC@wVZEq}o#+mKE>2!a*rZLCbusrQ0)L1$9 zSY#w_LPjL2NW=^t6^^g_@eD_`ju(cDDiX3hL-_M(vNK|KZiw=lsr)@~sfn>p?P>TQ zB&n9!#Y9Iemd~yG2a84^R=&4SKYhxhQUS_|1Udk;@CHby0%@#VnsfsOlNBuc2N&|Q zUC$Q@Ifi6vOEpczs|uc3Ls<+JpTltIkE{@+b`MZ}b+a4ODrT*xZt*f}V^1EW&wvNw z!Azr{*W|nD#mI$sN7;S9jj4Y_h~V%c*Uoj7WdphJ{5T}$iYk-7zXk0z z=Q6a|)XmIl<9D$y!fZA1lXgRSdcv~%j*Pnq?kw)`W{5bwFtqYS{vICGGli}Vhvdw+}+{&5C zBkifKCbdq^!{_J?#U4i=KULthTZ8lRv4RXN``@noA-0C;LLMCo$16+iL}5Lg_22bf zyRAmCs38lQ);sC0Bz}G_%sM$p+4$V9_F+}^JFYHTg}U|IhI#NwUBvqQx3vQqGrsF7%{qOy2q11GtCCsNeK+0g35 zBWir6fS{q&8xIh4H`Yp245mfWEm|~QmduMEp=j|D99J27_N7Dha!a{3kL5CZ4#}4Uh)N<5q$Vy}Eg?JOm!8(hxYThqi`+ zN%ymf&;^4?!0BvX2K%Jj;mrj2`(95Dcjwus$PcP3nkkf#%>vMDoSQ^ms4;5si4CdE^B8)7P zBQGgS)CX6?Koz+KOL$S${5}$6y~TXm-bK6e8nJioyYR1pGne*O*@>z519~kAU1z+T zq0?-1`l+TAW>YL6e?BQRIcs=rc1nukwxE`VH&@&!Pt4cf{iEyB$F|^#@Wohb?_2je zYJ)6i!wch5T5}GrG5+gYV1VPhC!;vE)19 z(Q=;uvPvY0rQ1WJpKWSCkZ`g4VP!e=F3{KgO@Nc3dQHq8d)xE&+nrT!Ce$X3-{B9HZiQcSW#Pdzeu0Tn4ul`FIJcTDdGUNte~H5!vmn0$)pn)@SyLI6A)g_>?H_9 zHEiX1=tvI?0W%RC{7F32um7XVBfZ_IIrW>On_1oHoYO+5cC%o zr`QxD$_re>Ct-9gsNR&Bpgh#4Sdhb8MPWi8IK~w`m=FB?q<*ll)z7Ul1^67tgA&oy zb_>MS-(S0lY7fsRGdv&_UuSOdZo;A1+TDHbjABDl0D5{Y^EU9F2h+Fy-auvfs!Gtp z9R}2NDafWOm--^bpj+w)E=S^FzNE9ct?7Deq;@ypQC@6D0*z8_ab^!@{9cd`G>yfE zOE-`1{ibrk%(MIZH|uv@CzpM}i~}rm3758Eg3^nt-vZ&fh}rlC=5=NW^U5y;JqmVK zzIre=5}4yJ2MdRm)C6v4RFas$FgLrDe%2aFwq#ygd^LI(chz=NSqC3&K+5x;4NB|u zp3*)sI>E(^Td|l7C#jat0i;|K21pTezk6N$c!4iys|ma&u(Z00_lgu*V1DP51w&)p zAK8}usqyIb?H0(VZrs||1UdpbC#;PKN?E8*fxYZ#$+pIkW$Po?RugObB7?!$y<;!# zG%XACbS}6IX5E(?Ty!eSte~}xL zzI;qbps9g&P*H9^4fk^)wC===R_`IiOMqWc6Km5Wn%WtoG*{(!?R@{tA*cl#O1>Jd0Zz2x>D;0XQn&{&0i75#LZ(E3fu5#fr)j zIh9$;i_hJeoQaMoEV(Pu#9yVsj&AXMbT{rAr|Fl1&|V}F`^lG{1HMxHfDrm`zk&Yeum0B& zG`mUF&#(rf>*50Imp*3*`^v5wF`7wxG_noZvy3;wzq)--_<#Dd`|^RdTFvKK&;G18 zwS{k`YNhT`KGx~Q;u}A>S-#`^r%EHO(MN?JGn>N~8<6@9O_*13-p>6M$|}^36M6fO zck-uq42SLTf=(E_9F4Nd+h4xj(r{?3+T&jw?=VSEesPA0?7~UUv?_t;fg{;5`R-jH zCZ*jleA`E#TQ#^(A&l= zU-PYk-Pbcs`W{E!{A}xpQr5LB*3Dj9j*asq=0x4zpW`BZ@a0867+l9Y%>mH&05yw= z6hMqmzZ7sTINl_>jwxG;-3#1K0_9^gsm$bywaGa4GEl+j4@gWv9P1VVQNEQUy!cC@ ze-NVn?~WqL2C;4b+xP#UemnI4{5b!o5C8vpbO`72|NqHK%K@u*16a1UF+cZW*ZxxA z80`3^@G<9_%rAG>f*)jSCC(Xw&K8Gpnb#Yjan~*&&e9eMyaQ2gFc75fK3fR3)Yc_D zy@YwyX{{+UksVk($(AvpRis@1H)L&0dYs3~&uW~LpV__FYhzV#UGa@222VzeJb)>~ zR;@G<>KOpD@nBKzpsBU*BJ~L>sdBWO!vy&!s|hq{J(=)+9HI5F>8WyMDW;CrldVNpIn}^6&cN;EQrPdm74iBo?m~2;&=Tv{S7rV-+a!Ziu3~JC7UT|8LMVr!? zA1KHpX%nsjYRB6e^1;yi2dhZS1o2mF_3n_AzWF~%d;f-^*XHEF1kgq+P$v(aI{X28 z^7FKx0>YB7nwC%^aG>G}Lm@_1b4ehz97h#j9+T@)dYSb-Oi7e9V#GEPlh$q^f9V&W zPSFeh5u^>Lh##X;rT!O1R^lX4{Y1bNK;D#Me_9;7cee4{Y{_1rKR>mrQ))Fwl^9Bm z!OGrC_K-C(2^eJiHX7d}8wy$rql5*b39-8@pBbhP!gZ{H`8DSXO$is46*1Nk$?t=f zA@*G*`VDOeOJo!%9~hJ3`7~9hs))jviRl|>)u+YLzTM$XlJ&qH6^n&BY%Q3`Hck(2 zJP8yXERKrw*g(4y8B}IWZWVr+g@^iQHY$a(7dgaNo`=+eq?ZOPxm!Tln=ZGJ0zkN$ zu-Kkg!})m$V9hH?G;jDgW#d3YAK~zsh5omFJf>8mg{vr}OM(d(n2(`OC>8gZD%`~f zw+R{@23J!?qF%ilDKsB^gzkP!=ZSyzdN0ZG8Onj3(byvk=ZcCPqn8Xt2l zj;4>aaA{Yun0KVgPWgUB50gc9xcGpuICixGNYjJkFsT=;KS&Epl6cdY$SCu;i&5pn zgdY!?Ynj}9v=WX;TO)r1K@4CUNt~Dk-p-NmCq75G>mn~P{x~uOrr%BuNYOnyFoK~= zH$y9-Fld={(~xvU1)ih`q#3RH0MNvb*!ovVfwZ|+Kt~e{wu;t1R-uchZdH(=A6l1{ zw%_~D*E5k(3VFXkWp5z5Ti2ZSa5{dK=v_FpnAaS@4zS;@Y^uGk-813h0WY)GySy7Y zdr9M^*B{C>i~WvQ59RF`o*pf?3?HgqHC$;}81AC(nF%cMYjxc$MqXAQD@`xA-goVI z^}zj{;vK`lK7TO6*+u<&sbRUs$Y|EK!tgynFAc(XB`kyGqK7Ra0EkwJ`g?J(J08kr ze|Ry|zHI=j=j)Gf#77Wj)xkA?IWl!{p*ZzPltNHIf0)wr-$*_0eaRA05LNTl>q=rm zVpZfB!5rxOsz9|6lF)(&o~A*}Gd8rVLHe%$SoC2gnBw3j5x$4^HnS_IZ^y(09{D<@ zf}Iy=&%KJdKk2rj{2@(bbzl@~wH`8?6p*GkZpkjV^E((HiYrRP<0@yg8plSpM~B9N z4D+DoNco5IVYd~pYDXGo;CKE3hvwJ7N2nT)ZJajO?OIv7zH=AInLMO=EP3fG=gZXpWU+}1B&D+G@}neqZ(7vF)q z46O%Kbb2Zz;DTDR2hT?PHz2w2EN`l*25>dg(&Jh@(h5gpmD!Q)YbF9g^Ux0WX5Yy$ z8sv0g*S-0^8q?4+``L0I<_t}^nn#0A7f5L+VFEa2WiW7C7cT`Jj>7j$~U<}ecNFQz94;z$(5Rf1 z(Ah-2Zuv%JD=_AQ)Sy_r0{Mt&4A43wusSUXEf5OCe-o-3(*#7tnQe#fo?Wm*9aa4j z>r>Bs-27`~?F{9Mnmg<_M#byugR!oLvbg-|3vt1Qpq(xCO>48y28r_I%+ zr7N8rm*frH%nJ?OSiSV%@^yzT6lS*9w7CWhScIEy9<|IeaVa>_>V|WrdJdbJo*t$H z28>V0p9Nljj1}ZSD;Q65!sHqjORD~Fowwq*6wq=UfSzBKZU%iF6Gq9asMH0S!5H|3 z*8lc5Z*te6Z|81AYe0&>_j|>s(DOn{4^13H+44(a#D_liQBkUMEG+&GNU~$R>Um0t zE9M-N%EXXcG-rM)Q&D4=e4YZPQEIdAI@dwbnKBEM&egmC zo#LJHek%?z0C=U|rA@&iAXG|K49MNLZ{^$V4LUw4B-?R9d zFMi>l&|>o>XzC-I#P+PSx7}^)S-SLL_6tXqi}M|C&)IH)1+0<{!@yoOvv_;No2=dX zPA*^13CqSTZ8Fyf`K9M@wg<&Z;AQSr&~6UEL$-MCPtlLhH4$GlahhdN(iR2|D`@ynvM zb;20+FUUTf9;sWdbUT&=N?tHRu9eMrr|qD7*1C|!=E4WM`!thMHdtC-%T_v?Z-VkW zFN11c;e7`i^mO9v&Mb1=A0^+({iw^mmPS>bwD(Y@)Ow4&E)i6j z6hOrUmtGVe&uV}fQz#Fz@Wm$Cc7I&Ip>${Whm#oL1{NwU?})iFhcb2Vrsh*)7tM&ThrFui z!re6q37AlqV^yAzSt3p?r2a_L=2yGM%>!k%g}lG&s;~A5kIBx|74Q4{^;og>NL%s# zyl)641ep(be8+_(zwZ%vKN-Q~n_>-2&vq>{fGNf}EJ~9A~vZUgX71Wwu*6 zYwv2_bFnGAp-tNlEPzB!->juy!RUP7Sd^t*D7_)CZ9od`c_7_^c_#pmlrD~`Y+*sO#Kp|m-N-(J2oLlSDe)iO_>LAlbvjSPtRcYB$)`=ExfI} zVkRGd5Y)XcTP&Zx@i59z-wY&;Xg6BYB~8F9 zrqy2KLLMPOW&0m^$=@8W`B_$q3H6Stc48kqRQb4i|A|teU7oYcU%626hub0iGe%2N z=vnaC3{u$e^TD8eBuft)-m^!n`N^{#&F^ilAEbM6;1>Wh`B~ zo(+j+38B>k!0;zTs)o=($2JX+gd)KZmFWz;mlw02C^s;o}GpxeiUA~EjJtvZK`i; zZ*9DWuWKvw#-Aw=mh=P`i-L^w((Y#Sa87)tme}ez|NnH+w{rO<{Lze(z+&{j^z&bMtb90lf&JO3dzA`5`R9TG1OVwE7 zTO$ww>PL*m<`|;B?rk5in`iNB=4{cTtAoh;1$~@=*jYU>pTg8JT~H3&mSA%e$>Ywe zyEHcG6q{8voe4iN8jico%mA1E32bn(zvjFt6gv zKIA!$k#F_aI4d78YoiZ?y@Y$K4)87xRTB{-D0`Te!PEezB`9?!)TJMC^4t_#KFras zUBF)t+AN}!$M499BDU_497Jv`v=I9KuA3V$O)@oBv)3M{-9g`BHdP8OE5LRM+9FHI zu?WY>GQ7je|z@;M8i%E)OE5y;da#@SKvnZlb59t*&$rC=xZv zXweU;da3v-gn&W8@-N8K+KA@tr=m}Qy;BHrOQ+D0r!Gbr;nssuN}?V&UdXDj6Lw6- zCx(fDY2V7x(IuJpE$FI#?GC1Kywp?_M}VViQ(m$=o-~W_LV_p^K%wh# zkt%B!l))Gk{HsAU{I`6dT}_ltd)0F*91>vI1)T;f;qq&o2YsfwjMm@^m5bp&=B1hh z`7Vh7d`c_1l76^6qYSvy+`lWkCAXQ`FWF0rl1O)xHG7AfYL;cH*Yg6vaNLrdEtrNM0Zx22sK+FboGDVG`YS!@FE*T8dHVzwI z*Ws3Y+i+xNh&5Jqh&pOARO%gjHs%3ks>b;B@z3AdHVMPlvu;fr5ZbcIfgmFLN#T&D;Ow)Dq8mRSS)H7I68QjH{P0&nnsBGSqqoSSJ#S?x@gMndZbLgmC#O9&4Shee&hcr>)Yd*ZsWgG z-AQgOITf)~PHEP`$Z>adBj+My4ofGk#S${7eJf=Sp%RKvIV{8?vmBT6jU?tc8Ji-f zY{e|L^;|u_=k@&YJb&!v54^V5^}TjopU?aAK1dPKUi=|)$l}hqc*-}8LjzG36s$1o z-*Wp7q`@H5b`YY}zoDymgc)l%)`T;=w5LHe`u`V0QOMQiHpZVA#VMDJU%6So*Ogjo zLcO&hK&^Yj@^d^(6aHgIAGy5$z)zuMwc=V-Fh||_w4{?MI!5uuerN5bKkmrQ&U5#4 zb3p8>&`g%u7;6@9)V|^5cjz`lpDfzG()vCIcu)}d!xJ$vla3BCG0)_`-hdr9OZbtk zCXrE?d}^tQC6YbFZyDDJGPsOKn1u`uwmsf_w_sDJY~;;%eSW~1r?Sder6};H#mA0) z>D<}Hk5#urWqjLXcH!|DF1etw)T%I!Apq>cLhv&AFiH-&S4&$$u`=J7$j-jX=# zvgjKA9A_E2WO_LJByFw0iXnw3;I<#^GlIqCli=51ok!;+ zsYQSMiYMT0kR)+dY%T`1(l^+zgV?)RL6}4ebPtF45=I_N;s6X6V8Y!x3(I`}_og;v zH0PV-pqN5xos>g+0p6vo;Ca905$KzSRG(${OW~b%$#(IcpAu#Cg6x#Asd>$QP0hIq z{2kI^{N+jea?{1o5034R;CnWQ322N%YW z3O(X40b>G2W^3>Y--f>!yNV&DzWV%a#WXoJ*yw2xRDjEP>uJ8-M+PTwtxWH|6||u8eDXup4YSBH~GX6rX)HG?m)5YJbSnBFW$E?%p68J zrU2`uV(QYydx#L9Ufz*UOefq2V<1Y({BvP6uqVTtmSq(Ya~m-> zWHsP=I~b)Gmaik)n?5v@ptu2m5wIHoj4%`@q35SWHow;uQ?b;p6yafe35bKM2OXj7 z8}L|aClVH+iCOC1T>4bj+9AmYtSUGWz?dD)nNASd0C+D&^$a@(q(uY^LU|7CUE*xX zCKkPU;eu;@LlvKq*udmFPr_3Oc@^bvs`+6Fxy>xgw7}3r^j4yK-_V(G@?Su&Weaui zBts0r)tm5DdX)S>0HXj*5Cy;lfkaAViA*S9CVdu{fen-csWfODD*(b4Y2ptU8BSM9 zo2tK%Z=4JsuUwRy&~@z;(W7aI6*|0T6JPmX!=WfSX2_GJqD{CEX zFumv~fWo2I|KTV=JbULjc*VF#$zHMrc(4j9TaoX_i+r&?SyzTy-9~ z+ltdJ;ipV6lIjo>zZSpCWfx}fcN!Lj5@Jn7L+4GBiiN>kjVw-5bl|@(hOold#dn`8 z3A7ZYenEd=&t!30gBIyO^c&zFPe!Y^C`kH9AQxOybW==0U0L>$i#KRN(6li=)dlqBmNYKg{k08 zmig3Xd%Q`hr2>gb+Qw^Nu=NWnn=x!qcUB;^HtglMgMuJoTq$I<16h#ltYBYA?3y4n zGoKSNgZf<^i_4><@6OpDUA7^x?Na@6Z8NBfQb7O2~nI}v3=bU?4dSdos)Fzk^8<|X%3d!u_`%fS6#jqIr$D|*7;;Z zmAxyDrCF9{Eq~ucA|?Q8tbVJ-t%=JUM&eG$TYJ;=9NqJ)^YqQkuB;Ufc8`mGkPbtQ z;PBvikF#94fJ2j#Io)KT#!aX3Q(7^U7IiN!pjKRQzAa!)CoIF{KX(-Q&W5>r%(CY7+%>5WSlELQ)Jw2@{xEo(DgC>M(UvB>}bI3DAZ#t z+GPuN#$)kIXrc_ej;`7Zvg1jl-TWT%5`GLE3yl#J@*Y}m znYk=)k&BpzRx{b`)&mdNGpo_BXrAf>jdO3%Z4fVTMYIk1=Y+XqBk9dmZ$OfIAqDj1 z#a%=K2$HcU#IDMb8=aM-ocNpQ{-w>6z@;Gj`*I|t9<@gp>bL3fHN(U>cRa#cGC$U_ zMNL!I)*Ko_D1DAN_J0iw6@iJN;wb=B-3KoV2>S%EWEsB<#~?|wFQ5|l*EXY8qp^>H zq7=xHuJB1ca}&70n|RWm{>sGBDlz zi*JMK`VqL1yNiTNEQkT)T^Gv!f$+>wJQsKRh21vFmbCo?r7m`gMJ^Q6)U^I{zo1Km z59XIYR+Pbc%!FX`X*C<<`@Y8ByaQH&H?yy~8{GRFwIyW6wZxqkv7BGjn`fP7N7MT7 zLb^*o8gNfyr`t%Igr|$y#MG7u-|T{@qigE-=;WwlWkS+VN4|RZU`Fr-uDyTXvRd?! z(>biZ!S5fvkn*_9?wHm+qiP<^MTk~{I5E_qN(7Q&#olGSv$F6Gvt_j{kDC;X3BYu= z1svWPfRbU(pInWi8{_JkOXtotRL1|+BE{Q&=`=to+w9V=S8S%(K2K!hXNUx~yB~;=d)p_xgA~ipnqPL! z;2wOJdDykUH_01ia=gFi6v*4ti2$uTS}>b6-u~5Rq)t&+~|N z<^y&|?^|3`*K;j#x;k_}jalP#_&!H#XA^L?IqloKqzSHxtp9n)spC8kIBaI`gd8Ku zcR*_}#OK0ECg+huh5d!dQXJoKFaKWLL1iAOERD z$t5WQg>x^^uL<4#Wkg^zPv=DIG-0K{hk3yI_UXJuEXkT2hxdp(1*SjfD%euRyETX>+utXIG5xG+p{^@o?hc(TKAS$}qhy z-mo`n$19f?$J3Rc;g}SqNbCKJ?wB#rAyIG{Zn`DYmAKX%{4Gpb+0?v2p9ko9ia6PqvrdEz z`>I$+eIMh?j;Hf-PcrRE8$kV)3}pU{RcD=eH18X!H&;ad2hJKGdH>1c`O;5AuI&(+ z{9ae29FK*1{6$BnC0oIV$p1kE_t#eP0{CA47kU{j+&wK)iEJ69n<9bI;eZ2tM;*dE zeF)A=64r8I?PE3$UWr%>?t{^*rU=nr>0cKD2Sjf=Q1^Fie87(y+HtPjGez#Q@PN|J z^M}sfM{21ayzWwj#z}Xnm^2wz5Io!ci+-4gLm3x>1Gn{5%-6!q-Hny*gz$tBf%4g& zYnU5f6N^l**Qb(}xRnv#Am7||j4uhIg8*$i4KX_(i^ss`|} z?@Z20c78(auBz;-M3`~?7hp>1SvY)vQq2j1qG`w>E43Xgg2BAy}z%~57!^__WCp3rXz_s8nMH0o>dc3>%CHufV%$6-IH7@?L_-~ z)7CUhKq1E^N8_3QChiyNP8}5-DrA1F48ouB;M;>G1#2Axz_%Im9Ke5Xez9f^{ZNO_ z!pniTrah?mH$s=j?|^AE4xU7ZR}$Lc8-#~Pt%NE3;yI^igUR+xuCK4R*3yFyi{Upz z7AzwXoAH>Zs_k(e_NtPKhqET`l^uOb&!l!vcdn^xj&$Xo{X*#A(GxCKn#-)Z|+8!%X$e;5y7+M%|>su;a zXH$qd;a}KMYEV#&wUVoIr)M-ONjZ3IMMmLXM49&y3>mV*#5UCi+9X=u6BNl$U*Ixz zVnY_}R=vo*A``BhZ}@aFyK~&RckyES*GoS%bNNG(J)gjX0t|`XAR*|7;@0?}8F>s! zw8f17l%x(otJ~2NVD2g0Q?whNj8%NU@9*4^6>gPubvwD^{p@v_rHw;NI=m7Paz`=} z9RxWV8JyU9SVDtZ)LEYKUCBNXnvbfdEkD-S&BG=w>BF`QFJKb7T&pVj=TlvKL(TLX z{a=l+u&iHftFNW?A8s_=+GR7}%va+QTK{BpSx?Yg;h^~6OhewvRT4qG@unPoVGPgT zqd&vFU!q1V@$3s&L_u48$D=blaXL(c0%E4xs6N7}XHSn?MP)yb9Zs%bQn#tRPTj3y z0KpCl89bYb_66yQ5^C(YM#FYsoHfGxAy@@&96X&?#(E-_YaCNXL+p38eERA$(Z6-o zw>-}gqBuDWs-#>TQht=GRrj!bpC|?Fq{m?Cz)jnSg3hIg{zZ=bvE{M|_)=W+9s3xtF7ONjg%u6slR*>q4NC$f>4!kx&*j#v3 z#=rW3NExUn^kB;-3{vbtMb)~yDnxHImTM23*rQHsZ&|)mYTId z-{;Jta;4jlEDuki)g<@^Ml>*BO~_aVi*D*yoqN1t=p0jI#+lRVzvl1tWV$b8VNV!O zTvx*oB^+va-QpH{WL;pEaTFN~=|rTFzGbg#+9_HrrU70X(H(?=`jq;Q&o+ z=E5r_Cq;P#apg-;3m>yy5y@V?d-_6lhAcQW$r=1OT4xb$Hmf42X|eXIHTT@SKuMlk zR+V`)wK)*l+mm5_x?6)2JF;KDjFTEei?w!w?R+kC<6Ifg zKI+82@{R+k5{{%5yR8n-cNUxnJW43e@ra>Be;_2=h4p*g>FWC@f=Z9Q6efCnTI#;R zJy?{LgmqxPUM$nuToi8J=i9Q;_|PZm{>uMzHXVS%+gk~VAf--cqW%O|x}`J%4I^G~ z%p4r_YQ{%GK^6;34UTC^X|dUa(CF~6VC~~p8@KL_*RFndCE#2Rk@1AVQUE!Uu*BS| zUSY+MF=o7Rl%Xop%{rx;{4i|SAETKX=a_kOPn>pq5S+y}*_vCXS9wUe?x$y-yUG?A zwA9L{PEc=2&_d}`!XUnKr(m&pW#}g6?u{8bm2wsEfGH>YJb^cTv(S-1WfeuTxqU1e1Z$?F3l@5<6U9sS+$y7@*C*Q*czd%wh@e~SGL8fA4>F%_rL z{?5ZC6V&4tX2=ph>3u$X+qKyLwmf&%|7I)y= z*rQfanOkpDW;L{+0mSRTy`BM7lx}5Yfj?shaAt&jcvJowF2L zx=FyrY#&<@Li_-l$dMcn=iePymY80Z?B^}sqP@_Xf>QT;Kj-(Pl=;K8%ax{R_@YuW zxv{yhB+@@L=yh>1?x9vzSs|l}A&b65h#BA90K^p&l-SB>>y<`JBgfDv-^}ktC_xEV zforixUHS~ZYwcpWa_drJWTbv*-*e_9OWQmBP&gKM-;qTvAi zqCoM5HT2|_mLTECDFMTjaD+n8RT(CAHNF;x^87C#QrJqf@Z?tbwRKA38|b- zq;Q5n&|oevy&y`@z}gy_Q2yPrbFw_t{wRwHrl81L=j>6iZ-Z7=l1RaJCc z*I=_c*`E6nj3fYJns||0(F0_uF)a|dL<|>W=^DD}J#D}?c^P4c+&){C`JyVzfx#?Y zIM4i2)weXW_m)+-Zcxa|jp{Sn=S~EQe*x=ctX!0n_%U#6*wE&VC=&X&=5CO{XH>g0 zdr+?{Sf7c;|C&wI&_ii?;Gxc@D z!s*7_{-N%d?3RpU-_m0>rOvE}L;>I;JsssEjDaUbg}v;7xRE8p06vSeiM7szJ;J$8Z_P-j6X7(VgB z>l@#zF~2dd9lw319Cw|ypVdk!cyjOBWR=@(L<@ei{5>U6Be?F4{f5?Eh5=4H7*IxS zco}6}%{LbSiRx6z>sc9YfJ@JrN9-x4oAUM63y8vuLc^O}g`bFaR)N3N{jp<`2Mt@d zlVnBu`vC0JMCFwduQDTJv{@w!21D;XzxmLd>IoJnoAe*XvNW^+ znT+c8#yAZw7JXxH9r|8bm1s{qkeLMF4{${T%;y!w|%~Sk7{^673AD!QW{{%A> zOG_dbO-BEHz-0x~Z}^LVvaadB018TUvmlHGv6dl=z$xnv<^jSbW&zRfj^Mi&wE~fr z)II%hCy+MrY=JAKiqL`^VBhL%%1^K5Bkg%PjMwc&-&}E-Hun(AiRyc%1Z^MXRDas` zhpLSksl9ViEBcNyi>$Zau~Xb<%Uv&Bz1>jC7dj($h9BXYN`keA}Fn{3&tF z0{UY6dU5Z`FIi3lhHI}T`VF(4Hc!RcRxa2L4*ob=7<-xAnW;mXot+(Q8=Mjdrew|Z zk80P{*4AX2MS6L85n1@etgQH_d+u!BW0Q_62u;=<$R2UC1pqkDdVwTC#-Vpc85k5u zx){8`7;48w?_GH!bB==yUJMS*eGA<2C&hBQ4q`vK#p5R^XAR(?pG3 z)u4nHeuLygVJfp42kdQqr3bEwcIT-07@w?pbeL-N6fquG&`|UC!k3<4%CLE{#O{{V z(lp@HO%z}&q{%3Jy?VnwU;K>`2fgF^2Aep0d~-A4t&UfrfzL!7N^}%9bQ`c@AttsBZ{}iyd_s9gNzDB0+oUvHTvn z&isGieUQi~Wxo3NI;)H(MmlIRI%oBNZSGh`KLt2-b%gHAjOHy;6_Df_`by6)JN8rX zUhRVGzt=IHn^=<6Iey6`Y~GbmZvz@pEG+7JuVJYH;oc+RG{+_xh2Gv#hTCSJe{4b> z-Bh(&_RumOH6O7sm=}q>_f<6{lav*9&f|2YvByn`+xR1?HGS+yXOZ&y)y`?bJ)Tx6 z?Q3c4$827zeatC{eut~)|0V}gCRY8}LC{QM*?V5D1i2Bq(`UjFl-Q6>dh%JTM%1ZV z?kY%GA8+qrv6zDA!XsQL-gmc<8b)PD{mnNw;19E`O2+XwzJ=9<_S35#zSg@0aY_^- z^X0rw^FBz_vyLS?hE`Wwt&_wxzOUsqwmZri8h|A3&P`x!Al(cK{tJy5ofa=28~Xu+Q1~`H#`0dt zzBjWNSnP6=)uLgST9@ao^iKPy8jGG@ddD5{$|bvu<&RyjXjJ)ZC?!+@PzM+fJ!DS! zixa#hU=q))B4gje--4Or1LzJUI4MyBdJ?slL(}6T#S-B6(Y|(KHdiLJ=WeEYN<6&z zCVOu$N^Cjl-5a7euQ?D{8Ck3DrZq%ZTEo|(jOY)2Tk(c;Ud5;({p^0J%bTP-AOEpf u3eM=&k$MAK7a2O~kd%`YU`yvU0Cwo7UnPI$AmacGe?=X_=x+Eu^1lFz_TqK` From eb2e9477b376378186cd2e72bf1602f9758d6609 Mon Sep 17 00:00:00 2001 From: tipouic Date: Fri, 5 Feb 2016 08:57:31 +0100 Subject: [PATCH 4/9] Suivit du projet --- Multiprotocol/CG023_nrf24l01.ino | 65 +++--- Multiprotocol/CX10_nrf24l01.ino | 102 +++++----- Multiprotocol/FrSky_cc2500.ino | 22 +- Multiprotocol/KN_nrf24l01.ino | 8 +- Multiprotocol/MJXQ_nrf24l01.ino | 247 +++++++++++++++++++++++ Multiprotocol/MT99xx_nrf24l01.ino | 221 ++++++++++++++++++++ Multiprotocol/Multiprotocol.ino | 32 +-- Multiprotocol/Telemetry.ino | 18 ++ Multiprotocol/V2X2_nrf24l01.ino | 6 +- Multiprotocol/_Config.h | 98 +++++---- Multiprotocol/multiprotocol.h | 69 +++++-- Multiprotocol/nrf24l01_H7.ino | 151 -------------- Multiprotocol/nrf24l01_hm830.ino | 321 ------------------------------ README.md | 1 - sync.ffs_db | Bin 1276 -> 1285 bytes 15 files changed, 688 insertions(+), 673 deletions(-) create mode 100644 Multiprotocol/MJXQ_nrf24l01.ino create mode 100644 Multiprotocol/MT99xx_nrf24l01.ino delete mode 100644 Multiprotocol/nrf24l01_H7.ino delete mode 100644 Multiprotocol/nrf24l01_hm830.ino diff --git a/Multiprotocol/CG023_nrf24l01.ino b/Multiprotocol/CG023_nrf24l01.ino index 6810652..0e5c0ce 100644 --- a/Multiprotocol/CG023_nrf24l01.ino +++ b/Multiprotocol/CG023_nrf24l01.ino @@ -104,6 +104,8 @@ static void __attribute__((unused)) CG023_send_packet(uint8_t bind) packet[6] = 0x08; packet[7] = 0x03; packet[9] = throttle; + if(rudder==0x01) rudder=0; // Small deadband + if(rudder==0x81) rudder=0; // Small deadband packet[10] = rudder; packet[11] = elevator; packet[12] = aileron; @@ -112,15 +114,11 @@ static void __attribute__((unused)) CG023_send_packet(uint8_t bind) packet[14] = 0x20; packet[15] = 0x20; packet[16] = 0x20; - packet[17] = H8_3D_FLAG_RATE_HIGH; - if(Servo_AUX1) - packet[17] |= H8_3D_FLAG_FLIP; - if(Servo_AUX2) - packet[17] |= H8_3D_FLAG_LIGTH; //H22 light - if(Servo_AUX3) - packet[17] |= H8_3D_FLAG_HEADLESS; - if(Servo_AUX4) - packet[17] |= H8_3D_FLAG_RTH; // 180/360 flip mode on H8 3D + packet[17] = H8_3D_FLAG_RATE_HIGH + | GET_FLAG(Servo_AUX1,H8_3D_FLAG_FLIP) + | GET_FLAG(Servo_AUX2,H8_3D_FLAG_LIGTH) //H22 light + | GET_FLAG(Servo_AUX3,H8_3D_FLAG_HEADLESS) + | GET_FLAG(Servo_AUX4,H8_3D_FLAG_RTH); // 180/360 flip mode on H8 3D if(Servo_AUX5) packet[18] = H8_3D_FLAG_CALIBRATE; } @@ -152,32 +150,21 @@ static void __attribute__((unused)) CG023_send_packet(uint8_t bind) if(sub_protocol==CG023) { // rate - packet[13] = CG023_FLAG_RATE_HIGH; - // flags - if(Servo_AUX1) - packet[13] |= CG023_FLAG_FLIP; - if(Servo_AUX2) - packet[13] |= CG023_FLAG_LED_OFF; - if(Servo_AUX3) - packet[13] |= CG023_FLAG_STILL; - if(Servo_AUX4) - packet[13] |= CG023_FLAG_VIDEO; - if(Servo_AUX5) - packet[13] |= CG023_FLAG_EASY; + packet[13] = CG023_FLAG_RATE_HIGH + | GET_FLAG(Servo_AUX1,CG023_FLAG_FLIP) + | GET_FLAG(Servo_AUX2,CG023_FLAG_LED_OFF) + | GET_FLAG(Servo_AUX3,CG023_FLAG_STILL) + | GET_FLAG(Servo_AUX4,CG023_FLAG_VIDEO) + | GET_FLAG(Servo_AUX5,CG023_FLAG_EASY); } else {// YD829 // rate - packet[13] = YD829_FLAG_RATE_HIGH; - // flags - if(Servo_AUX1) - packet[13] |= YD829_FLAG_FLIP; - if(Servo_AUX3) - packet[13] |= YD829_FLAG_STILL; - if(Servo_AUX4) - packet[13] |= YD829_FLAG_VIDEO; - if(Servo_AUX5) - packet[13] |= YD829_FLAG_HEADLESS; + packet[13] = YD829_FLAG_RATE_HIGH + | GET_FLAG(Servo_AUX1,YD829_FLAG_FLIP) + | GET_FLAG(Servo_AUX3,YD829_FLAG_STILL) + | GET_FLAG(Servo_AUX4,YD829_FLAG_VIDEO) + | GET_FLAG(Servo_AUX5,YD829_FLAG_HEADLESS); } packet[14] = 0; } @@ -237,13 +224,7 @@ uint16_t CG023_callback() bind_counter--; } } - - if(sub_protocol==CG023) - return CG023_PACKET_PERIOD; - else - if(sub_protocol==YD829) - return YD829_PACKET_PERIOD; - return H8_3D_PACKET_PERIOD; + return packet_period; } static void __attribute__((unused)) CG023_initialize_txid() @@ -276,11 +257,13 @@ uint16_t initCG023(void) CG023_initialize_txid(); CG023_init(); if(sub_protocol==CG023) - return CG023_INITIAL_WAIT+CG023_PACKET_PERIOD; + packet_period=CG023_PACKET_PERIOD; else if(sub_protocol==YD829) - return CG023_INITIAL_WAIT+YD829_PACKET_PERIOD; - return CG023_INITIAL_WAIT+H8_3D_PACKET_PERIOD; + packet_period=YD829_PACKET_PERIOD; + else + packet_period=H8_3D_PACKET_PERIOD; + return CG023_INITIAL_WAIT+YD829_PACKET_PERIOD; } #endif diff --git a/Multiprotocol/CX10_nrf24l01.ino b/Multiprotocol/CX10_nrf24l01.ino index 044c20c..6722fcd 100644 --- a/Multiprotocol/CX10_nrf24l01.ino +++ b/Multiprotocol/CX10_nrf24l01.ino @@ -12,21 +12,22 @@ You should have received a copy of the GNU General Public License along with Multiprotocol. If not, see . */ -// compatible with Cheerson CX-10 blue & newer red pcb, CX-10A, CX11, CX-10 green pcb, DM007, Floureon FX-10, CX-Stars +// compatible with Cheerson CX-10 blue & newer red pcb, CX-10A, CX11, CX-10 green pcb, DM007, Floureon FX-10, JXD 509 (Q282) // Last sync with hexfet new_protocols/cx10_nrf24l01.c dated 2015-11-26 #if defined(CX10_NRF24L01_INO) #include "iface_nrf24l01.h" -#define CX10_BIND_COUNT 4360 // 6 seconds -#define CX10_PACKET_SIZE 15 -#define CX10A_PACKET_SIZE 19 // CX10 blue board packets have 19-byte payload -#define Q282_PACKET_SIZE 21 -#define CX10_PACKET_PERIOD 1316 // Timeout for callback in uSec -#define CX10A_PACKET_PERIOD 6000 +#define CX10_BIND_COUNT 4360 // 6 seconds +#define CX10_PACKET_SIZE 15 +#define CX10A_PACKET_SIZE 19 // CX10 blue board packets have 19-byte payload +#define Q282_PACKET_SIZE 21 +#define CX10_PACKET_PERIOD 1316 // Timeout for callback in uSec +#define CX10A_PACKET_PERIOD 6000 +#define CX10A_BIND_COUNT 400 // 2 seconds -#define INITIAL_WAIT 500 +#define CX10_INITIAL_WAIT 500 // flags #define CX10_FLAG_FLIP 0x10 // goes to rudder channel @@ -37,8 +38,8 @@ #define CX10_FLAG_SNAPSHOT 0x04 // frequency channel management -#define RF_BIND_CHANNEL 0x02 -#define NUM_RF_CHANNELS 4 +#define CX10_RF_BIND_CHANNEL 0x02 +#define CX10_NUM_RF_CHANNELS 4 enum { CX10_BIND1 = 0, @@ -86,63 +87,61 @@ static void __attribute__((unused)) CX10_Write_Packet(uint8_t bind) switch(sub_protocol) { case CX10_BLUE: - if(Servo_AUX3) flags |= 0x10; // Channel 7 - picture - if(Servo_AUX4) flags |= 0x08; // Channel 8 - video + flags |= GET_FLAG(!Servo_AUX3, 0x10) // Channel 7 - picture + |GET_FLAG( Servo_AUX4, 0x08); // Channel 8 - video break; case Q282: case Q242: memcpy(&packet[15], "\x10\x10\xaa\xaa\x00\x00", 6); //FLIP|LED|PICTURE|VIDEO|HEADLESS|RTH|XCAL|YCAL - if(Servo_AUX1) flags2 =0x80; // Channel 5 - FLIP - if(Servo_AUX2) flags2|=0x40; // Channel 6 - LED - - if(Servo_AUX5) flags2|=0x08; // Channel 9 - HEADLESS + flags2 = GET_FLAG(Servo_AUX1, 0x80) // Channel 5 - FLIP + |GET_FLAG(Servo_AUX2, 0x40) // Channel 6 - LED + |GET_FLAG(Servo_AUX5, 0x08) // Channel 9 - HEADLESS + |GET_FLAG(Servo_AUX7, 0x04) // Channel 11 - XCAL + |GET_FLAG(Servo_AUX8, 0x02); // Channel 12 - YCAL or Start/Stop motors on JXD 509 + if(sub_protocol==Q282) { - if(Servo_AUX3) flags2|=0x10; // Channel 7 - picture - if(Servo_AUX4) // Channel 8 - video + flags=3; + if(Servo_AUX4) // Channel 8 - video { if (!(video_state & 0x20)) video_state ^= 0x21; } else if (video_state & 0x20) video_state &= 0x01; - flags2 |= video_state; - flags=3; + flags2 |= video_state + |GET_FLAG(Servo_AUX3,0x10); // Channel 7 - picture } else { - if(Servo_AUX3) flags2|=0x01; // Channel 7 - picture - if(Servo_AUX4) flags2|=0x10; // Channel 8 - video flags=2; + flags2|= GET_FLAG(Servo_AUX3,0x01) // Channel 7 - picture + |GET_FLAG(Servo_AUX4,0x10); // Channel 8 - video packet[17]=0x00; packet[18]=0x00; } - if(Servo_AUX6) flags |=0x80; // Channel 10 - RTH - if(Servo_AUX7) flags2|=0x04; // Channel 11 - XCAL - if(Servo_AUX8) flags2|=0x02; // Channel 12 - YCAL + if(Servo_AUX6) flags |=0x80; // Channel 10 - RTH break; case DM007: //FLIP|MODE|PICTURE|VIDEO|HEADLESS - if(Servo_AUX3) flags2 = CX10_FLAG_SNAPSHOT; // Channel 7 - picture - if(Servo_AUX4) flags2|= CX10_FLAG_VIDEO; // Channel 8 - video - if(Servo_AUX5) flags |= CX10_FLAG_HEADLESS; // Channel 9 - headless - break; - case JC3015_1: - //FLIP|MODE|PICTURE|VIDEO - if(Servo_AUX3) flags2 = _BV(3); // Channel 7 - picture - if(Servo_AUX4) flags2|= _BV(4); // Channel 8 - video + flags2= GET_FLAG(Servo_AUX3,CX10_FLAG_SNAPSHOT) // Channel 7 - picture + |GET_FLAG(Servo_AUX4,CX10_FLAG_VIDEO); // Channel 8 - video + if(Servo_AUX5) flags |= CX10_FLAG_HEADLESS; // Channel 9 - headless break; case JC3015_2: //FLIP|MODE|LED|DFLIP - if(Servo_AUX3) flags2 = _BV(3); // Channel 7 - LED - if(Servo_AUX4) flags2|= _BV(4); // Channel 8 - DFLIP + if(Servo_AUX4) packet[12] &= ~CX10_FLAG_FLIP; + case JC3015_1: + //FLIP|MODE|PICTURE|VIDEO + flags2= GET_FLAG(Servo_AUX3,_BV(3)) // Channel 7 + |GET_FLAG(Servo_AUX4,_BV(4)); // Channel 8 break; case MK33041: //FLIP|MODE|PICTURE|VIDEO|HEADLESS|RTH - if(Servo_AUX3) flags |= _BV(7); // Channel 7 - picture - if(Servo_AUX4) flags2 = _BV(0); // Channel 8 - video - if(Servo_AUX5) flags2|= _BV(5); // Channel 9 - headless - if(Servo_AUX6) flags |= _BV(2); // Channel 10 - rth + flags|=GET_FLAG(Servo_AUX3,_BV(7)) // Channel 7 - picture + |GET_FLAG(Servo_AUX6,_BV(2)); // Channel 10 - rth + flags2=GET_FLAG(Servo_AUX4,_BV(0)) // Channel 8 - video + |GET_FLAG(Servo_AUX5,_BV(5)); // Channel 9 - headless break; } packet[13+offset]=flags; @@ -152,11 +151,11 @@ static void __attribute__((unused)) CX10_Write_Packet(uint8_t bind) // Why CRC0? xn297 does not interpret it - either 16-bit CRC or nothing XN297_Configure(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP)); if (bind) - NRF24L01_WriteReg(NRF24L01_05_RF_CH, RF_BIND_CHANNEL); + NRF24L01_WriteReg(NRF24L01_05_RF_CH, CX10_RF_BIND_CHANNEL); else { NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no++]); - hopping_frequency_no %= NUM_RF_CHANNELS; + hopping_frequency_no %= CX10_NUM_RF_CHANNELS; } // clear packet status bits and TX FIFO NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); @@ -178,7 +177,7 @@ static void __attribute__((unused)) CX10_init() NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowledgment on all data pipes NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, packet_length); // rx pipe 0 (used only for blue board) - NRF24L01_WriteReg(NRF24L01_05_RF_CH, RF_BIND_CHANNEL); + NRF24L01_WriteReg(NRF24L01_05_RF_CH, CX10_RF_BIND_CHANNEL); NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps NRF24L01_SetPower(); } @@ -198,13 +197,22 @@ uint16_t CX10_callback() { } break; case CX10_BIND2: + bind_counter--; + if(bind_counter==0) + { // Needed for some CX-10A to properly finish the bind + CX10_init(); + bind_counter=CX10A_BIND_COUNT; + } if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_RX_DR)) { // RX fifo data ready XN297_ReadPayload(packet, packet_length); NRF24L01_SetTxRxMode(TXRX_OFF); NRF24L01_SetTxRxMode(TX_EN); if(packet[9] == 1) + { phase = CX10_BIND1; + bind_counter=0; + } } else { @@ -226,7 +234,7 @@ uint16_t CX10_callback() { return packet_period; } -static void __attribute__((unused)) initialize_txid() +static void __attribute__((unused)) CX10_initialize_txid() { rx_tx_addr[1]%= 0x30; if(sub_protocol==Q282) @@ -259,8 +267,10 @@ uint16_t initCX10(void) { packet_length = CX10A_PACKET_SIZE; packet_period = CX10A_PACKET_PERIOD; + phase = CX10_BIND2; - bind_counter=0; + bind_counter=CX10A_BIND_COUNT; + for(uint8_t i=0; i<4; i++) packet[5+i] = 0xff; // clear aircraft id packet[9] = 0; @@ -275,10 +285,10 @@ uint16_t initCX10(void) phase = CX10_BIND1; bind_counter = CX10_BIND_COUNT; } - initialize_txid(); + CX10_initialize_txid(); CX10_init(); BIND_IN_PROGRESS; // autobind protocol - return INITIAL_WAIT+packet_period; + return CX10_INITIAL_WAIT+packet_period; } #endif diff --git a/Multiprotocol/FrSky_cc2500.ino b/Multiprotocol/FrSky_cc2500.ino index 449f954..dae03c7 100644 --- a/Multiprotocol/FrSky_cc2500.ino +++ b/Multiprotocol/FrSky_cc2500.ino @@ -178,26 +178,6 @@ uint16_t initFrSky_2way() return 10000; } -#if defined(TELEMETRY) -static void __attribute__((unused)) check_telemetry(uint8_t *pkt,uint8_t len) -{ - if(pkt[1] != rx_tx_addr[3] || pkt[2] != rx_tx_addr[2] || len != pkt[0] + 3) - {//only packets with the required id and packet length - for(uint8_t i=3;i<6;i++) - pktt[i]=0; - return; - } - else - { - for (uint8_t i=3;i0) - telemetry_counter=(telemetry_counter+1)%32; - } -} -#endif - uint16_t ReadFrSky_2way() { if (state < FRSKY_BIND_DONE) @@ -245,7 +225,7 @@ uint16_t ReadFrSky_2way() cc2500_readFifo(pkt, len); //received telemetry packets #if defined(TELEMETRY) //parse telemetry packet here - check_telemetry(pkt,len); //check if valid telemetry packets and buffer them. + frsky_check_telemetry(pkt,len); //check if valid telemetry packets and buffer them. #endif } CC2500_SetTxRxMode(TX_EN); diff --git a/Multiprotocol/KN_nrf24l01.ino b/Multiprotocol/KN_nrf24l01.ino index 53e902d..9e0775b 100644 --- a/Multiprotocol/KN_nrf24l01.ino +++ b/Multiprotocol/KN_nrf24l01.ino @@ -144,13 +144,13 @@ static void __attribute__((unused)) kn_update_packet_control_data() packet[11] = 0x64; // R flags=0; - if (Servo_data[AUX1] > PPM_SWITCH) + if (Servo_AUX1) flags = KN_FLAG_DR; - if (Servo_data[AUX2] > PPM_SWITCH) + if (Servo_AUX2) flags |= KN_FLAG_TH; - if (Servo_data[AUX3] > PPM_SWITCH) + if (Servo_AUX3) flags |= KN_FLAG_IDLEUP; - if (Servo_data[AUX4] > PPM_SWITCH) + if (Servo_AUX4) flags |= KN_FLAG_GYRO3; packet[12] = flags; diff --git a/Multiprotocol/MJXQ_nrf24l01.ino b/Multiprotocol/MJXQ_nrf24l01.ino new file mode 100644 index 0000000..484e798 --- /dev/null +++ b/Multiprotocol/MJXQ_nrf24l01.ino @@ -0,0 +1,247 @@ +/* + This project is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Multiprotocol is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with Multiprotocol. If not, see . + */ +// compatible with MJX WLH08, X600, X800, H26D +// Last sync with hexfet new_protocols/mjxq_nrf24l01.c dated 2016-01-17 + +#if defined(MJXQ_NRF24L01_INO) + +#include "iface_nrf24l01.h" + +#define MJXQ_BIND_COUNT 150 +#define MJXQ_PACKET_PERIOD 4000 // Timeout for callback in uSec +#define MJXQ_INITIAL_WAIT 500 +#define MJXQ_PACKET_SIZE 16 +#define MJXQ_RF_NUM_CHANNELS 4 +#define MJXQ_ADDRESS_LENGTH 5 + +#define MJXQ_PAN_TILT_COUNT 16 // for H26D - match stock tx timing +#define MJXQ_PAN_DOWN 0x08 +#define MJXQ_PAN_UP 0x04 +#define MJXQ_TILT_DOWN 0x20 +#define MJXQ_TILT_UP 0x10 +static uint8_t __attribute__((unused)) MJXQ_pan_tilt_value() +{ +// Servo_AUX8 PAN // H26D +// Servo_AUX9 TILT + uint8_t pan = 0; + packet_count++; + if(packet_count & MJXQ_PAN_TILT_COUNT) + { + if(Servo_AUX8) + pan=MJXQ_PAN_UP; + if(Servo_data[AUX8]PPM_MIN_COMMAND) + pan=MJXQ_TILT_UP; + if(Servo_data[AUX9]> 1) +static void __attribute__((unused)) MJXQ_send_packet(uint8_t bind) +{ + packet[0] = convert_channel_8b(THROTTLE); + packet[1] = convert_channel_s8b(RUDDER); + packet[4] = 0x40; // rudder does not work well with dyntrim + packet[2] = convert_channel_s8b(ELEVATOR); + packet[5] = MJXQ_CHAN2TRIM(packet[2]); // trim elevator + packet[3] = convert_channel_s8b(AILERON); + packet[6] = MJXQ_CHAN2TRIM(packet[3]); // trim aileron + packet[7] = rx_tx_addr[0]; + packet[8] = rx_tx_addr[1]; + packet[9] = rx_tx_addr[2]; + + packet[10] = 0x00; // overwritten below for feature bits + packet[11] = 0x00; // overwritten below for X600 + packet[12] = 0x00; + packet[13] = 0x00; + + packet[14] = 0xC0; // bind value + +// Servo_AUX1 FLIP +// Servo_AUX2 LED +// Servo_AUX3 PICTURE +// Servo_AUX4 VIDEO +// Servo_AUX5 HEADLESS +// Servo_AUX6 RTH +// Servo_AUX7 AUTOFLIP // X800, X600 + switch(sub_protocol) + { + case H26D: + packet[10]=MJXQ_pan_tilt_value(); + // fall through on purpose - no break + case WLH08: + packet[10] += GET_FLAG(Servo_AUX6, 0x02) //RTH + | GET_FLAG(Servo_AUX5, 0x01); //HEADLESS + if (!bind) + { + packet[14] = 0x04 + | GET_FLAG(Servo_AUX1, 0x01) //FLIP + | GET_FLAG(Servo_AUX3, 0x08) //PICTURE + | GET_FLAG(Servo_AUX4, 0x10) //VIDEO + | GET_FLAG(!Servo_AUX2, 0x20); // air/ground mode + } + break; + case X600: + if(Servo_AUX5) //HEADLESS + { // driven trims cause issues when headless is enabled + packet[5] = 0x40; + packet[6] = 0x40; + } + packet[10] = GET_FLAG(!Servo_AUX2, 0x02); //LED + packet[11] = GET_FLAG(Servo_AUX6, 0x01); //RTH + if (!bind) + { + packet[14] = 0x02 // always high rates by bit2 = 1 + | GET_FLAG(Servo_AUX1, 0x04) //FLIP + | GET_FLAG(Servo_AUX7, 0x10) //AUTOFLIP + | GET_FLAG(Servo_AUX5, 0x20); //HEADLESS + } + break; + case X800: + default: + packet[10] = 0x10 + | GET_FLAG(!Servo_AUX2, 0x02) //LED + | GET_FLAG(Servo_AUX7, 0x01); //AUTOFLIP + if (!bind) + { + packet[14] = 0x02 // always high rates by bit2 = 1 + | GET_FLAG(Servo_AUX1, 0x04) //FLIP + | GET_FLAG(Servo_AUX3, 0x08) //PICTURE + | GET_FLAG(Servo_AUX4, 0x10); //VIDEO + } + break; + } + + uint8_t sum = packet[0]; + for (uint8_t i=1; i < MJXQ_PACKET_SIZE-1; i++) sum += packet[i]; + packet[15] = sum; + + // Power on, TX mode, 2byte CRC + if (sub_protocol == H26D) + NRF24L01_SetTxRxMode(TX_EN); + else + XN297_Configure(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP)); + + NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no++ / 2]); + hopping_frequency_no %= 2 * MJXQ_RF_NUM_CHANNELS; // channels repeated + + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); + NRF24L01_FlushTx(); + + if (sub_protocol == H26D) + NRF24L01_WritePayload(packet, MJXQ_PACKET_SIZE); + else + XN297_WritePayload(packet, MJXQ_PACKET_SIZE); + + NRF24L01_SetPower(); +} + +static void __attribute__((unused)) MJXQ_init() +{ + uint8_t addr[MJXQ_ADDRESS_LENGTH]; + memcpy(addr, "\x6d\x6a\x77\x77\x77", MJXQ_ADDRESS_LENGTH); + if (sub_protocol == WLH08) + memcpy(hopping_frequency, "\x12\x22\x32\x42", MJXQ_RF_NUM_CHANNELS); + else + if (sub_protocol == H26D) + memcpy(hopping_frequency, "\x36\x3e\x46\x2e", MJXQ_RF_NUM_CHANNELS); + else + { + memcpy(hopping_frequency, "\x0a\x35\x42\x3d", MJXQ_RF_NUM_CHANNELS); + memcpy(addr, "\x6d\x6a\x73\x73\x73", MJXQ_RF_NUM_CHANNELS); + } + + + NRF24L01_Initialize(); + NRF24L01_SetTxRxMode(TX_EN); + + if (sub_protocol == H26D) + NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, addr, MJXQ_ADDRESS_LENGTH); + else + XN297_SetTXAddr(addr, MJXQ_ADDRESS_LENGTH); + + NRF24L01_FlushTx(); + NRF24L01_FlushRx(); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit + NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowledgment on all data pipes + NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only + NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x00); // no retransmits + NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, MJXQ_PACKET_SIZE); // rx pipe 0 (used only for blue board) + NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps + NRF24L01_SetPower(); +} + +static void __attribute__((unused)) MJXQ_init2() +{ + // haven't figured out txid<-->rf channel mapping for MJX models + static const uint8_t rf_map[][4] = { + {0x0A, 0x46, 0x3A, 0x42}, + {0x0A, 0x3C, 0x36, 0x3F}, + {0x0A, 0x43, 0x36, 0x3F} }; + if (sub_protocol == H26D) + memcpy(hopping_frequency, "\x32\x3e\x42\x4e", MJXQ_RF_NUM_CHANNELS); + else + if (sub_protocol == WLH08) + memcpy(hopping_frequency, rf_map[rx_tx_addr[0]%3], MJXQ_RF_NUM_CHANNELS); +} + +static void __attribute__((unused)) MJXQ_initialize_txid() +{ + // haven't figured out txid<-->rf channel mapping for MJX models + static const uint8_t tx_map[][3]={ + {0xF8, 0x4F, 0x1C}, + {0xC8, 0x6E, 0x02}, + {0x48, 0x6A, 0x40} }; + if (sub_protocol == WLH08) + rx_tx_addr[0]&=0xF8; // txid must be multiple of 8 + else + memcpy(rx_tx_addr,tx_map[rx_tx_addr[0]%3],3); +} + +uint16_t MJXQ_callback() +{ + if(IS_BIND_DONE_on) + MJXQ_send_packet(0); + else + { + if (bind_counter == 0) + { + MJXQ_init2(); + BIND_DONE; + } + else + { + bind_counter--; + MJXQ_send_packet(1); + } + } + + return MJXQ_PACKET_PERIOD; +} + +uint16_t initMJXQ(void) +{ + BIND_IN_PROGRESS; // autobind protocol + bind_counter = MJXQ_BIND_COUNT; + MJXQ_initialize_txid(); + MJXQ_init(); + packet_count=0; + return MJXQ_INITIAL_WAIT+MJXQ_PACKET_PERIOD; +} + +#endif diff --git a/Multiprotocol/MT99xx_nrf24l01.ino b/Multiprotocol/MT99xx_nrf24l01.ino new file mode 100644 index 0000000..ab4c825 --- /dev/null +++ b/Multiprotocol/MT99xx_nrf24l01.ino @@ -0,0 +1,221 @@ +/* + This project is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Multiprotocol is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with Multiprotocol. If not, see . + */ +// compatible with MT99xx, Eachine H7, Yi Zhan i6S +// Last sync with Goebish mt99xx_nrf24l01.c dated 2016-01-29 + +#if defined(MT99XX_NRF24L01_INO) + +#include "iface_nrf24l01.h" + +#define MT99XX_BIND_COUNT 928 +#define MT99XX_PACKET_PERIOD_MT 2625 +#define MT99XX_PACKET_PERIOD_YZ 3125 +#define MT99XX_INITIAL_WAIT 500 +#define MT99XX_PACKET_SIZE 9 + +#define checksum_offset rf_ch_num +#define channel_offset phase + +enum{ + // flags going to packet[6] (MT99xx, H7) + FLAG_MT_RATE1 = 0x01, // (H7 high rate) + FLAG_MT_RATE2 = 0x02, // (MT9916 only) + FLAG_MT_VIDEO = 0x10, + FLAG_MT_SNAPSHOT= 0x20, + FLAG_MT_FLIP = 0x80, +}; + +enum{ + // flags going to ?????? (Yi Zhan i6S)ROLL + BLABLA, +}; + +enum { + MT99XX_INIT = 0, + MT99XX_BIND, + MT99XX_DATA +}; + +static uint8_t __attribute__((unused)) MT99XX_calcChecksum() +{ + uint8_t result=checksum_offset; + for(uint8_t i=0; i<8; i++) + result += packet[i]; + return result; +} + +static void __attribute__((unused)) MT99XX_send_packet() +{ + static const uint8_t yz_p4_seq[] = {0xa0, 0x20, 0x60}; + static const uint8_t mys_byte[] = { + 0x01, 0x11, 0x02, 0x12, 0x03, 0x13, 0x04, 0x14, + 0x05, 0x15, 0x06, 0x16, 0x07, 0x17, 0x00, 0x10 + }; + static uint8_t yz_seq_num=0; + + if(sub_protocol != YZ) + { // MT99XX & H7 + packet[0] = convert_channel_8b_scale(THROTTLE,0x00,0xE1); // throttle + packet[1] = convert_channel_8b_scale(RUDDER ,0x00,0xE1); // rudder + packet[2] = convert_channel_8b_scale(AILERON ,0x00,0xE1); // aileron + packet[3] = convert_channel_8b_scale(ELEVATOR,0x00,0xE1); // elevator + packet[4] = convert_channel_8b_scale(AUX5,0x00,0x3F); // pitch trim (0x3f-0x20-0x00) + packet[5] = convert_channel_8b_scale(AUX6,0x00,0x3F); // roll trim (0x00-0x20-0x3f) + packet[6] = GET_FLAG( Servo_AUX1, FLAG_MT_FLIP ) + | GET_FLAG( Servo_AUX3, FLAG_MT_SNAPSHOT ) + | GET_FLAG( Servo_AUX4, FLAG_MT_VIDEO ); + if(sub_protocol==MT99) + packet[6] |= 0x40 | FLAG_MT_RATE2; + else + packet[6] |= FLAG_MT_RATE1; // max rate on H7 + // todo: mys_byte = next channel index ? + // low nibble: index in chan list ? + // high nibble: 0->start from start of list, 1->start from end of list ? + packet[7] = mys_byte[hopping_frequency_no]; + packet[8] = MT99XX_calcChecksum(); + } + else + { // YZ + packet[0] = convert_channel_8b_scale(THROTTLE,0x00,0x64); // throttle + packet[1] = convert_channel_8b_scale(RUDDER ,0x00,0x64); // rudder + packet[2] = convert_channel_8b_scale(ELEVATOR,0x00,0x64); // elevator + packet[3] = convert_channel_8b_scale(AILERON ,0x00,0x64); // aileron + if(packet_count++ >= 23) + { + yz_seq_num ++; + if(yz_seq_num > 2) + yz_seq_num = 0; + packet_count=0; + } + packet[4] = yz_p4_seq[yz_seq_num]; + packet[5] = 0x02; // expert ? (0=unarmed, 1=normal) + packet[6] = 0x80; + packet[7] = packet[0]; + for(uint8_t idx = 1; idx < MT99XX_PACKET_SIZE-2; idx++) + packet[7] += packet[idx]; + packet[8] = 0xff; + } + + NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no] + channel_offset); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); + NRF24L01_FlushTx(); + XN297_WritePayload(packet, MT99XX_PACKET_SIZE); + + hopping_frequency_no++; + if(sub_protocol == YZ) + hopping_frequency_no++; // skip every other channel + + if(hopping_frequency_no > 15) + hopping_frequency_no = 0; + + NRF24L01_SetPower(); +} + +static void __attribute__((unused)) MT99XX_init() +{ + NRF24L01_Initialize(); + NRF24L01_SetTxRxMode(TX_EN); + NRF24L01_FlushTx(); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit + NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowldgement on all data pipes + NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only + NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5 bytes address + NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x00); // no auto retransmit + if(sub_protocol == YZ) + NRF24L01_SetBitrate(NRF24L01_BR_250K); // 250Kbps (nRF24L01+ only) + else + NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps + NRF24L01_SetPower(); + XN297_SetTXAddr((uint8_t *)"\0xCC\0xCC\0xCC\0xCC\0xCC", 5); +} + +static void __attribute__((unused)) MT99XX_initialize_txid() +{ + if(sub_protocol == YZ) + { + rx_tx_addr[0] = 0x53; // test (SB id) + rx_tx_addr[1] = 0x00; + } + checksum_offset = (rx_tx_addr[0] + rx_tx_addr[1]) & 0xff; + channel_offset = (((checksum_offset & 0xf0)>>4) + (checksum_offset & 0x0f)) % 8; +} + +uint16_t MT99XX_callback() +{ + if(IS_BIND_DONE_on) + MT99XX_send_packet(); + else + { + if (bind_counter == 0) + { + rx_tx_addr[2] = 0x00; + rx_tx_addr[3] = 0xCC; + rx_tx_addr[4] = 0xCC; + // set tx address for data packets + XN297_SetTXAddr(rx_tx_addr, 5); + BIND_DONE; + } + else + { + NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no]); + NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); + NRF24L01_FlushTx(); + XN297_WritePayload(packet, MT99XX_PACKET_SIZE); // bind packet + hopping_frequency_no++; + if(sub_protocol == YZ) + hopping_frequency_no++; // skip every other channel + if(hopping_frequency_no > 15) + hopping_frequency_no = 0; + bind_counter--; + } + } + + return packet_period; +} + +uint16_t initMT99XX(void) +{ + BIND_IN_PROGRESS; // autobind protocol + bind_counter = MT99XX_BIND_COUNT; + + memcpy(hopping_frequency,"\0x02\0x48\0x0C\0x3e\0x16\0x34\0x20\0x2A,\0x2A\0x20\0x34\0x16\0x3e\0x0c\0x48\0x02",16); + + MT99XX_initialize_txid(); + MT99XX_init(); + + packet[0] = 0x20; + if(sub_protocol!=YZ) + { // MT99 & H7 + packet_period = MT99XX_PACKET_PERIOD_MT; + packet[1] = 0x14; + packet[2] = 0x03; + packet[3] = 0x25; + } + else + { // YZ + packet_period = MT99XX_PACKET_PERIOD_YZ; + packet[1] = 0x15; + packet[2] = 0x05; + packet[3] = 0x06; + } + packet[4] = rx_tx_addr[0]; // 1th byte for data state tx address + packet[5] = rx_tx_addr[1]; // 2th byte for data state tx address (always 0x00 on Yi Zhan ?) + packet[6] = 0x00; // 3th byte for data state tx address (always 0x00 ?) + packet[7] = checksum_offset; // checksum offset + packet[8] = 0xAA; // fixed + packet_count=0; + return MT99XX_INITIAL_WAIT+MT99XX_PACKET_PERIOD_MT; +} +#endif diff --git a/Multiprotocol/Multiprotocol.ino b/Multiprotocol/Multiprotocol.ino index d9a8430..e9fa9e6 100644 --- a/Multiprotocol/Multiprotocol.ino +++ b/Multiprotocol/Multiprotocol.ino @@ -419,18 +419,17 @@ static void protocol_init() remote_callback = ESKY_callback; break; #endif -// Ajout protocol -#if defined(H7_NRF24L01_INO) - case MODE_H7: - next_callback=H7_init(); - remote_callback = process_H7; +#if defined(MT99XX_NRF24L01_INO) + case MODE_MT99XX: + next_callback=initMT99XX(); + remote_callback = MT99XX_callback; break; #endif -#if defined(HM830_NRF24L01_INO) - case MODE_HM830: - next_callback=HM830_setup(); - remote_callback = HM830_callback; - break; +#if defined(MJXQ_NRF24L01_INO) + case MODE_MJXQ: + next_callback=initMJXQ(); + remote_callback = MJXQ_callback; + break; #endif } @@ -448,7 +447,12 @@ static void protocol_init() static void update_ppm_data() { #if defined(POTAR_SELECT) - if(Servo_data[AUX1]>PPM_SWITCH) { CHANGE_PROTOCOL_FLAG_on; } + if(Servo_data[AUX1]>PPM_SWITCH) { + CHANGE_PROTOCOL_FLAG_on; + tone(BUZZER, BUZZER_HTZ); + delay(BUZZER_TPS); + noTone(BUZZER); + } #endif if(IS_CHANGE_PROTOCOL_FLAG_on) { ppm_select = 10; @@ -458,7 +462,7 @@ static void update_ppm_data() { while(!IS_PPM_FLAG_on) {} // wait update_PPM_servo(); if(Servo_data[AUX1] < PPM_MAX_100) { ppm_select--; } - } // attente de la déactivation du rebind + } // attente de la d�activation du rebind } prev_protocol = ppm_select; @@ -491,7 +495,7 @@ static void update_ppm_data() { ppm_select++; } - while(Servo_data[THROTTLE] > PPM_MIN_100) { delay(100); update_PPM_servo(); } // attente de la remise des gaz à zéro (poussé à fond avec le script lua) + while(Servo_data[THROTTLE] > PPM_MIN_100) { delay(100); update_PPM_servo(); } // attente de la remise des gaz � z�ro (pouss� � fond avec le script lua) } } static void update_serial_data() @@ -561,7 +565,7 @@ static void module_reset() case MODE_DEVO: CYRF_Reset(); break; - default: // MODE_HISKY, MODE_V2X2, MODE_YD717, MODE_KN, MODE_SYMAX, MODE_SLT, MODE_CX10, MODE_CG023, MODE_BAYANG, MODE_ESKY + default: // MODE_HISKY, MODE_V2X2, MODE_YD717, MODE_KN, MODE_SYMAX, MODE_SLT, MODE_CX10, MODE_CG023, MODE_BAYANG, MODE_ESKY, MODE_MT99XX, MODE_MJXQ NRF24L01_Reset(); break; } diff --git a/Multiprotocol/Telemetry.ino b/Multiprotocol/Telemetry.ino index 48f8f2c..39555d7 100644 --- a/Multiprotocol/Telemetry.ino +++ b/Multiprotocol/Telemetry.ino @@ -37,6 +37,24 @@ void compute_RSSIdbm(){ RSSI_dBm += 65; } +void frsky_check_telemetry(uint8_t *pkt,uint8_t len) +{ + if(pkt[1] != rx_tx_addr[3] || pkt[2] != rx_tx_addr[2] || len != pkt[0] + 3) + {//only packets with the required id and packet length + for(uint8_t i=3;i<6;i++) + pktt[i]=0; + return; + } + else + { + for (uint8_t i=3;i0) + telemetry_counter=(telemetry_counter+1)%32; + } +} + void frsky_link_frame() { frame[0] = 0xFE; diff --git a/Multiprotocol/V2X2_nrf24l01.ino b/Multiprotocol/V2X2_nrf24l01.ino index d761c57..887e60e 100644 --- a/Multiprotocol/V2X2_nrf24l01.ino +++ b/Multiprotocol/V2X2_nrf24l01.ino @@ -180,13 +180,13 @@ static void __attribute__((unused)) V2X2_send_packet(uint8_t bind) //Flags2 // Channel 9 - if (Servo_data[AUX5] > PPM_SWITCH) + if (Servo_AUX5) flags2 = V2X2_FLAG_HEADLESS; // Channel 10 - if (Servo_data[AUX6] > PPM_SWITCH) + if (Servo_AUX6) flags2 |= V2X2_FLAG_MAG_CAL_X; // Channel 11 - if (Servo_data[AUX7] > PPM_SWITCH) + if (Servo_AUX7) flags2 |= V2X2_FLAG_MAG_CAL_Y; } // TX id diff --git a/Multiprotocol/_Config.h b/Multiprotocol/_Config.h index 4c58806..f0b4e61 100644 --- a/Multiprotocol/_Config.h +++ b/Multiprotocol/_Config.h @@ -35,46 +35,48 @@ //Comment a protocol to exclude it from compilation +//A7105 protocols +#define FLYSKY_A7105_INO +#define HUBSAN_A7105_INO +//CYRF6936 protocols +#define DEVO_CYRF6936_INO +#define DSM2_CYRF6936_INO +//CC2500 protocols +#define FRSKY_CC2500_INO +//#define FRSKYX_CC2500_INO +//NFR24L01 protocols #define BAYANG_NRF24L01_INO #define CG023_NRF24L01_INO #define CX10_NRF24L01_INO -#define DEVO_CYRF6936_INO -#define DSM2_CYRF6936_INO #define ESKY_NRF24L01_INO -#define FLYSKY_A7105_INO -#define FRSKY_CC2500_INO // FRSKY2way -//#define FRSKYX_CC2500_INO #define HISKY_NRF24L01_INO -#define HUBSAN_A7105_INO #define KN_NRF24L01_INO #define SLT_NRF24L01_INO #define SYMAX_NRF24L01_INO #define V2X2_NRF24L01_INO #define YD717_NRF24L01_INO - -#define H7_NRF24L01_INO -//#define HM830_NRF24L01_INO -//#define CFlie_NRF24L01_INO +#define MT99XX_NRF24L01_INO +#define MJXQ_NRF24L01_INO //Update this table to set which protocol and all associated settings are called for the corresponding dial number static const PPM_Parameters PPM_prot[15]= { -// Protocol , Sub protocol , RX_Num , Power , Auto Bind , Option - {MODE_DSM2 , DSM2 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=1 - {MODE_FLYSKY, Flysky , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=2 - {MODE_HUBSAN, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=3 - {MODE_DEVO , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=4 - {MODE_CG023 , CG023 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=5 - {MODE_CX10 , CX10_BLUE , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=6 - {MODE_HISKY , Hisky , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=7 - {MODE_V2X2 , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=8 - {MODE_YD717 , YD717 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=9 - {MODE_KN , WLTOYS , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=10 - {MODE_SYMAX , SYMAX , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=11 - {MODE_SLT , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=12 - {MODE_BAYANG, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=13 - {MODE_SYMAX , SYMAX5C , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=14 - {MODE_FRSKY , 0 , 0 , P_HIGH , NO_AUTOBIND , 0xD7 }, //Dial=15 +// Protocol Sub protocol RX_Num Power Auto Bind Option + {MODE_FLYSKY, Flysky , 0 , P_HIGH , AUTOBIND , 0 }, //Dial=1 + {MODE_HUBSAN, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=2 + {MODE_FRSKY , 0 , 0 , P_HIGH , NO_AUTOBIND , 0xD7 }, //Dial=3 + {MODE_HISKY , Hisky , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=4 + {MODE_V2X2 , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=5 + {MODE_DSM2 , DSM2 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=6 + {MODE_DEVO , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=7 + {MODE_YD717 , YD717 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=8 + {MODE_KN , WLTOYS , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=9 + {MODE_SYMAX , SYMAX , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=10 + {MODE_SLT , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=11 + {MODE_CX10 , CX10_BLUE , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=12 + {MODE_CG023 , CG023 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=13 + {MODE_BAYANG, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=14 + {MODE_SYMAX , SYMAX5C , 0 , P_HIGH , NO_AUTOBIND , 0 } //Dial=15 }; /* Available protocols and associated sub protocols: MODE_FLYSKY @@ -129,6 +131,15 @@ static const PPM_Parameters PPM_prot[15]= NONE MODE_ESKY NONE + MODE_MT99XX + MT99 + H7 + YZ + MODE_MJXQ + WLH08 + X600 + X800 + H26D RX_Num value between 0 and 15 @@ -184,14 +195,6 @@ Option value between 0 and 255. 0xD7 or 0x00 for Frsky fine tuning. AILERON, THROTTLE, RUDDER, - AUX1, - AUX2, - AUX3, - AUX4, - AUX5, - AUX6, - AUX7, - AUX8 }; #endif @@ -201,33 +204,28 @@ Option value between 0 and 255. 0xD7 or 0x00 for Frsky fine tuning. AILERON, ELEVATOR, RUDDER, - AUX1, - AUX2, - AUX3, - AUX4, - AUX5, - AUX6, - AUX7, - AUX8 -}; + }; #endif #if defined(AETR) + enum chan_order{ + AILERON =0, + ELEVATOR, + THROTTLE, + RUDDER, + }; +#endif enum chan_order{ - AILERON =0, - ELEVATOR, - THROTTLE, - RUDDER, - AUX1, + AUX1 =4, AUX2, AUX3, AUX4, AUX5, AUX6, AUX7, - AUX8 + AUX8, + AUX9 }; -#endif #define PPM_MIN_COMMAND 1250 #define PPM_SWITCH 1550 diff --git a/Multiprotocol/multiprotocol.h b/Multiprotocol/multiprotocol.h index 793645e..dcbbfbd 100644 --- a/Multiprotocol/multiprotocol.h +++ b/Multiprotocol/multiprotocol.h @@ -27,26 +27,24 @@ enum PROTOCOLS { MODE_SERIAL = 0, // Serial commands - MODE_FLYSKY = 1, // =>A7105 / FLYSKY protocol - MODE_HUBSAN = 2, // =>A7105 / HUBSAN protocol - MODE_FRSKY = 3, // =>CC2500 / FRSKY protocol - MODE_HISKY = 4, // =>NRF24L01 / HISKY protocol - MODE_V2X2 = 5, // =>NRF24L01 / V2x2 protocol - MODE_DSM2 = 6, // =>CYRF6936 / DSM2 protocol - MODE_DEVO =7, // =>CYRF6936 / DEVO protocol - MODE_YD717 = 8, // =>NRF24L01 / YD717 protocol (CX10 red pcb) - MODE_KN = 9, // =>NRF24L01 / KN protocol - MODE_SYMAX = 10, // =>NRF24L01 / SYMAX protocol - MODE_SLT = 11, // =>NRF24L01 / SLT protocol - MODE_CX10 = 12, // =>NRF24L01 / CX-10 protocol - MODE_CG023 = 13, // =>NRF24L01 / CG023 protocol - MODE_BAYANG = 14, // =>NRF24L01 / BAYANG protocol - MODE_FRSKYX = 15, // =>CC2500 / FRSKYX protocol - MODE_ESKY = 16, // =>NRF24L01 / ESKY protocol -// Ajout - MODE_H7 = 21, // =>NRF24L01 / EAchine MT99xx (H7, MT9916 ...) -// MODE_HM830 =22, // =>NRF24L01 / HM830 - MODE_CFLIE =23, // =>NRF24L01 / CFlie + MODE_FLYSKY = 1, // =>A7105 + MODE_HUBSAN = 2, // =>A7105 + MODE_FRSKY = 3, // =>CC2500 + MODE_HISKY = 4, // =>NRF24L01 + MODE_V2X2 = 5, // =>NRF24L01 + MODE_DSM2 = 6, // =>CYRF6936 + MODE_DEVO =7, // =>CYRF6936 + MODE_YD717 = 8, // =>NRF24L01 + MODE_KN = 9, // =>NRF24L01 + MODE_SYMAX = 10, // =>NRF24L01 + MODE_SLT = 11, // =>NRF24L01 + MODE_CX10 = 12, // =>NRF24L01 + MODE_CG023 = 13, // =>NRF24L01 + MODE_BAYANG = 14, // =>NRF24L01 + MODE_FRSKYX = 15, // =>CC2500 + MODE_ESKY = 16, // =>NRF24L01 + MODE_MT99XX=17, // =>NRF24L01 + MODE_MJXQ=18 // =>NRF24L01 }; enum Flysky { @@ -99,7 +97,19 @@ enum CG023 YD829 = 1, H8_3D = 2 }; - +enum MT99XX +{ + MT99 = 0, + H7 = 1, + YZ = 2 +}; +enum MJXQ +{ + WLH08 = 0, + X600 = 1, + X800 = 2, + H26D = 3 +}; #define NONE 0 #define P_HIGH 1 @@ -120,6 +130,10 @@ struct PPM_Parameters //******************* //*** Pinouts *** //******************* +#define BUZZER 19 //A5 +#define BUZZER_HTZ 440 // La clé de sol +#define BUZZER_TPS 300 + //#define BIND_pin 13 #define LED_pin 13 //Promini original led on B5 // @@ -241,6 +255,8 @@ struct PPM_Parameters #define Servo_AUX7 Servo_AUX & _BV(6) #define Servo_AUX8 Servo_AUX & _BV(7) +#define GET_FLAG(ch, mask) ( ch ? mask : 0) + //************************ //*** Power settings *** //************************ @@ -405,6 +421,8 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p -- Bayang 14 FrskyX 15 ESky 16 + MT99XX 17 + MJXQ 18 BindBit=> 0x80 1=Bind/0=No AutoBindBit=> 0x40 1=Yes /0=No RangeCheck=> 0x20 1=Yes /0=No @@ -447,6 +465,15 @@ Serial: 100000 Baud 8e2 _ xxxx xxxx p -- CG023 0 YD829 1 H8_3D 2 + sub_protocol==MT99XX + MT99 0 + H7 1 + YZ 2 + sub_protocol==MJXQ + WLH08 0 + X600 1 + X800 2 + H26D 3 Power value => 0x80 0=High/1=Low Stream[3] = option_protocol; option_protocol value is -127..127 diff --git a/Multiprotocol/nrf24l01_H7.ino b/Multiprotocol/nrf24l01_H7.ino deleted file mode 100644 index e2c9e75..0000000 --- a/Multiprotocol/nrf24l01_H7.ino +++ /dev/null @@ -1,151 +0,0 @@ -/* - This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or (at your option) any later version. - - This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. - - You should have received a copy of the GNU General Public License. If not, see . - */ - -// EAchine MT99xx (H7, MT9916 ...) TX protocol - -// Auxiliary channels: -// CH5: rate (3 pos) -// CH6: flip flag -// CH7: still camera -// CH8: video camera -// CH10: elevator trim -// CH11: aileron trim - -#if defined(H7_NRF24L01_INO) - -#include "iface_nrf24l01.h" - -static const uint8_t H7_freq[] = { - 0x02, 0x48, 0x0C, 0x3e, 0x16, 0x34, 0x20, 0x2A, - 0x2A, 0x20, 0x34, 0x16, 0x3e, 0x0c, 0x48, 0x02 -}; - -static const uint8_t H7_mys_byte[] = { - 0x01, 0x11, 0x02, 0x12, 0x03, 0x13, 0x04, 0x14, - 0x05, 0x15, 0x06, 0x16, 0x07, 0x17, 0x00, 0x10 -}; - -// flags going to packet[6] -// H7_FLAG_RATE0, // default rate, no flag -#define H7_FLAG_RATE1 0x01 -#define H7_FLAG_RATE2 0x02 -#define H7_FLAG_VIDEO 0x10 -#define H7_FLAG_SNAPSHOT 0x20 -#define H7_FLAG_FLIP 0x80 - -uint8_t H7_tx_addr[5]; - -uint8_t checksum_offset; -uint8_t channel_offset; - -#define H7_PACKET_PERIOD 2625 -#define H7_PAYPLOAD_SIZE 9 - -void H7_initTXID() { - checksum_offset = (rx_tx_addr[0] + rx_tx_addr[1]) & 0xff; - channel_offset = (((checksum_offset & 0xf0)>>4) + (checksum_offset & 0x0f)) % 8; -} - -uint16_t H7_init() { - H7_initTXID(); - NRF24L01_Reset(); - NRF24L01_Initialize(); - delay(10); - NRF24L01_FlushTx(); - for(u8 i=0; i<5; i++) { H7_tx_addr[i] = 0xCC; } - XN297_SetTXAddr(H7_tx_addr, 5); - NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // clear data ready, data sent, and retransmit - NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // no AA - NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // enable data pipe 0 only - NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5 bytes address - NRF24L01_WriteReg(NRF24L01_05_RF_CH, 0x2D); // set RF channel - NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x00);// no auto retransmit - NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, 0x09); // rx payload size (unused ?) - NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps - NRF24L01_SetPower(); - NRF24L01_Activate(0x73); - NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x00); - NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x00); - NRF24L01_ReadReg(NRF24L01_1D_FEATURE); // read reg 1D back ? - delay(150); - XN297_Configure(_BV(NRF24L01_00_EN_CRC) | _BV(NRF24L01_00_CRCO) | _BV(NRF24L01_00_PWR_UP)); - delay(100); - H7_bind(); - return H7_PACKET_PERIOD; -} - -void H7_bind() { - BIND_IN_PROGRESS; - uint8_t counter = 58; - packet[0] = 0x20; // fixed (firmware date 2014-03-25 ?) - packet[1] = 0x14; // fixed - packet[2] = 0x03; // fixed - packet[3] = 0x25; // fixed - packet[4] = rx_tx_addr[0]; // 1st byte for data phase tx address - packet[5] = rx_tx_addr[1]; // 2nd byte for data phase tx address - packet[6] = 0x00; // 3rd byte for data phase tx address (always 0x00 ?) - packet[7] = checksum_offset; // checksum offset - packet[8] = 0xAA; // fixed - while(counter--) { - for (uint8_t ch = 0; ch < 16; ch++) { - delayMicroseconds(5); - NRF24L01_WriteReg(NRF24L01_07_STATUS,0x70); - NRF24L01_FlushTx(); - NRF24L01_WriteReg(NRF24L01_05_RF_CH,H7_freq[ch]); - XN297_WritePayload(packet, H7_PAYPLOAD_SIZE); //(bind packet) - delayMicroseconds(H7_PACKET_PERIOD); - } - } - delay(15); - H7_tx_addr[0] = rx_tx_addr[0]; - H7_tx_addr[1] = rx_tx_addr[1]; - H7_tx_addr[2] = 0; - XN297_SetTXAddr(H7_tx_addr, 5); - BIND_DONE; -} - -uint8_t H7_calcChecksum() { - uint8_t result=checksum_offset; - for(uint8_t i=0; i<8; i++) { result += packet[i]; } - return result & 0xFF; -} - -void H7_WritePacket() { - static uint8_t channel=0; - packet[0] = map(Servo_data[THROTTLE], PPM_MIN, PPM_MAX, 0xE1, 0x00); - packet[1] = map(Servo_data[RUDDER], PPM_MIN, PPM_MAX, 0xE1, 0x00); - packet[2] = map(Servo_data[AILERON], PPM_MIN, PPM_MAX, 0x00, 0xE1); - packet[3] = map(Servo_data[ELEVATOR], PPM_MIN, PPM_MAX, 0x00, 0xE1); - packet[4] = map(Servo_data[AUX7], PPM_MIN, PPM_MAX, 0x3f, 0x00); // elevator trim 0x3f - 0x00 - packet[5] = map(Servo_data[AUX8], PPM_MIN, PPM_MAX, 0x3f, 0x00); // aileron trim 0x3f - 0x00 - packet[6] = 0x40; // flags (default is 0x00 on H7, 0x40 on MT9916 stock TX) - if(Servo_data[AUX2] > PPM_MAX_COMMAND) { packet[6] |= H7_FLAG_FLIP; } - - if(Servo_data[AUX1] > PPM_MAX_COMMAND) { packet[6] |= H7_FLAG_RATE2; } - else if(Servo_data[AUX1] > PPM_MIN_COMMAND) { packet[6] |= H7_FLAG_RATE1; } - - if(Servo_data[AUX5] > PPM_MAX_COMMAND) { packet[6] |= H7_FLAG_SNAPSHOT; } - if(Servo_data[AUX6] > PPM_MAX_COMMAND) { packet[6] |= H7_FLAG_VIDEO; } - packet[7] = H7_mys_byte[channel]; // looks like this byte has no importance actually - packet[8] = H7_calcChecksum(); - NRF24L01_WriteReg(NRF24L01_05_RF_CH, H7_freq[channel]+channel_offset); - NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); - NRF24L01_FlushTx(); - XN297_WritePayload(packet, H7_PAYPLOAD_SIZE); - channel++; - if(channel > 15) { channel = 0; } -} - -uint16_t process_H7() { - H7_WritePacket(); - return H7_PACKET_PERIOD; -} - -#endif diff --git a/Multiprotocol/nrf24l01_hm830.ino b/Multiprotocol/nrf24l01_hm830.ino deleted file mode 100644 index 0243695..0000000 --- a/Multiprotocol/nrf24l01_hm830.ino +++ /dev/null @@ -1,321 +0,0 @@ -/* - This project is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. - Deviation is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. - You should have received a copy of the GNU General Public License along with Deviation. If not, see . - */ - -/* This protocol is for the HM Hobby HM830 RC Paper Airplane - Protocol spec: - Channel data: - AA BB CC DD EE FF GG - AA : Throttle Min=0x00 max =0x64 - BB : - bit 0,1,2: Left/Right magnitude, bit 5 Polarity (set = right) - bit 6: Accelerate - bit 7: Right button (also the ABC Button) - CC : bit 0 seems to be impacted by the Right button - DD - EE - FF : Trim (bit 0-5: Magnitude, bit 6 polarity (set = right) - GG : Checksum (CRC8 on bytes AA-FF), init = 0xa5, poly = 0x01 -*/ - -#ifdef HM830_NRF24L01_INO - -#include "iface_nrf24l01.h" - -enum { - HM830_BIND1A = 0, - HM830_BIND2A, - HM830_BIND3A, - HM830_BIND4A, - HM830_BIND5A, - HM830_BIND6A, - HM830_BIND7A, - HM830_DATA1, - HM830_DATA2, - HM830_DATA3, - HM830_DATA4, - HM830_DATA5, - HM830_DATA6, - HM830_DATA7, - HM830_BIND1B = 0x80, - HM830_BIND2B, - HM830_BIND3B, - HM830_BIND4B, - HM830_BIND5B, - HM830_BIND6B, - HM830_BIND7B, -}; - -static const uint8_t init_vals[][2] = { - {NRF24L01_17_FIFO_STATUS, 0x00}, - {NRF24L01_16_RX_PW_P5, 0x07}, - {NRF24L01_15_RX_PW_P4, 0x07}, - {NRF24L01_14_RX_PW_P3, 0x07}, - {NRF24L01_13_RX_PW_P2, 0x07}, - {NRF24L01_12_RX_PW_P1, 0x07}, - {NRF24L01_11_RX_PW_P0, 0x07}, - {NRF24L01_0F_RX_ADDR_P5, 0xC6}, - {NRF24L01_0E_RX_ADDR_P4, 0xC5}, - {NRF24L01_0D_RX_ADDR_P3, 0xC4}, - {NRF24L01_0C_RX_ADDR_P2, 0xC3}, - {NRF24L01_09_CD, 0x00}, - {NRF24L01_08_OBSERVE_TX, 0x00}, - {NRF24L01_07_STATUS, 0x07}, -// {NRF24L01_06_RF_SETUP, 0x07}, - {NRF24L01_05_RF_CH, 0x18}, - {NRF24L01_04_SETUP_RETR, 0x3F}, - {NRF24L01_03_SETUP_AW, 0x03}, - {NRF24L01_02_EN_RXADDR, 0x3F}, - {NRF24L01_01_EN_AA, 0x3F}, - {NRF24L01_00_CONFIG, 0x0E}, -}; - -static uint8_t count; -static const uint8_t rf_ch[] = {0x08, 0x35, 0x12, 0x3f, 0x1c, 0x49, 0x26}; -static const uint8_t bind_addr[] = {0xaa, 0xbb, 0xcc, 0xdd, 0xee, 0xc2}; - -static uint8_t crc8(uint32_t result, uint8_t *data, int len) { - int polynomial = 0x01; - for(int i = 0; i < len; i++) { - result = result ^ data[i]; - for(int j = 0; j < 8; j++) { - if(result & 0x80) { result = (result << 1) ^ polynomial; } - else { result = result << 1; } - } - } - return result & 0xff; -} - -static void HM830_init() { - NRF24L01_Initialize(); - for (uint32_t i = 0; i < sizeof(init_vals) / sizeof(init_vals[0]); i++) { NRF24L01_WriteReg(init_vals[i][0], init_vals[i][1]); } - - NRF24L01_SetTxRxMode(TX_EN); - NRF24L01_SetBitrate(0); - NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, bind_addr, 5); - NRF24L01_WriteRegisterMulti(NRF24L01_0B_RX_ADDR_P1, bind_addr+1, 5); - NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, bind_addr, 5); - NRF24L01_Activate(0x73); //Enable FEATURE - NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x07); - NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x3F); - //NRF24L01_ReadReg(NRF24L01_07_STATUS) ==> 0x07 - - // Check for Beken BK2421/BK2423 chip - // It is done by using Beken specific activate code, 0x53 and checking that status register changed appropriately - // There is no harm to run it on nRF24L01 because following closing activate command changes state back even if it does something on nRF24L01 - // For detailed description of what's happening here see : http://www.inhaos.com/uploadfile/otherpic/AN0008-BK2423%20Communication%20In%20250Kbps%20Air%20Rate.pdf - NRF24L01_Activate(0x53); // magic for BK2421 bank switch -// printf("=>H377 : Trying to switch banks\n"); - if (NRF24L01_ReadReg(NRF24L01_07_STATUS) & 0x80) { -// printf("=>H377 : BK2421 detected\n"); - long nul = 0; - // Beken registers don't have such nice names, so we just mention them by their numbers - // It's all magic, eavesdropped from real transfer and not even from the data sheet - it has slightly different values - NRF24L01_WriteRegisterMulti(0x00, (uint8_t *) "\x40\x4B\x01\xE2", 4); - NRF24L01_WriteRegisterMulti(0x01, (uint8_t *) "\xC0\x4B\x00\x00", 4); - NRF24L01_WriteRegisterMulti(0x02, (uint8_t *) "\xD0\xFC\x8C\x02", 4); - NRF24L01_WriteRegisterMulti(0x03, (uint8_t *) "\xF9\x00\x39\x21", 4); - NRF24L01_WriteRegisterMulti(0x04, (uint8_t *) "\xC1\x96\x9A\x1B", 4); - NRF24L01_WriteRegisterMulti(0x05, (uint8_t *) "\x24\x06\x7F\xA6", 4); - NRF24L01_WriteRegisterMulti(0x06, (uint8_t *) &nul, 4); - NRF24L01_WriteRegisterMulti(0x07, (uint8_t *) &nul, 4); - NRF24L01_WriteRegisterMulti(0x08, (uint8_t *) &nul, 4); - NRF24L01_WriteRegisterMulti(0x09, (uint8_t *) &nul, 4); - NRF24L01_WriteRegisterMulti(0x0A, (uint8_t *) &nul, 4); - NRF24L01_WriteRegisterMulti(0x0B, (uint8_t *) &nul, 4); - NRF24L01_WriteRegisterMulti(0x0C, (uint8_t *) "\x00\x12\x73\x00", 4); - NRF24L01_WriteRegisterMulti(0x0D, (uint8_t *) "\x46\xB4\x80\x00", 4); - //NRF24L01_WriteRegisterMulti(0x0E, (uint8_t *) "\x41\x10\x04\x82\x20\x08\x08\xF2\x7D\xEF\xFF", 11); - NRF24L01_WriteRegisterMulti(0x04, (uint8_t *) "\xC7\x96\x9A\x1B", 4); - NRF24L01_WriteRegisterMulti(0x04, (uint8_t *) "\xC1\x96\x9A\x1B", 4); - } else { } // printf("=>H377 : nRF24L01 detected\n"); - //NRF24L01_ReadReg(NRF24L01_07_STATUS) ==> 0x07 - NRF24L01_Activate(0x53); // switch bank back - - NRF24L01_FlushTx(); - //NRF24L01_ReadReg(NRF24L01_07_STATUS) ==> 0x0e - NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x0e); - //NRF24L01_ReadReg(NRF24L01_00_CONFIG); ==> 0x0e - NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x0e); - NRF24L01_ReadReg(NRF24L01_01_EN_AA); // No Auto Acknoledgement -} - -static void build_bind_packet() { - for(int i = 0; i < 6; i++) { packet[i] = rx_tx_addr[i]; } - packet[6] = crc8(0xa5, packet, 6); -} - -static void build_data_packet() { - uint8_t ail_sign = 0, trim_sign = 0; - - throttle = (uint32_t)Servo_data[2] * 50 / PPM_MAX + 50; - if (throttle < 0) { throttle = 0; } - - aileron = (uint32_t)Servo_data[0] * 8 / PPM_MAX; - if (aileron < 0) { aileron = -aileron; ail_sign = 1; } - if (aileron > 7) { aileron = 7; } - - uint8_t turbo = (uint32_t)Servo_data[1] > 0 ? 1 : 0; - - uint8_t trim = ((uint32_t)Servo_data[3] * 0x1f / PPM_MAX); - if (trim < 0) { trim = -trim; trim_sign = 1; } - if (trim > 0x1f) { trim = 0x1f; } - - uint8_t rbutton = (uint32_t)Channels[4] > 0 ? 1 : 0; - packet[0] = throttle; - packet[1] = aileron; - if (ail_sign) { packet[1] |= 0x20; } - if (turbo) { packet[1] |= 0x40; } - if (rbutton) { packet[1] |= 0x80; } - packet[5] = trim; - if (trim_sign) { packet[5] |= 0x20;} - packet[6] = crc8(0xa5, packet, 6); -} - -static void send_packet_hm830() { - NRF24L01_ReadReg(NRF24L01_17_FIFO_STATUS); - NRF24L01_WritePayload(packet, 7); -} - -static uint16_t handle_binding() { - uint8_t status = NRF24L01_ReadReg(NRF24L01_07_STATUS); - if (status & 0x20) { - //Binding complete - phase = HM830_DATA1 + ((phase&0x7F)-HM830_BIND1A); - count = 0; - NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, 5); - NRF24L01_WriteRegisterMulti(NRF24L01_0B_RX_ADDR_P1, rx_tx_addr+1, 5); - NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5); - NRF24L01_FlushTx(); - build_data_packet(); - uint8_t rb = NRF24L01_ReadReg(NRF24L01_07_STATUS); //==> 0x0E - NRF24L01_WriteReg(NRF24L01_07_STATUS, rb); - rb = NRF24L01_ReadReg(NRF24L01_00_CONFIG); //==> 0x0E - NRF24L01_WriteReg(NRF24L01_00_CONFIG, rb); - send_packet_hm830(); - return 14000; - } - switch (phase) { - case HM830_BIND1A: - //Look for a Rx that is already bound - NRF24L01_SetPower(); - NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, 5); - NRF24L01_WriteRegisterMulti(NRF24L01_0B_RX_ADDR_P1, rx_tx_addr+1, 5); - NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5); - NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_ch[0]); - build_bind_packet(); - break; - case HM830_BIND1B: - //Look for a Rx that is not yet bound - NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, bind_addr, 5); - NRF24L01_WriteRegisterMulti(NRF24L01_0B_RX_ADDR_P1, bind_addr+1, 5); - NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, bind_addr, 5); - NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_ch[0]); - break; - case HM830_BIND2A: - case HM830_BIND3A: - case HM830_BIND4A: - case HM830_BIND5A: - case HM830_BIND6A: - case HM830_BIND7A: - case HM830_BIND2B: - case HM830_BIND3B: - case HM830_BIND4B: - case HM830_BIND5B: - case HM830_BIND6B: - case HM830_BIND7B: - NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_ch[(phase&0x7F)-HM830_BIND1A]); - break; - } - NRF24L01_FlushTx(); - uint8_t rb = NRF24L01_ReadReg(NRF24L01_07_STATUS); //==> 0x0E - NRF24L01_WriteReg(NRF24L01_07_STATUS, rb); - rb = NRF24L01_ReadReg(NRF24L01_00_CONFIG); //==> 0x0E - NRF24L01_WriteReg(NRF24L01_00_CONFIG, rb); - send_packet_hm830(); - phase++; - if (phase == HM830_BIND7B+1) { phase = HM830_BIND1A; } - else if (phase == HM830_BIND7A+1) { phase = HM830_BIND1B; } - return 20000; -} - -static uint16_t handle_data() { - uint8_t status = NRF24L01_ReadReg(NRF24L01_07_STATUS); - if (count <= 0 || !(status & 0x20)) { - if(count < 0 || ! (status & 0x20)) { - count = 0; - //We didn't get a response on this channel, try the next one - phase++; - if (phase-HM830_DATA1 > 6) { phase = HM830_DATA1; } - - NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_ch[0]); - NRF24L01_FlushTx(); - build_data_packet(); - uint8_t rb = NRF24L01_ReadReg(NRF24L01_07_STATUS); //==> 0x0E - NRF24L01_WriteReg(NRF24L01_07_STATUS, rb); - rb = NRF24L01_ReadReg(NRF24L01_00_CONFIG); //==> 0x0E - NRF24L01_WriteReg(NRF24L01_00_CONFIG, rb); - send_packet_hm830(); - return 14000; - } - } - build_data_packet(); - count++; - if(count == 98) { - count = -1; - NRF24L01_SetPower(); - } - uint8_t rb = NRF24L01_ReadReg(NRF24L01_07_STATUS); //==> 0x0E - NRF24L01_WriteReg(NRF24L01_07_STATUS, rb); - rb = NRF24L01_ReadReg(NRF24L01_00_CONFIG); //==> 0x0E - NRF24L01_WriteReg(NRF24L01_00_CONFIG, rb); - send_packet_hm830(); - return 20000; -} - - - -static uint32_t HM830_callback() { - if ((phase & 0x7F) < HM830_DATA1) { return handle_binding(); } - else { return handle_data(); } -} - - -static uint32_t HM830_setup(){ - count = 0; - // initialize_tx_id - - rx_tx_addr[4] = 0xee; - rx_tx_addr[5] = 0xc2; - HM830_init(); - phase = HM830_BIND1A; - - return 500; - -// CLOCK_StartTimer(50000, HM830_callback); -} - -/* -const void *HM830_Cmds(enum ProtoCmds cmd) -{ - switch(cmd) { - case PROTOCMD_INIT: initialize(); return 0; - case PROTOCMD_DEINIT: - case PROTOCMD_RESET: - CLOCK_StopTimer(); - return (void *)(NRF24L01_Reset() ? 1L : -1L); - case PROTOCMD_CHECK_AUTOBIND: return (void *)1L; // Always Autobind - case PROTOCMD_BIND: initialize(); return 0; - case PROTOCMD_NUMCHAN: return (void *) 5L; // T, A, E, R, G - case PROTOCMD_DEFAULT_NUMCHAN: return (void *)5L; - // TODO: return id correctly - case PROTOCMD_CURRENT_ID: return Model.fixed_id ? (void *)((unsigned long)Model.fixed_id) : 0; - case PROTOCMD_TELEMETRYSTATE: return (void *)(long)PROTO_TELEM_UNSUPPORTED; - default: break; - } - return 0; -} -*/ -#endif //PROTO_HAS_NRF24L01 diff --git a/README.md b/README.md index 578a7a8..a4686c6 100644 --- a/README.md +++ b/README.md @@ -9,7 +9,6 @@ Afin d'ajouter : - Un rebind hardware en PPM - La radio TARANIS (TAERB, B = rebind ;-) ) et redéclaration des radios - Un script "LUA" afin de faciliter la position des manches -- Le protocole H7 diff --git a/sync.ffs_db b/sync.ffs_db index f8a7ae005d708ebf4d1d02e67f56a37d87fff8cc..b007d3936fd7b12599fc328514befd5900170180 100644 GIT binary patch delta 576 zcmV-G0>AzI355!}2A00000-)|KL zfN%pp6Fb1BO>giY3Bf`>VRLvmu!HLozCI@$@9Xt!#})7~KF&`Ph&Lio$Rl(qA1%<# z!4yBce-ppTK#EUdEI-q{cG{A8+X}%GynJsEyGlHY@u72v0JwkF+U~xUIxpvmfb_LG z_4;TeQ9cRhF}#mhEB??%&#Sw+s1(TZuB4j3vBKTgV3GWl{e0>6o{>hrm^yETa7YYK z+#nv6(`(91)v9GyDQiqQ^a4=cozkNBuBaK(_;@=-5N&g}BW?Fr;U zz_WK;-|f3`lw>WbI~UImgZEjNN%OxfQa9!wG-_H+VoV4I{I&Ej=y^wE;4vPhaQ*>K z=+m}ClfMH(e_#AJqliZZF#^S%8PLU9gF)g(4Cv-;2b+`6h;Hu=uy{O%_)f6+E(Ub< zyTIZB80vR}#dk9FF-=Bs=N_oPGTb(xh}ZoCh1OmS^RI!`PiH)L1vT7$fx}IP5#9U) zVD%A8bY O1FZfy1_J}2A00000Cb)W# zNdSU7ys^Y>sypF5C3w$yhI+ppn%?aaE?1C4f1QqL*(pAT&7}fD=n=xSJfyFA>Xb4E z6Miv$myc#3;RQ%b*9?tM4Z*x`65>f3t`kPK6b&NSXpVExgOPuf+`b80A0G0A31G7- zCHMUxh{5e!qs-j?^O>J#r5g1L!{6r-!%U9wac`qEYS;C9{^G`gmdty0+d}kGkxWoleDllghh(Q(q19txs z#$Gh>zhH3}#^&&aDCXP-oA1xm_IWXi_Vq|BZl~Su(%Q Date: Sat, 13 Feb 2016 15:54:15 +0100 Subject: [PATCH 5/9] Ajout de protocol --- AVR8_Burn-O-Mat_2_1_2_setup.exe | Bin 0 -> 1682097 bytes Multiprotocol/A7105_joysway.ino | 164 +++++++++++ Multiprotocol/CYRF6936_SPI.ino | 3 +- Multiprotocol/CYRF6936_j6pro.ino | 277 ++++++++++++++++++ Multiprotocol/Cyrf6936_wk2x01.ino | 449 ++++++++++++++++++++++++++++ Multiprotocol/DSM2_cyrf6936.ino | 37 ++- Multiprotocol/FrSkyX_cc2500.ino | 324 ++++++++++++++++++++- Multiprotocol/FrSky_cc2500.ino | 9 +- Multiprotocol/MT99xx_nrf24l01.ino | 49 ++-- Multiprotocol/Multiprotocol.ino | 49 +++- Multiprotocol/NRF24l01_SPI.ino | 53 +++- Multiprotocol/Nrf24l01_cflie.ino | 318 ++++++++++++++++++++ Multiprotocol/Nrf24l01_fy326.ino | 234 +++++++++++++++ Multiprotocol/Nrf24l01_h377.ino | 210 +++++++++++++ Multiprotocol/Nrf24l01_hm830.ino | 267 +++++++++++++++++ Multiprotocol/Telemetry.ino | 469 ++++++++++++++++++++---------- Multiprotocol/_Config.h | 66 +++-- Multiprotocol/iface_nrf24l01.h | 15 +- Multiprotocol/multiprotocol.h | 16 +- README.md | 42 +++ sync.ffs_db | Bin 1285 -> 1464 bytes taranis_switches.png | Bin 0 -> 76943 bytes 22 files changed, 2790 insertions(+), 261 deletions(-) create mode 100644 AVR8_Burn-O-Mat_2_1_2_setup.exe create mode 100644 Multiprotocol/A7105_joysway.ino create mode 100644 Multiprotocol/CYRF6936_j6pro.ino create mode 100644 Multiprotocol/Cyrf6936_wk2x01.ino create mode 100644 Multiprotocol/Nrf24l01_cflie.ino create mode 100644 Multiprotocol/Nrf24l01_fy326.ino create mode 100644 Multiprotocol/Nrf24l01_h377.ino create mode 100644 Multiprotocol/Nrf24l01_hm830.ino create mode 100644 taranis_switches.png diff --git a/AVR8_Burn-O-Mat_2_1_2_setup.exe b/AVR8_Burn-O-Mat_2_1_2_setup.exe new file mode 100644 index 0000000000000000000000000000000000000000..5f9e431ffb4b3e8039bb8802de50e24427312d1a GIT binary patch literal 1682097 zcmd3PeSB2K)&Je>CfOtlSs);<5_M4^fPsht3w0rE3`k%hgjYeSBnITI$-RIzfsIR^ zax-pCTWx)+?W6Uj7HN$y)qqqtSx7(;LqG{HN<_4?T+|2=HW1n0_sqQ;0tJ81U%$^U zAJ~~YbLPyMGiT16IWu=|&H|4VBT14)N|quKNvcMi{#;UDJ@Qk(CP~_Em%0voE8(M? zs!h{Ax~Z~qcHy$()HOw`A1Ye1GIga=ET{fFKeb3%m8z^-nqQPUciF0pQC$)pcl{LF z|Cf0lw6(+blg%mSl?QBmEXBEA-TPe?(}<|0;TR>2WX)ERf>x--7?* zZw*q62V{E%po?-)n9A!hJwm??lH^ICM3Z!I;pODZF{6MNY&yu42RkB?Q0JDx`%Bq6ZJ)|%oP`O@l?y_Hko+_Q5!u+CTa&cDC z>XpgTZX{VJFDqWNM1HU^MQXugmz;dLaP`uOOP3bq7Z-Pv#t(H#iFz8<-a}fC1Y6d! z{1s7{o)R&l>*V}`CCUmpd&#P$EAorF3(h1>&tDfMqKDv=gadSl>II# zi2sp6sry|L3q%I>H^SaVm|}!>BeWTz)d&Y0p~VO#BW!Qb@r8}B)d*XR@U#(fBRpw@ z%|>|42%C)Xpb@$Z{Ns&qj1k^pgy}}uV8HJ+!rex=(+C4bxWfpmjqoiI=FWL<%ubi& z`e2KcB9%`jhp1V zuv9tC;+S3S1=vbeQeBoH3*^pWXIK;e6Ht{03`DG#>ansp7S&^8Jyg3o&!SGUsOBmY z3Nnv{S=B^!riJw+f>iqp6a;hU%*~t0zE@KmjI%`&vpA?GK&x{s%*isXtihaXbM{hF zSdhO%glAgSIF@NMWm&Xdte1I?#aXL#LFOMtCZ)6EPEDz0pR!#%4~d%siX|hU#w}QM zKL~-0P@TS=Vb;VhvQfb2Y$;m7_L-+z7&kv`bAGgLv9m?#$0k`!sD6@VNT$vAs7+EP zqmt3Ur#V?7E3%mPv9S43oAYBOc1W>JyOkvZgKBf6wW%cz3+tZNpyt}xK@@7Z6eU8l zRhcv^>*u_vlxGCy>l9Uj9(IJalwG1(qcr|K3N%|;9oY_LUrVqd)MCqWQ=yb9NpsMD z;UB?Yv{&ueR=SH=H+oE3I&eQ5NhXs9HKiOdg z2O}Ac>THJ%J#KNBcd3&db~b=oq0K~>7h9d*uFGO|=1iLtIqRHG*{QuTQcEOaPH~jgMv~DnC+HE)uo5nHFn+CRy9_LBv}n$F zw%E!x*vuE5+S(ZQnX|-UU29?ZbzWS1BXt0bgtUuubNQ`C0|*sSsU@;I%PtAZcldVN z1VuFFXsk4`v*;nB;A=s_9S)|M4eG#8)x>tCA(&_}h#1pBM1M!Ine}%#zblSmKZ1n* zg*2TC0{(unGY82o=^!BRALHf>3;$~xxLQ^pxf^8sTMB^FizF?>`KWE-l-GfWU8Jd&S885&*vO4oP_l3D5;` z{B>Qh;*4RV^Mho|=3p0C%QZ=gp&H~^XR%fJfqv$K#N=O-t>uSAvO{SYqM25R8b3<) zW8g}12C{5^hy(P;BBFvsMtPl5No1&x_#hH4i-Y@ci+I0vt{6eqGH%5{N1CY4{J4Ga_n(W}{A1{ET@dl=- z7}NLzi&&eQ;_yE$y6a2PU3WOlEf65|ob&VIh3sSYY1#oG`ES$(>cE+5>S4YJNZEZ3 zOZicGU9b?-f5$}Xi0m!19s3(m;lCIYtrjQ(If=_zB6I_L}R4uSpC^Bu`bXz3HN zpilDcv=+V#0+Bg&w zuDvD{BU(h7d~>Td0MBdyHBp_-TA8HAs2&Su{b;0;^(4AAJDX~C))d8?r`izoV%^Iw zP`bi()lFST76|4m_JJ>C@%K0RF4#+w>&@|!2p+=lpi1nCnkr7t!x+c8Ef#{?n>K_CU3N`aM~qSm$u6nwv~1#^_rGzHIrsJ zPD(f#DTlx-f0l*sLjoJ-DF22mCM}(PlJ+SuuOZC4%rw?f5Y||2aiTxvuCxZeg>uNm z`P;cjq{?JyX3zygBg~Gg#a0$H*ZH_jU1NoLL(-GZKCL;W%MP1d*$U&)E(A%vud-EL zXi@uV;~>wO7PSY=&jl837|M;8q>?UTmPi1fVQ<{rf+u)>$!$-#5_*{3B)!rzq~+?7@-6u>|E&27S`e)?|A7Y*3O^P z)wdN2QVhiLKY#=GIjrSJ1`ZFzj4HN)Pk8%>*$>-`^p+1YD zUJ&*k0mDRRd;OR_gZ$&p1#Z2nfQ~<-v4+P?kU-A5Ub+Hhvma|MZ&a*?3O$99Npz4c z+44Ry|6jx=HsAsLVtP&f^(Hih4HP!@hDWLU7g~_MG0bjICs~~XWs5pcd(e=CE)Xph zgs>(sZ#o|O>r};O1VWpE$EipgUmT)HzEa6nYBek971b???lO(0USgj{2eUrvye>9jeL?So zp(NQ&hWb}}@H9+Bkj6wJtUWXvx+&vaUSal4G#lKxRK4{ol{@bY`Yagl`?B44(N-G! zt__VWyGWxV`H9~V-k#DUtZZLo=C;t#t&3)tf(K0xBD(Z*xw^zXWaLVg_UB-KrNpXc1HRY7#GJ~FbpX-tt^-n~{9A=Z~aO=TuZ|$u6ev1Z?CH&Z+>sZ3~eFN%01qsJ7_%{XQ zSangmb{Ayr1zKT*(IMQzr0589wv@)OI`}ubv)xz&1^IC5+91CK;a5v9YYr9FT{V_3 zo+g=8Fz~OCN!ZDWk)D<+csK*HDTqE;4w8eFdb(AlD@czC%@XO%TE0gfRo*D~_Ncof zJ#7G(kCJ^<0W$(HaBv~RD5()f@|UB8-J>?>RZ)q5qXhJpuX!WuVhOk;pfxXu?9Z<7 zPPo-2J(9$4#_(ZYOuACY0t_GS-M#0~$Gbn;ceLq)!$*#N_WAMVFJOmwX3gYbs1#o{ zK}z!%%mcL}1ECkuiG<(7k0AF6frp;w%vI~uL+b9a=Qs9{Z?9>KSwHmbOKOep3-j3* z?_V7B%U#?3CCTlS(d|bg2eXE+9{EtWw9fJEq#WEe{9A7nt2=5R7ar zV0o>khGhW`sYd*qsX>h$hSssK76mJ-8>umO-9Y@!oikJ2SMzO*d@HlEzGDw7?&)$* zmTh4REO;2>3s`-%*6GR#Ee<2nS8G}9``RquSz#TQsH9JqdsJkb#!WRTgQm;YitLzi zQ)86ABgtpEc+6qNKITWoRui(TY#EwJ+i9tLlDg z_?G*FmCJe(nX#L!)=8>}oei_u49M%<^7LmBas(ycdVd zZtul3d6M^{L!Pwhs65K6rF$5BwMg58PYVhcn&m10Zhctp_2L7U-53w~TNA9WUI#KUg*k>b;CN#?ZnTwLG&Z+H+ zeQL#c>!|UG-hUrgEK`&-nVXxyE9N>KoaU!5phF%qSuQm1s*$-#x}@Sv<8cbA21L}{^$OVJ=zQf z(k1zw}S5Zn2PCfV-C|p zSJS>3%J({XpJ}}-`fA!grHcEy#*ONq=>77z^6eDlX2p=G2%nbv@yMei_vpBKpg3?j z=fuc}-e~%KigH%RbbNEXmguXC>*#s09@Oaop==HMMotl=#Ob8;#-NX%p`6jnf4)HL zSJ4+a8t+8QH$+R^0#gG~GizpU#M3&m5sn}GQr1`Pqb{@7Pqch96o$b>+fp@g;rs=` zP%l!=lO4mD%f@fT>V|&=oe*U9$gD8hewER*cu#IIHO zpl189i6-yZkZkjg)f8Ludx41)HM6fK)>P9`w`pyEQmh}N&`iCy{Z!leuOgB8P_doh zx`9HXrjhawA%DT;dV564KR}t=DRUmtK(qCEmn9C`Fu8mye#^$}0|fK*X4xt7?K~ah zhV``3q|lhWi2)$eSRP2;RE8KPZ1^O>PPLZMuxy(z+Y*D34clrd>z50%0Wx^GUU$q@?B6h&KX>}0eXtf6{-qKKfyJL?}n8k_huWh?NlC74*Ke> z_bPR?3Ja0r78Ipi!N}g2o@wft?dZ?{MoSCgSPD2c@@OYc5&N)t;wgM(II+udG7?!R z`1Kcv>s9;$vkn3ZXsnz8W8^_g=oVDX*8=uG*_94X=Gdv4zuR3Bmt(*IT~HELU2rDZd=FTDG~}WS zn`Gq!Vbk##2+_y@T)#`1eLm~1cDvkM)W_4Vfym0gLaP?ArH)}E18~Y(=Plxo0!`#Z zaAYH!ru*K(zolwSWPh!V<`Ff;5&8%VOKJmb7M5paF%y1^!wwsV$@fk8HAQ;LbBDtx z7m)88{ws8%JRw`2u00U@i%8^dACD=zQ%=`rO@L$tHg=OI497w|AdkqFdt}QFZQSr5 z>G5_SpCI3=4XfI%4XxUv-CFgLc5~Io+KqVbTXjh5Rkcs+Ue%;^tvaG5Rvp&jsy=`p z=I|hF-$`tijn6|17S&oh>jULsK8jXbkQC~#@#)lGm0utQ&h|2=P!qW+EVH*f;IfA3 z4?JpV)@yrzB&FftxX=ET+2`%n!UCI){I@OBK z?2Q`LLaQ3P8S54B5&RWVfQ;R(SQ&&cCdd+eZ4ucz)};IZPp+6(`J1R1e)km6s>Y_E zUf$MB(f){H-Hcya_*UNm38X&B^-X99x+JMIvHAqk`Awjw(2Ce{7f+@3lJm!==fxsV zv*kWd1w8x%LObAbkVo@kMVEA-X0epFX^%2^DeE~5SeWIpAb*;8A#yzYag>6JF$GyH z6%Bg$FZGne&}DX5E`91z3S?ccg`tq8I*VPxQb5=t)ByEkHO%*tthA~1 z&?5_&2lV^bd67%G)djRV95T^W`d@61Y~HH_8>~#O>3v*O`oGCXn(=dN7~t(cGHEi z`{Wz=K2)i;u<7lrhv@>J4YG(D{tl9vS#8re;aEZ#o&^S{UB1t0mAiUoaz7py%nSVy zH4@$f>OK$4Y&U1M^W)Sgn6GLRySJU2sHGP~73SP_egThl)NXW+b7 z2`!ihQq7U6Vg5Z7`hvv^=lLB^Mw$(NVEZII3H|CJI|yZCf>L##J7~0#K%|jC$b)iW zRzq|K5Gl22e-D-o!8EJcVUnUdQ4i~}5G#~iAQ;Z(wPPdh)~O}^#vUmhIOIV2o{~Oe z4{z*dq8ZQ1+d+iZZDgbNm3mmyL{b8h7DDyFvnbD@xmXtv)_oRH&StgGD2*8z8GC3$ z43-fOx2r9tQ+zl?V&2#$C5GL|;`}MMgODNnO|_;l|0}$5;BhZCgr55&9)xR@_81B6 z$Ov#|Gc&5X#kW3eQU>@qR(A;=wVD4N9=3T9Th*+tX|J=SOWI(yf!_w|)Ou0Eu3kVr zW4|wnQNQPRi+cDpsQ##|j@*-5G1WvB`Q^k!R+1QpZDrQW)Wo6eC71{^HhxRpYS023 zy0IdzVvflhPL%t2!!|k18}1^H_J+I4)2hhU4lM^szBZHEv@xEafELxV)em?ZMebIc zd_g>P=VK++wFFBG)Khw^u#V|yo*(TJ_I#lXDP^25fR%0rD=skEGV>i<{*Rm&m#!!0(2gc&Tl5nVGX9~ za%oPk$o&p>I^%h0P^`!#Q$u8YN*VQ?D6FhX4(m;RPxC5(g?59}1ryMq z`31g zV1j!rp!c&C{Tv#NfeAJ2J8dthw>U64HE$yc;~_v}#;k*vm~^RX#!j5rhYLMKm|5WY zN>~`Q`7T1*D|e8M;<85IQ4)zbUL?}68U6wR)yEP92l*s3*gN;waaeAa-(#N@S!0c? zNr|NM#}0|!HfIEa{AI+0h|FXjTY2M#zBtg3ZJS94G-jdzLCZQcw*KY^`8qsk=ObjS zR~n+N2)`G>%;nN7 zk3TEh!6YbE1- zzCJ6J_<%E&L1Yypt3FHgL-jHcqJ@knz8^W-QU7M5NXSp21r6rR0#FdefjyFipH)`+J+ zmg8N6Wfugw=c^wA>d?Uuq`5Ot>NS8~0}#y>P#FL{CCYd8U5HuNM@O2(f{|PY3dX>2 zdknzZ`3Ykn*m8@g1hz-ug;YFyCy>!D$v1c>q(J&j$&Up$~1!NmW zf*2=}22Jx#7%U3?;(0>xuA|B&ZKEYcM&tSKy|w9^d)$kP&%B$C^ydk3`1)=bbPc`} z$rZot|1*~afEsR5zVS{NNqCf=5WrCYE=<7>rl9TzL2pX6rPd{FrzAcy21DgFbVfC` zfyY7dh+N(d1;CSz(di^2UsCM+6BuNX(L@;k%K_x>!gF1$$Q9(CZ|WCtu?cok45MxI zJHSf6!!7vTgC%SF$Wa-0jK1@(F=HoA%AD-Z!UhcKfu7WoP`yxNn)F1hc&x@F^mYqu zhB@d4k`Ou3cfq`_4_|^TR;MnuMCSAslS%u(#Ux%`08a7m@SuIao%&6CZ##*D_Re-1 zWLgy+%_v(hgj*TG)~A@))AnVW$L8F>v6snXOZ&hxlYMaZMZKdl=FiiPn6hocvpm59 zmMJMSG5gU8;&}_^8;In0goN|;RPCqy7YI=9Blf}eG2pMS&9&hsU&!T|xeYv&_%BhG z4+r0jtqi3LfIoq~|HK2x3C^Dv%%F8hXcnGwGmcjDP5W>|5*AqdIZZhW=CKbKP6~}i zbo+W>7b=P0ipLP0$%{7aM!0{R+1Anob9Tz+ZV{I)=$WNA={Bs&PUubPj+W3WW!{2l zL-vSPy9hO(^a!H@>so}A* zL&&jg)6>75sHa?__SjMa1kc9ptx)*wBA(`pr;^d0SJz{^xLtJvZ`i_kWpA zG0XdV`u!SfC`sBiV#i-zzY8(f+HnsjeGW}2an*85eFap2^z*H|wDo@n`@Fxr;hkF# zHBEL&m0MShTK`|a%63U_%}uS+3nL^{L$U z((0G;T;q~cTW@>f!+rByn-ZQ3uOEAN*?q3BlD6G>DE^7(?{^)a{*dLPJ!kg(-1YmL z%iOM#)$RGNKmT)0+ADwG^`~X7PhS2wGG*ZU+5@f^Ql8n>>(w{En=rBY@sM}VJ==fx z%ET=uRm}5(?xB=mYJE4-@g35 zKJB+QzMHxB%e`lY+`g&o*2#^Dl}Dx9Ui_cR$v12X|HJ;}uALVq&wsWm6#s0+nWgT7 zXU}V2O#S6kAG?44m#5;7HT|r5Y*zhmy1x96=lXp4Le>p7rR=|ywR^I2PX6_GW1XX` z-}ol?t3?xbEpoCy|8~L4Ezn@IUwZtmC2Rp}8nj4lJNi)g>}~J=W%r`bysMu1Luy6L ztOs@uQd;JJvg+sEM*ri3M`1I<;3bQ%A~S073Fl2sbIc0|gESS2X#fE!dIY4__(<6G zP?BkXO2DMn})A;d+ha+B0t`B#fH8>g)2r^%Lcj+_RRfdMN)V>G%Fbc^lC`V{Lv>!HU)E zeu9TP4IJ0vVWK-{iCid1xNaLPm`q5f2+x1=V9KhsOI9pfI%Cas%TNA^@=0!DANaUz zY5w*4VAD^OPjE*WaQ!~q`4i<6-FftKF>&y^^joG}e+(p}4@CPttCy{k^RFw1**}4U z`cdG>TvAN$_g(Mr@t?ra#htl&6-43xCeIB&fy3^e_~3(hk#Wwl)hm{eQuqm4dQZJR zPZHgpB6R4A{D<%>9y1U)$Arh;Wtmsg)IPc%YK77MeO?}Dl?E+(NId(6FKUept z!PxG|e}?j>A|Dew{4m0|736*3Si@qeE@KZnz+1`DSch!%)ttGxbQlVUv1p3|em!!0 zt2JZyuZ>ankKJ?jWqD}D;s~9?v3f85avdGUsn{6tM(8<0&)=nvxhOX!za30|`_Pbv zg*YBniNnClB|0ov2iK7PGEwbz`!o=L&O*nt$lSmpAQFRc&{9dtorzW4LH-oT634b< zSP;jwiFSBD$=HZvfXKeU?u^a&?kc&2BgQI>MRgfMy^AB1mMuzNG z4~g?YpJFTI1DyNnCa2*X56*Up!%xPkuLw?kMR2a?$Fnc`zBT*4GvkaD0nwQ+cxA<* zu@BP&*aC??^AE)|ama`2d2A_NP!H?44vQ0HThxYyi|;4i&h>Pnf70b7ZzK57YA;LeRm)*vYl`w z_D4(WEdB8S=BI-BjySw=l-icfXB&h-UX)u^)yQ0XM}7C zpJz4g7}Tr#%sFX~H#|u0x&>Q7YB&vNymz5Lk$y&`bN}K? z>Y|p-?(e+e;Yuvhk8I^$Q0fhjQxerhVWjNdsvTDs@pq}Kyx|c_BGTU4$`=4iU35}a znrF`9bgE$iTf~QaSR6C*sJHaH;Y#9=4~i|O{UaOCzWA#Tqw%WLvs*4dp#w`>;SiXG zja@zn=oidqN^@uuVn7leD&Oo4rx%U)hR3eE>*1q`UY?%(cEA)w{pPLO$$6nP0K(<$ zbX(VTkGR8ZkpTRg*!*{V&f=2ahWEko zr|+k`q%kvG(h&TA2LDHS;0i>Tg0R&{r@ZL@Cd5Y|?`4G8Zi9n3r+LVJZi5JW+a}B1 zylr{%jo!9-%86~HKeQVX0*`b(-^AnbP&Itw^v!WW;STaEyGQCCA@7B8MP_ep{PfMe z5(3I8f6ne9-?O}vcyXx66ddxw+Cj+nW6LZmqj0ku4Gu&dHx)3)7i%avipsb582O!$cm$DLsI+ zFU1I&p|%bA{(j_plFMz#uXmrcqA8+rp}Uaqj!BDoM^fwFl)P>C$alYK^0v9l6r z+p^^DZ<@Vr)8!;@TTXKMKCtLbOLcdYM)Stjt{o(twa8QYCBNPCS$LT6W`q0Wb~7M+ z;qGf=tCJDKp$@;hT0N8e_Q$*>31U~{SE_^1oY+QyLkiu-LwpU0vSN~%O!*-i_#)jYnP?fO;-j<{pE z9mht$f$>9s`6Zkh-)=(ZinAT8sq7*>D2dg7#Sj+fTKrED3>3nLd@za{v|0>Wp#?z` zl*adLk+qQQcE6ue$T9U1{7Tp=$Fbol{--DrwSU!&HDH2J1HVR8Z#V=Ux_9nO@lJGj zd5pfNHJ3lGBZ#fAI5g7Hs9WC~p}ig2ZE02AaHHoH#^pwrynH>%KyAEBD~R`Ypc~#l zjUR}U2m2p>-}}_8lnbCGr^TN;c`62-c#j-MXu<7wj>Fd)1^t*nL)f1ZpkoARBDDgb z_55*wX8P(azB-HVVi)DldWHRWp~5lv@n^3AnQ}0bdhvVJG0B1pF%lxSl6;Cc&ya-m%>70(M|eM@S@p^K&@zLf>OP)-=8I zh==6A$IhkhF}N?UgMDMM+sm4W-i$rl;UA-e-aYjitDgiT`IA6L+1q3k+TKrxI7=hd z-HLtB=P^nC!_HWaZ`f8Y51)3Om6R;(_pzl1rVK z{tlfkM`T={Rog# ztVP#kn;e?}>@n=WIJnCEn;c#wy>TC}ItR#xNo?n~yOF?i@c8bFb20kqht+K-TbpZ* z;{A%7u*JuJg`N=h&b}YSJ{4wob7X`Z`~E8^u-pZmH`!D8XAF6xx+hTGa*O{-$5yZb zZ`}XSeo;L=sUQqN-6qFo1Qt@4NP1jPszeZn_elqWQAmAKPkkCetop3uS^e=j0#bK4 zUeq67p-2DY0xK-I$!I3EoUexRiIVm|mq}~I`yszqrz?=3# zH2M_UQzbg0Fxdl?n*oLs3jALvUbgcU^tw0*fmHmBz<=!QTF3_FI5ZUTZ2J>x#41F} zLdq^=hfZQ+kn*3O4Gqgbr6)Si5k2O97~Iwmb@=g`=chb$7~DVF`PjSusxHlqLia@r zKG#u@CX-e3qS_Fn&cpI-m|8J6`~kWKDjTSIB@lNE3kBc+5Y`I3Q^B2`( zX(HzLE9!P!QTLaZ>&|OOrOUwyqtbqzD?MdY`Zfk&FqCrrN~5~I6PwyA`>N*-;jFM0+`Ye+p2w}9Hr(LV{qWR*TgVm@W z<4vqJuyD&bs+lr<7vnaj@RtsuS}zt=lGE~;w+j1PUsJ{n%=XzPJV6w^Bnq_W!&v zzmPAjuivuk71WCtWZp30ZG%Zbrp5AmAe*_N`Dm$F&oU``!gYT1gln#T!ZlAn;W|EB z&erlePPk^scWL)TPq>cOPq+>iCtQ1Jx9cZd2hj=F0oqMf=3td2SQQ(riVIf72dk{X zs)S%wQn1Pvtm+c1>Kd%-8LZ@wf*$>Jt4=O>3;Fi#JVujyqndY;4yNQ49$FafXUwhC z2E9y!ul7gZDQl5c9)Q*-6tB44XaNrbtTsdoO{xTI_o-BVdpA#?3#f zo7cHd$NEuC9p3?S6E-i5vO0Hbl3E(BbGOIRYfH;xw*9x>E#%tag*wtfIAZ5MR_AVp z7#)LR*tS)NA$J9zEMU~dwhnpw94+v>Px4wwdoYxWaihV(V3;(O;yp>RJmO>NsPwj9 z>Bz{x%YTIl@&!^F^|6+KOL8or7@gDQz*$YI`UN|l>SL|=Z5Fw7ioF#vlGC!CE5Iv zZO2<+Cx_EMA&M5;{cpK8--jJonhMXpsNLdM{+;~xBD?pZNyd+5T|)Bv?vqZpZ9~kP zQY7V1gBL-r>#>N2=RjY2%s|TP`0rS(|F1x}H8G%=v0Mv!OTU(6bJg%IK@R&clKg(o z$&5y4j&0*WU)zr*eUtWV>|d3>#fuwbT+flow&nccs`Rs4wEkjsHwk#;K3h(NDePI% zEI>r(hQkV@SAaRX@fK12C&EAxM@xHo91(8 zD~@II6VL@)rpR6HRa&1TvvtdxX6+Oj(N}N&mkB61Rklr3+W0#JI#oFz#P<0BvW!I^ z363UJ3?MUjTQYRsxWj8>Dh|hd=708?vta!;vT-WR<6ZKNGjqo~hz?Cfbg*OS5Z7?ZaSW%Q zp~I0j)PXbt96FqS97r2Z(8H-5BEty*{h-Lu;m8<_=OKfUGeiioOBZC^d2v{5{d+IM z%wq9L_gLhZ^jwZ;{cmM&8f^F9&ycLViG&g4r zLiA~w9Kg$_AMyf>i2~*h;K-X7FMmylY=m3lqNJo2Oz19c=<9{sMM=S0CK<<%aQcpl z`~jm~yUAM`l$2ijk%Ycf;}NIQf|Gtz5a-|F#}IuiJ{9Yi1GbL8O?HgGSx$vi+Q&PU z?@oME5r?=1@gzWqhnVrsU`6xRaXaM(42|>JzjIZk)lWck;vw}@aDYM zt>bTzZyld54;nv09yWfMoB{l!fq&$9w>)lqzI^9+rH;k-G_mv)#l%x(_qusd0TN=jU zCqVeZrVYt&n9rT@wwshVefUOljtS4g>AnzYSm|e=m+@X@EbL+owuH;lVudhf;U2s} z)akMv;s|d^N?Nt3U6_a~@RnZ*a7VpXA zg4p!*f>)<1+Ni)5RvI>!S|6e7MjmsP+AvL&+I*4j#kYA&oaWI*gX$(b&C-nZT`nP{ zq_OM1(FPXOXPQS!s6k74pVXZJ6i)!@^7pX)3fLTLLCvY;0@b`Z7cZa0(Y0T@lRik^ z^cLWg8Xt*2f8>0V?+65+m0FV`5VMFcVksH;KK10p;g|^jT6W~kx0|~ZpP2$(hNnh) zf^DGYwH{yDf;(FXGObpQKXONTA-JHo_L-zTO22K?xWPn!0#thWGAt`8)`(IWQFdi|ym+X`BwLh#MD6(~@G%;wzDI z{)ls*JhdXuaeTa6Nz9tXWhBlsH*hyX%!oMHRf}0z!Brv_?!yX{@WmW%CS7Scem7nw zyZf2r%>{o;kd!#wM`-yB)*4Z=^1?H^f(p_+X&Ij?pP!C3YewVNVdE@`#mPsy(3A!< z;)uI_l6FeZtLW-&Ba+*QN*@adJbI~cvi#dOUq}}lTOwW&6hP)oD zSpG-2=lNl*(YWP&Cv!g!V8PJec0;%7XE^BG#^grW5dpDYgWU;B**Vp+&Q{cwS)GaN zEJbme73cnfzTG%Gj(1{AcAp2YKVZ#9J1ls6;%3;Q-$B7wNW*TIdkz~ecVl(i4x%FL zKKMS;cL``G;=#QlPFe$v5LedfI4UM*L_B=!=fWWC0c<9e!i5D^VM@VWC@eyRwC2Xs0oo;F(!?>g%+I(2B=YU?k1=W=%6I{f`+flWaigk{MeK+#oOv@h<0c8ZB5E#*v9K=^Q!*btb-QdC zHe8uek!3QXliwv%F5?^L#gaQJCf^t_lKZ%QKgN{aoQdQ?=To&>*j16;> z^J3{<7R=Tb`y!^2ejV7mdFhU#c)=2F5){VI$|D=bMBDT#in1m`Jjh#eV`Q9iqX18F zUff`>u-s_WAM4LFX>ly5VOqKRE<({VES2hb4|EhR#iXk@>-Z|Lf^q--CZ|@C(Wxmq zITm(NqiYx~nedm>eJ8hwCV+g}&~s{~AF=xA-4_tp%RX)Dzu9mtSUuwEMwA=`j(Ye# z@Jy+}@}nDW(693;O%~S&*26F;#5H4ZKG&mLyCDi(@O6_@88$v};~u4qZ-D1t$YWvA zkejI?f+_uoDI@U8rj}{&`j=Rt2ws21c6Gda1FD)(GRQfxvt_P-j)^9_jYz2jAE+|O zfeCF1Tiv_;%Q^gUedSn~G5I->BgM%{N5iTorbB zA`-n9Qj`A>OgyX{qyb9f^RkZEqvnVUyGTL2w7i2iIY19G9!ElA<)Xxdj(QX&KE89sgG}5dB_O+9Wr;5&XRD@Tp9EBEWSbsSI zk}L2HRLyq#pQ2}oZ#__J!})BaQr(FpWe0X4EtyDK1RzWr=6kgh#M*W~4d5N*{b-Q) z0^oxoQ?%vueok)LPC7o0O?^>2^oobCp_&iizP2Q6YC#i#ETIPk-#d*Az9Pye-0mx_ zgv;P(7?5=DZW3g*E8@84DjRt=%DcH!-Wiy%$Q$OHKt6&Pr9XiB6VQ*yh$8q%2g1!~ zd=5z!CKWSJxd__aVQTaKFrs2e-j8;5H1<1C1?ka!Z~HLrg2g20w&s6QMP^{0*eh z=DCtg3g;^fgf~s0KOqr2SS*M3lwL>s2qC?ul!Gou#K3zLuAm9004uB5GnnIk!^Vq+djE!d>-me?bbe9BiEj#m;yhB@MHrHb-ec`Zh57(|ahamOr>XTF$q#6D8j6d zX>dex;6H3*vDc4jatO#KUDF$Cr5xtGcg%>jHcY(3eu17khD;bFLLX3B+Jg~ipr9Xc z9p1liz}ql}>$X2h1&#*L{1GTFcDK4zi`^|7t`fr~n7=|Hm~aPCQR~|%Nbkwsg$i&& z0Jy0dQBQZ&u~0v1rhhA7!m4E}7NK6_=+zP9{Y)5b)>(MRj2=fx5+6+dUQ;&C6LhVZ zZHahK-BfhOd#a244J!KZH{1`(^b=XI^-;w&|Hc>TCyK9i?l>EH9{it&{}14QA^s=L z&cp{^Ryh>Q(67YtgvfZJ0|8MG;|*+jt*T+ zGtd_$7)E3%DSc^Vs*76Te3CFeGWJwg0+c`f8TvG*9h)#zD=&v^sPk-m=DVF{B`*MJ z%1(vy2!=L5c?si#reM+c-9Rf*l{)428L9bnB080hK#*_@ zB;XBMX9O?Fxe!Nt;<1DL6uMZ@pqHZp0=!En@NSpE3v_VEJo;j$ej*8TI$2M1=YUIi z?^*yWH+Ubl!dT;;nTKFV%@?Jqen88C?1(cW zW_}t*R}?p->6(AD*IxhZa95n$UAcxnr}EQh(w{bP5U#7oXZH>qlkvTvpT^Vt6L@-c z;4!9=6+ew@%sRbY*V2JI*Sn-?$e)e>Jq+D9IsZYUt*eVduf3-0z`yF@H5rG*N|f&p z#dLKYV}9w9dd-gVE`RAHe6i@^S@}zFw!Lyr#<^|x?ZUKQx7`X9ubAY7{d{z)ulgG; zWC%-!>_9=; zi3og^71n}`{mJh%vXrN&vKq~raey6}?!x-=sBYzAY|uH?18g6>R^mG*z7`ra(Y4{` zoQqgxLQ}?;Eb^^vw~!Ob>25FeRHVdtFK{^DE`*c`u8P@lX4>xdUWh0|v9)BzMythJ zij506-!k^#F7@QM``>6jfXL>Q8*5HkC;HmV3Wt+WGr54Tq)Hg_ILU{0qVCJ8?Ck4k z6;zJUF@3A>;I`6L!fw1vZoO*j9V&+ug`m9|qcExtUn3ly)Zqd2C$1jA>O(lkC_y6r7q9dr=)}v2w3%z0r}F2}r*Aqo2c5I2C+{X|)}mUWsqR*mt_aSHa~H+|2}s zU5Yv=>TcK>CWHEGjnbM$+Dr>#NawF35p(^ORoMx}ai~?XmtoH>9P=pA0R}|q-f_CP zA=6fuX}^ZLh8`k=+#=>7QUjNzF!kpohN<|h+k>l%ij*~SzL=Bdkjf%63TJnY{sVPx zuuHfA>L9uQK|BsX&$02LATydY6K_sKOTPeEL+x*(-l?09yJ$!U;%g!JbWLn2+9b%< z**6~ZDo;Y2@Jg!%bkWy3q&6thhiw*CY}2pj-Vpm9P4xcU{+J5^a2%^beCLKVe~Mb% z+n?DVrrsn{a~21&y%YXp$AJIUH=*!A1@L2hME-Z}r|+Azk$B^D1v>>-;oZIsy(OiK zZ-Wire^02MpVvU)q4@I{p-_6f^M@lTHH4^La-tMJq=P8qVew^>WOXzK4Mk8G@= z`9QdzF3;^^u1ykCeD6rEMH{5g_Iv|SW47a3gZD8)1M;Q9^FgB$S;u-VfVEBa1azcD^z&^UWjjgxQcO2j2z%<_K}(0=NSuXx01uCyVOOAs`%wZ3 z^*;2cA=Iz^orD^~B>b2pf=gNE1DLj>-_G#xO~NCkWLxgThH{u(E;KT#g|CL*`YG}gba?&txc?sr{XUI8_#U0S@4cEOPvRMrKR)w{!k(U-W085h&Edf3O%#lXx5 zK_`F_xRKdZG)j)qY}G==p21kxZidE%rA`NMV5xIh>f?c&f4d*VV!1m9Fj&z$>(F?T zBK|KVbjaN>fYPE^hA;+0jZj)w+UmVfVjAR*B!6jsYQYlN?Mro0k?LGs@E=$H>9!d( zo7tIZQEtP>D~j#p#ES{3Etx1UKG z3LgOahT�HV+20gRQa2>H9VFH_p%3#ipJ0ePqIJ07S01SIw7{&nFZ9#+t7Q=cnw< z4D@URZu?f}Q?9zk#&#LHiXBOQ$BJ(k)SOC6er>-q*S6NF=32MWJx_YB4L-JZQC&zkf)sbx5ua1#2$E77VdRi{T>z{0)-B zP7OsPsgw|T;WLLm4&fR>rXOx+cQ|0$^z>WqXP*e)q50@^bFlmzYf>~cL=-#F?7^}5 zv|7C>f>%%>8N^s_teIdKi=*qM1N@Wm$v0e0&J(~I^HF^9WZ!}2q;M7>O1|vagdyF1 zfwhP-e#>HZh#vvn=A%it*qp8n!q-7`{|Guq^v!16q8=@f{Pr+M&5!ZyfbT1lxsmN^ za5!q3t>%Ea&Rok5#Y)%;g8nr5>&yNv3@jq~)q6m60}GX`^KFCA{+)o`)o7v^5%`T|z1r{8A*iEN)R zQTZ~FY!^!$wAI%Zi+x8Da!6)HqPOjfqK-!#A!-}0&a)OJMO;>I%>g_W|3HZe_%I(O zTD&#q@l^an*%!1YqFQmF2OMLy5-MyKGdM z_-tS$>6@~hCFnUYUCn7#^YG?WJA7x@pU1sMdGOYr#*@Ailx;n5Vk%As>Q4a6wuppg zK;R0cykiu?gTLkuip-zPJY(o+2vR1FSKSB6A3fEj<}^^QCtJ9jbdX_DIyc$HilcT23txNP0sb3*vyB)Ee) zE3ZM#J4o$6g9g%x%AFZUS>6tuNy>-_$FN^e%|~4%4@xCY%`kUm=tn4SU+I(Z8VHdH zeS>Ez3|_V3)RRBOq~<-XrQ?80ozuOe$ZRGK1u85t9+nfBx7jk5J zvvh}o0~V2-y=bDS;52;bMYT{`$tcBgc2rDGjBIvm_*NZ|OdA*3oTJfU0o7fp<~`ZD zN|tjP2ltYFO~f7dX|sFxEp%dY>t)L6lZ2fq&!8zN$nv)0_H%P1MvuG2T|dWwI3 zfyP&Ic@6O#my6{b1Hz2PTineDnsG@OcJ}kMG_e1IxfTQ6Z*hs@u`9Zwii`0jcZd&7 zUK3mRfz9S-eB&)8az^LZXfs-=Lu;#(E)I z{1Pnj?Bw#h5Wh0_Y07OzF17x5)cR|4D7KjZ-!TB+1E8;TC!8g^P&5fr;!ESjffg-x z8;l4E&Y}Mh3N-vb+CweR(>B}Da+b3b{7d%rfJQ>oLrDm=*;i6rMTF3|+@KF*nY&55 z{mT5^l;5=@{~$KX-3^Q+zk%g6sW}H#r3s&268#SIBDN5xU0Kdn&L9G+doQ}PG`^a; zT#Kz1&1llU<8dVh9gOTQfYEtb7&kz+6b6cc8Ysu;DE)qtF-W|n6a?=@0m!UW(;T;* z%o)9x9zYUr#&Sq?Kj$lb&Qh|D0m4}^PWS= zM)a_bKK219m9$!x_pC2)i5~$ba|^zOnD?wcs(rQX{J-HhhwSU{W?Z7z5=$R%)jt*W zieAEusfcK?7_ud$%vJ*BY*eZp-qn76FNXy&l%-g%x%5wIaa(2QJa_>+f zsaJKkEe4|(>Vv>UdGMLG`$(Eam`0wO93I z=z8A9*&it0ulFBwWs@>=!>3eN-#l3L3R?$ z)d(F3b^lRk{w!+6=>}pEj(Wl<%`5zxb#SSkKln0w<6QElU!&|BgRu5{8Jjp_8>knW z1Y2np8bz-P*Yjr))0R2U;uEoA1I5nb;DhDkVF|^z!kcaO@sV&0 zZG<_7gLFMe=AQh`c=REk1z3DqLHjkU-!47wlK4amV87o zp$vcbTzu))Lg$BIMg=*R=pBCJ+&OQ4{2pNdhtfd;-UGe#p>js7i?=9ZBE>@UFQ54fPk4!FtCX2>Mk=r?Tb$rr8v?)!5d`XpMn!6(}t5b z7Ke8|Hb7#VGVg;JyvMKqlhP3ojU5t%bZ zB6H?>9+IhBN#+nj$b6C^Q$ls#@3r?ib#!yz_w)Sj|L1*w@8^H`w)S4*wXSuoYh7#D zd#g^A6FtP*3(dKf;w%YH?^{sJwTQ{D<(Bd*z0d||+4bN7@`jNKtGUFUI>qG0Qu5Hk zmrx}~Q8Jcw5H5PdxmX#K>=j2LDx_bOj9jvc=WL+vj#0uHk!=*sS|x^N2-LYZX{5DX<+^VB?wsUnAlI8!=xX>0NG}it=5t zL|PsHEx7d0#vf5%M0XUKNN{&QE0;bS;8uX-tuNLa{d(UbD_MDkQR}3BFqI@FjWftxvW0(YZKI0(z6oucC8nUu1%W`wIf4+wW3dPBg>A|OM7A(^uk(>ZxX=uC4zirTZ3k-pGN<$;CWFcw#aAZT((nk(i#fj@` zs>SPFddiyr$IZ()wF`@&o{uu|s5;^VBGYtGB`>;}0?*RK zs=+hR;$k@*@E7;}8qsahNSf4%uH2<0Zx%U}98+6eVzOzsm z6>~xK7QIm%QHlqFA-KFHGlwe6^#&I#6rndPgRUe+{sO(Qy26tw3p}+!rkH3HLWod9 zxLL)E)}r>$B;&qR2UEO&aDCFjJuZ%r{J;yo6(W~a*B-mhbj~6cB9AHIiKPg^=?>aU z;GXOd4F-9RqHhN|TOnBFk98|raX60rg?L>=x#J=SY$sG4Fcg`8N01F3Xm~@9rDcg8 zo}hb7a&X?G2=_^k>AncZXuv=20g(fqq5@dH7|o?@+j<^s6QV-JK427?jTNGY8)Wz} z4fHLtDdPDs93dcqACLy(CaXAp4VdwWXGRuiL@r|DiGeUE6b=*X+26$Afp2oWk)Deg z<1(?6$P*QG6urjI0Zbz5Ws)}dx*zB^{!Gq{% zzZ?#gV#8dt3YnJF$Ne=5`?*KauzRd)(~u9A~hp^`tJQKUX$=(YQf@q_ifc1)C-LgKmGAiS>aP!0elm!jkHBy zQKBPvyNGVJK%%?oQW-{YE(NU~Ljp%8m{WC_uwSA%Wr%g)SmVK1AI-r$6Q6W!%;l#g zpGL7n127&!#MQxZA*xz@5rhpI9&vMHHj;Le3sV%ZB)z(oMWgTiy!T>xRK6&F~XUENO;^p;=4nBE!>Av$O}oub)Ep(9f~ylbcYi zDYTtYJR2>9jR(CMaT@eYE6K|cPG0okqe(vP6K%9M_k&+a^Td%_PKhHmoE%9vq!ocH zj-nLeLSEuIk8>K(ci6*vo>+)4%ZTp4-&wQ@f9Ydh^v_vz2zOxc(}e7nXdlp$kiCQS z1m<-W{0S85e@j+LdxZZETsr$7!C&l~RPY1YX{cVjWe3|s*5J5k$`aaMNvG>YHapNS z)6o@c{&Dh)6x2U=W19=bs~qqajizDLW{;z2I{ZX~zSp{Ye5k41n zK^Wf9v%^tz1W~z*p}45-2Pq(qlz|$0cvi9h3Q0fbPDSzZP5oFGKt|j<%5-(GOk{rG zvIRJ=omh`9q~lV(v!JFBd1Rd^N4`?;vNP~LPu`Trzd6S+zFDfOL3@4FSF%qfmM;>v z@5CJf5;dmkKAzap)mgL&mskm#wE(p!iJO6~at#QEXW5{}auM!WE*+$Wr|yIeXjD*3 zDA&M;Ysz&Z8oNxiNF1c@h)-mQ+_(&c@`vSmyu}HBWrg#inW%|EVEa0KgVn>{Ve_$} z3&u7&vc#w8NTn+);1&8=90_gs9O`1fzVC$wvuN6wkZsNHH&0aapU{;CO3^)<)bk1-Sj7<%NMJd`uC zH2pdHkf_Z{bP~KNf1+GsJ@P=aZwZ5c(|fSbMev{u7glE|s*B2RE`@&@{lRvDT*MIW zl6z^5NSg-B#uU_dV5bNJjG$?h2_2qOOo)4fhihRd)p)^HlE&5uR}y(w;)BGL7z_Da zBvBL;UIx1+nS1hn{ot2Qei`$sC#A88+@!QEG9Z3vGRE>@giH3m2 z&DKayF^5;joY*R32Ms?4=rd^)EE2y3IsK4wGwJU%`jePP%KMxs6vtXNa|)arEQVs- z=xEiWY@*sv+Fc>Z14VKXcJbyk%(4i}iS5(&pht_QpiyD8mL@i)8XZ_A zn*AQlf>k3A3V>j)parRNW%^dN1(K4fCwh{BeBaC`1y?HC0l^{}`HT`oKVW|>8d;de z2~5~!%Bm2#XLN$piK=qBtnq%2!Za>+G(@Q{u!{ z++V!Fofoh~CvDLMRF2YhsZRF`>FDx6Mmm~R$4tD%moY?}Z?feOB570k>mVBMtqwWN zDt?4<;ir~dx45Py`y#R^3cXSE810J+{(@3^zYLZIxsF7X|3UYXZq*X%qz{ryxTu{* z><|sV4Il2RGp1}kZt~ZC;44Epg(u=Pj7Bx(&xvy4l<58(X$C_UP#v069iB@gmUJk- zw}`I;9nuve89pxPD9Xp`#Q`tTY>10U1Jy~VjwVXEP8H+dHdHel(v`mvWX9hbe;|dg zka)8-z|B|Iw9=-N@Fu?^ldz(WunIX|pq=h)=(DksrG2YUiJHhI$9_SiSfu_=JL zn$20~=`JLeR+u~>ePUxyXdRYwcNw7+WWnEHxGofxLX|>TM~k|`69RvNxOhB8)5I9n>mO)sL(WDOd>>1bcse-fYPd4xk0fZ z1ekj_kjN4;n?~#qS*@#y;@=P~B+jLvwMkPfhMQIV1{$nHgn5{#AtLhz2#EP(!JpJ*_$&+Sdkb=&Jjb<^{u|M2?BcA@+K&-@lyu>3X_ zY;0Q#me(Gy#B7w9=@bzx3n z3*gdxClM~KHZ6qf3wIG*0o=uKC&FCldnsIcM|Tojde`kO@F|`MOd)sm^py*Hm96faFSt6D-MJI`*v7$<&~`L66P| z|GS?|dIuc5#uGN-l-k(9*!Z6$ug-oRhFl;!U!*X^R=}LPh)Gz2q z_27Q+`@g^c-5hYa$=H#+pX*?jk7sgj{OsofKciZHXW%!amS30KjCt1b>r{Z9Ig}&& zQ@)3OTFb8s{OoJ_Nz-`4KL%I^>;iIteBe1y3RD4Fw=ib}jDSIaJ1`N51?B;(fnC5c z;2e+-JO@4k@~Ddj&>H9l&~K2$^@bY-EC5ymy8!xKfm;NW0#!gm)SZ64;aUSOfFB?P zW&sO<^}s$L6UYOKfX@KCgYp3#zz7%!xC0Y`nZPn&7jO#516~5LjZSRA}|L?1~vhQfE?fsAOgMv^wUCH(XY3} zt-T*%EeI3{1y*4J!T>zD=Pcc}VD0JWDp^II;0wW}M zc#KhcR~^qKM4A{W5WykDHzH6l#4Ff0P(U*#^0UX+0QdouzsEu2AVjba2c zXRuBZ8XYba1i4_8=kF=hB|4PuY@z~$j$tA65dqv;g$cZP5~)g7fg$0N8nOsH)>-rH zrex3=7!qa4La;#_A*>0LyoDcZ#+Ndv6q_jICH2M5tu0rjY9AyILj>j=9qud)3kaTI zF9??0bM02+>E%1cD>R^{Bqzay5fOs0Xs)enKni~F8y+eM9x90DJ#f!e10D#aAW3aq zLMHL$*oTBniU_S<^XD?N{L|B_vTY}kH?C|dQ*w`tg^+d`pWn!*bD%&FifGh8A%4;) zSScN3;3paSwUp4af)GDyK1%Vk)Zp_hQv}xBb|JpgBH>Am^q@cBAtU~oSxRpo;^kZW z-af!P%uABiHr#rkl{5OTucWh(wDG2J_|K)l-&GJ6jy+1A^SGCJ7MK>SZLO(9l2%S0 zZG-(nWbY+U4cl8)$D^jQ^!24@%Ooj()$4dalIdYyK{b7mdu*7>_+9TD6cHHc=q2=* zP4#oXp*u?|I{>GO=qWNe@!`F_#<)zQc zD=?71=Y)vjK<_(-38q*wpO7FQp>!)8AvDrZgM$9CvpZpAZ>RrJO^gh+b71z&TXr&@F0%~_85Bd#<&d6XRc2s)+r^W5c_I`Wm? zCws`TYck=!o=6WGrQug_e?;a!-b;?{lestY#xssG_hWJ2U*>)-?&(d8()?T|$gycM z_jQ;9vt+hx7+}SQ!-d=fMt~Hu0m7hot53J`yf0#^ah z*R7aog_q*`Gw>CFYGmI4T16+9{K|ljz#HHhkk44tOvd_e!NKNu+>Zfz1JoYW#>BJ# z$&Y9!o>PA2fFH07NQd~KZ1xHudO&NVAIxB7B{PkxVhx?D;3sBwSRK{FYdz?i2l-b5 z6#(j0{|lRN>n&@O@rZR?k^?`~gOe}n0>rC^0JX(`BTrQK`alQ3fhlNBWA5Abuz?Hn zn4I1#=CmDru1~xLJnLXS zbHvOEA3fWRaBV9wTmDtd%=RH&v6#IF{r!R|FSJva@7N3|Wp(=%;C>$v30MGBhreqF zlJ|N5$({$RYoE#*Z@hwJB}}F6H`ZFWlC{>UVy)YXab3mKw0Qcpnv0n({MrIKKpQ|& zRm_^`idi#U*U=O+O~h%~Ud%f75VQJS#LRY#m<@;*GwVBIhV4J*L7(EFep083#XqQE zO?yzkB6&IpP#vfpngG-ve)XfaQ3G@V7a$q=UuK8J&=n0y&UqQH>5G!`s{7`Df3Mv~ z%v|VW0Fu07v#XeHUy>*EF|H2O4k3UkKz*8Ir1p>MMQt<)m%Mr&DJ3GQ;xa-Bt0di($jW%fb`*hOutbv&A`3~9S zbQslv+Tkuh{ek*)XMl7f$%^zxV;=QasvnJ^$AIU|??^e@TnxTLPUd{8Vs2<>Y)`T| zvwlxU0>W+~PAc@yIRLwpECD!JDP|eh`Fd2-`ir)!Z!X5hN)-#Dohh!(sSfV}8fTUP z!+=%*@tb6ZKz*C!#vMol?g3wzX<8-2855R_K8EuI%mx?_#LWCX{nHWl0&%cwPTzTC z{=i6JI)Dv%b`bryA@}I^@AJ5a{=es^*S+zm#KkAI{Yj39ujhg3fEhq~p4y=gFayX1NY*GW zpI(0w-}VDgZaDA_i2V!tNwz8xhiE5R(*Y>0H-IBE%oErK`H<%SE4M4gjybn$$Dua( z3Ood;4P1eiKnuVb*a%Qq4ez z0N|7WJ9Do#Z9m_4>5F)eW&MbDx+lJp?RORs0{Q^yqaYvycn#F>UdkI&$f5W7f$p#W61D@zq8XrnKj@)4T+2fq&3>Q0uO;b!G0P$P)qfR_+`-=|fuhkU)~?a?sOKZ?JKOKtE0AYDUa!32QD+gh?uY1;t(fgO;AOK`zY zI*Fkb0QWcadwHSnWy0P(ihg#)ML!7X7A38v!f?Ah%EosIr*J4T1X` znj66WYK3xJ0NSvbmBHKEai#RP291%BN9ymT06y}`jqkhR+CLPtu2;pZ(IMIN#Cy8` z29T~_2}}h@mdMVNhD*}4hdToB2hN}mtV16N5;K#DlJH;DArAfbC1`mI6al1j&OH~i zahQL}QJ?xn8V$@3vLT;%&;m)^s2uQ(Rrh@c0iRV!#JD43K>dn^{V;j4Ky{^mRc$#{K7@6hLxp4^SV? zf57+eUzJ0Cl%_7(7b>ze%U%=xWJBZu2>^}3+kmG4^$UtCZ6`im>p$S4FNZ@H%=-c) z$maL+b&nZ5|3`xkvioWN(iLz9$gaL|Tg;j^{W*=aE^;WFbf^~k0nPcO{y)1UBP8pj zGb4b(zzX0lK<)A~?Uc4BbWcm@k6s602fV~Qc-HUo7PEGOKanRNAU`Z+HnG}h9XOR{4MOb0FkztBOTKLk8$7mYkYH_fda|3dz$|5hRn z&6CXleSqxFNZ`RUG3(a-_w@TD@^igd8tZ>aKk=6OZV|8va0K)KKi~);0;muC+y=W| zpiQTUS^s&w{)wUSjFYoJyYmo6I%*q`3S>eD`rZ^XW5}Fdhd;-c=3{IiX6G^PlHKfo z1@U_RDlW+m*~ldO3xIxrHee5=0`~y2Eqt@R>v8H;?R@_GdwB)e)eT`ocf@*~t(duO zjB(H}r=BA&>`fZ4 zsILTp_K9$30$Q&@_htb06VHF*Bk`2_?P*{NKs+bjD*zfmPk`Fs3?Ll~c>do(6z2wj*T8Y}F`8d4#B~S|jcXd;>;PJ4 zX%8DkK>*sdrSuaoX)Wvzzu-xIhyP6V;0eU2S@;x14O?c zFa{vIfM_6HnF@Ny7Jdv!*MWxN+6CARbpD35UV!e;0cQXK&=(;3&4E!O%s0A%cQgib zeX$(wGl0ffvKI^i;=ObYkzBgh2mFEEz#{;1WKhY`y&h|NM7K9U^w2mt92g8ZfM#;l z!MDY5Ujss*9H4e1nrwj8fGNhmW`G;6_W}6;@xe%f4sacwRxx=!DeW|-(tMF@v^jt^ z&=gPtWPggd(E>;(#Q+%)t>;W-_E&ZmwA1(#3g`f40Lki5fataax}gp*E?6Yo3%DN# zNxK;8_(@0Pk$!jt8AYzb#+_H2ezsZ-EYkFTnkH zzz=cSz-$(RA?XRrgcaX$(7)Gy)yvX$9axD0$oKf>M%@q8%iKyqOO8k<3nG)B1$dPV68 zzgCDZ0kL)nR|V}bMp+ZkJsJ01KsP%H{uYXvA?`Z?)Q1|B!v7xdv63|teP;??iSI=F z7Jy{BJD>@Wocz^~>PGA9?O|G=4(;bL&Eiv_zX)>h33JFFtlN(&-1Ft*TV_lFH0j|U zi#8l@)zJO}aj!vs;59lbYlnJ}%xELN+*$ZxjMc!k3j8T9D}=mUfWEj|&a^(iW(t;9 zLBmF10zftn$u`M6@%Zn4k~%EVWeR0>tg$$bX@A=f8G-&f`Ud^)EBq>8+f=a@fKoB` zCcuAn*mi6?uuIIEf5!bsTw|^#f0VDE+{tBYD})I6;t@wALd;kOw=_{zgetd>0{9Lo@ter zV~ME(FE)T&fp$5_1QaY-CT8`ZLsUs7F!xjtV6P0k#^M5oPXKKq_XRXxu4F2ZmAWs{ zu1j8_Jm~E~`yjeAAnGGPT^E34=AZJtR)wt4R=IUxYB#|ekP(LMk!bgL)~IR+tCN2L zUE>jS4(yE^7+Y?AgINWAF%)&_R>hPtZ&ij(Lu+@e34pyPwg+LGAtQ&u>ld)qx4j4b zFPPi~$a(kUh_?(+2av1}0CWJ->3=8hi1JrIN7P|I>Yspq@1+A8`(aog#}s$X1g)DP zAE$A;3Vb{J7;+)Pc<~n72_Ko#i_c7{^b1TZj3G2%G6#>7p--kjmmheJZIZiqYAT1x zz1k0RED33X5zh`=TwUQd2Ee!9>KO$6r@v6hQ)}e8q9IfH(GF*-&5#4yW5i@^nL$sT zPlH?>LVrICo?m2&mDiYj@lCAXfwwfCH@pIsoQ>tmbPO*$(KT1VY>$IJ^MYIr0?SD^ z!XC3whx#C%gKz)#PZ@a*K;HXMkLDW4y%j)XHrjiG6Q&eC*b+f~dV{WKvq2l`H8c_7 z^B@W{u+$WZ>j1zF^&gD7nW7%x#c{}|9qBx@^C;3C|M&;3$P~mHOq@xpjc_R?TnHRg2a{6VDWU%nS=lTaO0^Os1N6&ewlPDby4pk zx(6RoO3xoPOsr>HJ^(RU97>K)6zjy3*dinPD=sFNmu9s*1#lSF|Y$T z0h|NQ1DU`PU;{7{@Bn%N%>c;cf81ZGk5IbSz)&CoI11e1&Liluo>3>n^nYtkLPfkuEL@K1j7h(vYn4idt_J(R0agnQ^>d9Ys|NSKMUswK54Zts0TqDi_PZaIP5svrSj=Xfy}_NUVcjKXYOuaT=V=s2 z@n>m-S(0-!D4)*I)S>a9KGtQD_<0V;8=RX_*nA54g#w)c;_I(yAioBH6=NM!QO}3W zYg##*GQEm9#bfWp9(lKf{f_IY0J&oTKR~`6_VGZMAMAk~*epXX@cVHbUs_bMfd@Y# z-&`OHAR34dvOg+Y4WPD4hFSMmayCSkum9OKo&A6YLVj3ZJ5SvO?Z?p&0=F$7D-Y0b z+f~nDe;&IS!WwYgaG1JctJ3!%1K? zKr%_~O?7VwxC4IxU%0suooz5hI3GU7RE9Pwjxd$?diGgsTh8 z16}~cA3iS4qo`irf0Jh=`~!i;Ku5qHC26r#;38;xf zd&^X}4Zq2g_}?6$edLXBKLOuBvuqyH>#qp=d9Q}*2|dZ;0Vm)BKr~6xL&ssl%2bh` z!oFYU*#I`E2g+7M-Xw#xhElKIpW|*hCecNZsp|Z>a^B;9Jum@)UYDK^P((ahpWDID zpSUN~rF6--v=^Fjmfr{MIIMQwu;Z0M6XqdLL6**?2Tw90nqQ$3RWnGw4$8 z3Hi5he^dXT>%!+t`)D3fVoZ(rwR&1Fptk8y1f4w&ahmb*__Q=;odu=>)D|R{l5i`y z{s8nS?dw(hOT*z(-zQMJF9wfm@8Qwj9j$e(0#*X<04CTnc~N`Q*c}Z#0c6T=jd-R& zJm1HERX!(g$dmNWN#Iv~pY}*;4WV%+<}A;U-&EQ1ss332jnNMP8U9mSX#iLU{aybj znSKXs0Z9JH9qulhKYtwpe@xK1aT^K+xZ)b(rcqOKaLxnZzrSWJD6cK*Pn-8P@z6%%(oCJuTns~Igg2e=GUq#kmdQE#NVSqKz z0w6u5rB#z&8t*OqvC#Qb-h9|=_$>ttfVIF|peEjmN4N&RsGhR^(reOxO93yS2apJx zLmDP^4UPG|PBx@=7@4v602+&F3<#6llRqE#f4Vn7YySs87mX1(D8=iP>iT^_IVXT2 z0NEYZz#-rxz?Xl9bVhajzrU_mA8R=Mux_>-?SS=>z2apU*1!%pM^l#HD{w$X<+-Tf~0uunud$Q$| z9Ypdr0;mtrk9g1@*bI4ng0K1K|r*M_9hE(?*zit;q{xp7IjBK!k+LY{zEr2aR zHjixCxaEGz_}d;w&jPu%#lGSai~&DzRES?wq_rwN$`|WYw3bNi%&jB7ZfweG>_p}b?1JD{+3d*GQuLC9g+Lz)se%(vn5E<74{;J-! zXgZ9z3+qBnv}1LO?IEhMP?N|n7h`5L`e}z}Sf_=(+=KedD@@ml7+Z4_)6|pT1!OFJ zBK-Se3sf5}wd=3i8{U8Q8;LZut`mv1BW_KnCwS@vlMOOTYdP1TL%4OE+58%gk~hD8 zf?fr#zNo-*g|w_GFx`7!DgB;~1THTv$-aI+}fEirubb-GRmms*3_p`=^Pr z$1|B{p<@H)C^<6JnZ?yo*Xd=^A&IC<`GycfUP@j2ljj};yg)D?0e0u zWKC?)*Vrt8%8;!G@oofDG0JAqndQuEEcP3bm#pn*0ULA3MA$?qrwi;C=@?p12YW|# zV6RNZKASV~j>?Dvz$@-Yb}8cLO937%L+9@#|r&{AVM78oS#ABY|x+o*=#~0@qea?uk#g00)5N_cp+X zsSf1z|G8TE6a5azSEGXG(^-rMvU#`F#hfHd)(<+G+ZPRki}8kNQ2_Lz%Q2n}Azd#+ zpV=~uhoIRNx_|Y3w6k?hxOx+uE5R5Xvc1NS=f_&)kq8jK5Y_^i4q)6;S|J-3<7+GI z-I-$ShTPX{%7?W>U1zSv8KKAgxGz5i{%xh{sGSc1ser_Wu7@zl84mX{t!QaH-W@#- z?Y9~B!5r8Puk+#*a&Iht)JAN^2eCL?dyJmEAelD{o4pUFHt0o$GdLO3!9KP z**COCGKqL0O#|1KA_cosnv(FL;!_nq=paOXi-UEw(W&n-qCpH$c&<<;F<6%o%BAq(q+Yx>=C(#Fb zA*>Dh@Nm#BM4Z-ik88ztWT#VGjtA-kvOn;t!62qQdOtJ#`i?cheyTb0YKn9kAJE@! z^LfkV;OqcsZ(0a{5&8kb>lIYNJ}zg9W|VgT02}XDKPy!n4eig=Uaw?IS01ot6=h8Q zgJj=!CGvs%&^fMpD38`ipX)Ok!{xsTXpnC(Y$=T)dRw1nh{edKey{ zzt2WuA32%H-P!^(e>-&88chFZ;th}c2K z0Yv(*Kxs3PPZ9DfWeqGTZyLO4QlbO=2X+|jOU|y}%v6Rwz%`8}AAw@vBK9Ju!qoxf zf!aUR73;2K|ERR&ZJ!a|yxrq~^O9uqB;@|!?Hz8;Bx~z{|1F`9RlXq)#Qg=-wa_1r z!uD~e@Tb5Kfasun{5Tt9%DJEI3+mfsSLC9fNb@9ng1^27R|lZJoComdWb%uo;rv<{ z*$p!RY5E!$^2Cj^kOOY73VI2BPj>vyK{^_@Nxw+b(Rj@yx{O~VpMfywSm-$UMd+`a zYT{a9?8P^ySPM!6`kJ=j&&1W7R};aX#z}8z1JTCoe!PH2(_SNT<^|C{CXfuQ**!GDJTE;4Zf=LwhtfKnsj5%iy{JG*-}B4PEyH__g&U zxX_*44{`_{+9a=l)1S0{M!M4+d?vkVP501g`nV^3$)B^TrO&z{k5k4>>E=$R{NgQ^ zu(4J#4Q1&7CsEfs-b!qDfk-*e_t*% z82$om4+yY4C=H9iU8jGXhaYkaL7qb78H}8Cun8K%T~mpCX_TY(KhDvY%k4i&L1hP_ zjDKEpX&JnpLaMmQESTa0?j^%5zfgN)jb&T1fZrV zHoOGLhh)qfSJB9e=Q711U%qbAd{trClB7=J%8Ece0&xtfb~^-1+8_*ZeGrr6EtKPx zqooFy!xS!;0IoDDnQ9S(@`+QLpowZmvaW;l{&0P`5^H$L^GUWxgg_D~oR{)Qq^wQV zU&}ww!!VRg@F*79tP6g=_Pq9tNfmjl;LT>(`LI{)A5x#sIP=6wMk?P8DE=2@# zmC~t+-bgi*b8!W<5Z9}WmNozndOnr`Y2gyCjCSNzc{(ODaI6v~& z1m{BWk2E-OQ%Z*p%8+UVW3)JxPCc1;C_5Vbtl4<|K{Sx|2|~Vnj@}YVA~}xuBahlT zumzS%NL$qQCtbnk%Dc5`__KDT5rX(leUsO%ysS_kr8eUGUpQjW-JfN%cKSc}I9(k5 z{<#d&ctW%{ah=Mc5iyXHDCtNUj@BSP*R-NywN6vQvLaDTt=qX4uX#zOmZZ8+Kj$?L z^%^RXYN^9a&;$D5p$lFQ5p5)?lwTOAXi_UrUh1foXmq8qhd3|IyQNIaQ+`AN-->+v z+Weu?sJv)s>Dqj$Z7mS3HSyd2DSk~DuZ?L8h(a0~cc}inmZ!eJYngCpb?OUzO=;{2 zL@Y}4=iU(|F{B(V6>v0__@)592+*?>uvAASD{y^*T)K~jYsZztyMbJI1bC(ZT|j+L z0ezLYtiZ|c6u8##_o+76R3zm@aJffgVV^HA47pNy(U|)4CDZ7kBq^OnMkxh~5()&^ zbR${8fbtPsX2PYZD%h#MQja8Qe*K&wiFYu2$fxG-R3v$XBRz$xO7aRuj#9rml6*;C zrFrlr@OO12ACyVV$G_ck@QM(4qi$=QuD zmB2gr%mlGCOIBn?*tVeAGQ9;5u8!mm6KQ#-tVx5E{hHoQ>9Izs*l$2oP@oPzzf7+_H`g^bFw)f#1p9>e;#KzMx+7f%>G#&v2^Zo! z0A7J1!2)yLXhFE{fd2K=`gw(i3xd1@qjiu$aJac{L|Cv{xR1Xe$SYhwD8MHyBs|1V zsE@Z*n|Xx?8B8(O)xp;U0{rmqYsrh&`O@mC>EOrZK@q3)_}iR%=*kvv>x;LO2MDA2 ze1h=~b#q-iCjeQ1%%S)tozq|$)=y7tUnhGZ|etbKG8@-RYXGGM`$VG zoFsq?lydXu>QE5|u&Jxz>FOniL&jD7uT6&r}x=tp=>06)9Pgb-IL zLt^2dIaK4zak8H<3~w^07vuj!x#OgT%RXG-6M=77NZW(+3lmI^fJ6#>YhH^k(<(nl zv57(k)a>^7TzQ~QApJGh^$NEQo`SD2gy~Xj=`SL{(#Hoc{x{e4^9l?XaFQbp>u31; zQu`UoP}$G0y0Rb&9S*(2%quh$EcfEXPr^4o03wPne9^Z+gy_5BQug=@g`sAKhLWCX zP~9^P&@&C49c&G|8yT4zO2kH*n0i<>xxS$RmXTgzg8raJfaZ|iN?Yxh#S_7XzoM9Y zdBuS!j+Ty=*4DPe29F*sx%jL5m_YC5Sj3FSS)G){p{(iGH%cd8e-xJ)%>&!i)7T{PBrxHS3t`N3UtOLT3jEWaOiTN0+I8Xsa7 zIPScQQsIt{nrdS=EE#d)l%Q1q#@lZti$67)vwfpMz_${c$EBCP=;o|we#Pz6$VDUd z9KF*X8tApRoAz}24b2-lWo`WjMK9<$Gb_CQ~Dsen>MvOxOc^ey_b}|S0$(3`>wt*MWoki>4CB43;KFZ>z-n@rCc0ma@k|@CXeo+ z-e=X_wR3yE`_}i<%aokJHSdG+3OecswlO)}{cPj*_fBt_ce>N}7^ig)I*dCNG=Tk4 zCwSe!4)u4<)y~Pc3D9{y_vNOp$B*j{IK91@MWYT?yNjIH&D%GkZpfW+Re9$}ta^}M z{BIc&qwdiPFJD^D@SN}JU0*|f)V;6KZrx|4YG;}sW6PFo z-QumR5%sm+^a5KY2hrq!9&*|a4<_7Q-=V%;>YeNm@s7p?t%q!{Yh`gSaaO|eM@oa& zJEmRt(Pe);&z^Pkqu+y$H`{GrzT<=c=s%8G=9%S%wA1oEH`QZx#g?&aymp6|ZcF-b z)m}SY;9Qk|v~iljN7kxgYT)CbAFDk^uU~9(^WcoEVJ1)N+!DY0l)I_;A3oixQn&F4gLcbav~|}{x-l|ZN%2ct zgPgSU20h&`3@cxMByswJud^<+O`6efx~HwPUE8J+V*9D9qYc+=`m}RlyUQEfG#p^! zzdxnP8WsJbp@(#}0&Xj=e`1&&?RC7%;jkBqO;cm+wLFb}Oir9&yt(Is0SB$OPPm)o zGrz0tnZ(s^&IZh0obt%!+nkWZ<#k%M2^;<>af*gcBgKQBAA8=su6Mvh{iWu`38D}k zjf*9@a&Hbt&aS_5$$`$=V#h~^)3)yD)$B*rd9$sJ(zJyYc8&IYS@FlXR=su>ZkuJI z{Bm~M92Wera#i4*gcjD_cGrKiGVa*w&#K!h_8l5O+&E>F?~FvfqmPzlIz6m+PW0Kx zNVrU_AJxODvq8(at^@SzsUH3~;O@6rt3=axcdmMRDNY`Kbj-6j)+Q#b$>e7{LZ2=U z8>{s_a?Yu@3+5@j9oqZoofh$VC)(UP`l0vaZ<-H3+8m5}xPNx(d85pby~TOUTm|QJ zCqKwCO8t;=r*pr2CGT^`+Sp#mn4U4&>X@)i*V6d24U<|p9&$}tynbZUPxklM_c-96 zqmkOdb=uJn=VCJD+kS8N*z0KBl#VxguD9_%HQise((_XEDC_CFXO%`gN$?z$fByJ{ zWA0aSii}%Z=67!t8(r2!^dPJ0qx#!MA9wK>J)+c7wfvfBa?!(~Z&h~p9edn%-P4}q z52kcIDc%*o>gL)5M{ZZ8u9iD&Hl*7?dvh(r2d@JiBDaQYnpC(@)TGnMfTi2EwzApn zH9l#~O4qv$l>$wjtsBXAS+6&JdcfM73hAAVFDa$!KfDy^b!Ay>vwNcphjjkl(IaZU z@#yY8&eMu-?ObJcbBX%WX?q{`ihUk4t#regAcv2N8{R8B*j_#N_HEa^gpFNyKtm3KNb9MifX@hcmG(CGe&pTjd$&8m<<6HQzWJN7pBif&J@3SW2 z-J?VEpBH`Ae)nlhFNYPYw|u$sp@~It!+me!M|oU#=^*Z(oU=-MWcX`Q@0GjM=Kj&n zvhmYX(LVQkDt>tO;M9&t&1JjH9(%TXXJRo;KiAGRaOd8pYm|-qKb@Md^I>?~X{}lq z*-tJM9NnJYq~-Va$BnxrwcNDi_+z6@zJKViSsi{dx7ktO*hd|&%-d~qAyjPCS#ZV6 zBmdm^Lj$r5to9$j-%MU%%Kk8~l!ZM#MjhM#xKE^oaKtLxf+m7VRHsZ9=1f9dS;a_q+um)txP3L9pxFzu&5(dOXD9bH@% z99r*xRitY+bg{FgkKgb~*0z0)_?$Fu`RZx!4~36?)5>O?>ak|fNRK=v>$p1)=lHzx zyw!BkZmUCvV>(+**dp}KbJZ{pn=+@>wbTXIrWU)$n_o7*VUd`kx%+#)V^0(YCGS`l zdGWZv*`4x?>(&Q096O@bukUxEt}!|3}NdPllbk{${hT$BLO+BMgpjdVI-K6XLVqV^RyK4WOEd@pK{bw2ORNR$+ z@36eU^M;Sj@)c8d_pH-6vf=7GPlbW*G3kacUa7A=5#L1N(TX%VITb6dAsq~JcW2h= zeXW7YqwH6g9&hY@W9u8Yl{Z^ucmGuN>_E$9KVIK^EVq68r1^U;j(HHVy;Z=hq}?xy z6qSs#TBnLrrWw39HtO~ce}4R)c9yOr8}al&(4p0c>C(+5VwszLK z%kwRsbulsw(V3y#TC_YeaO3Ft5&JHc2TdM7)}pg@{T2aH^9y40hjczQ`c(Ti-UjDR zBv)9RF?DYv=y9}Oq`{95U2n>Do1>vI)oW>0RPjpP*gj(xcn*kLc>nvreQ@vO zV>|6jyDyjOk7)A1>e9;3_cRigt_uA)T4DC4OD)D#%B$uy+R|%Hwwm(zW@qMiiqGCP zdauRE#BY^;>L1p1TlnGGZR>kahfWquz2v^`d1j{ms-e#NW5?KtA7`9CJ-V#5oS&Th z%~e^W=8bXLR=Rjld+(Cz=Nfol8F(!uZkl$NrT6_y?st2x=@JvDzuC1zm{sFVCr*rw zzjF7K+pfr%`I#5X$2=GM4WBr6r9;=XJ|UtdIMeCuKQT{ zAz|K=QLD1sD6Lbj@_yDW|Kd{fgWta&pYn2loeR-H9#eL>M%=x*tH-ex6FR?(8v4a6 zJ2Bo})Vbx4qNKHsQ8R5%XO#_Z(P!Jbwjrl`=BcFbp0s=6n979BhZk>m$(_5zD(HqN zI#1oE{BFM$Lte+6d|_*MWPnD&xwvM|23oP!-E=z~xvuU%W$q*=;cA-+qTVr9aX!xW z_b;kPROP6DS$DLa*6CBZYDQzN^YV5J+}$SSeoxsoKm7T?RyUWvG2FahVmI|1)1^0D z$`X%`%^tb8-t}RsVZOz_KB*=VCh9{6y$DuG@0h5#fFTExM zy^b0tPc~3fn0WcK#=!3HDpU*4TW(zIaK<*t{7#_9r(6AUUS6~_8M!k2URU*v>;2qD zq|KaB)G^zw$&LZ4YSVjW7o8ZCd3lM3r`zW68+KJ=##&t&kREYswqe-pi6O)6&f9M7 zK5Sa9@BWGd##VX?3%lDcO5OVC-rXiCNjaUr*WYqjZRO=No{CrYH53KSu{>{edd9-! zEO({YucH=zGCyWk|4bK~KTMZQGPQj^@$>A5e$NB4w3IvUe4aDb|3F*qke2rg#uu!aWzn~Ap`W3FS=!*8 z;jF5>?wH5{Ui+QyEL*uFb*_4+TbaX`JUf3eyj^cSyR!{FLOc=-cH3<{uu9iE*2ck4 zchTIj_3P>n-|HT6egFKfE!>Qg&w55Jy~XxDII`b$)yO6`7l#~(o6<`Ebif&dZ5vV_ zt=jW2UA6N^rPr6zR)vMH-oK;e+FhOJ_UqH(&>O|QhKnQ6{4l>&asFDLdxy@i@N7Lj+Gmo& znUdzlNn`XDm=^Y&sJw8(!y8sF)4%RiIG?%ZZT+TmMp<5Hk#PT2#bU#wr|e$s+P~o3 z<`$aI4>mbv->*-1laN(PgIk+55{Fj3aLR2^+F{Xz=Fg}0(Y6g;^XT5g!%Oa|=w3bj zu5Mi0HB(Z}Cha_StW%TElP_;o+hZRRIs4__qjOFja*h9x-}&St=Yys*i}HG}TyJaJ z;-h`pBdw!<+=_2&I#MZjQ*xQ_wn^(EvL{$K(=C{~X2G2Ri>Mm`FNW`m-FM^Z{2gVg zJy+kD=I`Ott@G$=ndyH zKdKg8*(^SHXuH2n!rlY9hG9$ZSkIpMV%(I7yCIk7c3E58_4>stkLzx#Up&q9-F@M? zc*<~I(ui?n@_s&_>o7(E8h#( zRh;fz@3HjCh_$9`r#i1p9p&ciI%lQknkFx=T`^1&>~tGE|44@QoE{NVS*ic1*sI^e zbOYC9tXEjpSuydGyoN~eS=sk(1}q{mOKzv%?Pgno9v+|lrsdi%qix6Ec@ndydEaZA zQPa2TSuDRbtU%j8=KbiIcI`*M{it~1VN>}x%}$uT>L1zTLczW5Uu>0!E|H6FqByn7 z=eC{hpD(?2_UOs(56hkpY89}_bJFz1%OB4*&Pn=`=3cM${&{-0=UJsUv-;3Q`B)>x zTUo;fKYr!c$@hg|$Cvc2^G?lLIC`h6?D6xd+LBo9U5IP>UVYH z$Mdr%z#671@0aj{RTZMPzwG!C$~tson2P8$=K&hj+RC? zU2-DfQU5h#GUO&y?celHd-Itlll8v!oLSs!NY$zi*L#FMz5D9O(T@SUJSQhzYt!9r z%!{5D1JkqZyNo&=rx6`+uwl~mXq&_9#%0P`C1|`l7HIL-J@ZY|M*dgzcaGYo(ce0y z%zH+O%ibTV6CAE4x9bwT#%5sCao?8Bv|8W3#gyZF_nJ(4nrnD-(etj|>Q{cMR7g+r zeqw3dGivsWbIWG$iMG~@c|GfkrR(OUnoSOLPl8*>y883)lX~F!zy@Uw?mfdH+vS#XO8K9*tAc$amcRvqsCma_5Q5Y=-u^05%;w` zhjr}VVs6n(-O|2Q-&)?uuxPP1?$`u#i_gNO`%6vIzqHrt+d}EC_TXKO?>h_h6k@LT z7ms!lybPby-_Cs1O%2WcarbBYckCr-zDn!m#I387ch2_KYMb+EsokADxw#r!H@JrH z&%e~Mnb-5l^Bu?kQDnKbVrGc1Q{%9u4)LG-pFg?2QTx!hE}kLd+IBqaJs>qB_1%D= zxbQO-F&3kixlL+gt{gGolS6OM+=kj!?s1{>$ErLl8FO@n_O{e<=ic_X>$*Scvu(wb zl12}lM{fw+-t>@~V#>%72WFaWY_A#KsQa@$;j_$4M5?DRB(!X}eC`&rfe}%f1I05g zx4rg2<#WQiimN8?mybDjILT6ApmRO*nog_zb%GWxnCo|CxJqt*mYVvI!{0BwFx!!O zc1uaN+p?&*lqD*k4{i}W`jWbSrrW~%y9<||5%tu4ou;UG`g`*}qP8<0oKD#1b3Ww+ zQyK3Z_xaI5rTEr4VZyCnGTn3ApK5p8vf62;r@5??PKR+eKeA$k3NfoR6HJ)X0>f|n^ z7T=HkNcz#cZrKDEi@b40v72@Z)Eck$Jj7&!X_$F?CP&9b$X*j803dd*&;%8-%&d-|iK=tW~{*%g@1f{7GpXRg67j_q3R_lgKN8bna5LWvRdG$)Mr(cFqAvf&;lcVz zw>DfZGCBQVz&Nkv?dqkzX@A^s&#EJX?yQ(Rq3if4w?B${Kd9Hh*6;qwJDr`4=Dc0G zV^Gp%<#Rj7ceZKJXhu{$o8AeQ&OdhNb}NeS*5;#p!pMO$?;Y>5s`Z^$>snk@a(!j( z(m*@R@bbXZZFElU`Ct%uY4B%J%WaoZ$8qyCHMrRntYQFFgCb@a0Ki@Gfz9I_$e>=tExo#nGaz62n)lOHEr*dGAp>A(e}}c@=xWbSv+HQKfK%DEmE$yp(FU;toc`5$pfN6&As)GF!mRWTVzqn+s!n(kTofjv$ zZ@Z~I@5O}H`33LaT$moTu`!-$)XnItS$zD~%9b~kr-dY4^bz-1yyW$Umz5_p&n}DI zkZ3;XxZ;$_Cyph>*|&=~{&uo-fuYv!X<-J3Eln#;d!NktdTiRq@#R^~yc@nY|EyKA z!tm*p$cM@+PtDF0zU>+9F6(}a%Avk(07*zMS$+d-~LvH8u{w%@kez5m-7 z!;`@*@b&zQZ;P$F=#`aR{*rpz%}VLp#(O6f3`NEJ-q+Qf(5vuJigU`Iv0HY|%w5^n zv$-QvxY#f2-NXL}BS750syES+*x-A$S3#aL_YEJS&5>MxqMUWTc8q>;G0(bl@0_np zPY7+%kv;IcNQ(rWh_KY}^TA2gtCUp8X9f1-mO!5>=ndo}dVRnHig8IIPi$raVQ|~- zv1x1gau@|jX;>r5k*>{;=FRVLycfE(N%sZJxEN_6FjMYcwLLSX9Up%Rf8z5PqfGM# zqvzjRV0+e;PI)o3u;?PYCUMO340YRDv}I2xd@)DACDm!3k?rGx?>K6Ey-e3WNF?6rUGojxoxo`K-jGUpndbcvNScmPrnMtSrr{uc^9wGe1n@z-j1TFb)SW z-%2(U)~li27U_Tn9@2t}XVD!Dgky z*P6M5gIc;sEQ{02C8yLQK+X#w^3#TNjVZhNNCNRwuuZI6F*Xv90^sfb0Yeq7eof;b z3`M#w&deZ84ApH({hL5bVXj^C?@V}sPSM=+YJn}tVxD#(1HcvHZWzfxx0#o;n;}4R zk?qW6xZg?nb758Z7g{9sjNcp=6=WT#u-=%HT|^@ELYhLNGO*iu9036d^un&^(QuHn zJ!zdph(v@;=HpsZWsCbkC_acee+tmcteu`cLIur+TQR)~-fPwJ+)9%HA&J8BX_0t1Izi1aYt z;*o6x=&!RM$Egt z6o@<4EaCOBN|v_RRs~nCpc_4P@ah$9VC$<|p1)>EKU6%4e>%Ng<#@;BDnFKeW&@*W z*#c^NezKv>{-i~Wc;OYLZJtXjeEQ%!C^GU z^CzTN;D~P(yg4VMgbX-LG!ibS_e|vSyHuFbD_S;z1(#tMS zYBH!BVEG%k8%C~=_xlmOahbFBIe8y2?gofo1c>}C#<3PP`7&Dj&<46x4N$$4^~sNI ztD{~E6yxENlmie0WW!xOTVb*ax_|2(JX85__6UE>)0=|>`SH8wFE7$UH>vDPS6(c`_5%>~a(+WB0>ug-|d&1$w1?442x9B;+ z80j$B{QEy75JmyHKc0RiNn1;9y*jXZeK(PC#X-Y-m9 zqCTBTu8e7dC|4wxg^UjJJ&+7PpIdNtXTp@T_-C*XVK|#mP&{ilGp*8KAUkT>vZgY4 zD(nl8n*LnWvvq?wz-Q@1@1vslfBVPdcao0p$S^w0JxH(5ctB&Cjt3OH#|T(BfyZI) zJ?rmVvc0}5jN~%%Si1)R@l;Y&x_j`F=X4MRtU>1-*Gq3PVQ1kp*bc&Z=t$EMa<4}t zY6NZ(XR)o@MBy?VBf9`VPcWU(z>n~LQ_dd`Gdlak>BtHw-K8Xq+0;m1gjqsg1p9B9 ztlo5IJkUdcrOKDsT-m07R(#0L->{$cLz3*qAPg$b(SSQh7Q`Dq(Q9c}$tY#p{7{H( z8@#C3F9r6sGU6#Z?~Ii3k-OEq3MNX6s$@Kg-|*yC+Mso_BOO3WMw2doxvHHfw8Z}7 zjzBYQv}$?CH=M4~vvksi@)EGpb3cZFcxo7E0v4vk3NxN$Fs-+F91=0l9#;f8WH1|d zqZ3-PLTW(tdfN|Fj|DK6lE1PmR0!acNx?Fx{nL`Xz|NOgqBvAS)e(TBOopy5YUD>A z5)>$Ibyh!c<}@hIdomSg?+o;{NY}?Dhsk6jeN)-VB~QYClk8M&w3_aE6FVH2NWsS^ zHz={1D>~5eORKElIb32Ja=-z*hKZP4+KiGm;RLNx!vz^1RK~hL#viz>JJg+H zPCW&9Sc>PbW-!(i#1}wN#{q8o_Kku1GI2s=3@1?mhf8odyaqJ)_z+OX58GHNd;w=* zUt`Fup=QqAun6v~`ZU)B&X{0t=W(U zEqUYnmM|zvZ}JxbeU`nV1{HOG&2*Ux>}rZQb^sY|(=i0!Gq!471ICx+HW>07sm24} z1M`iRcKip}-H(gG^xpivyt!Ri5rrgFWTTsX3kxLhiy-Bd$sIPd80SMADi=Aj&M4`B z2?h=7 z<-0lA5il<{0)VCE(_tGjS2-{f*MuV01IX${I9qL!U^2I_6SjH{kj|c()~Mtfq}H`@ z^_g8TxlD)*`JCuu%Fx4D=QOS71%#kgOEyGxn1^~2EP378x<42X2oLMHCT&oW3VA8BWWjg~=Qwj`Q8KW-Kt5{}xD%;b1 zV@|)9AX~k5Ir1+({)&S}G`(%}`DY-<4)-(1@-U_ndfMeE-ZFHN2GXX0*$&$!fDU}| z+<6fvy!Jb=y=Fxrf>*-CJtik$F4PS%=IQb0f$Ke_y}yhBub3<{kz}LOgqU@6gQOT= zTg~JKF7m%FK*HZjs^PzsVY5tM4g(&N3HmtZzVPp+rwD5`Oc%MA2XgvIhD(%`dyavR ziDA(>n!f?M9Ua}I_$9;=fxe@c!gc)O{{U=nnL%=V>kIXD2WI84f5`pZbJBxKGdyrd zJoBT(0|GSOfjnRlg+`FepQ;e9Ne$f;TvI?D|MhT0m@KKnJA^P&VR8Me_+Gxr(Fb@W z;!gXD2h)DWibMG{9k0-2)U$+Bb(cZUF+K$s5&x;ri2NfqX909 zfp#~v#Dk_t_XrdO71Bd8Mp%^7#1DDsBpky^XkoEU7dq@;LY+QPMRPR7rGg9#TPE{& zT9AdMu2v2-jFIej95{0c^HZkX8YEsk5nq%UQep60tw|u#@8XaXRN~dNE`jj-5l`M_ zK26zU84g~K16Z}S*cv7~z z%LHwl9sQ2td=jP%C>L1=`9D3MNYsrT_blGb^|lKxua5|8?J3Y}#(}r=*V$c>H$`q) z)n>{Nt!#ywi+|&3SfSz-qVJ zaHLdRZavJHn}RpYr#15PCg4F2NMvCJ?2s{UFQc9Nm5pNhRnnmIe4NT5Lt~|PWomea zw$0VX@PmBH=TXR>x$AU9GIxKEWknY?8!kpUw>bcHR@+^%|6LYKNC36r1c2}k4D;2> z97XFTt;qo*ZKz_>G*;G5@t=lg=RG6_BLRq=qSaCUm~UBi(d3E9k`KYy66RkNjiS_P zv%NoC1=n6KJc=xiN8k7=mcyfUnI3@XWI4?ENtH&iLjAQsNeMvYJr!W3yY%VO6&+H* ztfG+|p!+>Bl|iy#+yGFF$$BgB$&6Kk94Ri4#g9%c(>bu@&f>HR%NT9n`)h%j(%zq% z|Bo73ss6J2TP$Rpaj;@aNUjf6u+1@86;mqMcgM!BH>;OE|3Ihlq8`?uzgdM6;I*^G ztYQD^R492Kow&(tORcwCVJ!CZi-q@W5EZk$qW~|xBjQd6Ov7dMb9Wfx8X7*m3!BJ! zNxv7t;bYDp5)9TRhQzaxcF^X34%S1rA_7zvelZ467l!lW1DEOcEWL9X zDbq*N#H{x%`$nfs^Mq^O)cZB_TiF_M1~*sBBCL5UepTV%-y6{V$G8u~nZsGxOiO(8 zBBCeR_It`pKt^N@c(&Eu4i<;7LLGaZ>l2<8;oMx*j56 zQynTz5G%@Jh9ShmKRjAJol#y97TT*Q#0hNA|8Ieafq!J@DFuimQh4%hRe`9si!8n; zSlhY$ES!4LX0*6DZVf60a%$Tdm7J83Gw;4U@6Lg-qYjQVpocT{oX{}fWoemt+MD`6Bo~)sYtP_G0lNyWs8-nJJj1K04+cd_Q zRImEA{X@ukoTOQI#M&U!yqhcE*5>@6I(09-1&N2@U2c-670o`AsHXpiBJf1+NNEl5!xQARQO@P8uGGGfMu4n~VFa9~6weWzw!H*~EY1)!Va5e~Cm%mkXqH)bWZ44DB{@MK7;VZ6k1yyBHJhT*t_ znO{m2lk0G8ykH#h?+YxGS#7ixcx=wxj)urGDHpk$K(FYkL0_z-4HQq2y2oRjFYs-) zJEW(8x7%Ivq!*&cyCRL`Y?RU?%BlHm(q}z+!#=bkJSI1PVG!DMeH6o?pvJbuVIZcy zODn!*wE9&CMM&@X*W03FnwOrqZDB1?w{x5pp*%ggKa;YF9eQIrUV2KayA2(vX&c1dMv()A)7+|t0>!?f%_b#4! zCRaOd6)aTTFKW;+-$aG6|E|w+@&365{!CXX0fX#V^Jrd z353{yeF4`-D@)>Jk3>%=!G6@U&?~Q7;ZGghw2v&zb?2s9U zS}T7~0Qyy$a!k1|klS7B-UCV=)x&NsuJot0fJ{tj#TltvGe9gH3zL(S%A>g6k8)(V z9ZU{h4|;9-t0)e%!1_Sl6l?>phEYjFwn+mdH;DednS|vL&KoXke zEBd<>D20QVy8+0p-rvcI#Q{6^^TlTYD~uoHFCP;+1Haq<T6n>so(88}Ye4&s}M^cKj|VxNFA}F(K8RRJE_#y~}wOUQkae4iTIU&>o})XkIOn zMX(sn-;ORH_3^0GeF(`@b{PyLn02G~%nArWh77*Q*E~NH4D|nv$Ivi_R+de^E(kBM z)#ZE~M2DJ?Qj7KyTD_!Yk4dAUP}Bf1AAWh+)x0It?6|S zgokK{Wef0w_f^>rmwf3UbOzKUip;EBJfupJ4TR-k44V}%^NExBIyZRVw>f~9KQ^Dm zKnu7GeZoM;3EYguNldHkf=~9oW6Qyc>RE(I7+xUcK*8y}f(h7AISqlx&cu4s!x%IglxW;_aIJh+Wu4DyHyt24ZkK#+_|Uc^XvdoAu&II9K1 zZv_$1l-X#Z0k~=swllLZG#NGMG=?{rS6I+lV zTz3lGL?^jq(Jw&B@J(?2QhZN~MYIJ;I4EA5a6k7T38@@amo>t)l{@-9{d4roY%$Ow zWV63Q^9MWBv-@R~4BBhd3-UG9~9LTs!fGQdg!l(lpwT2&$j#{~uo#kazVwOZm9v(KI3U%TPL z_3N~k*Mcm^V{g&W{hay#L*dto8_i%nUXw?*rs;rQ1{yCF(M4W!%S--KA$0g>wmNTV|5S(0l9GlxB~`QS5$q2e80r!+ zgr;AI<`DZ1go=|f-Yx{@Zym4K2+g$4gQ$}xZg$ZnQR1|6hL2V%r1EYYCWRP_g+9Mw zBT$KK+iy0sK+J74`eMsM=cn0X zNwJZ}j16T-2T8%R7VIHuS_jEFvm)1(i8k!JJNo5*rsZ27NPh=t~|$j2RADuu&28 zq?S(yluFL?Ip$=)^Vy}bj750%g>Zbgf6UFLfu&FMDaVpI$ZK^&8DkaBkY|I|o!7Xx zM@StKqS-zTZacRo^o9gQI}{fJzbL8$#-|C@!u`)tX(+vU$0hiaR`@Q7w=*Q6zESf3 z^ZR$F_y(H8>&X$j1*QYKw1ngkp_lmmU3V8_t_UgJW<3{_3l+_|tEieVh+(cO9|v|qkt*GJbVGRck^1>997uAa?jFAxh7`(Hy47`usar>$(c}3@j zM;;&ugd=w#^k$T)m1Rdw#)aLNT^pUxh#`85pbmqabhkLYIVey}>iZdcjIZM72uOA1 zt&;g98OA0d(dh5FH09sWuXQ~XBO}5*&I@?kWh3&E*jXK_|D9f(l%(KJ1!itxx|KD5 z@rtif!LKkiLCRIdAk##Ryv1$5#4))pyQyWye^5!Rk(=ouE# zu`=`N8FF5_DSmZs1?aP$(up3G@exa9V5A$DTWyS)au&TUnFLQnmiGAxr%AC~VA=dE zBm}PKR~d+t)8J}s&HZXB?H!p>>=NZb#1K!>^)<&t0qu^sUZYmxFSno>6}|8(aq7H$ zYEn}P%I~a}>SeMj=y+OF9r{?z6rPGqi1yl}Np8=#@%My?`%<0tH2iWB)gq?hSp>vo z<{wt>V}JArF5SmavgisydCacb&tOR&r72!AFn1IC&JUa-NW35)uyeOsQO;;|fNU;$ z)cTM!QL6hW|50*>(}6{Q+h`mQirX1K2KfejVAG! zNVUTEvDg28X1km)9;hA}5#fr|oUxst0m+u9FjuLy*6yM6J>cgo)&)=`(aMfABw`hfkLqIKLrMGO2P9C~3PP%x5aGC;L z)ROpii_qC{J9j%o;TWEt?$8WLH2>%|=`AzvrVuzX*rumQkbiE1L|?Sna}dVISl`WN zSEJXCw+lo<{gM(KH3C9a3^1;LaXUFZaeoj0^+wv$8b6fdVYKT9kpTq8HXrRpB2X1` zegX{KypZp=dv9pN=C;kQNCdTGVWU0C=thNa4{7oTWXhkg9j~$OefkiOUg}IAI!s@C zbu4!b?_RWQXaT&0OaY}PoJs+=eTOv5FT9rHJDpvpp;0od;u;O1{k-ZV&*KYafES4~_SSfM<_!R_xuo4^hC*!42BD67SyCe^*q5oi9f2NAqmnX<&~zzOA!!w~dl`3D@m#jgh*c!7&m-%Ns> zgOWYcB$X<-zPwZ089AEzxMxj>%P#U?l~A=kk*^I4d$$EKj0J>)23^I-$YYT~V2*+XkD51I^AlxQh- z#Hq&YLY)<6X(d|RZPZ{gwn1UD%feE8cD&*i6h+d1P6SIJjQzUDgq$+EoyN zEi7#`mo<)fQu{VbtyJGAw=s(t$)0A%fc8!A`tThJxI2*mL2&7;STE`R-vpe*0hcH)U%*Wsp85lW&w#Rrm0fI~2wND@FuLGu8IzD;hne z1~toqDa*-;Y>2@TMR~ zH41}NJUxPDugh|kk05=s`DF~_a8C1}&Q5-#WvQ$CVG(*m}Q=QMRL0ii?;AZ}C-N`ejM4}~Rr#CERtN7B<%|?ch=kE-YT^KIMPH^Sswx;Z9d0ktBN7Y`_hzN6!ElOKWof_CI=Oy5b~myuss{wJO<-Nr z_YQChXCBKJ6M)$NGLuD8oWNq@P%5iQxD+Ns<(ZlCq!u=(p30eKq@Ug_`3yGqDZwMku0YI&7zNKuWOt2oS)i) zx1hJiT#M}Xc}aIoHX1R)w*96k$ODt|?SP5L3@P$XB$?TYQ;l+oN97&T5>{y5?WUp0 zAI?Q{qWRIJsI1q>q-0!*%gXMc^uc&LxtcbQqWA^uKaF}4_3*)Qc$>q~e-%`0{edtB zQo;eIkBfj9B99f4-Q9oWx&sIQM1EI$VZ4&+7w?~4`O_3K+@gZNp!nCR#Cf*7ssXX% z7q;Qvrz1jaKpHi^Ms*#+s+%%xG>dX!r>c@hW%%b`rX&m)R&Da#8~Pmwt;2DG=PxOE z`jjaf5mu)}>)-uDXA8xlYOtB^y9tSeqDEp0n5$jsUKS4G?3W!pxxRAsq}<-X zTp|l-MQ_)d9Zx3Sh_qJcK4OHIl^6*?;AN8t6a%`c5y$h*$5}6S{C;<0+#xBL>41vj zIAf=?D3S_Sb5+^PxqgnlqpO}a@k>TntyQa81Ln$ofbA$nq1T#F&E>cQFEdPEO zif~x>8i*tAYIY@|goPI-Da zJYrMU#qUKZ#wU3 z=*t3}1y-;h?|3&nOf>;czP+}(6x5Gq9EQOUHwJ4{VCW(9I^fq(mB~bwHM{bfn_CKL zp`C4hEZXQO!u~E!&y}BdyG9_x>l8Tp7ZP*Ao7{t^>&eaESrTH>A_%cy4x))NMRo7D zH?2BTRs-GuJzi*l-`Pl|HO8V=-_?hDIUkd6Brmg?l8ZL$oU~HMoV>ror?+LCYNt&d zV%7Yj){)JZu)6bn6@0aBPt9JM(NqSnzM&v1h`?S!W4M!y&gfyu$|d0kpt%h_++6-4 z@fit#)+EXDP2QA_Hf;=i#DuAoFea9 z4wwq$FVS9!cZ_Mc@%TSzi&I&fu?QPJ!2yvcl9}dt5ASkv&{ClTX(?5P3K+u$>a*6) zE!dTvXCk?;nQ{FPM=)J!3yF;^6J!}WOWBCnnX)#=wX6C7_|H(8Z!5H;Ul zes#_?$mST=4+#>rm@${#DDe_zD4r_7N(9L~%|4|q1a4Cl^j}zSaSU%*)%!Wzs(ur# zx43^T%|d$LhCJ?vZT%X4H3pB9qC)r3$OLbrbaGW`%JAP%0=JZc#B<5QqF=!c3lY1R zmPxs8(hVVp<3;RFV}(!U;n&rtlK-hMncvpv-dmU--MYVko0qbp{LE`MsL~@c%;K{Q zrvxdDMr63o8ff;g5}!r_v;^B7%&#KzS~Rt6k#hpS_X(D(F$vSMQxo&d))poUoN=c$ok16{~{@Y&?iJ?1wzdR zwCd-~&37`W@+OVRxPFG#%ywv7HFvoec1<9$3w`>2GE-LGY^_|y#{%`L9%ml;^XE(Q zJ!5K&b7IP{SxOlxMSI8d>Te3jp4sm(_IH+hIH;3*V}M3$Yw*Cc#+t8=JNA16JC6GK zR>El+?r-Z;X3Gx{28i=~$m&m3O60D9a-s~Ab|sxI8Z@^N_B{olhEk?Zp(KKeR_C^} zo;O1t)PKPH&z?lc_>z8XhDgBye^H)s*8`WC9SG0h{Vh1%Tdjw6_^Rsoydv-jh>guM zA^`d#JZi#@hs_Yj-p+M)3|YF+(iK!C2915hi&%h5b~MlZbto$xu+Sb>>rRNx69a;19C<0 z;r0k~ajLwYC8Bafe4Cj3wYma6X3ZM7_aBwp3*e{gCTxXV` zH)$^H5oHL(_s27Cy3a1XcG6^1HnS4h*MX6=wtb25inm2#Q|t0!G24P&Bi-!n*IXii zRWI{N&S_{?RC*ryHp)Y}g*h7haJM<{-0A<2IYtTv4tQdt~*ZT$%ax47!x8#Z>>6jmj~Kh*TqjZ&}o;Htg!Fp54Ng)uTqmc%Gaw zGA-XWt3to*r#Bm!L{G^$iX22bnO_>fPoY7gK_-a#$4``cNV zB8OO)XH%}I%y@2BtJ@ykiUg4Ei7cI`vT8hkMi0D6xN^Fu-^^7>W#sU?PtNl2keu-W ziFXXH>XS;wfrT$)+6fkyhBAdO;a48UE96L*pC@{K@g=FTdN(fSoqLXzH{!*?wTuov zRt5wXx&M-+lueSmDz)(0WEV3ACdJ(!fERPwdZN(Rhu+h#u8ZJHVUTnLgK{e0U+8ja z;nsDdU9Oks!l|^TSL5$(owXlupgfsYLR56}`TM^lrL>173|v$pHsQ!c%fEy&eyDZjX~4>!~V2+Po~`HdiR0j?v1`;;1L9h6XVgpmWz!$K7gsA6FT zepub})$mxb4bTj*X@xh6iB8E9YCktZO++1^h!adL?F*g@{Tj6rXwQlhn3{oiPF4T9 z`Lhh4Cb0gAR;a4 zRVc%Vm!E;fok}G{X%627RXBj|xVg-o#~KCUg|nn=n4LY)4(xvA9HZ?oz&NkeawyNz z4B+bI$$meUXar$O)69l9o)d%PPRCG}r*Gp>}pBRR+C z^5-BfY|*tHTK`Q7s{IVuT}1G*5DUVxD$ELzbc2g?XcqD)CclmwTJ!x>U5QdzITw|l zf{vE?=b=FNx1raAjgnUpvBx?fiY#XjicgqAZe}Lp^YhcaGV0AmII*wOr~L0A$!QHK zgzk4@x})o3a17S_q&gfj=~G1$3)_s>yh{$7JKwaq<6ZVGp)AATXK%CgiP!N^2WYt) zQA#GF`aG=dEd}4toV>>D6Ban&%_{@2SpTydvf{Z-|xff_ZCQBpgAoP|NU)02IzDaS(Ka5 z`6psY;&}s%IRpl;AewOZ649?%(+(eoGvOafVCRlV`RvO_O&2T79Sl4u2()FUi+3#S zx65u(Nj79UFR0zl9@BCa2VApCwa~y1T)osmiA77YKme?Dg~Wdf#L68kefJWX5C@Sg zlTgL9QPvfmv>2@WzjIyUdB>DCQ)MN|D2si=GMnnDSSwQRIl33~S8G(`X`zj*D=H>Y zp*PW4mbTzWQS|keAsP{nXV{mntCkY74cV%S{!W3B1yXI6J-+8q!sh>25M7d9E$IqC zw&dv^lQ?b>4OlOxwU-x0yD@P8$VKM{?DfiFW+fM~H9?NO#t!+NO-)K*uR~om?E{U_ z?)uN^{)kl^a(N5Z1aZsR8sN!PMYT>E$F`nH{@*;?!i3B&a)y@tYbAlFVrjxdP5RyY zjG}aU95K^7DrqNDG`J`#M!im?w3|>hrzw%o;z-IMU59Y%0;4A5LjQVwVuP$XXrPjNiIIruyX^#YIdY;u&J`8i< zgUG6y6Y!B_nEC3hj(F?;-eUQi4L|%g8W6s$@&|L1&d~qr;($Oas)2ch4@YoiV-?$V zmj>ez_*xwr{Rbbb0%DjufRgdV?EAMe!!YiCkWh78fssj6gYQX#Z&gTnQ;l;2S*f9t zE9v6dq6j5s;oB1Y{`@%$@{i<<^>>R~S=<`E3qflby)b%NUzLQPv8+3`R~z|!$-CFg{gKgc#E#FWZ|w47C`0P?>-YfeE*?& zwPY5Hxi>HdhZ1{-KAYUQW#tVirGa^t1eAz!vp1g;m(D{d4X)Rkf8W^Oe``koOtDKx zV0IGB9`5r7S14Q)d!3k_H~Dl-C^RlUDIqvl(pz-Jf=p)XCY`%qm=nfNXtxEc3@Su(|Ht~y8yT6dPuG~tQm1L6#IARcbEcwohcGxJEWkM)*zYQ(R~fMnQ}TA z+7%-3Z!wIoB~^Y}k7I2|H7#~CwLbXqI{PKae<2q$NbrYF8@CcKoyytrNdR z@!ML>MdJrN+Wd<8!wRIg&Fr)mEEpE^aX=}pxJ1>HXD^4Wogr3Nw2;gPu3R6jGaejd z_f2aMIF;vAWfcnc#wJ4Sl6)VQ^fqXCRNA@5qWi7+)TfsrWo#LTFurmKGUO|Z3Yv6X zaf*L76eH@vO3{h0So@%WJ{44Jaw zxR|_JPK{-r#YCC;shlo0yGb-{1c_=R9~4~BVDMa_dtkoJfW^jT*k~xh7FgK&u97G6 z60p=R_}K@$E1i2$vgmDs3x$nh`733Ijs;_q8ujDANrg}rWBPwg7=s?6+l+k_#}J^| zOa|4C?LlzH-)AToN%v40m7Cr0?U-LakNglV)xcLJs3~LvO=Yye_-)y=Bb4852f-Au z8Jat?l2K61F*EvF9LF8qD)%|mV$O5d8VvrPs5g(LrdIU44NGFV;JX=O5IhBR;3W|J z^B?r~p=A?#)4Cj3m3QJ}W)6Q7y-Ls=Lo}Uf4FP6yRQP@*&~^>5de9r|x8=>rxf#`F zbC@dJ^J&A;NXQ7lFODwiW_-3I+p(=cPwKFncuAf~rHwn2JX+Gj$AY|0L_cy02Z)MP z_q6n_AB;Tp69!Q!_5N~Oc;SN31Gas>n!Q+(DA?#Z8o+q3@qJi^RekQ#Fd4wc^5^%3 zlip}!>#gS%A34OS2B14>UEh-oHm?1_L-XrH+3jmW#T;r;iw#y=>14Uy#uaGOBbaTy zVT8fr<@dQw;dvdbKQxl-G08v=cUg+YrdJkv#?XM&c5y2y0$IVG^;6~mMd%-f=+U+U zhnOjgeuXW-n5L|7f=4FWh`Zz1gY@_+zW$(c99}W#NTSBJDe(y3w?A(utDOK)$hWX4 z*%Jv->r#Al-gO*H@xxlGbrb=hEx250t(-Et9Gx9%AWf1+?vU=Nqz$f5xstMEh>Hdp zeZh!E*;`v;Giz7+qEg+z-%QCk{ASiWJ$o&9%=wq3V1@H>J#ggbip36Ap2%)6@`%9E z4^kuO;Gt~(6CC}!;8C`w(*Ke7T3{W_XZ2Zsb!J-fFBvdkNM%;N)zTHQadn6!bs_@q zu?9jU$-spzel5(3F2p=O8aHE21El~mot#nv^F%S~@d2KC^3qqzR{t-~l>l79AchSo z^tGWZEJ7MWj2eo!;1<-IjWLr$Gtnj2Yy0CEE(XK?TQSa_Vi&9WbH9xCudKGxEJbxC z4M|mh9B^G*EajdJXKwV|T4{)Uzn{cR)vP>nNRk>WxE$pfKBqQKdDq!kuqBgAEftyQ z_!~GGMJGWZ2OSPIm}2V;>x1P->MAZF;XyU_`|SX^YqLKyojh|-!p`O!diiJ2_o@AH zjdH;b8+E9vQPYR$5zI{vvBTnvNCyx!gSOkuuUI7WG=H)-aq_u9Tvdx)R_GrNl%Eag z6S1Kwe!Ze;PAs!OtK*az+wY`3dgFdet$YNcXGLcch9s`GLw!(*3%@|ClJwYn*EEIT z*)DmR-z_~mdcj@wR>Gmzy>WPyBpl6osDMMCb-Iv7`1e=vkpmQUzMd_Gg<2tp#)mVK zh%HQdJUAx2nd2XpMS|7UkJX3yB*hLN5B8`Y4QxfitX{uygb$mMK6f`HIUMgG`;f?B z%N&PSX)3fhKlI<{vI8kx$~P5tI{C1TL)3iM2e#;Ria47@Zw|&pCorE?AS9`V{&WJh%p8x6 z3NC!!hRT0-=nGw{XOr^juRe+n*ihKK9!@!}S7di&nyXWmwj!3kRf+_*P(*T{CrUz# z;|1dhBN9en5R@DAgtVM`X_XF%_gW2EyXG>XSA|zYYioSyU&+BE`C^4%C2a9QfJzsA z_js0_AW`c{a|A>dx&_^o?&R7#t6>b_81{cv#Vt*jfMo20HTW;A!b`gTwVEA!TLB$7 z{v>AGRnp%Oa(2EIIWs*IqxdJV%Q){)OeplYHxoKJ{oLM(1}Vq*`E6y4XWD}NKth7gkzF&k?h{$G1J9_XAPlB| z`ei;Xy1w?aeX<`qQ+yXIrK%eBX0X&pZwdM2;Tb2IYr}j*b7hE^7(|zA!cOk&Et)7F zAWnNNC2UtZ0t+0KkK{XO+{}fUv{XGSd55JF~`SH)xYC!~>|o`IAtpziaFP9zKRkuD!&8ZFd8s7MX+T>sRa=&sa2EN2sS!a3b8z&DBt0PiZ!KNAbBlOMAA(hqGK%QF z9-La#WnE)Z=_Xlc&o9%W$+oKdcgZ_9Vv>rb=3OMV|-1wH-06&)rG+ZW%)K?1e7KJD7VU_yK7 zg9$tAf%kg{6*O2z3ECz#c6<(RR9WlT2ywLSQGOjgTkQaTlsOyR%Ht2eW*9rFR=ESE z<}=$`LOH$^nj!2?^4*WvtEed@AuMv|yGgPE-hsD{493t)8Jx)e zEWs{F4<=GptsU-9hE$zrP0?5FeX(JI=;PyjP@(nCkBgH*<0(i_Yl4}~_1X*xk1Sh2 zO}GfpfU48VP@JctPYMd~46TvLejPwcqQf;nz4!xff^q^vD!4^^t)WNCt3d!C86k1N zR9hCRuHysHa=!G%^l{uWVu+xMyfysD7w(C6jZ z_B75$6VJE&hOfJD7`P?L-Xq&tC`j0WG3sQ8ntI#a-*(;QG>aY`;`rx(UPemqtIb)m z0w2iv$|PAk`(j!|-Qs~jmX9IS&$jyiWS-S#n7AK<_7b~<68tMS|9N<)CyXwkw<;JK zY)V7kbPY_c38Y$78LpRKA)6w%0 zq#W%4K|sF0^)u~w@XsP785?|r)4(!olS*HYp4J8wW_yBOy0T=+3)lmsEHyt>+#lRzfv$?2AVoS*zeimuYC2V zWpoztT~()VGYXWa>i5WH1qih$HLq=~vrv5CYJJ>IBQ4BU!A4jkU&S3AS*^a0I z$n~~wjEVA=N%T*TGDKw;b67IM70zE!AIlK9l?uaMcSnP zkvsH+r{d+~Yyh;7B#ZD%4CXrdGjB@a0A;Cfag}!-b(oT=50NjR%>^f$PAzgDi2Rt3 zHLT412l=ISd=S+5h)oMa&5S?{{^|oh-Vze}PSLv1!|_~qj$k_?tS0W0bC329{wbw} z(80@LLkjxDX@dga0a1yMYSjdyHa7F*Drg6TE5^lu9aeOqc045rmxPt?N#{<9<3fmrtw4oO*V{!geXo6 zw4N<#$rKtulJ)34{tYPok+IF{SC6D;Q&jlVvO+{HV5aY0&IvqRp;Xlh4>DoJ6wE$A zovbD`2KiYDfAS2VwRH9sHB!a#kM}G7Hd5BVaaWyPTU#R8Lo>BnxiQ@ubx-Nq2^eL= z+4oC^Oa_5OsU9M4#`J#&@`_^7ht1ODG!Eunk-!cT;_Qa@Fx!6TM1ZtJOL zEQHrY8K*JmG{%}H(igW^I6=q;FG?C7 zNp5u$ZxqI6H)V4je2irAYu3&JZ^&80Y&3OsEvXO$x>7C1nYG=zbA8rXhu6!#UWkIm z?KKUo0p1zZ2hu^v^In6HG5r@r`T+yCScGw*Z|U|K1#G51Ip%ipFeBq{I@0yO$Azm% z{Y8_0N;Yx?vq!kIf;f-0E7;?el0xVFU>!}z|3=|Ida1}lBm@rIBB$|zW5IrN(74av zT7u#(jmZU+#L3SK=o2M2Nlu;0t8e2n`yRTqQrlVdbi-oyXLW z{u#bi1hyIS2u7r66D@|p9Q|j_-K3OE=k7WAh{pIU{LBG2#yOPqzd?6O?n*meQ|Rgd z^5LY+;3`ljT9d9afCVa1mw_wLdMc6#JUM^~FI6I(aRFLx(xle99UiYaaN7f@0owk0 zF0%u=_r`1@wlH;g6$niIhkj-YhhpDm+6rW(ZhnJ~Dk(UZGx@*EU9iHUL?&6dMpI?_ zPt-xYhr?UOmIX9$sw8OyJq&mAFR8{cY|fVc&r@znv|cF@{TiQYJ8;E^PKUPM?iHFy zhsrCLB>)Zy66uocCQ?U?BP7{PJo%gZhEU~DR73Fl4dX<5Po#m96>KH0{jD6`n*~tj ziwfF;etwMDt8{`yzYFrfGHu8!JGR&K{r!~S4}fphwk^>rPiPrDqwmTC;9uf`#|?mK zJ2m{Qayw-15`D09ZJvVV`(kMJ_Em# zO0i?JJPfN}hh)EU7?`rqO;e+G{C%;~iNvaR+V}DS9<#`65l1t`DFfmyovF@=wqg5F zUESb>H3H>?SKBpfL@NtsXG3>Ey#|z7Zf{#&fxfRpYhu zstZ4BI9MGnLcl8ThO?baEqD#3`MCGHACGX}B$nn0;9?JoGt@LK%2<~1ybW@Xlm#J# z2gP(Gty6e#n)K>%!0w?q&XF!b_qf-HuHB-VD~Kz%nmsq)x5vFpZr5kAoC-Ax^Em1C z%p~0v2)z!IZ^g&>^9L`RM1=tWXachDV|3f0a_f1avdkA|1>soVpLN%wlXLoAY5XuY z$C*2dBiG}lmoX%%+{T2L>7^QAD>|?1SgRP~DBA;;31UM!*oE&am5233#3?GJ-cu6O zh736LuB1i2%ICFp#EhLeo(~!~No0cQ2DJQiw5LWv`C}Ii zOkX}7Hi`Zyl{fBK?$N(~6}#+NTZYxhWM;tOq*S9r$CpUR0PtEElvn}Ay`ygdQ9>5x zPuWV&=_d&N9NqT(HV6_0S6h~fthpkSW4bS)QYgi1M$y|#qjn1g)X?%KT!rTLJzmQF zT%Oa*L{U_Z8DtX-hT#8jWOMo0tGFv7)CJr(klj4Ug6UOYn3w2o?2sKuN=`9z* z(ADa-ADM)3R7BuhXkhMZg=g-=Vkk+{E_A)32gF^@qhxiK{5-v4>dst8rSQ32J_c|s z#D@xg0b$>Va}Rk)Gl0k-b{esxsKh~0?CLN=pakZRCuJj^k9bmHVoW7n#_pu}mNG&# zfyC8n3%P^PX>!ffB%+hYwOu^vyNy02rDFtfi1l`B86btZg*fISe2w!s8P)ejnkL5gK_d|WjhPKzcrbd-4BRJ;E+6#xc*kd z38mLI`${mg#8OHI)*#dys`XrPZP8OYgh>kxdRMx*B&Xe1l-SdWN8sc0lJ>CTAM<(8 z@xN`=MQf*h6~LOIuqZY@^+6GSq9Q7C_RYQz%NO@J$o7G|%ahOaE4^hxz7>kH%m5X8 z*{$-d)7h_ONqVqM9?Ulr4%xgb^^T{% zO>f2YdU&XpOhENO9s@~@(u^EzHK0iPS26 zf@$1p)EuvCH9LAYrUl2N3={W;oHaY1{s^&Z*PC)_vVqAx+!3?x7#(Bf>W&ljxDm?j z^WA~u2F3D;kt(t7twH!+L}Mp9inC~?$x+&KPE%yd zZ>PeUxWW<;MQb4*C5;guwxbC1eS??wl7h2nujxqXw~&Do4)hxFeWjQG)~S$5xL2J- zS_*}gIV=9?DC8AL==Hp3+cI~)Pm^{pI8lwXusDlIuadWj8gaYLZL8zcQMmu3*Od^RS)}1n3dxypbNqh!w#QXi+t0?#<}{9 zL5Tf()kY^zig!A$0tpY6{|jzeq-UiZ$)iSRdM$-Dz9=yxF>}RO!b+R_bXdep*y|!o z^$cE?pLVr?kKU1H;oKagf*kj|0PtfXWtug`1LcA&p3qz$$^7X40q=`7*yucnCwG?7 zc-*#voZp+Al@Gg#Tu&qn)*&OTDF`@)y|Q2C}F; z%zHF%in|$^2>yrb=H}-P&Odq#3S{juCVS5iD9{c0fp!~M_PcJ2AAtXPvDv5>3Dq$e zt6vxCQZwpUwDs$58FbIi-agj4dZ`X1&Qdf0B+j`->JW{6 zgG%jPGiDY4OIIvySm1&tqtGwq(S-D7I3{3jGZY*Ux) zwlg~w6l}fICMoA?U7%8CTuS9I$iLBN7=njjT&5(hbNj~|>r){&oU_#rX?4 z8$rS|RVpU@a5`Muty7Lsr3dwXr49ZFFk{!CYj^TfR%pvw#%TWHmhqknWQZW(703UI z3<@=qtoI!)N&w-BZ*OHx?IQ&hJ|y;iiaacb6sr=uQc3!jy+PCG5C{J(hjQYpO0@vr z5P8rrgCYi-82lV<$MjINt)IPcF;wAz_MWZpnsV;JOT0#*qmH8By|ig#)a|ffsDofv z%AStcgEP6W$|c;MzzJt7|Zhi#wBTBTN~nl%cX~ZG4WF=RyzkDH^S0=!Xdfhg#i4XHd+k% z8vrx3wYx2I>K{ZDa+|Xh9JqPee=k4}6QBI0yEv24;)Q0B`Q^UoWi4-;!Vr?5O?Hv1{SxiJ+1iyojp<9#-PLT)}G_IqFogk_WRJi6V zZbBY($il>T*N=dmxJEnIXcG(H%493@9%g@*BfvVH+g5U6U>3qyL>9ayU|M158A-T0 zjFmAZn;dMRobRI)XQByZUMrex@@##GcF~z>16d94XpE0l0sZHpzlg0^V)#OK=WN{k1Z5vL^tSF|LO(0KDl-i2I( zhlkqJ3a(E@-YHI_c~wpF)CpmRfmuxeU7HUH--Nqt$bAP!ga4s9G$$~40bQry(8|l*=n=o)U+txz z$6xtJi4X~caBSm2`%V&d@5yV1pl~euQB--(4;O6DfLXZe?S$)lgPz`(&Dh|G+rqJ( zj7sNWoj{XHX0HYP^Wsd6dt5*Mofo7@)K#M0FR@a}wGr^u*Fx&sAY0SE@6P)(L&v~% zzu%+wgXB+G1eXrTg|-QyZ6O{U1(_y;Ksgzo{P5i-nX}?CJ03%SOu?`WC&0?QnN$7E zqQQ8ToXZen8vw7|2fzlNK=JT9=vHe8p%B!@QwETf}g)4h0ilLAYw?i zkmHH^WxsJO;&Uo)A~?()(`^s~l;%EMvWYHD<3ALci$;1KekfF0DhxPG<8Q&$wf{5YSLN`u;!+G{j`gP=4Q zT^y!;K)8~O2Dwz4Hl-xqqS&)al(}JgInA5qwMW+s1pG!fIKt-)RbR9+|lD1j+m6fMe{5w z>`jN5Xe*iA#B0kZl_>A8vrCG{6i9>X65Ctn>XiT}n5%l0Q}eOvv$ccUidSITlaQ9? zsJadvx};h?S8s^`e`yQ^IMA?sx-pg$f3vRwtp*tmE3R6N=G`3ymRSLA!KoSwoCJnm zN-VRkrm?CZwCy%cig_nunIaoYUX6g_MdwMLE^RJ}9cm3TJ_OeeC4y3relz+Py&aP_T0!c83u@R) z-{K3jkqG{iLeXKW9AkpUC8E|7!u4bp>ldn}wCou&>mt4 zGNPhCeMXa%3J=?uwrSZTb9XbGMh4EI^MPAt!C&ri&tEA3z_`s#bjU_=a@d1ERG$J* zlVeXwfu1`6`)*j(g};B8+@>Mg;$WdN^PBcxEJhqNUQ`o9Cwno5g@trCGC>u*=n2!G z$1@f<0|Y@BNF+9s(QmW=x;^B(D=k*@%seQU4_)aBZ*W%jZy?+Zv4Mmck;8@5M1X|c zhAu$!?Sdbj_5lcW`|H$BQYW#|e4WO4P7}p3~If%9FF+vlW4jDV7 zx+}U=PBIK^kL3R*PkYh13+*sx#&HO2+WiGg~w=Gl>cldF1-Yw8JML}LSDBf27 zPgpYn^qF8)qFXA7wQ6R>DxJ78kiHUSWiwE_lmq%q%w>lim8(q~_G$2B@@A2lh(g$m zwp;Cgb*cQJW0lP2&eQ>AK;UKqFx{fZuh}y76a|nB`T6gy|_7l$*yRDk-;Lw zzGCjg&*C>d{`pRW<|;;IzW=DKv=A}Sqx`*f(Py5B_j+&mEc*ji@-;wg(MNn%ceVhs zFD)0cfA|E6f^fP6PEw#Gp~10h)4FgW{f7?b*G3Gs`&aQt4@Gc(fG0atBd*(0gq(w{ zjGBTT9m>mZEA>a36i9Al&}ZU#8IPI@_C>*c9rzKf3fmmb73VpbSbPHY&pw_+qVU5x zhh!WaELoZ}GT;@YDb{nBb=)}x4BYF(Hr`n{kpUFiWyA~#N2oelHGZ*$tMh5rPr{0y z^epUr5OP29yGm%rRuvp?D!Vg0K-%N;>}8Su%kWLX7O0Sn z*PoHK7WY7+^trJaVYq#v24a6E`~2EJvh{wS%Mvh%c|h+ZvMGJ?mFDC-N74zqRX{Vb z;<5U(O*&7IH*1U3!Vl>LB`*lKx_GgyNFUihVhBt$19-uD-Cg>_vM)R}Es!uPCYNZ2 zHJjeK+p=eX0ZLxTd3RHoX8qfE-9f(k68z18Fdj z!bniH6g`x~&R&gmWljS+)+e5Vr5tE=7u0;QPe>ROJ|MuP`%xZzT+SR=#-C~F320Q| zIuwMH_%{%U9b%Xi>E`3v#Db;L*`{Leqv@A?ikjrE#4m1LCW64#8tIwFY)wXR=M=_; zl#c43hw-#Kcs@FdYN4M-I;f|D2->#E&m^Db}O8~{n& z6E;!gTf+XvWSAC|$;lz%+IEMg)D00EDjxTcRNoLC{o*K>66*8p%~(G?IKEq1L=;TU z*MlvtRE|s#Z@c22Y1+_@c8%{sGLln^w`Ww}O3MGNsQ*S4zV%`Ho~gxpQ(*UZ3JcnIqqC&Zwxv$T;6pD-Non-Rzp zi<*1kqOe-Ek%3ngAOOg|=l9`l{cAz0lJ)nsp5vhsw#uCBuU2msMs-6=V};Ro6Wc#+ zn!hEy6W7^{3jDgZreWu+1(+$G@q2Z65% z;G6cvcEYupKqdrndKyUttPivp!aOokLcR@rRC$>1$+C}sScQf(kZk*y@L`qJPL6-~ zSFOX7{&P5`A2n6i5TzhfBbVK{1mL{+jXk@8+lEk2HR7~s2Pv#a?x(~Zc-z3^z~Lsl z?Jh+$Fhr(>*ghwb=&tya;PI8{-YedJ@U(!%I+$hVy78E*H(zonEyOpD)9RfR-QlVG zdAq&P$T_u*p4*QaZ=(z+8#Uub)kP`a*)~b-d~eA@ zBiFEkbfnK1Jave5{1C+Nv!$ztB=5IPQ|-jn+2HwQpt<|jwe1)+A$(F-SW~EA&iIJq zm4vAtW50X|T%-!fQ*D;OuIA*pL%_r_80Gfl$&}lY?~e0K-8-M9Dc6LofL2mClll<) zkr*&5CvDIsDbKy(66~dC6I)8a44fw)3D{Hzm!AWfW{n)dQFL5q2b2<{eyxMqS7>)X zqw8jvY04CJ9Q@dQu8=a-6td(P*Xzm(%jPFkNbUk}7&MYqhHG~FZEtA}h>KuAWs1WF z_~gP&!yTN49DUReSlYC_^udYDyCwq%ohM2s!Gp-BjyH9t%Y)*+-Vh&b^OSgAI(gHO zgZ`u)-)z(FldM6@!ur~9?m40$h73J%U>*(K&;}ru76~#Mw#&``jK;-VmYFrb>GMBW z;jgvH?WoEf&D=;-b{@>5f_-r%jTFA-GaK;6m_?yCT$Y>kwe7j%N%AkV&rr0tU#h(z zbXRz%2SF*Vf=W$)#Zwl7XbQLTDUwpnLQDmx1Dv1rfqh(ijK1OscmKjyKx(kB*MN$= zCCCmIe07l2cJsflmZxItgEGK-_!Qh6CgW;OD}w-J5OO3e{ad~39(XP;d|1YL^z{;v#oI|UL(XR(pelLY0ZP2Gs;8(}5fkhAc^b}jaj z`8U|F!T@3sM&3X9X8@WS)8G|KjMubNUy!q4_a_#QlBSWC+)$XXR{>Q8F60;$AH zV=}aOHIYj^tD)vn!6Q{qPq>|qPGD1$A}bu8WdV?H6nSiTUSH*nUIZaV$zIl#ih>)q zt2Zbaat;~toe}NDwOUyXy`62lRa9dsB zAFLePUwJ}2dMk#&VD@r9L12XQ#{tFcv}r(5gF7eB+E;ue+~6-C@sTE2hb;A19@;xTZ(>7_hIy4i@ezyCMBlbmYvYC;4}jwTNQ@* zX1ohBN-s2mmTJ&Ev8mc5q*c<6*$%(73Da^z8|XC5JAD56b|BfRQ!Vu4A7IuPkSkNz zFVAhXyI;6~9@y%Yh|f$s68u2?n1)t-N%ng=)UOiFHE+5~s-Uay3ocfOz(K!Gibfga*I_SM_D-}G^^G(_I~R>dM#W&n>^hD>reexR3K zttQwj4Pn@HN^IM(%J(yaXgg$C1#&AO`G*y&E;Lezmy;>{&n1fwNDmO?G^oBtSY;E% zFY_g@z=17gv2Z5h*;RxZfZ=^@WVW8)Pd#dWvq}oICU|M`mk$=2&16}`InnTSn`iAS8E7mZ(^Aw@JLR{gcp<^V_vS(RpqhL3hrv6w zQ{1OsCRqinhh-~4c)&g+s{fbhsnkK`H=lh<1BSgicmgQXoA^v^A018V*GxdH0Xl&W zIR8XVSN9G4WD$pcJwN>zx#C(cd29EtLahE{PSQEJi-yheHl2Tm0(wNoIGO0oY3uck z$=6Oj@J_4e?eXkrvkCEOU+TDY*#@GV9HK2vT0Y)w+2t6x90VbtoMRf$y98%aT`~20 zTrcS040K+trRXJR25B72SYUPX(4|0E^s3~jw>lH?VwciKVwUB>Se$WyU)Nix%HzL) z5b6VREgK%QtOf4RO7V~?2oC3?sPinp9Mg83hw)kSJp8TuJCNTBRAnf31;2WzAb+3? ziTXOf5wZOZ(x#DX*q>Wq6kWvb$B31uTG~HB5k)5qluMfBbQghz8s!pv(r*LQTsc*W zQ|M#Rk>bVgc_i?xm^1+cQ$sprpcf)g3KB?yQ`kQ%2+&SPZ(~lEq;gP-!cqMmB%lbd zD&b+{INmXBq)Jna_zcig{o2@YT}^|OIbjgB03%n=X)l=^4`uW>aix#-W7o+aTkh!X zYO0G1z19|hj%0j=z(Y}O18Ea%?rbH|K_HR#ArW(dBi?3HeK1)(tiQ#rtZ@B2#1D5r z?@CBIw)3)7LFXYh>QSwVTHBa6Kt8QVG8dQP44LB66(*Z7(~yZ5&b1s>2;$fRK9#sS z-XT6^Pz`N_UFy|}@b$V0J>>-@Uf+DMLlB`=w}LZ|8$BwIFD9V(ivAu z(npfUeZ$?vhub6Zlt0{pq z)ZtV+Dtc@~L*w4m^>3F{C=Q}nDYBeN$rUcnnn$+VGrv}CtM~D{l@|=CsHA^Ef)%S> z$ef)ghSy3do+*thqZs{*gaJAM_#k2JkeP(F3wxvECS&cI8=3gQPf0nTVj4qZZ<5g* z4M|>roz(@L=CkRVUJ=_~yk`Zr2&QHg0fdFfUu=pfl-Ui$V^a8enbe{O3 zrYFIiyUgaklVEe4hldcK^f-Ue%m*Kxjn?H1{^{}CQ)EtEJ)hAFW@ zEPjmz6kP@DF@MugJ==af!aec1M2#WW=yYkoSfQpk{6a}i<%`WGhgwM%qdnax#>D5q z5(fn6-^+s<cB-*KlNE{K1OIUb0(k} zH25ybCv+@muV7+rXL!`c_1@B}gq(v=+Udrq0oOS_P1F-DliBx^TVbJ>rk?^kOy>In z;O#U5V+lIXx1T#z!_o<;@SyET8r2imsoPwDY@q5ZVkxVjU_^nXhlkpenIKt10zB>l z)Kfr2nmH^U)f%wP_gsfH9VWT+wHw7P5|-g1j(iJwrTq-v&`MC*^+t+05(F%Ejc*n@ z5r2a?E4T|sV5q}h7fjHGOelG=Da|5KCOHB!gol=Swo6nDi({^E$XO4|ayqZhzD2}~ zK-NK?qm2N`rTw&-J_Itw(~rRQQ+c6!w5doIYv~fC;!Rl2&zdts;1}4iq%5ZfJ*(d_ zDqpU{_y4Q2{<>su5-!6oMg|3ult$ZPlSs@+G4UX@cDwl-PX`*eUAgXsJ=ghR&G(hj za>|dby(Uh$H$V3Y#Fy zbO)*ZssWnZ&%mZg!Geh@WtW1^kqUDbq=7mg;l}Q4ZylHoA`9!MR=xCkNqV0}$BI6d z1$S4c+c+oe_x^e8{qZ6PYe7K<=UDg_+G;&?!M4OLsub5L8SK!oAy2}z0FPiu5eq%) z{J*g3#{9ozD4a9}2O+1QeIlL8QQwbOLTV)JbyJM;{hlqdOLUTo?~0f;Z5Gu*a@NP` zx}ocmRhGPbL4(Vr*XB%e)>M($_v|z4(^qV+dvpZ;%N=1-B-k^w+rzLP+fZbp{3w%_ zUap#M7}38o`lGi_;(YAttW(t^lF(gVf`AuA|Gc7F{T*n-XGOyK)foC!w==sNge3pI z?sR@g1Y(f;D^tl-6m=t#Ch790->9i^gpR>6Lgq zdf6EjvcaZwia1{L<$^BN;M;K{3CiI_kJOO|TFKWMoS(+%WH&RpV)v~yJDG{%j3Hb5 zRCk{ispL&4#BP#d@&T8cqOB&G5;T#vEMzJA7yuo*853z-<5|a8FO7rb4)B(ae}cMO zUXIfKNS%k$f$NVtLra5mTJ5wGB$)!Xbf-H7rGPEfr7fwZ3bE6qYm?&~0W|g)77}Nb zaFQD$WPm#8Xnse!LPJ+*3dnvZQL9~9*NCaZYgTTanxi-&46Z3O8QDZhjf{&oWQWvZ z3-}&x_9TE^O(X46gvHn_Gw9L@!a8t8TcF(3cegC7b|7#x^JnC{oVK|tAaSY5P-NSq zWjt9Af5$No9)sz7+-J}pG4GI<`l04Uj7Ep#xSdI&JT)XRWR`^t*6)E*2*L2gC~*8M zLPOU8@rE2r$l+T;_XKSk*;!EFoMBwfQDVJhYKvE44+fb`U^aV0`PCQ0Z84i!+U-0v z3KD&s^fMaH{)@Ib2LKZI-J1@vaVcQawonw>ySwU7FM!&YB@-|J)D+G31rlJq64Ka% zWQnN=VO1xQS~P;GPRwKl20sr{ZthQ+*~1ea5Zg0*nnClWn&D$ClI)1N zIq{&7^Fc^q>6a3oATR0JrLLu4aC5PE_v0Y402JlE-!7N?m|Y+YkhJ~ z$5(~?lIXTk@X4bN zdx{ikUq$^XM=RA|QRZ^C&_PO9=PV0L;*dg}7qyzNS8)ltBE`zN_Cv8vRY&C1muvmD zGJ3aH%E~I|mUFvpiFH7(E~#5ws<4-y^rE@m1r}jkuz`-SD*T``gq+BkO(_-NC!4yG zzPiJ}Jm9zo_;T?B?qSREx_k}oNKV{_z!Ic$ovS3F*-rYo>r!Ea}5h@1^!elenk20uOKMtEFap}-63^#j5&7hr{m{{g?5R^ zT1|w?{R+b8L}K3IcjxJiH-o+EX+*$2;pAsnV=4R7QTFCzryrZSY>%4A_X{O-D*eIRrYst ztvAktcQ1-Gf^ICxU2yJs)tW34mcer_&$XoKIT~~ zWz(}1OX^^^KYId7rDrD_<`P_=kpFBt5(e|oa}&Ep2C+3WqSj+6*u5YlJ~zR5!fqluQ?tRJHh*CvjN5MTU`7(% zhndl~GlnvkbYoRa_EyAce}>4i!sNNs`H_Y}530+gfY6m?D8z9#_d`TYU#78x;dSsxj% z5}9R40c_QinBUDIUyG$lDS+@I(855~ta$b@UBfR39A3%Haooi?!TqqDb8@7u>cVV0 z`&)u{Qp?9=rLiZX7A(`MeD zfQ6p+j2B}zE=&9!@blnr-V7acm>fo&gajgJhFM+3F9gcE))eI?zc|CJG}1EP&I`+7 ziS(+bCzl}jXatdn^9)A2`{$CtKAWRndFR{RRm$*sQ56$3YRKbOr- zyO$2{jDo4In-=!D*R72{!A=}GSyb>CDo@_cnT+D|EvM3h7f!(nk0JQnG+{w;XSB#C zX#<{$kY0?h7TIuJTZEujk~fNu^R#(Dt4hr?7B4YwuTv zMueFX6kyLsOV)j;_4JuMILP0VXc1Fh!8p&zs>UIGU^okeZ>S8a$Nq8AFe+|cMp6q3 zOXpi1I%FmP63q6^;iOsjil?Us^|nXPf7qh~n0BTG`f*-yAkTHNfTzX2|@5$iP((5-d^q z$?u39{>kp>jQg0e&f>;(5OB)jGT(St0D@YE>R6pQ&!}8SU^964EJUu0OaC{ocrYW+ zGqPuq858{ru>JoYM|!m#v&Ddah^#7OXNBlW6a+|>9Q%t3CbmI>70x+eh~X6|%e&gs zL#7tvy5o6UtkacQHoDgdToTK|@?ee|OGtTejSGAs_-#!;8 zt@<|DNo+RK2ARW3FkbKEeWXyWD8mSdl$Q8u2p1o3^<3E5;WnqXh(fOZwZ|2{h9OYi z`of_r;FNz+v}LK9_)`|(m2$et2sv`Sg4m5uFIhNeb!7aDvwl}otMpZB|GGkm#>>?f ziV3+k@K~@oWy70lo5>3b1L`ATB6w3BZ!fdQD+z1OZ3>Bk!1$$E1@o(oTT$@mOpWtZnpQ!Zm8X_qc>&v+>6goy?8LG&P;2HlrCvg*}c4 zZo*0xfv;`bNRGk0us##ODe{6Z=MK42fRrQ4d$~feOS~6;6pY*Cp69aoF|`yQpN={* z2QbeZVd4LhuiIQV6m1dW72XsaD#tW2(qvQ(ml-`ROZ*Tn)Pw7GvZkqL;JB1_4@a%k z^NlLJOp>)F5#>hsNnBleZHqlX`;9c${s_&mVy8E>GeMGL$*+K#N*nl10X{NjTvamMc}tK zi@Al1qa@Oa3SE=2eOEiURdls*u6hL1Aaa49@`eru=Yyur@`n1?$2cs{J^=T=dN0x0 z{@n8+Qzm`sD>+y3)-sOZ&QT!&Qh zog5drZxr%0)VjxM1n#uIGKlaaba6i6FZ}qMNsUyswd6Y8V%EROxDa8Jtdo+elBGw! zY)7qA*7N#!>hlYeS=}8-P&ZWuLN@-OGXim2evaI|~$^y5(;W?fl#!&=2pCc6KMt9A;cgaJ?TnWF?TF6e zf2WG#fy+X`iI>_Yc)nAyL95dGSj!Lu-+ZINxY#j93;|Lc$C(+7F=HjW0s2NGlNixm z*aR_wX4(+G)8_e4j9ejitE3a=PVqMqO)Dli<>cvw4F{mK__8{N&nMIlvh~_;6~KA% z1&?{06S-b5e=(Tf3uqK9Ik^P1u+MZW!o++U2_DzS!4{HjSjoY4xFa$h0V+e~a<%kN z(>Z|?;CQ;!2-*8b(#eW_4G*9pkgTpfTi#3C3({SkobedK-<%6;l=nWFQKieJDh`Nx zCT4%#Tm?5)^ZSnY=Z28wyC(-!q~zb-QqD$I()4uJ70P{Q`fQ(>6u^6R!b&fQ?V$M7 zgnd%Q3t=gR8Df!jod*p6#?VO4N&%_F?HMr~|byGZ7_t+3W1KcpXY7%pZVYI-Z@2b4jJE z0rzuswB+~X`$;qOzvgTzy>-J0Yv^ue?gJK>7nSrJyH?D;Fv+2c<&fIGd5y7P929?@ zKT|+ii3^9g9?BX2NRWXW8pHirxx?ZgX9)VACJ;5* z5Sz0U%l$L2l_v=NQ@fv)_4pFVK&mq3m@xcuT$nG|U9qCR4(o`XOfovGE zn}$x|oArg43ki~eE?NvIrG9fbWD5tQxXD2s2?pPf5DlB4y)YUYpGd9|T~5MC_$-9O zt9{jnO?vU<(a{(q&P}Sn%a8rlqxvoH^xkZ}@2Cq-B*QnWzI=U1Ag`y-J$o$l^7@kmZuN zb+lrPGeC+t_`;}I3)Z>GV6b_deK6l3RMAW=Ox5-^g4>GghWfz~Vs$pz2O8yI+^W#P@_y-r3c}GGa z8MHllD&9Q$!{QYY@7!v140`<#Ff2z;WdCIgA8 z-h?y|XhaVnbwKaJjMxp*Uj-3iF3)n&-u`s)cDc`(kAVWbEQ8TFi&rO1XAHOb2(h@U zbrN<2MvN#3TDhH6GM8xEJkS+JCUlz}Zs!mjQe6%~34yObJmF2+UEwD!Oq(A92&6s? zbXyd2U8E6G@$eRF-qJ+b?~B5K1;)R`rz8w2+x9+8kq2O-ljz5LLL z#iTI4ZEdRWDlmY0RJ3zX`x;M!rV}3X(RS*qtYahw@toOt0^@)Nr>jQvfh|n<98Was zSbuZ7YW=w~!-97AmwZc1J%^B8{E^AOcAQm&XhN6fH5fnr4)0q=_Fk;Aqvb_HV^ z941;9fsMD9Uy)5}i}Z3p=5RnD<;0YQm8VnOaN5$D=I1UnqmGC|!R}gMl#)H|r0~l0 z#meQjGfBAS0WcHuk63L+SQhjqY}%WfWbuz12*n2aR84n5q|dm|YtC#tH)3pEVxczN z8pu^tOVr>&l!{Csd}t!~%^XA+Pn_kg*r6fB7{{1tq-a>GZNdz0`zAi`xU!o3WwX`G z?f;(vm3tx;t2KYcR}baX#}m3n?&e~p1fXFp#Xh()P4A|O;1A;#`_*+Ksc)FdV5?)$ zbKRgO;*KmZ;4`MjcIb&x^q!<-qF=APW?O}#HhQ)lAv`4rR~)2Mu@i5GFfBIy?74pZ zGI+)sf=PjG2A+uWMW`?)kUxgrvZ-T3|5fk~$1$Rye1P;^S5mD6H87U|Ey2Xa{;ZgAYI5Jo}35 z#NJwBLmY)VFPn=CU?VhztvwT@m=KAZ=w zuxIzP?~?I6-oPYAeIuPLzIuVON=v^emu#q&;SclY;C2T4pOy)ML26wMZnriRf%5-g zR?jUMA9ey!W3cit&_dY5?1C{}D%g;LU*m5smG?p4whV4owVl96?>vXi?2PY~RKzid z_&xY8>eH0lIk~Zsd%tE+joGa3Fj_|Z@Zc1bRCw51Ier(Kqn;v&z@sa~{@+?d2Kve_ zPF#;&PfdR>S<+wGKc@Wg|9h`d>{=vwaC$rnoo8xBma6z+fXTElj~__ zcz9*6UfaI9i!$o@&g1a-kYDZrl-ZWs4*)el%D)AtK~?i|vlhOX6X?V}0bTIiRUnx6 z6J|vBwZC|Adu^NqL?Zs@yo$FKzaW2`Iu{B$57nHvl724at@)e$&-yC?KiJwWg&(7u z*YU>%;)*Ab$3KS|{^n<3YzWer{FEyY24zN^pJWVg+^^_l#%&q|NJY-!W@#MuAEn00 z#IsYugxXjXSp?1NuS*F8cVylfu-*M;@y8$d64j+moqRmz4hk$GLu(Cn+(R+<2~zXz zCX`DBn$fig^BYD=1RyZ>Kh5w)r&Som`vh)o7F!BrI=RqIXLXC$I|d6{{ERXFj?J&B zqi?|;l{wS|PSaH37T8(~B~qryWPiIZ@iY9;)sem&TDId^O$)OWa)6 zm(l*wIW8shD~*ZdMxY7wLF0i9VUsRuG4p99#JlUN*mEhC%LUT(V>U>ohX|6?8Fg|q z>ZO|3->X91>p1JopHCk6nSHC(1ZXA@&VT%WdrP?1nsXNH09c({Xzi7wSALfrrlX4w#iz5pGG9lB9ys{ z|9W*Qvh2Y4FN;HnlLrHO^HR!#-r)-3jQDdB1O=Sf zZIRGl(#{-v?(EotOdM;a+zD|5=6(4^*~cEw5Qg&=<|89h*KrH#8Ssl0ZdN__GF)oW z{kd2=RaZ$ImK_spQ9=@R6*msnxr3sWHNdlR+I`Shkymp7dIbi|Y+Z?ZCD4lU#eKvx zJ?;KychQap09^sNS|-gp4-3dd4PQ==T>+*jhvu)xAy0-_-)6QV@>(ZJLB}ZA)H?XyOj=_={s0FJ`Izs)xJ~)a3_tk`G zhjWeJHeQp6W}yidvwi!7UKVPSRvR#zY$~U{DqZ;AULAOeGDls9r9yRx7q7<9>#F51OI6T& z*bPR(1*?~v(8qEEw**tY-Lc=MzEWE%h#B>^$oO3~LY)q8vR>T?M+p@( zM!bsyVwdZ?%Dog~Ae$mKh90}C z4$vC%-5n!Zdy+;H+f|?{UnI=fd=63M-7K}dX0&kJxDQ58>+TS2c0jUC%A7#Au3W4mIN59|L!d|2|8lFc>YWvptY}&-s(#bnZ8E; zM>W{J(n<$#KN-Z@bK1fK5G5eHCjS?>F5ofLib+X9DX9^+C0*zp=B9%Ap%hS^1eIim ze52w~NkAM+aEvxb5IX53DCUP6TML;Ul1XjFs5j?g4!Z|?AVc97;cn^G z!MIZ-F!R3M!3AeO|MJm&Wt;A~h_)Ej9&WrOc4XiK0TXz_E}f7?kj#OyrNy97|Hq^q zHLd|{Zt%=Hzy{6v3~9EUNST&B#}E^^I!Rq9J0T_w*;~uWPT^X2HltrWeP(hP01#l{ zxmg6uH|=fyI*vu&!j7@aHXJ(oCF|zcu7(D%368R&t2gfif_ z)`~dKRnJD3ZAy;@%28T<>*GFU5qRbq6M!$4k+po+zQy&~4b7RYj|1FgHsLEwD6sn$ zmM+TNWh%|gAD#p>l^{e;vkCxQrYygk}vLy*|+HvD+)?e*mCk)?UvwO+V!_L zep7-T0}?WxZbb*pG@f~9BAv5xVC$92_MajWJo%=$$VYrb-nu~yTW}Txo0TAHEy;ft%&#w&Hb$l? z-7tjLn}0O)MY(2~!WtrvmCBpJ&9$k;!j(X7g3LOQAxh>kc$g#I>^PhObq5mi*Qo>I zL5;pL0GUS6PJwJJ)_`K?43rMw-NM=>n+48Hw-=z3#Wra(Mm#ow!^)(hUqnDyWY+M5 zGa>?xan5zOe^b-}K4LmkE;155#z^$Hr*Gjhe6)?lPw<<^^N6#XUS*Bm+K{1pffEl! zFkS2oeW~&#qaMq-oCGyWIw;BUSrW%l`j+z58gBZJ9@R~LQ#Yx5IdLb>Bp*ypU27P; z2#zmCN@WujFRVugeMF-FqS``XF#TzbZ9JBTm8eAYUq*$vX|xK8i{s?iBHglaKvHfc z^&eDRePq~HPDvI*K-Q0Usg2Ig{lIjuB&nEwGyPY9NvLRn3{Gm>O7{!E9JKK9OI({m zD`i^1R)h$&_R5Cgqy3+75=3D%n1&<$K_;KLR{<)J1-ZcUWAi;?!=tky-zMxWi`GRp zZxPcyJHF7ROr%CARu)##k}3Q9MOV=aP+f?Oajr~V==N`YWYkV6sN=(ux(I(e<&Y34zgA| z9Q$n5s|s=lA$wOUTV1RaBA&l(&A`vfnf^&Fz%B1dT9kIp?66n;K*_*Pe})E(%kW9h zqZ?SHQkkUvxhm&*k#Hzf$2wi@BIzx5%F{uk?h}&ieDbVVCgO$^D2#gjS~%|jOaIv0 z7t9zIamX`N&VU!AkDVS=X>l6TN21N&sqX(w&BE3s!=&@fZSv$`nciX@&LQT$t*j^= z%%E&KqE-iu;v*>+Z!>w4XfTCn!Qd)VRIC#INio=NIg15m_;s><$)ua9N={0f2unQ0 zCaVI+T^TB-SHQd=lhR-)3zM*|+(E6mzh5DmBmP*qw9q`$3SNq%c^+Y8co19B+XkRPWo52c$zA zj!t>Ahk^DikQ2rbLtnhb41BAdtO|1DWt2R1R=Znt1}y&L?XI%8{o#o+nQOg3T^1bz zrbgm-`hkI0&Sws0F$Y07Kz@5s=Fbn0sCRFNZ3BJiJknx_JUhai?r_3UM6oRwuQaUGapvbU6!+p-*CtsGeVvX{}Ot<7RBf0*dl4L10*G}RP zg?jWzk((9}yiXdDw zi@Sq%X})0)ks-XbsY~FpSgY^}=IbMHH_O8-rTTw*1C^;{W5-QuPbtl&mhwY^<&V^S z>rF+Xr6Fm=x9&<%RXSM$mPnc?u2B2EY*i?bF!X-?)PZcLjgHMQmdKFQt=3br7GJ&U zI;=lmAe{aJa_)A~!lFBSfv4OzFMQ}o=i1wfnZF%dU1l=R%N5D+tK-p#L4Uh(5L#3= z9I}XqupdAo1(X-g%TQ)7e@a*=FQ9omUDA-+bY3KC6O4_TsIuK%Ywx?g_N@-7C7mGL z%X_wxdm!_xp?%f-Uxf_gA`IVFK?zE2#NOE1EXmVXb08q3%yiIKtWx}oexq2eR5Gpu zutGg3^s?I|_1+`JshDM*8mgHbOR1prqj#<89W3Op+dzX#{cpM_p~ zEo>yvvmH^LFH%uY{F38% zzzF}Tu~YwLsOMu?26w`tBnJ>lavmZPbQV-^&dOab1IP5}+TCtQSbP=cN)@He95GD+eM|mqMYP`>UxEU7m$qHs%&}z{s*uJM;!6qa9HgZ-l1>^qARW~xl2(txds$%O# zMIRR3o1ZZr<~cApdZ_a)Hfk?GyKtoCtiDFgE=C!{CA=++Ehaz?vmiu{OLiMpY9c?5 zdB;9(N4BxBJPX_mwGdka-UC&n3A#=;*`ENn0Cj%80+Dwra}6FF5qHon%HzjMUCju2 zY4ikrXv9O*REd0mWcH;hPlXom7&PT~n=>NqK|ajMs&0t)<{FJ?oR`ttn}N)y(w~y& zi))EBiy~l&u)MLT?3V{&E1<%SIg!@d32gZyg?e-;=d;}DN;7q-!CcQJSnrYo@Pm-< zIFbQE5mym--$6dGk!i3W9*O%jna~FvQyni=1+f8HvLRqlG~7d^q)-C(2$P-1?fB_! zL3MU2(`hHbBUkbBOGPOf9Ms=*nf@O!e7mnd7UW3LSn39@jh7{Co>x~#n)Z0o7opI)*aC$s>HoC$-3U0$FS)v4i+aA<=2?xQ)dV^+6-j$i_F; zbjVf9h!ez$rw>o+cVan8{WDLd{^y#L7^-POKuDCw5;G^ja;0SdEb&a4b%lWXON@tA z%Sk0Kr_#{E1zsd2sY+N|>S~3tUgNxSAY~bL{GDChHiM&*rePG=Ozr*RzF+vBPN+jz2y)PtU)%{=klWJUoxrE}KK{rzrGSD7H_0NOkj3u!Hd`>I54g zIeP_m#5(%YP$;OXLCYMa-7eiqJff{(^h+GZXdb)X{3Qjic>h&2rkqCIZp_;U^l@i4 zNQGTKjflD8L)>wpqE;KKNTJYM8iKoX)wvA~7OGSFqv#46CF7>ZGe<5q?i_i>6ti^Z z#Rgn~Z(p`L!V=?b6t7q=jW;7+%Qfdzz2Toju|}Olo+W%32NGBL-}n` za~X+w+$|MYl2vK%?7QA1$Io!j>*CO;3`x^FT`4ch`}Rl22(d8GuSep`EL4oFeU_@# z^!RzZxtOPw7b0#q{YjAi&Mww=g#QEjZEzh@W$Q`{>X&r>l1ffuzgBVDfA~%P!oeKUxS+UHg=G;BOc8mL?IHkncz9- znJ>9D;+>`ViLOt-DxTO9nJ~_mXM@VRL0^t7Qw0pfDyF`Z3i`(5Q_{7T02&};nwfP> z!2xJwc%LD|w#5AHh{V=6N}Wg^*6DX)EuCW(z97rCR=hipB!`iPMQZ*eh(8jXa{}R9 zXfui>gaI&|+?}s}q2}*<=PIhtrrL0kCHl+rKv% zHt^kp(Dkg#tk6a4!lV(H_iIdNeTs{?E;J;rG}F$i$3c3+_N0P;Rj8hNIAWKYR4hET^C@ ze?7FTKvClYWo0rI0qw-&HjNg($Z1+(zXWCS1zG!hk@sn20ApG9HJXrNybsIT%EbTM zx&*dYLNLc6T_|C0wzMeTfFW+gM$^GPrcJ013jPH(s*iqU8NH$<<56)*<8573hwX zOoT+!Yr{(3`6RY_0=)IZg8!T~{M~mYC{=N@B zfK3A1dW3T6rDrtMFQlOn85~dJOEVdi@q7X0+EI?H?kMTFM2Eoxlv6cPYkM9|)p0-<732`MOq~nzKDtC!ppz z&AxVpfkmpOXB5D{eDv`?YN-UuxX~=;bovoBGf#meU;;ff0)R~TD@w(%^xgb`;c2f2 zy_I%Rs}bF7(eOV&0s4)Zw#QaMeqqDa+GuQoLm75>;bP44S~3A1+-*{*Z7fe1%e!v62wbq7Q}G;bxA zdJ(IxT^?Y2D2ZI3RDqz$d2l97IvvtCReyX+vsQ`O6W4S2${Aosj-yJPqrUxs&+5*h zLP;(wo>!F!w)6z)(9|c1)ea>4>pZa%i>D3;nDR}H87*edsJ+Ct#M?SG>1mO;>p3L1PQ3jzkUVsUWC*@R@81dsiD!zMB`V~o?V&z-tfIR;@xUGWF^PdahBXEj6xLl(EuMIbc5fxJ?4xvPy94;<^q;uYKa1s zwVl@Vu@s&K>#PSzcqc!CKfhw{6US1WS;VVt-*yI^5>32+jjK8rX&C()CCu-*$n1Rm zx{oisZNri2`P^aYE2C%ZEq=Is#p!{lNO6^Ygu@IAbLjYO4%U_Jxq?gOU5gtRfI2}t zH+gyN06On86=2MRDtxpufrQnH??*jP@vV<1AXlPr)?vLWE}6qtom7&Y0mgK6N5UHo zD#B!`*Jx24tVjK^7qyR8mI!pmbKHwyeOapf1TE%45A{YbFr3aq`zW9~B(9z>+S#k- z;s?2TxP9~Q=?QAWMM$7mQ#X!I2Sn7gQSl#{oND1o@;*S+>b+H>GaI4U1<1{k7z5QX!bY~(%(cWS|i@KPW**&(>LTmN;U1ft?T(BPcvAQnYM zlAceO^%V!>RP7$3p6n&49FpyWUJ-qH$4Rlxu7II+bo};Drmd)u<+Jw6^6vkcb_LElLT^3*G5yN*>TN_gRx5F#3vx$F@`|UpB z$Hc>HG3mkwc*S@7W$7Y0wJ09`d|%)EzSopD+}8V(-C0FPaD@CEaz z0GO<9F{1fH?Fne%Y?4g>(qmFI&rF1h77yxQ z5A;6X1?>rFG=~mmhABUXf~_fX@a}8$8Ukk5mC}G{N+q%_J9u%rCfgzt3(6!rf!7oM z_<4_X<4z)Fhygh@3<0qo+@mO(&aJdtxXkNR2e>Iz8r`&iW1W5Y*oM@G<5qpdw*4YD zS4@vCJpZzcBQXZ1sX4f$Ac))Flp1;n{H06HnyGKdi)QVvWQL3G+obry68QdtBMP_l zRKN)IVkxcM&ECDufsIhD892oCWB@HZ)W(+uSAdUr_W`=`o{+jkTSn=o4TN=G8oJb3 zfB+%tf$9)d;v*W5t8`)Uqlxcy!Mbvr8$obnE4p^=VX{yY{%g5!8J zsO`2tvC6GVvQ}|A?Xc z(|h(8lYvD%)7E*zh);;6d|}AbX3#6XQih2bIYYA)VSzJ0w;J17AeHq|HcJhvY5=@Z znJqfOo>QmOniS&LB>=2)zTpyD)(bYHe%>-PN#dK|vj$-lGRP0u)>X40!)c$ z^G_(A4cxULL~-jalga8It}b~Hh$~Uj^rQ1|sQI>>K;v5Ik|C1P&|tj6iJ5ft{W9XF5P6o%nW!PT!&51UY&tqKs4!mjH`$224%~}$ z6Ph_FerdkKGco0LB3U^ASHPc0@p3Au6^s3{uk^bPipy#% z$1|rtv&h?D=o^%QM~veyF3iYsb96qC0{jwn>U`b0$~D{Hw>N^ma)dfD*jkx!L8OZ} zY({EWd8`CG2JQZ;{(Q}7M2|<5N5#h@Qd3ezn%YMj#ese~VFH3LU0m3QHIVUE24*p4 zal~tF(<6?*Ax}uLO~doLoSdce1jT)BQJvms1)OtAY%#l!U-cqI1FVk)r_iFN^~1+l zq*;-#ApDAJsYfz^AUaK%I-G-AIfy{Va_odv;y)@;0wyA3JNHCb?J^ee44E+&5k z3)c!#BdhwqB*foHB_--xNU0EmKQT$_ou{!r6Yt=dL8%l)K+$z;GJ>WrYv;6jinWkXmqgc@atD(3FOP_QV*L?D}B7M3mFP@`^-c% z1@B)Mf)`^p0o;d(RBW?QWLDUT>ZTKdp!mPm(Sfwo&9LT_EiRU4A*t6GQW0FilG(y8 z|9ewftWI<4o~-6H4a*=VUB20-kb0rMNH4V1qXqRkl(K_gisel?wB;6(g&sIe6u+OShDnMie>ZKWrF%Y$Lb+4t@(GpXR)GjRK6d*S{V$bX3t!}T1N$#8N%3LqBDlQ}tXL`*0Lc=Tc**u- zp4Pe{m}9t!+6w7<5Y%|}0-LhF1oRwKpUb`6T|#PYTX%buMKyL>4mm^EYn=I|E1qx{tof_mRULcdT1{A4j)tCG<`xzjSsQZNp)75U$}C z3fa~I-lb5nq!f0}>=1JMnbR7G%9v)>_W?!-*Li7HD-Kl2HTTq%;*5ZBqMmYw>3`mO!S9|S8}DDT9jS!FFfCW11=#Ui^aon+`* z_R~e*?&*NtheKPAL#XJ!<#%(_lTlHd#L)oggjhI;9e{<^Z8Nf2%*%RePFsH?qnU4; z8$cW{?=6U3^6;M5GS@A*L`sVyc`9SN$-E)h{`-T6=k}fyw716QAQg~q@b+F?t&b*4 z28YGus#!M79uYgssy1_vAQM?|xQErl`~!TD!>csGpj~4=dQ+GD&xuOllp>2%{q#I& zQcpyv1}F!+QQ$uNFfJw4B6ua$)LNsUDdI|$`3G57_Kk|!l>3gF$M~{dNL95KEn*pr z8isn`uyui(oEldz#Fo&u>YHMCVQ!yfM{S3gY$Y-;5mO=IgUM)u%9Ab7jh`iXV8_Ix z=O@jMtn8i2`0sEoM9Xx7pWLUH=lfzM=wcZ4C9)Tf_*`{_!*`(2{-yOBNs=nB3O0u_ zabw*)%ZZf2Fm~38E_G;JUc`w97}{%szqvt2QH}km09CG`@QvULRW3f=mS!`xUN_g0I+qYhAqR%m$NcomYnrM*y zQw&0DL^1ae)4?#f6=Z#fd|*HN{r*5^5ER@H`byPJTy0H!mVfiS+K1f{BA2RJWmq~> zXYMwRKjOY(YL%5IZz97>j3>h54hJlwQyOaTfdHrf$*|}4g4>?yN}wEtqi%4mE%QeHL6E3Q$`3FjSXnbTkp%-p;%qVFACnN%>+HdnV;Dm}8`MQ{Ro?B?+dm#O8A6DU_VgSjz8oLU*!^Mp@A6m%k(X zR)CO>bS~h@N1%?dyn%I`Fy?criuwQ1ig*#L2+HZW{VXdCbxBm;1EQjM24r}NouYmD zIaicDcPi1jVUaQL@PP5%*8Rw$99#r^60!MAU$fyG5I)NDoHEh3uKdyl?X@007Az*k zCKBFM3FOZQ36ltKGEvPBfNNFni*fC6dY)vAN%waapVDf5NO0T*DwV+tGa~_AZD|>OM8kNu?Xh)S=Y+J1P+hJ+<=#r$yOFAE4izS1 zn9nQH=;>}$UI|TS*rStN#q&o!Dqd@ymH9qfKz20y;<($Wy|V*RFT~80t!Gs7G9gYR znh{r%^`L+tvC|<^QWbfT|FcHzM-P8bM4}AGK?veW_rKKKk}9KqU%MNt&eigp%^}`0 zDM?x1qAGJr{FOKRaVMWjT)-7Mhbik2d#dz8J^1yqS9n2PGs-oF+SX8t^wV>{E51Qa zFZX{A=btn>^tKi7x?3^qR>q&6+B_+;%{G~|H&Pz3{$j~Jph|IzHQcqre4`Eb-X}o# zwxe7l8px?=##|u=S@fo7{>k98;eQg@HsU6Ij%%-svxOvNpX4nOi2)y^CgO)fy!!UQma-c-@(6FYpc91j1vQbPqz%Wa*wCd z6(EZ;$R=brJe%lgL`l%PPL!G!I0PwAKSMQZFUMcK>7umTyVV7zUFyMWPM9Rcl?95o zgM*#i)K7bEI1I^9$1>8oX>Ux44rw-9-i`_?SBNpQo}cdjlv=zlh!Rd5Uv!#V)Z@Py z;PhWLpYj>_?m))=%jhsE7DNn);Nk*SgwXmdtTxc-Wv}&THk?AZ+Oe6vs+<>hmwkR2 zREZub9txKWPsJS$a?>o!z_22FT~?TGuJ%#f>sE+zaU>C;@O5FpdyQKecSYH}*8~ql zNcGZyp1FeApn$4Mw9s_9fuE-OUr5lF`KQues-44gPnDykg`4{@__UOOgr^m7ttu74 z)XMQC#JLRK48lGflwA6igr~M##ADI`HAcE#Ul{jU_w%wqDog-l&tbIVKzFXiScN?k z5_vxxit?t*mqU&8$zAH<5A)T+MK$H9xcUX^J5?_eCh+LncW zpQEyb7RvZ4jno57&W}f0B28R#%4|I1cm}lC3;@nHAm~6flm|Kk#d7XqdC_x|Tv2UU z(*^uVbJ8G;VUn<14hdI0dosh7#}yBnaVte1l3o1(#cROPf0FdLM#E9iqwND8NBsU2 zHJl9VHLWR}fRRwx-oA<>6quV_t7vLwVmO5WqiCKHX`%nwPHAniZx;w1pbeVwBg!+; z8(f6qrxwB^j~~!D5>c(&laRFK@6VGdY1@Wn#$49ii`+#OFsh*=zfMKtIuDEl41de$ zP^A0Iu&>DmAi2IQZs&nMfoIB!;?taZyA|_+o$@KvPoWw=Ej%Bz5q7Ki!RD4r?wTG4 z_~O5*Aq@NQmvb|UvLqA`^IH_C;f7*c^&t{An5BrKfT-w|)zslmBT!6k^B!~t&-s?A zhkZ2Ve(n^@x&s+$4|}SshQt7hu*wl0&06-~H#f`H+Y6y$Z?ZG4QR7?N)04IjacyJ& zS!q>I9yVikU?ZYrW2KYUh@yp(7(XUg<1$6U@Pymdq4orJMxpktuSJo+U~UO;ZzAFi z?FRYm!Rob9q?(ll{zuZmjNb+}POHQu%S2W02Tk)>|LSJQkuqg0Ph4gaypHS(OHA1^ z&ZZeaaDTmEhKGKZG*MJJ?}`TK!u>>^^`<1;m@hdO#InH>3bj?XIVO5GiCjpiI6qom zr3n|+gL68)fOt_MJ!}V<&PMd=@bhXf(7)LUWirQaSA^BUYj8E-mg)ZFGP*+-Rt z%ZPPGL-=sD)(4W_4*aByQ_`v4ON*@&<<+_|`&qcEg5*km{-dG;Ei@y)yvhTKHJhPZ zH=SlSLHYB@Kpc=QN0~OpDfk_N6tf*nf*j&MKQvj70}9eZ-ePjACD!+U5Dqk0E$PoN z-YDlR+7sPD73J)D_X^Xw!w4MKvDd@)x$lMSXZH{AC<%w3D|oH6bK$$cZ9Nxpv8I>+Xw>D0LU=cIMg8u!Buwv>*z zosmz_k`PA~|9sJ$ZudbX$j{JxkL@z!3HeJ-HUMq3wDqfYC^h_2J3`WR%AoG$=7#`B zIn8sFMFVG60WlOiIWz9^ri`Ps{2{LDz_;Y!Pt@8dyF`9EDSXZ;S$U?>U8Nlv!TISA zDWi+&cMPEP;BV$A@)+^v}U&|K0vY|n8Z#$&@ zdh7<4JA{j*y^`b#rj6l|DcDDHE8mNqFfNCL1&fl_rhc;b3vI)J(~Lvqh_;U4w&cI4 z{5OlsqL8spIW)_KW~N0HS1zO|s5(d!WJ!DWKiYpYCM6?&w5Yd`%9)+$A9WZq4|cLd zbEB-dMMGg9=rqbR3p1+f0U%9ihGt=tjNF32z;}c}iv9j?H7|P-T6O&<+AKBcI9(8H zwbA<`dzgKr*{A1%dZHceD^*a?UKsb+YM&Gp8S+~NVs01nUM+2gSle;HwMl>HLnXYG z0Ch&PhJc*T>*AzpY2?RBWdHe_`B{fAl%b1sSgJ2BY1c|L89@#Tdg0Pz<&Vi0rw&XN_)G-rSYrwcPNa`D|Jj4o2ko0vtOcKY?A}7slCKW64g!XE34Dei-RCan*Bp|Lvk6WZ zx7To1$33aqu1vO?l(kTu>0YP)?yT6jaC#qHmr5DMNQK(;;!1sda zDhMnG2m%%a*Z&9ax*HA!Cm1S0HVpLOBwKMg{}NC(e=gFa=QO1++08aN+XByK7%Ma_ zgj%PHO7lAF&n@kOZwNGa>*`{5HgEq6>QPY_MV-=^sbNkwbq5C$9IdGiWGD~3aCg|g z*h=@Z5y{|~NS^1t^o#QFr)wfzU?|Iua^(j50`@1#%m_cC`9t4dL>#CSziFqsNH<)7 zLzdmgm}TR|2{b{cz&3rvglG?8hVp3adUSt96Py~CnTBM+vUFNz!Y}&gyN1p;orqrM z;oF5jdQS#4|B-uwNTGWZ=BLYS+5Ys1ZOOE zz9|83AqbuCn?Dtu?7?Ppve&k}Pvj#D7XAz9Wsgqh%Y^j7`YzJ+W~Bjs*n66Q6IJm` zT(OjzvWlk7Pso|w=}0G;$aQ=@hJ7boz4eDEN^5&*flqn?9jp{ zztNVsX0T`KH<8>ek>b^h);BL$u{Y@myur=9B>KB_5L6{#Z}J%J&O}Y{bf2K0p^!cd z1yCoUmRSk*kTgHUVTB^5+;eqoIcOIT-s-)>ZJP=2(1q4s@&cZYCrSWBz9-O@spF7H zF7vy|S9QD%JXHk}$C1#=%{J10o)d7~b`}up>pqqB6ugIT?K{>pl0Sw0*$7J2;v;+k zT)k5p3}S&@h7W_YCsc@>o*}%i!Adx-!X37TOGBOeuR@)umg`!(fr%R$q(G~&)?=5u zjhcwiqx=2`^F2;1=iBP(_bmpwJG*dt_j9`?B;4u7vFJ^c8bPU6O9wIKnr8o0zS^Wr zpS1}nI*M2-SwP+qxs*!f$V-7!=AR`P5v?0??cL>yLQ(&XYQNZ9@~+*PVy zMcvhoTHpY(7Y89MG0otW1b(Biuz)<{65PY8w!bH?x3e!hgts{=ugIC(&Qbp&c{*qX zjf@AKsUb%CHZ|+Mr161WzeA&k6-Ox=N%!8@?A0xBhaKtm=@3iRgRq#(DS8tK z%;6_4Osv+PS*%x!i|JWZ?%dcHn?e_vhYXWA(K@!xGnZ@(aH!b(*a3a)N}Hv9w3gI7 zZrH7peR*i2bWGD^T);n_rhKXcvy3=Cusk8K4Hj+9aW{XV6h7^8ZDA;uz48dW(z*#e z;QHfg)8y|f>?D9|sKspVaZR(gd|^m1lk005R?}@#QkOah9^>fUTJ7_w-LVTYT5)L8 zZkrMH%c3d?(GV0O!zJw2Cs#SUs`cR!p)`^V74R|s_+v*8mUl?olUZ9okUT?j8y&Fq zL}$dO8C<~r$?^yfhI8t#DvOK}o$Uz(FFW*MKDrN@5dJw8+P3e}$fD!VGJ9$c$&j@~@(Mb@9Q$6-T8dOMa4STS<_jMihLL<|Mz3J5?h!cjuKPtQ+ z*cJ4YzHNtpoebEO)3abo*`$5R6Uc$=4Qy!NU?C0{TI=9@-BD$7{&t2NYu(p#2`c2c zhXV@GvC}QajiT(2Rd12EE=mk~rjEXzw_ zdbm%zsL>a^%iAon7S9sS=>Q1+-_kk@b>R*1;*1FuIs}L>KdYiXx@F2< zez4F{+BtgSXGtEf_1kU)$P%70s9@mFu;fT5<5PZ7K+RDSc(Lx2(+ALmlyY-z+!MqC zGwVwl9TDslpSI#$a`0-WhJib$L2!dT0{6>^!9*{`!?J8KeMgr-e0v40X*xZi`C2~+>c9i>m`P3*i5l~Yc zgP0(NW^&I|5lF1T<%j6JMDeUCgYZQ0gfj zYKJ5d(Q%1WBPA$V!MNYG&MEc7!U_0x0gn>D_TD9$0?zF<{6U%X(H{neh_W&4ZLS+A zV6cX6dgkNTSz|9`tWthQFk%@$AOezE!rgffDk@+yP>^$PRL6favdZ^e27;S~ z)i9aL5F*3(Fu zHSig8uLgjxFS^31TkT1@nf;UWq!H-TIqMk0%42c!x{3A*0<2_&Te=+SUtrip2}FfU z>q>)!)Fn5QDaDsQ9#3%-{V4;+u6ApOKGzhzd*4Nv0s0UL19~KS8ABjCT@3On(~!l1 zkp!e4xLlmQPoi}s*Xgk=r_cg-8+?!nx9xj)zwrhDB_7V^LM}!V=CNe$4 zTv`Iqa85;E#2pDOy-6ycTWM1so6%|R{D;hK&g1GYntD3^#|gX@Yp>=V9%%e)!6ecc zi!cyuz&zHr_s`n@PDm-es>+l#RI8+7vZsB!=g4c#|7K)%Fzz2VeQ(K$6FN(PoErc* zzBh_CLJwC%OF^jiZS}Fc|5ns`JMEUnKTW<`$-r&q0dU)nO!o-w?q~I#NC6|r=-zrE z=@N}6NiU&khg{oO_i%R*Ud!`)5S3Pdsy$2`aO7?I5K^m==j~_^;iM!#TVAKdB*&pL z8FI4{5LEopyiKkpG~I-86?}Hfmo>j7-lTLgtRwJX_)fRTULxS@Y5QEfkl4{7lb(o2 z%9Fimt^y(9$!r7%l8YoL_<-)rneCmlBxVr%G?-3@j)vlE$ zdlgXgT2lJ27N|MxaEt@aBxvcb%6hG$jfH0)4|Gx0C`||>6a)Fz|u?0|)?AtvT&#bQzsjr1!wI&m?cXYMhYccBau-K zx`{l#eAuEPHvJ5G*g`>bn$E5jsvtM;5fu)X`Esh+MPE%e{`%TqM2vNlpmDgpS=uJHA#OliC4DXShy3I`dRLM-h=q#33T`oCA$lvBTl0=YI=@P7vJb z5J>5s_TQZ6Z)wU3t`<-%!^>oZW)t7A@?R+-=_|PptOiSMDfsN6sGk3TPg0px&_Uk+ zUAkr(55gl>5C9^b_ewPR)&pBmG`uL6a$wftAKo$uxdLf-p_M7cR6J{R z5Pd}ZIRj&R^n2ME_Q`=y_Y1zO0aQpDX5K+mJGPEj6?&kC$xL-`oo9!Q_0bwSZ}hG; zNP%eU&Lnhs;6M#QUC=G6XmdjngrFlDqUlPBHpbnW~HTa)| zZ?=`F@?)=jN7C55jQHLJ9w5#8VWv+lp#-fW{DmQ0+J64Rkp!tKwS|C-jcY+b4 z2rZ<}J9WqslnEvNSeMi;>Y_L0l~`KSZWro?kIDqVy`luKN1D#@wE`97UIB=XkVBu> z_ql?mZL#ap=j3Csp@*GktX+1BnLchz|Nc{|hcOfKhTtPJyL3o*$3+_-W&03wykZ?= z;9S{3XumC6>lBjk*DEW$bgC%_&lenE933TH)p$Cn@0^-rjIPeRx_kki30=^5j1TwF zud&Sn6K;NcUmv7yS&2z#j~?>*pms2Mc=<(@ZMg|)pgvroJfzNi>|N$&~wKP9N;{pP6@SJdzeKrqUQcm0S5 zkJnHc0@A&Es|m{+*1qR1C#h$*f3I#;3d+S)O7m%Hag4gQcFq~CkCfj(wv%X=%ncDi z`we#dWP`~^ddJJpIWIXd7%7q)S}Yc7^qLT5JXVp`-RV(38jM2FBAsTaX&WkxF+^Uq zH*_z~58+wJKD2lv{ytZehVaqy zz^Ic&N0qBQiEY;{Z=U>B!KoK(@hNLD65(Z7&tnt+dHJ|HE4Gb}#7E7QyY{20)9O6D zUS3w`DcR$5aI`QT$6*RL5E@Y^<;^g>?+Z+Lm`$PWTTC~zeJj=^By?s zo<$}0nwd7WLztm^Q|N@-qcf(ecXX+x2zxP}I;OE+mkrE-F2lqTKw5|uAW;A{ujRNb zjFz|Y$MmPVJS@81F~`qLh;Yi%wccY6(La*HFYhNk;q-88!zdqdc;;SshC#?o`0wUgs!Hj8+$-ve&1t78Y!$CA4q#03~J^*H3ocQ2F06; zWf!Y3(jAkREr@>S({;3}1Wji(HJJc{2MWr=YHucvYN^A*{-U*SS~RY6U%Ip7m9bI^ zly*!Hxto(X)plTjdel*qrdEy z;N1->TCbtRluhR@N8l+dtS*yTIk`}ty6Q%6GsY_=L5DmzkUSDzFT_D0Enx&lgFWwF zdm1*h9B9#ur>`7o4y6U!*3DV%JQA=c~=?1;V9l{Ld8QomJ29g#n=6Y6`e@yEdlda$f=*4kFXB^@KI%0Y) z!-I-B+q=B*w#|H}M8z#0tv}oLh^@psj#(x+o|2RJBV&B3Txer9sNlNGB~vhr>OZwi z*Lru-ZM1Tdvl0vGzaV*hTVEWWxSml;j4E~S0`EDC2J?e_d!x&(Hk{gk<{%xVM+-*>UFCSh ztXM;!610nE0i-*9Aw$5Z4?|#BU$l)DC?#}GcUZ47BtZ>@=Bxa7?^GScVXmq1ZGzs9 zg@m>`ZtA7FU}y&Tq~k1FyF;{1?9RE?1<)l4h0ZL!RtY-x({r}samOpfB!pZ_9|ebX zi(5#v31?9+4q(Uw2#@ZIkGs6xJ^)8oD$t470wA+A?Vy!{awCXEZ(46ndv-+SLZubD zrN$)A=#XM3Dq-+s-D7lz7d^$Bs@#&r@zD8wu~{D5bXVR1#)3$rQQYWo?*ZccX0C0q z7gY;Oe2$2L@GFkyDpmHEbdlA=}Z7H5G;M?Z8%iJzTLJ)~{r$$V7qOoSiOGp)|3up$A>FG+gTwX;34 z#I9B*G%qlz&=EL$QusdBczEtthj&mncDMDx(rd0Cg;2jB++%e;12qK$68X@V13bYl zqNBQ)0=RhNF;R#vsrK2Z_5SKG;XMBsF1mA+U`|B#(7S`Prc*(1$PV`eR#lmMe);Q$ ze#nX|t*d%AqSzH0kdHSi`bp|}Yu!#TQzw^R?6giB8oC&?wgpqa0$O()mXqB(Z0k}5 z#eIg$`)Zu(b`OxHg0plbXras@p3~f5{0iiXcuVwm$HGcMF97jdQnZ-(H`8;y>EQ^p zQhHKqkoyiVe7Qg^QSkSW`SeMh6d_vGqTwNhtELoaRQYLyB*C4I7l6$EE--vN@d;tR z43rGb7M+#h05f2#%X>$C2b7paFNLj`C18qn=z3=`9MZnctvPQ3Vma#A>TEzT|$ch`XAg?!|Ok zA2c3M2BTM#9T>WH3KwB?(iVLX=+tOm-%CYMDhxiYAc= zV_ytPaAl9W7YDX5+W|H!>f@rNxJd6mAQ1@yEI%1NXLy zsbOd$ydr3h#SP5qgy*%o$$*JT)n21YY_u92bI z$o{VARH*(GcM;>r8oS?14svedQnkfx&^AGzI3OKUnb=G}z7!Vcl zx~_BRQbyS(A`=yMzEi@K>eW`YFEO0IAc2Nv1-uZHZe~&ZH#)r#YW&T41IKTybHVf@jrosmhf?If( zAXm$?!nC`QYu);`7%MqVU_um!WIu@tn6F)!)0o*5DF2s}NL4IWh zn&>x0@~S@jF{cWovdQ#Byk{Zj`)FVS#O{a!PkF&~+_cqFxSEanhQWy^zAU_LXwHMx<_DR<7J{!xx?1aFl$!L|4wZnRml8^iX1fXII9h@Cf}{e!Zfq zW_+qg#N0^J0>bpLG7gm);<@@9)J1ibyQOW^Ox9}V1jb)FUN5_TK)!S(o`67r&Ub5Q z5=x9a&`4%xsn`jlbbm;g{;({1&=}}k3!*hW#+X9rY!27G4GSY78EqWi&E~=ut9tL# zW3AQTC@J1`E3`WsY8U6(ilB-Zc2Gv`?_B;tcA0e2xWV`l247x%1;7DO_K&m(wlLc~ z_=T0qreG!t{+joEm+3DM2&#g+HKl@YhH+nC;^kB#v_tVd-c0>;qx17^k0#mkbv@hK zpaAangkn$4efWtr(z=FdhsLgKM47LRNY{--@_l)<7>ogVlOk??m5|9~(c|CA#>!Fdj@$ z9jgha_v6iCzV@feKq23E*E!h2Z};S3b+^`4jD0xxe&B>2rS3-wt2SHR+{|hoz zZTwZOOQUy2nAnzP6)vAK^eGR0Sdrm(=`Gcxj9va`a{`8aGF&titkwTTS(C&wc^HVX zMPoMRQC6_NwfTJ!(yQ@r5cDsLl-tCcBV*KZMHr*1VZ)9QLFigc1rxD#bT74TRF=rDRIlW~!Jy`zXfriF}gn0XV60tC2mYJis%KZ1B_shI?!RlUGwc#l}oV!I(!l+ zc@}EfC?Boo?V;o=AH6^;GgbZM)8&ER2eJGPfI0!T9Ib#NQ1R8$2zfYm#3)KHi~84 zoPq@94yg5%vLMt>bU+_Oo}Aevdm|Ce&Nm9v@|ZL+CfUi2OE(|TC43HdWPO=t zhJ_rz8n}SR)CzzcOL9(+${xJN;((;h3WS|7$`)0ub zCJBWW)7b<%8pv5=K`5ox7aF)d{W7h-xoL9=kG zn9HVFBF}_5i@QJW@3n4#ke$TjmI7z&(nJm0`^xNSMLbZ1uL$n$MjN=0V5t#O+k2af zflYD(8jQyQXE1Y63P8oU5_gG4UzmQ3<8a58VMtHvYBl@cj3ZZCmN+96AO}M-y_r(} zU>_M>A^Qt&exnpDc+Vd)Bx> z>1?TuMywH3(PyB{leYY89-jUs4Wo+%xq1~PlQ%88sFB~{|2j3H|9kjfGU+m&IlL)J ziF_I~cLVppx6pr6#h<2&wG>L!k?}VKS_lu={HZ_&yQnE-!s_p7hYqxZOztVLjHA+y zy?w%xFjCnT_bU%28B{+-Tu6-|SU~hU^716iJ3Y~@6>}Q07qe}!^xoxAYvC_L9OBKe z8#OvUcs>iAVC`Ld;n(r52PU44se9TGx*hp%1$A(^-Jb z>JiSL+0$i}kNX7f8NAJwRom!-h8`G7^1BLysI0PQE0~?%b{I*ncqt7_;*vnuT z_2=~;B95_V4OR|MBgGuChsa7kzFW=LH5r3huyhd^CfC>Kw7w1J6qI5u(#Jo4Ci=4 z@G$HRrtFIF&&l__J2WI?s_UR$J)=d?@!J;f*ZF6JX=ZcYsh>701P)-r47%^jw;LZ-r~$RV$}{^eKiMt_?ja+ zQfgCmUTt*X<#CdOZS+>;-Cu&gj7a)0lypShC?%3OlnQqz10Uw!0eE%6il#_Z*Z2g<(1aI+cF(a5Uzt@ zy}=^GTK+eN`2yCFAJG<=Cb}|i*&hH}4f56p#vP3#vcb3ILH+0IL-zC>qM}Rv*$gGI zWfOa;U*1$ztsjjn>_ekcH^|zkFH{&l9J#W|oWJV=rrDGnqGPJnT)3z1a)-*tZ2cov zR8_7qLN7r}^{o_O)R_W>gs{YVlpEMg&xlKLctx-g@GNCp%pjmnX!mTvy#h)mI$j^T z&ya+by4st!^$PR2Fe^c|YH-Vy z`r`I1y_;a-J{y92AH4P-L92ye-Zyuht_5eVqg+v=gGc};06G2WHCy6Y@3pXf5uVnL zATzWwNpR35T|xzo#T)B;SuYK-0+78poyUe7ri6Y5&P`f53shsK^y+6b?Bw(Fh)G7u zo*~BZj-c|i&Nu={(sPqq(9tNAZ+{G9+!Be5(mXT<9pB~NP)(VgOta)(&j8N-Z@ZIv z6n^o+K$YJjP#ceS09p5^1;z6*0QWBqFBzI-A?*YOi=-wXZFW|DarxitY0KOG#@h4T znk_6?LS$Q4VW8PQI>0DtP9a2p>7>ke1Fg))IRh{B*=Cgsw>^SiphY?M+jZ(W@d9#E zA$^!}{nV`+m~gw)47`iWp^S!xuZ%b_pTZB- z@FRXz_?+Xwf)-n9kBo6?%@HPUrBo<<^Gi=30Vq=OW2VuA4soHyP zr>j2fg*$?cX#0@98wbtU=C?YKncYi>3?6YSOiLn*s=nCM9z?-hwdlG?Dv;sVlMIk; zrWA7}lLaN0<}17XW+8e5Si=e~Vn@zsmt4X7N*fEOl%NME#&)vr;eXA(P_$dAJB#ew zB$ya!Sjz!32@Cb>w$>I}^tkjyQHP-+BnZhY3Rqh-6-!er8a(*jDZY+{AvjhpXX}}e zFqRIMbslOGvzIek4zTk-aNf62(w}nS{(A{SBT|p(9ZY#X*1Aa95l2)pq^Nyd$sM{F zxiuNzCw~{a(d@y-R3rxXJr}Q5q5a`ojG^YZ$k{?z8Z#ITBLkgG62w7I00- ze=m0Uel4+R;~Q#3+PbkSUvPd%QT*&0|KlBKRd?ME!Y4j~zq=8FXV}1WdNY!kauA`| zt1tHAOQqM_eeTk^2OxuT(Y8W{@jcrRm)+ce3X!R(QdVj0h3&n7POeJTmi0P$?Dsxx z3AD)TZp5fBO*zuBTa+`NE`SUU`f~w*ULTIsT4FLxKDE((wC&y3Z6$l%4n&q7D*CEQ zvvyiSPM<+lOq;3bU{;Dj`;EJa^eJz05AFpFA0Z}s=28z@C*cSu$hVY+t8BH&f{pjG z#-pZK^&aP%k!U*1tp!NCn}x(_Bv9zw*70Wy%+pLs3{6utFXv5e+F33Sby9B5YyI~0 zBgUODlvt^z=HHHj@SI(HX3D0mZu9w(fb5qV;WrXCWunnh0!3wapekHuDAEm@YY`~9 z#&Iji*Tvmtqfj#a^u1RcZIHe{>nFy$a)4gqwF6zYu5N|Z(kIQzicAfU^p7)spO%Mr zAjZ@ecDtgnXpn0KY|JW&PeM^5Nx;t;3LM0zXh(Nzo|QT60Sxs6M0*tB-CsmyU(Ij* z>x2{mbG+@ORH@&h9wM$a=3UyARb6gIjcs=F00n03bW!I#A}+L-_`=k+YwuX9)!&^KYdVq z%#|!Ytri2!l>Vp)jQ8}IUy$z#j}p;=YT0t5o@Uu!7Eb4^sE`dc}vZEQ2sC{CK`j@qxFW4fNZ3d}))DwmaN=LhJC_NItmE|3`=b8Rk zIYBI^57)w|H~>8uINkLQy1m#FINX60YNB%En@+R7j&TW%&U0m|C4Zyf(-THU2k83v zNM+ruZpf2BNml2|=)MvB(A0ggVxqdOA;G1#!9CE~QqRxtD!P0_FDuvLw?$P(55amJ zr-F$mOr@8Ra}Jox)t!QPU)PcfK-{N*^jiTOUCg>9OZs-{MjB4Am?r~!IJdRO%7q|w zeIgtZ>by$!pLC1FKRswDru^ucPawK7_<)s;mXi^tPIU3mIt@aY>?LAG%~FB@YT8QM zH9($S!dczFj1C_W!%PBhMTlsS>mmvIN>Gce%)&TH<|Kl~Pr! z(Tdi;?RB$y{N&qfKQC1RyfqwQ?FyinKV(-aUE!kG3rw%p(SL8Kd;Tcr%Pf>zq5l}! z{B^vgAeWZF4#oRdvPGjQEW*7M@?@F2j(_$a3ObzULvAiX!by51j=Q7kLtO>t92Xd? zwUWR# zJxsj|K2bCO)mVbZ#wx>xBg`=ZcsbE!S8+&*dIPYQ!;?GA9vqjEAv=DM&Ta^gr5H$iRb|5gBkKm-1P z-l-4JWie{&$9z@n50r-prdPE?5S5o95ik`XlFx}5RnOppI9<>*q2NzaJ!NXel>?PI@6_%cm|!&n(q*LyUTAvs6~}SH`*u4 zpa)l!WkgwIrA)!mC7)lD?R-FiD>_$-Osr|mYr_-Mw^leUc)x20;paU!4LyNN@-J7a zb5`iX0~U`+fQ{|D5auduoBvvC`B*~}<5j~KrhEcFMn*hL`-vFzPA`BST4Fu99}}yP zcF8|#pd$Zm9%~&RT=`ZDHNmJJpnd^7@S^zogAHDq6gEwaoGXNX-Jmzki_6JH6Dz3^ z)uO9^(nKFW7>G>cao@?<%}bq!@=T^QUw~C$0q|Le$eXy=5J2mEIfk*4o zNx{uSW&v$tzZkHWtRqSX<$guZ`$0V0-<*69Jl;XKf*;9t_f9*>p&ps+4pEmlLs?vZ zX)YGn;0tsHwzPANlB0VxSG0>rbrm^ojMaQ4#T}HLTHv}3Ig9ii_x>8I7LFBO>|24P z7V2p|i&^LH_j#l3tcXlampa4$yCJml$MoFDQA}CP^AA008g;-4G&*+4;jER;SRn3ilsMF;o_1RaLP#&J zdz{@-Y<=7%CDA_5TjnFFj0OHJV)^QOdF6ki^P2u#<^b$H)Kc5jm;*O#9Y{t5@HC&> z^4(|-P@6*D&^vM_4)LI%Z%{O3z3s)Fau>Z3w_z!8Tpzr7_DT%b$QDDLY36(&g8YRXl+fjKGLf8!ZV0^nk)(C!A}jz~_AH}~n_ zG*pwrHzAM+xXqFWeKA<)r+GlSI~O0* zJ+&n7@M#mkue^!<6<_89%B-}$lel;h-J*m}sL*)R)m`I4nk?dxe#pdY zgmrQ?5ci#Lixv_qysx9{Zb+<*WUt~1{qPI$LIFtEYKH7Qm}f}KV@}J>#t9l{2j@Ds zieCI*Ld7FPIgpyR)NE=hi|GTkbCuW>)ICe1uMiIt*+Lj0Ati5cq&>pQO{=hT zZ_XBh{+p;>sfp4lYh!vK`R&ApRUe0bUGaT%k)7Q+b?Q7F^o>Rq{-OM_m zXof4K9&1uGC75bsq{9zx7+}$#H9kxHaFJL(pnl)l$|ikqAAzphAA)ST(#i^xY`y${UmUB3jS+!k+Y-}Po&A-Z*k#o zVK)UIVb%5PJXx`UDrWu>n8TxsnGq3jV&fEzl4LvhxQEehO8UpT=6Bzq`T;4hGpr5z zTH!lE!iTLVuG~u@#23(_L}V`BRHe(-Q2H~@B61=*)TbqlaOrC%fLi3R60EG14KN$o z$Zw`zoh>Cip29N~B7m%ebg7@Ca?Sis7JYoCy)Wx-76RFJw7UY0lo6Wf(lQ%z0O)3^6?hXB%agUq~gi>a5n zbfbz>5_1(7^@QH~E65vjFWO26>BtDa27Ck|GVZ$gB@b=GFnVW~04`2T&*64ok7@~w z%yOu*q6we#oDlUiq`}4^-{C=7T2QYzkU`KQy@PsCmn{mrT&kgdn>P&I;Q1;r?Xw_% zArix)1OVj27Hv9&M8KbF#=JSH4+dC$ti}Mn9j41ii9!^qaX40yL;I7R)+E91^d2Q5 zp^njrTLV2`%aV4HqK!;oMh#nT*yd>Q zxYts=A|=&$hMQ^Ij+{!@Mbqyi_3 zRQaZojio0AV2~p4Ep5d74a%tJm{P=ym-^!(elIifv-_*|AD#K?dg;#}w4vgBsR7H-+5X`Zh@1O@=wo)%@ko5hTBlC)kv*pTr1hoHVq;3O@4 zy_8=<_BeuWOlQE?NxqEFshg)+=mDOrQQK?3Dj%}g=|+n1A!muhBg@YBv=;j5v;V`C zL68PJ#k3a%W*J2W_c7|d_jXgPU&*Z4ey5|u9r${nd`2SJivEGhsC{h34r@+mfUVpb zI|jFXE*p)th-FJ<^u-&?LGy~LA~^6D0*oj7rnq!ShYJCf_L?iG#gd4Q;Wzl*$29xq zSGfssctE}7K}XL*xXBh_4d%xf9uKuquNgru18Sh-Lo&^8%Z^+ch%{_&VSLh(J=9Qm+h`EWm zcHb$rXS3H>sCzgk9wCh!^jNlKF2A5LMUfI9JEoA_{d7dI6_U_|PF^oZ`h%SKfg*#A*$| zSfT8jGy{jlFxl*x$7XFy-X|UOw?3IK>o?X2+=hD1)%-^UMZIx?L2H7ROl;)_W#|cH zu9u?fEYXL)T;1@tU6%iPyo1m~RiY9AIK9#zCtG+YkCR%iAw5qh=YE>_mMlw!##25( zoJAt*aWCn8-wG%y3y^zw-$!NVdlgLnWekWNKQ_ZRv)uY2!ytkb=c?x6p2w?aF7 z1YJ~tU3^j&gr^i?Y`E2jfvFVMwu3YNKCCk+AeO(-6%J>TENy5^DM!pj58z!|6SZB! z2QQQj*`Kk87+Xjp=c@jdjQl|rgL9{z%y6rTyEM|_CM%;o4==`KFz8` z$1eOqE7z!{k<3GwtdP=mSM4Hi8`Lz4QbG1)a3g=i3T6n?E z2TI2+Om#NhYF~RQp?r0@NmMkr-7u=8KrINMpw{hespzX*iE61n8FY06Dn0`g+Viai zdSl?EV9}Wg*hx!H48`3ry!;3%gxBn6nCbJ(dco1BlP#$YN%sO&SuiMd@3f2h;_#V8 zwNa}&@Ud`diwv6iP!>;E9cTl7xLp-{8l00Db`xFVILA-kSErNrG&JAKCxwwTFt$(? zLc2l@w-OxA2Pm=uXr3LY_5ll2%e~dZ>6FelSP^UA= zGTqb`Dahrv5o%>%OQ<|-HpE5gdMUHUPA}06kBh4Xytg-ZP7UuBZJQ3Jp{!FAuyS>i zmR53aeW~FM>)&t+2_$X*3I~{^*oQLeXyMBFSWWwZ9 z9KSC3c7otJ4y2bAark&PUW(1(O$O{yeXh4^<3g1a*5FE;GwNQUcH=HwJX5bD9Z@5O zu$k{D1S-+6tV=MdL`0FItjW>j4Rs>*T$H*^FV(P}Y#DXobP6BAs}rZ_rJC~$Nxh9v zLx+o5>Y>O$CO8HdDW>QF{GJ)9%(IlEGnRD4LpmE;TgfC3#&)pJeF5T_BMlj~mfklk zp`Drty*{)8`DN*)CD4@wbUzUCxNyMtoud(1Y1(Fa=E*{IjMcQtt!WVkr<3Ii z;*O88CU!f4Qp5BRN3oodd79|!8xWqQ(i|1^)-2?|uo132uXVIHnDiA9=h+TRBfAi_ zV0$QytC0SYNR==@5{GI)Xic`Tj==0ykHZ7`uGltZ5bY!eByw4A}q3k4x!Ny?+<=LCGMW$g|4(x651d2n^v7kD>iD9tdg{aungI^q-5i0 z;jqFWgWsb&vS)Vw zgZjcP6eO!Hk)r9_dB5&-OU}P=`Xe=FUb^cqbGw+TT7vzL6UZd0O6CP2xbY7+ zmB2V}7cguPum&6i7mGm2Z@r%eqErxTx4Ciw+t<(1HBHPj^a&vQtB~O!yxjXyg;&WH zs(awUc4U7K%>+neMMR6G_cgOB&CeC5=GGN&5b(qtF)6WB@M0dIvm@Xxu-FFgFcUvP zMip>T(^LbZyD>diED6uz4*IL8*xEa6EqCOKRMe@wA+Rb5S&hnMFqG4+np2&RxjLKh zmi+D(^7E!#xQ<6TaA@1B3|rgb8L0@McvK}k*jB=0?@4oxwLS4(n4ucKY0a0kAY6$K zMt!>3poNmwnJ}sqsbDXyvT6xEZNVzp_(`Xwhks}*noWUQISw`(=O2_K+vyT`SQVmU zgXILA`lq=@qjDFXv%%z^TZJ|$7<-6`!Jn&=_FLnFB5draAM0MI4`%(`5p*W2RzESxJ;<@({(h8TWWpueN(Ft?lXn2bULNk1&E zaNBTv*N1xIk0Z_PN|9)kEZDpZAyAYTzMVWNKwXnVF5lcW9%1)VF*|wumJ(IRW|D} z9XdqkO_sC;^0zBcpv?Oj?}gfd@`ckq8B6V)v6fR@QV+j_Wjfbp&-~CnWZ1#qXjW(+ zZO(s+(_Z7M{WV^DWEU!@q1U36m>Ns8RPcSoW;l}E8bPQneYAB9+M31^M8-we!|!)-AV=rd4 z%Cm0^Lr{rZ_$=c?MgoE2Hc)dWevyBJ<{Yr3pOm>E-)rs9Q$GHNWN0od2fM#~u1$Z; z`g$YVL-jBTK%#|AF)XwSXXmImR>T7Fbe-e=p!5y!CkhHd(V%Lv*gGGR>9b?RkzK6C zh*m9VOY=xys!dL(*r5?WdXVSH-#%$Q@ob#jTQh2r-=9!jXWkia%tOCm3R%-kvv3Q zuNz)I;oM(~X2CFlp%Wd5s|ZcV#Z2q&tV1MJK1uHpACfhPUR^U6{T+Dud7}}% zdLQ|BEP0hVsgkYg)DTCmfn`tXmoT)&!x?5pT2qb)xrpX3X>6H^*&XtlwJ{8>>R;)7 zv!y2`3utR=XHbDX@pt<@==qSrtz(OEod#X*kkv2ecw5aT(Ers6Qbdb)!GM=Rqbeb_ z=~_8g=#Vsdw&_48c0`j)H8?-L=;PF@jT*1;C7r|~jPrXDZrQQqfC!&M1H(;koT%l{ z27}^Q_RSxD;=FTU2n3d92{s6ex4L?zK)!GUZ)rs6#+#;8bluXqFqK|-qqm4;Htt87 zyYhMhH%i)k#=Ir|rQCN-=icT*^8$i?vh7$?nv?5-lx}OlwaO`aXYNER(dPi;rY!I< zqCr*LZ!>Pn<-=3o=r`H@&7-qJ@8}zr?MwWX(VeE*IlBbbRy^-z0+af0|Ixl@utrOu zL?f#YlHU~}k0;=!>m-A{iE>zjdS zrfKnx^`sb}JZBb$vK8UHSa6AHkw6gA3USz63e*4tc;aP+QjuQfLsw88e_vDluDJ96N`S{62K34nzQ%i(LTWIN1ACX_;FqZ# zNXE2C7Yh0RklSPPcsE}5AfN=Dy)?t^(#IQwwgV#7Ph5_x`dqkULZ^j&8N$LnS{iYK z3Sci0wVI!6X=9lEY0I`X=`tjdSb#LBqm1kJYi8FdES4kTJ*7GaA+gcWLx_Og3wXh^ zN0e%8PIN3!UNuLj8Frh4rw4$GYqk6Z~T%c5gWShCX3|Ph=I9c&2Ly z@tDD;JS20tU}!+*OmG!LUfUfHiP~oq+gl_ zt7HkE2@fP|pwq`q^lwQLoO2Y-fDx}$D|BdSyxP=6F6t(Qw@q8AIR#}x2K7};AsHKT zs8&e7g(vVE#67)Y)gHvv(@hlPc)EG93B|DJ)KI&se-u>_IIJ0zeu zQqe4iGqdEcx?AEA7qU=Ci8!W?5Z;L{O&4#6ZE*@-cJ{naZ<5+_?ekgaZY|k zc4l`fghbVQtr`pW`16AS#Aj)8N)=hL!ZYU}N(9m*<+@jL%12j@$K91(7u(FUAi#bf zq~Tp*@%-jb9w6oe)NTY43K?V8%MJv~KL790pAqgzMhNSIq;qzD{m8Jx?WM>IWE!fB z&Qs4VI|CkFV$+m4@PP(a@uVcr!^GcjP=M`8dI$5H{&Nit#-k{-0G$Z~BrKyx_&JiR4x4mQwQQeN zr+)E@X%|_sNOFaJt^wqJm@icI!UeO5ZDe++xQR<{Ykv^vvmSHXgp8p?`tI46JoW8&P=m9O9QsD#^o_O2 zmuVtbR>4a&qC%*@^zdg&g&=4Y~d-FeFk zSW>H=-~E=uQQ2trsT5_~56_lK#5|>%;YO-x8PDO5F}v^e*XMce%B^$QuRoOa+X0fX zdp*4au(5_(1JIwdgOL;W=W=Br399=C)o%UKW4Y!v#i~QUhVHnejD8xmf(FWbJTfYh zAL|J{6X66SF8ThN1!L{aV$7Lmt0w6!6-7OdXYBM{UsOkSmg2W(n1SQ${bP1WXjJfCydow+%KBkQrWi6T&}Wx!O|&(v0rIy7`}!#ZzFz^KAHHU zt`cnC-ZkuJ^d{AtH3vL{XvAl>z%B<<0Z#!a3;{F`{E0G4T_ud`^+!nYtN-fVBiw&M zgPdq~Q!B*?w$NaCDvm1deLk@lxs#g2OrJHEA9c?=vUxUGHbx#x7O4KAv{Dw9yR06H zv|MXw&6`Bx5e6;b*~uT4!e}d&Aa2D+cV(BeD=<%U5N3&VTRG(u)uIyp2%9xV#Raxk z99kgjaRaU=m+2U|PDXTkkEF8{vXFaty{X;E!Y&UP7Wk#uCHMy$uv@;ZE+{L0v&BjI+f&T^`Nq+zPIP5wxvXH{f~Ur$lKE)7 zRv?RaJ)0(Wf>k>nI~NM5Lu?U}l+^ABIMokD^0(Nb&N|)d>OZhpPN%2f8Znm)RWfcc z%J)5`*&YY3#jtGj>s1h+2M?%W0>ev@&H?>?h++V)|02Nzx)osRFNhaczM0NvGkFT2%hzn z^Bir1+ZjbBMj$>g#n~&0xN%~5f_YjT7xfC;(t{u-*TM?gA zZR7#D`amhR>o*5MG{%3MB&?4MJrE$F#Jl*v7ghWKcv0nFm)a~dpfT7DWNRSY3yAPv z^j3Jx+wNR!Q9EuHBFPZh7#6zvW^Uxft;%@$lM1$p#vIk^21t?;iYNC%pKTxLVU%%WgJ*uS%R3K z@Y|b7MQfVU7he2rhvr2{3++EYV< z$CEDDb)gSeS26cS;E%ZebVFwO9UgD8QPmhdt=K|859VU#xG$C6C-9rbQAqmw zks*=(;j>mcUz73HpuAX5bZZHV0K^8FIRj-{gK{Y@`e~haUIzs_yl!Xmn0a#S1d6>W zs{oQjfInGP;6UVZ6nNd*9b}Fi7UK4hH0w@6srOB=9ScaF(%^&~3%hoShoa>9=JZ+AJWMD65hPH#z zgNob~xjKZeBQi)^sPAkMfBN$jGHO*d%C1QzoZen3W()bf`KBoZ#x`-&Gd{&Gi! zNpM)ht2D-xQty{^8kLG)3NDm%kZN#Es3?i(=pRybk3P3JG`Of3!>S}$z~6=hU0+dS zgFK#Y6{Icn{`K1HyBx*RLD?t~SzAkZLxF9CX@JP3ZRsU+T{!-oa~m33qjhf}9c2)f zv=Sd9{Fl$B%i=vozk1T*Ku3M;GPx9L?_D*3CeuG-nF4$H{+(?G>9T@MWijDPmQ|>2 zWL7nXo7wD|U#1*Mjx|&v+pM%W^Q)eHcBP)5dmu zsjsj6;)mvhC0&RPyXQz4US*y~-wpYBct~`FZroBplY&OMMXmtNG${RXBKL^vJz~C+ zU`Vxzg>V%Um5eL+N9f&jSu1Pn|GF-j)t*UyNFu7dx7M;xJkvxOO>%Cjk)-|Go&~ra zX~?@jS8ZH1n}0@78SwrG=W5bm2ES!Z^gH5+IR;Jsn=aNRg=AP3eLn?UB`tGm5L~bv!Uh;8`5jm#}wikYUIwS-o80&rVQ9&+F{|6=c;wO?^B$is_X&*V05Px@Pbx(<>;AW4rqD9H%58xO=-(w2ZXTKbH5A*-?oXr^N6H zpF<32=f7^h_)28e$XoVoMrd5&Nn{u8`Pf8~BI}|2=_2QW7=rpb^K*1Q(Rq$aS!|V} zV0{ypRXLFX#YH;Ge?@oEUkCxRJZ;}c3WA}e8Q_ZC^1y6L2K10DLkaD`V7Iy)_NW(7 zJza{cHq8eT216w6!Ef@Ziv_t8G17tFG4%x5zA9ZB=A0F= zDE>G>mS8%Sg)HkISRVl z%*xt9|K3a^Kjm>R&KQ`aN7yUQCU+PLJGrATGpnC;csOfjxI_Vd(?s=`VQ2M=8mUOT zdUMq=A+-M~olo2z=KU&pO)B@^Ha}Ms5{9rz7glja1(q^g~k z^xFo8I_+voDS19mBLwMoQ9YK>G2jq>g?3(l0_dqm|72Vu^MwS7d&yik^uWCAocX+eT%mj7OR0Rcj_4uiyB`pZ2`HQ=n{$>$(&L)lUuOKdn zjBY3@r!Z|%b%N-!FG{^j%ut}sGD#0>Dd8F}G0gKq(3spQR0Y9mzCzvaQ%Sxfz0=KKlfyua^Rm>||Tfxl3Y8jCfguO|~A!~n;Y=NBe_J^Xq zt`D8aUx{n!!oS>q#bi6dnvl`>4XB4%x$yFFSi3RNMwziO3Vf=DJ`ADzttb+Eod^n+ zEF3e{Uq=!2=Np$XIozXJQM0VVtg%xybyM|FTO5HUZ6`xE>HiCgpyG`SIWMWVDwOUL z6H<@(OP%py53Eo)w^vF7t>Mf`Dj8UlEaKV?-B|-j303%dV*15UQyDlj!cXqO8J^9O z7y=JP$zSC3Zv@w8SzohLI86@GMbGX=0BL0ATpr~-VeaIF+mHg>ljXj0|4CPIQvo(B zo`8bQkKH0|kJG>y{VG+^ZPMNRKk+3&o2+0LoorI84%oztii_}$1m8d*vF6o_>yk>i z07fcTg9)ilstTjmlc1=?jNsJ(b}W9SGac%?$=IJmC_!h((UhLM<-z)ygfm?qv0P|} zX)4Y5{&4w?@WqJRjQkSk)nJ2jT$barVa^vG?-bl|r<}0}XP$f*;7n9mm{3ZPhddTj z{6A4oS48C56aL;!+-LhWYs~#Z348QWJDFd5>Sxxj+lM&Ed4z%7?X@-BULty8IO)@^ zlkg~?iOP-ih3~5_j3Z}nmpbDqQ&C__ap*XiEZ>1^@ZvV)^i0H;T z!>N6YU)RuGitam@m{4IE-$Ki@BLrzJlM7eni)aP0Nj5H7D&!G7&d^Ra7b)EsE|Bj5 zJBTp<%_U6|xRzapgrk>{@{Bz11g?3ItyO58&bkkqo62Gf($$jQi#s9%29?dJ5%k_l zGS?dy>!6#%hd@jcef{vD?0;zeZntOA0|yP8mbzGIn1N<4J~`g#ea`|UhZ)2>A9_c= zqsDJHAhJk{&6b4y;q%B93@yD{yVIOU&CEW zQ@R}?ti@fJ3Fo$4CW!Z?dxT1kZtR8x7b*~vk)q_VkN zaLS`i!aBj4L=C%LD|;lRxL`8gf~*oo&F(-15t)O*_TENzGNrYT#E-LS#as`D_~(PW z3(kT+5>jwLvCz5)NBQ~;dz8Z=>DVc9Ko9X4)qh#8@b|z&VkpKvFR$bJ_Kx^dr&gD1 zmeZAK^k21qTIG>$NqJy;FeGZlpum9ErppCN>Vd@NJk|tvp$9lrKI(NWx|4_*t=cC{s3$R*`@)A zJV7DLFVi+LkF(Be(7r=C0t!7zf?37$X}eX2q}nMHX4ak&-q1He7m9;uA3e{Nw*Wou z113xj83P5}!H_#KRxKmu`iVJ7~A<4m)39TS!G=xU~<>NqL9N0d$6Du5xdIy@OjDqXW& zQc4Sigevp0zj`a2&Go^`T2wU?+LM}n3p?qe)4TlxB|js`n|X7MiFN8%gMI970T1lx zGO_`CPSCtuv3PfP^jSIDru!XJ(P(uU}P!S9knh8(J7ivMfup*2-sKU z%Tikg|A~UWbEFuuZtz8plq`V)rsa%j-1-=z z!vWrc_A;W8hn?lUWo1dDAsT^Ba8z@n)_o=DaFU$(~WAs1q-64M<>{^-RFH5JC z_|gI4hV@JnYC6-n;KKO73khR0uCXGoS|^EM@pfbC(*;@LFU&i3pGTgCzrvM%e=90j z16SxGzE6AKv=1(lL?2)U##PKl?_~N0Vka(m+^lL{(eic+Y;o4@AhA}xzN{5{4s{ua z=WN$wa8p`(X&p@q6#BpRo~ra5-n?P^wo*VG57t0`jD!p+)GKtx<STKhr$JL%A^?ff2FXkRDZE2>^{lhHL~&J zb3iD+7$m3ag2Zvfh|~UhS0qrM+6k-;2BoTdnhSN#R9*5Lv5*~U^ zvWBR->&;rFRN-?CHChg9eWnM5U6F+ek{`2NYEHYuYXgNY#wW43zA(i-c+^{nFbO0` zNR+Z{RU;xwxSKS0(k!ZFYGld2^La^FrV%Aq?wKpZKn3>{r-R{nz%mcasdWAFL`LAnWt;cHqrIHT-Ux%_d#UIhDF4^Z50 zVtsu=IZ2E;<}v?hNoX;!cQYv_7{~srwV=q{>971tn>%z+=n>u9$yWcO@ad1jTYf z38@J+yj+*R2=p!+ZC_hZW8R}}1YiHYXKLvlBQ}}LHvRZr5td2+cBOR*ZG$krX$-f?&qQXI1eS5E&3=}IsHfTvs--x| zCrI9sB=Qp4Og66GdCiaa|D$%Bn#z*{A3&5A3+G77e$R8Zby2j_^m5P-qSAuG2v7qzN$50WQ>aLSy#ZUJCZJ0$k+qmM&)Vry!bJL$GC^|JdPdnz>( zC>*cjp&L=PM`y(w`s3Vek}OzTot%hbn$R)MI!m>=q=OYBntDLJ{UZeuLz(9k4(qgcN)_tv)a;x-xl;tBAQVRuNqVRd19Tg z{xe_z!wvt6H?xpqM56fZo_6_GJ5%g@)a3I>aYZr%FryMt_*Hqkx}~ zLWaz_*F$4xhx+_V+@KP$_WKMGli@6NTtq%bJum2n0h#%(BBAk!NG@zZmXD&~*mCH> z{!|#%+d#F1@<$!Ym^t%4t=ZN7nRJYMq87q(OrN7yZ+o>s0&x5^31B7copj&Ip+1J+ z7`lGF%sq#y%2oZ^nCYIU7)to2PS+FCe@xbrH|{I7YM!YC!zcxF2C1Su53a43ZM_8< zj(Z9iqwhR&%>`WN$Sq$ckFpDd~mpqs-(sS1X?R+6rb;Nv{U;$z*zUo zu?vh*4q!e6pD}KdLWK^YW+>ifQnRJD3qfB_oNUuKiy&RXyW7$+lzdth7g$VU!+ybE z=GCymn?f<|Cp|pTxbpUfa(S|}bDaQwu29-$dJ-7OR}Z* zvK`#Sp~~sCf?A|r^PcqG=IGX;4)P$MmDdA^vvL&z61k+i(6X4IrzssD z=dGN4FT9t&<1Kc&Y!9dT2S$s@lu0^CGAdyI@k+M_!HVZ*iR{|6aUd1 zwM1Z<>op7&i!(t8@ei2p7uqD{$%wkREeDcVk#q7HLP_Np`)f2IdKtJjm}e4(*zLN_ zIPs+JKY_;&<)XiE2IKx)sihO7Z%gEnuML6n7USo+-1(K*v3s%q0@O=;KdYpP1&G)P zQ9I+SrfF?Qk)%H|ZlOQN9>Cy7Ic|ux#U-ZxqATp<|0hU8DcF#Qn}!&J^^?<<|xYx-1IUBVYYDGF+19r0K&XJ2KSn4R=8rw@22Y#71TX5491MnUZ*EKWpkE`FY%ID)peQwVoPD;Z24Q#@-Iv>t;$+clA6QqW0#Pf zT}1H0)AXN%+G%9_wn0MNB`P5#7Tj)BNXrb{&Ew2d7~li5UMzq(#IUgL|5_R~=i1>y zS51w!(ANE2AQG8gNLAk@22=vPHg6?zs_GK`fE32vj5tjlAMGf7S zb1^UOrf5Z{eBA!O*M!t?W$8PkDS>{#w9O6a#6*>+z4v1ALPP=~2GSVMHanML$B6pC zi9|1cQ09^Jd*DlfpV5nUnX%^rh+Hh%JHmnK9pB0(ct~=vpGAkEf@(bErF6A>4hE%t zu##sR;e+>-1SG>%+RK$A^Aib)xJuo4P(Os9T&EL0KKyitEivjpD|79(n$PqljFJ`; zlERW%NXe|e^wT+NI;hnbKjjy^u2!)>-Dl^md~tN603G7_H(#=L?#{4OV3pdu#4kz7 zdxs574=$_RCB6>gUA%%5rfBChe5B?-6LU zM4F7W(kIvjR(En`9(wYaG=OD?vz%B>7Os;?%uK(3{?LHtAdj91mgMk*9CAzm`^43+ zYXX}6H*^R&n(=nph;loyg*2(BL~VA|0yY5guK+aT{&#GX_91&=%~tL8RaY( z)KU|O6fu5F5)Vf|M40b-2=r2RDN}qBj1|JRpfxNqIO-rcPca!w#8H9VP5>4AITLkH zL26fge$5&wVP@y9Y{-;nH z#y#?mja|jrwzZ43wn9uDlh9CaHh46eYkGHQB0j!X%Erdy5cWQqkH0jiL3{!R|U5y|3b$h7#My}SLO6TH+@RL<1- zi}+boc%f#>UVTp-G}BCp(Yex!4I`T=IJs23|0(&)<^-~E<7p>z>_BQd6pJTdyEjiD z#WFEL2MN=v0Fm1V8Z+t~am!vIc_$w>l|H3r!h7bU?$PY!;Wz}b+lV+n4KW0#S=`nE z1AB9ymzkDM5>qN@JK5op9mB9~{I{Qeza8z^n0CMM-pNyhBmqUWm!H-%hf7RBB{kwt)TYk|?}5tD{uo3W-r0X=H!6_jL{0EDNR!QDo$GuT z&ry85zq9^Qd|!_Nk^f^k(|BlTO$IQ$e1fQbp%Jm5#5}|ZV({1Uz%ZlHC9LO~bUY}55ECk&HgsW+O4&b}P24l63?a*;!=#Qf=T}JA?PFBaH zj4N>xf)G_j3Ax=c;3%pwQX;;z2epuS%98o*yv2~3PcFU!%r_rpods+o*A-V3TOQCi zY~BM)a3ltxBMevRDLa_Fyt#94;tOL&*OL7u{=H!D90k<4QdU^uOwiH*hpXw_jH}&#` zmlpv!G6geGxSSszpTT-<&%B})!DO)oUnzS}eX^shQR(7lBque7Z z@nWZ1!!BlCoNbJLMM*8(0loeeGqH_KH0XEbWOSpYsHgv%yDB{fng4_O93@kkAZ+zK zKFWREwHb}C(bS`j4$&T6RtA(#yOA667!8HcZncvI`*Xw7AW$GJtCPI%RjgfQOw2{@Ee+&#_2I%FYXLUqgHrrK2#?-d_= z1`13Zl4A~K=tJH12P}2>hu8@SPB~F(=$0w^MP0FKRDrnPTj-aQaqx*0Wlz+M8mx)# z4a1AVQh0ILi%f1Spqz*Nf@f4`q{&3X0`zeJ7U&5|$tY7d+?ljn!lWV?`%Y0zCN0<4 zbuAxSA%M}{_<-nx6Yrd<(%s8(3$1* zJ4_Bw7A4ogEEGBuso(! z*c_3YneY0HdDqNr0j1l*7e04*W7pSZ>rMC+-*7jvzSi3DxIOpSjNFJ%%}sIDFq-vS z3B(;I)QUcypb5CDqSEhnz1rS>9fSHCg+v9|m?HD!bo-~Hpop$a_zumfW{IxBVOhc6H2!Q zj_}^w0~`|&-&IINn0b^0dr9Zc?_L<+R_~EbEpELhXQGGW1OW_fSkp*ijfE7+h9N0zp9F z5h5~pE!tcQo*NyWA`^}BE$U;z>UE@%saV^KH z%l8ewT}i`s8CF{>I6H7;-tPg%<$p>Wl8f0JucV5VIHvjk`6JTx{3u5ZUCJ^3Gbm`m(b0Gl_Vi&fq zZAy{Qb3fUex60s=!(Eb)>faO7NL%*m)v#)KmK7x-Gj@Ux)yFE3kn4kBDzWX>$5TB@ z!Oe8fajd;)sqZ;fNDrY(s?OLr^sPTo+#vvR-~v^dl0N0_Gp$?K?t+eI@<2<9BS9dt z5GiQ_vw5DYo3~1qd(`hIar?~g!Xi>=dbLH-UZn5>PE?g^R8+3bNu7NGp;K7=+3Xw! zSp~s1UPTq9XBFk<|2uFHTB{>Hu~Dk6(_REvO{gIQ<+%i?FgOhh=b7;6el9E>l812B zAkhzVqK^s3{S@VM8r~4dF^2H2(}rXFIqrq(C7`s`(SqW=c64UWBmzNgUL3-36GJll z-x&3J*$4AU?NZ2sSj_!*%M+}ESj2oXq;=$nd8g;H&Kd|WL5+-XL|q=`_%e9-u^_s5 z2WvyLQurWuPw*_Z%`9Du9`^Jk%k*Fe1YC11X2-jA3(dzBhctBxjxWg$$0|dk%fl{G zY(F3m`Va`&Dof_Zq5A(<_1jdR&i|G`FdFtlg)x+HcQHymVW&07Q^T45ki$SP8!FFS zE3!?RD7AP!=EoS5W?8n+N)h_`o3Lh`C;=5B_!96usL{gZ=(aE*dY==tiPh9Vr4=0yo%wv7!L|ZWZ)=1E>g}p-Z26D!%b16 z@l`x|2)^QP5kUFl5?OftyWABKn8HMoW>`;QvE% zHcz*4THA^!Jrsu44VnXTTrQrL|pl zqtFBqbIuK13BZmX{x9p!n(It0lFWGSY%O$XL{P2Tcu<|FP&8MUJFL0|{^L-5mZdwoDsQhP8iF)zQ<#xHE3okdSqjJ7GZ_ z1G0R^6=;pKNcSfVmWWKe~$=pwDH%V*FD`Qf{w(w<@RIF7< z;MIKuHI`|lZKRrBG1q*QZ>i6gt8ktpd#sl9RG(nB7TiV&$MGvGv|*-?ot7y#_;Yae zkCaH+&E;lAB0$y@@%I=h1EKo0?UfnC^q(|QI!-pHSh(wV=4cBMP)xQ|u?Dk;%R*Ko zTP@@}qL2u-^SR%=QoF4xl6f_W$a+TT)Kjfx1`Nf*q&K;P>T`?TR>Ahh-Al& zEzY8=z{nUB$(+9@3)tquVIzu{5N74tBay8OTTN>CQvU3^1}_&jisCci-&J=?>d4{g~J*rFqT0y#W7 z43}tft{m*q6CKwJ(dK`m38*yPfx(jbJ2;KUZ%Ko$z5VkAQX$F=-fUy zWmS^3HU5fVLZ08NX<;szKLiE}*dR&xU4u{)#xMFoRo4qf+Ngkg*Ok_)H6$8Q| z;o~sfzib_aT2{{UXWs1+Mfemp*}8(fsh_Y)FQDa1-r~pdel6AN&EmAnkZn=-&->}! ziGoHg$*-o+%yRU}S(M!G7xLkVlS?`AY zI4eAuXk!MBf`igq|4hTbhSTwLTH<4-B6W@S291Ta2xy~Ut#GZ;k&$_eOR5yUEl?*#j$p7y-;JJv$-tK8z#Qtt4 zp7;bEK9q=n^$0wI@L|r6M!8hHWKAVdGwu;C7sXcvf2_zi${jZ$XatPbsdM>MfAQ5 zSA6y#6)WJ}v}&d=@<2dlOlJ^lJ(RwZ^bQ0PWx3^Rr> zmGZ$adRxd=49x?#ceOS3;EepQGYM90+pm!nej`EWr&g%|3ZXHCNnY=Ad%0NK={eJH zH67Ijri5@3E6Z!TvSyqXXlR2DwB-H$E^2jB$Uv3W*ovgudC!4L{74PUp;5V}lqd4f zP+Vh2BI{8CPJ(k@vZut0X)udxKl_1cX>xGON`hdBdVB=zVAY{g;&F59iH|`IKm&<$ zl)f;sVjya*Jyu0_2#SW>JE0UtZ5mkUMvT_^K4}A(GFU&_`<7EQK}o0I;GETdBT$E9 z^XQ)FlpB4mo{XaF@`QlUF5GPQZXTxHb3MuCk<}ZdxW4LSNOt4J9yxl_sYmk1lv4_< z>PJxsCgK5PsZ3}fu!otTl99#kjp*GjQD~qSJBhs9lJj>f@rOpVd;BA z|EL4|%Q;C#V>@u}^QxB5&ivGx_*6R50ik6dUQyyug>o+hFDce}57zgDjZAx`}=sJ=AtS?pUB11^ec z_ekxq9aT@({X2&~k3HD?3(Y7cjt0^Q2Q7V>Adr|{sorgd~;(m8f>bVI4udVo3QA-;V{LkFdtNsx|?gH;Lv_b&T^+0t6eL=3d2}U(D!^ zU)rSk>f>wvj|;%>`S;<0VowTJ^;Nlc-ne?&QKFOlMhtp(I7>dqmGN)wP8@2di{P`j zW!U113c}|0Ssd7b9<@|Ua5DT_2b3zrLb0kzrIp%o>3N57M1t8DTh@M9kPYijAa1U( zm@2i{@ig+Q%8Ev^Jl?O-HpL2QE?zRTtzAMZbtwv_ta5 zzL&ZrQnXH|R+nVFm6~|tURI0T1a)fcJYN&b2f=Ozx;7+)w?4X9kc=08$^$P$T=`kx zg^*yY+uTs+(SUCM>zH&Az0rgH&u_-xK5Cy*k!1mFtsBjrU`^5J&OFxpkKwO6GK)S_;s%Q zV^5k7V|N3A4CPpqBK=P!RQxzFjfG$Xo~>QuT&iHHkdwGyy<6ayAN~FBW!2Jiu|C;2b_Z#W?EFKC#z80$pzT;#X>aZV0f;HBF@n~S3kCX|2U6?S%#aJ)i( z3@&JcG0Z60cE#etYT1vNC>vVRH*bqVz|Giyqw;_?L}$_L5FlNs|C&gh^xbzCRNJh)7JOCg3s)dW9Bt`7ab8vg#~xysWSW(9I)htSLsmtJa-w#uKZmIL)_B) z_*c@!4;`W^=*CN1vuKFfDh>w3AP(0Hd23EhPLB8iz7`MX@Q3i0=#{(drvsQg^-P*h zBT}=AW_;%K7O06(D7I)22(o6F#;_8@rRWDqNZ}Pxo~y)^mIrUp#NI#1W zgmZ*m1IsO&`S0+cNc$k!G98e-6)29WGTy@)62tyj%KKfq3T za+1zrZyQ{#4UKsP{At?iR>DP(%~iKvNslCn?unv=?5%iHK>zUEb_~14lTL)3{V*30 z+Tq&%5RWwI=Gv03b%TSgM`A!QZ2sP=sJ}n;!~zxK=%Vb$q?^}0NHeL5P#y5gxX4e` zBWLcT^6_E7M+T2EQMFXK0x%s|KX=z8K%>y4fi*PjA=k6M0x&ZriAFryl_mzZ)u6L6 zyJ{~Iw&8SAwlWYd9Ev*vDpb= zC{almPOBdiu-P%|-cKBnUQS!v|NKR)z!tNs%D9+ghIq}3#$Th>hYShkB3xJl?*<6@ak(9%yF0GlED5d?PCp`=53ROP;pfoVrr3jAQn zSgj+!qpg0=Lx}N|VHK<#=(_KHMu=0&>glm?}o`Tl!9 zT&^vpJ?@^;;aIly=}ang!vP#3;WiiocqYW#9OCAu0Gwzj;<^Ulf=I5Xk_k6)7^}LF zCPAYBih4Qy>oN%byLXtvD^;!MiK8d*-!NOMgNI?nX)?BsHKTx2lOjdIy4lHX?*ZZnuW&GHG|LRE zwZR#f^6N`AjEEZJT(i5Rh^<#2k^Md)&DCH3lbslF^kvFQY~pw_BRpA@Qbu?{?XRuf zTqM9*7c~b`I5qk(O+NZxpKocg6wuy71XKZMnEdJL`nJE6I`${O?PIs!=CdppPoNX+ z91T4Guv}B#L|&#_K1@EE!88DjZftJfV>yP0#kgGV-wS7eD~U=5eA1O#^>8XdHP<~t z1s7@3+FxWUyWC*i`sKfd1N7HlVMpjf5?F5Y_zNZdY->N*4a#jMHzFQS4bXn$hrGhc zJp{PaUUKl&hln$Ky_#_5FLt)cHQp4u)~51KlagYR8>h#DV1dq#G1=^1AQk?tqs3Jt zQK~#5bF}vsAK0=mpBL1OSPj>l->Y%^-AqQZ*_Xi_$ZH5v%e6vd++C~8@Bame4N3IN zUO%{Jx~WW1)>LGXFN#;>6~uIoMrA7Khl^@(FPmwuF502Qq<*~s7mm+^ovoT2rm90zfS?6wbH%hUet*YmR#KKNFA7y;d@Q26O+_$#ey<iL%t_C0gSV(1lo^dyf2W? zN6g8JI=Nl0D|AtnxNV6VL$=&=IPA0E*s(^T{Xn$to8^MwjxO&bC0VFz74{? zHuo!|gJFHs)*U!WffGMs3#$)$^W|KL!uqHH2)`H?a(rdr4wbxxl6E;ke`FjQ!(1@p zS~OA!iCH7J!ZJ9w0M^Ox+hS!l0k~mnppdv;_l3O5hNpgL;|!5B~T;`0+H)? zavspyqfD@L)AP|2i>cx`jv$5rl{349d<*;*2}pC1U_f0g80V~`>GPmUKIwN=oXK8; z)-fJ0sJ^O(@Hz+K^4T4@IH~6lfauwPQNKZTG4JV1(2~d!0_ECk<|+N}rW|xNO9Wzk zdJ)33x-2c7eB0--@N%nQoWT8AMt=-@=>&Q-F4pm}!h|$?{?r_<`bZonwMyRZ%tbgB zNE|PI+wNE0+Xgjt0_VK-=(a15sAl?@0J|srf=S^G93ZA025d)sv3OpM~RtA;*0p?Ug+>DY3D6AQJXC{Lmg{}V@3+>u>Vq4!yH8dF2j$_>HEf_KHzU8ED#zmd%wGH zeQ{tRPX_M(3CCz|k>3sVbr8x=BWPxOM5%iZ_EYVeUZJ5?^``LpGx?RDNz#n#sNu=q zVU{W$tZ8l4T7gUQKX_Y8lWS_*DfCc(?hZ*k`cOU$ZCY@*k+VtR5~pL{)6VgK*>LwT z$6JJG;UEFs{^Dbj$mY# zAGpVCLFX8bAAZ{fr&1O+j{#%*>LjWahwK*Srmq zoKU$e0O4*El!Fw_Bj1F-MqtcYPu=SZU(@&T(i%~yDO%yUQ~Az5G7Gh;!4?hQvzm#pGke5Sq-_QvXTFO9$qEI1k zsET*?@}{uuZX+)C%dtdln89X6k}4S*TGZe9ut(&))%=Jte?@!*1d1B!6L5#dWFj{a zx|wPyY4icHr;VqPueyu5=h&WTno!A`UpJuXp0X|MNTDKbffWQ)Wf|&|c`8Fq=#Hnj z`Fu3ylR9+PmM5Vny^1;}d}>j1(P>s@ZKI(wlbSn+chrD3|Cv7|f8;GGlwBV{!!OpR z70VxPFcs^Dx8Vm`8oB!n7;%@Tn5^3KZT0OdZqa%b8D|n^%O{dgq+Qk*VN&TF4z0Xn z8qD&NP$~ufbQySng-RR?^5QlzK~3S37Y`{gd?bS=!z+#pVEFqHyhx#l%G%Y^vvX-s z&AFUqt{>^u3qvtsGUEGAQ=FLT$pQ9T5!>hMiYN^Iud+6~QU{s5H_jO-ez;aIW?+QR zDbTdABR1Nga9u<(7)71-Lbpm%rPkbBDNY9u8w}_WypT2utS?XnSQn! zK?8*39WmM7M80B-jP}b{ez?&~x$n8-`_>=E)?KeN#W`pBIrxWE(Ef zPow_w4JU-el*XmJn{&Az}N`RtsApZrNxoKbjHNKf~9w+rlGfAEbZ>;v&3 z2wA4Bh>9+GZVLvMwoBWIxR;I!T|ho4PAi{&<)==Ukd>MP22i<|h>`-%@U~d|XJtQD zdQ7L*t2Nq__)Oo;qd(X;UfLQ1$&v6+H=C{uWUcLO(g#!iD93=PBxf0_Qg-*sXk%N; zodnJ^v71!)h_Zh_)}Zo!H=Z|j!oxuv&gR72djrR-mx?!lRmmW*}6%N8k>z ztBzLb<-xdsl2N>6I5!R92u9SJApddyu*t=Ztnxa~q zA3seo26QIO!qEh0tO$3m&1}vOA7b6n{ZStN9+*Y9f3ATD#j#d%r{fm0q|IWp$%FQs z$MEIRSqExZ0$bEv!E+7fGeqH^SQR z0;gv{tyka#{uk-L4+^C0FdK&|=D&Hp@yjT{9E{$8zjkZ9$7`D%d-qngZP3=3N3Z?h zt4a%eQj>p$hs5!M-iAVDAkd*(wVx}DmdT}C&&^cGWfI#VWUJvlaDJkKScJI``;4CN zqD>BVmW|K!w2gRus(9m4O949YL*LG$u-s9EpcNO_2C$E{GlV2R%Q^n!!%|>Q(PEYd zmpZXNJ1v=5Ce}EE-Y85HL`PFwGz63nIEO6s8+*}b@Yje5X0QDYw=;oPoZr%{`N2rP z26rcq&?6sr$=8*VsF3(4;*AXVwI>OR02j&+hAa*ks79xGq@9^-gd7yqsZS?PV78&z6J5`sXF2lXGMq!tbI*LbzYx*%(=( z($~cJups~~i0(>7!B$ynI;J$K8zlaf=rF6hRfR~?F;dz}+vJ#puf;vB@wmtQ9g-U{ zG{`ck7Dit<+Xl|XEY3XN!}ybkRHLNHyNs7AN!_GEL@(WumNW*jhl~2PD2wo!P|;bb z``io>iu1w7b94=+6u6*pusXEX^*14+h^_(bJb_QL+u> zH^>FY+qI2}N3l}0MKmOEFeiy@18~WRttJH9dtQlC`X{2~rPy~@zZ;1YQWp^7^<@nk zlfwKg^+CJ$(yp^sizcRiTuLez@|PW%t(>M{F~z^XZ(EmNO*~)B#j^-y?2e2XjhM=o znUq}spT~t%?jxG`6(dwD%=3<*Dc-BbOtHVoUQ-Ie2rBkxQeKbgLv;qEm-S^m+Lx_9 z3f?6iiK7t5$5C4-;5F%5S`Ij1G+vSP-18$l?T7DBxB)KDCzL;<8&)(~B*~f`U_YJh zt!7}~cM%~-Vz>ZP7;}D%Iw#AaZmh!jj3WhzZe@Sf$gOuCy%RH;D3+=FWHmtfp*jqTfVB?seB~1A zcu-;c!SZfgka?!}SPt(kD$9R|weyI$AluIeldF%((320sGole|_PY8wl_@V@SKB38 zGeO)LPAW*IqOzNcQCfX8N z^+q03mHInLEr&sUj^+KS8V&&_`g&!@KyK}TikGJIKKeKW2)#_KRv=rU-cUmx^6lxy zerq2uUbnd;a`)@37Cap#f${Suwkq-#o&qeA!}yx6YcutFWN{R^5?ywADy@l95wlbB za~$>BbT%YpY0^{0lNLl>T_kd-D~MXhYIouC%CG*r_kd(}sjgITDy&dk&~4SJj5aqf zWX9Y8gAuJZ%95&ll>!}|kMQAYh@QMc`TgLBF}82F<o21jD90eu$+4|zb9$Qx#<>aD$6lTm!hP2)sTW(Q|jj_p}%kZ1-of z%c?HVq7S9UPAVNtc9SMxYusdU`iFb|=nA)MTh4|6STi)hXh6 z7QV?~AcP4a)u%X!=X~J^oZu~LH*R~<2^@HhGYfD2s@$TvIMQZp{8(ilP;l)YdXHDH zF(jeAPeH=eA71t69*799cu@=+kYA}On-K=Uf2XQXGYhPsiqJ01zUIpW` zg07l_m*tGa?jMuD7;Q;#lG^R`S$8x_*D!sB`*foiZ zN;(ILc+&s06F(C9DFsp(WRleXW=kkYpVOll*#G*JLc3TDV?S{qu$>8FrATsG{Opx@ zL}%h-Ky0yDK7O;tl(H8C+<>KWWI<6xCx@NcZltV6cq;k79RB>JE7K2K(XBT7wDbJ* zbroL`H9g`vOO#0CwFiW9-k{bzd%Oi6$Y`8|^RINrldavTJEs+tQZk~wf};+YL_;r| zKFCIK5SYH$I7g~RYGoX_K0v6m6{zIOy70p5I8G1W4f{we_=lx*)5~jtLuc zI>1}tkwL>MG$>H$wqoZd=NpYYiV=>}%e>rM7M^ffbzh*dn@IL|4r1h@X(Uc7Aur8kuptcdU@0FB*v_0aXc?3fYa#b&i z|KRlgqb5kE-^i3pf-ThCODJN0vU~wtZYQ08UI=g5jL-L=31_=6cLVJ6S$Sy~0<+YL zbv_(_JL^(da(l8VO*;PRZ_nagb9<>*g(p`^kE9D=-Eb1SI3WqzGnGI# z$b|hjuX<#&@WI%CQ7lhDh!#@5k6$KPgPRHkH)9^99h|v0<9$jSd{&6gwxFEPSO06h zW`R%TpLj^d)vOx|#Wuv8^lDyEBw3SL&~NxXgxqV@5|;>#`p%~^1VvL&f^XHJrXqq- zWu&EqP?ZHn*G~cuFl1{&e_yvP__V{TEaFq~0ijGj?)R8z(gVr3!CvHW(*ms9edWI< z8`B;iwyOz;GW@5|ipP^Y=X^54ngO#OlX;A}=1);}6L%8TI>yZiek!34Zx>m(Hd0_O zw~vS%Qde>|;6{Dtq9TcbM$qrrDXS_G>TTuuyPLhM#Z3X)Mor;TOTy?8IAV#L+X!%e zRt^x@K&O6XZlp#RSP~SLU?=l@>ApU94<)jZ!k0o!it+L$ zFy!aHs1gh0$q%_blRzDh-D_mji`Wko-=s18#_bBBDJCXOrfqNy7nPpcyLR74JSH~R zYM;&F#F8P#E&(GX?vurOm{;5Bn+9XyBcr-}{wh=8|6}(fs*CffpQ3aW3x*?QNfc6w zPSOX^7CW7Pd45~H!PF+xfFN{Xl71Mu7|>?e?OknRVyo%7VNCsBXw ztTr98xcGoMc6m&$QG%Ppv=XFDc$acAA*!Q{!-XebbOY8-2Uf0fS5m+K&2g!hKgisT z<>5Wyf!lT8(~>*eS2(1@3^XD^Pdp`26d>&49eAl`A2~ky{hGD42}$#^$^9Jprl5&T zuKWAX;XBeXM%8vUunOJQD9NkdW(SU=1yTK93xR#(+>R;#2VxY@yP=5EJ)oZ_^M^*s zih}&VbPUP0O!`CrYV7#9EabAR4>BRxf<(Ep*8x}~S>iQ_<4Yf?ig=#Jr#m8jx1%p) zx|=9DE~U?9hpAz^JkKVPNH7m9ev=kdo|;H8%j=l46+@ZYPl+>h`Z6H0{jpv|fR;+F zo5zvShn~@T>3_JPoF8lb%Cz;+ z5UGOKt-V&*LEQXE)3aQ`HsFXE6Z<88gsNh|M2+U6ywAnW)5?^XnckPfb?k%Fm=f$H zG4zISK@&l>Udlnp-|dj28ej6CYvVCSNUBbrhDW;I;*u*Y;eijn0clb~`v>yR1#FYx zM2!{Nw>TO{rnhgr4^PU3gV~MN+k^t|kj^BU+tnw)xt6l#v#SPlKQxLzv*@mlLbI0A z6K9>);y_3B(-`UdYk`$i-s9t~!7&D=XP|M%g|}=BuP^VXO`Tf54BRN^{MlIzO|!9P zHY`5AWzN`qx^`-Q7#){Ab2&#A3tfMvZmUA(g68B&T&ZfO=XEqiCiq8LrbOYTWWKz9 z_{JD*2La66Zg|gE*^p{4tn^u7DC@gWAU`{G2w+0Q3rkgaFR^o zDG`RpP+X>#DVmcAVU^xKqG$Py@h>M1We^Ub1WL6fAk+bwfkQAwoGE6>&}Lkz7Nngw z@RPvR{aj+e&gFr5COlH?zP=y6iZZEM+79)$eugGLYogF zede^FZR>=Xt$%6`FgWB_*R6BbO4G{I=BU`i6!}LT7@W*m?#Z-Og9r*F3-`_!Jsf0Q zwb&uf$y+S7#S$j_jJ(L*?LfRB2R!sTz!fFEPteBa1}m~xwIFnMviEX^RzsjKYqrot zFt5g6barZ|ChHb>q(OlT-VGf+5{JpePA(P&%E@btx+?!OFx;K$Yb71u@#BW0-~&P- zkEWg}bN{^Tha}J1W;EeRZ0mE^7cgSGn!UETF8NrBmL0^h60jHN@k>CDYo6pzihW5S zBaKap0)fnZJemuxOciwQnz0Y79Roh+Ogo7se*mnsI$%cf6? z4q)lOVK2b1`9e}&0vuZ~g^lf$b{P5u@^OI+;teYC;K@BFuX!yDF`>b|E)El3iz{NC zUiQjMqyyp&!Q@(+#l&F?cJ8O6XC+~Ca%7OIGHtHxDg{qI0sq;`eVX}Z*u?8n>!NL_ z%Y2Na)qzKQZl-U1nQu+54at}vP2TEH;Xg_eL-?a+Wl2di)II zA%#<{pQ-Kyxpmue1~fv4{fG3B*zA+rX-|4*RVFZa7&qi$WZN(4y>SWKDocA3iv}YQ z@DX8d1yqb>lEAqAq((Q06jQ7c=Ua#LEdBqp4wwz$tRNw zV_y1Njb|rav1Ryf1AX?{j4dJRpS@-!z!>}}6QR{UGIS^K%U#UeXSggl)eJ6WizKGX zRA4Z)KPcnrfPVlM{OrcKHX&T&%y;(Js*glprp23GE{O&rhoGu*qf(d=h)|_f@fRrY zE4>(&ewPObG!pH*kF<0J8)g?JF|aGXOCq{hyFgiNim`_J+8t|b5?1ude*Hd|43=R% z-=ms&bW&?@20Zd}t$AoFH1}Lh38u~aVZ9O-A-K*|F`npX*IL52HD4H?p+q`ds$rb_A~qa;(D5@BQ9yEp7UOk$OAJY~GPI(abR~!48Xd zV~Xp|JQ`2NpZLQncXN<*+Q430CNUCI(ytlV5qy@V!54pWuCon7>+Mr^9p6r{u1T%& zXUDI2*M7xP(Z5eRbu9M!3VUm$Tf$?M8hQzmBMVsPy;H+kgsec za$#bzfkHL@x1YQIW9Jx1ms{?NTDEWzj(+R4lo~W zE(f;}`$QViu!W4OMQrv*OlSDg7HZo~CYsLVJYB#jMe|>8WG{rpOY?W)%tyeXyV z)_;Fz`Z-!T)1g~O|Q_fcraR=@lM^9 zj8CldlVnB##tc@5gH<`t|)w`f6SqomSZwG6(o;k94DIP-(`1(Pt7xkbuu%nrKUIK1m1n}D-q&|s_ z+3aDOI&2(D8&}yi$Cu<#E?{3OQDh;}bL`YnhskO;H13x7V-(Pue@R1qFF*Z0VgTuA z1HgYngo2+r-Mllipkdz%c3y3c$FGVBylP#st>Laxg7xb0{Qxpxf2($-8KqT_3gBC% z$yR`%nY%H}M4Nhh)ep$yJPRoZVq>>XS@a1qi@B1g0$VaIX}0fmy>TAIICA<0Y8_$e zwr{NVtSERS>*ODsQ2dA{_ujYL zNDFI)14l|$36;lkgYXH~y%oSvg)`W~LCpRnR;S*07NE3o@n8Q&BaX3)zR-mcRoNz5*^|D_+0V`)VaGEI`OUBm3bmy`ic~Ge~AR z{5>Rv=Y_rW(t$<1p{gm?cWoR<0ef0dgi5U2qO;ht?_ZlnSZIvgTJ(1b$4;KK&x zVNe?Bau>smLUIUes3z*g0z?#c(sptpwND%CbHlEk`I;d0>z8f&Ild5giTmNE25SrG8gA zG()DYSqSp{CHm|dix|6Y9~*>*bkuiV;S$9ASB8RCMN+pro4%Zhdw_GA#IFl=@z7vg zlc=2X`hm1MYpo&PsYY&YiQB!@DQS!^N8q z$v`cr&|~fS@kC?aWYqcJf=whknP_7e5{kudrxi=i50dnY2M{L*s?fiFmBIauoE&EqUZG&KAAcVu59x~h4{qT`slUi&=eBGNAk zEsg6lca2CINP@V(M~x2e>d^azr21F?nfZfLmmC882_i6Cj%?OxyxyC34Pi%qE_ zD8UAou_+*Lm<_7G%=~>c5~1W>sOBJCMh%PLTQE5A?TTcm0G2He*_kV~MEo82ml{)q zX0nAB*xx(H4}ZKBIP?$;^N%;7ZAC>1tOfA8q*?Uz?GXHrCaSnpMP2EqCZJal3|$vkIANX z$ddpk+=g9Ml%&v=lO$8f`VQc3f#o_$dhXMs76G?E{Y<~HXFFAcDsFA_iJsCnhfdE9egI#EZ$%1Xd*vsRvAxZeIv(00V5Tg zE^>-YHGBMpWuFqsBeS6q zfY3kxdCD|b6SB2ayKL(BwD!AuVH-H^%s^P@-GYxOrWRVVE^TO!oAH_r11sBUU%HPV zd?URlfkeqv`Im(XQ77;UR&g^bK@QD^fXv!Da76~=T_KGhtl_Rji;f+w40+TXD_*O9 z&(&v$WiE5Bg-k>R7i>(Lr-1$P^FV|zArZBp+Y|7LC`-U9KjALt_TNhmM?7RK_HgF= z_1i3oIdYf^wx}ihSMq_n*nlW$B`IVZ%SuaijVEdOweUR;PE!Z+odP8|obcH8lu2q% zH^qm_R&vbVLA*>KnC!4iliL9^sr}j&gRNI=L$)LgQ>RPl595ArY+s2Z}1_HRGQqth_JP0ccbVPxt?^ajqQP~z>KSrYBs? zT|l~3aOx-1hEpmC{TpXmhN*qe(9Rt62t;O#vdpOFk8LYFV7db4(3d}EH)9`ia{F0! zF9v(eKCwL^0((REwPY4kQ+Waz+|yu@4VFq+3KGML4#{dPjYh%hoIo>Wk?aZMU|B_~ zj)mHS2?@R^FNmInZoM+%fvY6!dF+XcYLHy!px3B6e(fGXGv#Ejgb5Rzq_avNCEllK zt)>rcyrALykmTPMtt@S%M0Sx`LwAC5UO~D?LHtJS_oX8mr37)l}2?EL^5=0Zw;HXDMIG`LX%KlDEgp|RKmh){F*3= zAV<)9jelZg7EG#HSEC&3XRFt59Q0$x?_Th0T5 z`)d2lc-sDbyJ*Eazm;eb!ykV<@__NQzpmb&`BYx4l(!(P4{}35UFd_D7!G4eO1??CHP*n7z{QW{2S5y=TtvBG$f62#9dznDfy zL6=kzUWx)^-cBpq7)JE;^NrD^Nr`Ty?wQlvyMoksTMB$Q?7ma_%I^5bP~-^e*6G{V zwD|+oU=D)1 z+sR}mdX{!nA`^Q?rz~%1d467~F!)DgXV(?ErFq{Vd0B#J>LDe~(Muoj-KT-vNV5fs z7doedp71tHNHdR*OAFSPM&uXB!zgN8WV^s_qoy2=M_BsyRHq|w29VdJeIDaJfLq2d z|3r{l(2vZZ9DS2Zg-zL@ERNo*rl&D@!2}gP*J&YJqyt>GP6&IXHCwpP9|6Nvjg|yj z>P^g&oEO|s(-dEV`J78R+HUNYUL5vJRbru&mqrDp-)zMi+*~4J?ZGAVd z`ZCblN47Oa(RW!n%f6ubWRQn2x6u_sgq08wnT3n;`!xjs{2{LNI)`9Ym>3ufLCW*o zNLK3I3hw}ZFh-074%$#gSdvQrLaAHk>?YY#D%nFbqhqrt#r&tTAU!e7v z`HjVVHL7v>2R0lI?)kIl53P-?bOe=Q0DKJ)!Snyu8T6TfVGvQ0`?!t$dL^bBAGvn6;y*(|lqdABi?`AX<{(m8TR#&>OqSkn%LeoY|E+y zmpAuDGix-#Kx8rcuAl_`2*o#BF;BhMuLSRxipwBJ^*%^BNOM=WLRKrRgeM_?5u4|s z`wo67EjRtZa0W*VOqPaa1QH!Pt}@!|8&S<5@e)_-k1x!hNcqWGP5F~_2acv8ee#N9a-qtrXbeePUc9)V|LqYJil@3y~_muR{}KUem1J9Wb)G?8Cz zJ*}KKUh9J^MK5_3VUp=yJl3d>k^SQbvrUy*bQ9?f%0^@SuF@<3QLGc1e~F0HGjKpm z+P{WURR^Eb!2|Nb%bXUCC5nFnl)cBp*02j`yp8@o@G;NNMe$=w`@Ew=TWRszK|D4g9i`EIc4wFv#D=tuij@- zG;jzU{Nz{Z9+WzD00eHrZPPA4hZ?BX|m}e12uU?We{bBDk z2b8nf=aE`BulMRO;yxi$s-NJU4Bw;5=K09DZ)r@t&^}k$BWa-gHfavV;3(2yD2X-W zp%2>1K<$cPTq+Gvm^G$Rw6(a{(m^3T`TdaWDKt=(sdw=S9JM$v2!G!bzCUy{XBzpa zqiF6yf-8BdAXPqQE5Y~liVBdf8!+wJ4ngW`j)B6kx}I}TOJvv*nk3S;lS0TjN!rhL z-43!Dad75>Wq}C@Un2U@E+1kr$=49%s$at0_vu5{opglR8v!s_kgZV`5{o)9+S?9v zH%Pq5p=tZ7v5jM~i}8Y`Jxx|G3Fx#f^OA-JJ37R*#%|OB^keQHL4!mCL)xp9#q^h6 zLF}h^d2T&aw$MAu_jz+5Wz|Hh8+ulBhRIQ3<{~ChWF9OL;GgWzUZ;T~WB{nhS24Rx zn^oe0V$;tZ?a?^aCxf4io=SZJ@s4H2@BbQV;ggDf_P>N$xsW%Dj zep}uH(6Db^!+Z#E4rr64PKE*&k&PnUDleK-x3tg%H*|f{8}*_RibKO(jZEQ|U6Ogh zta}n;A+|2ZGA3dlcl3aF>hE@FQZzwHiV$Wy9H0Lcs;T;!ROiOBS%>{KPb6)-0SL;St4P+aNMP17pec1n@9%UUf}8x%XYV9#aThgUv&V zieDc5NXSIcJUD1P=f4j;((vwYyyrY(4k1++$2wyk?Nn`Dy*-!O08DLWKH2?9hJmWz+Iz;qE@1W9e50JP8xHI9`dXo27_uqoO!-h5LlVio&_BqA)>xW_ zKRB05L39rJniR#&rxy+$WhwqfEn8fJdL#6+^B(YGand=KoMo-}Ge$1G78_~%v^YR5 zdBJh2xvMf<4M=s?zID&LFVcW%56GsX3C!@)VFh!mA1y)o8d<>_SP9Nb0mQ*T&HZ^8%kr=J(1S{dnvbo);U?U z*#NhHFh9~IjUOdAHBtE$Tw{;}rUQzs1%=9=^SPQc%=&ZMDe8)hz14gUduc18Hs`x# z0pq^Q>!mtXG&XLc6dkqx+STbVj1ARG7BTO1&%Ay36kafDj=`J~xYQyYHpr}G84MVd zvgW@?iant?WFfU6$j!=*CMO6;JNP<%)52n0G!pugsfe$u`Wu31>0FRfYkT9u_ zML~jn{+WN&Rpdo(vLqlN0#u&j8w^feQVc)HW|K%bFRu?fBIi7Uo8>*BtEVRXJjWmlY`0`!-4jJ0R# z5RdkK+;o?+rruG2*We@sI`YWZs$if%L}c4I_gW)8S_N<(=z z6?yKwd_|Bp44 zx)W%g5%QX7(78_pb;qXrl_bk;9qKln396uoJjIZL65Hvd@S!>`akcKo6#h;FZglYo zPCcCOj9%l;%i`8a=Yld51(>)=*xkZx2K|_~Lk960d(X`&rel{o28;?x3BI|0W7=x;uKDtI@&qSM(Rb_z4an;4VSCEkM$|`5npt9 z8Z)K|3y zOSE1oDIz2`kwxcF4L=4sP zHu0`KAr|!nqD7+Q(Y&a2lK}hrWXjoMi}9rQ6dtA-4%(h;Mwm+F6<=KBHg`aw2b56j z4dzDXfjjZQACUwSE8UJsi?{&{=a&@_tZ2HQLaa#>9RGG!VypJO`4a62IoI9_!GMTUW&Kr;604&74_hiynOA1vU>GMW2eSaTq0x71|+Xe z`!n>161S(m&9HE%Tpf$kyZrZhr0bdA&?*75 zJi;j=aUe(3*z!ZsDzWqEm3DhNcE?=`_OD}>&pb?*AIv_Cv;bWnU-BCN#86wOAffS zRZZ;5L1(3X2zkbi*>=r0+mmV_EmcN?MAy_>hr-_Wu@#M+yuDiJM)TLx=@a#Qi>ZSp zUr{x&>YG=3e4um>26M*W2P92yJ6Pf+MM%~3V%gMp(<_~1>kA@Gk058kaxfr)wWW7Z z4mKGQ8c;nYS?kbkHokrlvP=Sk5^Vf+LyVH=dg|;;OEhZQ@I%lUzOf??J)ZVLM94B? z{~e=@Al4zW`+dL#j8XcqlAx?hmR}pgSJ=?Y*AIhO89Zg=#FuYFRi4g8yWd6enZQ&i zKa-6Qd_jbA_uGov0A)CKARcFfsTbad&j%C}hVY`&z1GuRRch*>PDc2pFb#|3Oe#S6 z{nF0r!^bDJGYm3KGcw%MC`>Y6V7t3;X-ElhfI~NND(@O0=Sk0_u^^CWKPHj}TAtt) zuAHS@fSU_6NTI)z?)f8ED$i3f@ZyzodA=ES*UsiiKt^!_<8MLpmYvfjLyzNA5XUT9 z7;xOjG5IpFw_L0G{^T-Pgd&pmGdtk!bZ|O6IGoxRVqWu zHolKTqY?gW1b55zrHI(eaRk=wx^~ob2OLbvc${vHwr=^JZ1*6(Lg#gi^X!S&_ve6= zbgzRym|enkvLpjnS?0-~h1OGN1Z?Cjaaj)O#dSqX*Z$kr2Wj}hSNkNRJmK!etF*F{ zg~^WyV~pQj7T{k|2P09^;#@nA;m_nW8|{rx@5d~=O>+(A#*WW~mxu*JR50=b#uvDz zNLo8pPR;l_o?}R^^@*a$JAPLG!~OzQPwlfG0-P9vMPD^4{>90o2UqS&x&#?TDk79N zI9rr2PBDx*$2(PqWwg4w0c}^h!`OAR4&8dsiz{|}ge8uaR|)j@SZAe?+T*n&6Aw0@ zVREd0SeK>?mAYnA=&{*%szM2YYG?N8!aY^USKA&5IT;pOJ-0qQ$DqYS*h8tIbw z=rJD4|C)Qjr-&1bw1C%=zLl@Xd}WwDk8Ef87%UI*wwyQ4QS?$vw|ohAe$mZToU6rvHxu&W0BA zRx@XPhWf!--DGUN`RL*O_mDB>bdF*L%4D_#}>OO`<4#8>`Q^jA~_^?>*O&k zE~LvF%64ed#x=X`Ol?AOi}WvTO+ABXVKa=mL@b)H%Kx_;G~6w!Y!B-m6Q#pvNhH?a zE`Cc5fydsugc}Zilyijv$u!Cj{E*z1n!wBU9bKbj+?#k>9Xc-RCyY8QWUgIt zOsicu1(IG85y@(JdxCVpf+{45xS(t3gPm3R>yNq!#MzU^PQrHkgtu5?apY_IwtqA9 zId5~xA;tr?ULrr@VIV)5SSgigh|#%VAvrcBDzPF(m4=C?hh7ZV5nOv^DZZ8Ys0df&5$(hb{HsM%yOVCcy! zJFL6AFZcHgycX4i43go(Ub&K+>bm=b+lAcNNw7n~>Dj^ACrrN~6`Zs)b`9lM9mhztnEMEI)`_F=>6lQUgDNlVu@Z}cH>z~w~%m=;dU7V(F3%ZYq_V!|UAbVYY49Azo zPNECQa1(%z>)UEfkqgS5>rBX?@%NbN%6eAxkRoQlk@=s9ufuDGD}?PE(gBmn9S!q? zg~5bqB=kDZ3mUhwj)1oj^s#_V_Sm^19?~RNJ2P^!C)yt!INzojIgY{OBCZ{0DxEIj zU_6wF?%0ZM;#I<~s!G4LXEh6oLVm_+1<1HbURyyoW>dt1XB^3h0y~OO8+jfZdyq}x zqv{HbbR(g(WxBeQTOCw5#?|oWOV*ivby~r=apKq2nS`nDl5o%AU(m3|w1q5_%LK?(Un27lW_(2CzaNa$75*E^3KVTZt}nxqG?ZjrO&AsO7lVHeg>!byTG)L;~upTS|^t<<7L}gcU=Ln9_oiPM&c$uir?h1rVcBl98xDkKh8w2 zja`wXY^YSHj}pfjBdBo40g%j0C-zf|wqU1#1B;A*kd3~Yn4j$(yo>D-14)9l9 zkpnl;X6qIzHr`y!O8V3As=e$>763g!!oS@E=imLtQ$aa$lngdXM4q&n9#g79J`4$1 zn2(UTUh8&?i;Z2ZQF6oB_lp=&Be{Xu+)Rr{6YnYNR-_7w*YYfX-=!kbWM9E7;tCd&Zd)mi5Rg>@sSNOKPKxK@%T+G03FeL*YnAENL_Y| zV0m-ymY~JyXq{V1X-``(D@+i)2Eb@|^g)&+2s?XVO1YyN)JeeH$u#x14`gQrF2VKP zOUbNC2Z38MtV_kk7_X5;>^o6#&OXuII`8f>shk-ae$kI5&U>$vbjt8gGz@bagM4x` z{Z56#zeJ8(DK>y9qH$AXAEek)B*y67hX0^LVC8keQyw*^MvDFfF>>AFOD41xd_>R9 z3FaEhZ9=KDYJibCmHpoq%yUwJ5q4>hfzbr5pEhg@{fIjEZa4dvw-((EBZkzFq|;(Y zjtY+73l7b)*AcL2@fz+>5hxcivZz^4g0`fGsbTlei{Ezwy#&Iy{h`o()Z0T_ullx) zRUFesUL~S#&+O%xcAv=xJ0inV=_Da~P6Xe6-vh?~5gjtg$5zmLQ1hbN%`V@Q<6RB^ zM7R(abP!@u&FSw`dmdMs{iRc37sq<%At+F(!V}`<$BXrIe@~;HBHLI;6=uLY6;Q;OKf6CFjauUnpuv%iKO8vn}K8MabyGA2E(5=s8$k=j89HBt;^vGHuNI8?IHn zHY@c%eE!_9{8llcSc#~itw|bdQ#a%0B?h%2K1g3vUw+`yA*^u7+sdEv%2~j>z>G(8 zpUUq5RS3dnK#zbtGBZAiCOAK}!VE1-r9R zp_z$eL6AKGuK1rrTDnr)AX4K~8Ja|Zme4t0dMCE?EBC@A;C0UD;@Qz|8k4S)Fh77P zLBL>WBrCP%M86eG{)mF&y%P>tE0doB5G~9%0N-M zjqFyXE*0={rrvMK0>c8+Cc0theP<8BxUOB?Eet2S@GgHKV-k%bj$Xx&02%wSd_&#h zZ$SPO;)jo7Y~4ThtnPjgBOgzAB6SIBETnrh4^4=6e6SI?oK}l%;62<;+By1mVI3#R zawT$q{vXpN*VWH-Jf0vF$!%}g9RrqN>*))-nAx250r%HS=<)u&nmu$|C?A*nZc*1k z)n~r6zX2dm>In+$w~#{N3sKb(x(?vCjxu-HCsg(B*fs6hEl;zjzyF_(n&tM54MEk1nAh4)<=)wz=P@^U&zqTVp$ad7)@#bHew=Iby(|B zY3DK2mI1!biHsf-^{n4II&{OKb1D>}IhjK?T$#{DevJnX93U8&9Dvd13M>m#+;BkP zRKzKS|Jmx=Y61dT|IKdE43Iz{cc0BF;*SrEXuZ$-%p{Y{d9V|6{b@GlzFgolb;<%0 zh1jT}eW!oZz!wY&2^w9WirigI+FOIN?QlKVmY-3GV_$H83SQe~3{WKOG7|$=P9bM=-!xBr(a}uN!C;&%7`lIL z;+i%krHg`Br?<92tz0w?PH0u((MnUGP^9zlQcOj`#USOyL~AO9CFQt5jM&82?L}~p zKxk5sx zaX~-Qhq}Q#1i8r(=JoApDfQT3uezytb%0$|(%47Oy|#=iQqfsEQRRfnND#Ip1_Fxc z=MsMa+cvh@!F*~ZoDD*+hLAwS(zXkMMYqq{rarmHx%Z4(vByJ)&tw$5DP-$km8U35 z9JmzzsKHM}g`)IyVfBtoDZ!Hg3I`aF0<#;A!pT}hba}^Me~h2s32uL@pieRDax4!jF+ta=HU^e?`rlh%O5NUhSiSG@OTid4{&=N{6c zdCA29!@|(BjiP_V(yPaL0^2eo=57$cm!{fa0?J=0XNO(txTuwNJGG5hCGCnJyH`o{ zgxIfjs*7hvs?=yGz%Ql8$fzCM_D)5BLdUnux>+hDT5o3dSn448mG=aF8@lp?Fwy?& z+R1X~3aflD$4iprQAH({AX~Eyl+E&lMCL)u#?z7+45EvcpFhI6lfplBqgKn-%idfo z9E_e{0fn}AsVO;*c?d#Wr@5~him$NiqCs4lbm1)XsbY_}t~-{a@S=jbUFLyxR`>a^ zcpBvGxpP4`TvQ(hU89lcqq?2i7*h87d4xTw5Stu}Mzxe$M|-%#lNt?Tu-}$Z=TDFk zgrC1HZRx6evba3Dw|-Mx?qkSp0(Mc%bcal_7#xzgo-VahfAsX)`LC;0(eOs z$>EK6teWz;w=v#cUG*iV>Y5(a+-+|lUPK`b;c)Ks($o~}cRZIlNPb4$KNEr#iWv<0 zFzSiE0N(6g1t#7W#*_S=#6L4MStUh^p|{F0ehYo^Q$7=#yU)6A6B6)>myCxIxgEb^ zhi-Fej>zwT1F)Ycp`yg1u*0Q{%NCIH6+N=;_uA?G4K`@=9@9KqtW9)@jF&39`SH); zy`gaw(aOe@R_ldQ;pBochaFALGk{DN>t~`bn9=<7Kt-oB3EG8jZwYN_sd&G)USN@j z?k3!GcL2`QuDD94tK84f^{2*yiLwLx-{Gg@li?Xw-cg5}SqMO4@m*^AzJ&^MHU-Wy zwgeVqFC80Y5(Gw^CY}e~c@RAWuXpoWj{gxs;Wf#nC@%9J(Z6Rw?a0c&(Hzw!7=t?c z=QjQx$3tT#qz*7l3+C_p7CeGvmQY}XL-bh{@`ySJfAW z8fovXphW}ZB4(;YniP_ocg%{HmLkskqxPxkX4k^tnXbx>9D;>XFu7S;6Src|^V30I zp)|HCXHl;lDQ{uy*oF!yYa>96-hV&Amt$hg0{bEsPQcHmO>B7mCh@MnzTx3WFdRA_ z#!HkV0cLe<*58K&5Wc5xbI4h}tJun=%=-M0Gk?E9{R`-`+m3~j9!3BpylV@?m6{4j=D(z$ zTo!hR)b*!$>+^e*C_c(QE}&R9?AxiXk=(_-SFm2<84b}8%vd{9=D@+;gTMgO%6dEl zb6xb8UMenhVz9HA^MZ%Y@8a(!{9TDp3=d+Dapiz+K5M#K2yt8^(~||xm?(Ev9r{w? zl(&fCdN3n5L4S^ElQ55D&z*7n{Q)Fb{LG5jNkpNP3usiRMGzgThXsPCfMEh^U6KcS znjZf(zkFvj0>O?ZMm5>*kUelSPl0TAJs+`P+`zj-M3=|Y{GZaj(80&+wwx&g(v^F_ z_r~AJWFg&2x0dXi*Bd5r!Eu15j;HZ-HX5n&h12%LzKJPlSfT(TSln$9UBXb3SJU>= ziqN`Du%O>=f4x3lU6Fg#wZy*S3AEE>lz4v-p2(W`4bC_||Kf(C(D9)QqYP#G7< zPDggJC_uOd|HQt0dQNx*Pj^t~FPCl~x~m-Ic2xm(IqB)Vs40~1mYm~~<+{f3c(R+b z!1V2Gj5W^I9eV6Yb11OJI<{&Fc1f2#Y8jX`N|ExkCW{K-Kp*1S#9O#CFpx5i;gj5A zN)d8z=yT!hn>D7J4Z~hRGsD9rUF%PV9Ua^2Ppe!z&LJHx z$AQzLbu-0mxIJzgvk`O3RN+sa5mg2LB|g{F+7> zuc>~o{jf~PS2t1Vi#_*oizl76d9-f`^g$TgqQF6eaN(jc@bcJ{!TA@K=YRySFR6c* zMA~pWDx-e^gw&~$X84Hx;Ekkd^#VB6PzPfgghonMKS#PyFRTZ8kkLg=YUDzCK zwpua^2k5k}pC2lR)r;#G>}3Y$6O6$NR7{EQ$yd>Ts5M-WahRGjYfu9-7|Ts9gK3Zz zdlzVT>y#uqmmlu+`h-sc z)Nh=1o=(7X##=iLvui7=yh;HV#CzmM^7$90e@Za9gg!Uw8#kStt_pfqL}{gMBY+0n)~CXSb#(A!Z3+g?$0kFt}eY+8v(v19moCJB37qy>eV! zT}VRZsdbg;J^@*4k_2QR!8lAHuG?i()3;U2LsMo;N{^~tR>c5Ku(_4pQuixF%JUQf zUi@UJVv4F$jAIn5$x_$g66ta;$6{^4pg|U(i~WuO4Jencnx;(!BVMQmJ2N}%JM+>5Su;PbkFv99Ff72$BMNLyWx(EF zZ*JJT-tNjzk$3#hI0&6wvzw~c!bbwajQT!fKL-ZbBZe^97B)i}wh#{4Il zqrql%w=E4+*A0*_*-aUrk-h)c0#+}IBI~K!Vy&MI%@}6MIi;S|y*f?ZdL0LiR_tef z(L3Z%F4*V^=S!i>?hl|4eo!yHx|S^xMLp=7N2YGXR%&pIRdG40K5jKzHIFm2?@Arj z{v51J(=tgi+{%N4DD5=fhncWVcgY)E+&^j*T>nnG*)*-rB>PSFoLYHYQ&{O`L zCt`5bJ=Hj3v@igrEifE)81`gs#f0p&4YS2@EH;0A>}a{5<_uhRMi19Eu4wnk;`I_@ zsqqM{Wv2l)Ig2wx+LIN?vs7MhfY(uaI@@AH7%hVS>}2FU@+Z8b&-i9Nf^>?gFy3s4 zP_W->72^R5VDG^C8|02f#^-gDNCRX? zC7|kpkM(MpSJu_cvGJ2zANvpltdg{s-~_%2{1;`qM*Z~>f+1Q*&70Iy59)5a)C0NE z;)DQExmIld{2U9?uMzX&mB;s;D=eiT%?^Ls&byW;As{m6yh47#?YOOq(RM`h3rJ&m|%M;#mFJ`T*YEyj>P6U(qO zEACv*@Z!Jt4RLgu0(@nhp5PORI~I6#di0bdJPz*LAUag;wkr0*c7&?qhHGYT;$GczkAyrN1~#>|X2AD{=NhJCDx# z$0!Imah?Lub`pYP%`y%z5pC72s5shVS|LgKbeA-f1JWq)t?*|c$zed5Z*@%NMI)w?9-47%@D}iS45EQYS>1RLWEUX^;gAOT4p6b4~&weJ6y$r zLXuk9x+F6uH8^`gr5u})x2P_V~X3oBMHZ9;KX_`YTl>nSOa8}_Ua^giSw*Q8OQlPfj z_Gs0*grnI~f^RvylDBCK4^4GrsW0bh^1&-u-0-A&BR%7dwU02V`}u#eCo#IL)A+_Q z7$qwCDgm^piV!c7QI^6cR3xt`Mfc_{1X){JiZk-MvFiLaw;X};WX}~x~=aGF!>L6I=9uU>t{^d7)ns)eQ4S}U-QF$UAd9j7n@DYD+ErO{8=1h?f+{lGOAcv`xmS;_QwTOS zGe=pM^YhKi-1IVdNK zW$?s_K3qKKK`51MENja~y-+JN^^xPj?F{v56NNb}P}o#B%9|nf?CKoIh+bInx92#L zLOC_vHY`5a0vU|P@y~;Gl zgAi-OTJ*sanhh;{{Y1KH7Kz(S2G`AIj90F-y@5{7>5rcS?EgXh0uCs~;pT+66VXyB znwa9>+V>G06BL^HS)cBg9ujZo%{qgvHZM4AQ=E}{JVZfZ$FU6iT>d)3YqB&|SQ4Gf z?U&@bjZw%z^gsr}ZG2+5m4^YPJmmEf#QM>zZz7G~{5a<_D4nj$dLjHgv&7LvQ;oOe zB{y(Rl6yns;1v{y+TKyz(0 z+GVw)74Sm|iXKW>N|RFyFVoD)*SfhjF)E#_ozS8<3SP9ycs-Znh4L16?8vNfWZSAt zH!K09Jf!r5$N?;AkvK!Li1h<+MNvi#y|#3b8_H)&rchiBR1=~jlUX75eL(dcG#>ST z&l`_bs)S_yw<2B512%cs>;$NMtR093MESlyB79afVR$n%+Hmj1Rkg!-e>2-oSNo`qiWx~!w)ajsYL}G zczy5Dsbu#SbCN46OcZPQWqM5P==i~+_^COB>HD&z9!;w;*H9$Q$5_88n}$RQ6z8u+ zDM?niLeL~aO%4b9aAv~U8GP2sX*Yz0jd$jRhuny z`#R)w4$Xy+O#kybpB>FEZ#o+4BR!WQh1iOhpQ_Zv*gf-CbigL}Xr#R5XX+lZ_KQl~ zqNOFQ7Y`W!x}x!cjZ&Po=~fv)zS(ovu`o7E4EN%b-`wUjbk3lOgpL!8z1L`4_NuL+ zm;yBqhcce#pmTiejGuV-oH2ntfw#}@WdzDJbf{NuH7AtDqhd5Y+{ zDv!%pf>H@kzbz1vT6;HZJ!Bz{5UBYby5-9dv+pNtMz9f9$>blK3t6l{Lt@6n-)Rd7 zq%M(gywTuyi_I6)9Z%BMG24oebsZL*9%KO14#zzj);_8qfr4f(nLf59ZiLiuA@{<7RYL;}ospZIp zDQ<>I1&F2*f9QCc)4ryC+3CS4uFdbPHjcXU1Qw7)EZSHg36mQNF(mme8^s6An^#wj(tyAo zkzw6>i$&?S5Y6Vn=U{*s><#f}R%KVI0UYnMq6X1>y-PMe?6|vHZsEyY^9UM%-D8@V zQl0OAN&_iOX*l40ZU3}WJm4`tKje9fuWaNoA0-$CyhfidZ`oJU(p#VR8&q0`*Y-v~ zyxx~cTYya!TreH|GQ4g{`twV3K@n_;i;G4Rz3Ig^IdPgDQsJCWTh%-MbzUtlK9ad} zq#=~EGnt^8iXfi|aPyCr30@b9ox&l@|6|ymsb_rd`vOjdB6~weDtM?*`El;zWrW_hL+1 zc?Zv05Dg9CaFp-sstS2nV0oxIykKll7H|RuDsaI2AgHC8wk{=6#O$)!PABl?W&PyR zdciG-Q(GfmL+2J_(v)84wq~Q47spnmH58Cr+=ai4M-erwn;29VRCQ2o{<;+UiC&j* zgB*`*bEqI#kMirwC{}9$O!T(%!~a%RY;<@b5ZDYcn8po~V|5i&vnFn!q`ODg{2gl= zkw-AD(_q{9>RzEczKB!uaC#h!bDJJs56rp=MF2wBL=|%cE9nL=T{BIeId$h-!ym;a z6jGU6I)4WBxg)fIeTx*(H#)$G#66YHac{V+B#K~wW-KQ$#EC(D3~hG>xE9xeUo#6L zUJqDx>f`#FA1H8gV(q->ZEe651D*KLpM-rJs_IS-=*^*j2<%cw7Y`tg((rFfi?+HG za^v!AUXp*qZkcXYw0Gz-8T!DOv>Bme)xcU=TMJL?uN4OZf@*@AS;9U$H0h#=E*A+6xSl9iMv z#->Q!ey+TAp700_iF5xMYD$7u36^wwe6}sAaPKXISCT+_HF&m|)ZNkMM%Esvqt;k& z1;hli-I5UHdvknEL#!L5)R<-cMLfgFd~0QChmI`!p+(B>HReYhaccBc1{I}3>YZ{} zYm@(CF(S5gU(ib9$Kcetuh_e+uM4rwna#Nnm28ET%gjv@a~lH`ZfCaiB2yq!AI`d3 zEP#Ymvoj0TyO#F5z+QQX9sjwq`o-fv-?ELp!DRJW$`|pR3|hTFePfy9_}1c832I(i z$IR1cytr$yJnAhCtM!3WGzY`KwNbWn<0}cu2dFf~mVA7>Z2a*LSl;{PHG>*FEyS^a z-=khMvn1_(q*MA7@lqxpl-SCH)pX;Pu+aMZg$%K2NoHb~a}r{PL9?sdTPyUe`s|f9 z#np)<10DjDCdX_**RW3_-%-j}73*d1enRCxY;&XzKTs z<*AuT`4<(7PWBMhvs5Ltk>N{T2u$W1R26hEi}OXqQ*LgC)0P`E=_MhTbv)Xl%Xqf4 z3*Kzf5hHCCy*@6r^4PFL@7kOjF4+z7NB#Zwf)H8F9+?{q2N@6^cWK2qGJ@x3pvZ`@zgzU+{_pCGuwI){Vv9r^zouS&7ZLN=Nv_`PS*;tSiPojuQU!c2Hb z3|7Pd$GTP;{iM|A=2m6_)50R9kmjObzRgL%IvJ!Qnn;TI!UR!?VSj`pJ?1uszDs#;68z@ll2X3a<>qf^u{C$!B znA6cCRCKJY@+;^-o+CV5XoIqY#9`YID6RFL`Amli?d^|GcdE-5u%%~iD@Ibva*3bOb&53e-5Ab~ z+Uc#gLOWRbl5Qd-cA3a3CuUYssoG;+CpNphH^lQoFQF zx?J>?~%QmJxb8XOw%)es(>on0bGQNcjg^DUZ~b9o?(G_>GQc z%Im01<~~ciIk&j7sqHTPa7za0cU{Hzn7(E|+jC2}L&X!aM3q~dYuE^wb0uw~=7U5X0c&jTr!8adcH*-I9)ZGK~O9!;@HG|Yr@O}*i1VWHLvc*BcGG79*WM1 zJIbQ^3Pdo`m^h{TR^)`>2DWnDkt7uVZ@zMDjL#r}FZx3-6`mw1kF}Od;kw+tIuL8g$^=EP#thuV)TrCd49B&OkKL~X_9rL7K!NA zcq*Cw_LkM2+~E5XntW>Yv!ScANefnfN2I}B*amRUA<6fM0KyK6SQF$yP?*Iu-JMPr zWGF^ajx+Ns*>+u!Se_&t=UVEICu$ksvu90EwdvFvoh&p(i1~R)Z`M9 zzEni`nXx>KO%=Cj=^UZ~>B7jri9b+?cWg3NSmPBrhedJYinmXY zSnmtaq}x@pJ#xb~K5m5N7wrcdxBcct%?I5AHrlIXcB@prba~5O9u?PlkEqH$LxK@9 zw8DQwjBM97X(#0=zPuBji@Bj2;n1_D2v$hh4-S^~aqQ^R)gG1^Mg>31DzB=L#$>>T zoS6jw!sWLQ|GHcG^NSERPCyZ!K!Cj;>m&5$NT!)<7yh&|_c5Q*^!Y~@=|uF0 zH4rh%zu5Xj4n%(k18slS&J%*=3wzetmeL00!0=d=8$=nE)LEarfR0fnKB^tzyJVC_ z-Q~D33ZfvT*1bi;bAsgKOl_13xr*uSwX;qIOi`b$T#%8z0!oFbBH3EVHG{x+xU~Ys zNs9L_?XF~IhokY1$i?FqF5laN;|7FAFheytb%p&sirD;`eUl6eb7#S^(vJ-eoW&An z@J0>;F=pz_lescNj0b3|vO3sQ*Ge??(I z0qKW&1wwaGV|%2cQh1f7wGfK8;QIV9L2dz>{2*avV4t?E_1@)Vvon=KULR$jk#mM< zxJ>1X_XEwgId?w5Fjm1YQo}hg=OagoFl>v;h+4^Hs?Z$s5~JDNT;}=8dfF~>6wUVo zw$6jz?AK`?K9ao+C3{%n>k6FT(eJNyI3*ve0x{&BIWDX`-BJU%J8rug;H@x6h zmPZj&#af*Sd4%|4(7Yp6HM{Z#xyrh3R3NL!edTn@b2%$%`k(0EUXv>0B5n+xT4gK)9fI!9HAN4GEN-jbSu@hYXD9Q_KI$ z)|7xfp&fPR>5o?YP;@KvK{-wn$rECk7&?5>tMd3=_83jiRSn|Hc=If^%=h z1lC$7?lBkq$6R+j4Er>B+Ka0=VFu?`5`u>lg*{YoPf+@2 z{80`pQFA5zufQl7*{OW&A*~0y3bZm1d5bm@`na=T&vhd4!*sE~%FL5)WLG}zu6?7Br1@>6$E0WU09RuHm5O@<);KFZG%CkIvSF6!ht*96&ic|W-c{xW@*{o z^(qodx@%g+T>a>lPbW3FF_45_z@xukS&u}A`VC>fv z;~fR&xzM)}BguY+(=#qTSNc|4g#{ZnsST@s@C1ZMPCNEp%MHwq2j3E?-0T}aR~`@J z-QW23`+=)69{5|K&Zw_wY%OOlK)8(oe=8anpUG0jxm!xno|xt~FnJRwWe|I1SqZ;! z(gpTo2wy?Rl6(o%hHN4TfU~F=&AKVj9i`a^ZRg9)M~x=2*)c{?nv%G~Bc6HQ(?}9l zG;K5YeHE-LMf}>3axm2mI@2;@gfo%l>bGH=MW!aWaq;8uJUa`bg9Nm1byc9w}CGlXcgb_hS5X zi5{^}%s5Cvqf~NVs%e@H8wcZvRyD|GH`h$f-p5a; zk=T+jUx@+Se&WCC{)Y@6GbsD?zy!f}n;x{H0jjx|)&l@{$j9SJ=Z#!wB4JVOy)pJ1 z_uO?tj0;3B(@`j?IlJ(N(chqwzSs<^BkIW5ys&55+dZUKZ_F#K20k5m>Ky+5@=ESo zPI8esWOfq?FEhood>w0d2fRmj5SsBZB_tCh&$`+LM6hU3%fMCi>aR030Y>*Xl<#LH z$K5xxMh8Qa4x2>gLqO_pngOqX1yk&+)XChTDiKB$C_rG5fLYqnx*8$4EXC`ITt0>< zLN%85B9GQv_gaKpef1tA1@zV%x$;S%wtQ@siid!zhQ+|?|Gp;wjNcz5pEs%=2 z_YIyUH&5(O;6P#k9()x z6NBiPPsDdEl)A%b=XGvg+pAV7`@y)Sd9>5$nSkQhN=M^QT<#_r2XoJb+!Gwi{6lh# z7ZVMN6C#*5(;`cM#Ui~c_;v#i{Yvn;w|jH~5UmeTApIug+vBZKm09?xf(DG8Sc~v{b?{wC+Q>ClPEt%HQU~WYq2kG+ z=viVd7!Er*AyUs`D8;78=DZAQt!M?%00jc@7l!>ATo4urICnJOD{8SL9t1lQ7b4)V zhXcs^^Mu_kZywHNC7cw&x0zFKCW)_624muoW69Bw$G1m7H|?@)JD@=c^zIY7!a}_F zR?A>wl^eYLnaID<4Hj&lFhK}ti@<)+mKHs&86AU?>`MrclzVKh&+6y zm9bLj%UjTY#a#jL>)ns(4~yHK!>e~cIxMLj+xcuOqeB$KE|cHgbZb@Lp<3ixc^l=w zKGJoA{S#)1@l8D)PP;eBtvj_roo^TL?&VYDi(FT?N}R9g&~P-sjx%#I zD0KbUH`H_=@(+>?^3PN*!^4#0LxYTEkYQM`cXJU%YsGGG>zVv|HA5qTz@Lu%neiA!;frXzM% z_Hx|uG&g{FP&|U|JDvb(=tXqN*KHZ?vg}W)g|wO4uSq8kptj1Sy3{r;>sHf5|I9mqCGX{ zGE8Sd?G#87ce_acJ~s*|K2+n!SMEo`Z-PBxF8h3e!oDBH%fXeR zw<=EUtxY{dA7FZz_cYKn2yVibUf1xz@NjNVJN36Q=#PIpEW~#l)Ma-LSJF`(K$P=d zF|xTX0|sj$i)rB+K?D}us7u<}uxNcHe<}DSZA(w)dx#gMpmF+g9^dM5IM0iQabBmG zM-NnTL}o5Qlv$iwF_J3{w&rNBB-LQg1R*TVWfZyoKyd&qtUPD_5LeFOFN8+$siJO5 zXbvPPg3U~Df#a2+74F^G5nRk-=vKM~Af(LG!*d7A+;b+~gW`jm6%_7^LV?OI@I*kT9DVLxK! z0>A5ABVP@u+Iy1#@^ED@2;cqq0j@!6OQi*TrBJfpKiM2)|Z0h*XXW-q^`@Em>3b~L4^I%SZ9-t8Fcnz!{Pt*dORZEHJ$Fwm| zHIRFO4GL>6z~3TZf~rMrCW8mlpg%tY7?_@T@ZBCB4C|()z$RFK(E0046UT69=o+UT zW1mcDg5y9IzHdEcF{H&9oA!I1^a75kZm3tVP%uLyI4(Sz4>fS{iH!5xsrih%mIg}K zCWD3QmCDEys;A)SskSnwW(#Bojljo*YRpJDgb(s8`rhaQP=rm1-Zy|RlHkl#5mH|W zrW~A=nvtjC>FV<7TMAHphIymYMPPafl~b35MQZdryo>$}s}9&%5Oa(j@~3T!Y=G}@UNF(MIpIdMb>H3$q^;ZRW9>cZ*y1995sgg;mH-yb5Yjg?cdGOEe1_q#@ z%>=1$$oJuRmg)IkB?HM>JkLGJb87U$vhq+xn1`ivS{(1SM_V24wcXOZZ+{fLceAxDVbRbEb|hjA!{l$)Q*1mqAV;e{p8b+e?5rO2iDXDCj#jV)VtK7hB-sAn zpty{7-eX72yERo()rh(I5CQyP58lFi?@ni!cUsT72lPW|1r^zFPe^0uYOb3N0g!3yn=jM`vwc3tRyjeTW&Y$kPZh z@LH1TG6oAGUMBD&++PE$un8s(Ei)_x^PuBCD=vh$7xxmT(0_;1SwTgJh^ko)F5`Rx zdTRxJ&KGKT1Z~A#Vq7=H5;&@_jSd&QXi(2wYY4l2)$!?yz`z!hXO8&sW>_jxdzp(8)jztUCCJ#Z<8~zfKra`L6i0|4(RxmA( zf*QYBqOqb8uv7|`e1Da1__R>)#9MC^v&WJz_`0AHAqBmh0Xqqx+zrOMW#Js{A~h7=zpBk=SD$O+!)k2P``Cmp8DL!1gugb@I5ro2Dq*gmL`la zvefL@XsJ_wA{~|8-^a;z?WzX**dFTbZ2eWvHmOEM9`GzVRh@SYRwa3!fy1@u&F-(< zTRi2%hQxpUR$poC0N}J)^H0P%s~ka^2iriZqf$}8#SAeMu*4ZN=9ZuW&V&=YReN=< zj9QR3?Mxd`4hLo~VfK;I{v*&!HGeSVq^VGts0AF;8}yx0sM04dNXb>D71sUUOnRQS z1KEBrHh~9V0ZN${_RkLu{WS5|4#=gz^#c^((= zY*>3vI|cwoCxMuVu-1(*izM0iJWkrOdZiXMD!&!!$_&T_VfJGOJB;3{G2LutoYj(CVHFH4u znw_2JV-n&(FX{NYw)gdbV@P)(77f7+h0k-VrfBgV8!5@p_6vVGR8qdy3t6e~LP7n@ zjyVe*t`Qav)YIH&TsVZ_zV)5qBnw=z9e_!Vj8@#-H79**V3`ZQ4Ve{7u`%;Wl_f&Z zAZ?Pe$WCX@tmLQ0pYar7T4!oB&ztEc^BQau%}^j3CD-5%>7W1MH=8=LQ0%0b?<<-+`dWV5NLP4+utnRcdH_|2nSM{@O5A6c@&5$0SdVqD$~>gkR{@!rE5@w zh$to5`j9Gj^{n>-mlDHM45OnAoAuA5SaIhV!I}%nnFX;_;Y#z+CTI89;WLx^vwHl3 z(WGcmHZ&6Ei2G{S#b9g$g&4$gqjo4lxU5QM;p09!cDtT^f=0>^ek`#`OeerMn9x*D zAFeMhBd#HRZk98x9Y`=KYYX#g=n=L;%H9!IR&;`9(8;2Z2N8#w75~FyV>nI#zJ!67t&2vCM zFwUc6h}B|MVEGie?41%UaFyif^k|W5r zS^oT@xTTBv9M(h>h|u2S{{?R&zJlAACZS?5j`3t{@VlL4t+EgB>|*M}`_9N)Jb9LZ z3#EgbdLB`+R-0}RN1y6|07=BZ0(-fOI-}=&mV`eq%4NhRd&yA2DDM$U+d?mK@@4)B zZh*J{AYt&Akfky7ZzDJwA$3lQd)8<-rE_|M?nyKloe!c?jMu_NQ8eXDID%1F zGu$kMG>-#V9OlJ1H6z>`3{OA*6=BK?P*Ssx+2hm2JZv>zHX4vDdO?5$O+Eap(S*~x z0}>th{t1&a-g8b~Vn9XN$fH)CoX_wzCxA+Q@~*D)N@>ymAg~j!VfDg_Tr%W+Vj_6P zWGN>>eaw7WTu+iOeuM1Wr{&>iDE59@-00J6&aVdOZ*0ewCwjjf tB;-bKf+67V7 z#lEikuGUIlR>V>LefzcY=({WyfHGmQ*Kwa7!G$Icb|bYqj&h*bB-ZKhj0BL?ANcCr zK!TF2(7gOvla5*?PfUDPOkG#Fav$tLr6scp5W?rDfwPV1g1bDs2ew$Bfgw z7}wD>HE$fG)<+7E8s+k2&a-nzo;?I=4|DnHHP;w|2*G8>GIk|;FO;5z{eHU5+ybU~ zX-9Wa?fhnp>}osREVR+q%lU2;h$t-5EE|D_0+RIQc`*?p96cHNSS?G zERYNN2V_~$N1;&vOW?qL%}%?ArFKkk(*kQr8ubAhdX~X0A`}ibTGBXaY0J}@qS3s* zbtXLwcxF5ne<#%-#;^9yKB~6U)dhU0voRtnE_Xu(fawtqpYA^dL}Dg4+W+dCd&%=~cSACL$!tD*wP(AH5Il;P*QmbW>3S_h@73Atdk?% zGl1Y@7R_8;`L^AexMoG;tz1^OSkO`3&qM!#^%*cHhP=t7t*2zH;(kH2(bNhBI2nZJ=wafS3?W2N56iG03z{+U zn6~fP^2&yieUV}ElAOpy+AH53p@sQZ>9bcYT~tmuV91%Z?Zj~&Ygn4n2A!u)2%0=J z{kSM{=+&xLHACuFz`t_|YA<~4=(9@S*jO5AojWN!$5&MZ+m4JvGcBxn7`!A|w@Syk}iVAr$%#OhR3cvbbT)!%DaJ7&C%R-0Yw0rw*zr?}P z9q;>tt{Dz;8|?m5Qi86p3p8D%{+Fg?vqE5LsCpN?@{FVd2>2u&wD`U9t8!8he%RlG zW03q+E8<0}{n0xK45VOcx_oDMQkMn8|3GXio}3KWRaAx@iz-(pxH>DZJ2L4p*rmt) zzyFK?k^Cre*QBT8>z65U7R$rZy9^5z#E?8kVEZX>Fp}pkHOxGpwh7iO_Oth3R}c3- zL=S(_^Fv{13olL{P42q(*H`wtfQ*nOwd!1?p6UXH27oxQs0jODoxPp0GW7!vOTCyq zx149#X5o~S{=Tbop`jZPq5+4<*aWq8XVzjBY2qWkKF!nzfDiTfvBphbu^BQiPz)VP zD60|$+lK%yy=_J z7CwkrWa3k!mI!n2E9hsg3knhHZyo-CcTp$|9|N~Qo=b$%ZSpcc^3k!}peXH_lCZ^x znxrUfncjIAoa6rMu1Ql-3+j%q@6`v})aCRHR1F=9z89|2h7o83QwM@xuM=mvz83t?q>0EPM(#x^6{sD*Y)kyXt_H$ADnou^ zu_cE*wk6uOCTjz0M>eo-D85`$W3>5{_||Tz^q}5ukt2D0&^kYOGQczp4eufe_kuR< z4{wr6`coJdd3RmA2y_TyJoiv{2I_J5OhMvN!`0J04G>JG(EZF*vu`q|Q%@@^9cD-( z9y@XwgjHaKQ}PDOEPAGpnq&{c=zrFSTfXXAoeRN?0YZLi93M2hJysUmiP)DcDFSPapzEs-a#furyXAz-ZjGsT zyp)HjdM_+qJr-;0*Npr8u*wAIXNupysB(YffMK+(`T)y)gR6*}NJ(d)8SvE`sX6am zOnf)3oUKC1j?L&`N(X-v`k1KoCBwM%RD{tyIC~af@gfXVC&9+~coIk-mSC+l6^hHP zX`$Ap0qoo)aX#|*3TtBhReL^Zo7Oupb3wk05pfUv@BXL10FY3#b4ID$&pH8C<30-_ z4#Vy%D$SA|z|)ASQMMb4w-##s$9RnHO-vC#G+_A8GX!8+ z5ysG=x&=PG{|5M%{ey)N9loeolaI24#C0WHva!N1WXx>OW<`hasc}zoMJ*S3p-!a$ zM~k$3h^zu?X>kFoCCrw2o~D@#I6>*P=6`_dy+Vsu7Zl$>|3;NQNey7B1rIAAyHtuV z|CGSl5LXuEwiK4`ondb31(h-5sh*NRMBkN$dW)j+7a_)Ok9obOA%wjUc5x;3uMW+l zDDUb41d2gQDU=gTO*;U^>W2*>?povspxIh;Ct2mPYQ8i;)4m~I2j`yPyua;%oN?TX z17{Jwbx0$uTT^s|SO6LPmZx+|eJENg7t9mYg$A(;p3(>V5N7CCS5{A&mbVr6ll}+I ze8ekNYEu!B;8YLD_hf#}A)nv9^x7HbRJ~~Igs($ok+3@VQKRCK!^;3uO8%ss(Z*b{ z+r2fIj2w+Hkr>`(r+=N!(B<<B1DF+yUA6rZVrEs0F1VBhIzch zJTB8x=pKRAvvJEc4V2;I#vr`7Tz|Cu;q~Va7qTrm#>wREJ>m#5QpnD@gaY+PBD(0)HUgWt`;@x} z*?|PVz*Se~`q=f@7taR1lS1-Q_rZ zV|W861jD*X!t%dL{yEY_um~rq|I2u;`#o@Ji<;U6OGv!@2GB@9;}jFwHMsB6m4rJ7 za;SN0Bct2pb}j{fWGVDG8jmVr4A`$LoLa_F`cxuASH#|7UoH=TmUue@FukwjNz-zn z>CT1Z_wwh&3qooHmGbII3I#>|-;_=#VJkCH{Zx~^#H30=_t^b117c_~w=Q}7<3r`G zzBVq@+AecaED-tvD8xiX_5=^2KLG(O~LIM(Q~qDdfxDNNqQ zjBts<%GF*pN5cD7`N{y*6F#Y01Fd%V@uP&@`R-poVxvDLU(~Hbg!$&QcP@Io1vCHo z7vGjle&uM`_&5aP`gG#e2)?mPC24Nr1XN!7uuiU%?Wl5--k`Ut7i`PZp^;*mMDr#u zS%LCouVRl1#LI5Y2~&EQ%-##|oezAsyTZxa?~#IH(}2+kNAq`jWcm3kT*Iz!UQN5W zsU=)^mMfjwzV^W3JnrjXASomhRK%Ev=@vAnDw&|tHX#dO+~!be>5%X`KMkUB`y0^LiW+c*%aq8kgT#L zefm|aML&INiE@N2&25MvZrrT4X+M7^tL}F020AXnCxPw_u_?qE2NOKg6OY?FtFoWW z40(Iguc{L3?pGdrRm}fND;R;4rq>i&WUpZ9Tol!4SrW09D;8Jvxjaf#+<`_Sad!z~ zgBEw`5(n6sO^$Q}pNz1xTp z4jau;eUFwH7d0Lg1q{O@T||6uB;!1b>sFoBcxi_N>d5rRAeET`N$9aF0A0#ICeUTa z%IE*;0j0Ju33An2O6;}Y!4tfqRMdL~X;hj>JeiJ=72YGo+&$>Zh=P{C57wJ?erPD; zW^BBCibEoxwgA9=fO-kw!D3b3A}oQeA{@&3d(n?EihHX-o$VjS>!r`uqldaPHX)&W zMHC?DbP`(1ZRezMnbAcL`Mk{6u&as^BMNo~;yd+=acIuGU4<_U1MPnpwcG;4A=Wl3 zH_{f4jX(}g;qU-8Q{~1S>YKr{HX6{_>Pe#W?Q3|wi(@43PXIsfFHQzX6VHvD4M~gS z5)n{-zBLA%)2vBvlQ%>{P+|>Jj@dd_8Y#gWohHs>M?KE$`H6U-ySnt!b@L)@b3|jN zF1}&LrdiOUsT5kbcijKm4*}LkEfyh~XL9V^IjWG~hJ@=Au`C?8W9 zhuzlSScJ;8uL!kO%wIB|*m)0bS0bBg{-bCrN*FoziJ$Ys?nX|nzqv?Bf;Z1c2$kY# zr4$UrTEI&y7rr{kV@0QeR1@kh7h!rP3=`ZNm3VAaYnO~q8VL5nM{vWsb4oB$qBNk` zCbyGFPi}5)QZY4$1!4*GEa@{$Jek?=GM9g~Pk0aKIWvY%fp)L%(an_*hN@~~;QLb!th{ z`Rcg7r$jA765G@tCWmZ@Jcrr>F%E#%gb*<4@ELUwJ|_gbJ<*CzF(O5u|L~jlzU|U< zkO@i_HfhiHxi**h=IhO2C9y9gTUTDOVRd#Qj)x2oc=O()8JDhK8?FpHErMqR)URDKGTaA zIbt1qoq)?NCSA@ta3XPad*zEE)3Gqh`j+$$bgqwHr%wLYZt}wGSi#)~IamLAnlr;G z9u@d1Wr*y*MX#@|it%LRU}u%1Hr<}#VJ;xz-o~NseuH81Z3t+UhLl83Vnki(<#xh1 z{(k17Oe)mE4;F~5RsK}%)H8%eemF1YXIOh@iWR~gzyq3o*cxY__oU$0#sXb6_J*yJe4^aqn9DN z2`Sr$9(HLyT>fA@1gpN*DyYs{285YACXBs`a#K!CQCQNOqw zqHF-S+d8-qy{ww?n#8EpxSv?=rp1r`Mi@D;P%MyHlF{iQP7`j>x^^m+PA`^3E)F&{Ra*FR+ig3n;bdyjDkfQO?^* zX9RkiJjm3uMuNHCoMGfwP}X(sYHP&{k@-?3$CkV0Ia`FySzPHVvftnBbX@u9(Vk#s zj|A2;u&G#oZ05A)c1n*;7|9sNAi-(Qr)3|q2SzJxn*^S3De>K3uzCiX<=Sn=5 z6wbY>asc0VuB-^bW-KPrw?;@6(dy)8p01?_N%{tC=N*L?J=;3orn{95DG5Q)1@WAW zm%D0vuuMbp#`+sNL>SdJ1!KpYTn5rnv2xO4Ub!*i_fuA*Z2LB^imA1dzXc#B4SSr@ zf^SaJWAmnckl}rqbi;hKr-O^liRq*HJaf_Nbw}i1o3@elkY4X3Ci^VqwO{zfojH*l zB#I-XTeYYvI}aF#AHa6Z;_MdJkeJ5OIc+c)ZhICB1AELdt7BZR@N$O|CqG<;#upWC zXn82Gw(ro3e-m(&`SQ~x$nkdp8vgC_WAB@BPkDt8;EI~^^nCB>kTu_k9O$g zR9hGODFq7)=ujBlqLvr__r?6u4+()3; zH=%MFuS4_Sb|3-6rk-}b^)+7Be(T2bHcZwoS1%gW&DdVA9K01x`HFfdR8Yqd3k~H6 zbF}CTN!OPWX&Q|HPEuI1!H%8buL;=J({6Of5=IA;a5BV>f+>EuyD`;t{3D&BiaXnF zoJbp${aw{`%JLBS#C6kts~R5I(|DZOaUcjOWrqJbIyh zLM9jnX*Tc*Q0ws+_7;)(Uodl&QxI3i21iTTddMUT%Ld4G>V=B4sj3&Xm0S) zC_eKGkBpBp2|mx2iV09@oZZ59M&(vm*YK^BzOFghgB&WyOP|2Bc=y|-;@mv$miesK z)tIJ2EAGIUY1*x`z{AQ{J-|Uu?NCTDXDd($p+UHpX*nuoAsOwsLZ1e6GqL3qJr-Qf z{QuB;mX$G)**Z3uMslLX8j0RerNhs=nsi2I+s!jxzy|A7t@Bt%ptP{DlGh?w(h%#D z_4{T~?O2Z*M#Nq9bI>Uj3w@>NX4(o%K2x>}#$Vf+qH<;Icx0n z-Rp^*w}ha6_{vS4k~f-Lp6p_3BG*P1)P3O6eUh}KPy`UmT!D1=UxIXnK79lY2r7|N zDd0 zymocOQt&qmhK&whX!6Y8TEn6d=_~-}c|Y$s|FTiLlh>jz=Z^O9hTsyLD+EVk~ux+r#fxG@2AlVEO65%DH5{gwxg%~SaD4J-I3QgHaZYH zmItg2bnFt<=hy2%suLbXN;Qs8-4iWuWeY{FN8~>A~X$)U=p{0!s5%%U~fpIX(KrxQYLC%EQ{~HtJJY<~4^-S#^3pIEu zL!QPn2Wm0{{!5%%wcTiCR33;K61%RCpG8ILQ;0%vk~u$zUvh!AB(wrh-S8;!3E;Lr zKe6-_#UYznDDYCkBiy3a_KV@1R;us&n{iB-ZfT<;lN^v!;NCow%zYu_A8?7-rJY6W zHfE!F@#vaC0gw`pk-(*Q_WtbYUj<-RbxiR6{x-$)EjlX`2H_sx_+57rS1?%~3p1`; zanFt|JOkDzRu}uajh>ft^auxv)!yPF#mAyBA@N$;vF_}p<0P%|aG$A~3 zpI169A=R@}5_Rt4KZ5L+P@lkldxs7ah<%(M@&I;{jk9a=j!X>tGd~m(Y$O{8kgZBJ zF8~e@pbb)iv*j!qWaMu5xixS0rE}V$k56DIfXlzeuf&u{mF zBfLOa;=lF@yZ%ww^1}=~oGM^xPH3sPFYjb zq0m^XmkUP{r0z}Dd5YZagUqmw&(N3~a`|2PC*HKvEp<2#|nYMNDV4c>0YN$02N$d@FtnnGAp1Y1hiC<;FV}6lbLX;QB z|2l}p%oBYskL`V#&HtU~f1U<$F3(#QkXwN?aJ`CJzpBmvBV&6L_7<#aH!R;L%e)hO zd$wqli3WK!qlx?1%&4p!1Zr%)oF;de$2=62SF%{|K1=Q9V$^3NNZ1A5) z@03|7aZk}>Yqf$06s9qhSsFqDPM#Q=3F)uA319aB$b?8gc}mp&tc5B z%B8tXUGUDh$wosXxsnyWW&Yyd9WGG4jSd=}Z>2KykjC~{NQ%x|+RbK-LanSkEZ4zf zwdghkS=TJgEc_1MeriMUiufcys9`iM_^pIaHPJe436mD>wEM%eHlaaRYD);ua- zqV2iv_NhZ}kKM;LOEYNAfjv#J528##u>_~VbaprSFxLX^Tf=qSKxzY;Z%PaHZ`5<~ zAsJV=0HmE-4`eNtzq#oLV-Zzoe*Q-q zFd8?CAy{-b{GCqcXSB8UHPWmrb4BE&kodzyi2~~-&Vc}u%eUMsY4aLYtXM+Z__uB| z+Im(kOaoL>RvpDy+gKkzD;nU*OKC}*ArX3_(N9X%;#>(H`_)>?~K!tZ20@e$lz? zXwYK&VaF-C%~gtn^TUI316{)8f9|HDBF;ovZv1&FPKj$eq9+mC zbtEmgV1d}ibu)KP^(6>Yn1j#K%D7bUB&9lWDwoYSI6tMcche!I{ zS0EgeDV34tdI3zV!f{iS65#=P1x?5bdovXTO>qQ*roFgcHeoo`YU!O zKot6t69@8s2M)SjmCCN^HSGgdbZ#u`^)EM7L4CF? z4zfw91g*|D`t58yJ=wPtc6(1?q<2qqnp;e>9?QDKm6iY2oP@+K7H;Zb2vv#oAN87m ze|{Qb$(+n#EOeN7PtE9W9$oyzMnyp(D)qS=x+dsSwp*}eCLSyx?A}%WOYK!LpaCC# zhw*9AVrmzF9RUF#-zFV5QW;fSipZ+B0*`g9uq@(8Rnmq7zR=2QY&8|?ppe3i?|>Q; ze3V3fLWb5MOi}rJ82w|9ym2n>ZP!0z4}wK$(N|xKU1ovrOa?H%)jh`cGy(L z5AVcp$vhFO#dm(0V(pZ8d~ zq3Z=LR@{q`dou3GFfOxho;E$omMQh>-Uu5Fd#mjXL#;Mil zXTYj(lxCA|FW!DjSW9bwV1Rok%+&a7r1-^-N|a+AaItmA|23v2Tpa7_i_1Wb$Gg(5 zNGJDM%hIBN=p5=#sET*(k;eZqWKR!e?jV5Zig(r*1*>%)8YbOlv%Wne(8Yjjp*}@? z%rI_8H0^@*=|(1jmHR=ZjA7#Tb11suD3nrCa*S$WDIb;RgQ{zquL#mPi4qU(vUqFV zCd^?RxqSuN-;TgizXP$DVA${G4ftgk1MvFq62g#t&x6mdiwz$f+O}_o-vk=2MHu|C z2(69cl=4F=?M+MEebMmvS%ZW+ou*Xfull1&)21F=)(DI1yuDKQ=z2yTZDaL-GYX@< z`MTssM{Eh|XA-D#@XBEA2zePCwxbivHh#KrqatseQ#UR`-hYh;c{@%TN}A(}=#l1c zd|5Hw>&$PFhT&ffwwHI&Lq!XrG1u``_rWTNg-IjU&f&GeL$hxXd2eL^xMrTBT2_h5k9W^CwOWM>Ux9 z<~C0)>UoMPwrfjTsG27?k}U>Zn#9?4<(J+=5Go#`xiN1Th8M5Ekh%)GK$m+9mmy=T z)`O+6eGLy1aX(uy#8^7Iz7=A;nUvMFVE+dhm>?Yb4A4NI-{z8H(CRRMeu9#gz}Oqv zM}3do|ASTk7)>aYTQnzs=k(oI9&pFuna%?iwNo*v-|6$BkryC# zr($FEZZV+ck@0$MpeKl`t4+q6O(zAtD~W$I`J`>@NL5Xib1FW%s$P`~MnA&86Ovb6 z&b>zEPo=$95ZV|NHRKJ(Z%8D5*R*sWtcZs)kMTE|_dGTEpWl&&JTX=#+qwW;KQcww zsMhqM3Wmv6AvAuT1>9Q@(!QM1t{vX+-?P4M@C{9uY|G{yq}h95DzFOe4oTA!{c4X2 zA&Xm2n{@v9>^E3@Gx*!;F*n&Lb1!(Uw^H(Re3q*FYMYeS&W!Ulc0*Mi$94Lpt-OM; zn2+f$yiuUSAojr@L)nxIF#ziW?cCp>5Z&As()RROp^kjH{|hksO>Uod^Y?4rb+^)}f7B)WfgXXBp!vK(GT3v>!4f%o-Ut=G` zBp?IdaUz~6k`HsmLSwA)tz_^C<}x3`kNu&2gh2(E$PjB+CizGLC^m9*QBE$k`sTjI z>0V8{se>E-g&4e_Ygw%0Fq^t`*^hLT@{>V>asZRQnB<>`HreuzeJ(oxcROyI@ttdB(3zgV=v!JtGpFvRY=c+S5pse=r5h*^rN==Lh2Ol>^Kt4pe7XqyJydUaXXRouo3E zTwXD5@prAy?Y?skj4#%uom+N0cSE}5g1&c>F(!sIz(LgnC_Tn=`{$Gh3KRD zRe&L+IrAL8$_7mUXO4)j+B;G9i3!C8<>4Zri!OXOg0x+!tXKh3`SxP)s70G`_3T>=8~VS32&rz+ao5__%&A6Wx`%fLceic ze78IA9GT;JbTF*^G6@c)=>g=idR9=#m9H6rvHJ7A$b?2yMxz3jD4@{1_zv6-kHIUy zMMuzx7&gYJGKlx#*<^?I;c25a7aO%^Z z9H*~A${^~TmHrU1e2%go*wztiw}IG02}_N)zSbJM2#aNUNWS);{~mwqviScSGIHC| z>sYXP*KhRgqojY4^$E?vds8-OOh34ufb+xtk@7}IaCRE35cEhE#ejxG z$hzxc@;fJolUG<~BGd=zzbL?(vS13ou9KO|;}b0v*7f$R>0if&O@V*k4I~d%pgK9M zrW0#W@Jn}ce#}BaMvmqh0*4-#;6$9cAn(%@;@lC}U+}bnJwLh2IT|6HL*Y}^x>DWg zYV{|x!aOU!G`Ht4QrfF_0X*z7sIpM0Llg)0H*|7Pg+PZdXZh3rek!4Fs%20Nr)!Y! z8{s%X@YZD$wzO+2BRcWt1R&j^uJ`vAyt@qByH`*}EzKk=8y)Ysy+;qrk0n}V?cX|~ z&gn#7e{}1;SC)e!be^$BM(A(NP#@NORTW^RW~rSD3AtOwXf)`qyHs7j_d3GGh6tC? z4tWDujPgohu+?^}J9AJY!!fFk2b~^h#*9U}J&~|}n!hGI9x(6nIl#*ylCX4mc#`xO z84 zO96hqKOl4%?L;ViPbJ~7dikRhZc_uPisSPbyt-%#JrcMp;1LK}zBC*^W{q+`h}8=e zPk0KK&^w273a-dO$9#|7+sSb^WSmV}LXpocPEbI`kX}+=!5E3W)#8U;#TtMY6fh>c^2 zCPBK{d2Gl$JV3lmJ1ZB7o;Dp^-&GL_|6cF$xC#oLhbi_YVXc?|&e)+>kEc!g^Fq%Z zGIkZdrDn@{@lIG}Ub%(S-o#T0zxsS$Qk(ZeUcW^{_+6`?PW_s0V=;i-QmJ01;tW|$ zN3m*Wz!DC?eFo8cZ0)16Bw?*`)Y1ZbTei8y8npwa#NL)EzAz-8)kWvcJL!sR*6p)z z5TPuvY`Z?4JDJXd9aHom;$#FlWO`vP^kxxI85+|)iu#Ie$ec%E=w5QIbU$G|)IkG; zTKELEqEV9NH8Bx6JkHj7xQ)g5_LOY7esGfnx%}tl+YHoSJTz(UIdTS;Ln8}PPwsJt zHWQ4}c{`fk$L=it9B(*|e9dT4U3Y#uwvp{*5$d9)9H)%!?U&5Bq;cEy!2-H! znQy?Z3$hFn{*Vp~6H})N@%o@q5BNMnWt5|Y!%1qpumMsYlJ>N5nlFf%cUi=@m1Z3> z6^-v%P-}HC=N9hsmGidcTE$kk<1*vLxAWS#Y-@cV4**xW?Ulj-|L|^;>wtXOTT_E= z3x2bFYwX_D2#$|aTk~JN;;a?+1XW9ySzAn0b0Jk#5}52@H+@23298y$tfsEP9_U8g z{FRsY5y}ltN>`>^m2CfV2G;Q9Z2DOzp1>J3<0;nfkLMb>pTekyU3xooer9Ox#ULt{ z^SZHPhmy=Ya5Tyypz=yGcHg%Dl795=ez>u+5AFhKp~#JxyqSGSAU&Ys${ zY@p^g`ZaTbxip^=%~9xdB;Zw zP5_;GQO~pJyoQ-!N05tdgT~os<3ywG(x1N*-EJ+w0n1t9QHg8e!wfJccAE;B1Itrk zSms=LN<}LY;rN|3tlj6fkh>DO615CAtalTTwO= z+z@8vz8*RD+1DbT@}vAZ5Sfuvi#)49@?i59tglo8`bOR{v=jo4HzO%}G>{DuXL$T% zQSzMY(cQN9i()qKJkaRJPY_VoTks#O}R>wo{VVzh#vopSDo_-fw$ zwfG|-0LjS#NWZa^W=-UE7{^N7-nts&=2mz6=M=DD-QBuysR)^@AI>drW=!M~W<5nr4 z#_n%uRoniO<*YAnN|5eXgK&vr&;%eJmSJ}4ZH=qeNVG|u#GC#XJjUIoW)blD5$-%= zX@}~W5Xk1ZHLfVbjNfAJX_T%Qs(DPyk`@>|KU4L6VK7`XZd zQLgW?a&i@@mzp*f|N3%NPYBDE-j<-8F>3pQR*V|~ctHT~<8CxTHIuy3Ikztbd|N_H z231Vpj69;T5%sv>8bg_3Dn8@HCsQ zr13;JbMX$WV)PCGEU-v!>hLmLqOnbfuMssg^w!i#Tas75!SLPUuMC0%vkx^0J#BI& zwQY3$DVlL%L6B1NAeFtrW-OBMH3-xMCh>V*Jvn!TaI=qL26{F_YE0KlrFgOmt4*Sw z^;j=mKR|1cbKK`+NsBVB^y6%#u%E-b(I)BY#U3ZF^_s_wVy}sSZescyM5M6kGV@^+ zl+{&jBx@q`jp2p9@?*kJ>lq>)8Q)_Xai{A-iA5JP3vbJbCXhtI39j;~JfN^2R$p*q z8R%0MkTL5)a)q6-z9O1dm`h+=jHoEY>vt8F&wO-KRX07Wh*&p}-Y*K*oY82sPl`Jm z$3X=pw^Ux1H~x-v-|moYGZMLqIqhI!((JMe?7xs7Wg9Pb&Im5zmxP+`_bBPU3dI)` z?kP>SG|wHk-=7j;JspLCSi+p-HRWyh#OKKwQ^K~*seG#YzrzVjxK=1-Rk_TIjbB9H z9-o)%;1~FM1Rix&|>sNci7xx`T%&eO;(sZl1bolPlg}^&4of9*(kvO&18tqd* zBjJ4e5IWZK%5=vLXx+G4Xa|7b7fK5p+WP_6q>|rhsd$C&Ynoy%^@SU-$6z5tnJL9( z){Hf$ab5&wL-@-kKh6X(5`H={)S9L5o*9bVUyN@!g1nXvMcc}TC=c%8O);^OO^1qA z6vXH_P|%kkJ!OgmeM@!qxTSX-b6VQtsZZ$9%~{)_WE@ihEkSvj464Py9t7r}C4*uT z>}C}EX2ovFl9`*g0<$)uB?s2kY%$oll0@k(S#S}hgN8z~6`D%c+U)=2UcUdh&1_u! z5up33Y}pcG?Lk98qC@9)$_}sAS&EdBP74w{C|`-P1uSoXU-AOdD0xSe%S}P8yC#}X zpxDLw@5dyJ4&%ia33Bu0(6{C)1GsgLbK@RZK%6{nw#JP=!(CNY&iT_}IHY2Puq(?3 zC1__4`$X$g|G3G9s}Q2OI;WNwBEPM9g2-_(&3$}-6b~6uT`5%i2ekx;-vEO_^5lwK z?>vB`H%uDTcb(d{C0lMMccxm5hwvafu|G%6v#5aRzmuGb+tb3>WdnrU+4}%2@dI>D zZthG#B-e|fWspSTTOL3WSpQ>|_`By@cZ`5NaztCE3&b0{vQa=Vrmb&%CaAzv!dkhH zbb|myzmIrs9DpUnM05&bVK;k;sns3&7gA!wCv2R(ub|R_qu70}@iXy@O0ubx{s^HT z?8r&7S0~+j{#u8VJ8IP0)ZoiTz9v^ZX*r~q_Nz>EZKVbTMdyj^6OIwPwY0igPeoun z$m&EYtZWFk9x-B2k}c~dl;i4&XUzb)*asx4dP~F`wYB4%u_~0zxF}3`y}``eb}l)E zx~>Q8hPr%rf?5%1GoXmbCHj;ZK0(F8SJ0tiL)s>$P8KXyfbK?{F-7@`-1kG44pE5P z__UE)_Y8Tw_yJ= z*#D|fvg%Tt6j6K@haqEY87RLkm?zYsfGBSwpP3%%>5OfB?@N@&40D+&UToXBoB3Ki zO76a6neSMLf6WQo-3#!I%#_lwJltRXRoho(hEIlPQE$Le{{q60cJW@%w!d{ZKpzVG z)1ZEm@92k>i=f(`vsojSmtOy1{qwGAnVC#XrTn9%Hb-TkzA8F8Dt&geE^1~4Q5qyg z`U$!>oPb|%qdo-V@3jU#g&*O?)`(gaWS&Rz_|$`eLn#}s=Wh*`g<=Pma=4AGeKtru z6{Q1mf`<&g#=*Ki@4eD`0nFCKTL50p9(b5A_S67jrryJZp82Tn-Bp9q&<(j_#b5!? zRJzUY>qz)%NO<#-#I-skpf{oFTa2BQ`^QjsP#~HdQ~il=PQUd$n#@_ZGO`fTS2;A~ zICY}Vk4edVW}_F1>0puntg%$OE}9!P56jl~8Nw6YNN8E}C0kXxr$`e+)SNwgVtakQ zOTtD`%>Cx%KYu2lwP1K<-@4ERZKXxuQYO&s7ngCNBs3EV(u+B!40lFsX)S;vW9c5m zp!y;BAb{R@zbI6R9aOSQA>yUNhy(q+H!b`Tnl*WgHa6nZ4SEFE{IW{C{k|CShwb(4 zw_tD<{m$tUhO60W`w;&vtRY@;u-ZQ=FZ6UZ?B<}*v9B$#`E1>OmkVK^ZH^`ysVy7z zlD%FtCxMt=q#$%e9Bps7X1+-f#|?LbH!N0+yv}l(+<26_>vd3MZ_XUajmRt*hrhPZ ztAoCy)kaGsp1gwrl$Z(4L`Nv&zB8r7yVKRgK<0a#SVET%GYf#Kzi-OuDX>wYuPzd2 z%$|-D$uBZ2=n1r}Eqe(4uFi0p)emt)7l|xiu*MzlCHju5pWGQgqcZJ`(>QsIIJCqK zd)QKAK@`v>E4@b%?)ol&1;p57p4Hm={a*`x>?T8^6^=V+L}+r(7B>xE5lt-(5Rh(V zwy{h#L}3w@oOx+cye^S*ZEUpHOX!-_4o!T@ZZ@YS?)(D2wH!$t-vDJJpK6(XVqTsW z&6wJ{5vi^$jIr~Ft{+h|r0$NX&t;C@V=cZ|tX~96-jBQ?8L9VKwh%ruQ$(Xcgm4en6pbWzZNzMmniw zHE?l&$LRJQljN*drE!gEA5qw_b^J9YCcdtjUW8ZjhsR_-8FD?*P8_gpRVxj;qb2c6 zAv}VTRZD$djiINsLfc5*cXt17WS3VRw8g~J00xh)C`QdXH*Xi)vnl_tPefNFBUa<3 zwr@n{lPb_$X+1O5?k6pjhlx@yn4pW8buq-7*YeJBT>B)A#vR1u@>X62qfg~(fh4qa zZ(BwGpvLsNDq>XY5x=CX9w&Jvj%GYNO8@8rx~e=lw)*g2f%K#Ox|dGHy@XTylQ2zA zKaGBtZ$|<1@5yjh@}2TDq8pm25H2}2N9yibNt0`)QE>l8n8I5=s2GdJ2z zhGZI24qCTZ2x}WQ06;}HFq&Rwf!xkfSkbWgl8oX;zwL9%#XRQ=y@{UTIim{+e+TT0 zL$qA|>MeYRcZNGFI=V(ZSxZ5PkR$p|WUO|?J6Juy=|gJ*aQMYnpSwj7^{m;g1kQV*%mX6)Q0R=Nz` zyy@E6CJV{VOj2w}fqeR+;xXXZk>&$q!9pTX_Np~p7NbUI%HCl z+!k&L^{}~lSPyOU(yN^$>>Zfc#caRH97jK7LPO50Qf#aLjQ*;(1?()b7br|yk*OLQ zNhyBVOA1B2SCfEP)|%Ur(%M?5GmHOj6rHtjd1*1eyjCzwM2sND?5gg}I=uY^JFvE4 zA7q-~lFQ}uuj#-|e>7~(_UxD1oYPQQ<}Rt~zo}uDUQV!{U6U(1EX45r-0{}jN9UY8an)w!n=T}6j!E?bSFbs#r?P~39Mtp`_wTq-)BiVT#osBA`a!e>VaPgp zT+uCdAHmVNtU`T?=q!=%)7G2?fbB5i>eJz>@2mkHkOCe1LXwo?EaEF*NCXdS5i+>A;jg-I3jOCqe*OXnARlZCb(y z>$F+?Rbwq9_?nRS2$NeM;$R+DY}tFp;7r~SzmKU@0Tg{@NjdTQ(@P}pW5J8rV#z?T zn4(=B?huJs;BEArF<1fFS}YbX36G_Q4OblR0`u;=SW=2Vd5=@bc2ge#-?xZfq*r zY9ITEDojtAOPrQq`Wh|4CKR0q4M6yVSO2{~sX^+5dkr%G9&=+FM9B^?o5l zYLxflF%g-+8(~w)YU9$?TkwcT_W(^mvcE{T?x817j=}Wx=VnyJ4o<9C&FpnJjz(); zyy7Xl00iu81br*;_@t+b_NQMI;UEAKMz?oUSl)}Yo}td7-=J$ltLXY_WWANGPUbfk z{La)V_nefP4!#bCU#J@=RkeRSxzWZO8OGaQbS;OiY_K0>jI^63s`7EIC5v84(L9$? z9{GSonArT2!=efRCZDq-wBrh(t=h;(SbXQw;>QouP>6o=w~h0x7yA`6Y%1S>wg2f= z!S2V}puYQcku0mp-AthRerr%x6AMZ8jjW#YojuNmyM1Q>3cgf-taeV@oB#K6jnTq| z_HxESPxjU*yI-j@DR9OADK9KAx3#$1kbte$fyej^e!oFo^SY}G?P;5N$nf8z&h~a1OFXK z99J;Pq&U41h8g=1djfxxD+nG#(WyxThznj zWJxv*@CAex*c}fL3?J07eJFNJ2UgRpZ507Sgimu)$%MQK{y|b&tXi-0<9ik^K_U^G zU@mKKc!B02qElg7ufzpuA9x9au zhot-|=blW*^{zY7q%j8;t{NYEod?GAz@Y*G{81g!P^BAbyhD?#nyoq(Pj>ntXj6UL zbkCLTmy+qpDC1EewFr#Z2K~wSBwb_mA^Qh0>-4H^8Y+=xn$eJ~uD&#zMO(dKj9DpE8wp7f3J61&X1)ms1RJ>|a#L;tUxP4$%nu0QBzPG9v&)>t4 z=kFiH5 z#40Wgaq#y=ucR9(kRs*I@?vxp=^g}e!g4`bK1X%$=2lk?K{Y`3ikA9canZKKrb7Jq z4y1o$4|rAY)-8HTIdr1Yf=`GAI^)x4Q-+j+589t!yxMNVUu^q^t4|i1gz;-2Bui{* zHmwi>XF*`|8J(w%zz12{?XY+y6R9@3%C;B>d-zqyME&a&1GEmt1eTI9RxamP@sdioEap+1j~3dq*f}J5@tj#k5aOmHvWMeVDIJl-~}e zIURJMn0>Q+CY?3Aw8!Y%TV2F`BJanU2!Wt;-`qUQMt(^glSD0lJ7?1b0ndL zwLkn#o)~95z5HPe`wgO4p-3WPUW`63R8PvFRqS%Qzf7A=PuGf8Qet!aH8C5wIvkf& zRUE4W=49Y_bSgQse96E`t%rb4JqNyY$OV5c3YZB-MQ7-%^M?#ivk`~d=Ia+}4gu?8*r3EMi z*(xNFVSHY5VedG_3p0rJ$>8@Gx zkklaA@>KoMj_g*qyO(b9qK3XM!o;o;L%yjWNDQ{!YE!tfy(C6!|s%A20cr$Y@OPI zxNBbB=0DRY=uZ+|?jwSXH!)xp5m!2!f~U86KK=jcU}E?Ub{-3AYU{s}&Li$xEttp* zuDwfMbyWj~pBrgAkR((Z0Rul}t7*&jfc83G8OnZQeBCPzSPR55*~X&Tg7Hagjpp>l z_Pkc=oT;jmM#hx^PHk%ir0@PrMfGMds#&n=HD@-Vnyh2JmDAPjckPcGujJ1SfbdhC z(`{|;mAHc$9g=eqqalR)#ZJP>oEL+&`M0XJuvE|nueK@kvhfZ5B47c`RdaagzqJnC zu4kMd*p;KRH#RoF=iWUP?xhyN9q=}QCYG#RzEXhUb%v>wip96b&7G*XMt5xvu&f}8 zXG~Lr*`JhRv>^u~|ACt5s>{jw6uFWub{fi41^FXDk&26;d%AL-kiPFU9QjAgs@y6X zIU(X^p)P5keaIFju{TB@5oeR8^DUTXFWobq*l5zOK_DX zSt3BbAr{s1)psWIbD&}XhelP`1ODXTdAoaNNv|LuGDX!gS9q3nMqw1MaB>PB8?`-p zb1M3y!*?u-yOZx}#mkdH1Q>tl>45~SH^h3Z8T}h?=7yUg0^Tw%go%8uj(13{%Yg95 zQDF|H&tN=olN zM(|$6O5k;8n!$zF<0ck%6ZdtPUH2z4+;L007+IVg!9wS8 zvLXymn<;fB-RA;3FdLQb(nu~Ev<(e>Yh`Ml^o;}%LKClY5Jl?VyB!z8;tC4$>f!RR zD=etCDQ?mNljUzBGbSHYHB4!kN_CzoJ(1U^^!w=nb65ZAeVt>7yg^b zJa%|i+#Z)T3o;k}1aJs+G=P6`p76EygD}*ex2lec`o}&OIE_6j?JQuC? z4X8jA`-|88f+5;Wo433Kr*NF}AJ?AD9)t?D=+zDW3*}nVMb_>Xh3*SE5V4Tc7sNYQ zJtzhW6D6s{o2?DiFmW;Y7%<-5P&1;zy7IRzZhieVRPvEQKc`RIBw@6*2qyWo#+g8B z2>oQ#Cq+yhBxrxS^$e%&=%8%N&X+ZFxg$ykTy5}wfb>vqvQm<2PEuv@bLd~*)AAeP zIPTUwOTvU^M&q62wmn}?nGw9~?jh7(i|>B*OW}7`k}MVf7N>0hni#o3#PF%TwDrby z7EB2p7+}AhZG0e#l=4$z6>D)1=*EO zS%+sodQ@VM+dJwdY%*1NYYLt@T={~QBk?6lQVY#*^hJX?UMqg0K=JfgffvLVl6=z( zI*OHT%~Af0n6tvB)v@R^3WhIb}W^f7+*IV(V`p+RvF{9#b*3jYztNnB$%4n?i{znMZrKANh_11u?*?i%5`sj>px~nX676e(jPgyzH8*&x7 zIA@+)`Dafi9;jwVy6mSubvZatCe-3G=h)MLarHb3^L==8sj|q$53*Nn$04RCB*TpR zQBS5o(6iiAFfzUMWZSU(E{vCL!7*mZNxk0^l)6eE_Ty!)=0zO2sau# z_j>{$o|pNepKxzR-G2XJcXd-iRj;VC4qk>By>kvtys)_ku^0aJ`|DXOgm=2`)0r0g z74>+=^GM9Wg=K$D6aD)e?z$+b&((Uke6KD4WakVUQp&TjFm`3RD%>K<+Iv~2I#&^v zlt?d<6A10+weG~{DzHXjX5uN1zwa#Ns)L7X0+ZF?+HZKudjwl4Ck42VG8cxG6-kX@}o zP196k97r|#8tdZ=RyS^gPUeG3Ta~1#oOH*dv59#`)g+_&haNtpZ)o1KSg31#uVVKI zb3>yZ$GDn%=1;}YXKwrr5xDYhX8s$w@W-KFQOQzLljx16>R=`6%EIr;pZC~E#E?#u z+Ca4^ETg$w;`BKF+1#Zx(sr2XoVnFbM*k+>)!V0L)6!5T=fzph(CkK2;;T~NOs@y> z&p64xnYwz_pms?(1W({kS#ai0KeXbLTp)dP0pumVv;vFOqn2#sx$}#8Y^b}EEODtN z_>j#w3=sk1bvu<%*9ojPgvPe7DK+`4NV31-9gB~Q#>^alLfAc6x%I967hs{%x>)9Q zTy<2W%eX7Jq~q`wPjd<6UHKfFQjgu1+@kWi+J8{j(1h`6E~=^Gr)iYGH1b$T zjC;C#!;fZ(*l>IlP@i(s?7_EN?KsU(Hy5mmR#?;A;`E3hZ^J0j;y>vDaZ^d`@mw%j zGq6NRA3`P=A&_9z*8jsc&;Ecv@vICNRhgm)Qp1R7YIa4Uv5=)x{Xl+x0Gv4G6un6*M|o0VcU*E zSvyb=YNlqNV)(t#moI}znEl_E1hTe-Yw3`*R5CAoh?kCalNuiDhm3~!{s9jRBsZ1N zcDVTgrhLgYTk~uW0sBgoWG0E=8Py0CIX$%askb(3gE`gB z?@?WKxmbI*Yt0nDf&1}i74}Gt@`)7ASfkP8Gqb6H~+eT@BSU z%Y?yK0)9(El^cR|5`VLQSkA8t+^$uwL#iKfvDNput|@j<LV@zZV0~iYB74uQq?@Y?w z{O$Hhm-((wqn3{1!UqRr8OdYu`mSC9pnadw4Yo@mKM z%@LS|bSJvEO<`R=mxsLUf^e?+y>=R(NS(X^NSg-sRumH>mSb{XfTi-YbsTpYoKFUYX8__Z=(Gb((A+)Kg z6IcV#G)aU%Wz=Sb42mTHrYdb>;`?aPYNop7;i5rNzK>~qf9MAsPg@wR&?rVD<2RW{ z!fP&z1o?e|1FrU1iBjs^%yHRaZh)wr;Y&5-=~g$SDQD+86!PCM6cRSWOgik|@yac*5$hu){(jA}2pyP2PD z8!D}&Oh33IrY`}zX*6(0W73PDXpV)g%T)Q^@@H%=1l(9gXzQWnMHx4)kqO6oksgvV37+DCl;QkaE4i9t<6>^tlN#3pH!c|jHHq@l7um{~s9s3~UB;)Adt zYzKzUWtJJ(pB(!C)RRp(DefCkfST?_@(6eTMydBKR&rgu-Z)CGP6Yj?a%sa>mD@3_ zjBDYEV;P;B&72U(&Me@2@h5;>UhEeSOlr1q+R=mIGMl&~#;5 z;X?HZIzpt2VLd4uFO(e^wv4^8oq$8|E!eFGFKnDl5?rUEyk1X);-f-e;&WGlzc9#bBO@|SUW!x~r*&m0pg)QsU zQvDTAdswmiKy8t(D<|6rdCzE;cMGsveh~YK|0u6No>Q;Aq_>j$Pmrg8I$|DPbJ7eq#OR=8V| z9`Yv5o&>fMKT%0#|8mh|wRS?U^i&}%OU_=W9H}1t(;W33V9JI4yMAxps3%@-exZc2 z9H2Kvr{n{UD^qT)uyV!m;ya7ZLLKjxL}_;v#gps&x@Om7QEVf+C=?(K4iJJT2p0y`-Q}>&Eo`mc4`|w%VKs(6eOMNzrqNDPL!bPZ_ZC#H~z286- zr9g3&Y7ARFnwauGqeEByZoqN5mcC;W@B+=PI*cXt@LGli8-I(BoCnH6A3(LJ%?qn8V-GME!lk zmr4zc0{bhd4S9!ZNaTffW_o#xVGaqRD~H=*uUJN>_?&np*tNjB>(0pY{80M>I3CP< zRCZklR$zShHxXZUEz(Y`Wma3e|2upc(sHY1Mb9N=+_rnz$mSMM*^ZYDjTE`_HVakb za!U2k%Dg?~S(pe&K~~{~%?iWGn}zev9~+#QR&*Pw@Dr@`W~p;!Yte0z21~p}eleQS zQ8pzjlV}ANsXV&#+XL#xA@;9Tc@Hj-!V;5-NlJOy--#0$8#qK&b`k7Lf%bhTBm&P5 z1rQZ$>1)E&9ThOT5-X@W!U~&CDgjMLJ{x_@3(xB;J|4d_O7HXoh^ER!>C8R5OTUi&0@8!Uly?eyI4ATs^ zSTaY$0(ckTjkh!oO7#5v4Ch9Ek42NRpfR08(79O8+Z;Kz@9#Nq?WjH1M!oL=nhY?I zp|0#a>Z^3fokA7nQ!)!V2l1XKsfHI;kj+HWVpdw6}}KpFx{L#bLpirsMRL! z?>8{}Dr*^v(d0wDvsY|Y>nmkPU+e0lg#n`$UG;FymH8D42=P2zYKC`1aIrI%eFJRq zoiJsm>WD#fCDpSxF75M}{q$K{%#drrF3rqi$IS7=@BBn>=hH>dK{b`qPeURM^K$7SRpNpm9 z=r8IP_K1jTf0YbLwD1kX5fLJ{^Dhq{HmG^sAitFfuu)oPi0h(nx;k77byvzC@FvQH zzEOUAqwX0c5tor@1rmUwmtc_kp+VFdz57kG7bTerhQ^`yZ)BaV$H4@S z&ZAqM3qIJX$*+$Q8p{HCInsl*De$;lpz7k-eiARb!m?x8^X$Dmd^QVj)In!@B46MfF~MdNGGmwHQZ+G8Z9ljz zjJ;Ck&umJL1+F$9?a)Zl-wGctAcJQ9N6>cKVKGMptR`3IuPgCAe7mo_Xu;<8&_=>> zih4FOLQ`<8fJ;<=Wuqkf0PXe+QX9O`;NtRZ?hfGIlum)IOQm0C*kPUsL3y55Ew7M& z`!N3hX>OAaTCLRQzazdTGdT&t!Y;gB(mzvZwkE70g!~cQpr%|P=pPM+EI;WdPBZoTH}jqju*T8sp1RJGYoY1xaUjgQ|UnR;GRri zQtPJ+>@X~aJLUICU_9Idf#QS59}iUExjHyFi~bUGsQC9NR>;h8KT8?&zl%u&Oy(!o z(qM@l?99hIiLUM`9;X@g@-!K7=4xz4V!Uoqsb~gb2pO{0a^L(tkf}xxkrG3QqSo-O zW2KmV8t!6;k3~Ubji(&!$tKjPXL9l(koMSY*>=)#RX4v!3Ll~*Ab2sOT zl>gZXIgruMw%w7HGwku?EgijBs+o=N0mT7rMiMW*m}6KZcu7;7qt3r=oYccadU;C& zVIxpvls5BG*Ev_O-b*Bw$edg>QK>4SHb5m@V(4tZFq|Nj>xRLkCsOT2P))O5unU?j zuDGPYQ!yr$LFAJ8=Vbal$n9th?Vtexl8_(Za;alU>d*+!Vb_kZUNT zu#yBBUg#Qi-^au{#vr@?Nnv+^_?WAbdFW6V<&&coaL2j)ezpBCLm(9m^n95q*}$Ob znk)uc-FW(Je@G}6T_=#ESNn~%$V+K7nt0K@OXkhI>@J*@r!v8GQvMlO9!;VR0a%-U zLd>=S@1f0~iwei@{lesvZv%1Rierdp!Yd@)S(>*O@=aE}V9^mI1jq#7`eQi;Dx;AE#&4;( zB6YnCZXJok8G(aqgwS1P_Fi#e@ZaP7yXhlj+8;O#Eeay}n4(%B-CAbT^E>l~bmcsM z%2Cr<>ieDepFl2tFK~?Ko%ld>C0WIYp3ey6kT!+Ek1uZyYFKmj9hwOfG_3)S4p4VC z%3oI-@-02sa)anTZmD0}kU~?Uj8^lMIH@gfnF|?o>sk)#C!vvEFktx&Q^Num-nK9x@ZquAxP^Sy&PIZNRLK1^4`A)JI#seZTo* zI#x3?-;rr!=ujw`mZE@>ypkVcE(^*V5kF6QCW8@eu3}0`$Rf)vf~yC&zh#J-#chV} zjC~*=_Trh)Y7}B*eZuMw;h30+aFZFhyyUc_qO!7LeJMj$YSS>wy;Sw!Ne(K^?IX1l zbr@I>)vEy@L7kO$<~7Q{GYAjcfrUaD9s3J1f#zf5cKn1^rE}WCP?wM^3zWzW$I#AM z0=yHo!4Q@11WAaE%y_xwm^AMWpY==;x6L^E|_}r=itF1zsB|8m%^p)=9DLq=tHGi@+elDI49^F z0aNMjI@d7I3|diP?Caj)3yFWuVOC{W#*(8D0kNF|+qi_+;9;$B-rVJAr%=bbwn%Jb zpfgwheZgN}7?*U!DGy1qVA>Z-TDoc-oO2?JdOqH*jdlIWSPKZibzBu}2i+#VU+|V% z*)%`LJFLS2Q0eqI!1uLWoetyv&bFC~-X;gH6qzv@{m<+poSEHLGzbF1Cd{?4e|c%O zr2K%S0nauX961Mq1wLvl6(HkKz{s217g!M>BWV`7YS+=;=-c+eaiLcL9S~Yk%6?(M zJKmOMKEh-ijci?neXm%T-@h+t_181;Iss-rs=I;4AyI(F4 z*Yb%E5bg5CP*Za~7klRoDtg7sP*jd#O82V|f9cQn+vFBOSvuMsDgQ6Ndj6 zJ|^;`wCYh8Vo4=jDKp?>Dv-t($ca$H({Ri$8_GbM*9>@O3c(sNgTx=gal1aPJ3mAh zqC9r)E2}U5FamKLjWpzz67RHon$tKC*{n8jWM11|jpqJ3 zz5L!278nIyr=}*SKOWpX2Y+$T496c44IRgOgh;%g;{eQZQt~llL^l_Dv8Q`DEahvc z@SFmW$h39C3@$CNNw_u%HzY|q7?T^|aw1!!4wnM@m~MQrokhmQ&D+${%oy{i7id+^%*ntC zMN5B_8m0T;d_py?0O9M-%{g~3z{KCeUsb~OJ6>i{W*fuWhJLjW6Y9*>Lf+9-9cyaw zFC_g5a8zB{9yYuwW&Qq7hT|+AbUyI`_%QjtD3Z0Joj`m{aRj6K+aw_*G`2dPRIG1c z^REoDLc<;&+e;d9@3PW=sP)Kw6V8oqDHDAHx9fYf`if7`#RJ!Uq#8?@u|eUx5vX@b zIm^bS3E&9gnh-zJWC6(e+te>W5K|I?XUJNy%VA^8h67jDj6L_J;Na)>(KkFh)yVjm zcxI#0n>+mxz*y7cHEl7gkQ>w}o!$6bk17fSO9vn0n?HbX0=rRrRq7x{HGVH%t(wWl z9(ih`jio9=?N)F!m~XW&p<(|h#N9bqTa(sZ+~;-##$t*`!CC%!YfLkpa6u$>bKbM3 z8^i(%!S#hKrhD-|5sTW##)E>D>R(qk`D;ce;#zx7hQ~m@$1hf`0qVpIn)#Co@z?2_|>!!CV zJFamZlk6%kptV)I&n;YhmNp19VLCI|s`2<}^2>VySKR>2pNcXjKu5{Vn#F!+ruyq< zSR(Srw*1Y4D40HIKv`;|5~PI=;;RuL-U$?&sP}~7m`q4cjVyKGDdi(!NLoW`J<7*v z0OuCNwHe3JzN1nT$&)_?nz~~Un=JkPQ}q5?_{tn zo>A0H_(vNL1DkmkaNc z9;rwBg;q8BXrTmNodh4pSW+Q#< z%S}A@z*X4DbmWng_N<;y^k&^!bi{z-daT%=b|9fOUFo2P!+y_0V~yTUf59d~qAg}8 zYxGt}_fE&6k8OjR43i_l*rho8&lycVZtLvarSconXPM~hVVDyWznvr#e&CJZz++OI zx1w#`Swn&&pTSxp>iA))5BE$bv~j^$YDGvoJyVkRfwSh*rCFAk=c&KD*I22G-*XS} zs?Uht$%hAwptE(5;js)V4(#8Oml3NxktCN~RX5}eVG{QX1i9(T^D^Pw&K|@2N28hR z)eE!8Y6;k!I`GS%gdwX3V9q$i{rIPG3gyN=uE&HnIXD$SWw9qDfP7M2sNqX8OnvVD~0Df zitCdsgAW;A;ZMQfp-ZOe#q0TpGj!Ny=r^QL57L@O(Q@njS5B0_=}c!5&%u5h^c8ZR zvW>N;{p=5#tqTMIjuwo0odW z(~J+z54>^}$fa$>^4TMMXJlP-@O4vmH%HPv*lu1Rj9UCqk#byAioFR5yG@1Rc@qQH z)qLRm@RQNY5jIkjDh#SD=*fVrD{py4%bNs2->K1%zX9Ep*40aWjSc2%K4h;1uSW9h zVWd!-w<#93v5V*R%vm+1JfAqDx4vCM$+K zEwtFaOf^pk*W$o<`M>=c3?M>m#H7q`dYdi-Ae081DK=XZPip&4Ctu&a#J;XPEE-k1 z_^%pRG_Q$;mOq>tt4}+xwIfPqgs)m7*|^(mlOt3K!m=JyyW;RwQb@zLlb@4oEUG!w z^_aM!$rvRB)p(giWN!~BzQdKlOKRmEqracMK%77`G`v>W=dE(7FlGunD8-L64i~1M z7$_FaFIr;SOlI^cr;-$8NBST6jGOy>O!YYGJ#j1nT~~@~K_h(Ef@%tIF<>~QUR4}V z+q&kI{X=p3Qrb4ieV(>gBtDlls73i!@80@X^$n2>{a zFZCp;DVFW7xxC6%(qmPFGB#~6or^t`B9o#Cl~U%vv%#FCqd`Fenl(z&`fvy;=xq1B zEYZ``k?_?d7vOaAWsSSWE`QS+_TH%Rh|8hQdwi-fVHlS1m)T;I^Y9OX+N@SZN}#mF zRs9T`4I)-T`p~*FR0gYXNH{UN=hUowN9fkNd&0q4ZTVnewCMc*?r4F{JPpgRCUK9c z=fqD!;W_&us1P6pG34saBPyBDICRD;=(umb^4Nu{&qb(7xXt^jt#(N5)xfle!B^+6 zadoK;`f~h_kg>u^c>hNeEtq-HLnsV~U<34OG@DH5ap@q#AWEk%?4cyNQ$1gCehZ|0 za@^$}$Xeg4)9@cdnpSJ!ktebh#cr%4BVY_?VCj*uy#8DZFVwMHpc+Yr$cyn~gJk*k zR`0={;!Uc@*=Il=Zc!-7QlDy>VjL<@SQznTmoHkkRxsv~81=ZxmzMQ;z49kq zg%3b}1eSF3Pe}wL=&%T*5iX{1P$=W2N7ke8@|760N#rf~PAYUEcn^M>2z@z81)YzZ6D#Dg(OSIoh=4)1{+CuRKPV5?(aXEVUsw`^b9PmtbDwC zeVFUYabsE7J5qH}Ssyv3ti}13m(nSi#32uLLVoVRSD%`T@PI_Qc9?hZ$|>kM>A zNj3V`o*3Y(oA%1&lpA~me50xK24 zGUe<5lGIdyv`m!MU|Q}#l}IG~ONFnxg0=Z;$(Xpia%Fr2frTvv?}3s7fS%;=&e_1( zG#L54dg7VtlJK?}TL?5Ev$5fPz$@pM&$3oNljqeJvLGy;G$nU0eVtFLO)=xTpm96k z3mZD_Wb)_E7!tNpVykdUqA4x^V6S##2; zjY{xb5||M~N6;cmcf+P_VAIh^#giTPdMvxUAs;2cTHlg3R=ZH^QDjd8V$SgFz>9_CsjXLsg_5UtCVA zf}I6O6{qCrYg+CluoU6-fwyZLIs)O9;82MX%`@uF@=)usfd{mMIlLl$j$ZTsuP~K zgkX@Lito`3Me0}lMk*LzxjeZbvSg!==xJtk?tV#Yfg-(p2#EB^o zM!z7?q!7NzR>DVYSvomk#GUx`-%TAbhh+I-6TVrQCLKBQ?~qL=IEHgE*Rd?xNJ8LBu0{TtM^@ zSFQh}@}N7O&An$j?6NNymxxNMqJnSQOerp*7BZml0I|u1#BV7HY^YwFefA#oK^PD49&ad1i9|T2M8#7L4Se|lfZAm z%ksXYcoa{6THqhBQ`h&;pH2angR4SQBa`*i#xZU$&_qV?t{ffM(cC_-vj%gRxEKR5jhvI&G|$8e(dTne(dDOQ3EIWkJ}jBMmv2uCyxfOvTli)`)U`ZlD*Glp(Q%z$ zz{6o@rNiEIU!bCkCm!9 z4CAxx6ypeh#c0-K^O z;r}_(g$s0)hjTJ7hl!706bb*0vJ|PJVO{z%%nj7opT)JfiBh=aDv#1$TFKNYmAV&! z-K+-APj`y*{4&5yX$K^&qYve1SU}9RUioN+;%;wiQvXgo0KvB}vMKt)QnTZz_*&`e zR?R9Zea`a<@vX^S{`0LEr||9_#76yuWz&OnfbBRPy!X^^i_G?Eaa|b|cj*(lwMBhU zZ=Pq1lz8j%$xkXH+dM3HJb)$GglB`s?^?2X$!mI2LcNd&u%1R)RM0I&b4Eus=HN#t zC~7r4<$Dx6z*H`dR1=1V=c*kC$_WBJ# zKO8M>QUk~W#6t}e9lq8XWdP4vw#M8!)ld@yTr1r_rA#-m906l?r89Un)&v+}x z4W6STm6(;{aT<)ltEG8i6A1l7>%`B9*SAr8`7XoUAZxgOWoKRpc13!Km7W~hB)I_#zsr^$gp2xsC_w}`ZB^QM|;ju~Gn>tRh z8UDr`HYT^ePzb>q?UpjM2%?3!UR=aeGnNWhSOHxu?2PC~i^t|Xs>66z9-wf0ChO6C z7wr~aAaP7@Tc89p%PvYOpSh%E$|b?{5(U)&IrqeOgKPvq2a|D(F6_F6&uUFd)o~XE z*>+?)DtFJF2fpNOJ0Tc#$+H1gEgRL$1)_LDq zeipmWlJpVQ2@?avk&ap%jXFcp>u`r#Eg=N*N8`;FJeH(V^q#k;IqZoi_R!AEmq2}U zlMCz;>`bY0ee4R-$A-toAN@-k>16w*dM#tg7=NfAU{8!yA0L|JJ?~!HW_K^Yu_4=Y z`9mqhbwE$at+{aB5ix3^o>#LpoRA;;LSysCVPL#HfmM5LiO>EW_0p25Yp~MdVp(H9 z&Wt{`U5CyFFcf$QTk1IiA`Pf&`8_|nyF!ER_(Ap+unwaSoOBMRi(j20<5|M-QYdPN4*2gheOxC}<2_&vK%8UCHS3pa2 zgcimc<&qsV8UP&$iDYZvDB8nZ-T)khb=!g>mmwg1b!)#{#CE4x0xdj@>24#oDSxIq zZS^=$SvG7mKI-EWOIR3hfI|lX{&UauL#r4*aP!HjWo!mfTBQW?1(-Hv&0hS8x$epv z9pRoglkV#|Z`Agd2 z*yt6s<#d*QU$(z~LU>LTa|m=nsJ$1ZE_qRVVc0ki3W|JxLJIoql9v*Th9aiB4o?D; zdi?viuF&6^!_^=eYdIm(olTsWSxeFeyUNd}PtD!Oy008y1l%_VOe_609BIO_l%tN! zD6ou8lNR>FGFcx}Cu>iR^$}PFZZ3rbWdkGiUnea|xF9S~~i_1x)vB7$@c2o$Ec zt&H7Pqw+!1VRiKsRDwubyIabyAsbD3tpFk^6j^GRiN9Um$Ep^`YadCFKJ(`1xMQN} zwv3ijVW7x+Z8n4A0#K@vIsCUaTRuuKT~7VPFZrblw|Tf1L-x?bv=L(qhQmq#;9YmVT zzmMLRlk)_y6WaHq>KByD_S1|_jCQMog)!K0fliE_CUDqW(#`Pz{^YH z&ejioJ^|VXc0Hk?^}`Lrx@NpDx<`)Qi(y50YS@g=|CUQ41tt+Z-i2|gTsA(tc5G_F ztK}M1@kdRE^~jtJ*D=yV2?yJJ4<;{XPl!veAcn#sNZj%SWm!;yi)qXlCo}%^tdOng zs||3Na!5^mLXXJE$lygg9{+O6hTEt>jX{HSAZ z;@I(+Mi4yeXh(x#f;Zt8;92j1xRlY98%6R@;k0j40RU=YD^ZT2jv{mun+P&u4N(s0 z$2oGMwaA2;lL6D?l58xR%+#{kc!KjvLXM^af?Ofa z`yO}iv{;5Zb#H1qh^F}%>e?10_<6{(lXeVPp+^b8`_!A-nhK&iBD+nN4a(yDq63@J z;8eki3UW0pI<@|K*SP^vRSH1DB={Xmy?m$cCk7ky>v1M8D9Ub%40X?0Rsvx0VkMop~zOmc4l;AB5h|6@OXjA$^{s*ukA zHFt3kbZ-M8-0@slsgN;C%v~9NToy7! zPkJ7Zf~8s~OM;P%JXt)MB(U+aGh#*E=PwS~sc8`e)^MEfd_YV@#VKt&1iRi20+TtA#}=sUc5-5%RHN?z&756L=PER??@B zZ2`;xS3s!0G^2fGBjC9uOrwba%r=jsq5mJEXykv8SJ63^tN*K2PhD?RpNXZcV*+QV?h7iSO(CoOnS(!q+5dr8lqXjvp{lZs*&gO49C{DMqQ(Id>#Nb1o#3LCrfp(d2z;3TInd zR&nW>=AhN~7jeo@e6Fo*ck;$hZccdZfKZ)pSTnQ+K-Tgkd z2&A9m)Uv?b9JMyw7(fs^l5nA^O;%)tS1{=Wh3c?yY#XcD>%184j&STW=6|63G@ZlB zW}3jS(4#J>R`X*Xusw4{r`>Ay$h#ZjA?mQS#I5PI+yrHQzxDi$#_0e>esFCDw7B)0nnbIotjf_f2x9_>DD{;X);F({ >YQs_f~8T@X*k zID9WJts#4Ta?JHIv2l=ufMbx{ugmlRJQD~M+UQG2rK%!Sji1d{-YI#MuoW}2a6)0> zc|TRv&>AcUNWqeWpzEVXZP*;Q>&G`tg}93o>B5H+W92F3qo^sGdaFh=Zvq4u?}p<1 zV$0NcF9Ap}z~mON-}NojNgjtNNarN>1rOp9iu;CVNieQ8jwmp!Dpa$@V7Yb8deg|f zVvx2Ntf^6{iQq?7?0H4aj;g+IgF@Jm0<_^lv36+bQB=f~YSM9qIJV9EU<%2HL$D&D zIYVk|{~ey9cm4qpR@e5j61jijQ^#M?9ds%Thqa{S$&k>*SVgIQ*5!1l6u9q57REQl z2WJwV%*y?eVyqDqc2nEfWPyJSx)=suNFB`jzdP;xhbYqZ+_b-oKCUECzUcpkZwJ*QsP~aE8%(QB#POxc5M^Qg2-7#pifcP1hCx`tCZj_1d&(25xNSnmJxzPxK;{XVY_V@7%`rl zNQ9uq{G%>&0j45 z1Wh)TGNYqsHknftwhI(r60O}v6O^(>l&5o8vRwGSw0@BhlS|VtOBQxktl<*4V@G<( zWZAqzkqKgEfnhvE=J7?60WP7)G_mH00upTvxqztDqwu+esD*k9a_sd}dUsM|E3F6z zl<|kGlREuL#**vch>B$6#tVuBJuJHMjMcza`}zHItP)iZcogREIOdbRSupv-baC{p-wJD6@2!0Iit+k|WH<;Z%jb}#e`^^zr`k8mG zsnt`#9Jk-^!Xzn{WW<1F8C#ZDdW1*)ItgY@!{^y&u$cpG9UogKd$eALFw7Pcw)0rc zgk?0TTGF6TC4e%-g?%aMbs7i@G0t!0Xl?+HxPm8~^T9X)BbID{hN>S@)e2M=XvG5n z%0x`6$^F)VBWl!&T0SGLZ3@%J>Ey>qQ}ipkD?5rljRJn_3;O zb+*=$eC>bxWlS)5M)}OC`4)YZz83duWuuUd->%I)mrHXPIn0wN4{3aT9NY(s3w_K( z66VB9nN)9ccTQzz<=yL%N&V0#PjY5uV08_y93N zh>#9fE#WKu0!GQJy{|)&@-;3Fg;}N@hSXY)q21Jv1&KSvwisPgcTt50aon3bJPEl2 zetJM9d#q;fe`Q$Ov7P@u97{i|r^a`Wo;`WytYq%vCN8`W)`>_c9K4Vf_f7=uI=LNApO1Emos80w&3(cW>Jv~8_ ztG0m;vk2@HmTPSI|H@j4^0mP!Hs(osCeO5Q80)l|tLPiQn1Yi#C~`YlO~1&&kdR%2 z@&*aG%PXtNol20`@9_b7uprk1WqKsNGHCQGQ(i1T_E8tP4xMV{h1!Nd>1jq_SPFiX z$(FP4U14ER%_@xj=D>ksU&@4>7Y&aczem87hOU#65j#uvUYnYn2{8o$a};CzIAt}R z9CQX0TirWC&8>uZUXiuAnm!n74r#SXtL&iLSLPidIFpo6xQn}n=1SqcjJ8<_P5cDm z1HKB#2;&|e_B*=a&uM8O;-RLgITg$)uaS=7O;f1F>h7&+labEos6_kmb}IDnpNKqf zg?8(+-&NPunt)fxlHR_8_gQ8R?;9Fi+*9Q_oR=$VO6B%-i^vhyBfm-% z{Dy2YjPR3Mgbei+om5L-WvjzSt12iDzj}sW6B9b)v;Cf0+-8FKSuNudUiK>E#sr%) zO7f_uQ0aE{r(QYJ$r3^T#Ti*H(&gM3(L=R3xNfuEiqWX~`eybkU*MXk>3rTUAGlko zgUy&BMD9qT2pU!aS}-lPO8^9s6cl??FXj%KIC11D`VMgLNnwfMb-SH5Lv`@pt-K;+6a9 zWENRUAPamC>C2OEI{5A z*@OJj-ror_sq|-bXv9o&j}qDTfSC@ElkGQBtC#CvBzIoq zy{S7`p9m8U@y*PDln01@ zN5Y_vyv~GT?V27l7*n`iDLb;I)j($pw6dqrGc<^{vl6XIn!`0h>J{thsf*so7E0^+ z3vEs*d0ivN9zbw=E^xi4SNR^OuKM~)?M&p_2$W4bzUtx?0Smc9WU&BSmj-lBydqh{ z$y>X;!79S1n8TR&f|SH}*RXUsjgl9mL6>_Qv=~>w>PvD#u<3*lzQ`HbkeA_=!s)AE z-w@a}_dl16^$dF3qrXyYk!A zWY2ZP(C$Dg(M|4IY_?q@cf6QQLqeQox9Hm|Olvjh^mwyGBc)RD9`6^}_lA$Ga^zZ^ zvzaRTKX9s6Yj8nOG7dwUUHao;T3Gdifd;QcSVtv_s+*7g9bbTH*&;U?#Ncp}0yr~1 znYTqeuX$3LA6R7Q1n_~t6kXv*-(#`E09V3H5Rnj!9mKg03fl29uId=aus8!5HX!T0 zpQh1AJ=rUFsf+nEgcxpe5V_w&C?b)tyJ*IWQefEJi9g!`Y_8`Y8;MvdCwtzA8F)M> ze{q2gwDx-w_2ktGAeS|jjI;Q-$mHC{*lGx36C@#K?L8%ijI9%F*Fg{nrA%4GF(`T2 z%|Dj#{oHBP)?g#nWIIL8_Tt#Rma_BpwLFr4XkvwkV`qabpCSaBO239;PxP0iWO*g1 zs6^TWnYr#;e@UjaA$^E8JVftC1YbOOO{!5B56gygo%)Mw zZXaguPGcZV#Rregq5(0Zwi3gcudQy?Z&6wV2*H@MhABb4caOCTy=g^X7_0AMb}Zi~ zIc^v@{K=Bz)4wbE=#kRS>F&YAx4yx0`)_(gjnaF_Dg?P>c(3>+hLBkVJWZYjhX-cQ zDjoLe3Lt{(!zfG%Vq%JdUmZ3ZWBh3J=mm|JZdQe{xY!>JE?i=Sf{gqDq-In-PW;y0 z)|Q&E^E zRcL1fGDd<~;wvyQq?ZsNkn$iTu@#TN&C}+OTNw0PGSJXyTvM0iq|5uP(o_`OgT$k; z)48)_=iTOx>vkdb4V9?G>SL*G@}4X)omzo%8XjgBLYe&eH|H`~+JcXIz70}g5G{(I z1n;uvMog-*FF#nzc(b3Py;6X!N2-p)VVk+;EeqlZ)*7w|P$7w;Z`LNb!&ixxBG|_% z^a%XVxLq>OG4k~RM7C8RglrY$!>d`7sx=lUqkjSd1pcPGk|cOM?=OG^|0kzN(ZPlN&F zD7N`o2q>`u80s0OO=+K=Fn+Be?-W?ej^X@~?;Hq>E--*&t!EOj2XK`>wiDTBv!~dD zIyeC2Gi8q+qu(R*;_S(r}}TFMen8;`+a>64Br@g#K64K94dSSvTwZIw%|d{X0cZI^cu!a zIk@IQKc{c|o$-U6f-(590Mz|I=}09dDPX(iluS;uPeI~NpUklBQXvMl67SzsN(tl7 zfj^i2#LCe>W3hnwxX&urV{PKaasholgbEj1_Yt~4H>XqN%SZdx&+LNln+9Z{*$v9=s}p(u93N<- zKeK8+dkxdOg+GLYUCKC=rQfy+b{Dh8nwg2aiE7Cil`mV!tz}6o4Pr1TX&e z0Pu`|LS*`=SrDW>5vyY~ zTc%jKai7zyhYr~4Q+@4R?z^~!YA>_%A-n=`}u8v$rRQYGM z&A;v;!n(|G(uJ^Q7ZE(*Z~%BD{+=8m5RrKttnm#wvl=xHlFyLrObCisHwjT$unR#; z!272(^PVU0OUWjpqS`~~@B2U~he@{L(IXm_%dg7KV7#YVwT@;gW4CmbzDj{c!175D zilL=C&<7SQ4{htEl{U&yo0oe;n>(N=5ijEt$RbL;t|X-N%KOB(euZ@lZVL>@gNL5) zlsz@yffe%sz#_c<0myCcaazUk;9*Vhrcqp?URuH9m`&d{A;9&VjM`jM`|{NNFwp56hYi+r8FeIJWowyi5X8Al;;hZ9%MpJO za1NPixMGXFKbBr7R?kg+f!D9vSiJgWHoB29zginJ;RfPu5|-1WlQ`j$_$VY$R86!6 zs5aEpNiwRT@o_yegS9dO9#Z@UV&6YM%4R2DHELw`9ZX;`0$ms*D5Sk)c}1`t?}{JU zvm`WAQNXBXLDGf)H(J0V5SwGpbnh;QT(|61%Imi@nTPt&HtpQ|yGp2V6Sl@O-004E z;4j3!Yj_wG7)KdGvzag`k(DGoSXj__gs*cetKBgq@l08zOGp}{q7vTO(N|aGsNrv> zP&lff_Jm4$^kz-eF(WPhryTLC0pf7hwAF_So;{p3v)#6t-Ap&k%7T_9yOMt6NnT^1 zxWgujBBl(#_Vz|1CbfgF)pRi5A`!c8lBktT8}W`|apdG2Ap#&>dk`2*XB5#>b-jpF z>X6)t^ArGyS`N?3#(rwu5N*wF7Fa>A$vX9k3)yLzzp5<-hOG6Jh`uG8+r~YsyNe*h z#`O0SoviXlenOZSSEEBfILTmY`faKR`Sk%ou5T${ysZFvJ0x(r12^$1pdEy;M$cPm z=nxp>9`1#*hG)72T61rTil63AB1H6zuH0#3ZciM9ms4w%g6V$8!>IQ>qN-YmpZP!j z&=jQ*9}wI4a_MuWyJLt!PLaMveUXHHg!wc$WQ|@gNLg9~VZ==iM zEK2(uh_*xpm;r^ww7xEwgj#aZGuq+cdsI>%Zr{C4B7@_B#`zhA@nwRg(J#FINJ7Dl z1*)VK<^5l`0)1OEdY9PKYkN@0JZ!AeR9B)F1!(i8V0v+X*0H&bc}ywp>SuRBJN&$M z&B^A%^RBzxMH6GUXb{inel#6D5n(9zT#778m&j#&^ZeE9keYm$NBVuNw=7b|(HJMh ziiXPVQQJC-u%VQyI{Il`-Cdt`+w30K zWv|pui?L(6EqzH3nkm+^?+x41718nsdjB(WA9?~)q1i0ER>Kh@4`7Et{y}_14pST~ z@v=TUcujQ=ARz10uT8rgyUe?q8*fyOanL*b8Mw~4O*M5ikUIoH0GuiPJenxS!o$2Q zyl(V1%lMkmcMVF+z0q8Db~oX}BsaE1yOy9BD+;TC7ly57U7z>VI$2wiB%+qz58z+E zn`DKWO)$08h@2-Nu9gfnoXT{#Y${kT%-Ka2RJX#%P`+GK zU-XmCh$LCR+rLVS38B^|N2O}@VW&lXh-1E>-i?}u{_VeCJJQQU@$Gtnd5HccGy|C| zw`3kj(L~+J(a|A@qCJcIEvhL++@+3>4vMBHjxEpff1r`)fLDC!SC;88Hn*}M43GxkD z2qwkLsY~NDKcNH8kw7!fdtr+jrFG1jB=LK@QDIv-zs4&u!D2kTO%$FhRhsS>ENr*1 zs`_NaumR|RoOA*}#wsSb!%hcpsBI*pvet4RcMtaQmLGHfSq9jfSJrPwiq3LQz}r)Z zYz$61yM^fKEKH0RTv?a4Ip-O5s8zoccRlDj$GVOajF(;7<1m^@Iws%$C76_kBP$(Q zyt;w(s+ZZ=asgQAV?D^bV=0;sx^E#AsrJjMK@Oq*4p5K@B9Ar7RmpCqD;~H~^U0ZH zHP%gaVNeNla}0&y%R#X{nOuVeDxfwQmGR*z76IqEW#}0Xa}W-pD~_}G$$)|6xa+`& zp7&z9OKi}loC{(x6xBz3EQ1?KrXxVi82-k0Zi(t@I77nG%tBAt9PHXW!X>W#_?~l- z`czuBRYbxh6f%}$z$H7Gea`$H2zyq^^t3gxpS_%yVRtng~!>dDlPsAl?ZHf9n|pE7Yir$s9lGNvD`-*+|_` zNA!&o?&DdDmip#?Ymq@?)afdf;PnHh7DDRqR?zsvL5S0N@@dzwhHbd_{q1fiw#b8D zuyUW?_rMaP0_W*%hj35Jp_BAIf%I$da85=(JqR~`{R{Zr$yU!5#Y5lklht%|1I&b> z!W4%xSODQxuO7t>Pt|q4=N=VDGFfD`5=Ur%QUOs}P~hDT2-D1i?uAOtHd0y`wLFis zx@HJ0UM(kH`{zYE8tv`Hf10Kvr>U)~z@Vhddiz5O8$J$JQ1Zz>U4K|RMA}8B1zLLw zoo28WnPMZmV2iH{fri#PTusJRoPCH$#&m=NhzepkR-_ko)|W(dmd{%*xaT0|Rct9s zg!_Xhmt(wcu{HlCp3i>tMidrDp;Yr@+7E>0sgl?#$6S)PFs>XjsD*n;A{iSh>s|q6 z)I5oZ;KC_9y-0=AlerLymm$B50*TGFtYKui!qGat5Z_DHauHBQBsN&9bFi>#a8gE* z3sF5(gK%{OL9FmHP{4Smzv~ZTPtu7%PisSFldX<~K=46eMBMxHKTCYva48?E^uSvgk*O7D2j0ydTzUqQrU2;`B zdUo8&C>tY|U*6iWO00gTm@vmZuaZFO@SzrxFH`@1r&8n@jW>1;yqHmo5FP8Ge9iV| z1v&{o?y=l>x?va35 z=w9au4s8aoVJ~tQ!Q{?AF>+UBi;o$oW^Pv?e@rA|ou$C})8`e@&Escy1g-DmV*PAn zY~0HJ=2bRfRMgy&Rg-**4D&r9TvAVVNe)J}lg8)VlIWZ&cj$AFllhV;+zvXYM*5Nq z?slD$FcA-uTtr{lEB*vxCsw!{=lh`~l-JoVGfUV-N@#!?087_z&djs3lx>JJ6TZrjCcwhd+Y4l{y-5M;OZJR zxhKHM`lQ>(VU`A2jIq_@TX!9ruKh(j!Mb=%(Q*uzLp(=>4%6q(MgLpdt}f-tJW6)9 z%ZyPWla$A+sz9CYx;SLYOsIK9$P5Bh6|dS$#5`n%jX&i=?qS)6Vw)l={9IBK2GyGH zG733t$*+-`8`^uwrmbj;2EY}i^Qh2WtECtJKhsODclI>xUtnB+v~ zZC3l+&YC&IDvto^O7hHHuMR*=uqqjs<2&Fjm5o_l>AzZs-g$9#w4382yagF7_pD!gi~zEK|sgJPrS zv4o|cuwS)ajw$=z7xc+vi?-pOxWtPs#X)?_9Tq0P-(W>viPl&tG;a?N>!n{qAipCR z%si^pR&t_jI}BAl0BV*Dl2Kg+G(%F`V-(DBRKkJIEhRt4kkN@8&xrb*rSx^gIA5!g zh9_2*uHgbke(+_XUpLcUEukeowVA__(=yDs!a!3~i<#{A!2P7fp`3k-;}bFa^?}*G z)FQy|ido^3+9?vY%BXq9>RRtabWjZZ&3^q{9;brvMEKqmPvALV{CP4ZuH%z4F@c4v z6XQN?Tpc10bQHyL>P|sR%Q-jKVE#g1O8Y}~eWVIIMXt{z>2IN^Q{U-b_k3V)&i=}? zh8$V-szW6VrulfV-9 zpL0b|)wjMPP=|&qkvW1Sh{aIJhxic~_-zOI4sml42GrZ!L21ylmbT3lP_DVBHf9YhdCrxq1q7s zM+n3Q#N)W`8_R(TSVv>gG#MMT%K8pv1Or{85IRD>uRZ7o^Su|=45L2OvxDP&)@u0| zQLY2jTHAHUEf14&N=W2ajGT7Ri@E(@cD9t8UF9V@&}(n53I&dRQbadu5(S&f2N7<$XIkU%5t4U(;WU@^eOW9uNp_lGb|rjt zwZra5q;%t@Sp^{BEs=A^UcWN^Ll^4bsS4ST_gV-|`0plXX}kY_)riB+x#3#XyU-L3 zqG#zlA2_Njmj2nCzP2H*g(caV$AX7J7t0F=5{Yij8L2Kd_j3rAa@ukhd=SBOJd5NI zKo(g%NqHoCLD1F7GtM?H^3Y(~(j3^Svr2X=%}pAhB=e4uL;>mP64%!$Z^?3>gxx={ z*G4}`89z_kxG(>vN9av^L(z;4Oq@KSI-&x9Y1|nJmJ<>FhD&>a-}Mu3^mj6lW<#Yz zHsh3(c~xB%^F2R_t2@QYve>bleKXpJ>}hQkQKn1JJ1rYT(C~}@x?wwu(Y>7$`4Y@168m6sKmn#tTSP;0j?UYo|k7v zw>5ofAAE-ZfEx?a5?&zYX{^4`)=jj?v#IdL9;0%z5@&K{z0!&4=-Tz*GG2)??*FZ_ z>lgcl)l{;LCV3|wrPQ$h6jjyaqj~!wFuItBH*xrZJvqam=HwFU+e;thPv+5`z|9lI z{@mh9CCxx~!P-CRK`UfeA1?EXbwKFD{q$>84S;pv*=R_|yr_?d}V6?EMo{5OyeQ+xA+9=4xGTtVY- z6n0Cvd%Gb9-KvlvVfz^qTBvTQ3<00@UA#yB5SEr*Zjl71xwRl^PEUKOy=AGMhy-)W;KT=UV=7W9e( zJ&~1)1rS-xxPV0b7Va?V>I)lMHq&y>a=VsT#dYaM;W0vr(0yhi-1eb8uY1p++aZ&? zU#w~llju-~m52^+yLoy4FuV`~(r}<_1VJcz1IUd%o{UENHHQ|@VH?S`d{2`C<<;Tm zK~(xYR`aSBc%*EqM^8y2B89+LM@M&>S86gsn9*ik|ywM-S($ZnkRwUw?Vy)4}S~~ zbD*Y+z9AN2dxWNrUUgy}F@wzSG0(X{Ie*cn3ebZeD}Pr4tB zpCNodl#PZ?L>a_^KmM{BF*F(gwxk@jY^M}Xm$MX@x`jC+)7aZ>sSQ!SMjTR(tI^EI zwgO~wfj7n07jlnyIuTOk*d@x&rD}6H%mMimJSisvc3=s2&GlPpi|4ZOC{>v01CV5% z5Vq*+L+KFf=4(mdC~JbmhFn6eR7Yjr^RrNDQ!e0{387Z@C7a#frN;+a6?~)4MMBB1 z=QR1J+RTv~lx_QzwaTU z*VoE37$nqT-%!6;Foc^V_-16l-Jvr0T^j!tL~i*sL89~}4a41FW}&4DDMq%BfhXA6 zqIHU9HEr|3=r=1~-vSzQ5Abv)cPtmOX@l$X>n2Gw)F-XDJntw#;4Rl=7G%BKQYhVH zLj_`7#EFVvj+X>MzP(|G?XozIkQ2pOR?VlYT%5{#kVXfZeyv2e>Y|hgE*NoTa&M$I ziwB*KI;K&eB+1qGjz7zz*9A!a_TY}NZjL%UPQZA{~C zGD)CKNpNqFbdUAQ_$g>hxGcI)LY>FfU#WKE9}fILmyN!LC4>IfTKXKKqcMw1x|Jq{ z=YKI)*ZtEJAdip@&X~_$pHiP!V@5FuY&z?U9J-6z3vG%sM_6YwD&J$Nl23%qDvt17 zrZqk#CdlqjV!buq*8>0dh0;#?OX#>E9`CsD*&)LBW0>xeB+6fJ{NQM_K2>3eoTYVe zdmz#~?H^CZ-KF5slk{#=&^_~YS?m?cp~+neO!9kXDF-Isvq^JZ016~}D!nCu?S+N( z*$IW3Qf51wc=oh61Q^04%1i zOr%qj0Af7{jkp`qFib1~3H*mUE+CzHPRmJ#-E0-Gn3#3e1kC^vj1MCaD3jc+(O09aZD3Us#n(w%d2}q)ad5m4&`*YFq&49DfkxEjqV@G zrG$mvh7Df6WGSM889k*a1w=~d5x6_+wrEfEiWuul1YC9l5H9mX!g)=tK*3g|uh8$Z zM%ZD$%Dk8irF+{=_JCD|hHRqQv~QOZ@bK9w$fauO@rJq`&LI6c-#5u$idftA8!(X< z{m+b#<4_T{YR(1fcj9rzWJW+(nGW+2jYVVcY@qOQ#8Aq*3Ia=^%y|6}9CVqBmR_-) zH>t&U->~Fo3=g-Ps1+(o>u}+saCazkj<0z4tWq%w80So@mC%m6gZ?j=U!7_6o|nk|1- zbL!Fuc>crW^pDo++CNFk^gLCw@6>j!njqRxd8ve_o+rzCO%eR$p~QCg(i)~%9-3ONrlVa(gFC!ouVj4ih8~et zoK1!n+^SK?vs$Bv097$5a$ht3!fo!&YiCW`X(qm$M<9-yTkp#OgmV^0AkY;|o0p9#%6Tn$sJ9_xlk~!$ z8jy$lzr_nMA5He>|6evr+w0U;$aLS0`~WAWN45s+qXR{w1mUKtH~_%9n&SymeLRb! zqW+sC?bRIbE4hvE?KwI}l?n8rawVMt_s57*9Pa+Xi&R_*Bwljledf5RjS?o850FRt zxg{&BARGoKYz9W7o$n3j{3_9U%zsKSl7}i@X8+TE?|ugKFjnqjf7F#G>Mq*)ViukD zWmd8`P{LzWu=A_BM#AISJ?+xZp^n$S~;k@D{Bwaw3 z>fkOA17;XV#%sBOqy}deI=lYgED!(Xo3cJ%&PTF)juORFbubi~>(6fSTpyndBi%(t z$7(dM{$aGk>0NrX?mbO$idShW%&?Y{GeMJB>)}CR-h>r{+}J6FS$uv%>}h5SFb;Za z`*^lcyrmMDfgM)%S*@pOBX%)2jOTwfi|3J$HWl{(oVw(BZ0v|*pbjyjV)>+3Llq%}{zJ+A?ylfmA5Z*`UpalUDE&?xLDBTZ{SlBHg6ZBjf7 z23HhASUMA<4!jtN2KGXO}|0Eq!MnH6L!rhI0GzX~+yJ^M2jjKyeg!9e>bM&S>ZF$|;Z^yA0S(6&8W zB{;Fo7Xx6;rXT)Uz7qtZ7W~-SEloE6YfW;^^s5%2J#H@jFiWL2_gtFNc{`qWH9W|FM$3G}$|3%F+chXknm$I&HD2$`J=33p^zXV@Ei2q-+{ggwTP-m@?> z#YN`iU-kb?>+(W@xO0=%jp1V+&On}NZ}Yg;aVO(Xcl?hR@e1mgyolOpJ29(7KO(UG zjRr?cG-RxhTVQVbn)gG;=YKG!;X->DJ@5oQXI2pvIy zG;{ayC~jydi&T@BxtWt6Q{S+Fu2w5!&@P>Coi+j8ULf`)P+ZjNx*%Um*k)7U<>sT0 zl*R1`#KX7Ruev`o&6ZJ7<+GpQiScj7&~8yELvJq?&gooI6rBqIFuU(K>~gFQ(Qv15 zFu8?2wv*O}(Rc$alY#yLIuD8TPdc3f6$sc<$-iGS2Kad5<);>i)WKQer_F91UXOq3 zF(`m*L+yIUD&{2GXf$ji49$*f*1s&I!1a~krdi^3jWYs=5EfF(4&AOtE zc4^9gYyVhYwt-|EreQGn2c1w-(5pW4(VsLgy@TY%Z`}Q^I3p_YZ%=a1o0(7PSp!S* zzRAfNx!>?@@Of)Mq<_1Pz5Ba=&)=ey&lcTC^W#S3KGV5EP3?xFqSUzLo=yZh(TQWb z>AL<`N9tMN4&f{t5S%#@b)R2CMY3$?TPxey;Op2t6wCZci_9qHhZz55? zTKEn0IqK(S?o_5Z;X2K zzGV;9wY8HW#2pe>I>@a<*#k@RoH+Q`F~j2Mchw+mLa)qO_u6g*hp>67CN@ChE0zEb z?LvZ zB~!~t`1WP3aT4*=y9IQlg-a>r4xl{10K-t!YH?omT!|Kw3dR_+Fg8ptpRshc-<%iM zlpmN>o{)uEh7b+`Qe$e1%VW}iJQydXRui~{iO?E3#atGA6=u?enWIao;%fQ~fTH*Y zOC${ym7K_FAsOz1+ix^f^_1tHPm}t4V+nuP6Sp|Aj&^^(J069hP$6f0NsM&MD+mS4 z#wjDw5DC) zD^SV)nZU+T!)vn zW2f-$T3(r1xN4BrNx~_CYU&zo7vG*%$d1tTq?d08-{O$+<ldehs-RTj zY>Ir&jpQ*dbJE~T6JwaV5X)S^)8--p&La{;_)SO}-e?C&L~= zO(0G*H38^I-+5nvDZ8&2Bp+_ha?om8+#rGmz#`p`%pmo1j3)7C+EK813O9% z2#5Ts2Kf==T^FCeAWyd>F@;*V;$3*mtD!Nt^T&v*)+QmVbMNIQYX(TFxh$sTP&&@S zhL@$wYGphJrT5l3CMwQ4F(*vlxwKV?Baq?Iio|VOL{xrOwE}bNTz{7OhLvz8CCrXr z14_YPP7sibh4~CK1RXpL`eBysS%+uUi?5jQtIJ!F09t-ZazZh)5_(%x_b4MULnJ-M zc4IP3*{wc+fgyR>d{?Tu72%7wW}P%jp}Sybi5*b zYA4qJwtbZza7u#Lz4nNfyj`OnGpK`xHejOvH=m36nAU1)gGb^N-Y1g}8=)dJYyP{FJ;r^WQ zoxkm`^57jbw%7~Te$D<~dlToB75Ez!9L1RWl5cVFMd^aQg!d+_Puu>o^*#y+S!VtT zuM|0O78@kkHYwCunr4{=2v;$Aw)g2P!}X>o^iaZS1|w3Lz4_uRDluN*3rBu&8#v^~ zXEt5xOaxyBm2MArDmwhOT~s;};5?|Kqn!*w8>rwvf^UH7k{Abo?cIzH72S?%k4Q6d zWjXz$$sZvS-#{s87yVe|swuq4v3h+BH@Q_pjCqpU4doje%W2zUXM&q@#Jr~+pAR9W zfj@kgq2U48h*{map3Bt#D8FC$>;Mow8k4|eMf!DpARzjC`wbI6{SRgcgPcrdSgx(f z!vknqVx;w3miDS#vN1c74qd}~D7Mgu%v-uz%4Byw|3)GXqHRPhs`?5fGiC;8+HN9L z%}~7aPV#Y{qu6^hKMH;L1cS4QifZ{$ayKR^ayT2aSxrl9LvntzEUBV<1%*K(#-ImT zFWMyLmV>A=x;jh2B2UFZVWAXsXxfwJ293{aNf#q`t*dIqsmWkZFc2KT5_k1jzIc3- zyeT>`F>}I$;4Lk@Q_m7rFYS0k@G7nWyXRjUYHCA#mi{eY<4W5HhbJb?lx@pL6N4%< z>YksH94TG!!^)YG>3DCY)1=Ej0D*NVPkyaldj09l+DGCf2A{GV*&OYZ5RA&w^6rU( z>^qlUUDDqnQ^Tsj@T=KNQdg8@B@o+|z}v1iC!Pd)0u3soDfepmvE92Yt|FTNKS030 zPi3}+3u^-8k|;@=6gB zTB<6djK{#jt-mGD%Bh)8VJZPdmmGNE4#M!}Kud2PqnJy0^y88H^gZr|C1qez3QwbX z+-4G9FOft}mgoR${AUT@2Q4v38JhMm0( z_F-;kKROAsT!0aES~rQt&UiLf2@ZRP^{xe+sZrvB${U%Altj-R!$`?oqJU;hNnTyS ze+G(K1JHtTb#=MA&k;(J>iO-sF~dFX9{iq2ylb;Su|x55G|VaphnxybiVf*wyk%ZS zz^1~ptJyU(aAj<{O25)zZ7NaYMLh zJEO)e)6C^J#5<@cs<_;COiI1&PnN?VEr^ty7eB;s$Ob8K3Nm)3;ZFMqSZ&0g7-$15T4OV7 zRz*cG&ed^oz+Y)9{02B;US3Fw9$jPRrp*nw_8Ra>_fW!Yx4HruQ&sh^VX9AoB<5Gm ztsc*W2Md96cj9V?BD6r$0FEE!}=aV}2a z8&3YKjl$QPOpnP9B<7aNF=$BGH@)aD}L>4M>@>-?_goA+Z!;)IPBIjDH41A zb}4~*=IPA+FUDJP0s{XRmPfkU57rBA~vHA zWmPs3KX4h8zlE2~R6qjJ+a-f@W9NwImH=6ao83Y*>Mev8{*gNRC-;;;xDy+|PTD+` zA5Z&2bKeRRG8oRDvT^mTx>ua_n7rBXjkp8k=5*?+{gR!XhUqsRBQu~NYYm~a(&VXP zx^6wYVcJ;QA?cvFFS(|tFv1%r$jJ2$P3O+FL$0TFfGlS%wTOV;?6v-1X+X-zwoxM|kK&V|5u6y;rC=6czI^~6^tR$jXHSCGS;v}h(?(#W4)NV58KA|?1S!|B91KqKU|;zCcpm}=2X zxNWZ|z)|_b;im+dF(-y3vZK8VRhyouNY3Wq;rPM?Xd3m^Q)A2C?;5Dnax{3X_!ZS# z4d84Ak2ZoxPqh`#W>-L5hw&em2o$Z#ov|=X;^oP>9|02!jzl+`5v8;=leJ4K}yfkZRt?H=_wDqQGBnYpktcd(U!e)y7Jf1e7)xq}2 zjSU}nw~Y#s~zeOv^cTMi#uU$l5h-X| z*pJ6t`t14!(*F>bkNYc1ZV1Z5?x20#9`ZD#-AmL05&A+27r%WDvFabMrmc@=1Lg9} z&sOQNe8pWE{!+4MNQq7~V(7$ybMFMNpc>M`AOn0h4}GAPcL-Y3Yx-Z;lpu=qd<17} z=q<>ZD=Fa#(_;lEpu}~quMR~Vl$m70M)z`7;+AGUWwKuvDWlBGjP@X#&jxIt^zqFB zsT6%02v?BQrs8czmGd0DjOP z*UJGBrvSThUTLdWp5|?Bbo|-njt099lZl?#e&z>>Y6MhrUG`KG7oiSmL@f3wq3;hD z_Mt<79Y7;yh{lzb$uP1a)?GT*`31VcB&5j)f{yX(^(L~Y*}q<^Qc$4Kt7 z<#Vr~5C^;dZ4*<_qJigkQJLTlnYmaZ#yv|~CA7*;k?N|$@A>K4y%zQ~Rwlm+JTS4Es5qbIFbC!WL z;VXT|%rx#VHbAWk+o@WDx8Ni$uroJ zo~&ZCkP8LY$I3-O)o;5WUDSviAQ4XzYodr>(xJ8O#p1CxpuI%G z*s2N0LqraB%Q~62PuJ}uB5B-%2+_Z;Jx};I+NsvxXOv7I0kPWax{-FNebPvJ?X8Kl zqP0#c^36bcy&IfNeQFiA0_dhIMSvyZavMov9j_#f7Dr#j#V0w=z5?H#zJKv_kr!7_ zJ8k`1sr88A)}idT>_Lj0r5>bVaeyoqAV%L)8|s?sMrx?18ZS^7OS-N;+%hWvCMs?HQGxX8-+5CiN~_1}B7Bs3gKC^#ujSeyrWR#cMWu9X3mrVJ7f}M;2c|yxs#C>5CRu3N0!<4*Cu2 z0@CsiTq&V!3*G)W?_f4r1O}szYgeGdWkhll(s~zHq~fKRh;g!4na1b2Z zp>&DxuD2qNtymcW3(H4Fj}{hf@-VmdS0UNq-n^Q9=uV57LzK1htkwT+m|+0du&MH} zSvTC#yCHTTzrcZB>KprpgF)#BMm_Zs9aDQME6v$vb!_vT}zMK4aR9fBZ-il`dYa4$L5`CLGR%l z&CZ^1EErnFH;L(^w*AV9$Y!qICJ?~UmPu;~(`mB{PWT5SAU-H75J*?ARpf@Qr&*oS-$kN#CFoG2dgyi)|()GS$y$XwejLqm6J;@4+|cDc5|MYK`6 zGN8W>w$(&cMN^_vY)|1xk7D=W_k&x~J)fGdY1hSf`$(=#A{nR6@V865tUa!M?6$}To)+BqKm;_&Yty+E1tmHCKJm|>d^U^8u(|pbHDcKKLHlSNISlRmt;+$TnPF$p?G>& zJ;0{%eduijuq2)(I%O{S4(^~^ex6ES4PU$JfVR0T^Ld(&Qu!WXF%F31SEWdIk>yx! z2I~->;EDCnqeF;od@=4Kt_HHP5{06>#U#xI2^XLIGV_f}kg961+mQ2Vc%2dN&LS_W zbzg}z>gFdc#6b_h7I5V$=%Y5utVFyV)7lbIJT{3g#wQ)9if!-*MVSf82Gfz$X{`nB&>}>6_`&d(FYnx0tzS7wJhq(Tl^8AYPPK$sFyh)}X4Px-J?)t_;36wdGdQNkbHJKn;Gp;|v=X()ivxXsY&i zL82t!KhQxZt|v-%`~MbWsROB*mC0?TDYtymZ~;TE3aDGz2)pzvHKQH6@b~9TICr0G zXR88PllF6@Mi?kQoqB0chQ5_mta8?OINdZyWWle#VA&cAh0e>(>QXu&NfJvhk+-<` z_D%P2MEw3(_qW@6=v;Q#tT;2`LDI<;-BCrgeuEcF z9YOA>58Y164D$Vh?*N>1U21r}suYC?$5kM~<8}gVXo74?V3{ML73-Lk!7C>;MnO0I3q%UN!#KOI{cP0C@f2_5Ry zmC^#965zP6!wpiomYRPd;t$c`LuGyTWF(zVnGt32@OX+1QQP&=m=KBi<$v9bVNpQ= zcqh^HuGSu>m~=$3N^>3-d&besZeP0ZC*seGnLkkZjzY5vH?pHPqNxD{DmZVj$pOL( zt(A;fY<9d&UgBc1`jQ)05i$ov{DJ$Twf+|hYL-A?<3V6~g9`$VP?3qQ@ zKO5l@$CBN4%vqm)4wPRSmFyNjbDsx?=lNtD#q$d_G&Ja2erd{&%OY`8JobS|-`90e zluM;)aHm$c=SUKngq5oxf}J>{XB1uQy#jXxpa4ISP?XQ=nV76Be3z#=6Z*#9GX}c` zb8a#_-2$gDX(&L5l@7I(=KiH!a<^kU++6ZSYP4%-&@v@8V2R9hMiR4aU!=wz)Mz1N zt19*bRpQQzY4!9`Av(&|N&fD;T!~|v#vKN4@7X9> z6u%Q^qXYrSy!yh-$nnI;tA}u@N$k&qFRqx(b=7DE)Uv3zujmz{c)(-~K6Tjt@d6md z1wlv${h`;&8>LerH0JZ+6^f-I zoGeG-$8p7#RftCetO$H1}OQ?S>bkG&Sk8z2i)|hM0Y#6MvoqN zW1h90=C$*+AYT>>7R21Xa_uXQyF5_M6r{`8q-AOLlI!$Gruz*Y4wMl|9rry8YI2Na zJ-wok(%O>v)AX71qy0 z7#~gVj)~(6h}oe{R$P)Y3GjZO{)WJNPI09{3@*ybmrpFY)o++ss*?l9arT>=Qzf@XSV9^786IZz~5b%C^& zWmy#?U{9C@2F1ie0JCvC%&utBg&ZzU$yNj&;5p)P{fskf9(!vuY{`Qhgbg!I=qNM( zI^`DzxRNA;K>kfw@$nCGAMlKVBZvndaz4@`>#Q$3nwpW0cCFgK?;@w^B1!Tf^AKH! zi(3&!oR&FEA&hb9eZdJLiV`7`psX&5UEL%9y6eB&F@Ydy!6%VWWNO>Doyi5@q}9{1 z_dcc=g{}7PYT-%lSepy3?VYdKo>-aCY3B*TBc$d04$st^3vUD}p>jD2qO#w%83*Gkw&VO=>_yPOOuwe zq84!w$}xoJn3}P5Hf5vulceG2;c!uoCwGYRKmK7QG)qjJ<<89au1k;kq z6_z1Gdtq4lZ^XinEr@3JS<}31an7pKsuj?tBDRo2m1li{Y!}OE%wH5DH)_&AGB@>) zs3A$_)NL94cWv#Gfh!x_Sx3FN1=o|wseyMzxWeaW`V#2c{1SL z$^Pl7W`$&)rFJ2jORNXHaNiZ0Vwb>JH{*lrMwQ9PE+?_h(n{yF*lOtV1o9 zo!DV(SOnlYn^7iW3QGsE_MXkXO7)?x7691(4rzIh+RW^-g+$ky_HUeq^q7-y(4dt$+osZD* zMpth)%eo&(=d29rd$U4RZ%c;OO~*XxSDHR1yY%A-%Mq8Z@|;NC7?vD3Q|fdVc|?;1 zQ9C|iQcFhs9VxGJyUt?C*~^CX=8G@Jk%00ctZ>v-jC{FZ7XDAt*OW1mLfqBWhZ$`m zqDSxvVkQ=*Fgt0}%s&waRxpgr6|*jkR03Ofp%#s^z|&D-?0jc_p;wY|C@AojQu6PQ z{k_J>knf>#tdJ;X{L0>N>SkFNjORr-;6>m^wWUhs0_7lrf`Ata=?AwxX2}RsDn$0J zuh8EoO$-P-!p?~MvvhY;TkW+;Ea@J`cp{Uq&4@;t;t=p5zSfSth-dDK^FiH6S6(2{zkN^!m9sXd~s?FTP z> ztBq&-`^UXz4g>Yw%`(H5Y0q!}_vdl<)=QkbUSjNT8s5o`f@wGlf;V}`F#$}458T9g z9#oD>v8Aa84G00A!g_LFf!jW%Uz}cl>IEFqsuH z0Q&z7Ug&*)sz_Wt|ADLW3=s9yts`dYywwRwOVaX0;n%hZTeE0SD)eh_taf?hnMNVi zi~-qHqf%U#(%pznn{DrznkTf zOcw#jBTF=`pTL|<1T8hox2P5CBm?LQ%L}4|=D71wHWn7brW^G{#F$tR`{ChKR?}dA ztZh^p>mV=4y`?tu#28=VGS^t4t~=d&YTxy6kTBEKYI#Wu+L+0ty-^##yytK+3DtZ9 zzz*gS9fq@x_S(N(sYIBjKBj56;@tgT0<|YR>Icnh+-^sK0r@8C#|1T?_dApK0FwxOO(Pa{o~WU4)6_%LS7mRML&`qa*b954p1s5Di#=P(9Kx<1O1Z@EgU9Uchox zpwgznn>SYs+xN4^xa|=BOV$Z>0 zV@h`7S$QpU#9wqp>tPV+RSp_ODY7>NN}n$^BpemXg%2THNF1H=nzUrN<$5l;p9t^b zX6u^(r9XETtluE9G&4c48O`@PWHd}{W^*N|oNYuw7eG&v*IAL7#BQ}x?yNqpCtTj7 zL)@h>Bx3}O(Ihbi@U3c!gxYpO(#f(-8NX{&1?L4q9i$x_6NudD0(@9dWQn46bW7b6 zIy5W5EGlREY%4O>dnIh%@Z!5^30qO9S!FhDodD6X0}scLX?w{E$QyyxD&Yp2jZE4K zIb1^yk9+s;fWvdfTr1;?;SNm&^@pH%Aa;mTCT+EN#caC~YRy6eTceIb`7{JgjvGy( zoyyGhK*5$x-3t=XPC5w#x`p_@xpAxJAb>|XLoQKW!c6#wo{4T<_GKebjB_ymUN{mD z?r}&0yTrhgal@!lN>MnN;~c^kEJF6Xy_%lz`i({tN?(LYk2AmD4$?RI&XtaRI`8>Q zjyP{oRrK-gu-fwjuxSSak!4Z!a%*uSF}*U$sC6mH8Y6B}@zt9zR_fONWUw(mFmj?J z1Mse7y%1_T^aJ}eE)|?Xp^2lTG#fGB5=1y-F4)|7bNesy2=Ug0o0!fm?xL7-N-W7r z{bk0zUJpQFZdy+K{e&tJLj#a(AJ8CuDED&F;^7}e&(W51bF6+rge`L$bfN*zWXT%< zx_bojqNO@q3F+!;Xnz16QbTD32dB~B<|E$^^_B)AtmO!^?$SJp19U$iAMxV2MM59PZM~c1|6}qo7 zk?f+wBhIo&>d{tS%$~qsXsQxc~;Kr#g+BJcWDT_%_OWOp+ zz?6upk!_Y_`AQL!F^jKyUA9}+(SrqE@Dp`zZ zDI`XrquXPMQ}#g#2Ri7+kotO03DwDRpT_1sjH{wcr)@~!kG!<5C?x0Z1dF*8%xVR% zpB=33p@)!!}1)NMCih{b4QnZ0O@ ztuG&~5EllSp^WxbAS!F2~`xMN>p1U`}d&#N-a~PX#)nuLW>OaXP`9yf#rbw8)a+c-Ltp1)$!X zT`k5VagOjT8oZDldH@Qlg`^+imz3@pL$}8^jfM?Tt0}@qb+coB)(1n@*6Cs2^=PL+jH{^~H)s6vG|pk5w?VstaMoDCIRFPicfLX;KtPqE1Ua z@P8pJmm#hZj_U5H?~s!ek9S2sJL!f*{rKJE_>>%&*z7H*viydqB{S+^!VS4X^Yt%O zr^7HQJFRfOP=a%F8P-9>OCW@>q7V@(-bHb)pfD^RLpLsBL8@3X9^A^QDH%I?LiejOe*sZdS)tzpbdFAuaR2$dx zII>?rkJF^N^E|m7Bg%u)*PRU?fj>g38$@0CGXjpT5dflcKq10Cc|ESSk~J+d{6M@0 zi(Q8`>iyb^NtRgyaNcI~wKiE9oVo$p|2ZtY-PjOCP4tijzBm*vDYmNCvX@4MMOxpw zC3)1VkfB1HTt?~AgpF6j^Km=msV?t=t&}53&-7bcj1L0oXRdY8S&zOzp2|)zq4n5A z-obCeGt`Ga*F!J;YZ@>Wi$p;uQeJZ?J^&@sc+bhB=^Nbc1%XbEd-xH)Kh`_ZEIi>Q zBulIsh>GiB*wHUYxxr&u_Ht*%>ww;e$MX#qOc-Xj3Z|O*-PZ0@r3lRNwLlgh8r^?xQzfja_AT3d+YL z{Gy`tF=k@b0~iEIR;PcTQU>Uv9fk_g<^q2^68D062G*F(A(fxxW1 zrR@=@^uRRD+&e1e@6I&ASI=QZ)yguO>&k?(q412?$CXwBoUF}lF#-Idf(8G+Y*+wX zRbQ9|bf;to4H2mlp@Dp1D2O-R)c%E_CL*8_U~|= z4OKjoC9IZv20(Iq)7KT^$W>2ga@qozLq{qsH@dk-1AI=JAv`=vlTUJwVtErY`Q_-q z$<<9D(18kngGqP%`hgwAuiy{s|M(+hhoFdJ459R$zlUIl870G2T=0lS`B405dAy{a z7Y_WptJZDDe=yl`zTAm%KvwQ@I3VrWim7+14dEZ8PW_gR z5~pM>#5iV0;~}-1HZBDd0&M1#o`=6*JZ713m3t!-GM~T`vOms0G;VE&Na9!XpbCgr zH}@I}`5pEhONZFQsOGS)Zp%`8x2N@4j@<}^`S9qh(KSL*w>3WkmgB*}hMfSsd}z(- z1AT+$CAsa)_o!~#e-F6yu4x;)6=+X8-V?e?|B`YSYR&9B_jzx8Y_E4+ol+Co1gzhA&R%SQU^3|ozRrU|_yH?bs? zIA0yr9r)ylsktEVZNj%Xx>->bRMINV#R}tPEKgz$6sfZ;DE~zIT?-B)Yf3u{C7ett zxOH)**`yq}LV&!R>y&VJtpc4I#`z{qg^T$h1~j4ZW@X)`N^$h#^#azCtUN8otG+c= zphR;Cy|`~>Ey268Hzl2g7md*DqBG|$oa~;BoR;t6r^vdWOf<>cReJc>UAw39VGEXK z!BBmm__*A9NnhLrFrVHd9}xnCX5&Ds7eOjgPv~tcLl7O5#pDABe7idzJyEc@iPFN= z`3WrH_>qOz6!`$5O|3SDI`KE?yp98+iQ+k6NH}nAV0+C~t#X@&OQuZj+YAM4{1*LY zOcmPfl{-rp9Ls_w2}^!9-1W>|zk@>~LUa&#gthk7O}8a~8OVe$KAWs?+{*D51m8q?LTP}|pRrU|4Z?ZUcctWErX)WPP33}g6)^ggu*ust?S`b;KRH%Utl=Ey9NXm|B%rX8cCG{CJ9((X z2!XNz+DAn_Izm$n0509Rsie3j7z?!C1)_c*C1&}<*HPHgFBiOhaq;( zKVkBo-#mJwIEs5>b7=Uz3rYsA_@#(t@O4@ye0?uPg-r|@`iHoDbB87<&=*NbN(h$! zZ&-GLGZhtN4TqUsh@}``2%Y3d6FJPQ8}d~xpN@6$SYLWUQ$6{-xlVp>e#lo!>HC5W z`y{^~$%q^#wx2(wNcRm=GG^mcmGSkm6|@m<2HT2_?iwJl&ZPd-7|ii)<&WP*4=O=3 z#;({ugJaMeoxW^pZTjo8lHom#Y_s02_(nAgJb0E)8Z!U<89>d|Y9^sMO3S~U;;6JQ z9uB0`tUf&2&M+3bQbby2lvjW}xji{KoArCow+znebLKBhGbz6)*S|ZK$%3v$p9NGt zCQ(d@x?k_T&{zjWfu!Iq@|vz)k7_l)h7K_|%pYvghjsO=<+foyJoV|`0K^#^Z9fW%?Y3pjx9rGwCR9kf z(Et8Z+G9op_rBAX0J^WYV0*5TNb5`;=wV8VSN{5rSxKh?b50z@!Sn7|g2f9y%k6Jx zPWT^k0kEdx-4I4Tsh!{}hsz+K-IJZfZr%n(f!l?Qavlc&z;3V~m<=8R=HJ=>FWpcU zfxTy%R#RpcL+rvJfLC%FfoE&^q+gZop2&cq8Zfh`?hbLi*#*)7>W{L9!1PhkLh~l< z(nwe8;w@6Y@1mc>e<}4Ly&+aM-^egOLe(<Tf}vo&F@rZ-3r^1NeJtdF}!(EidviPwV5Qtd!`A(kQF;UjCI_ zqASB5qPjvc*&%#Nih>j>xpM{Q%sAwtsNs;-O%AKr)R^)Hn!~YeaaOt_{vuku@!f^8 zWk?hDAd`SUl(7)zCOyOf`(>;hYG?Vl|M@#K9RAkJ_aSrKzO<8CD&bjvULgBcwRI-# zIv*_4|2=i$LBV~c9V$_tCA*?6o%C(BX=*ri^j8}@+uX#pzsK^KoJowxo1cPF_y2wr zV#v6z<-Z=DoPk_v5#s(KZEu)UK(qQ#9I)Vf+yPyA2MDtDpHWx6U|V;lUJ7RBc6ygW zF9ta0Y~<4(~mv4~5>E&eqb4X=y+6;D2i002Oi%8elI~1MB!4-yk*l=tvtF z1$T8I4T`~-k3EtuYiKNDsT0X`^PZQD86ds9r)y59MDb@aNPf`k$NVVY(YR_E<+(*p zOB52tMH?tPML4=%xyVp>zPP7)7dQ6E%A08^RxvV={a%(u3g6PsYE_!ItoUOq=Yj2p zznfQ&5nYBp&}+&(;3QMQT$`J_E6l+ku70lT3T2~{nsDNwl;+N0MGeg>kOY^;&Ake{^&^qrFQ_miiBQEj0WGzhjDrW0Vd(~ z^>jBJNz8Yat3sx!D`iB)XRUgj^HH;{dd{7NI<(!Ei!eqDXW_G@33f&^_~I|ReY_WD|;Fx z8!WK*VzT8h66Cf@Cb;MCDGACw<{}91ntR8}%fqB%leeU$-|YF+iI?fXQ4Ea&sytu0UWnCSi-O>ketfIose9+qlpNgV+9o`+bk{4w4QqiD6xteec zZI#qHIu$J^{$7$RVBHxgFH$YJ3`2DL2==r#(t@g_@12qY?QA^;P8e5Fol>&@pK}8v z`@g0z-gR(5lpT@hLY>Pj{E0pL#zT4HUdZ3pu4JE)#E+>Yy>+S-q7+fAp!`W%?uiPK zQWM9lonr6G`(I=n^nj)B&ZX9wJ^OBalXrY3K_4syA^0){2U=K6pJ8;DYTc7)4yBCS zZ$DsWw#4eDA9zS2D^={WJa4pA8;egolf9_^zr&g2M9!F)WFIA)eCl2LhEOy|L#1dQ zLQ~2+aNi3%D2%J9ufg}cE66F_^R*R&w_P@WV4j@Ux?rSa`eCd$rL2XxTIEWq!uhh= zQL|CzSbQ4#zs&p9)wbneUsA+Jbw(krkv+N3u?LaPxNN6f2!8EmKplOI|Fb<=tePr} zt=g=W97l0z?<`GIKN{+@6^6yF&Edz|L~lvn`c|A_u{sySuwzH!IE7=2(ODg1u@w{X zX9JEqZCyr(R0pj^^K+AJ0BZ?*@>G*}CIv*GY33HOgCvZh1)a$WFQ&6(L;AWh0`SlN z1?+A$5>u3fMMwV2qYLr)tBy>FS7&}k+9bz{0PIgK*PNK%K{ls1pcqCK_0p2Of!AE7 zK-SY;MO$om!4HNn``n7(+_l9E_nKliCY4H?7%Ej=B%%a55>aHD$qqRzQx$r?eXcTe z(@;pw0%}G+%n2>zSN0@Oe}yky5mPU1dN~x4Gh=)~%^9aY!Bcmqri!CS@0H5;PX}imlM35o76gP<| z3|p#G%$`zZmuYlDdBNAp6L0HDa8+aALYt9J%LJUL6bJL_p+9xj`Q@xPDREwKIz#uJ zuVvrsU~du_ls;3ARUoKx*L56-KVnJn=GtaMaAhi=DEO*^^3$&PjqqkyuB|GY@D%X_ zDV7$+b-kPNgXAM=?w$;%a?%==?tw!*-9ZVoq0y#q>v)dz%@9ylk@X(%HYuOTQ-h5f z)0c$|Lpn|nZNjj7FEly7Ma@Tw5=M#MqcFJ&Jh+wYSJsX|qU*Ma`bC^CvyNNad#04c zSO52_TKjorm3{EtD&k$LS*DKeOcS6_>@Y5eA5?I_d-ZM2dC#DyY^XD)Z6nr!HuaV? ztgZa1Hm^RlH`zSrds|ZGlq*om*laR+3Ymx0zXu&8ql*_uCdgY=8nz}?u;JHL$O8zZ z-ftVrh>i2>sQz1FaVC|hMVpUkvmbTmcQ-z{!;VO(vqOko(AB*>F|Z zr>}-4l1R^t?n@jIr6bkJh+BhdX3l5^_eGtOATKvYa=XmgDGpizDB47h_`!Phu>$VIn56!8tp`qY=IU04s zW(r4KdCYS6K|{y{1BGBWgcDgV-&+5j8HdO@gWtK-dtFUsvJG!=J<9IJUr0M zM^>GpFAZU&1zu%XGxb8uxjM$ge5)=i$t?E7I`Bn*UYFuV15z=L=%#!;6SHbW_snPD zWMRB!VbXjM5V&h_!|(sadP;jnlJ#I^2u2Z>kKx?0(&;v8w}1Uj180%y6CpJ7Ew@^LI9DYI$ltP`u1grSV3XZ&Lv-8;ksIk z=$(s=zWPz_{D;O{I@A`RW2PcY7oSn3ai^MiXyZ8S6X9nGCmGQ#6!SXigV2~>;O=~h zn@jto$Zn#|VG~jUB@Y+On@MFPS*-aN#XRFoN?VjvLhSH?;2OUMsb+lb@k&sp!0gZV z7T54)=)C@GYJNY_>RBAG=_-vzAJXlBhGsWerXQhr>Md#OLumf#^b4Fl`{deyRO6B^ zowBmUWF%=nn-O*^eiMYjx(Z2F%?eW0ovU+BYA|C$*hxA-9!@^ z#1%F)9p#Ac4Bu5O3n;amzkZXqNRU6D>frd&^_M=hfB(c)-E9d&)|x_Co!wgJOuF`vFR)&Y?lmt606>?Vr(|GCOAt{LIXm? zM#tr@H!DNyvX0(?uRYPBPt<$ip2zo|c0RxHh^ZJxrJSu|7W7gqJc9x41zHPn(_dF9 z+s}Yumpr6OX{}{{m%{`*&Bxw3(fJ4-7C(%$DXwB^!ydEPw`zfB@(3Nw!WNhD9q=5{ zz{D@=`#ts4#<>51w;3eo(9HK!81dL~Zir_YddDT8-vE{Y@iC)PB zBTgtPDlb#B*0Bip1kDG0jHO&X=aT=;`tEVe4ArOwEgwS#h=Gjd2l#}>@84;@k}yH1 zS>gddPryUY~*x&TaD>TwJdj z@DMfrNqxf2_@o=+Iy)U8S#L3Y_+oq;Af0Q^@Q-{IgE}b@4KcqM{@9OMh8?imzf5sdV93k$kB1Gt@+bA7oBa1PjTSoQg7r-VK zpx*#Dugu$}pBrq!HyQbeLPkNXWaE1}i%1z(2ue=WU&VO* z?+eG;+*ooeO40_LFjH zy=XrX_R(kfm0eh5ArN-v$!gluGrU$kxthYzi5RD!vqDs^wXN+gBXEH;D|axBpj6mP zyR_g35fkt6CSCFWyb`O{mbYea?KIya&6;s<$9rn%PmUtUV<18)`DhAirl7YIXl^WE z_i8O`_Q549)Ep+fq4hwYHE}p_@q2aL>Ci1!Fv%N5EyFKH&MP0gV~Fxos$BP?p~3^* zbOgVVlL(3Vrs1jveMr!bcl~`&%==p{Z^X?)QJ1el(5WBR+NUSR|J#y@Bjo8~MTve! z%^K+@uWyqfGO*`yr|+OqR4^?MMLq18s_ODyoIevHLrA^##+x4!>?%1c|o%kM9?lq0GmbPH@!sQTR_|RH^o7FxY zC`z+Uikcm?ELT?AR(lQNZ|&B+5={4dmCBxx%NJ}P1@z85ByIN_lKFHtPgdyPpT$NU zsj=7$wgnyF`sQC6rJtq!o5WXua}^1SE11rl*~M!!*NIlluhnMZq<`C77zDMhq+NAN zlllQX{jaX@vk|7PN<)-)L&)&XUsiRXJQ#|_*E`j&iL}QYnnC@c(wFhXfdiTE{cD8PD(uZ)3Up@vkj^ zlEdCOb|+%hZnD5kZWb@Xx1FwcD3@vLipl^}f+D@x|5&?Nx!xX6D9Y+^3cxi@{7s~$iq7L_H7F3qX&ELL?6fLm z!|GseqH8Z9=@!6?u*vFb?dCaF59P@pJQ8Fo?>ZmC`0gBO{1sjKF__;kP@Z`qx8 zmU}zCQYcP0jDI#(TM-9hj2vjpXb0ILG`-33<>e$I6ylk=0i%&1UnHf#2vaU8=)u`P zU))%~W%4a99*Yt>#&sOw4rOyU1vBPa-Z~MU#&M@!8g5mYa5{*78!GA?1vpYf#pa5c zCWd)z8TZ9KfqEMN0KAItPWcib9>HQ9S`%3dB{ZV8_N^6 zKUOAH2r0P=tHU$VPD9#0Ku1SwPXJncKU`PJ#nmeoTbE2*RxrqFMXdPFuEOPn4%+iV zZY1Fd2RNQX>qRuBYT3I^f=-ZCCILQL_2ixdlpVQs@r@SnZ-kQj(hLmAu48#H=uEEO z{usR+*!A9xN){dl_FO@_Pd$UZxXZ32?DYY~o+ypC%qvzNUHmXZ{Ct_M6coLe8VB1dnhEuvwy5e2et!p~KSYm7iJv7h@p46XTRSXyLjCiL7R{D(qWC zZ-*d?=h?nJvTPQge9LrCTZ{+5<&}AUm7n~{eXfG+Bz7zW2f1V(vBej+pHx^VDG+Y3 zlz83Ao9<@za6S#7So3}}2Hx+MWGB`4a~=pq3LYl|TnY8iL zEl24bB8HniJ_9afPYqfU$)As+qbbzz9}aa8Fi28jr<6Or6;1cOcp4QnkGTCT=r%4jSWYa1aYhk zX#+b@ht-wIg`55e4cZ~88K%Fui5~b!XI0X$$pASDYsEjgt#>iAy;xUbHP&p(W3HpT zI(^pBpxi6bLn)p1NX2BR{bRGuFIm;PP)I5X3Sapb_^wz#EoYJEMGx8N-YmRhEZSx) z$sZQU^R}DA#^(0Iwp=m#$AA_`+bi1i@M!#zU01f2??eLT{j{CUzDGRtlgCY z{tXsSKk9NLtJ=VUk2hZI>@!pS-s6-sKl6YDeM-Q&%-1Qe2*9qUWTqNppxz@v@qt&h zbFg>1Na$2Rw~!?9_`v``LBd@y3=>)Zh$zxF(1!+ho}T7$0`30>Q&(yLit|SK6wt*> zek-BvDVAZAM)>0jjbz?sN+4msAR-%If8sC6Pu-j>muWN0$(~F%`I-kg3w*Kqq+-eF zAm}5$uF1JMfB)Bx3|uh{EBvR5+M^#=k3#2a>K#oU{?;mIQZ)XVE(hyKIBpT1F;DF< zL8hFd!?S;{WP*nFg_`tl3B);yWt&vM4k2EX;mR`W0jXY58|!EmS5W=ei>sEiu66(E zsn{-ebm#;2mF3)E!>oIhZOAVCol`+Fu8C=(rEo)Oyq6=xGx+UVlbZ)7QBu>`L>9|5 zUO-hK=0w}vxKCruERWMY<-Rx0Jf7LR>}mIt6wwCZo3p&O4?!pz_TI?)uyt4f!dY!2 zpb(QU15NE8(@X-d@uYJ|&c;Cp{nSnsPoyAu{qT+p|EqMY&jg=#{|_k-n-p=)UWFCw zM`=6itYacMWsy`bbC9PQye_>GhW&mdYs^s|TfEVzN;s%d;kNZo-bdkqyj^FQiE zMh)NiJv=?Q_^W_cSjlfOzZjbOHY#?=blwv5mjj`UX#|0U2 zVgs=YGBWF^ON=sGiXhjH8*SC++QAzg73LH9r&PnA{ZV8&5d$+KneM@sb&o`~K>OmO zo4iPe(yf7^dn?X^^v~b^<4U3}-Sb&@HKsf1u* z_~sH`>**2TpxxMEj1=gTt8R*58V5TRdN-Ds#IZvXw>~lPnU+z`Is=o8BE-wc;tHzb z8?@Ji)9I_`U^$^+h05J~-$Iymd!2_7q~uGnU5I!$Nc~?Xtp5=tPZJ%B=x_@6D?W{Y zh2WHEf}u2l#QGUS-hh;&kF;L~$#iXT38o6QJ6Yas9@Wg@Z+6VqFpw2#B z6ayD;T@T;axj%wbnZmkP)Km4Gv+Nv*T_a>m<6^{U_Ag*V?Z~4FuDrr;T&XT*b)$KB zSwPvGJ5vzqMZwxq>(fzC^@{M~f&O4WfE@Nv&f4TXyB`8FO6(A*UF2c5{KWc)D*GKq zhEa0?c$`O5259FWz3$Gi9s)Y2oX97PRkK@Zj3nEqWclb`B>||SI&uXHE!^SvUGgj? z&Y`EH5n`wHck)O>d+t`nYL6j&Vf zouciP7;+#*jlT3pF{uPEta4jNRyf`%diPwi>C9s)NUXmae1YSC?kI1h2&9L1ei9jX;w0-; z6!Xymz?PR!x&dC^w*^$Fq1b|qEu6)&@;$qL+jo0b-_H+$gHs-E8Yci+09dy zBMqkbZ{;fgnF^CzJFDc@#)_lxJ{4oLk_e&l_D*C&kRm*oq`o4K3(fRb5f_P~)?j!n zd9x#V;VI|=VYiaj_wjj`7|$3lu_-6){WJ0l%BT_ySY1w6$E)PYb`91J_bfWMDZ4T; zvCCv_t5x*oY6j#vKo3$7$i)2-CxGb7?J4c*#d*Dg>3U_bVGSEQnz0@4X1`>!y4Z~+ z0HHxW)+w27#idsT9ltcPjkU!u-LJ8~L=I>2lkdvlI{!BQGeeF96Caph#}^$gEq=tN z^*~8H{=syBizp>H&ndsHOzDx)tbKv>dU!TFp?^p6$&D6?^Uea4JwQn-N@W4{_sHQ0 zSE6ofkhNwDok|Cq7?OLuf-x>6^1s`b0v9IprT?lm;yE+lY9Rs#a+@b=>0KjZnhgv& z-rzS*{7dvBv5yFtk(8yJjxnURbN})vk8nm-E8SEbiy`%<<-^8*PvI7|>jLo=(4!G~ zCSYN*)C^kZ2lSR>E3Ve%&)2z5+!Wv zwy6WIM(V)PF668K(ZLl^Ut3ghpB|pv3}4L1bQ8h=DjH5Njq=*Vy=4jadr16z;0&|$ z0ST+llk%=u16Y>7sJ3}`7kb-qWh%y=D0Irf@LvqSf(^A?cAxaC*}^Ge_wMiPhQ}`72uI~DBq2_PNy3MfglHeI z)w1RU0l~lLXV`9aF>tY`>CRK-98I4;IB9<2(os)aAehU+!#xV}4fk?{j+<=peB@Bv zHh00MkXTLPY!+`2$f*6uzp4OC^q?T47LLP8&^i6L9ndMOldzppzjFI}jNaF+zboVc z;VmG!Tdkr*wgMxTTtiag)FaORD%n6WD$|xI=)UeX(bQQaOW{-lbL&?Oq8hFXOES^s z;O;y89U+>ty(9-Y8%k%de1PTX(?-5WOOY;&YznE+snC&_d>a-By~j{qUNFRmS>_W*{+isi=)nHxz|@q^gQ<^Jb*My_uVZ2b^`{yzjVjdpV2RPgwzl1E%Ajx= zxVc*G-5s=3U0441>#!nrAqkQduK8?}(kwOImAh{L08Iu#cYRS*1N1P9YeP2`S}fWC z`juf;Zei*wA-uZtmBY>WY8-(weCOJ{1|lvpC=|&`ZI3zsUW`s!=B2Ngl!KM2+DqiG zzOQtP^KnZ7jeT_eGt3@Fzg`}4ZyH(;g>^KqEsU7voy_(MPC;L5;rP+R0y~&?tn#1cdH2$~aCpfC5Pr`3xqiS)Q z3NH3bed7_ZkG)M@%uQ{U07oQgPIFc5O)#iS7HxQdyxqW~=52fmZ9f}S zY|D~X5;%kWr>y5G#Y$U(;gw9$4n2+2HWt;shiE6?SdKXbAq1+pzCCdke3#z3UG6dP zk9q}dHAtK*@cXhLNy5}^z)l?X8i<^E0pQGr%Cad#@3f(JZgLGY%0Jp zE=fgvElIGV4f!*7=h=4`Bb>Zlk})r1sjc_xdzu zTz7|jp_-{z*WBUOLT~z|bExJ+h8O5$qR6JUKNi13vtIqXid)4YRgiQ&bLFFPo#@1% zw!_GoiAa784Ikw@IF6hUJ#)f>0bynBNo08AXYJSKW&h{HftD|=c|NfZadd5h`U(!P zrk>9Z^V9r-m&?J9azn4_%-yk@{o<)Er;7DOqZ5$6y6?(nBI^EcpyQHq$^=*<_+5wd zZP3YMmCRJB_KxnQQN{#1fBvf#b{MX+e26S40y;DVr1&zNT1n!s{ExQ5{*)~f=2 z#L!#Q73+^ZU9dC_mekwFqNG%Df(E33*(w0D2z-BYi~5eCa#^gZwA~wvdp*wrpSJI3 zHeL-5qSoiWG?FlZv{but*QxMt#@P66{R#Ywc{0prGErZ=YY-Nu)f4Ist7p~1T`t#n zaI@)*!j`u_l=wz9_uVix?%mNp8(!JEP6THAk)O4@ZOYX5)+{wB`k|x(sIdMtFHPry zUzE|u^FW!TXD#pW)7pI?bkW4{mb>vdpgzsjxmSv(_p)0JKeI;)(U%fo#ZbLpAr6Sn24|7j2)o zn$7N|>m&6;5Fc!pig?Ti@sW8?i3FOgP!#Vf+z?W98=T7ssD}`({H{O~Ik4YV{R0Zt z;AyPhNcyQ9F}7Mn#VUpQ5Q3K}sR^M;{*aw}3l~iKVvcp^lGDP<*n_P65=S-MJi#jM z`IEy{I!kN{$H%$%vn7Mu0W@c9kW%PKJrWS=l+9`rcUAi^JLd`r-ZV-_?Muo zqV>I`eEGj?_H(LLoSG5a0e4gs(}tLK2rP);#=!XknuNaGPmpA)2?LUU|B3Pm#}wG- z0d%<3hKv~&19J(ti7B-O;UUaAi5ncOqtNGpqC6$l4cn9?y)XfcR-I3k#&}p8aCs^Y z^CQZcOnbspwt8s^+EFZ)F+)nA6{f#$@exU}#U73Z#;HibkiO`dFqVcA607Cm0AbbE zs(@9+)E_VAt`&?qbQ_GD6(AjfaG$mgNikbOX_PsM%;$DHjWg znBurGJO2XsgNgPBj)frld#;R^9XCusGZyG@}2>=jlF{z^ee0( z>AuGOj04>lOr1*^2%LJwQO8Xw9y0ni_nwTU-vI$l|G&hQko7X+9$R!Y?4#o8WnDm; zYjEmd!>ew5GI?u1L{R57pRf7hwgRq2jVy`+DhBc(yOh%@6Rxxu{>n?i5L{e12q2E7 zv~N(CoK)*&?(zzgrXDi#Hc9Acgz>+@c!uOP6RhZ`PMxB;rCdyD168!!rf9yhtuevx zn=BLrR^plEt?YeXjmCA+8GSR`+)tcMTT8f)PSSFTidw<`1xBV5 zF}xB1nx0yVz=^+)VL2XwJ=XR)qM@YXbNx2@tx-9Hc`xHgYpb0Djy{Zp)^1(;grU^% zif$TyhBdAhbK1;AGv-xM|umPF|km)>nL|$80fgg6_;^(Qo zMEYQJRM3kihlmQ2$%NOEDX}blu9X=%R8;YKhF>Y{MXW_qD3a4w_Un794NC#v`MxLq4=;tW_rm%ONzG zm~0LXTw;r|ez5R_;3)nyTWlZR+&Jy4Fe)(Uh}8>0zK#}@a}+K09SF-LdE@%=e*Qkt zq}Qo96YR0xs*ViKGl^No<}(QHMA5~GED1x|VPEuduqJs)u6$8JLsaJ60=bVaM007? z8sS2X$;RIJE0h5f`39&(O%ZYt<|!o~aiTJl@{@$~qo`eehxiN9&=v4Ap&EkLpy`r8 zOhjpVnXKm(k;F3mfYMy8PXXK=f-#Kqk#}LsUw(EMS zdCNk8_tQj31CLb*>YKoxvJJ;Q*eiOW%dJgYG{w5^7Wrq%3UQDYA5J3%#xbtfB+4k* zzlLu+c+fsnVK8peN3#_|4;fGx$PQl%d8X?ZHgZJN{N&OELc%Wmc`lL!pG~L%X;qsC zMik$&t$XobF{HqQ&JLC*>_1MfzQX@AL=T}o`UPlAgN7>2Vs4xtDe-YRof<|b=XCG% zxP02XYxu=31e~L zLk!RY!XRpSQ8?M(hTx4Ii5;1CyBV}|7zWQaj zJw{{FK3EamOHBltAhQzL0yFxja?yp02T^Rd%A>@Fm6PhH7#v;6a~LPGSWB~qRRSQs zkNI}cb?*L#hEA_39>7xNp}Ex5$Z`N5Zs}bKI;=_awCDG%ZBF$N+VOiS zzb@pVOhWc5JQtXY%s~M#Ua+KBCX*s#Y??_jT+wYb9h#yn5bOar-6ndR|3qNDkNVTI z*BqXI_`CBL4s``Qeq;yN+h55>R3KgFu>(*WJxQ;2R#P&*(n;8WZ#?iG|lpf=@q z=K_1OL<0!i5JYrI)cU&uql<|;j=<*9a6Fw$3!sZdHT`Tp?lp@Azx80+p-lRD^F;pJ zpPp8;n(X>S_Kv)>R%0i-Y72R9qQAYbTAkJB?A6a{x6zpmNxIC-A^WiT;5Hyi!K~G% zdt)Aw6Lz8oIg69#8oA%q1*uUMKKoe*W>#K!Oyc%cYVFwAKooxV!r*4~ZgTBe$9NY{ zBCGB|1Of^~G>?yT%$)S6|EjDjS!h2O=&}XPGb(1t z3lt~<)&bCtxLOT|u0#vN!#ekn3spil75~v49<^}>F@)M8uIiZ~)3{;sr?l$#D}7FS zcj5mqYi z)?jccZ@Mboo(`&gqazT(M^pbcyBg<3Rgh|q&~mpbNU;6{g7S*}PRVpQLVP@18FSoF ztzbo=c5;5KuRLLnx~5wAI*z8dP?clGnKsRZNaADG8&bQXBWN15BBRyu+=@NiGTp z)m-KrdZm?Qs)i1};jWy~^^z#_KDJhExz#Zw>FcF4Z*CJG`H(-cRaBYv z>YKr&)C{X?UHe(C4>9bbM8b(6b*JaWfk@T=Aq>)Q()H>9$V0hmTGg%B6epHL<&t?4 zn6T@Pb!%f!R2ATFV|gcC8KR+L`+Kp_5&9~{{PTftn>?3WcX;l! zR)Fi-1fNN7d?fVVE9$zQ;8<(l5SjUlp>yzi$+zMFP?c_B8krCHx*@`xJW>WZ>^ynG z2U27fT~$IxH4G6yNi0IrUTUdC zP)1PD=2svi%TpnC&l>T2_5=~R zpx2jK99#`&yH7;$eaX_GEJ#TeCM$Nn75>gP10~mdGF1-Lg3DG^`6+YQR zwGbfn-^PiLoerbd?>S93MoQlTcMaDkIy$WLU|dvOn!IVtHvqw-hX~R`G-vOA6Q5Ll zYP+fYVfivpdgDDuDZ2;{vxke?`J@*6^RG;4XHfdIfOj=9TA%N|W!Mn}xJ~_K>Q&LZ zA!B>t;B!be1!0-A!~=wYx~P8ierWCM&u*<@ju>yFw+_eG^of^LCv34g2b5N1H6po} zPA@e%lq^Mx#ozR|Q>6;H`*hQ;6pMDL7875_Pi_;$;i7- z*p#29(3jZFV@FP}S_`~3LW4VNrXlCF)~E+ z%uf(oJeg4@aPgZf8Au{dL9Vix2Dy&<3H`ayFzU(a=?a3Sp0vU*8^~7+ z^oxDqQlTZcs45M$jC=lMVsN&(_~?Rf8j7D@7k5j-&2!KbMC#n~h9U>eF=gs$|E{(I zWAmc+okR|93CH2}{GtSp#i{rom7DDb`pj4$6N=+B=8DGF&~R29Kv3Pvi4U~m2%L|F zIE*o}+b%@DA8ci(r+LBO!>`fr6}Fy3onkvw#VIF%zuo_A*at%xgcU#chfS z-4@4G54!8(f?!1Nm$P&pG*O>$I1gFKKS1z*w7cfLh%eix zckJ6z=yE1H{nj?OGx0HhxoM_x)Dshzfc~KSjkHl#&t(+#o#ZUz6qSe@^z0&OAH?ay zpQd&H=^?0&d0)I~7AT+`S~^XXFsYk=Ie91!uLs=w_dxgGIJDXjizse|I>za;3fv{J zk?4a1ZvCX4kMBLD*_>I|F9hLXnnNvDpqKjoKg5lb`-F;6*)Cs!lNO8HmJV4I6r1Vi`GN}7=Wxd z`IAUiVSZ76bM%PT?q2Ss;);o2ghCymW@G4qO?7$!a5j-X0viGad!+^~ACPnbheGTF z5+@ghgdrozdiW7#Rdh99SUbrZYQX^Tgsi@H1sa9v#%P>w4VSo-y1+1J6L;|AsLuD` z$?}>@%K+8jyDYdtVQ9{k+y1k2d2~`rJuY_fgR*QV{PgoNz11$}oPWXw8IZGnK7!>7 z9gOP?2CBJ^|3RqE2$KF&F+}jsONkuA4^hv73C>eKjdJ!=^J2co^=$0-X(guh9C}ra z?1X&_$AY8U*^9Thn4(*-$OzC?bOZ6akTLrdaQ_CN()&n^-Puh@En3vzVh`CC^dn^9w&&X{Vpk zr&`&En%HnFeO;H|uvqXftuh*i1@4OaY`GSDGnbogGzIedawR>jtYp?Fz$<4+y^oox z z^g7>A*p2X#LZO)NZL?uf(=oV8gRdEL#0rz57Oa>t2`X3}(bO!3LJfODxd;$0Q_Z!q zNgT|EoJdx3`F{RZx2?*;2QJCI+ufbDJ>1wcGHb8SH>@Bvss>-a22Vc%df0ogX45sG z<>tX(i+9{S_pHM%wDXIT%GN{d*{&Om#!}dabAaZfL5?@=&8e}#BbN2nUEPFUA*)Dul0kTCNM8qTzI) zvWuKHz}ro%Zr!-_XYAyaw;Vq^udHWBl$eNPf5X?<*2k}*s5moA1I2F|XBif7^ea`` zden8qr<>RRKF?fP{Ex!bCbGT;9d09pQ500;jPh?RRbvD3zsNo%YX3779r$`?o&Zo9 zj@K*R{8pvasQfR_5;naRBIjDzov`6#x7HPv+Q@Z-3edC}fWBL!eYC8+iOiz|?m9e7 z)&*cAHB%V`Fm7qq0D}wirZCPYry{Jb-8p0X`bIxxwb${|-8>gH1KU703864zR;g=G zDOd1dH)gN}6tX35p?;2lwsv2Xu{;#x)d>Q^v-94%yk-fy9l%g(0D}Q*)8lWmkmBLs z?gJ>X`r9vTAz*~nG9ZjNI=2*d@}O+LOuER^rCA?Yes6|13Ep?Ywpcs-D|oOpd=L&8 zuI#>u(3I-{EoQ7ti3vr;TJPt9E?XK`3<8!Hxbf!biP zil75zF2w+iD@}`*nuJXFxuL-^_PYsZ<6oCQW0Jer)_IG*ZVsRx#%?nc*=nYS+wISF z`ciDK4t#+n`3U(ys1El5z8V&J6Rps->~2RGL~Z>M@LWJPQ#sYl0Pc&gm#|q)D#ETN%EGI0l<9>ZVf!@w?FK{m z!I)}cMg*L}Yh=g9E&kg>`C!kKCiq(z>O@(qpfQ{ab}a0}%A97l%>`-Fu|Dx!p`y9U zXpvN2PTmmkKI!=O%425Pct?S6v6!ne3%#jF^pK)zi>f3O&A<0*rj29sGaWAZ&%A=kkPtp$dKg8%PccxHN~*3xVTZ9whqQ^O&PjK(W%GH8%C z%Eh{M)#76RQJnXRs6m3hM`50Z!aE5Q*pJp|pqY z8F!xq?*m%yZKRreCaoU&W|!yt`{WJ334h?|A7sB4joK1q)Chsoc%{#agVQtdig3(n z4xYXdw=M0_{s4#kD2*UYd4s+Dg1j=rZfuBvLw;@IW^P`J(;P!srr-2dC7$rg0ypdO>0Bx>Skwu zT$7rWQp-|Q67g>XN63L~aNf}t>S=7G==OrRrT@L>S(i$oC*l09RN@Yi=G6mMA82+t zd1R`6`)pXBZl~;Qd(m?al}~XZLO!=c;2ktanI9m6UPsLK|#jysO|tlak{ZQq9ENAtd-0V7?_t#g(#NO!SbXK>N1t9bfU$N{>$Ni zCj5-|>}x^}S34jne5o>wu_$l(UbJgL215Mtk8OXffEZMiBsa*gQqd9yG0TIbg{yhep1RoFKV5u z1+xL!TfQrcuR8w_vv>)LgjwZN5P%-D1~Br}vj*`ORkt79-vLvhvt@dWzV1~=pPy1r zGJeGu5^nd6Jh&5F_yr(?WOxfNyXE%q885BuHf_+gv zJ5LOdehgQ*r#l&zDQsM#c)B$=s=LrFoiYUI_pRc^)qII4d)05pjYABp_{8GG|F_M^ zN=?A;>6QEs6q4_32<7qm`s?fo%E!3w){TN<0QhRGOt?Rsl3|;7CwWJVUhQ|yrp=oB z%ZftAsP^!RTVb(0WD;yve&HK`vdL>6s^df#jW- zT}FvOqQZXq_S(9kISoD58+fN;fJF%8sDM*Zhs)zn-7U8tc&(`I^&baZ$%oQ7ahbae zy*08uU^m^vzjL4PQVTIpYG(-5tSUG!n{ca;87LJw#gB^YoqTUb;k9lWOH-woX6hqQ z#=Qc^xgXyTTn`EXhVZmxMAP~OND<+To~?k!++prX>{({{m)={oxJ4M5@DdB zI^x`V68uexw)NcR@np1)?pC&tQ#FrhcF)SF)$3L;R3yaB=f@9?pfe)H33&x(x4a|> zF3_}yUvzx42Z{HCjv#{8Y5Vb=qT&Q%zLE3S#k*dGdofG?GD$DG-h7f`U3a~!IgW~f z^i#Ucaaoq1R?Qae54=v?)?E|fl_uBzxS8%2^uz^EggMw9qLYl(nvy3`UD6Ah_2rE8 zoIEA#Q9zbf3xANrJ9a_l2UzqfLJ@-eAVQT{fyib-p=>p6CK8Sq@~LA>#Kxnb@fw4} zAH!5T*GT3c;!WpBij2{qWts!Vy7f_LsdxmVR!f=cw9T(SwKPNk!6+CR9OB~FrQCA- zO_7Z)<~q=+QJ+k|{p+Xl*1!d*&AX`*N_{Q!84VWKHF51+A}&aSkO+S_wqo1QQu0|h zzHK4i>K;Ts`x_7po!lcC*pm1~Sr)C)bo&Slq$6mx8AhZ)2@Qis!0eDQBsVfh%8oO# z9O->KkOuVEwTnoG3hI*9^0HLVK+f!8Arr>*0x_?BKsaZ8TTUDIeisZbF~RjB5DyeS z%KKXbSngB3mp2*cR2dHQTtbHN63*f=7a5TqQ-pzLC-`$|ZnC>Y&tG<}AG9Aup)<-i zINiF?mE$$=FI$Yf?=ZYAEM*g@yk{2*A~FgjXLoYKezWSm4A_*!k$GF88oh3i=6ULt z3z{sH>T!{6vT8zXyZ_%bN%^=#Ps%{v{hc08x)J9j^G#`S-{y%;r@mr25m10^{qR%+<)3m9;r1eKG-5^vky#LC(Y7|Qr2opdhLE#VOCX9EwI0-v zmP4?UudQ8h>nI!E*vr@|{dd4Q|)2u42=NOsaUFQ6*pK{p`^)w$ST zm+QcB*- z7$St9D&QkUB&=m-+~_mpX{dKfOm0w$bVY(8HX%?f=in}=gXPz3Vv>%1Sxa_!WNMmU zmY18_9lTw#C`%-KmWlhEUKJ*KKS07Q9^63ZljOIBaLUXXz*!gk$Y0H$jqmsX5QBxb z`CzFG=4Hz*vtlu@#~yVM%$7;>g-Dedpe6C|WdCZ7=yXh}MR8%$w%d1mWX8-j>ezK^f<*kQTMqX2-5-;)It`|)N0+&*4j^5|=$$Et`-qpjaWG&~#1hpFun zY<}2;o*G3m_`bVX#>Lzg!JB7EKmN1yBb$V?Ej7RAnP;+l%))(^~C)m*4~vJzf{M@->xJuaURfJdmEX8bkFn{KUsBQ z3T1t{p7ECnCb&!odP7c!&9rGE_nJ9PDXrsijHMx;>s!Z&ei7FwiTpQS_G(^vOw8PS z_zBqxe|?hH0vgtqxHtBUPs-L^Scb~b2-w|u4Cjbqy4bUg6^5FQ^>DQ+6*f%!X@|H) zMFNDfod|)gZ%{`&KtZyaD1pNvJXSxgRCjXxiqD+HqB@vM?b?O%gLtAYSEji4^UC4x zwp$#>6%zEx^WW6}#9RS~VeG&v{QXjnbi+z<87_WzXBD4GYH7^#Wa>oVM^VgQEk=`Z z_iHkT)?PyfO-FYmzj{tpeVO~~v1&qWhR*QY)Bjg6`> zeaUzZjt)?ZIln2l}!XJNx)MEk*e{Kg2#;*(aaq+LmpucT&f8?#LWH zggtRcqg_B%K-+TbPSbsAGzd-7BIQxcN)h4_Gs0O~`lQP&{?XTyV<)V#N4;< z&}3tMh`+NW=mZ%qYD6>V@H`9sqz*!WiWt*Wi=r2k61}p0h0zKI~Y&nxEf8`;83si6L*;(>_UN zJqJhf$-u4rSM*MI%yCHjEQ5tK)llXMRg2Aeya9G#0wo<&#rf4i&J4^MH&N+b%TX40 z&+~i%D^%bmr7eV7x~Y_Es^SfYL<=IY=lvxJ!=rWbPa5`PB>Q_ovbE^4me7RR-2^&q z6o6a570Z)gx^|how&BmBsXf`C5_qlSxRs4ICE)?h+k z3giY3VyK3>`YDG3S_(c4b{Ns#Z6&z}Fs>HdxoQ(?6<7J44&h79lAs01!_AND$yZg$ z3Zm}!BggUd3*YgmjBO@{-~yJAoylZNt1CTv(fO8iWqf1fkBln4%uy}Zdi?Lu4f@u7 zQLtSTul5#EER63$kBTdb)wu`^u4xRyC2V1x;A5YZ5-ee#?EFGZ!Y@3+Tr(3PT{C!Y=+|YB>Zs(pTh#xe$z- zk&5Va^7LSEO-y4RiVDaX%Xvc5rgAiHwn7|pz_mY=^PbM^DdpkPQw1v(sSuG6!qxp&L`^{p`Bq|La;q5}m zBdPKhIdlWxd1Z5gBl!npq)cM(BBS-?|G;3^CrTA*EnxS-m9JjtbgK8T=z_H2CzIUj z#Qruv9vfLL$Z*jL2HRe#R$2qBDx$%2(&7a{$t*DFH|M;mzn}h_(#9o2;#x&8yV_X3 zTFP%v%Fj6C6ZZJ~Yq7Q_kl{Tx-+8@-VVqa4sEj390Q-^n3VvcMO)gu$IZWaPD}}LB z!@qf2g)l~RZknS5@T0h8KFmk<+`x`^<0SPE$tBj7f<-x>65I2RleJP}9Q6rTT%0#< z*z7C8WnZdG^AJUwxoY=3B@oC=GHC~ETTQHFz&EQN@HAJBu7bR^_%Z41_R1nlg)Ln-E(^s5w67h44zop$E%kKafloc~7V)1hD{#$=uC zKT}cQaiJOvDurSQa|k;QH&p-{Dh$>>E*F-ldncvAD6I<&i;K&lcHbgD)IVRcKm|HURev!GSZ7xA! z%9Qk6liQ;c{26snJspZ|sbuL)^e~1e4S1zCA~H&Nis?@3AnysG+Li)DXdRElKJ%uw zzGj@~35oQs7J$`V5y&;qClAD~(z%(YZKoIE;kMGs}q$&yX z-EBw@`S``81ic?jYEef_*}`8O)wxU%HfQ~(-4?_8w3|B$+B5}18-ri-j?1Mp z&-twEI>T}TeJg}AB!f)*|5tb{+yMmIP8G~7&G|=AHd*?nYsv2|L03q{FYTxxr75(H@YYQzz7Rmgr8JcQ*y90jB6I4v(vl@rSo?i zg>ZM+rlDCbQ7PEC7Olh{TzB)58hHnru>P43!!53R;1==N@A}9LDYypDs9LRcXpzdI zf?`UBnsZwZCbp4Q?M_l!THZv#enl(5|2Q8gVl{p)Z0v5SSku?<*If~cA7O?JWK(d z2;o_`HF{+}t(lQ1b<*^9q}mPe#5wY3&wm4?z2C$-MMXh%h@XX&OsTe357Q}9QaDW7 z;Ln*?+XE1OUa?J-6^}rB#h0NYFx2&omI=gEV!c|txX$mg5P1dJ2{0)FH%<~^POZ#leVGmPazHZdCy=XFrI&Um0y-3!ut z5ay>7l|%LbH9*S0jaXG>C9f!=;FkMR(t>AEgx%fsu!An^q%{)KzOLSP4|v}Ow1OVf(*7cd)2_^)Q(NAqbt0 zC}0DVn2ER@QE<(D=8PdzMRkWRHGe*Kk786rC|5{qpHI=3H!G>rtf{z- z>h-GHL(WvZ?qr+}e;8X?N%kb<*p_^}w5BeBV6Miq$HJb<4&rSq<26+sD`Gx37Q76TEQDauY4kmgFag*NX0GCVF~WZLgKTgUQ(5PXkMt3sfXc zw_RO10eNRN!;caNOnh9Secjph;LE2#;3L^a>cUEv{ZH=u`eEp>?6i1^+02eE$i8zI zsm<2)8&e0_5DWBs_wVrD(PHKtd+c7D6<_bO81fKfgxXUEQHkB zOZ>@8YlZhV0dXh|2{A(UC5Ut{zm&LyeWwD+9t2^#BvDrkQY@H6$-saHaj&?k=|Agy z31u=ti2xi_Jybv~HJc39Y$OmoFvQ}S%MUaIpFrQ31r zQ9{e;Xi~FS(rhfgRkSvbZzL*Hs6^c?IK>>xLcPsms62a_;?ylxu=WSG%A_5s;T|C` zS6>I3#TOq+Esi}VfhFHp9ibsXXR1Bk2X9bY5mZ~V_^`}_lv}jQGsTF435bus%FUKH zSo86k@^AQh!bG|2b4H#JwrqXP=m8_||8gZ)fiToO3;|lW;UAIOsa$9ir)sU|c;&sZ z43G%kwjCx~8MDVAbxJ3t|Dt1$!WHW=pORqkoLM5Y<@QkmK=n4BtC-fhq2)B|`G^X7TDx?0`^(2*AJ(hVkCnQND0kmzc_~wSd zi}_uIyy%>V<#MVBDv#|I?s(iULFrs3J!nvl-vs-pThBey$=trPslCqy_*r6lqt=54 z1B=D+_{h=u(uL6jEQ1fYyxpzas}pP%dRZ3{_KC1#_b=pkol> zH2p}lx108pJ5xM|<)#J*%@e*x6;IG+tAxoU+MUuN`b`eD+b80B-Qd zIz#!JO!v#y5NC_?{*PIs^Q`)ZvP_-?_u?9X(ROre9hryLtQzoCo`W(-(=qrc5`bq? zqwx;H?2p9fCuGFJ)+!hrn(@kVR&J6hnRA5io0ZpSee|hAJ>i(U^<`r&I?D75Py2#G zCs+h#82dd=8zduyQC7q$41beKI0b~4Ihw-AEcjN=o9}K&i?gEG)YfgF3X<0==IDGk zJKSrYBt|=C1=l$pF2y=T&kkk* z{`z@K=NV$ZXME8^wV3Rs7Qa%hHf;}_?bW~uLi{z^;dEIB0rebnI(|KlW(&3<(lTHG z9qd0%iK^}&Awumk{YlznZ>$IF!8*x-3?y*X>`-YX_30MzYF>bdV%_40pRrhhG5H#Y zbfH5al08%29d-ZPsB)bVBU@Xy7?X}`14$($3&zKY-x-kn!d(B-%h?+XRa)`pU)>t< z&Lh8v7F%L!r<0Q7lMaAd!p2l?vd7Tl40U7CE~stB2jpG*W(;1Wk?e3C6G8*F>7KL^ ztM_e31o|1%3NKVmGY*ljBlHpeqt3ze76dN-EdcYm7M?4Oip(wKF|P@O+j6{%G01FflM{e`)(sp3iHeUZh`w)0PA;$Z}hUMdyP~i1SVTfbr`~M(oyjHCf z4OgpqCp(Le;H%02Jd!dDEbXmzZsCt-*hIvFHLUU}bZ*o%I!bWrJC4Hfx(sGXYl(G< zU9e{woXU>fDMwGi^Oc<6_M#QK?<&uWS#Y(E&_j?e4k+mA#8c~I(%o8i^SS?nznKPF z$Lt286^hWlmGHP#FWLUxT=lp3E`qY;>(KBQQjeEzx09{O0q>^{fzrHf(?RX_+<|m{ z1ywZXcxk1)?r2yDmCG1TClLVd6aVK46la+`M=!Td1#H74)>g+Ng>8)bsL4Zx6m>3- zHJE(|eifgIfZYbx7w(hL$+0BSgzPg{xeTDBgC7j*#Utm|RIC(PzHPGyviEe;VY;a1s|INA zj*aF`FpiwGKN8j}5~bv?&$<^@WEmMbIv0m))o=I)mbibRni=|){wH|Cxz1pW9j>Zd z>|*zsr?jD+2Mb6@5?|7wL&ipc@0v2UaP}SMBR7zIeNFg9yOttJp5xH&k1P+r^mGavGH>fQLVN`O`-JJGOHJz>cxzF+`2~A>2c^^$7Lg zT+j&|5K24Eem@jWLuKuBDk}Senl+;&l%fL%e1C&rGvx(?!5|?RIlY^4G_Fn$HOF(R zN`_*20GE*B^+?&XrkuTa-(y{1Wn7oBMtSZSkL86_QH6DO)B2x`7_lrmLv5BV;y|S}E8|J8EUg!T>j?-qLLNu^TRn_7i)+#nGdRD;8Ti z9oYN`Ws}5|2y(%Fp-I{SnJ)*09IpQ03U#gskAy3pmRlQg2l3?tNFz+hSqW_CJE87&5;F6|I@mQvJdyo)}If$_k zq}a2?7vB=9!VRBI3@EH_8V?wOn8b!j9cGqbS0<}nfTn7ftAO`cHc_4xmy{hAsw{kg zjJ{dRi%~n0wZ>y++@WEZ%$ZMTyuQPU?~@R)Bj~q;G?95a<*AS^i@QD$ z2ix;`xLmD6UDCMi_3o(T3=+JeX*_H+7(zvi9wch}h7(o;NkovhlE2GpfRZN9(SCIr z7ZR5YaBv>7W+_1mj@YVpiEWRXF0`HZ1aJ17(o*jeK3N8<+J?@Q=CQ71S9i4?ww#PK z!AYgCD}=5?NladaY(5edG2fj4IB*dR9z7BLm3Z@6-c?vvJx@z=L$DXDxcIaX=jsjfNR3MVw!QcdWh8KTYf&~wNl zCr{wJy@8N*FOZbnSq^}T;UYmyg9&3hv|>R{CM~Q43qhm-IDEusEy^i<7DJV`#`Cs- z3iLRwd!Ub-9o;Scq5*7%@>P+G#}6^?1Ov*#QVtU4sZoM{3EcI4tL+m9g;csr$+t39 zApi$5#E6J9AE9z=QMFWVxZA~VcV*me?WFoq%@Q4!BdE!|C^n~_R?KN`uTvF$>G2`b zPBT?k+h!Tv&@PT^lv?ub>dl)YXWU%vlqL=Nn*(=KY zWJ01ApeGFG59Sm9gaB)DAh8sn2+jOkMRVRfW6RIgoi!@(!uN&Ai++L~D<(d8;FqS6 z%G-3<3=0RSp5kG@d)*j8;}BTtQIFQ(3sN9Be+3u_(^tYg%KCcjUi_p+EcJcoH| zB3SSrB-_sTTnM8=D#uoSoN5-$mFuvJy^I(}fnSe9F{VAI3i3yLG`vA>A;kkIdXZ_; z8%&LoE7iQa?asC+=g$?#0QNKWYgc+RT0Z()Yb39IDnHc{_1V87J}c3y-Xm&pg}&lQ z7@0{01-GU_t=91eGyqyJw8i7H2CatqK{y2mt(GU!j8Qc|W^nZ!Jj?uHcOfX0iOgTqNX|{}EJhXVC?QHd z?r_@>Zo-Ygwr&y{ZLw_$?=zw;`Q!(_hRB?GqXFXgoiZwOtQY-YsP3=BK1R#5L z#licDQ_T%iVNI?Ve%*xG=)*-B%$|L9llMQTMcUoOnpe-0D;hbi|K8;7+fCbAnFD9@ z$6drqHccuTu|SS*D10n$p0G>Kv3ET3ug-tMh?3(${Jn^uD4+9V@~+uPigMr)SnMg_ zFuwmZqAf=v8+cNQ;eo(9%bKk)2P}j6=1|6<%-f@PuoeBH;U&?Tqh)HC3L^wY)lyBW z_IbI^JTn~R!zPMcsNzSZ?;pRx4SyrytX?$N6tYauPwx8Cz9;)JoQw9yVcapfcY4=v z*JpB>R6W9FDVrsJW?!4mha$4x*mM8*YfMif>pujxIR?GQiFa z7=)uWg~aU@v@d(^5B`tMmwJ-|g|}Dh*Ir;yVf@{PtMg3OYTybp4dvUe7rz=9ejdd1 zIabX%*w_dfM$nVR47*Q3Y2r>&pxdM)AotSkATw`QwUpiSKU(bagoWcy`gs$@sb>qU z;u)nk7q=8KiMy4Km3D|vyW81z=?q10xo(b1h*Nl6Jyl?BXdInx6aLB==J!SFYlhM~ z#H)>lTW~f)Cy^sXu4yK2JmUhPjMENU&4WN9>@|nW^k?_Slsm-ALzFloIt>c-2*=L^ z`^eD6qcY!96AHm4Vul<1bo};Bttj;Eg!uz(I(XBq_SY$L5wSoy1Px@{r{y>eQ2Ivj z6!_*t#X^YS8V8NVJLxz_C21yCzes--^^`f-l>^d2$(Km22r7U{bQ+AAX6k58__mbW2w%%fP z7~yqtxp?Sdi)bmiR!S_8ke2R&{3;cbbvy)h3TB!$y7%7MRp$jar4! z&m~27old%tm8KhMSl#oMXGbSmfceFwzpElcS3;&ta3c#Tm<_t5@dED40t=P&i|xae zJk`#~LDL7qwe1!}T?=KaMRqCdjA*rK#zxNV>)}sU>)XhYX)t7Q-tfJTfFbTjW^VH2 zOXkm-dJ>?VxFu2lO4xLLquu>7OuHt6S@;@2Q!9#6oMHTB!|O2> zOj~92oQs<;OxO7%Mx)3^JknfOTix=brMbu|ww;7llYF2jG8!n&;PyGr(~7&FuOdpL z34zB?Lz2kUln3D8K&gp$Afx^+cI?b3U(fEnxymhQR8VP6P+DZKT4$#ZtJGXW^^vV? zydi-f`R3{kNSngc-B!AIeCO2_@~;`vCJv@~H~%F!+5;#Wn8}8g=_D;weRc@ZfYG#7 zV6)&X&-So!-?h+{=%mMn?(naP0S@|}0f?O3-?wh!VojaNHlWynA5i+DeGM{!#c z&hbR#ua0-+=yjj7kEacIc|?8u7-iyATUl`J7Yp5h8#O4sh7ZWC3=kR*EAqjpJG8H* zA?W{K(fFZuBZQu~D%4F>)IicqHLddp=O3?B=;kG4`V}LaOC2~Gv2Z5&23g5AOAbIx zvTW%Xug`c$v{9T^yM$B9Ek-qsRTBFRkv zvqj^yr9JLz!QY5NeG$BZD?ousB$vSnRG=GG-93E3#6RG@gurrGVK~}7rcr`FaDCwZ za+^hvN4O|X$cB0WEf(o!dOClAvkjiXXi!+herI;)lBZAT1X%T>?xg9dZRqgTAqCTr z)l+8<1|6IKj&oX!XgC~T8H>TtD@rd%_3>|gfL1`-CyB7JMS2p_0K-+&yO8=?_X@X? z^P)BZfLEU2T6pw*MH38fi4*VA+i9Mcq`bD|HERc5%KPDAj%~H}RrAQb0o#!T2;l2t z9Jz(8O7Zf&G)$jOqJ(9FlhFj|F@lO*pd15*-s|d)n1Cxf4 zbdzHDutu7;cvrBKEh``H;&?gIVBtC=GGYVn!J4MX+evnc^b{qs}M8$$U~Hmo`oWrV>=haB+cqLY6)x zdxEWYrfqoWqmLptu_-G7CY6PESzhP-^N=kh07%oq)hwf=5P58fe0ILJ0*ezMfD{t} zIpH5W)w_lTV1-vIJKKjt(4xU$o$6rjDZnkQ!FrRbw!5P=Hhv;$1&Ol$tH6$Uz4FVT zW1Cxou z#mvHvi9lU)naU^D0%q!1g^fmhoLL68^Sa6Xc5U+F{+b+$i)ObmH7C=oAL~)3lCSxq z%1e?hyRVNTV7zU?m8$bXB3?p-6Z8yq`z`pY;Z@SQalsM_r1Pj(6y`Z!^7yi^l(H`6i?h;ILL%?K3PPt1itP_;38 zvCsO}0o-z_OJ^9BUW+U3{T+OeZoz9W391YXI7Sdp5efhNuJ9CTZnSDZ*GSYAX8`}J zQQ-T6T;uCeyF=gLSO;|xO4lZa0*%fT76q3O^EF)XkyP$-N68O^OdxgxO~1=l?K?e0 z9s#+&C8OcgmzAIIVk^A0OOuEJ`ft5o)$jRF>lIxq4H`sdp0{?M693Hr8;Mp+KYZrP z&~{5gGyjxokPtW3Tjc%%+kY7L4rCtpVOn@I%m&N8{k&tMSt+F0+qVaS{1_Ac?DLO) z)59LlcGmd+K1S5)MWB?Ak#FREz1B5|=P&dB5QTBk0(sF1d_`4nM74SSb4tHbUvs?? zv|QMjS3!TmO>w+&loArFmfCFFhWozhQ)LLLZgfF;3b~`aI4$@;^E+8^N)u4kb0BrO zAYg*Rcx>!H$Qj#)62I>}Rb}<%Cj+44=;)3{08afrP3LIxK0xHC0?f@Zzw^?+*s3)} zSjY|SB^79rgeRqUhNAR9(;2H$Tx558CVF5;@kCPE#PYb#iXx6vbcPED{(Q6{eS>#T zd{Hy6dl!Lui<`rfFKGy&IwilJ*Kk>X26q=#~D*^sN{9%`9JJKfuLSq;| z^0{iMxbeeC1lmq(UDG9Or?d_D>vB@=>3JB8$UqkHzt7-+mUrLg942c`vu$CN=A@!v z->x%{@2Pa9O4g&+pp`lK0eT>Ta7h*p*dbMepLk*`aQtw+%>o?uzjBydpRM&D#_RZ| zZSuE7{gdw&ZAQ7ek`W)uWPI?j0L(9EEM7NKFJ$9`PTf5E%CWF;mc{8;twpwsgh^PM zWVX`gmtw`jX3*kTu&ZyS6e*yJmyYrkdaJYPN>_-GQl~ZCtkwpAj`6{P23KFdjzeQP z1bz4^%5>D}4&bGEZG)bm_o3Vnslqzw>)Bf>T0)>Y0=j(FN{OdeO;%yF4e#xpJH5Ua zoY#?G*tFDRE<=L#sX}GU*M`{p^^Q@bqDX%jiEmb-D2Ig0?!+XKyLSMC1VqLo1)s@e z1Yv84REi4#xZ1b3B0ug=E};YO=Gp)G%kePL3Kurdl%>o5-3(<#dJGt-4EYi&EMiWHX!xeo%v-q45yJDYn|D{ZDI;J@^Ln-9pAD${~l2@P5eFiX3h*}a<~LLxI9>PKo($h)nx(Bhop&D zY+*iiX3^{o+I51Z`;cmVpcKTG&MUrw>K&!7uPTvSxBd)7TBp(^ko=6z-P@ZmqZ((8=xJgyT|2D&+uy(`% z7e>GJtB-vD=jOr5^~S6MgsJrvj$M-pt!OMIv<@LYV2U5C_eaVBQB2griO(X_gZ7Ss z%rcG~pYxl-`yu`IFgKp2>u|JpFc5hkJ($KZ-IBOdrGmHo-tLO(=bXomdi5LmF!$@7 z<8v<-2F0}`+_0{h8QGV7W2AC<@kzQ5u(6kz^tG|raU$JwQ3w0K@kmmXpWRk9Gb1hP z)!nTKK<)W3XR&|aI5r*nddq6R8IFeEB;&zkHD`xJNkSXb$W}z(G)SU?0*Q7chLo<3 z%s;uTSaqB8_=b;C_F%Kq&M3N44oGb-ZG9YWhQec6N{PEaRC#z!#yQYHl_pNd!0Yk# zb14Gk>b|Wa$m-91(X!H+0IPy|kc>Sh+?U|p*il}1a9W1D@jjMu~pO@>gAiS8-G zT`I!n3D$8cKWH|~`+6C8jGubR)L@S5O+WLKm-qrADo(bYp-}tsHMF}~2?IeISs|HU z)k?c7NGT(Toops@YtX-oI0(VPg}kgU&ad7@TWU?xYl^DU>7Y^5!GSe0_=rD$UYC2C zQ0v4eT0J2pv=wuvCf*Rj=XNNi(Nrq6{~f)`UJ%X&XlUSM>b9`-aaV_}Ll?~m5;a37 z@D^jYs?$>%U*q-`P^dB`0PY*xt~L;I+^cI0fv)9!M(_Q#gzdr6D*mc2W`CN>NyGqU4VEK5d$*5DUJyBIaf(^yt968^^$mvW3 z%%MzX*D=h5)J1WVfKl$t`x5|SI1(v} zIPrqJ9zDyW1P;lf;TG_-2v=Fv{O;iy=pvD5taPq*NVe%t127~IBNW&9VZ?=R#D0YU zSR1w!R;mcZD)R0?=p+)QPI1zr-PN(MGpO1FQ1+_Tt8muN57v2&alr`c#Z%18D-!|s zGEnCRG>ERRn=tY5y4s=ZbEYxtteb0Qk_AUNZb>r>USer4gi8cx!Swqd46TLy6h)by z4AP^*bx+!}CMF@+;@iNYiRzf9GjsGFq1`lmD>*%U<_J%Lq4zwaiG5povd%aDbLzy!~360k~O)9a48N z!aCW<_MyOZW<0Bg$`hvFjzaVq~|Bx z@dh~ndfzP6_C7KFa;SG`%b>I)7=g`fA0u3^Kg}p*9#=b9llLwVb2#2u!N8@02*`mV z-L}Ip2Q4WJtdDFp;%)r3f%k40=6qL?Bw-TMU`9Vw6Z?A>98UCEdo0(9!d>4qh8V4r zfhk%wDlrFJWqoXBRYF&j_NOhp$3 zB&}dm6Q*#1-PH=w3RZ1Ou>4RAPf%4kTF%-mI@~K&=($cse|S6ZwWYOWHJh%(bJ2Dn z%J@>tM!W&Z%E9!$9PAshPW8}lq3srki02n908Eg+m>NIl2f8Mw1uQ|_&Q4<9wlXJg ze4*@fv_>ePir);2>a!5#$(Kw0&MOj%gfg5;>w z3EZxNrt#R&&)_U;QPN9;*B;4A(lYx<-5Z+(WA-(#woTOiL41|=h?+9zme_CM6I15b zBk-nueNnrCMzD+CZI7h{jZNWU04{*~35^_p3KIek`V5mF!qF83sdE!*`jCm7pxb`- zMrYwmB^gP(v%S|YX|$W_QQ!}k1A+96LL z(a+#YGi{H3u9_sXQHV6et~?WV+>dkE>>G<^0=#k)3uUG_v5E~F;7LB*2dvy5&MR@w zTi^Q{m>(rhwsxs9vK4c2iCR0&|FD$??$bXZ$dUQX;Ai2rs=!#aF~CyhMn?xF;)D0< zR&6iZoB4`=l7_LFp_i^6tM7h%L$$=e#1!G{RTIl56h0qk+K&8diK5LFds6({O zkUaG=yP8Bn1!*`WJ^B`*eEpU>h1sO-C()_k><&>{)e>%R7kaFbt{RwffM=bF?ij&U z%SMvyX9%>){R$A&dXkZUsA*Gt!(V1)krg|JH8}DN{{;5Wi&|(WS|hcM{>mjO6neXoiJ5d zg158g*Yf>?-0lMyC(7WuMIHp+{jt|6eF;0U$hbe;fG*zbS*N#8!Q8P;J3nYRq8y@j0L_)nfI6zj-OY3Qb%zvqrjhW|NXDBRcl=)RzB>)Kbep z$|Gw+tb>FwIr4%`ap3;Rp4MFaRaFw%<@ZFw!p7_ut-#dkx|9dbIcFM)NqPSXN`D|l zvMWLzXxlYrLu8ubJo2Z1dMGx*_t9Tf7dd(4_<-)F8N)nY=Zd&@e7}lo7&FyHP!IMy z5XVE*UI>2BSjHWq9ktRwQY||tf+eTqX>R-BtaKY3fvchZl=fYVJVY~FJMDeRT`~ig zJ?aYVzE~(WrTiWR(b<>Hcs$K5VHQLBzn9|$Xehq|W=72^vUZoBhqL!SGR9>@&o98_ zPjvLC>y`IN5newn_-5x6$+V*m5D$GZ*_*CC+=dtKQUR3YX{~fA;O6H75Go&Pj5MWz zd&fg3N-AW-&(S{|D&biKG{5KRMLz8tIQ8meWp7?5_e?z!$8hY3>-;GprggA4*el#R zDyLUkUF!JjD^p$|{Z^YtioX0&F%CoTWY70TT|s=l_UT#Z*{~LqMF8s8y0LzkNbd)4 zu}DI$w5O&#_4x~BjcSd?Sg|SEDxR89Q(2xY|3v=KF!A4VgNp$(TUu4vF_6i0^B5fGMYmgPaz(M@nOb`zo9}WXRACqU}xn= zZS|oJmpX&e=sG6pLf0{R%AutL2s};yndQi;s%RLtrQ%_Sz>M5XvWHMJo1=DOEY~__ z7CzRBTJ_qmUa=+7XB!cBF-GaQJKzTy!gpqondx<@D+4Gk#$*g|H@472b<9iX3-xp0 zdHSB+cZ|DPGbsV{n~t3HCjB=fo9`k5u) z&!T>e{Wv@|EXaE&)WM<27pM7!yET99(nR)_4K6Ka&>7t|r;L>fTE^~2Dh@o1*uN~W zwnnH)$1J*FmpisWl)9(Q@vXmU<9BAuA*y9dTr>`436k%0MOIN7nh<{>Oh#3*IxEaq zQY1><+2LzR{@{PA!+?@oHq&mmw*NCN?!c`wLzEUNKxs1 z?q-N2^9v$#iGifn9Lbf34K(9~Kc4|;^1C9M_rtoVYZB)!Qg0Dxa^jtq5|ztsIv4>D z3&unQ9XQAX#;aR7!A5CY#E8v>PGIMEpx7LEB?Q((?{Y4+Pa&M6p~v2ReFWE*l$gl3 zCu>5Z@Xb=>%Lil+fq&9~bLs73?22V+r0|!juwh6wE^m4j1D}{*qF{m>v-u6RK~^fi zQ)|T4cIcd<^B(%%7Td2kLH|i7&XE^A6$bM&NAspf(S~9>e-C}0V{f=Biy_G40ml4~;Br=l7I8!}i!jwpAL?lJHcuG@+2 zblZXA#Pkvh>SSQQcC|CR$$H$QusrY81_qzg%F1=*lO*d2+KC}+No=WM!m2@g3Vx(V z)_oXPZ-&}s4aM5%|HP$qkYi&l%d=3j^YY6U1<(vhqOj?6PgxPQfipX=k>els@ z6x~nqQ%6&`J43Xdj1K4+Gnwqac)1@fh=7JyC2H*b&VXmg z>iebgU21>*5`wK{(S9aq2>hCn2NY)-ypOhHIE~jkp9Gh(X}tvuDc`5KpDBaq+atAFJx30qrDq99AYcBPjwK zr2qiHHiNlw_$&Y#VgqFz64wspEpjnL0kpAGW3lj7G2~3Ds0Ex?;$n*lFkvdg%~5n3 z6lNeVVZq*u#@-jHV|aEmQ`6Or&C-_!T`Q9fk#+i^!dOi0t)=1%XoWEXnL`0x&Ue^%PBjJdyz7#YR%-Y z(8Ub=+y?Qa+b2SvA2fW_V@Dt7tpSY8LbaFgfVP`T#V{5^c+O3rWIL!`?^=Y)cARM{ z|7mjx6ONVnxwVZRw|@9<(J*g`M!O%A)69s(HkFlAm13fSXuPwU0-jtBR85^6ma zH(lnaHq0j#jLLNi5T-}Y>x3fL`%?LoSvFQ6ImHQ85j2bzgnmK^E`LBVB&(<^9ko9(E^b6IHpc-xkrHF4!5JNw=H* zkXhf;pPIjAU!$G|9MnRgU`^>a(2~d#GluBWJy{jUOKjiu>hX?xic=iO#5e{*`e2AT z3Q(Gp{Hq%1@J;;{EpO}M>gPPiE4Iz!q&Xb@B#_M~OBV~8)6Mnj?1@i?C2s3YcCj+HN2>dgBFsM2KqWbOUR$Ja3btdmfR z@%8?0H``D<98ovcP^l9vZ z1(F=|M^<0-?weNr$BVK?&?2yslZkWfa&>>i;9?0w^#zgx1Ke?Lo>x%b2v`&0iFSG7 z?M%_+fS%@@7#m}1n~aQRXPGJ!$emRR`;^IR6@VlZd#;S(l-cGijKqjH{Jbthz0!eK zVxoC&yMOm`9%oYHR=HI6M~vd5pK^0<2Je)#S!5?`(z=qji$Md|72$SmXV@78&#kx|tOa+cS4+Qjwn^3y@_XT6^@ z3-Z-4BZBDykNo~z5rl-TTw5HX^MA|pO(t4F<-&sYomWT)E0a287pOn`1XmM-l%hR1 zPC&wZ)PtfdLJ}9oJ&i>;UraFyIR3%?PdX;GiG8MrhZ{TRPzF@A+aeImg;8h-FN@|U z1`?khDM1bQ$4O@yTeLp$r>IjSc~gZzp*x9z2s|%g{a1 zayRdWymBdRz6LwZnwg;fPCQmsqD5|WC=#*!)XEDFA6Km<}0e_2DxIIFp z>^_mTQku?dh1Ex0>}y{2oi6@HmisS3NW^lyZRRTiDZ0$-iAd@t>Htxq0XHmbazd?- zWzDW}`$hLtU5&+un)7~hVHr3fmMO983cj@B5(njK`U`~8<>zYPvesplps_}L{cPM? zZ{@M_lD;NN(8&ankk1C>iqP(yXwWR*qDqA=b6)NKpuYtt7Y;@pP>&w9c&@5HhQFqW zWGJ{%zAXr!YvD1u*apBDKBO`eQH;saqeQr*eb-UL%E9p>D0@b zJ~UoCYeZOZ6bl!67r&bHf|6mV4?FpFG^?HY2!YuXVy$kFGHYE#- zvFX9w;|UMX#e`K8v|+<*mOC7Qrx=h0Hm70jElwi(<{cwmH3Lxn4QR%K1<7M$f&dUA z{qQtW?X9LJtUR%H9*~ck1-yM-M}Fq#@>z%>NzsIplW`FlQ%wV$k3l1}Llf=NEmO$d zbgfRBf1)>WnA;*r!}@;YQ$9Ro4vuJ1U0$DfY`lq?h2#O2Nj?jUd=&YeL%S0)Zm+=9-%ig6hoaF`YBjU!IB>L01lSm56h zZY^<;NLTjcGXQex>Is0k+SY{;TcqhHHAUf`yg%omQC#cxz=tbJtfHQ+>9t6T%_fnE z9!knZKXs@ESNsF>SBfLPeijKUEoQY^gYkSf^R;#SvMA;eS7DfDhh_H?Sh?8jz~Gpv!A|k(mDs# zVgR#{L{vNklDRk=<6^jCM415*(!nT!l!m7{Pc{Ur-BM$!g_UR<;=)45*{hbv&aT_y z{)Z5@?2T^EF>`#md%L%Y=8!HamO-rKKYqa}JQ~XOm|M}eWN0`;2G*1Eeo04wD5@0^ zvr?E=0yUf&#$_pZ5%3a{Ch7x4jW7`nayS;Fpc%)us!D_8$ z8z+knTq3ymf()Z_dbkG`&`dgaaNuF+?HT+Lz>Jjn#h_7M>e(?kn#rGA)5JOC z_gu1~G6gxyMbrxZjfaX@d^pzBD{JFi4gHJO^BL+sK!VQH8}wTr{N@iY78q(>upj^^ z1JYx4ONz@|72N}@g{>de@+nJs!t<_}JG^?FfFTkTDuWBuTjYg~4VG4YsNPX_~%8x zD+=bZz9w{7$$GqcY8Dvc^oT3bdI2HU)PCnZ{g0V$azO{xcZ7ZN>(|a>(b-^ zz(8uI4nt<}plhA8E4o&0L)qJ>&&$XT%XmaiGDqNX@h*Nfh8Y~?!V}<-LX)Y;Veo!x>THt_!=Sc+V-}aFzw4j# z;s8Hq-aU2cWM(hdkahWAakcBeve{M-25neIg+N)`a*T8hjKfr)s)Rgj)9}0V{lnKl z0&(9LepdD*3@+)tB zva)dMh3LYX^|O10BI)fknLFMlEEpN0zFHbId*9m8bx!Lopg`x||Fj zXosY>3M+$k*b+n}jv!pX2UjIYRr!Uc`0WnlH>jNHo=n? zsXzQLb|l|;cUHSiis88f`s8p>IZ|%Vlfrp4@bYgU9#Nc{JNK@XYi9q%n9iw&)ID_e z(X2hT89bA~iG#0twL9{)y@>xsoP*<EV8~_fn`Ba zfor^XNR%xP=xnAUFdzQjTP{({b+_ygaq+jj1bcTm>?^W3@6VXz%hGgT!By?bZ!Y)Z6xntkQkmyfZA4Ixyq zT?8kBwr+wG_6pT*W$1nzUhd|Jqh?Y4)E1DnC_C@yRE2LO( z=R7pB9Ff|i2<#~bLju!HCWb`;2tXznPuZ>`D~Kqf?;gODcvG zu}MX+hx-O7NuScJr`C%k&E=i+(xt8lVcHU8tj(0$8UyHi6TZc078d?gAqf*M(b}9N*Nm>kx%LTt9-KaFk!6C1c`-UGobNf;$*WE0q8+-A*#%5 z{sl^6QBcWVZhfaFc*m3ST(=6MPD#RTHv<< zW@xyQVYRbEud%0v=v4gB;WCj-CJ3C+E~QrU%iUSo`U)sUpcw&9TV%RSE>z9X>4-E* zB518h{+8~NCslA-r~?H*eLplnweZc}z)({=sB@HAZ798!$dcj;k||v3;W50~+$OR4 zeP15V-&#fPw){vt`w=a1%ubpfR35{GDv8lw35YBuVp z6xRzMN2KHEe+vQ?*!k2^S&>J@TNlw-e~A(~#uF(qJYwaUwd|Y?t6YDxZ|>&~^oCdt z<|nnSP`&RpC*?;gWllk>x3CDq#h+@?dE^EuLnO-Uz>+MwhX@bQCS77)XD}s|$;tb+ zFN*0Y$I=R$812WZj)40MR*}<@z&w=$NY0@CVd^AmQl3=+Tm&$MEHc}Z$#6OT(eud)`#d0#1pHlp07%({gl#^yA`2osyVUmMXk%KyE^ur_3B1(*ckbldLP zJeia{nyMhB0kj;X{ftMeT@68>YBDL%q0W9=8H{;WnXbQ*aYDuyD*9o(-d*nd_$5t*#l1q9L<15?-s>;p}ZKx)vJoMYeav(jNgTddGq^ zoa6IfqRt@YTom~JrTr(>o(F(aL_J+PLQrI^s{BK+m|5~|X>5MJVUUr%ZpT1{- zKv>pZ5$1*NbDi;s-PRqf#5e*>fqqfwJ4*AAoZV8CU^=xNP^c~$nkKc2Q?npdo=FPH zC_v@2!O?3WGl6<{zsVo=P#f$_x$M`p6T?gStTIUo@D9LIuEUD#0tI@!5_pNG-w)Hx zndef5$h{cUqUy6;au|>(cxDw{4vLqXJrq`@2Su=4or;~8;`U|+%Qq7UNJkU=Ij6s> zOKgi&AVfTmSBkvK1Mmf>{WT4z1UXrw|Jw_^N+doA?;zoN4EOMWYnN;6GJ^>W%v{^Xul1ies5N5b{26B$7{ z_{R+13OCkKbq2bB+f`G(WSYO!EODwF>#WMw;@cz5`!AijT0Q<{B*L`>DJ{JIFHbhC`?Bh`;u%aYR$M zak7$DfRl@^9zBNzq_Cjyk8!dd^xmGZ6CYMe;G>KCa-tdb(WAcyqQVi4~o0-}5dW^T}QBpLo3y(%#;iV(q`waT`ghW34cv(tj7+q0CAe*s)sG7LC!>v=B++OYOpm+TyD;kil;0bFtcJRLeh$5@Q6%wn zF@KOU`pnHoUGK!Scj(AW2B-JP>}1sP=6KGH7E9duo7E@6@0)p#LtHri`|;X$B}P;W z^W734z^=)J&|f!ha3MwHWd0c-BiV<<_?dHQ#jv+Aa{<7^RA^gPuFFp^MYA$?<0Bvp z+0tzn?U7zvR*hP~5r!@wmTI&`+<#vXEmXc@^0e}Vn#_IA9~}CcJ=5Y$Hd+P{e`Nr< z^x_Qc`*iw{sHK8MEh=66_*4~WLHnBmCw>Sbs=iV%a7uK6J5vsVr+++asvs!jRs=YZ zA^v?kCsiq*CD0nK#2ysizqQ^afxr%FL4AnA5}igN$mUjzh$Qo6%&fD=7{cV@l&V7;eP=e$@s#aX#uSwj)mx!0XrGYDIMK7RWbJV ze;52O143f&Q7X!fy!>r4opc%#tP~MmTvk5=gfnO_{m9_ibUk$oLRN9PiHdZ-xzEh) z5mKRW`@aKB2B^xNxjS(da+0Ua0y3mxk(zXH&`*kF$%1_T*7QUO0d6$hDZKj2zpe{? zqr&nb5S|gQ;UC2}q4ya@Y7vFnec#EprbK}+A=_zLPSewZp^;23AwpRrqJy=HgHTl% z4w_s};UenIRp?>#L8=W_y{ z3#i{k;d0Qz9&{MsSpxZLIr2nhQAe?jqU^grmG_68LPM>j2Nf}Qg`q`5XtSXz;Gs#T z+CVG70v_O>+&#fZL2GT#|ga$VBbI9*rgK32DxK-y%+Eg zA;WI_!xK$DH<^A|Nb(eJFelxOLQh10l=b0}1HYQqxt1he|Pq>Z{V(l8P(o~;5vW;%!msP^0m^{((HNKsPv2||Za?_K8 zmBoN9wJ8`$qJi2!KvFk=17|yGJ!kI~x%jM)yhslb3C~<-oS_D<1h*d9gdkbu%6o?4JBzk|Q!v=&S{^Y23@li*?FA=oeOK3F# z7@(9g5RV> z&69^V6o-qdx)7e%h6nh(fo{2X*JQMpAy-3aI9PbQL2R1RCJ?y!uSv6lTh$yxWV^~s zW@GEy%m6f{iO&hjlX9mrYOPL6@qFwGEswswm3@~gGRn@28{`6!j@(JVd}Ayd8d!lz zOONBQ;i#&`Bn_NJ!ffG%;R~EG1sQ!pg zAjSV*P)5)>)RhGP!f?n=E5=?AHaGHbVq$ z-()nnLtGqm$+D`u%IA||3YpM-qTYu-KU!n~(<<$phN(%@opr9X0}vwR15NLI>w74Q z1LI!|mm;?>bi+88peJFOSdYiw){T#EK?uc4J=1S_nB>^5)b0y=~p7K9$Y6t42tnpS5D#t&`c;P zXuh<678SiI{J4N?<09+!1m+rUE7|Us6f$4p4qcd@{g=7)==DW8lDxwqx;y7utucps zm?2eb!;CDUvj$>nM-Y?@(%6)+nh$IV_r^+OnKYQyiksVzk~=&#tcK;#$aVS-ACrOz zX}8>}@6W=;B8_)nfBaJX?k$6A`kxoG96!-v4BqqXc@~j7#r9QZoPR4h?IZ=aQ-=Gh zf@>1<^fXC}!TnO=EvHQ3w)^ETv70tYx+nnwdQL0^J*jQDc}utnr^;3;9!r@L*FUal z2@+yOo=YIwrLzMC{_jAWJu$Of7Kx%ZZgZ4z0{VcHFI+eB-FdCS@vAQf!b(GJ8go45 z#vVdIC4ZSVm4_JQ)v7+xqheJZzeohu^IxR&6E(TxMQgn z@iFDWQ-J<_Z_HYph!#m!5L3`#tm3MJ=`z(IyjOp0&X>yYIZo5jDe zObcULDt=KevLd%TD#ohue=alblHiLqj?p+XqH*-G!nl)z)I+$A1pXLYwYyHW>g!`m zM#Lx5K~KCk*LxVMK(@OwkRgm3RX)CBvyL{QWR_kq!}Ma+sSg>%*O4Z_SGphT-_S(M zkqy1#UgpPkecFCjjyhtR8eR#CR*OUbl^!L;Jo5+yPq)N@?eD}UG=sFk2f`prq2yDU zlWprZ1`$z2PN|R0+)Oyb&b6*izkMva2--F9EDJr5> z<0;9Zc=m+16^jMVLG0kqW@GzDP!OiSa9QWP4#WNZC1#6EVe zPx_s_Zak^vWnaUINm0YRx#yHRtO^{ED7b8YL+#U!?LLhBs$qm8q644^mPTSrsAsEf z@tc=1#e5+YuX1}7dDm(=6h13UCbtvdGVs#JYUtII3i~#%tc{?J>523f;2e|DBBRWS^cktd@B@`pQ$CI?R|IGP%t%xw=@DBmF!6Xa)+ksUCwMcCSFgU+-OCe~x7r`UrRrb|2~spN75kP<7^s z8aCsX<8ET%^y@p{@#9q$Z3~~pZj6s7aUN9=*eVWK&}gMa@_g}xgWe>RGR@qbdXl1J z0O(zepj7mJ^i};=*P>Hn@7LQ4ge>4al=8wK!F_tf;4&%r(qwZ#5Cs3f3DV#hZ`pI} zNob|r3H@iP0!KWZ{sAuB^*~3xD)1-syPZ{-}x9>vFr#bNZ0sEGX;`+ObjD#n{?VhZ9XUhI3 zSU2yvy8)ytl4vnL$QN!kLrd4H_G~#n0?hUI@ty`;XROuo%$C<}E#l#Q(VF_hGjDRe z=u>oWY1OsD&5wEBHl7~$(67BLsXBVT$o5a%>@BKqd$b9OZnM4Q2W?y2ahE@&4E>dv zsk>#~>4+czx!2qn?ollzq`3_rO5Frw&DZNoNc&Y;)b(`f@4*6o{$$PNm=ogy-ORp8 zPMk&)1A;Asr08L!BN`J#=%#FwS5mtjC6&p|!y{iE+&yTnmuDi=Bc<-%tmo_O`~zqk zrLqZGX%IV9=D;%X;c!iJ*I~PjyW1cv;l`PCGIS04zr#KDi&)DwcI@20H|vFq zYqA2Vftt$U zKk2K_k5TeTf$S5mO$PCq43~}0P&pFBSMRyDHa`zE0nN;&x{0GOm0&q@o1t0_PT@_C z8vs7JQUEwl8dqw-&Q@j%2wtI=0mV2#w6mJ}#gV(FwqVIl8jDdPF26gEPKxC3mj7DCQ74(8%q(c~!5 zKGw5!3Es98-FC!_GbkeDLHHZmluDXJ1`uQ55$y! zz=-a>;`*n&Dmda8jW%HHKAqB7Gs#Op;xzTAU2@dI>wIPr#F07{IQGe^Gp)ww>GU!& z%1%RMvs>_9h2%v;5zwLpC=~>Y@J5TbuzgFuxUC5%Qy!^C8W+eP1Yeb{=tlhPD{xb)jC7)6HnXL&iX7KG*Q}KA zKfeQr?N*1{E0xxT2P+=7(UnUz`>p6O0Cn*X-zpD2K`hG??s8uq%`i)D+A)Q%Tg>Ss z7lB`8>tm+KuaB#2O-*fBGwWx(gNOT0kOd-m*zzIfQInJD*!?C%7+vy@) zUM`IbPF6WVK4}m?ts<~AotMV6rVhs_(QuDCA<4(%@*>#43CrY;2A(iVXNgVcPvx7x zRx&}7FKH*eVXTM{=+Uzw-)V!v`m(LU`rYAM{YedunD$K<2rZ6B1)o-2saMn?jjJV% zj?Y3(U~tYgkg}e21Zt6OFY28gZ)r{n39D1`M@{lVB%Y#>AOuL-l4OCvMmL>aUGqCB zuF9T;Ijx6yhO{U8+6=t=_6DKDvJ1i0SgwHIM&kjXK0GSkp$f>1LNrz;#|;?p3LAz% zA-NVj#5PIpw6XPCCK+rhj`FCf7zIH!2W!Dcp*Q)RWfVKq&9}F{G)3a^6LZa&XQ7&U z*RoX8+mp&*+^OJFAEWD9tjkh10`la@H$iuX*G)WhvdwpK234$#|2ZUdHvZ-RHIJ^? zlZclMz?VAG`@U4&EPOrZQk})(#cKoRa=uGpeV-eJ@jdC`cpDbzBqHyYY%Z~41=l<%A`1=?t5UV1c0Oz8 zsGuwh0$l%z6XC#0EWA5I+H^nchsvi#0ASWoOVdA{fLkvFu_ZV^>JhFJma55Qc{{j& zhnMI1s*TOP_Ek}Jy73VQpEQ%@+auDvLcItv6GAB@avkzo{e4ci%t&1exJJEa_xSqh zv~I*#wA46c&zL?{fe;;Cy(h!cuM5NetIww(M~yIk=oguSj{-1M$_+^sO{$XU0pepd zQ)yu3%b{AKHT=*znP*5`VmsFOh3Rz$A zM?U%QLo#)6&O`EwK(}9Wd=af3!-Uz-1KF zDHR?xgJBz1<(39vm_ME<>?Gv}tPI~af*->PBgvF=JLvO2D4LF)QiMXw{5fvKQ;E}ehRC>D`fkg-l9k@R4 z_EH1{-gIgWq4H>Ypp^K6ukx0t_SH7dK)xlJVEmHHv@fAy`+mZQ zQ!~YT-cmBZ3$VgrE>}VY+1y$gL#kjYp2qdysbkc+fe1D^D^`iB#3*HThfC(|91$YhQ?uP`BN1&( zZaW8CJ>u}=NR^w&#%n%cZWx#85 zqNC5bfdd&oxJnxshPeW@S`qla6s_rCrCyL13-1O$#uKQ91J^R)8#H1*YCN`koG&M`hlW7uj3Om(^$FH3KjM4hrkH;BJD5E4_pZ|v#25~f z4J){duI#@f`!zYSXOH~MAc?vio`U?M-2crDi@VXr4Rq*Jy^jI;sgFjBbL}12<$b;k zgq#F%N;?GT_SH52(XrszJK-h7of$H@)MwR`u(;*HYmv^b4QJVXGjY(>z0P=Rbh=9` z^ltUbJ1@M>r{N4_V{0*8_NsD65E~d9{+!jC&o*ahZEv1m91B4csU7h4>sl-|6RrR2 z+Nr*Q@^bD@;&Vf5X)ICt7EZDAROlQ0^{f0~4+2S>ZpnfUv{Pj0H4GC2VCTT#f#cZR z(z5OSkZ|-~)(_QR1L_X>qMMEWEB?4(bjsCeog`6#1!Qpa9pXq<9NProGs)X0qxEr* zoY?1860_r*p|p7IBu#*T_BgIEOkqDcj5ebFFv9^C^Ur77VvI6r;|C6+cQ*6^Ew^u? zdrw4yMF3sz=BXQbVZ>aMloWTBobYA=zQCJS@~^l_awD!Bv|Dc!aQNKLlz?q zr2+TQtfMhzbWjU#aW&r@-M^<#uU)YDx<3w4|1VSn2NLEt9enyYa_3Sc@7+S91YlR) zDn~k~--?AJ(K+GB&|5dBE4#wX<|ep>UH+=Q8cyLnK82&r)BINy7}LCB&Kt6=C)iYKBG&jYlTVB3X;(LTqi){2FF__(5^ zBGSr<#d&U#!@@n_#NN@Ap(3vuiT4FgbRKGl#N;)>L&4?Uvv{ySylcgXGA+`QShq2N zZpbGITbeT3t&~65)5>KH_J4lo<^85e0*E^IiS&v=m5egb4Cd|H=;{~W&BjSL-r=~2 z(L((lAI6~Lq)$KPAbxymrjwMK-9}bsb8ryUqV@W@jPF|*`~ChEvmkO)^27KH!OI`u z;~yACJ|y}H9_-(~~q?gx;wEMOUYStR*AmVvg!MHiE*0I z5L^B35#fVrFyF-}2Z0liZ}oxj%d@~<Ws@ zZNH(DWJEneI|FQ@*}f)`GGahH2DO4Rm{s>kPgzw5Tzd4x0cmi4;kdjK0sMsc`}HJc zkXCHEe;WE_vY#0uX!1jvU9hQ}NAlq^&6Ze+0sL~dutA3gF%LVeT``XAMU$6jG&K|b z$CWn+L*A~sn+f8Itw<@1_zktL{*DRlc?5DJ)?RF7y}$OJm%66&cc82@D@4t$mr7JB zzjyJ1lsY+8k@(g5dqXuruDH~VDFZl?c z3eHtx^Eke_^D1Hd{lOTh&uPK$I7?j<*(m>V^Q_pYDowYq)dl>YFI%(>YSqZryh#pZ zw=?v2gl7z6@&4M)2S!UZR`f^!b?@A0JQVlj8B_{QCzZ~e&2@yf(Z@A@lVD;o8H@hp=?uT`M&3o0 z4DNH#OJr(gJh$s#lI6}>AF=o?M4a9&@X!B%?wVWxhO3%AV4=c)WImf+hKXPK2LH{c z2+*rBXRW|qcp%Bxaj0Md7SVGxfwUlv-)qwYAS@8~F;{v8^p7!x;E)O-(d|?~PD@z` zMJt=vuLj@zwb9X$t$COMj6*|r-Q4+6Xv6-dfH5hs5h#={tyOE}t3Z@T{V(fw$bv96i4T7jt@_Sq%0Qs8!oFjngZQ?~ z2mem@)KiWM443e=D$m5nf{X<^brV$Xwdf*HHs~=1I1bv@Zj+vQV-J|p z6L=~B5?uD|qgqT3)$?04vKukMLS9~_Ez36QLGyCX^gFLFs)#<@!UrT%FYzE(i*OK+ z!T;aI2bV2-+~8T&m2Y2Kq7R)G4$DlJyEMgSkj)U=2uus~H(a9-Zl5CawcsCh>Ipd~ z&yq65E57hKhRP`|e%GFnY1nxEHq3#kF`ezRp17Z0(f7J& zkJbgwrduPI!RbVL{&^tZYZ^Jgg5arJrk2iVGgaSXNVQo$X%qm|9PS;Vu9EsBO0V(E zOj&lq_&a4LivF~|crn6ZYSXyE^LNiwl-0!OPC;HDh8A?bhvr7S=4x_}F6ok1d29R| zTmY9nB!Wn~d%N-+4~|^`oQalWkisut#fE|F0FgNrt}1y&uYg>UFZ8NE4f`>0g&D2Q zYo^X#i|{J}dl6H(LAP9F;8`X17MQx{vV0KqKQA9Nu7Pe;CM5u$lBU=AAp?2!m(H&P;g|F@7+zL z--?PXIOL`=F#mkb9+1?M9pE- zKHnRP&uq4>^EGb?dm3AS2*_PBvNEf3ATmzq<;T+!e4nFURYgnq_0kjeA^vdBRhrGv z00W)IyW}^~9~VeRQPp&*WAHlJu}A+lh`a9K7!`PaA8W&s1kByb2y;ec#Dd zU_zUBfBvfqFb7o1(2JCrr6v1pffigeNK!<>Nc zpL-g#diQ?n{)z}iHQ#j-YXMji*h2ZLW3xGb#X}D^1BLC^M1-dSZSA%hSCwMFsFUEl zK>LAKfP||we8lc-*s|i2p~U4=70k#x+?>*4s4pSk7%MCltG!Y2u)*VzRc5QNK{tNq z7sxlKU%IAuGpNn%kkyY=fE1&96x~5NfQB`^raCwScRIUTmZ*c*ju~RBgJzn@X&Cr* zS*51!1RE}zjt9u^-Vt&~=G0YZ>DKF+=Emqa8JIAU%ggNwtw&lhgvdi>w}hVYLDW%4 zueoQAgls zR3u8PrC3|L zG>F%Rfy0YH^W%?~BSJ}Q_{u;8JdB2N&rJ;`Ig5_lSvGZWRQ;tun!Rejt3_c53vtyl zj+e@nJNhL)Y?awP=!iR;JaAH4>$AF23F4<&moQ{}T;> zJ&5!i+ucHE)M!QeGSB&$-l1t0vx}j<0^p6pWkd_He#?=I6=dn7OJmPwzf47|(iz5~}&ShMss8Tlo}g6pB321z|WO_I`ydsxD8y@#cw?JQ2BiCQ;s_qSoU!giw5 z4sdTux=ObzY^rLSs}w>lrBZm!vVqUQ$Jm;A)xy?Yf2+dToD9LIURqLj%5?fF9c%) zM1MR@Ta>Q%eg>-(KLsiyT<>UI@aEq#-2+koY^S9>mmmZgc2{nwse}43wDS*E0`0+y zQ$hyi$K=tz1?2>O>-1W^7$~GJ>`9za7#^f#v~M^9c-_sEgTK=c9QxHPuw-R(19x}7 z3p#*U2`?~)(>wLh_e#tM>ig^V*$pIJ5|4EfBBCgDnxboN3TgUP0&Fh;U{YVV%L17Y zm5qbTw@{9Z;DExw04;s)fI`z!4JIbPKH)?r%Hf<=_=JYxiT6043&*|;T43!F5LObo zDb2w_YGyLncX_nP2Cs7`3=(JSI5$Hp?K3FXX2&-;p@{aX=@O2joh2OM2x`dJ(`Q~m z#|H>8B3OZqX|w9q7COB3aU+)Q#4>naNc z3vTGZGNdQWL3nxTn>s!E)8s$c#2s)kCU-_REj>u2)dN^=ngz`p-m=Zyyj?>9C#yPX z8R4?&uvS6~CJz^$HjE=d8YtSGlrYeMdD$>8nQE(X;LXFkWp|++ zMe0`5%CRa$4%ndSV4^Si0{T$6LEFq7uOHWvH+Q)dRIYle5I%gcs2zPwlLkre)a1f+ zMU`hgFB5a>@kh@lp~B9|mY4fzVY%wTSb;0&7iCytJLD+7^YqqXrG?t4-gT*#g+mW4 z!+g%1O$e-w*&Zy_FFbPI|!d-yRds8le{mPa3Y zekK^ZWL#6mm@qL4r~0TK>%8!btCuGtA@d%1(*WlkNlDz~5puFpwx9{Q)KM{|I@O;> zQSMnL1gIyCMk_=F2B+IbeY@V{3S|rEz13@|K1?q@x!qpNSz3`cwF3mtCd3*HzzV?! zg2AoF8PK!GGK9uzg+SKV+Ofh%k*W>MWCb&)Z1UvC?#q2cpHh0DHeHX9 z>l$Mte`z4z6Hm;tko}NEeh(W<_^ojxxgo`RXl+_*wSz@r$QL+#^F!tr6LW!0E;P^+Swm!S2=p01cuK8 zfKDBc;rKNO#E;$}4>j6OX|VV?nU3sX>d0B4oE1b@9<#;_Saaai&H^%hT|SwyokDdP zu>cSr#Hf;>US2Oqn3Cz^`gD=r%U(HH#t5%t-}uz)5bg3bxCq!gt$b%aWnDa{F<1Jy zD)HB$Q$;739`I)&RSlm?bo-FYG|nrUQVqda0g>U4RwYy?uZZTdwF1KHBstzOLmyz4 z{!_j9_s-{;eqFqm>WIpBM`O}W7@bs)*L2d*)>>|jqnYE15=G5@z<8Ts_3aIdELDnK ziJbff^4i&bTMkYBIfXO$$X3NI-RR4$XPG~-@?#i49w}|u4x};)DAn0MzcL_#oH*mz z%!;05+xow}DJlK-EMmTLa-noz{L{EgvgmwlX=Ja?(E@G%iQa3>?izRTG;J8)c%fFn z96%d8`fKD|7b(hcEY|i&H?fsy*$GmKCr?;SF?h}-TGe|hZdn7xkIGdU_~5bm^A*s_ z&r{t}ECJIuR*`phG5qh_VOPn5te!fPK@S3g$+L-@$?GDfhIm^M-w36>@AVveL#CTv z?^pgmiRI<~LZCqe!1_&_$ z{e-xn=nyh($%d07X*(01>23cGQAn}ze9bH0$0XR@-$vTKM`xA%F*%6B@$>{QRzu9f zD!cAzuR>#0ECGF%iGXDdVYit2<~?O}r^_Ha1#H)Rze7Y)v5UthF7XsvS9twXzBTvA>6YU{H%e#Vs*q^gq>QnwGQ=; zbW2%nm_)uEHwvM>?~hGa-i~M*DihE)VnWo-0;c~(aITe-3g`=x+T;`8PoSRRvdb#Q zXlh&BR7X*BC#DOwPfAY~2#HC?otwTJR}HFN`sIS((IsvXbM@Uvop@dDm-?ezl~NGD zxRTH{hkI+M*F_Cjpw-mNO{sYOgy>H1ZR5gs1RY(nL;Pw(pA`$ z$}=2|bHaYn+Ge7&4xG}yDXjEt ztCKKX>|XJit%%yyk8t@KAD=K1KLt7uv|^KJ@M@oO=J45>7dah=tcht6H}Yg+&OzTq zx1{ri8yq*E1hW&T2&q}`W%$e`)ZWoyPIwYz>>vvc%-ZC!+pHS@1-;@W&p92}9_4zr zt{*}qfLh);p-gz*A&xS;Jubjmnycy4?M(R^{EnW5o^@tRKuF*eSa+>@#lyYPOTax( zCtf8Basa{rDBTUeEL+hNgu=`5>k;?|=~X-067lx^L4u{LW>frrRMhNsT7%I%p(F(}<8x0T4ZF)zJ1OcZ(JD<}O48D3EmLGkY2x>{0^; zA=*I3=-`TEJG*t!Q7rBvQuJEO3v44m|J0Ii?0+w;^h^)1ao}06nJ#Kf@HNYn|AV4a z@FX~V#Hf7Vg%F=7KJI)c9|aW8I?YBDkFjl9V1ogANieLvuxt9g1L7*Onkl-j?3Bg&7VZx+OERf{v*hEmj_%~X=!mF8uc(XOKeHA;uu<}s2h_+v z02DgrwED!*o0hd5mGrWTeGtnfXOj(u5S$DZx=mz{>0ZT>GKKh4aN8d!gGn-PbM#j zxEQza>b8hA;UeFMNpnUG{6)2s27c<;cc%}8DwhXe6Hz0i%}~5B?PS4G0%e$|it*Xm zqUpox7`zieNqedcew?3DSsbfbZWVKKy`aCf2J@n09OWPDD%d8i8FNj@EU>{C;6_ya zm;kj6RsC(`fu9c=68_{M6sEiwLhw%_>*~Yj4?x^UxS%VReFBj`f7b7O-K71?j_(?o z$R_+jbZlkbU!|Bit?wgLY!=A8a;uhZSef%d+>B#R8=YNFvN zwzF7?h!I;+rNU7E8O3)XCo{UVrlD^jeGQ|hC0#u~vlFwwvjbf`D&f>vvnJ6Zs^+>@ zcVvU%GtsSXjJjW;_^0ok*R8!}%*Z~slyjv(Ozd2e%sBLCW9X-O2O7w8H{5cPEjh9= z?$x&%cGr7mXsBJ!C980XlW0}QshQo%Y|ENacYIBMoscIKRPlPlL|_hU&;X_C*4#8b z3B8V($)f?Vzq*q)Oa*We@Z~jX^y*p3`E*`hPYd97&HI2ax3XQSYSWrcU(@dgK-1xs z7Kngr%&JElwoWP6>k8{8PtoO1B2($?sPMfkTJpg~$^-0c``!^y2#$eJWeg?#xE zcdi>Kw@?t|y3PkRC-@iXxSCBB)yvtwwc0$|Y|41g98FNTCN)bqq_hr#gJ$X{JjT>V zLS&fxK(wX;%GN8F=0Tc1@7e7cr^aQ&vQP6jaI~`$t7rkX6~!e-l)g*=ML@d0$^hhU z5pB1dCD?TphfR!$f=Dq~ZO1}pisJD7j&a(3UU;r|m%AM9gOB=!R8WTyA=^7K%{0%< z+Nr7!q*Q?jIdR9o-tcrWT_|~$`MYKA?X@ww>0Thfh3dKco+tZ5=uurvjU(k-;K-c? zF!H4Sx=511y|;B4Uox#bZvyt==as|mi5L;SZ^x&G!`VLN{9j$)gOdW6UYm}G9;CLT zb-c2Pt48p5uHYA9kyNa)F9V3+pN2To1 zgUKVOJa(xv%8u3}JX}i)$nE5uW?P!jmh`%?cT4NpTSsu#LaCC_wsWw-BJYAxuI83G z8*7Rpl-7_Tgv6R#R}6El+H+e@nNZM|E51(^CKx=9OY|=_^iN zCOC6JY}wQ*>q%qJTMED!Htv(j6}9-VJ02bEryqbeFCpcGivEsXatDFC#98^k>R))K zWKxI};%Kr^6jsjVhoFnueh4f%;@i1>z%uz8Q?Q%lzV#OFzm%Ds%banM@RgBI zpA32d+~`OfRlpI&t0^7ajn~Het?3=h3a$K9rz@2WAs@4tewVUX> z35c?axJ2A&qH0Po<4jduQ*TvHM%z{n7#5OI}sV70EZ zfgW_mlz+v*YvhuUT3wD^-DyS0=XYitM!~yp@+!g^kkZ7g59o^gM2GIO0F2k&lx6lq znm6b;w5y55HJ|9)gA?GH=Y*USi$&Ol8{egJ5!2l$`_4d!Zx-ie6$ zliTKmniiL*sTiYRg|Kl@Vltua{IMN;yr4)u(ODv0Rn}{R+`eWbG5Ks1_ROy=)YKiA zavKXrD2${Gi`cwog85ieMD=sK&Ptss|3jwu_&_sPT%2KI6n_4xC#ZHoaNi!IsBZKS zT9AWk_RFT@_o1Vg9VmWpaEhaPk-3w~zee>AWYQ1;)Kt(9_42mu!Ko5e zg590YuZ#cvdT@T-^7E=`D{7cL@)mCxFqF8nui=|FBu1y9T&ELO1OWuE zwN`Q?p1y}ru-I_KmT|w)HX9d~%kFApzi?Rm^&k5Z<@o<1ih zou^p-<1KE(JHWsAOb4Xo4+>2MLa6`a?y93Cyv&yh1TChoF<}Fc`cefyz`mNy7^{D- z^7ZN(Z@Q}Lq`hdv{QP_4-a}r>*v&Gi-wH;ulM_U|aFi#rqq7A)dF<(l0|66Yco6V7 zVX?=fpl&RxWQ<|Jq@d*~GK6jF%2G1kaFtOn5{tMx^oGMQ{D!vLxEScI+Y23$jnsRrq{Nt;QTwc&M55Y+$;@%G-fdRL+bM} z9<~=)o^Kqr(dqA!7O9Q?kp=8pybpc)PKX@wNeQ5xnkE|g*k5ISf+W z1eOLz3NVJg7E!-C6ThFz-R@^*2!4ke09R~1xLmJ0s9A^TA~GHe=9X8*>1TEoj;hE< zc^$?e+Wr-K+^Cdhj%7?)N{V;3Bs@ZQ3RTOK`TeUG) zoQpU)PhCs{!jA{8j`<=qW2UQRYZNIK!H?N*o85X|0@tRezSyW-Pz(BN?lvXc3z9lu zESlpJW?`(D`(=bJ{kVEaq_pA|75J#V_F}rV6;xl8 zRL)nybFj)lnPNLaVZ@u1o;q7B+P(N`WuV^J3;4v+>PwlBX$%;4J>QS8l!(XZ>hFK2 zikEQVDZ=U5Npg$AQgqh?GHJ?~2_7z26=u|;PMn2WdTh=Yu<@*`fc)GwS*I4hW@`t{ z`($07;vDp@QfYR#8JbqqnTe9C?meHp_bZ0L;bBE0oMKHa$UoQTl*(l^UJz(jJMamp z5M$%o;{;0KQDla&FcZu8e&Qnwb;~0t$gD&}D)or4oR2YcZ`tpjTZ^1B2gZF2o<}XxB(_Mt9*)~C9f$U9kv(0X0);t>YkMPDj_}~H+g&{1=j8I z`-gZ=y~X@vGiU!VgmWRdYQ;%|Pj+F6l0(C(SA;|vbFk#!z4SZ(eEMVPy4?)X;oI^W zQ(~8_*u^8bDpl3+M=_A2yws?&v|BtN=}gk#LZ!jFx8C8UQk)kf*g53sN*uu~e!PHg zk0ZdVnwVBhTV~wmBSr7eASb5DWQB{{jo+C)OcAnLHK1>smeZqDZ_J;!Zi%eycLhUY^k6pQomzEwHcFi=(M4`5NHZ}`(HsLD} z*xk)Stdbk4rV1;x`ufL+=N>7%bkWL2b+=Wi&OAz$xI%Q*kz<8FoQ25@9N zZzo&H8u00}X;`%P79k}q#=@80&AU}akTFiiy!`PHTQXbD2j2bXNx3`EUMI|d{|)w9 zvDNbVu}nj4HeE8#w#Hkl!EGb;C7pU!V}?O_;KX~G7d`ybOr842D)x~mK(4nKYvALo zm)Y`qCh2Q zO>+8rOBxIhc4mrpf4UXeyAF`n33LmrRFQdhs6vO1-9{1Hun^5YBy)d@PLIwaCB^_R zoc{ObF_uKv&6*wt1kpd(5iwGh-_PX;b?oe4rNvi1{;jz5VC*W6#L*T(7akiTmZr6` zJ>?omVa$WmM37NBb744%%u1dGR3~)tU7q$N@eX*7#|&Vr`@ZpGcO0m;)aMkKSay;3 zX?9`ki}F;;%qwB8>BxMxCC_PMV&5-Y3wF5rLP3hwBp7H@wu8}M-h%O&6i_cj9KBt_X1vpTqfR8+n>VyJfx|2)cgxsk?9GHDxc50?p@#Z z(gdw=<36ohwp6q-0JsmoAYN)Pm!}aSheN+78Vbc4jY+sSqBj0Lv+^< z!pD)GGO03E$Giy5khiZ<2gJ7n=zl5-anN6+QCCH@t)KHTtZpb;BbP}8n30VJb%slu zdbt{5MM>>lJ~WdiP8=4jM9(7wZ$Nxu_kqWA`H=m{u9I|jqapY+y&W@2O5_>!sv5&a zw>qP#b*7HD@Eqsi;|*3lp?hf}4*YpGl?207A_4be{P>qDIMka38Nnii0E1iEMV(^A z{be_*QKA?|^ns=IMQxIQNG=|Lo9&u_wiktc9b5LQ43|sywG}tEPn_Dg z^y3)X0xlNs?kTTPMEXL*5ns`X5Lyr8oJEb^-tzK}J5^h+8s#cig!Pg(&hR7*(P`72 zDq;I0#57kw;BpF^+_m6kO91k5p>45ACS53~!u@Fl7KfG&5HmH&DfHJcu&vuS8pf+y zC=1(kDh0mBh)pf|W85OEP+=Q@&pJ%!6!haTWzoLdXO8#yfl zLlDhpYq)3t$vhMmRiv-9RDv2n=}NUFqXk~nDNCxS1R-;nJ2f~OflF|!w3v5U1m89J z5mplw$~C%SK`&I>CFM64;U)2Rf0SdS1nkWo$0A5$6n)0zr0+OT$ zhOV}6Ss<6hvt)F|P`JNYQ84#$S9G2O>e9lAauyk0kuV#Gkd7 z0vpdlw#Lz7!JH1*HYPSY!P)A^SFj_qksVyc*T@=`#}wVFfSV4|T$#cHajmkgBlNCO zot992+%}lVAaI?6)D=Z&7rL!ykVOv@h4^mie!j}2eda~>{_FyL!?@kgG2D`%D=g@A zP>&f^l!7iru2(Ik43k)Z;lkQy@UJ(sOtL}xQOkr#J=$;<@&S5sOQLq0RT*aH){icYc#}Gl-4y~c5NjQ{Ze@UzXy$cAtC8kP0#m)L%q{g zU~a)ikYJK$I}I32v5Ju!xe-8#&&6aP+C-q zvegu|7r7ujYvQ^o%#0m}FjxC;zQJ5*NL^=CVQ0l(mUu$jw3%;o0%0tw^w+g5HLN)F zH8cE%)J+cc`3-2CFpD-|LqvdopV?0Rs0Hlm4eV#-(jO6{G+tvsINwjw)c z#uh^pLid?FIOG*wlp$S+NsLq#=)iEbQd7)8M@rClKMnUU%hlI8gAO=g|cx0Kpk zMRClxTeLbnzEQ-7#Xdp|=S(qO^z|qoAa)@btTiaMBFRb|!Yy)v#p_gHr%VItbEZn? z$qvUS3zV{YfIOBrXGpt@%9NFy?!;5&n6e9?)vU>0Kkg=Sfx_TKgmiSz1@0ASIi+yI{&NU^E6vZxFuLJ`XU5$bjs1QI>@BJ=Sty16eijpy-#@ zKj_>k-hmlh=ASn}0u>L`<+baqJCCsl@JI>!T{+o@tFloYR#}C>m~5J0f)5E59`P3@ z6NunVIWTWYqC=9|mUB95rHI`&L|NHZ8UxO^_KC(+pv@pe586}?)rR0w(Fc1W_Naw? zL{O&b>+WbQelchfJ4~kaJ*Jo>9Z7+$xxqW>M$n75DIh$^&==jhCtw<~EoP#PAwKKQ zyQ=AVo*aW^r<#~YW7bRX_1+8QMF3S-ZQmmUi)?_R!hQtKSrXG1{+55qkdm>UirxXV z{92){@WfXvuUdgiAXycqQ&N4M6ybLXrlG46a#S@J$+YmGc|4IyJvrAGyTSzEt;(7N+se%< zQC!(9M!DR~1!GPXXXw6xf~6ix2Z483K1#@^F*|_`B|l_4Rr;h+o!esl%G3Q*Vjwiw zWSBR$489glp})j$Tx=w3&_UKYa&t(f@gQu|O4X}g&(FOPjKj%Jz9BCL{<1{D9Z=dF zQq${ud)BfG*O0is3E@~^_IL`+3ILV*Wus>F5esya4Zh6)<1%-{g!{Com0>J)moT85 zG~>Du)LU5pC*!L?T6NPuwyfjUp8A|EbIRJdji}{%6)Ym69$>0h6dy_%k3yav*h^eFHMXfY9;_S>!Y-!7aB&wy#Q!U|+|ovI$jvFhL>;P*w8j8w z-%zF}7!m!q^Xl$_iL0pz4cxM=6~PF4%mO^yi0Y*NcdkXY`s2jP#*2%*nopdRiT5un z>WP8a4@4r3rYzm3G>0)1iVNac2WAba6?Jy<{SuaAw>QD^yEe!w?ARMH%ij7<|D^bN zaahUyAYtSYt74ig{aAe|Qqbra64PeiMtierFzw89w1x6yyt7|bX3Uy+a33kXT``JS zY@HwX$jrqEkYWq}EbWYEo~l}}UgcWa4!4J8VhqFXK}KLzTM+SS|3*d0h6q}e^e~Dm z&|4;72JzkK0YGKJm)P>#jA~3uWy`$DG;6GzGtIA{p&!Lk+}9VZY3i{b-uXcRDZ7f z#O$^?-gLZ^I7K)Y4PgQ!EP7NmV5^{5)4}Q^PO_qx@wq$g4gv-ijC{kQp6jq?B&@tXu(S{IEBc!B+{I+5D2rur z<;~pP<9%;?>p3q<^m~NFQd6YGkYDIJ4T4&2Ev`+AG|5A^yf{XN_CiiV9C1L92i_Du zTh2?q*o>vmCg)f{Ka`dAv0hP&B)y)6v3@k0vBq^a&}{;NPaufZRPCr*G(96gtcH7s zsW5|*ME_ee@N48sVpTOZR-6dMbeLl6U7i=8PNsdG+e))ar5+cXk5hsGd8c;6Js*$?o2X6(tqnYe?(zm1vm1+FM-k%BwMJ zxYX8BprOID3px?Da#trFw6w9qt4XW{z{_!kHn%_^4kK5ki5Zm)dzwAbPA2=C+qK5V zZUiNq-xOEB&RuojvwA8+G0$53PUxs`Hv(FZ-et7DQ^Vu+Gbh4FdrJPT}WFulUH$ z+XK2V*hClhZ>Wz~tgC5V9<;s9Z<@xgolkyVL;72|h_e0yQ*4yauX5GaRfh4PUp03E;T2h5EBUGc~BcBK^c6$>D%yM&|yqZ)6=zV z-c=Y{)4DfiosDOuS{K1uX}KT$H>bulPRvvP(Bg*G0L9R28E>33{Y)9LzHWODz!3SzbHE6 zf8Y)XE7>Wqa&{1&OFj%&Ox;JMl=gCf{YgVu)d(a#E_SA3|5@9K@xp0(x|WEItnM9K ztAi)UCae+SuDJ_aAKYqbGYej~SN4bpV_B#V75qy!@>yaUg2gW1vll*uLYNLNDuwAgHbQ;UqU?LUjUhX$RksCuf0+?JxyUi)bvz$Hg2cmUiZy=6u*K%q|o zx57Lcna0f8jhgLR0&F%5S*w^B2ZsH7_NzP@~UzCZ4^7|s8NiYL52My z!uHQ|iIH5;gg-c;rGS&I@>~cmKFkCQ_?ir$FhbpsmS*}Lwj*4qqMm>mej-l5ep!Bc zwM=1We0q`bYE1%1uLMU`Wqc{UE1r+aH~bnSbm#U5^%VoB9@RZqiUvUBG4ZHd$v!F^ zIBQ0|u{Z3sOq$__9>7HG0g4odxEO&VE-dfo#v+yPC?}Z`6#P{T-G!I8T%Ilo%(FgE zvqfqfDoKx}UCF0&sM<>a$sf3dnK2+60kVRiZ}ULqq;1-bSsMm|kLZ*|Gm}RR+<2p* z^8^9JfxXeO7~d;_&wrw}@q4r5KtH0*U^Wwk9CRN@%cu|f{RIRI31^yR?4T74B|_;{ zmFw0N&C7>{PIBFVa?q?^^p2vBUh&E;gW9lLONJES( zgXINP-4C_;(rtRTDmnl^>$EgDE-<6Yo3Rs(!&Ssy+=jz7+op^p=pA!HT^eQe0Cig( z8wb~lYfmU7Ys8by`90Et%f;f_FbS zxT8#fUvxOaln*v2=2H2C7&uyqD++WBTJPmD*5wqSLZeiFBXe3i4+}Ap0~D!#*$WkX zf$ZRWZMQINtALhA8~pTQR0yru5yh15$_*XGe<4_-hMJ!=ZXA%V^BSW>6@T?ZS}t!! z+r=qO`1@~Gx>zLK?avhGiVP#9wOxK}{X=Io_?Fm-hY%1A&l$h7yutlXUrcaxC*3`& ziaLin@@q{F!3_h#Dmx=YtyA$iR(EXSI!LsR#db4Q{g51GV+;N)LJ*G!Da6WG3&z9A zn{*gan?}*DEd0rLs0dxN^%PjV%bEG#X9la^7G<((Ju;hJs!)%wdtk&)r%8U)E~N#= zZSvfY&5O1pw@zb_0ak+>1KX8}JizWWwPrtgRDCB<`U=%>wMczgr|j1?26S((@BQ@^ zxvpaeT8rcEEj-BlzXXP1JoByt!oydTj0@*NqE8v;jymxGq)Y%6v911PhNMwJ!hC<* zGdO@x)p@WS^C`;H$C>3df77I81HA85#-)rl-+U8U1L~#_VswN10bX0(OfVxf(8%c9 zsM#2fG8F);oOXZNlK_Aw5(nFJte51U4K# zIJ_a9mFNNDO#g6t7!=6LDu)cn+ef232yXB;wgQN>cJQS#oxS5lsbVOUfGJB0V5V7- zbhM!5g#=S6!Vsl(?eK|4mHu_a;^VW?V+chTt8;J!Q=Y2{4vriNLS~ap=XtT}`Nz2} zklJ6Iy^FAR=X4RqBU-BW#dRmr7*&wUWh>OwD3PHDTTE`_G@>QiB5|?D5DuqrG}~5+ zZBx~P%$_gzGw%Y7xAeHGz7yysgZ!ftb;y|j98R&)`2J%&6G4`Rze>bvHOydgaR$jE z<5a_K=su{68ocmpJAw!e!qTf?PuwJDD$a}$rX;kf88BeA!-7-UgyP9sl}!>F$utt~ z-M;yMm(q`1N?Z||`$k|Ck|I?is1LV{lCA@an5^qdL2w5G5LGKr(&J47 z{@wbm<&e)h51g)X+wVH%<2n}(uadxMa0`5fjZ#>a0v+s#v@!)HaJAME{q4 zm|j;b_Hw^e@79K1@>Z$%BCAb7JKrB)zx1<-4$7W0zUoJfkDx-L7*B2Q<+#Rpb#ib3 z+Zf}I@^fYc3+%F!`T7dW9v0GlGP_Qs{IhF0wYkkWCMJ(>{4QCeiRX|dBXkY5(7Y6+ zRI)GJth^(dF#WWY4RMtJP_32Td@aCO?M6n-hHx>xYM80Gs18KS*Z zkJk|5yVs?Yk?K>KXLem};g;;e zSPW|;;^Qty^dOZV&mVgzjj%VIKLhlONFl8|)r~SrAnV!N7#E>8%Un_|57*ts@=a_^ zmj8vKIWp@ho}(<<)vbfWaz>p1J#aSe4hkSS229n4C85Jlde!S8=d@T&2dyFR=J^hx z8=eU8^tsp&ufyYIE-^>~AG=UK@G<|hn;ec=i}F16vj^izYA1^b@tn65+zda(*_rbO7xB71|wNj?_-)Gq48UN?7PppKR9nKf80Z^z~RTXoCh&t zV>GPfNU~C>3Z#enO8#IN3l(^(@K7bfx!9K77iT6WnnypTJP37X6f|~T5;kDnx9KzOl7_sw zhkU~!%3`3>vIeznG_HvTdo9HZ`p}8opsvJgJPg9Xf0XS}5#oLQaL{-N zuG7Lg&lvZ-=5{E5Rb?S_-erx_QWRGwru9U%i+Jh37SGBhl_spOioXw*%H00DAU7Kp zXQdrPUDObGSxNsdgn%B)5x}RMDl1-|!EjNcikyELYX7z2^gFPfJUwA{EbGaFnwTK6 z_Hix4XCy@q+dZ$5H3d|xK=fF_SGT5y%NV2cz52oPC;{BEGAPdN^1Zpypmve}j3Z_P zxhiXJ(ydZHnXQQMl!#3v#Mhb#S6iRl2d{(dn{_EgbucmHbC!<(f|9|SvAu`N|V0D+N1kN z(T6>i-&5Gn_>yB_B2|bI>)0C1lVTwi%-il!*C)i>>xX1Q#%wqm*FtYKjYvg1@3Aql zWGS{Ti7}=fmEm-^Y;sPnCj|A?$;Q1sCUG#X2P`ZwBHOM*Zg zj%rN^DE2RY{|3%!h(zHI#!u76lI2}_DP-u!`wCTbph6hB`&@a|whUGw;VIp+H^-ol zEIpD}#|n%VX5pNT;+bd{td45um^>Z(8aYZvni(wzvC{(N*Un!#+6?J@zL!Bw2OSXZ zeY;eqRKc@KoNK!Ej%mS!&zJ)ss_XSnU1`CK4;8n2j3`ww6l>cm(w+&@IK>_oOpDWRWrm7N{DSRKnYMS6abKR0<#K ztWGZE#wvlqB8GG$n{&=;e&fEG*CU>=bX`@XkE#aW1%yJ99VP-K$%zX0l;y9JoNy1t zUxfHWAo^I4?wl@u?4}wRC@1pCYoXAw?T`*^5R;CxL+?E>D?~O?r!&u#>{gazL`<`! z(5QIpbeKx)I|C9#ZN8VWiq~ew!IbjRlj>BB!)Xz zTCe35cwqy<gWZC+sTYt@0(5jjq_8C7Pfrq03P%*pwB+L^-k>1^*S2-m@=#aa; z=^CpL9mpIG!^2n6w>`r?gW?HEdTeHfZh#Xwg3cfHX!Mx1`oAP5vQW1Qt@HSs5V4Ug zXcH0rAq(-{lfGb>9|-bqx5gwP%tX7)V`kx|7h_#$aLQE4%Nf{-?vnaXAReo&T7ji- zmfr1u{*wl5SehPj6gcAF*6-1*;mkv|mq-Wmpy*i^)P*r6_~3zT_KhQ4YFdw?f3ok0 zX77>jlU6QOc+V;|(t-HG%jwXiMKcBbsY&*oqj^v>M`3DLl?{q=8BDxNy;b^?RmfSz zYfo1$t_k{%WcdHS}Kozelv#9qG_za=@ zVC-`z5kGZa)OPx1#8?~Oa4ug&Gju3J=WSBA?H3@SN$C zZLB6abF36y-Sw>h5+KI822Z}a8pKn1yP8~>3@z_3jE1E^hmTYVCFk)ea>b(3Vwxm9 zID<}UP-B#M@mUer*R$bV%D>0FSRtJC^EezWZ#Fi5OhRV#(D!gtlxUk+xOc_N3wC!- zhvPQ}`&-!w!lQ@-IsnZwvFPj`j@03e0F~G7?@a&y6Moe@cfJLJ@)FOYrtXw;Z3xe4 zz8E<^N;$xt3;kJXCCRwb^p^X|SRI8LL=^i2>h)_Ds?#=JS857Q#6@YeCAf_rJ7aDz z+_HqS*yglB7pA*B@P|NOFo<+TqJi4s;EM+A*FrM{o1Bp?$DXtUVi}6*_uhsV-r8U1 z_)7QFml4PIF8hTv`2@_TO$Obp9|-G}v*JGE>@r9_Ex*aCpW#01W&%))<4ymOBFNnL zM^fs;^wS)P&pN$BF(=rhAQW(xG!z#RH0O zT9==zxtX0x8rlrg-^@bl&FOcJQa4G!O4;I?~F< z(@N=FLlwbjJb1=RZhPO2$h>@r{&;0F-V4uL6{3#W9>94hneQ%Sbc*c+J;QC?P&&IP z?iLSIQ;KW4S{UAc_6)FZap{|ui0m>mV>je#kZIs1Ss3J}9$VF?NLWmk^7s*H8Vnpl zDMi=Ip018jo|jfogQ4zq-sx>{jLfubldy1XO875FdW~uW=57swRSS#lO{LubYYGMT_7-q%sPx!aKBltFz$CcxGFV4@ zDg77=mhRnr&`>+@7w6{DzJMX!ezizxmOy9fER}*9U^+ENdhU;Yl@7PD&Sn=R_pph( z;kX3LWee{^KjvaQjrlPF&d!iG7V-&l?%Up6qQ}M2Sy@?kowd;A2L1a|bS`k4 zUKa5<2KS9?HUpNV`ybt~TAHmlmPJdj#_g}x+2H9VKAiot!6_m*zVV)K6C?wgyl##gzq8YS!KeK@ZDBiA6!)4{Zu{^g>);;c^Q_@5Z_3xBWJDTxFx9f`gu zqZliqGFgXa!HtMl4v-Ho=4MUOh;0XmG+y!88;!{TyoIQ{#V5y!i#}DQq_r~oHGjH{ z&BL38y5*`178hwwf~$Sf5J;W&*p}CF-Rd+1Z@&{+&2O+VY0d&_fOTb84^_ARruc;y zlG4MM=sm?cv~#clqFreO$jr~Z5Cs6laro4-8<|EhCOGf(x*T&tiai1ms1B3AgoIRDnJp@Kj7dShTS6Zi|sD(H5OUBr* z`z;`H<3NWb*54j6m%g{Y)Z9Vd=k58JlHiAk?agraYdrUh7Yc+t;bwh{^u3XOPE{Z# zt+sLkjbX&)+I8xca5?3_E6L(gkJ!)hH~A)XrKIBC z-ZK~X1G$$KVUuGxaH$Nwv$gt(%Y@&=wi=a(fooj0+>>y7usApagx#KmYlxTbguVZy z-B0d-XI1Hlyx!4#Q|BK!_T&WM+dX0WRxGb};kon(yF`Vr7_r3MF4>N?KrLZYy2zKO-6IBTIh_G19A|$?h zm@yh(oo-{EaNs&EeBhZvlbTNcP*{_Kju{rjey~M9b?v%Vc&BAB2A;#3%DzW~h))QC z^~zX`$d+u{fdSW4=<|)Pf=*?kW)3sEl1p)FNMuWm;pwZ%34l&>q{tCS9u$?M_AMhSZa(oE)^0-1AXCwB4cUpI z3&?G#FA~Pe@xq`; z+Z#s|0g1HFIUm#XwG8@DxzO;B`-4L9uM;61ERnHU_0m#0BpT^)DaqAOx;3H?6v-#%$dD`=}oNY2sX4LZcygr3FzT$CH~TRqp+Cq zJbRDX>Os%WKir_09LG#*ok?iQegGB;D$SH1U9eCTqm+VzOFl#Z zzOvGj4w5Za3l+YJE$wzYF~Aj1Jos~VD{;pEJcGP6t^%>nTKYdX5@ka{E>&A~IZW^% zRNUx}*G+0>X1RaT)$_nD=UXH+@co=2=j>c0QG{pwFoR zHzZX`0tQcuxq>Yr9SHL0fe=V`xZPO9m9G8WeiK$gQggJ+Mg<2x3r&}$C^)14nvOG^ z?t=42Bq7j+BT~a+O8#R4Cmkqx6U!GWgd+EDemU1C<+7*` z8jl@K6QQt~FNTdFWtI-wH;4kj=uv=0F6DKg!t6uROk|^J2HO+?TI)YqXxO&vemT zPcS8^!V+{4@dM!VVHrc|ulCTi6gQl_Xz@`c{!#i=hMnaH~THR+~bIJsT zIlC|Xs4v|sdY)Io?O7$DPtlAVW+nyxU$bqk_NSe_2k7O^UGFPvorz%cp>2165^$Nj0JLRfeKhtZo&mFDUAF{1 z)#k%HezR2g#8@D>E(=m`WqVnAg%Z>EY3i5~=--5>~>)cMztTC@=&EgOb?#mxScUm=NGj}*-Lib6DYDr=ot z3&JXf=EAAU6!F}INm8aspn-!n%N4F3r00^sRpP;Q+VzXm1%2K2l!!SaBkLfl(WZvi zkN~>1^Lm2I{Ql(_!DGUv8$C8iz~7nujdDe`fhkcFwFE$poH>z4Qb=duVgOib7;MYR z`7plJ{BCFG!We=t{s&}LsoNQApO~vB@#*ZxTi+8WC`Bqh&!L@wA`hsTYeSXa&ZKiK z+@Xo^>`sE{_>l={>opETXsgBkreN!Aa-3NH8Di4YGP`=@9K=74?sT1K)AO0O;=+Xt zs(59&LcGdsHyB~IE$-YU<_=A zbh#iy1P!Ao{gKVKii38;s?`8RXjKn5IlS7wa@z#yklUeg!Qgy#PcbfnGg`o#k;Q>Q zYD!zmO3{62K4nf$x?X-Cn%fyLNZNON1z0>`5kqWbY1`f@;axoeoYKV1rz_jcJc%n0 zsyA6Js+z6qt+s((4i5$Y{UIw=(I>2n#PrSa2NmE5Q0+|*VAbMfK+gSB@`mo3AM$Q4 z>Fw{R`%6CMag*uOAlsj;+C`aZ5(*pGCPn9C2ey}mP@v$ra` znrsV8&-PtNC7)Q9Swq>uu?2v8-!sfE&}?maEO!ZXDxTqn&a9>;N=0rIop^jeFNqQs zGlmq&ck6HM7?5P$jG9u3nY{y9NUu8E-L87-c2VuLxmG@F-;G}0Bgv4>wclLfo#7!B z63l>D=$n5x1#+YbhA$v$z8PU14kbY!9rTr2$XbWOnsim&${ zABL=UV}~6h_h2dM8EQwB;-N;XHb~19^7oFLQ`3b7K3@g3N3Q|oq8l>^O@_P>esqWn*Rso)P%d{$*Ri3m(7l#cA-VJrQvU$P#&sRhAn^*>- z_cIhIEyN*7OwzZmk->NXMwf%|k4?R1CW9;2)UGT3E`AXT?&Ph}O*mFH)i?ASHHh~C z-ysr$$jD9B7(CBJX_&%4-~Gyz*ewLB_$)~C0I4fMQyD{5>@&WmYK__Ph|oHRYZ{5W zml{ug9Gg3B@9@)yOm1UP@&ls+Ng0lHOhHVp*6~9uU7uf4lxkJ`gQ3C6jz{WcmbS)M zg-ZTv8X9T$ubI<#D;h~xX?XCw)nf0!-Ne@yJUr$Z31H z-K14u9In$8WCKAy>e3GT5wcJBJX1y4Ul%Bd)=%gOGekrQJEe$XLU`}xChn~UFaa5lk>fVwF zbieoQw+M}(K+zm@i;C513C$NkJc3y#JKZ+hi8H%0>PS5RvBoI%y;+*-1bz?wi~4}6 zuM!{^rVAdB+xafmQgpm%UR{tw4ZDK}czG<)!*=^LbhFKce&MeD=k@|880r8=BOaTIg3NwfCzJ5SQ+bfURZndZsZ9-3`gTZpthN>hGU_Z&*~v`{ zkE<}Jp$lcCW$dhI`&X~9SKjLG2jIAOAFL3z!W$$2PZjYh5v_gC88s>(PY!Gelo0c- zg4zv`uH|$Xu{|YrDqAJlU^eIfR93m%dT2wH#q|PnuBul;kbbP~?o|SdD62_>4gbXfLDn922?z5}?_Mw1}f&uRG*6i7|(zAOMHf1&WK5o=DPvN2L}{3KkT zKxj$p7a@!)dKB6)IBB!8z$??L3fW90Ocx9CD=(rn6K~N|#_rh&3FhsBS4I#s} zLQ`7Q^3@lP%L(0M#c=_;^#DRZy}z;)2hy;IekA5KD;dQNh%886r4CnJ+0B7x3iosD z&Jr;$`cErBljolDiB58S;0-`fM?98Bc2?6PLd{DrKPbc;g??2zl%Gm76k0*T;8DX+ zsSXRi7i|!2kSax&qW?ksGpl3Lh81|C|JH{R^+v`~;Ht^Wn(k+9X2zB5OTi`+Z(kK; zNJ1J4MFe$ESC|<~HINR@Um|wb8%y9;sc1oVttncyH(c515i&h(kWdbNpvBtngHQE! z^B0hD{C|F3Yr0d(h-J%;Ae5DtnY9!EUv!CE)Fpl04F|Le*|#koDofS(o=mpLZvvQX%HqUsbe zN=@%oHe#b+9u0P-wYm$)T4WZ+yv8>S@8OHE3zn8?V%B#2>q~d#!QbA-+eB2KLhlZ&Ylf^t6>^d@#n~jt7DA?DwRw% zP(tR-19r@mQl4C0QL;!c=@t0|o*+Xk>;2bk@=1z{o3q`{$xjY1fC-=MOYPuDKy?&>hlGSz9 zdfJVYa$U(+{9)ZyOl(@7U0qy#-Ex)seVj}MQPL-VW!r3hZ+?d!hbzkEXjT&}9US{j z9q;@VimCM6EDZ(`2*&ve7h6`5aPFDpIJu5G!Jk7UtQy)1o+nl0iH3@x8vpH+Y-)uB z2~}-K)8CSDp5uvKE=}ze9eh;n%}O0F7L--?E2s$V%Fhqo23ufwQpEfOxkdZ^i9#O! zB{1>+t9gT#HTN7sQOvUJY!m9{N(qu}be)`lAgKhPN^q#eI|(@;eSbu5tl>nDyj)h~ z^!s3gZPZTijj_w!RI{2k1BFmo<+MTgkgj2+l_`Jt1~t8rd_qAI?qJ4M|K84%{*{Jm zO{R9?L7jHt&HC#}LmPMf$naXS+#8ILK+rbKsYb#6*JE@2HL;aOh&UySdKVf~@1Ols z^Q`Gg50M9Vj#b8&T6bZICGsrhmRi5c>iwR+pvia0s5E1s#l>$K_&*Jmvr|b7^eVR` z&Fl?_D}l1;gyev`qqfm7?+&%!%sy+?t#_sOIg_nK1&0E%@La)f3DCs3T};HpldeoR ztE2Wd%eHvFsI`PYh-L=7}&vk zV=rhaCcn5$WEz-@oQZg`E+y70LWWkAGj=`EL@`S4*WPP5Fxb}NBFk8eLMd`2Y%D~7 zO950K9jw0C2r}$JP)#a;aO47;3qgM%>$#!4QUodqmCrb$0k*^kkel4XPu9!PCIOsn zd42*A{!g17$3=Q)n9IpaiNfNsL$+C6`G3B=^yyY&84q7;Nfg3AC5O0?epg?N>S$b2x1`KtKu7b|iq zv&3IXhX_f7+{=t>wqu{peG^7|TjC5QljqIBA(Gf|jEF^}xPZy> z`=EZ^&@qdN2EeplqZsk48E!tkMAe0VgZSO9cvorbshcjYco|WaJ90K?E^)>`Ahg^3(?eXk< z^+G=fH%gmkZ7t)1Y;>7JNY@lAjE}F>=3TT0OY5tn+K=FtIn-5g^tk!!%^&b? z`3t)ltC6{9!v1m^a19MV%TK@n!?U00dChr&->OS0bhF|8@u^RbpeP`cY&U+%f?0jB z2XY zJc*LBVfPTbQ3))W^ZJ57B}=nsW4s)a-!#8l-voYi9$7+sL;WAc zVyWqVgokLOJ4TP#?s`Z$!Ri1`t&VUro*2GQy&QkucnA9S0RrX)P**y7EShCjxHiytT zugz1GHz5)^ZIdc?9}SbeZ+oB4>|}g9jrA;v@;4W!HGXQ#0kLJt%2c~E>`0A(P)s-9 zF)OaeXcz<%-VwU8+I+a^(YcY9+PG#k#DK{!5qRq-B|*?XeD`u6``~NZfcg>pDeOiaK&l?;MBZK|~gDEP?WFPrFFJ;5Px zqwcU2W4?rJr61$3r)=|T4gPqlH`7&F&{7<|xc_x8ooW%t1|pI623VN~Q)W3EooS3( zlmV@7ew<_akKba~ZvFvt5FA0s1lf)USB97|C@_twzY=6_%u^8%It264v7 zE(iY$$1N3AH@?vxN@hXp{IHFLh{tq*i7>$MKQv{Q$|XFQ;)}1DA6S?1>IhOZs#gu+ zo>(}}n`KTp%{-wk9>kA6+P;N*D}!5wOn9!!#}?5x-p}ZFF)N9Bt|^H z>)ik|CBXVekj|mG+y=%Gz5C}2*O2#Y7Q$SrU+FR!(>b%O&DliWQpsaPGWC+OE1Mba zN2BT`OM6QwdLFLIf~liYYgKdVa~yT-@%{I-!`{G6s$LGT$XKc|^jdR}a_7u#$+wEJ zV|Ww;=YLGNW*Bg0CMraYJeJ&jSmc6=c@w+7fM-+H?8{PpJdwJTb1tLc73Ne7 zY)I?nbTyM62G67GLY-1eVRBjJ9GB)>xvZ|$^Gud@WrQU+G?HC;m+Syat#Iv1N44=|m)Cz*ib%}kHJ91fmd?uU%zu4LsZy1!$%#)g!FoWOYM0nKl88ATj z2w%>RpgihMD%Odn@0>t09$}SaBy`f6(a^buZx(n`r=E<#sDL9mi))o@qr;!l0+2JV z_L7`c0OM&v*R}N*QDrv-4=F9rVM5szMWAmicNnBy9E)bQv`j!oI|>=@U!neuKal7` z);G2)yy_z9h7;ockBAig{quxy9Uqn^TRuCBS6gwnS}WYkvBFE!qhTL=n9qxIhzRrM z8Og-k8PAXl5LBq6N**dA63WImA&N;5Yrc^5n_SVUDv!nYow``D^A{P&sRSqHE$Yli z=gXz`YreM_<0tH4wU5%ytul`P8ct1S<#xZ}{V%XtP9iTLo*q2uce4)m7h8lpm4v6s zRQ5aH?LsGe|HjI++`NK^s2m*Tk(#ybM?~&>@<+FlJC#|Tb z{Dayql@%6^C3-PvSgSIn8tt=YaZ*FYfDJlnS88t6u*dr}aj+~#+5%nu+@j*ILUDBY zfvTRE5rKjjOAGf54kT{^&4VV#3?^m_U{~u4Hr8nzrqT{BD=9~5rrg=Svr?Kq6!xGV z!nx7W+@aqDJ^h?qF%9@r#)>|7a^uBoV^uJ>3Wx4|v`ETK5eU>lP7Q8HU_AJBG>pkBqj4#eOhlsZfVZdo|X5}9nZET7ZPILxL0~trCzpMM!PV0}sEj1$3 zw4M=KNBV-RnNrL5(hq3U$Q}bUrhB)vRODqbf7StT+~*!ljAKjiK*;H2nS3EYWmFBE zL=Bl`ef(zxmS+`lr->tSwzJih(wjodeeSFOA)kj7pssu}@PH8s_=P<2#5gMu0>d~W z^wmXF4FLLSZuVXi6=Oo-QO7Yx)X^Y5G2<=8+4xrM9qo<4Vpypf3|hQ)$Aogi7VnY( zBRombQFm9E#{0=r^58g?4Coh2{{;13b*zN`#cDcPfOReI6n~D`kc^O=WuTL^b)BZp zs$?)lMz%k);uIWs*Q z@S!LK9ieMjHGq+N+3wpLr^o!qA;Ga&HgE?OL6X`%3}Rdni~K^HtZU|^ZFa^H(UlZg z>;1ecuX)IaW&IC3BJ?5^N`=T|Xc&nBTn+oyPY3ntUsDrrP%EPh52cvPZdU|nQ_m(? zKSF;Cm0tK#qF^-3^d_THzGf~Z&ihL6CF($1?s-@n0Y>!2Q@Ld8QQA0wd zXVB@PdZ2&U4}RVStz#mq1Y6zLKtm7YqDbg%bJYXG(+h#9>(JB?QDw`I)xV|zg15#ISQ48bf4CBD?wg+95m}&!#}Ac zbST+MT>dAtj5X6Z!d2-)F~KfbxusnzfTJ8X9Dk3qP^htGzaC3DxLQ+UilqGl`{uzJ zQ2j)5#XL~@8*zqvR6vj_iciq38#}~20%!P9B9AP8Qmdu6TI|2pR*7TTK%&JY@9Z%eb!3%T%Igq&n?M4TkxwV<9& zC?(;`5@=+2?_u*B$N$VYW1(9+(vO|>N{FBb;g}xslQTd*Rx^$aA_iRmeQ=W#6^1{hc=fB&)bf@6zybo?0b-siT5DO@@lD?bq>T}@jeN`}SpD5?t6 zdId+`bTYhyIEuQ1-=*DvIY##L^TTFS>G#FY?qKlj)acUp1J;DoFmo z^O9NHQdn%`^c{`*f+?^Fl$TbuO!{+}OX|D+GhJ9S(@##z71!&H4)@FZk{NVnfUZsP z1^ld^XR1B~mGXFg*aTbe&rRPO2V&Ab8#$O$Yvy+RSi7d)uF+ zsr}H}Z~()2uIqyDa}5{a(S$x3Nq`%U^}%)TsxT|OjmvLOk$_l@n;JB1i7l=vYApq? ze7%QF@&}1e0Y)@_BGuSZYXSMsz-!Qswe6ApJoS1a+qkU7*V|=^VMMw)YTsSDr!6+c zpZTe;kIy1lmdfw5A9E+42$?Z~qRI#?zVa$?=%(I-RiNbgwEeXx!V5-6-lSCr*Ssiu_YECw_mkIJKE!k5N7o>$3iSWvRiD-_F;-K(p#5!-)~F+J zkctCClg%5;TpMYD{wR59Um&Z3%6xi4D5`KS_0YfC;|p+iww>n%uWLz%?72H`iI;hJG4rN zg+QGUC!`wP?vt8$=2p&x{&YgAneiw|Gp67vVR&i?$o~mIF)TFMGWLaJ+=oiCeJlOI zg@7dlB>;lqBK%PUa<|9-> zKu#&!2J}^QLQ|EGhE>2d8of=Lfuo+@Z8pnGGwl6WyKA+Dqc3ThK$QSg=YhO33kWwF zhL<{i?N|yFPLZaa-)r7a;6e(x5dXg$iz1`Dftycsv(}jIfN;37(IwIBanQfi9x#ll z{s#5gKag`^Q-!-7@ng2-uY)3PXa9C7k&+a*FyX3;4N8*|#y@Lk)YMV|pLae6+0DzJ zn@iFdDhKuhw$pxei-3ry$JyXUXl8T3ut3=c=b4}c^5XWT%nlqA&tR*aG+JcSba<0< zDIyf|PME|(VurGCf{xYWFkGxPm3=BK@|aI(OsBe%FNFS`t|dl^O58`*^jYUjfC9u= zjQm6%?RK1Pq8s0lG04eaCJN}byNp>H$G7xK__m-Q73tHd1yfrOvr2DSl|rZahaCe4 zh|-!*xGx1+7?s6SuVdM`)9G4GVd$}?RJc6S`|^qvZy%*Tyw?@g7x<+& zh>NNkKGPu5>hNZ7A*dgusn@-Jo- z8cr~uACd@w-sr>Tt=ZSDeGWeF{2EzIl7075TWhVIHeu1N&;bVMK_?GeI|v?zDOU<= z`nrhhAdNzho=H<%Z4N$!wq^i^F24qJJ^016ikYy;kT$_!x$(|uU@^QCCh%m?Gz!#^ ztFd8j+HKp6b)Zjka9{zBy=Ppvn^5=GC%}+E0@A|a@U(p_Ire1X1ole(7pg0xf~`E) zKoG}ypq;qBfq((a5<|_r<1!4?ziE?s!l2RBzpfBOsD~ic{WDs-Ji+*uAY~}1h|yzu zC-{}Y-&Z~4QH??V7-+4}2AzIS|DFrjM&n=o4WJr01YqXOovZ%EjVa{P{@ikG(h&ES zl(en~>r>d%QjnE51fPRtzZdq`e*cLk<}B>YgfD~z?E`YUqJAvMMYBtT7AZDMT*#eu zV0K+}u*rX!yZ}IW6nz_+bO#q{O(>|m$_|o-{4Z583tfWv( zX@(Qg{8}^E%zV*G73)Yh<{Wz#21aAJIBsKk0(;0cdfh5$K zP~)+5A?yoz-xYz_fTWvAuJF^m5ui$SF$s|nJa~Jn_@9=6F;25@lv(yCV2`i)zl!xs zXCktrk2}r{yX|Ot^}k2GJwL@DPy8QVpEJUw{jA7mC^V5<#jYyh0xxSeoE*|eM;;&h z8QC|da}$_8y8gjY(0bTge`6)o-}si;aig3hOMJOyFikuZrZp**djb4eLAla8_el(T zV{)iiA(Qr4tzTAdhlPC?CtFfQ^lXLY_`R?zL@<(soS4%P&8iGomG3*DFz6W&ao)HP z38GV7)n4yiEzhdcT`?mkeAxAH{TA~R)L#43>&~Yd>Huag1~Q6(eT?)`-!Y8#zD{>4 zaLrs2bV>~Ix7zNwa|5iqpMPLi*%-oI^ z)-1iNM}vz&$lpN{7Tes-uy(zm$JJ)tP4^@3W=E1y_(rj}6H1c-SFB#Ojh8li{G?P@ zU@~`U43)5`Bl&2}tu(q~s@7ww>pyA5GQFbZB-R|7dDeff?INr>J1=xDPXgl7o=XCq4 z1-$@=AXg6B_Zb!+tC2SexnjiGJMG*z=aVAZjxxgnaZDiAoStk?HF^|eN1wRNPd~Jl z3VDzR*0*+Y@52IzA&>9w)^WkljUQ&cpDy3=t(l4>Q|@2NfS}Vq81>J}>{C(%9wU&&Z=+2BeZmnV?$1UK!*Cv7#`Xuo>BkElzu@l%Rwej8iR?U4Ap z=zS1s+NIARD`>8(w`eZ?n5Euvg})lbFX%XvC#IEMsd@zvK-o zDZKbWoUzOdIp;rs8b9Lc z$9OR$Ptzbx!VT%l+6Zlv&hj&oO};-d|4oXTN@WKC^a6&*RBofnN|rCbd8D>rPz%TT zkc^XryeePzou0z+q}`xO6uqfHjEZ_Q*Iipa$ApcQ9KeL|Zj5Rn86_0{v zV-Ly=;UubN0HaOfcub-VhWyl{XX@wZBd2i}rE5_8Pe<3#=Rc?}cgD?CjLsL5S^dJ{|W+SubRCp)g4!Q)lScab~PJNIDaQ}k1NrovmXvL78177#amsyQU- z?lRXrFnNlRtn!blrFn&sP%paVK-zSu{N^&%WV{dPxk@ztN?X0oEuVHCYw}Qzev#|T ziXOYt6{F~9UFjEOOW6vfli>W9;sW-;=_=B8<;Xr!p{$sQtwxY$U04N;*i7E}>Iuq# z9V2x=&(I;gY2)XA)q%yKN@_ScHd;U9HLS0c>r{vCuq~I1 z+kzxwV`2JSyf-WEE8Q-(SYrAzz)z5W=Iw5B-w-b2an}lhevXB$4@I7>>~-oqTN`Pt zRJhRt-gIIH^=iaHC#T}1*U+n%zbTvZ$Cg+F+T-_SC{)!*Nh}h?Wg=jy3;eyo7zRL* zQPm=Br+QGMS&|-6T;te4-ue4Zu38x zHHkItJ`C*~N+@GzU`u)lYfQ7|r4M+^iF6?#&NRY0B#Jg>i}g1SvveuiT_LcAI4sNU zBcRG!=RTg0kC&!VEnDIM=Mnm@g21xZ-CM)x9yRH^WM1e@9L0^}E`))J=HMbk1Yn1L zFzz+a6lMM^;bzYha{AtgA^s%;w5H7UImuZJTBf!`KWW=9gFSDVi{2>0Nj;-Ba6W$r ze(SYOtKGP#!h1|jF+RR_QDZCNuhOcizhLjoyNU{dKm||_NAh{=mokBF(4vOY4C5WxF zH`R#FTgsi^I1*Qu0%f%1f-$K&@FdL5@TV1z`-2{49at@jcT~ZLhNf-o6u5@I;~HB2 zA>X-Wu`+!zw+A0yA^7#JCY>ujRutS5gwTxhT7VHihR}iW1_0cT-!Lvv5gqRKDrfUcI*U4;1kp!Rtt`f|wgef)Gu-3Ybe}n=Y_66n9GA-B+ zYp1jvHW|5ucB_ZT3kLpW!!b9qMDDAh9kA#hG1^;QZpS{fBgEI` zih@UoK*=!40q&8W*6$OSa`o$4_`)snLi`MTBzDJDERZ@4Mkr9ZEWDE31PQdnp8Z&@#l6p0$hY-9T`)-fb^PF$D&y zIK-8-fxoG6@s>nnUJj5*gD3w*R}Ur;y1K;8E|4QC6rRFQ(zs|8WspO9sATM%QZLf|cznK`X+nPXHUJfMs~b~1qTNZetz5}zRw>PL9%rjnGDjdi2fuwRD(}|! zz!@aWSf1R-E-tGSrQ;}@I}ZUT<4R0YRfG?|FwzxL8^h>HUVTP|^HQ}E*O0HXbK;D|%P6qBDY-yB9xJ*;c zZzI42NjKS>NAOT6p9Vx|PlCu9&)aMad#HCD4-XPIacBM>hHn?dbY2jq`CB+K;K_=j z!-$Fc0e-cfQrUw&PrPe%bd~v>CRKlKp25V)AFj08i*WeP=o?J3(MJ{;Z{bwLS%h`( zw^G^7vNGnEh^G&KQWi#0#EJr9o&oh_UuAOqcA9TH{a@L99);EP0oZoEE7_*8Gv0}` z0<(fSx!|q}Xxaec0j>|X=ajXlgNyM6Gj*y0YgOr#J-co&?YQ*b$&oOPjMd2a{MZhg zdAcf<@Sg7b*FsH$e@OUzUdTRIxH$VrmO-gbT(>yuEOF=o!G7MktibBxsq+7P8uemC z>r(;#B4h_|xM<(UY=@850K(azZKzfGCEtMnKd`zbX8U2-EpPLwKH^Ws>kR(fmbKkv zcmCI9=qFIEZn}Acw;+$8FY;i8prj_L&B|G9nJv^j1Qn*SI1~lTgz^2%|qmJWY ziRp)&68QxgAT}8XbdI(-Q^)I@9;&(-?UR#Ldx zCz#=t3ozBGBuW7s&5xBDsIi_0bXqi&S)RZJmSH9cE8o_b9KfH0^Pt_{^PXD-@!7kj zdob{%TtoQx$#u`Me08tRk{0x_xo!d~1=d1>!1)J26SfsUxbv$TninMzQS_I_3&JV= zX_7ejw3zZ8mn^+n@0UsBQCno~OiLV0+aMoJ7mbwAeilzKTJezYJei2y9YwRPI@6ax zNC>A9$|@_7^LD(_VJw|dqc!U=BYx4|29Zk&`u4J@&t&riBcR;eRCS_7n@>`^sj<}2 z7VQ!xVh2x&yoX(+ zSQ`T`I;>hJ9c?!Tf}@vX9MnG0%QsLy8o%>upGMMw1K-S_GN`#hnP;N{W$%cnpxU!NzG-Qq2<>QeUx{fG+p}PA5aSG3=*puD=Gm;{= zD~Ehn`@!8@!xMBlUZ)$c=IR3R_42?ygiM1@lXcb#?^~vt^MiB%21c_N-j7hGA<^7X zga+Rt-50tstmRj-^VSOKM8D(F zX8mh&0w3ft;#!}LeK)DgE^g=$XZYaemh%^a;uHH7vK$wgPFchE5c}RuLZRwb9!Txh zb5wT$j*27Y6PUY~gH%IMVqeUM(cNY^yOS!?^=fj#t?|Ec-o418Qjb;dT6wpp;j26N7 zfRdq3sx5gwk665Tg!KM9U5NeGR`b2{DtrNIKIswvM!rW|V$bQWwxXYD@)xX%OJ6 z@RF7n+BbWP+1AAUu5i3?NTz)O2oO7;P7f}i1FbE&y%fBM><&dPSI;5@I-brwZXed} zgdZ6Ta|ed5)!o?hsOIs74NNZlq=3M&z6UBEpZ*X|zMsE7a6?fbkm$Q-8ckl10DAWf zsQs`(&J2PM`Wi&skw<>2_2-TcCs;~Q9SeyK0p?Qpmd68!@sI`B5}j+5K890oA6`IJ zo2Ed7O>~M-AF~p1hZ6vd*A`@aTr=bX6v0v{3Cwt>vq@qs1;w-lrZesTYX#Vlju6i~ zJ_J}4OB-;#uUA1PhMmlz2Mg!pC&5&Vx<_s`_stdZZn6-f2Y5Gn{gVvJ_cv(&cD{QEdD2rgZTb=-K-ZFzUvTmoEk86`?-Y5{1Zzec!gT?=9L!a;G< zD=T|ht%UgT^iqhjVO7jrDqNUFdP{Ub+SwBPCA?_t=&lcJf^@h|i08e})~a`=z1HP+ z#%S$heQ3@@3u>%7*>W0ABWn8mnz($^VE}eWKxJc9mNW@SuewH zpP9*^qHXeyFwWA8u$vuDr};B@kj6j5_YS-2TrLIU>~fDO3i&P6DZPH#=`VC{AQl+>?O=dhauu(R={2_sVU@374u^J+d&<3Eb z(APRuEw?r`Xg~|l#oXA?Cv4)6T$xl$lxrmY#`C^>#;(5ZaSuiH{j*FMVAX}EOIY#? z#5oRk-?}7ge%#xEN5p#ErAGjiNGYxdJkh+JjTLu|2z{G$J{)0NqSln*K{nSVQKs}< zx(Ei2HOMGUpozM&0|INe*LgCpN3$tSIU&$?9hn?4R*rGaJp%hP_5m@RlBdbV^qJUF zDm=b*!mZINw?87x5=wZcIK3G{n(!6w)4(9p?i%nEpQsQ9ox*@v9;HO=`iP9rux8>G|0k2j zUhrUSooYA|dEYyQj&_zWJ7%Eex$oA^B&{guXoE)SaSKo|pVS}?dWJsZ@_Bxk3c+II z%mqxC%&6R<-%)_-l}~q3hpIk=@wM4STi~_&CuzviyGM;YOQD%?@oDkp;Sk4%n|`Mq z{ItGQ2t~FOr0yTB4i%J-q6gi9EfHnQHrVLgFjGl9;=R|2x) zkd5&Grc%Qf*&o*JpSRZGuiMwVnAMX>T!r|q$Y$oj4_tUyRWyXkw0B|7fEl%xw!+(J z)tID`N~!X!g47a8Yog~PRjjs1xW$YTwy2}Kf*NyrJ>2HO@}w1&{_{!Fl37$O`uJ#M z|NrbeF2f?}i{xM+BoZnG6@_zOf{@$*U3*C_)U$=U2gY1^G%|TFb(S&5k$A?(=-fAJ z26FaZ9wC`X>z*GXL6%~0eB%xXNTGP)(&N19Pe1uC0XE?O!;$Q+|7zc>Pc^Lj*w!rP zacT8TM7<_>qnixj+nu1}dJ?{p1J_XnyKnBSb+^N*db`v{-v=9;>nLj#74!m|DK?vC z(D4Oz$AJU(hd0qSbMC1D-x)W}3uQr4lan}cbch>7z$CUz4JYOdS~V&PwfQYoHjI*& z5={(3)R@Y6yFm<(5*nkPRadko4TqGle#y@vvCr}w8&kcOvhK%aK+-cUzZjTl4ye*s z;S2?TggE|!VkB*3#3FhJTZ zh}1;GXs=sBtoB~Z-WXkVkKEZ-|dix*9I**2fxzK|@Y{68E-T%*Hgq6^67N>|+&TQo%_?r#+ zfkX*^p>hS7x_sWw?!%Mxrv6kgd_&*h1rnqKt`tmx*Iq~Kf;YUxtor+dsW<|jEq+T; zO#y$Ygn7?6GnU~jopIY-0Y0+6**jP>PHjpH=~HI}j`gBcWz-q3S@;B8%;nh2^QNH~ zJ@xw~4jUl8&Af)osF)m!yx~?hHDP?wh10!nIhUB6XQe+v8HX2jy9|#&(WY%E-!JKH z$uVpWIF73-oDBhBnD@SEmsKn|XyVB%(+OUV5i-y#=<1EY)h2XNdZlCJ1;gCM)|f27 z=g2z`mjl-hSDlkk=8fPpO!qGSfeN`9@8LM~4t#up?k47y>A6`>-v*OJiD?z{J@XtUrV8HaFzQGP;Ybo=O4PQze zD>TCb!8peJ^;7m5ywsj{W38s6HvSJi#7{ILaYX3#pUXs?RX&Q&lPM;&D&OG>#w83) z2hS#|=M_y;3=%?%Ir2KWvV95z7&%)#0e_=51^1jS5vx^ALM*6t8?%C|99U}yVDmh4 zOZNY8vy~M{SXAA8%SD!wIHLq}v;zh;@GZ~zO;K8W_t-^P(VYTivXVp>`}E{KPqOVi zxWS)g(rJaFHHuP}^RH@#HF5k7$vs!S4eWTY<1}m!EB>?F_m~O!0}7LzmVs zLi%@>Y17G?GV=*tN3IzNz>8tSNC*BEV?CV`Bm7VzZ>)e(QO-)}>DkG-VyrsW{JEpq zerI|5RElF?Xuh6!2n_o>vdaU(&|hXPGp%9O;^0j|RoD{ToLrBnUG)tAI(6S}5V5A$ zON7&L&iKVgw(ny@PpxUh3uHGv#{Y^`2o}H8io=MFf7Xx?0Z9hD8O4VF?KYx?VA-BU zU_f?7#>frVtv$^r@JrJk(=7)gbD40Xk%h5Jc(qSSl=LFyp2}*Y%*x_liTzuG9O38h zEH32#0QXyGb-*`zfXdFKgqVP zb*$BH4#Snxt6kqPX5r3ZsqO&)vnU){RX0j?{jMuq^hzfK;2U>YuI#L>cRQYW+uhqd z+eSt@jJv;j>3sBUU9VHJg1gge1$Oj?LnDQuv|4D!hYiQ!e*<_fD}{D*PW|zjj*YTu zouz~J7UgTGUwPH!nfFD*n;ea&=VL=%f2m`TEWC_23BX}IgJcLMg!Rnns!2$>3Tj94W)2GcWS#CdPS+_B$~)s z2v3LkMKT1|AzZwtHhLxe=9JJjhAY8(Cax_$r2cD2QYA2E`^Z6HqY{bR~62pVSlXgsf;;as?9%%-;mIPd*Gj$n$C{K+7H9f-8th;GvIi`0O-29FT z_RnNArC0pM|_iowQZyExkH+-@LNeIG^dK>uP%<$M9@5%Ysdfq&M!TbRuj_X|uR703# zXK&B+mwLKODW_mZBPwLV@1vHT*k)dt#RIOcNqPP0j!6?**{643}L`NEaJ zyGtbq|I1>Py*1o+0+2uM1>;7Cs^bWM=R&V^1{o8pSbnZtortGY6UdxTJ|;ky@3eW} z&A>X2$-l^Hu?m4>hyxg3FZ+KS)4PSUN0`%ei=sh2od{DSDkeZ^srw5qvv2JO?iD z`3U?bGIThLNiU7Oco=?wiiinLf@HeUCo0g?pNo4~J_K+V%@q1IlI|NnO$)oBxY0g* zN8S|YFFhPq_QzUQ_BYTzM5&L?S6#Qg&d=}JDS$6D&%Xc;IU#qjm4$SGZP|~qP=PhS zt;5%-Mf$*Nrp@NH!Dsej{sn)q^x+H%5O-4nWgTh)vYqGSY|^2diLpPFV1mJGRck+* z%yVUTGQ|!F^{jze@^3y{H+`Xg!C8Ec8RwzL{I%NVe3<{&74r?(*~sbo^zQ5P{gpwy?EQ%06Rd$zr}Kbi!7RG zi7khwMZ+FAdvr@Z_VQCpj6h~dVIJhl;$OH0ml1er6Gpb5;E~lOH6zj6-wpoG`$l?| z%khidaZd=&MgY$DDA%7tgc>zaRNY2v!6_U(W-PQ4*2J*jN2xEzVY}cFt?|iLXj3XrTQV1qS z*|yZ`Y=T0Maj#z$k&i|+p%(*Zo>miKa;i`4a-U?}aHiCkkz;^Yw>%>MU>4~MT zP6PuD^sTtdOY1O5Q2{7ENrGn28-6PHk)SMpVF;DNz*%W2qc1On$!l(CFG4;Jr>?vP zvNUT%*knHoB@}}7F^}ri96hlDR_}q%49`Q58%;|^^bRP?DQPWD=5{ORD7zLpwK z;ej$+0TC`RMq3j%Aucs~l2liWMFpT)4099~{r(^Kc{q~d zt}RC5R7*5|jgn9%^cG+sYLl}Z919@nPhF&!#GC)nG7yz94~=HuO&Z-3NtS~RcPNu4 zdgX(#!S`n3Ad>y>^D-3^#iU}odxol!vb?3d|6{B5>upkc5V9s@R+pXMgFgOgkMhvpx zE>cOST){;VgVthK?o>XFEAP<)_;p1N9;ZUL5g2bF00v29&vQn16EhvCGc;CE{DQ$BmIi%V9*qAgR?C~1{u0D{4 zA3M|ACA=rw&G(8e+h@wW#p})w4Se)tvqBt7A({@)m+RW;Jus?YU!!eOhyhpLM?>9~ zYJ@@Xn={s9Z*mg0fm3JzT~FsE^Xk}&l$JB=S+M@Qe7z~y+RbcFIrI{zsjfYym?+IB z><71xv&e>lyiexnkf6$)KegbTwWTb_mwqL7*J%G3l&HcHklw6!zJK3vO0`h z$rgQ#3%R8$9kcP3Die+FsIdy~go|$87!qDE=6N_mpM)slOKovG63#f@E?Ofx>4<;E z>>}Xlnf6;Q(EO8^mTwzc!FrG82CFdF09N-%=6gth5QV9J@>p5J!TRwq>S%SAc`%Q zCPIShEefbS_sN5X`s&Ba3E&O|@<*0)M#G26f%6nHSOkci#3@KM!74x-Y3CzO6Vz5EgESV_6BC{XXLdM?zo z_QvOQVO5}UVy?Y!tK1^_+e#u(1h?xXCLwPzLbG|*+$)oa($yDkqY{LMgc)L4$w0ED zk6pqx8F6I#Q{NuTV20vo!I(xtI=L_!Q!VdO`YS=UU8{y*JaF9ocdod7^&mS9wo%U= zq4l_{TDk(R`^~L90CesK3+udHx}cpEe4Y!@PTVVxB$SQ9d~?hmBmV0qN= zJWQ%%&+&IPjNWu)9YxO(YL8O#K}sGrj>qOPd+szU3ztQmUz)IvcPKY_x>c@HNUWRe zR{0-~8Mb@CfAU^d@l&1+imEFO%awxCd1>r7tgY}u$O2FI)!T1~%P;!dc!$i5G zA7Zh{XYlUFaUG}Q%5CD0C2I2at)m;G#ZkrV&}1#}a?i|CQwjThkx>{hi9NiXQ1R%E z$B|b#Hb2I}lN7g{W5BI_e^2?-MBqYY4q7iUO+irVl+O|xt^ePobB&w8IPCu|0=4Q_ zN7YeyZrpG$+)deR;hOlbs>e2qH`C`$|o`XpZzF7by~&lwk5 z%UQ_ryCBTDUdSjM4c+X|kZqqulMk(F3teOKp0jYd9jup44JLdMTFG+-e%b|oV0E>+ z3u%<^z|ShI^X=WI9yhWNesvi3Q9uV4;v7X7a3Zj3fiW$>3v~Foyt!B%)^F|KH(WD{ z!&Tmt#nQr21!5k~N?ZO66KJXNm435WwO-h1LNy<8i%yruuhkv3dSR6+-*?qHCQQxh zJje}U@>I$OjXog1{2H9SzB#~dsxQ&L_pI9*fzjN#YYfOgaV_aMa>e=|xNyh}!oK8$ zAZ{|(MEyYn#{k6R0?M^YdlB6YoC(6wx6s+t;iy{Op39;Nulz!GLcO3EolI*yE&S9o z2O**AYDoHMzPU8gNU`tQp=g~llO&NSETOAGIP{1G-|HJ-(~Ev?Gt-7w{ShT}lmYmI zZ2!iA6;^a;p!KC1NaETTzX#+LFzMM$^8whMqWWtSWa4d}aGH)m5Q#);t%4FbO``QlMVpyV{>e68miSu5+{!zCTX@4- zDgo6d8u+|9Mbnd{8&#*0&yhh)lLRNB!?`x+!C{&EMg?$!1oeCdoDAFN=w|PqFsSnD z^d2Hs82l@t-8K}ivF{I9d0AOm$rane-(3*1j|BmF*UaoYPE|OMHUX?ofn4y*VL~|e zdx@1@E+^@5S#uYz2z|$F<|zsL4I=0TQc>pMI$Fr8Jz>~J9+oaP_Zd5{VBGqCq0yw1 zLh)~jC~N!c>-m|!##zXm;YGgfiqJRMDQJ_c-rGSo16o4elt63B<|5utYCpX1a>qbG zywdN}u5M0Gx>D@|hJO1{dFk#}sDzbUGGCQuz)rbgN&DRlaa$b6u({JM6}ROD?gyat zcyYtg{!@;D1y{MCJD&5Fjy{mMDT&ikpT9Q+mV+_EQ3H^D*3fE*JSCEVFl?XB=X&vH7TNTDF zR`ZjvvAG`(t0{8(=_EW1(cdqNMZ9u*YsZ-fqhhrb? ziW-a^Ifp#UkhuS1F>4=x&0TLNL%^S}>0-n@({h#}G z^rsYl=T>L}u2b3VKP5T3c)D?KA>YY^tV$V0~mMkWeMlS|t-d0Gy7o{V>vvXz@ z+e|ZBJTp#Uo;cy1()%r@B4(WF#0n(Pi{$$;(cK+UF|Y2lQVeZC@fmhTj#olI5g*-P zZY^GrHPVcBn02Xpb)~U3BTUBxDd@1Rj{>9zediJ-{xU+&$*fgVLCinDsb6!m%)_}h zeN=Uj^}QN{5cKMpH+<-Nq<|6~+Hw4vB(f7xt-T{NxB*UY9>?0SYMmWWB#d&7H3B?U z%P_^kbWS`DJhxhX77OvH^--XZ+|139+W`Da%BvNoq00mp2qXwiK+7dy|5XH?XX25n zWD3m3nOL>@Kh}5;vf!&R$wuKz(}0@kaUTbq!Q2d4i{)92_G|c^rAPU+sgsyG=F|+x z0AqWlHJdIyCb_x21^UHP`8`zU|203+TnB)&CkrXM{i2 z6I~Q+G`RSy7ECnJ21ph-2l%)4pS!Gb6Tt5cAw29^;$RWCOp6q;W1MUe1KWPhUL*w^ z+{AZ?A`kVIivkFAhx8z-2@#``BYWC2*3j=BKac92MjKG`>>r+=V-FU(#u7yxMvn3j zPi~Y@KN5wSPM2>e@?qcW%M9=$dU=nmp4P$iuOU9|Wm1ZjB69%QR7X|H-2w-P-4X5T z&F4oZ5$=!cR@766zgW&;J-0Tr)DbD}e-0VY-?es|knKObHK23VTm$J`q&(XFRe41Q~pb$7D_EU4W<#`Jqf0$5W8n(R0-N1{&q+Tk3W)cx-w>q*!kY}if zR@!)b*Kg;|OP`J?iJYhs-A+rV6}P2jvZpVT?*V{WBtqt9L1o_Y%I~mM&jdgt%99(6 z#FQX2r@3qc(A=B_FOHRpUb@dy`=gpTXm;A&F=?SxdXq4rb#v)RzU8xeUJN}`)M+tT zedM`uE!VV}lTRv>yXL1BcIZ^`(JU;VV`5(8D2F7nKd6dc^q(*U*dujvlSVgEcT$hG`YQ0aPWc?NdMLtE=-trllxISh^Lsdakp zMUI|UWUvdpxQ)K%o}JkvCOco}UTu7dsBaI;O`!J>Ao&}sC0P~@3B5edNfZibKh`6+it zvX=pgx-fcJFd*vd-uyIxtj&z$pEYvbWTyp(t&@Z!oH4RHVQQGT2oiQEyNd@aQ15C5$erLTfgv`wej!Ymm)pY{usVhoRfcscE>J$t zoRxfOPLX>;+#C9bE6tIUE^C(S9+yQ%Ih2=Rtn4bN2Rb zvF>UDJWe5W1wuXy1OqRkzPuSNNFX2w*4SxX4wuksN;r@=K&^A zAWhWqEitYHVa9y~%Mt&g*S8!LryQeeq#LNmM4xtVikJWt?LQ#~mHjVglPlCMH7VW2 zXc#gnPwrx3>=s^#`eCSy6{Za`W>624gYt#woGU1l94_&g5u+#u2bNfd`Z^9^C~2g-WEfQk;W#zz6U zUEvRT_mmJxre^=nCaLZ*$AMp;HcEh8$iZmb14k>&5fL^t7{4zGgG!9Yk%bJdZAX+C+ORGs~=qA#jxU_?Ubx{0C-7b6wNfKX9}c zN+S}&sw_U0_>wh_=4UyYxx-wc=sWY&EHwG9hv5Uzim=6znv%Q&#|QlJ|6kTjLwSh| zG{WTb+m3>7`0TWCB2dI2%9Mkc77Xk3I`-3IC2>8rO&C!!yN!3Gq=%A*IlxSF+VM{=RLiF(`M^QEp-s7 zszaqFYKw@_=wd2z=Bd5dqLC#Q-I2`YN<(ncPx6C@*N0tKwWgc1aQe)kOP2TS_f)dU zeLeyXaBUDKiVdG|4h+@MyS$u43^Rz^89OI;y^YhEKTcDMbLHIS`!df&slqO;@LL>f zK>MJ5v|K9VEC~34!j@~@%L;`O8XizK4bUBLe#K)r2>GE^eS^&i(uO&=6{VxQuF$0W zda}J5sGQnCu7x$}n9}F?J?@ttpK6Q+bD^Y@WcnOc*jVVI+qLF_AhpZ6p2_dM z_}FhOHVn$Fl%+eOk(4s^&gJ!lAa9fkXCd6kAV04>?@}S=aZWJ*C_M63uc{K@XkwOv zHFk;-2Vp69aA;jnpsD=5@PGNY)z3t9WhziY*TN;YrtG9%90OO;ulcF9IE(LoMeDO( z-a5w6z%9D}O#YyI`YUQqiXb$nYh#07#e4b^gOhF*X1}sc$D@)I#nriH?^DJ*E6-Aj z7sRpYaVEqXv%(rWd2_R^dqXg~A603HMjqh0=8=q(pbbsR_2`)Q%BypDew!0>dCrg< znkhXc2U-|~V{?v5=U#Hvr}T9qjY9IVA1fUZg2E2+IP~9!`g$61*qDUBu1<4RY>l-=$tQx|EPII9x8f zu)cpFWNpHuGY2dPm<^vGB$LF&`{_I#$crTvBaiDjHWL_AB`(_TSnf@hi6!%HiL;mz z*U*~WyT5KkWkT*Qx$t1&`Hc5*La<_)ozk`jYTPGkuw2xg&(Vg2wFs~8_VBa`^w!PfOGCOnMh{M`xY&&%Tv!+^6MF>8=XZ1eH#{!7^&7vlEer5ohJBdO zp#T^|E`_^>{^i8{-`_WtPO#Ps4Up)dQOkLIg`Gl7!t=(vwE4i(o&buykEI>Zj+a@K z9~+hES&@`xL>Qon)=D8#IjSQklae?+@+s%Vng!#kZ?C&_X~Fpuu>Xs7PtrzIc%VkHM*imW4VCyh;E#S<+C%gOQf;lwd+vVubTC81I1 zZ=R_1eC}J-2vDMdZ$oDJ(l|ZhozGr1H!zme&J%`kk(Z($yA0=ENpynaary8LT$C9! ziSMxM2Ka;JM`%V@|>5s^9t&FoXx*RGXByWe9UhJpPIt#N|XQ9kdJ|t~{RZ!=C*8Y+fTm(h3 ziGsrmqAVjaRf8;aDy{cVHSX2Z5CdQvg_8su*vEBDz zySf~9@S}x_I&R6P^`*aZy7#lx_wJF{fgv7x+ zqLk9A%UF<~1)o@LX<8kY0n!`*l2NJE4h`M&ERJRms?dd8Y;Zx(MiM+^8o6bjD_G97 z*SDB4JJ0e1^=fKeh}tOJ7fhfr-uiL!?+BX{n$d~@yD0CJw6+}64X*#qwx7W641&cL ziIc{egf!YT6u)5E6eaKTfSbn{n;n=ak5Zrgp<;U175ngVKA-*(hMIQhM+4g}SJz}B z$k7e^Qk64IfU+ktpD(75WZl zXDEH8NDOo8sk~VBGa~wgR3!t};Epwbk<<11!R$4pls1Eq*I_exINS0U2HhITxcYM+f#+trOWXIxaV7@n; z@+rj3LiD_!j2hnj9HadW>aR(Ei*1- zd4e6Mu?R%P5Uo!i`JM?Xl!}Nl-|{XSQ(f`dF&y@9MgoLOe_lo9ataheSrq-Nyb%+i zxFT9@l_xG#6{Ji&>IPcl8^!EVs*Ng}Z<+Uoy@wAdsVbW@bOhLvyPW8M2H}9+-4k*e zE7Rb`>6Qp~4fKX|eVM|YawM<$cOrkC&lV<cVMmxbEkwB+lB^U| zjICS`a%h$6`mxmmI{;DUg48YvtlEwc%_gpleULJVjGZ*4kzbcDaTrwdm2V9YJ0>n8 z{)5ZAWDA>?L>F2T2yoZ?f_77?i}}v_SK;6W*m*shH7jinSvu?yCLrZ_u;CF<1-Ahi z**F}U`qM8ekCHHqCbWcPTJpi-)Oa%jnLRf(T$9ROI?^HCDI?F2Hv64b{w!r_C`sjQ z3I@P8Rr@gf7dY0``vwQQ=I?8liM&XWnpywK32-<*p7+V%(j^ejAcqP1hFFPc%HUV6(vOa^q90GLiIc zpL3>&7QnC0hxJZr(^ajW|(G#~`<1b?8%aFKJr9o|L#%G8l{NM^-&?776)x9g= zc^okq3JHw&&^|3G*1Vqr7f7ACa0v#|C(xe^83pxVACP|w z3`W{wol(7>-aE3^OG$lmk;{5s#SRS=`nJ<*&oP1EEWB|Eqw=*|l}F;BiPgq)gV~qC zAR&kBYmqXq<&e}gT{Rv$rxAaz;|0pF0}hYEDkc)b>#DqW3Ib)GVziFsFZ<`T(}R=g zZwQD56BK8(gphjj2GGD2drz{|Y!kH8p?_Miq1@XT6L;)SsuapUlQ21(+ZXd)W|=;H zqwTiVx0OJ*^B(1 zD+5IK3-=1D!9capOO$K{G^65_cR0ZEQR7|Pb zNX&-{ho1h?`d;kdl8SC!U>AYbQm&|)u_~i<5rMS;g=0ORrzC^{pO9K=3r+#uqL?cy z0+iExoUYsP&&0SRq!hBAJCXq6xrK|n;3=s~u6A^`KDStpapcaHa`%=IEw)sgziHa0 z##E-j2s&$f>)2W2f-DgycB58^*psyuPd9z_#D*o- zSU@P^LHAtdijWIK;M5y~sxGA!WB>Q@H_{8{v$t6u9xS+hzC1wv-db76KHzti=zKrs zj$8XpKP?`5Ox?o;l>4|}lTQ|l(TVu4!~9*Oob4@kULvuSfRz^BXHHbqQUrmF@{EwR z(uHC8m)@VZlf_!}^>66pL=A<0W#f2?HfNrxDA&DrgEG(ixWex*ni)Q2kbc>F^&1&t zjABjRxC>lF#Z)L@)gI}|w>^LR(;IX*&-Plv5hOFWelDP(@!rcdY5&mzStE}u>Bnp| zKkuc(spzgBZ$tsJYe!n#_OAS_n$lTSd|I}QtSCM>tbJTP{fugJY=^mNH7yPm!Wghe zWeL6RjGb!b=pZE}mS|%r{G#6Keu5I_4A7gkK?5toEj=pQ*gD;EY%6esnS<>x^d zYydM$6msrvq4H<&X+dwIuf&hG{`x>Ln`&NN_YcN;VOwyE(kq*NO$6y7w9Vd(+p2>_ zN;W;M49h`(ICB12YMUZ*Z)bat16))0Di3o@Q~!jsuvKqz-fXj>P0|?1`Pk5P*2{UO z3fnoufvz6VRSX_HOeo0uDUu@Tr^|XBB_gV#UT{-r$kKKizH8d(3a{}PCQ{^Yxf$L| zmNnr_#tGmf>QT73Vu+zsTWl%3yJYGVcKTmP5_a-zapZfl?}b@ZZkTV`cT$x(VO z6%5oFJ#`#cSSw6jWv#c`FlF*f^vg`Yl+fG%2CcEEOH@{0Pb;9tolg%e{5!ImkA$g4 zZ09ZW8EK$HV-bCKwdnDsqH9$_v_|cbc@gXWBE)peq;%z04F&k{9C}!L^jT5qFiCVp zW75-m-4O%fCXMC*nFB`{4No6f2H9YoFJq^jf6DVBXHvyE*S-=j1JlpI$)iqL1u(_W zDzar)JJ#giKQW)QD(Mksx>?e2ae$YQuM*=Yb|7iF~aAMMrFvaz-VYtylxIQ6_WsJ3nt8t!`@_;Qk;+ z>qy*;c#OI;a4l5RCv%4wdEWJs*8`(!J3D8wPvI6u46nOUJ}Ng*O(GC!CBynpUikT> z&OOBv*SOM6FL#mb+Q|}Ouk=6EIAddR^S^=9njx~ND}JR=tn6S-ZJQyo zCv6k>w)bQMd166isl;+)7z5Za1$KD6opsqq@FUWj6GpJwzrg~_sNaW1!oZA>_I|m{ zB4YWUSfUN41|tYrk+w=Qt@LWv#n$g)3%;TUpjrT8Wv%LO3YhR}uTGV)>nUCVZ4od% z1nX`?wp6S$zHj2L^1ik>^#!A4o2A!k<%+ghx2Sruf4Ebf z%6q>tlm9+WFOW?_W$|I*Z}d#6We+?IQnNgjdx=nJ4FnAWWs?2(oXr2?e_vvXAY2*g z<-TPFcw?A0=(?v)2p1__CKcgF!;tyWA0ZYfY8u_w+{+A-{t?l-qS#O(%w9aRU@Y+} zzCDzJrI5dn4@>%AMfjCP=< zMpxq-f0P825rH58`4?0zk@GAfxAqcT6zb&ydpbX*SNM!ekYX5=*b)F*fk5q$y%%A( z$ERT%R_H%QYybfLAcW~`_79px2*-HAt|-k=(PBTpuRG$YaZd3jV)6}>DSTIQQDxXhmuyk)$!+Qn?C>slR@$iVRVNB&=w)ELP5$@?*R#m zttmo;Q>hQtx@N)cK;5Poh0Ug}=?~1HF~mRr$kjhm14-uxA;ATCAWdu|FWQGcIg z#Wp|tu0y~T%(n-Z>!>aE!sxX(IXvTT@WewpZ~YGvXNBt0_4;KvktZvMN`@=`d2SxL zB6V9CvfaxUJ1K+Ua?+}^`3g|X);0>wAs)uTN4u@tKu@{(A@sD?V2N(0&jk*TZ9fZS z!o|W;zrMU@DTV6K$O}Uf`~5n2xDGyDw7$Lqc0nR;f30Yii`nH4ha)aJf`ldf2(ZMlE;p*=2#vtif}qzDr6gRrza&h-rirpBBNaizZBJoKw3? zLktwtVx7CZ)^Fw(ZY0_GmgZ;>D>;vd4q&Q!|KZ zn5^X_;8M#eb4ck= z%M-6-{+J0sJ*6LaAhkGyO`$PmKkoO~Q!!+LS-uUBmkkVtF^SHU%m2XrlIBj9QXjqng6>gx?akmuIM5 zK%7y2iknK36%&XEb70|jkU4qzt8M)30pH=^erxR-ym9rQ&N0j`{J$0*+dYe^`w;@= znUBM-2&YSQ+<+KIz{kQSilzh;DJqeq{=EjtmF<$!()FVI8vjK%vzy5#g=^w-1rU-9 zGl;qVX0I?~r_*q^)r|B5AuIxvIhRX!@W%@3N2t-|ud80Pj3B z-qItYBvYPgphX#Lh#m}-mLpHCHyQ=#u0G9@xw$^}O@LT)$yl-jux4T5U&ckdnUOt2 zU52R$<^ykin->;VLR+^pz%v;2qIYEf3hT{ys3ar_;tP`%s^d;;El^e>FZ%Y`p=dEU zFAm3^=ZRjGa=iH$pkzj?_{x0RQAVK|%WF!i$bQIqVf0LLHI}q>l{QPy(-&(TF7Ay@ zy`M>^2j)32iA2gS%u&e0Po1@Nsqa~dB48AX8^f80GE}fFg{NOEBZ2<*Z&lE!zi-_} zE0U~<@fU$A{Q|$~J@&mu$$8ziRoN8tD?PyPpxuWqA5F|-9_1f!Jhk(8)EFpE)Y`Tz zXrjQ5J5Tq*3p{FtFqj@gA~p@K&maUb6j#Dg7WqTkXKsc-A1+sVOS*s;>c*vjdi7YU zOM2S5?bKiZRv-fmHP$m{Vu}i5Tt6t-C=(s`aaJl=|5v`iGN<7GMVn^dc|k zX;-O4NZFiz5iTkAy3Id87=C$Ip4(3TqL7a*UZ%X6_NOCwei-RF$2+|Bi}OACqvuVB z6h|w^0E&DHlCz_dL_Nig5oo*BjOsb5J>Rc!_AH<&2|fYC&up1Y&(p;2{naFMAfK5v zY*o7RZrhL)B&n)3L;}TcJ82kRJf1=rAWs3Kc#|3jAA3MXV$*UmCbW|`(s{&S72=lE z*GNF7162HA!S$)AX!pC(*6jj;oMw?*va@s-bf_H|AMmqlkb8Kun4UWe*VyzYzI?9p zm3Eb5fCf~_2PI#1uZYF_fnR(#Rue0|;5hShH^Y)4G>AU}TWLo&8Kwo^HX_#@&|X)v zKDwqYvPkmX>u|H`{ZDu~ty%s-PPtdsSXv23^2Djt$Mp0!7teU*R zA|sp7JFvc2cQi`Y+&gwo-P4q+F_k|P6t~xWb{cR3$L*T7;=^dEa>PB~;Gp+;_xaRf z^_!M0UsK)6aq3=XI%Ds5AINpP3A(11TqC=%aSqkW24gnNR3gQc&17XddsknBLV*vk z?2pwu66foUkc%y6&j0x&DySYu!mC(s;SAk_hkP)oXhVZ}e&{p1^X1+!r*3jL4dzm~ z!tewxfT_BJNZ~(*k1ct?0B4+_IAn7=;t`3~GiY8LTnEDte}XnKhM8dE^Pv%VONTGG zY2=OrwBUA5eXZ@s!iJtwl466rn86nM&VJ6JtE^shHZ(qB9eXCiovXCCylyQ<{n}e@ zD~nLi(O7EojFDzF8I5`>NTth7JMDDYu`}x|DU<85(oF- z^Ei%W2rnbP^*dNqGO4{v-w>a+tsZ}~iB|Uw<6&c{(jCY*D+662gGA`;1L@>-nyR)%CO| zpxH3!VAy2rBIA@P8dIVsp0_ApffUO#YpA&ZP;j+mmlQ?3acyl500bOwIz4D!x&F38 zXSf9Iqc@TAqm^8Cm`!oFk#eEnM1y*b&{9|PR=qNS(aQdZPxcso`_ueSg^wa2%~Wf= z=``fQ&40nEn-06CP*I`RA;-EcN7tn#!eq%f#ClYqpF!=Qg-Z;#ED<{( zajms;HeVGa_4?&ZUFQND;*%)hyh5MlJj`JhB->f;D=ebAH-%lOr4CwuH)p$bur2#j zY^k}}ryO9!Zr$2aOuyq})}a<|KJup4np_I7MdNUD97djVR~ zy~wQAExnQYL$4=OYz2@DhS%p?E$=^nK(G!?{-)(jt;(W3$xT2i zB7R+KYJJ7dwV+FoL{*ts=p6Jf_1CcYO<37nc|0XvabH4xCCv)gd zs*5PpP-0OusQ(v0Cd=rlV*UgHA?ip=rcnp673`cDLgMSMm-3ZDIvgVMZ7Vg61c4C( z>=n4#nexybni`RyWjg||?Wl0(FMyemQ;-&cdO@?Po?QjKN6f!q;|bRFC$;a)HJZHA zRBCq)F23Gc*V9bLYCLg0qB6R}!yRf&*7W-$^R&iT_jfR8cog9$iXg9X{Cu&vb0rPa z8Gl$9W;>=p%+K0XObrA7$d*5{zTeZ_z;CkN!6O~tGtT(yUk(83iFqd?eavh2kIHRF zMEn)`e9VN`VE_fHZNQe(Z5=9F=XGU8KO8A2MMhru7w=J8Zu}$b?Wv%m&VJnRaHt16 zlhW6AM~DUVl~O0xUoG);`;A8L<75Qnhj&xAv<4oWiFszCO9z#+DPrxy#L5!|GG78J zIb&$k<(i;*v|Zrl#J7dGl~i;PEI=~Q&)z1r0f!O=PQh@%fWK|AAsI*a5n&nl?y^+# z51cW{ER7^ld0!5sAElcGt`lTvIofRw=y9mIr~DWG?S)?^{dd$n$qMRPV!6l_^9uOq zPTmJuyy0dv7|O=f3u)T-{YBI|lS#B{Kq*1g(phCKrM7ODG{ktzD|u@j3EFB)KnIZ$ z5)$)(6uVgyTLbeju=g2n>^QbWedUEVRS5EkbOhh=st2YZ!&ci6c}SBLf=TTm34E+9 zB0-Hyh@}Kx_qFM|_p#_rQZlTk08P`D-IJ~2#aiROWC9K6mDU7J&(DMfyuZ>|elIo2 z6GK&-m*ODYRn@Y=NFnX*Q)?qyP*p74rb>@2&;LuFMcS~7T08sD-GZEYa*Q5ENslsOQb*kU7|rNV zo-=emf--i~wAHK@knMGU<mE@-*;#;1dp1pdv`rXcP z^1`fiqQN0sMSTxy32NI!t2S>R1XuiQr>U`Il-fb@pWr=?g3W|8cbR@m&EkLbZcke48^0X^zvAY|%sbQ%@h0MWjlWnPrQwuEJ2 zeTa$p4(hO=N1oT2W8i`IQIuU(*Gs(a2^c-0pSwfRyeZ1_4b!c#bz|iG+wQY`z+qL} z?@uGw(kwWQl}XFy|HANxbhlaLI)S*uujU8GP)~nA6^DX|Uhy%L4WRvbVywZULmpqv zyNwhRB_M|8(53n^km@^*VXuX@Zrn*$F7@YO5H8nX-p2MnhnKiemGZ78929^5(O&+m1W$cev{e7%E5n<}vM>IyJm{g`M> zSA;;46;F89*{_JQSh@AB4383uLJiLFwZ)uTJ;p%O$Q(G9hIEu#jdLq(2%zJfu4W3H z2hqi&WBzPoz-=6dOBlldC6^6(d||k7-edsm(zznf(y>;WfF#4r`To%v=J7t_LhXCxa^-U zy5q-P+_TiwEp$d!rj#b=cYT-Jw|BV*J~Z=HmCR>tg#`(w#^EaP7l;Rlw7cR*;zsIT{JNIf}X!u@kXlkO$HomDq|2mk^uVW{av6uP~C(5AVcT~QWLWI zWt{f&evmvy(#C3_T3U>Fkg}`_g^!n`4wVGq!rz;kS%)?OkKVh|SK?DyNxMzIYd_wK zWc>shpxIsnJ0MpdnHX(@HV2?(di)vm6#2-cZ0O(Uuqf(Vp0i%zni*fFrUTv)VgQg3 zEguGRkCyqilAQ{O9zYQXmluIpu)g4}J0J**o=bkY#*U|ZWm3@Q`p;O|qexnnSH$b+ zM2%=?QsG)gRx2Iv7F=6ay0WC}|AnEdF-HDZWS493TIT<3NW`jjea- zGX{u;hvvjM!4~D%T!(iEvzixIaO3ZgFRShKN29K^*3=j7RgL*bnUTfYX%~Hv|Hn~p z+C(vgMbE^M=3=TB(I5?sF^uEiXe=hkXziuKv2~k|#ZW)lGrjta7x6KJ-K%d_fRcK+2lHGLg-7*6T#d%SAXrIgwe^ zdeYJhaplyE4$-WL9rqVuscUL;*1z0pO2L(IUpwR-$hXWZr*z|_O{aW=87w5dTYbaBrMEhE}kiP1)1nT3(^M+L6NW^g1R%z#Qsj{$m zt#&H!mv?cp-KI<$Q%BIJ0IPqSrk6#&d*@n1dI|H=u8Jceb70O$L8f$pL>2cU0-toJ7FgJ#PZr(+h&i z_(JwYkEs?Nb2({8;6cuYCaqT^c=$&FD;~ZDaaIq(;;?3-&aCeLV#6F>lu}gk{#7b8 zcgvPGO%ntBkkr^RJJNpun<^iRL26x7Z{q9}s>SqE1S(dFr!w;C>Y_eL@bXmjlo|c? zX&_%X4B|?YAVPVnKL+WjLr&oTICyxyeAsC!d#WV)?y;g_h%i!j+|gGY-LmTukZ#3; z(l2UuwZ2b9>>`vC6!Qsbp44mG7F!_gJ#>43s>Vk$Aa9wK4c zhqZju05d?$zcS2ONfG*UW1!||AEKDRY@(>LfCsiT%bb(Zz#4VP11;M}lXNkDb|OaS zQ;A0%FYPUliKHP+1qT9Mh$AKuoJBNPz`WE7!r1F;Ahg8$+dJOX1|3I9D4=m>?e%7I z8+TF8lO%k|=B8m;HD{%vuM2Wr{F_tTdxl12E$~%BLTcwHxI0i?kds!=KI+F+vA~^b zZL}k;Sm5kHW#cDTjz@o?Ditjzg8@4CA(x~Z*6Q=ur6@gP>$ok$^N8s2hDI`Sq4#_% z9YKn>(z1*x+l9Rc<419+=$s>X>B`(OA(EtZbJD@88Q*x_7>*H`&#&wT6&ss7sI<-v zuZ{T4jlztiFRYmjuXI0aVVga_7FzAl*)bkEU;-)3bR#8yv?f0(kAWA1E9UZ=oZLSn zeh>v{#P3LnGo{<=4^eQ?FY|NUGn01}h0EJ(swKpGGFlbyC8Wbmyb4XFk43VM0DpKY zaNDQsFfs*`gcgoS-h_X1uw>Ehbr-|NcIdV>3G(&O#~K_tH?$TV`yi?z!YcGujBX!7 zZptvT!Oj!yFweEpYHCEwW+!KC$!ryECda=mq^~$l$RoH$G5uFU1>4&Hq@%ezXK)#Y z-FRD=hV72odXPb#g}P^tZSP6h311TPp;wzvCl256*z_{fGyJ<;3?j58d#oo)B{(PM zp^njY2`s+=9$d&qu9R2%k>{qEsd48y1-Nt0smtBK^BjcFYZ(9sr(88jKS|v2t-Wq5 z2n;N69J6IhiT;ix%Rs?_^$vIZ=i?)WjF0 zh}lr)n2y03bZq#(tY0nZE?awftBOQSt;t06aTHJI3F-ep^~jjsPzzLt@JM>D-1q)p*Q7Bg1Kqg2 zU_+=1B>@Qy^mssd6u0jEW*G0v6y6@SN^J7Lk}1yBt*1TQR+Yo5MiM<#Xk4;3y%8=>@X#E)2w7Qb^l))NWzuhJ60^pY)re@u88~mP&@0I}KGiU*s9# zVxmRr#qpA4BA$rRv7ftu88)ZlND*R6+e6BqSDx69gb=Z?5eYe$v!3EM{EoGYZ-~dR z*0gO-A;QU3A`%lFsMNHP#84Tz z1?`>(*KUOjfr1WYvRXwSLD182Ti4P7X_+)6p zE8LwVR>LCe82JlBky)o<=_Su+4VngopZj#;Wi|M$)FR!uY}hz!nZz92b_nC{S2I0_N!kfr9#omHD3UWwd)16>@i};ngI!{>^V(^e9ZqMXZu8;Er~0QB+IxtvPcdvRkl8}{gWiR z-BgsqnO?ZKHLQZ=D=8uz#5K=fpkS7{0@@wcB@FcVwM4g`_>;% zoS2gN+>@r*g^ZVuZd^R+B{vy~xO6Q0+n|P=eKMIp=1 zA+cRs7N7$mrNe0;TGQleTD+Za0c!?-@L|C`CX9c89EJVwv@`$np@3Lxp}q~-e$%K6 zsSSIY0cxFB&?yunm$Z}Ma0Io3o!ivs=yT^>2cYEbTXbBhbD00ogcXp^eLQG}-|^~5 z^(l}0sQ+|Jz|!_-wTU(GOIn>)5o`3rJNheoa#!f?^y(s);_y~WLim?49SYqNnAWPd z33amnu|%fL%Bm~2x!$=^#;y#vv>qJ4Ole%$D3f1OV6G;>&n0^GCa-N=*5JlhWYv%4 z_uWzS<_sJ*)}mDY7!S#{+$sLmCW}C-U}iF!ST|8}gus>tGFu3OOn4|X>)~^^Rw0vDY7e+>J8&- zovZ8lo(0MYP8oKK|M$|`vS5!6lI~5I_%@@VpXBM?z#OE<_r8zF*%Y8RZEf@KvQZfq zJf36_v*~2#Y&VWpNiK*PAJ8vg;O1w#&4-KOIRoc2=$u4UYUNsVEpM58UB6m04DrZOI_!{%?#9IM0ZvB~Ork(|A zgzeYn$QEr=QeJW$%gVu`ca*#q$QE2XB`=G$c-ARsS}4Yk!gq&st$M?cZ>1^i*(J&T zm=rQ9xxQ95C;I`3n6V1ux#_>sYXif&J%32Kt{6>~S{_U>(Aaa*DED3Pmggf!-o?WVLHb{CUC4nLt6m zKg2XsX+nBP`n$c_+LzNL3t7nE$I0asH1AQ}Hp(ll%%m5&KidBjXE7Vs((hWyZH1){ zW2XwXQ#n$2-R@vz}J8^iNOVwc8+0F_xuSUzVh3` zeuJ$mI~+p-t>)Ja!A5vrkqAxfnuJ;4h!=4k*Qxq(jYgPezeY=tLEe~qP4Y%>iI+MF z!jZl$8CGi5Ic1U|Dgd!z_OW1zc8d0cch3|3Ea}3?bM+xtHEV=v3^nnVXFi{Z1ptmU?8T`GwA;(W3* z2panY$m=Iq?-rR7mK>xW6m^ru;m9VJ9_I<1w!qoG-+=pcO_D6j1*C;!?=PytXWDWU zvl^akU>|oim{K7ZFQqu5*$f3aRm8$G%tjK}mqQ;Z(#RE)%Z!ugD-7YvysGbvHGW?= zu{zY)btMu^mmr*1NvE$@-~_Hwb%0ALoDS88!Q`&)@(ty&Q&&vMsx#X1)xeY^T2?aa zxJ^K2bgR0h4PiZSGn@4DOV3w4rARS_rAQn&Su>;mWY!HL`O>T9uk~vi!9FYoHH$e> z9GmiNQYW)dzWMuL+vsPDkz82!QOZrwi~@gU+G}gInfvrbRIr3Qnv3TF@$8HMBabSK zTT%u;o>LK+sGC@X7t)+c#Bpuufx8z7jytU;A!hP&-{R1*y0HGm?TL#?>S}d6ICfd% zq=vtnr}WYx#kw*#8rAV|oqgx~mWx(NQ1Re5bzt~WNU-w721#<8=!-}%)YwF|?zRk> zr8m>+2C}4rX;10h+o)u-a(&JDXt84XlrWvmv$g}WBy|kyw0-lVl!?99_>p*_GKl@N5g5ykZ@H9THnjVci*i#mI|?-$Nc@kj(x?ov9Q^BX+{gc*+L7~ zUwSpcBo+^U!ngo z(46J}QdjAn$Ir78V`J#h)EEOkHLt(wem=!2_jw-@hhnr$y-uhu8*GQOSLUP7%C_R( zSs(559BFDpfgu?g(yK1=Dp9@MRh{vGj6dhNP6`X@#-gb!eHM~oG^YA>SsL&19Rd{V4k;p#FN^D)4Mbjy-c0u;!< ze!xNAP+yM@_Qm?h@iQI^_bUxxego~-rgzFIWBMn|zwaXg=MF??hIQMH!dfGyK0LGxY{#`w8Mjfr2xtk5_Zq3o4H2* zF#_fvCBe+F~lJN2y6#vb5vEHfiZ=>TRf zv1n_gm&(StcX?~Rt=@F{$htZVv}@|*6EJ+$B)zzO;+Zs36I3!3mwL_vOs*7>n{mW z4W${pY|;`2Q%P@jvGZzt0<`sa?Mw2<(z2t`g3yx(2wk#bfE63=84UI#dxV$sD^!lO zxyvzK7T|wg2&F*SkOGme;34vlvuWBrg7iR4k*ITngLH*d>(1{pb(6Y~XIYj(NIGv| zd{@>;MO1*Ga*fq=`V_K56FAD}CWc_YL6zk-Yl?tRkcS8;=!cZ@V$hhxGXVddPfw_$ zkU(LdRP1PE=h}-Pe4iHlM9{rezrJ%a<;WJU_}Bs~OzsN*`UF#q@nePW_TP653bf`QKQ}B*HM+!r{9Vt@eybS-Fal%x{slE+4FWZ`xc}C~=*3 z#S$yP6ZR^P*?be)I@~mDz}Pps+RK$oGYM2#oaOE=19eh11pH|IXpNz4M1!m6HU3{{ z0Sy$j2d*twj9or01FDrW3$65a-6H`Twdq~=X@kPLkdl+o5sLnh=@*vNQ|IgJr zgP!dKU~TvNIu*KA0Z%I9A%!@oe-pLAgVKeE=*aPN+QlN%6?W(nZOY_#@TTC!Va!vv zNYwT6t(VUFEYF~90=!9Ayk^1R90m5PK>w%$;2H(YSN6-5q;^JOM_i7m;k=OwxaRfS zkVd)1sO)}ez1+-2)+uD(d|q#J@W+3RVuP%NpT>i)nzWXKvL3w=1-`*lIS{8yP{H{p!*cPl>J< ztH9r~JSD|s56+l*PI!K(m#D6+^_};CnRzOP1o7Rru?~%Bl@R+*u8h=NE3wLxGRx+y zGwf>zz0riIzO12zt$;-h>Y4{IM5P@XUz}6+>9=;Vg0c-Y>2nwxDU|ztChK|lSR7RB zWt{6(r1B35+hYsWvc?k+h_7Zp_K#RGsI=C$zQ^* zmA2MWA}_xR?tGhON6X5d7gGaS?}tRLJyb#@H$Avx)idJeDH~kF*Y%OFz@hfaJ7b7W z$9gjI3jCwUJPeMHGr^Bph_T@`#?0vx5Hd0jdV- z<&+o;c>Oq_EY*>EIi`AlYmdxlj1K3tK_%glaBNV3{|ad%0CTCvX{R19X&_-jGGe|i zYYv|8SvTmR1Hs2W7AbF+`&|?1!Ww-MmbQ-oHr2fzo6t-Oso`x)tajoNeK4m5&AZP> zLwv5WM|_qf7nFhZ0h1@ahzlGvhmYyq*Ywr6Znv$(NMjM2HhOb9+>itG*lkK?{aB`2 z|2k^zugUqJ1M>e4LqBvBbKEC(z6MdqL`p*!RGLNVpCzEPoMa1^)qe6kGx9gT=Lno^h*vE-3Ifqv6TgV!P7cw@I2V|;^Lhalc8cWZtLql=m7MAl*D zBCisn>1-3eECNxJgc?jJr?_D5n4J9c1F8y%dnAiH7)%G68e8LVx+&gUAQInz{Hb9& z>b=wC=_ttW)=-rx%!6z;QF4xpa97>0!(TO?v(E+_0l^o!W!v@3w^;4S(Z&o8mLW*2 zDV&xIgDt?dCHEK9NkQ+xFyZPhbItt(r!w!9RVNmmISTE}y`*X41GgZuo)(*$8>CFV z&peVMMqU2jZ>#{K_jmWMu7|al0RG{z|5U#k)ompWh+@8bvr|oChsmyZt-ZW(;7x&- z{0u)BP*qTT`nztKgjESx+%R8^CD+F4-&%{Ing)fWBLHS5tf4&fX^+2eL(vo{cX@0T zb#5ztuNqqM06B3Svh}~gq6E1#Vt}uxjPxZ z=AzmQ87n>6U40A{yqAo(b%Hb}x5{fgqlY$PzycAO39ZZSZOKsZ%JZ0RNCAkS?tEPzXQ^+2rVJ|1rCGRu(T_@lW)KO`4=iK*ksqH38M6?3Jwv z)^b`&DZ{@V3omND_*X#ce!C4?PdaS2I#oHODJ{aEW2tW$caXN9V9c%Mn5{Y+<~uJK zeAjoxpc#S1+p+W!wx{uaY7A=ucUO#gb7iTDrp6f&l*jjYe{B&sBnA8|oOeDia|28& z9Gpe~eJcFzm1lKI)tV?mM;cL8evmAHe_u{Rj#Jvx-Z^HV3;!y1Hzb*1j&caLws**MfHZzUc+< zf~vy~6JBqRo8IW0w(wE!$5pA(I}UPXmduSmW=s2ekn3JI)Q&|+)xhthQG%b*3VhX* zG(NDlp=rTFok|)!`wD;F();5#sP=fS(bPdGT2Z}-Cdcqka4s$EHjag5KyYQzhu5{U z`L!4x_|#vK4U`q72(ZzCKu@?rIcOPEMRFo(B?!kPh~=%Mcc?dE@{m7;fmRnoRFfAg z-nXb+9Vi9-p@m>ew9>qrXG)J>C5ctw4mpc^Rf~JM)&IVJw1;b=Lb-{bm~b)fgs#z($}QF5_fOa?9|vwbaBUP4LV$^o9zyLA={`;D9GVM?4vqD*!iLBA)C|xL8>tu$IWaOFpV! zWuM8Km!C}b#+%-E79M;D;wmJ9#JrGD&OfpoU$(39cqj^@1iJF|l=W?JRMr(`S8r$x z3@twlqWNG+Jg5Wy#h2nXb5}BC*!lJKm7h62#uL>U_~L(W^UyP%?=OlD?Q5X)lQ8INjNRwozCZe^@X}8t z_O|lrCOU0jN|0_ja4;;}Wl<(0F(?{S5~dseEfGRw};&)qm&mJYz%AZN1 zC1IgL=+t2T=4L80E4bV2u3{u*e9#!o4zz%?TtYE)+ZnW|FW9W%yu8@tF*Rt)bhe1-<~6)E$z%kzE*%`r!YWK{V-%cH8~1 z`F)YV`RLNNh~$2Og$Xe3vI4}|J`MK$><#%z5jFZ~|0`5r5EePl%e_z902SrqYQ9Id zOOKlWWg|nXgF`c_bdUi~L+c*XZ6GeZU%lccvl3pcZ>O0Bw^M2;^a`W<>8xI5(JV7!pNw+=58PE!cE>l=hW*Wde;Ix4@{Ohqq4ogeRVFVm%AjJnZn1GqoP-u4 zLOQ+k{g7D0QivFo^*8y)5SfS1SJv%`1HA_RF}$`KUfO7q{!z9 zDe$e~1@pVlQWCpfM>i<4y@EZK8;_;`XCPmwKD+%l*e#p2;-`EYY6T%aQBw4L&TLH;f< zD569OVxhe3If;x#JUWPcSC0(!i9-!^uz1`>UEbJJ9t8EElJY-`Gx;F!zBi-sVn}Ye z4~S>n*tvG3Hg=2o_>S6R2M=$_KKCm`e%&6jhd)Jp>^AK+JlWew>FN<2AMj$hY=l9n zXvq?wqZd>MI%?hXntr(#DwC6e&^N_h3c1A#N|nDEU?UUh#rPhj9P3+<8^P5Vlc)2VHd&Lyphik3T`$!J>QG zwfYxFT3DF1#?&!93`p?9c{uBcL@0rU262yTX)M)@fb*%908oSxD)|v}uyD2iZ^T{( z;jMuoj0;QH6{{1qKc+vRAK(Oat43OdgTXF+{6#vjj>Om7n9q8pJ86!d9_t;0Iye!^ ziD&)ZR(opDi&rUDIS!PMvf=B<0qXEBg0QtJF+tKkMOo0n~`b1;Y4KIT4@c@ixE3BexPQad zCUCntb}V%@nvMd7UuW;w3GyAylH35;RS2eO2IvAEwY%Q2cl{=A5E)(WKYn3&Z1yZ? zVs>%o-W^1~vNnJ3FE;Q1)QJ6OT%(JF4Q4<`O=1hVJH98n^YGh%gQ|x7B9>HQ?reuE z^>k1Kpfq4Oj&r}i7CTin6DtvcXSV3pJwzp(01U>8-=xz;g+-u3rOTA}b@ z5V#kj;tc{A15wAlhjtWF#2SrjqyZ{0jHVf+2kOsn$r#xlMn{5X9-`wA&;#%h-RGBZ z=#^;QHxqp+N&pdQOQ*SYdvQX}6g^JqhGA_v3OT6@dVCJ2x7)tbupt(AIgZfDgE(!0jLUoI6W-+4fm5- zDz#cIpE|Van5U=ke!s5#+AAr()I)w4c!NKbE|1`kE5xJ`%c?XkQRVNi7}%`R-9<-? z`Ru@&2ABJkazHP_aoAd@?Kot(kZpr>!@BpN3R=Wiw7gOC6&u)MJ%uhE~o+@o7y z+FkA)w7QZSk-9>_?PW`R>S_DG_1$oE7OO;z-RHsKd-VU$7xbPi_1Jxc_ZuWNY%qKTRlYxAe zop1DU{eabg74;zYfD&)i{i1%vi%Wxb+`hVI-=)ZiOq^7RuH(i-L&(VF{fa9zFTT+a(Sm59(8ex$_5XGA*J&A~?^ka-X3t z;QB$Q{rpS^%w9pRs2(s+IyMn_=*JnPL1}as(+G^VXnwg`c*}ssh4Bvx)(61tGd2eA z5<>|cPB}~=erNr*izm1+4uSBi|Ef{n`~9US(d8SPte1&}japVDLZ^Ef$j_iELVN{K z37&;Fl>v(112V56wOTlGHLk;M9wd&pS1|R3AwQ1QcNw5;GC;uK&z{zh9z={U1rF)v zM0lafufUk|Z4&VHDyz$4Rc6H1oJiQupjGqLgMX{ld2>!qq79RH3>OPZR2P?YiO(?z zxw1?ICj6d^Xa~NCr-;(`KRoch-*eji0pT(Zc#}r0SpR4&81k`!0w9^A*LNB3kyrZJ zJkc>W6xP6mDDm1`4lqY@_dlXFvXNAk<|G$Go{cpZtLP<2⋘2u^vyQ!$KL2U25vf z1J7308@>DoxJQ&1ve;Dksu;T3H_F-*Oi*kkY>##3xKFo*g)ddQgXF^k0Q+R4w3EwC zztZRABg9j!o9iqSJj3)0UkjHkg1g9w#7)j)VwUf~nLd9Oj>|=(rg^<;+#IMTuBm!q zde*El>*K>s8IN~&gK+Y*w?vz{7VX_b{G+UmUzc2%`mkib77!9j7aCmuPQ2^J4BynI zgvIb~LluCbn|(Y^Myv7H&<#PnHGtprle!dB6v!6dDt4%ZX^M&!iK`OTAH~TvKe>Vj zX<;r#OuC9~OsRJ4CuQUgep(&*8w0%5FW@ymL)zZmHqC9(q}W{`irI?c_rxd-n_y@M zK_;z2QB1LfKb-T5O;7WaFtb0jSQ0KI1)s<9s=7T1C?N3F@QXhVjC_Qsd?5uSOuK28 zBf>7aWmZcDFL%lF_5J};BkIb0LkppdJaZ8Yvu4@@IX`*w$_=a(J!hGPf()C9BDJ6? zL&=hsO%BoqNNZy^^z|6r`ew=D;;6@~rwdO-Q8~iN(KrSmI#Sh1o4tvNbc6#1&+dOO0!zK2oPr#|zbQS? ze}Z4~!C0;z=}XYet(9{jrL$wnQCH6_&6IM@GatpVDG#nopMl}>?%G*?{hf=4Y-*gM z{=pY0$B}^>m%|PIpY0_^GFNFHK|9k4(+Fj*1yrG&`~R_yz?g@%`3Yr>8&+4)6UQ>t zSnL;lM{GFHHmk%sHuE7ba};=3NCK&|44xPFwk~7c8&)e~vAnvJTJ^n^Eu8Fvw9{sQ zVumhGTWh9_mhRbQR9HdZr|q!))`@K7TfaS%mz^&WV5T~W09S0ig?7s&MnwPfjaXdumRT4j`HrCoylgK0i;lHRr9B?B-c%#>s1S8ZMt zrsRCm<2e(6>>exCOu=d*D0Dm*D|qJca6wF{!yR&Y3bleBKbPrwhr&@_i7=e1h1;4O zrd}4rr=?&lU5e&KkNbTl^LMgU`QMjfMp3*q?43Dy)-CH{k!3mL=U(WqPMX)LT34fN zjq_Hn27I6;iRix037i0EzQROechN|`53J5uBa-ndO+C3m@%?K6d$JA($;1}okOgJKUsUlMJht17#ib%;*K^yg>4AE5?j=bZL z(G5r`KzI3`l+=VIya_iWWy2W4lcK7yktbGL2BczgiT9U53(Z(xkQ6Gv5!eUIy=@6Y zXuq?m$`UEpMQg^fc6!HOV(95~=ZctgM|K;{CXKqV+s^2d1VaFAlmgOo=`%8QZ!7CphsudaR8r}Ssx(&j6hwNxh4a)p~MRT!TJE&V*Y&y z)u6HP>@8UHi!2W_sI1$>#LRnJ|R;3bh59K9WjI zk1mWB@-z++b*!?xqQQ#*_j}kLV$~rRXGG~E_5gq?Ie4Hivm7zrivxF;_;a;o=gFQ3 z8tUn7ZOZw09DJ$e3yXoUrE?(N@og%sfhk6#BgI@XT47YGaW+zOA$eFJY$;@X!4vmMBV zNtMqn_C7{kgJrF-tjfIOeX#hj+eDk-^jF>;gbG%Gk_Kf9|7kpLm@cmKR`cYVb1XoC zPlnw6h?~qJz;!C~4J6A~S{j zsuC|MP+eJtl?$9h_yu8?S=g}ji?bgKU^s;lFKyFRd5o{mdFz$AWuD88?-fc3RS=>) z5N^yhiH^uE^?h#oHM=(vqq~JOx%1iR&89!tl&DMEWYUvuGQngQ=W0NURK+@jjwyt2 z?#tVmZ^_;a4WU23Dr-j^_EiU2GW{ng8N_y69I(C~h-lF3JQ9wt^pOv>F)rg z?^!Nl1HKbIiBN?gy(;os6Ud)%BvkA2DvIB;Xb%2hB@R_pf@-`_fteC;1k!@NQp<^C z=P&uFRDT2g=>II22Tx6=AbbeD!qvq`NODp_+&(5v;RrBXf9J3;{A!N|}=Zv56^H}U=`iR_O zLhJ$Rk=fdnTX&saUpgLGYWf>I@Cb>QFv(1W{PGilMLVVMI*NGYWmG_;o zEW11xUbwh*klk56alN8FCJcOF6R`>RXLH6V77>mv6qMSV_yPp2B>0#c`#{FBVpNmt z4~DLrBp{wppdquB&A*SrhN0_f;<0Lk)PN$$BM`9u1V5LR@7HB+?ESV6`GPfSjI zt`E)HL3>MmOiZAH5q81rr+43VL2td5iEa}01hD#DHRdW2jG@{xw4Y(;#wl@@jk%Go zZhWQ@Q}z?pV9+1a4`8$JEE0uXzvIs=${9v-NjAYiySfrr)&XD*p3=TQVX!L4iw2us zl0pywj84gY3~Lj^ceJGo5G_Rf9^AOefs5KA8?S{u9_qeurI8} zt9s2G!PVyM%d(je%?R}cu-eccmKkO-q~XPQ#}-2G>hbVJH(DjesJ{zVgZIGOhU1N) zwnPl$Wn>0O0AH9gugGk#d>MqDR=#!&y|^f)@p5~EqI4NUj$=~z)Pw>8VLwSe%rT_Q zs3hQPAtN7y=E3V5gk4>-ga2QOOvGVt@#|O$I!fozA_=D}xiDX~S2+|-H{|G7HgG3m z7Ze_)Qt$XAo7zXZEb!TU5PQ4(soECurzXi3G6$8MX|f;ldU~V+XYeze8&Y3^4}D}m z*3t1O_1f_c>&U%eKX|sLeKt*$4)rJiuwJ&4oo6eU6&<3sE#i5#l!fyza|5SzjW=e+ zmD31CXPrx|MpBqsyP}S*PdH$OxeY41&0k7}vR3Z9tJ}-G#7!WF1`JkxLY_P~D(Qfr zXyS;US$D^5Ifn_onJ?BOz+NUfOtjQ6mwTrG2L-?_qYRQ)$Tiy&Wkyu#amcTGdY0g> z3IaBNGZR9A1!r&M#M)Y&EhZ1eYE(NN$Rfj~xBV$S0qJ>|51c~BLyv6!p(LY+`F50%W3di7v7yFYO4lTjs`5oOXw#^&b-Hork}Fk zT+>20Hr<4C(BkX;Qx{DI5mLrK_fO94%Cqq64j_2QR2L(QbU>uQsC5d3b*lQcfIEB_ zPpJ`{Qt`~s*zC3bl8f$ecgGW@lYsR_YS8KDLt7Nz^b`1QZ=)0K`4tqFvoI`hHrQbU!2nt6JF-%X5iC!on z=)P(DlIL$X5-|&?dO;z1HAXb=&0z1KI4=w23h~bOMp$|LlR!kpLJ52zhaEQ}`((u zW_R7&j~I{|zPWK7zPzXEQver4ktU4qI>BS_X+kr~D>)pQMUp%vpB4bntG2)`YXjYn zpON<#v=yAkI)Q>k%;a?axI==GIN=YnVrAZ>mIJ;=xg3wwv$~I0_mE=LOb=qf9x_9D8UJZmrVkK z|8#nlRz8alDm2NjP_-? zniRjY8i(Iz5abjVWSrekUX!n2_zmBURIffQn0Iwe`5Ek@|F?gd3MJM3kfrYyEMlS5Q33RnQV*C!s#hcf2xnJhp6 zRB{TV5`eXp;Brr95m(A%FbWxw=Z*Zkh?f-a{<1#GJ!g9?G})Bz2-yD9-x1C5?kJes zxCeNkALwhiHs{sKuv$TKm(Y+_gqDg`CmgwBy`C(^=$1`jtQ*QkW??V};4bZ0*?hWg z!ah017S{EA0yZSfp7~{8H()JinAMP0*zbi(Pe(3Bv2~*57>BeirrV z%^)X9QmCLc+Z-pnlEJu2_=9zJOuk*l-Z@AwWW!5BK=f*g^W=MVEVwVeb`?G%K>XW0 z;b|^_&e*=$ntcw#MJ6yi>pfDd?#cn;L=#nz|HreK;##Py%r%cUb|USoiu2M;d)c8 zmzCLg?1TG8N9Or~O1D|vD!OniK6JeAZGaj_CJ`E9QIcN}C9(au5&rzrRo%Ec4*R*S zVo7I;DY^g zunt^e6>}D-CO0Z;GaN(CUQ?+f#I5S)b9i+euc)8{-D3p8yRVoT;Q3YabJxm?2;z0! zC8{R7fa{%9KrMyCi`Z!)ZObT05E6mBFHO&WyD$P2qGo`UhNRa++HZZzi2 zlSU7J%myR2{9qu(w!IP6)4NV&C7z;uIrGh>*|R++pw3uGJmi$ahn5zLxZk-Shzj*= z&P>|2Xt`9;A|sB8=Yz&@hwJA$c};VN#k&n#{%e^>0<)6Itg8=f9RO?{P;DBcmC4f^ z;cdr32>;BNtl6mb&UZp_m27Ysa%}KOoe`y}UkfMG&q~*>#761&Q@wkB_A}C|OtNmU zp>r(voU;l5j+NP4?|RPnD&Wksiv3DaaN`0Zd=W^c0c7zm-=Le?r39<>T?39>=-{sYKMez2 zGD0r$(MIn4e%E~Y78UKcFqUTn*7Gg8{G&qZf;o*#CsH7@p-P#I7BR=J<|k1;OS+q7 zG6GWyqAMWb87W+uA;69eg~(#-sHe%@^LQKCIR@V$yFSV}3Asd^HKn8hN;I;#CHfr; zEr~G%;U5QVpjWO-&~C&|`q5#q`L>_N&H+{QAz%Bwn79`alzP63pCSGosbHWNxMg`c zFk>e(k+E0!$xDIMVyoBtLl~1$CLNT8?^95$A$AN`$kclM8s@28-3>Qhz0VqdT`b>O z(L|Mm_AvuJjx3-t`rzT=aRE2*31HWUrdkq0INL<$q@p`EUw?xzWRkG|2-%y-V&=&G zsx#Zf*6q}|_D)2K{S|m@K;4ij|2DD(W8Vxu{JH=xiG>=QsHNpB54F32XDcK0mcAGl zj{upo)iqpWc*zDhy_`z-!4)`ML$CzWjxn@sORD;tPG&O0=xiQsOWOTkSgATJ6!ci_gj4vP! z@_{g3A7Z5&XLCJg9Ge=eD9c^*JrabA`c+m&03-7OwKL{o=&TirKDXlh^r-==A5@b5 zcuhra*JUE5XINo>VT4gP@wCA64ZS#WvGlF~O|VPmt(rt3h`v+2zFT>^p{xZv2I9tQ z^^-8)eIVTmlnM_|&2Q>tEP-?CcQu!4;8(5a&6UYp^=4zsno!O|Uu{F_o zutmDnGDp_-^x2!knTfU0lp<78-lKD$9bTC8cT(9W3o*6?Vi@RBVqgkx4lS73ni;|& zFqW)Yn@JjOq9P19!m=%cfTHBEhiWFZ-sbg)N5(&;VEMZaD(aA6vG2acu;F8@cuTju z@hO~_^cFp7@{Jt?>$Jshv-^IX6TK7EDMU=V!S2JF2X)@-&8;7e7c;AVjYKQltU}FF z!BR4FGBKZKnTj5;F}{lpp+qh<8q3R~Wh%;At;*ZMa#&2um=V&4xLFO-S=TtorlA6q z9Dqh-3F1iCl{5Ln06Rd$zY;=3rSt2H#HYPvTb)?3*gm>y{NB2Bah}O~c>o`4-)heC z7bOKf$3SuFjWS|luphZH6wsoa0rs28IkqR2LzQqdb#{@(LL6RImFF!te?lRgT=bSp z=uE66lM9eB#wF(xGdl@YoCmueQt-BYH(deA6)v*0tQ6y3nBpgHv~S?0pjQdKl9RBu zHLX6Wqg)XAV5vXwC#PzZgE5euXxIAe>yB|zz5a5nziXU3aVsjTtwvei^7h3{{%jIM zBmuGcBYf9fP88+@u_EK;%7y^ZG-v+BBm}9L=&pfeCzunYo{#UHS|S&BAVfvw;N{}1 z#2J10`4GcR71ZVET-rf5Le@g!;rpg&-Y3wms*Z_`0jyLyATEK_GtF@0^H7#;;E6a& z25#XI54rH%)co(szqQGiTCOC6!mc4j2@L}(U zc7%9`C!3VWhlQFLmLS9w<^TR&)>;8VAQ=-W5eNJV$V!ZerI8O{+L>f@l80;4gL(V9 znRl}5Dp+Z0B0rKwAgW1M!3;+KHxaSkM~76>+5;-|+jJwM*cGEht(ugQ69!K5qLrv= z#X93>d^`$b+k(SK>>@wKp?N#63w`rjDO$8FDDk<3-%m%5ur0cpFM%Gn4)Rh{qLTvD zUpTPg;$d2)9YXXX6P1rl^eu{FMs&Z&?x}PDD!(G3MgE|Ug()Xm>9h;0Q}uVM4F+f{ zM(2P&NDqLA9ysDLAGlyUyxVfx8)s{2DsvElBmV9n9aYczfSr%Wh!2oS85x)tn(KZ- zQ{7FE2(Qi(J-{kzMkPOXJS{K>KH-){6rMUEWP2SHU=4!hBS)|z3 zu&t*<8~Gq-@d}p;988C#ae!M+2I>)=XREFKv_}0`HVP>FmpMoI$9=uju)_uQoHvq- zRinLFmKaZiUIiY-4v9KbN;cjMN&Na<-WG!7)tNGXHG#FauCw)1kv&EWA`!hjh6kb& zizKX;6ga#Ggb34kswdQlQp?8QZ9}lNh6Mu!yR40gm`13-+d8QI;dAp1ol>v0x*OZ) zW9@#C>m94sMU{606e7U6hK**t-jlOB=%nF_8-N*xKMd?S&3Yl~MNGt9DA1lBpA@Fh zmB%I#{~ub%VgD!HC?q95%JU{@`Zf5;j|(+p>619?-(=5X&4Oei{V2}ywr#T-M-Q>ZWx$}`fP-PP>(PYTWrggs| zss=7D+|pe-&@u!Pkw##gpNry#NtznR&?P1*6FT9e6vZtdA*vsy;M(s6zF8JZi-od8jV#fteM6Qu2no(pdRZOzt03u4W+i0cVV=2b+8kG%KJ zm}$PaqWyiE7Ks8P@z9KXbB#9Tf?|zmWm1@T3^Hy&M&jp~=ZCe_#)%H6qJd~DhVr!h zUJ?nS@QRewpE6IJC#u5^W@~eli7{}okf<}GTQWRR-5GcqlgRpN4GA1#j=#`btJIz5 zmwZo`%xK?S&3Q2iaXAPlXrC(Ogr^B0hWA((oi%dj56mw5N&N7aD{L_{KSX8Np|+AM zN+$fNS%AQ`O7opHlA+StdthmBl5E|Bp_VL8cOTX9nYACQv4|*XYyjZ64XWn*zfODe z*Vd*kKUlj=m|y)K26ib5XzL_?Rh*@LA&?$8&}v+F%gk18d%}D#1GxxXz-eB=cCT|1 zZJF{vend+CaI|(XyXQj)K!RQum+ZYowo5CS(U-^1DNF`Y2z*cpB=mMLErhNcojG+B(g1;+yBA_;okrwC8-7m0VjYC%l^tn6REg8fd)8_i*~Czc1X zz-3f)9`-#pbbjE~471n@# z^#k4g>azcFlO2=4fm2tV3Q7Enfq5@U{YRtl98GqElwmf8UNE@D`HclrUDP{Nz=Wl{ z6la|qr$A4A6PqXqs)I|`D?<{jM}LXE(Y@=jZzoEsgYOi@wbPD4aqYn;c5ox$-$g^+ppcj|rsHC7>_E?+Sdx=ZxaJehzJmOWDvafulefy9OFVk3`k1K|Mobo1Y{ zjmJB6{TXYsUrH{VtkNWSMUopIRC8`zo(|XuX0OGQ{K@|NKlSlY#;o3le-QpHfBebo z^%AWiwg+;_S$C9I+%7?rw=Wy}O~Pa3LYy&-Zt`w*Xpxl%GfJ>5UeI!oq-BY_2=mkTCUo44_o^GMV)7gIp2%N!H&M1Oo0HskSZ_+Jp-P@vE zb3%*ijRKZI#_6-i&4ru1Cb&tW6YS&8bN@M6mj=Sr%<}ras>ex7!9_pgu^0Ck15FLr zusPLHW@MsTNuSM*Dc^c3HH@f*8_Y+Wjz@&;+2rIMmhmh@s7RsoEN0w6GhqCWf?eH% z8=xYL$>b61kJ+18aAa$v-)IJhx*~b|L~<(~l9kKm#iyy&8mZ2*(T(!o3rg_sl9~gh z=m^{TtMrq**Z`rB6ZA*@>0cXhe>p1}iT@Jxo`e;!VvY;5xjZt@w zG9f=hZ~SDKu#lGvi`ICU&Zco#Hkxt105mIl*u@I*ZiA4m#IOAkHR7__!Tr0CEy zYEqhCH!z|!43!u@TPnFU$6@MPq~elV*gm{fuYybXYOY{iYhv~fx@awdY5#fI@ZQUX z?psi6q)ts^ClLs4?p8SBiM56s_;4Ru&JbMMov+BN*ocI6P#okw}CXLXVhBGuQ}LqtfWrhK90I^NwU#?HyArb2ds;Q?(ZQ!ep$ka4v z7}j;pHjd}UC`w#plz}%=+Tud)DSQ*%YLaj`GU!TSdHT_tuj_T8+$9w%bVVMt9kDnh>EI& z&hIR#gJI-}X?h&VmJfakt3!e%!Fq5a4}H0Q6_?L8>lAjjup?Vb=P!PzL8!YxVnJ1U z7;Bp8V#}AFfsr-LVt2o++wR<;f^{i{)bz5;G@EHuCX~_+ zjaTT5o~uBgh-Z)M!y$wR7@D}-uT5Z&?&qwCXKgP~2r?PcDW0ZcmpTP^z+k@zvpZNE zS`IW(L$}$!7?NeVci01|nUNMH$5N&n<_c@*TjV)gt)btmZ`D6E0t(P<%->WFVe}b!_G$qr|v_EB(rXG82aL~nBWRp?J70v`3_*2g{=OeZWm@# zS?s66r80yACBHK8xe+R?rlVPGh-U2TR^8rC+7ZcJN1a?S57-+gVL(4gn8p)NihU@>lD*&s5 zC8bk8yQY3D`WdAh8rC0g$w574%TosExC}h+G^O}_dQ6dtw2EU9x|$@FXS3pZh0_NeR&8y!qXt^ zoMg`-au*uPRq4*f?Mccn1lS|#Zraw|Nc#f>K1dt@Jx}t@O9Qk_3>hV|Ti#`Xy|F`+ z1XiuI)-F&z`(hndiP7y}7DrrNh==3l?`3S{fD?+Fgwxp_)5oK5#Eg4hcSWx*o1<~z zSg#1b#34`0V0^vUfBhg-lJRu0M1?*ZlU+(CjyGPH&cCZlC0McF#oqOirG^M6J?-uA zs1c@|NtH`ag5wD_b6bJP_!EsOO}wYJ*H06_|7~g&-jK&7&}jQX2pk%wg`eQvAUaxwCzqtt1jGi1+%j#!F*N1N2Ue?i^#|B=VFWrEu zc49L6X#5%D*l|FesFW8)d08Czz_+8iK4~I?#?fn7K54D=D_GmLUU>gejwlG1uY?*g z73XEUhjSAfwUz-Sn0p>ecV8V3_sRO?ZJhkjOL8e}HD2H27ZR2s^Ax0?CS=L8vr_HR zQsagvU2efZH(A-#HBA>S*ZW{cH>Wif!RF9H}A4_Zg#VAIjNylbY0c<~Rn>DY;g88*~QY(1qQVRbkc%f3*&tfZe!bUzARv^!7*oB&VU;mqnC_i z>2xgULFI>T!!xk4br~*IX&PH8df2@%uc`MBSdF<4Q>vK`N!Y!L6iS*;w?=QCvI#if zAR#RarkSD{MB6l7Hpg|$7SBx)d}A@_3QG4p1H*E$ngtl+*^nh$Gte~G7WfL-VW4qo zpV^DC@CK1kN&;>quGcaH^_dAdc$@$SOk(pZaD82F#VOm4$JZU$q1*Pp)0~wMyFNHc zsOPJhXcu+BQzVB;=X^K&$!pFsBuG)6ob#cS(kLd3{i4KwmEx5Nb|y;q&#O1|kg0On z1d;uQe_DDF+aN@@Aw!iWwlElrG!-g5a^;Y7^t(?f2W&X_wx`L5Apnf={;CtUVt?Y( zcJN`3Z*bG^u!>kx88<7ot&0YFZe+Ny)0S>aU{H>C?<#cYbL&lO;h6YIGtmKjCwq?Q zdu@YMN+|l_RB+7EQ)myLhN{y;Q#X{Wr+5|$DLKIdh)+>uvaMo-id)p1-jRPzWGlde zua<$UA<&(%Ij<;q+ZE|2nip3TlUm5eY0}p#~}i9 zNF8Xz9#Rh(^_2dQUg&7$3eilpdB9%hKa(yh(9)&YYo zhhjIr%}Js4plw3i&i+VbZTo6b4*2l4E4P%Lxqk=VdAx<%Hf~5m$8;R$*)t{n;F(Zk zS&t+(kIm3f|F0&Y;O^ixj9Mwiu?CJW*ZZzblRB*(Mc3;YpJ5BG2jRLLt-Ju(HY2Gb zEOyF~W946F!x7Ujr|8u2&mM25X#z=f+`cyB)k`Y^mfxqMn{4pA17zYA1?C?bITUpkaC~PKY{QJQA6R8QD315z0KF?#8=u*n zv4ViJz;7qwjUYapOj*SU%8XGJbnS)U-6S(hnTjSjQ5CW=I1C#;WxXBp{5)jkwF;_kk1o!JU0kHYF$}=n90yrl$8VUPMWs<}< zSP7vmKcN6{O)Kw@Cje6EwBE*DVSup^ft&;E@1+X)|JI^f5QZ81={v}xW9!(E`X|Pe zYGYB2(1SY{IvJ5rGr>j~TI3JZJ4U7OBvjTyWRqEDJitI&p}LKc4AW4xhCo{H>?0of{BS56{{sYvyj)Tx<}`nMri za|`C_ihu2IN2}(&%W`R=-Wu9nWreavmC5A=i1M9#MNDdPd!ueTReazrl$5%c4nW!L zu7V;4neUO0Nz`l1?Ief}ww!h?6oc6arpm#psCx)a#IperD_rL)LqIbH=8wP+dNhA4 z)RzB?KGu_W0>V_s%&{seSHNC>$Q7!7tNotQp;7%3AWp@8Ui8a8ql8J(n|P4+>qhZ>N5#^ z^V$nF^uQHU(Xg!&APPOLmKK)!THF-AaI%_!;V$zq z8}S|LDQvASdYz_mXCR2sSCyu;YH&UNohp$zlc8}*!QLtaC*b>P<#m5F8>WqB?jKGP3SsnCQldH#@fghyMrWB6+h%vlk%^rZL}Js)!p^p2z@K!q?(DqXGzPbrtsgc^tv9)V?-I-Covs{=bNwRw!2Y#CSJ-#2x2$_ zQk~|kVy!`DAM9d>3bLe+p`{Rl-3x+kl2A^>KlQCL59CW-5YD9}RXUONb2fze)mCUr zjnv68_`Gtr^>SpEqoGNWhvqj4z_ft3s|#h$0yqY}ihL;aWZ9c81LVd+G=)vl328=M zBG?&MLYgN9CWUs~%$~_U_?`Jv7UXsUhqgfb60>O=_pSgc1vSKHM~95^Sg^od z<4de|tY>`FM;!`wq)2iR`)baQ3yIpUCW1!-3jCunPXUSp6IaLNmDHpO<|+NDcz3E_ zopm%i%>S8q9O39E%|{hq&LeTwRPMZ1NLfm3a@(iDS0-N&G=^v5 za$rx&_~Bx8fB!A)@+0RK#Y6X1qt~KS_WyRhgcD*fT{MT~$Mg(GZe78#hhD7#*oktN z>sX};8}K&vo#kM9jl229C&A(305t$Dl2)LI2IjgFwD6>hPOJ}U5TLmp6?&hQsPs1g zyPT4f8>M4I#zS)Dtl7_YwxP3Im^3^m@9d84Lp6_97CDm$gWx+&yVt}-`6ZePg zd6xB>u)!fE8?whxc$Qp8qj60exW(q$Xp{u6Tk55+8klPFb-WuLZGKr<;l$AP&)?<# z5w_}KblOG@7~m=}MF|uYbv*vks3bm?OVC{qoR+4%*)1PA&jSS7=T9CTYlqJ61Hn_$ z&z;JLuI`rqQ{U66F zAeF#+M)Mi#{JGRUrSYcKBY^DmT!)4E`V|aTg;XPhdbw&wVn5qiB39i&wwlcjRSh^u z|1H0bjuOHhDneingmn#vPm0!3EUtbl->2oc_auir)8fd__Y&^zAO9+X;TlWjVIFjO zR!G?f@KjPj{da*}LP14-0e^cln}@y*!+B%M*F+EW7T_>G@C1k#q73H|Z6&mre_=gm zm2vU3UF^k&5um!s>Zi7nT-0^(v(du9E~EV;M4J;L^j;y%?$tWF2}cHR&R!^d71}vK zNm@z#oNP%gxWFRfSBK~V18?8hFGKF_lY#g%-BQ--1JyNQM$EvD&qcJgQsI=uGXi-? zL3L7m5D?Q7k4f556XZNyXdvSjiBYC6do^**E0&qKbF|JiiaIm#)RXlMOi3mMz&kF` zL&e0umO_oZ+o)JruoopY0_}tp5aP1ZVxPGRt@~2>=r9lqVhyF|XJ@gYN<4Avz)Ls4 z)E|@iUu09$q0q04m!3y~t{I!{jZ^fqU><>P?ttb(dCKn9cGcOs=oGA4Q5JLTN6%3Xx51F0 zJf(c2+9}z2u_81K$2x|)yDqJ_jv&IvfSSu_c3~y8*8LiSQ{(Mb&Faw9Nms;0twZj7 z^|##6<*Q3JB6A5eg4EZc>*_els5Nbc#Bb|x;M&Z)y{;x`Rb1c8OHr*|pUWBOtXLfH z?vbN$@QI90c%rk+-!~|~*=4u0($~P4mY*%If=YU&GDyM}M4Tqb3*cH8ad;4MxvrTo z^oI*u?I<@zHj8{k zf%-5UyR(k5v$6MPaY|7*8kMew>pO-UK0jRi9G!*sNlPqe0T9DEcqjR%*;Y^A-H}My z@7`4Aa`arAZMpe$)BU$2IMxuCyH%}=_S+h2y=zu@lg5`oYsz2kI$qbhQWHGlq)~x1 z_b^=-=YlQE<(5P~!jc~NDuzJkyfxUcEt#uf13RioHpwAE^+SGVLrAywM=3+iqjv2Y1dlP08bz(*eKY$y^zPUpACg-oB0)z{7;{LM98ZI%ss5yq3Hj3D z=i)p(LytM&{{8h-z1e0_A->r-DXH&I;)@zc1L#@@R%tM@Z|PP17_F-0a3owxRL_d? zk?WoQ6(WrvN4P;&qF;BSxRWamL5*?4ySPo6Y*JMQB-e1G0r?88f}PHQ#=6bnMoj2f*X(1th*|d~kz@^OEm39)K}a zBx?XM%}0cH+P4YGsFVvGv49S%@HaWS00WjgS+Ty>WVW!P!ycTMADHhI z*`dMzlp>|7jAR@uSf4VdH-oumEj>O7m&yzTg^x;7_d9&G5V;S&OUb}QOh|XW&2>l= zHI;gbj6|6=z#d2!B)Ysf%hEXd&L_wqrHARo@iwhOlfEXhr1_VnAWwGaH&pYdFN>%P zmk*&Exsu?c)-W(BUxA^;JTx+R2bgc$9eK~>R!NC%iW#Ks=3IUyn~UvkN5x?N_=YT z5u3rqBa0_;JIIk9-@qJHCbxZMv`_r6{naZK-&-lf!1wamevk!EPOzw$Fn(gb3&S}xuTK>1 zmuKeib)ZP2%G5ai#1J|4bk0;d5{dk+wgq5az7W@->-$3nbidU3sT_jq*R_&H4b`U8 zi}{FgU!E*Oeo?Uuf12OFJW8D|wJp7smDg)J%;S-Ajfjxza3>7A=_wJ#zp^$G9KVPfN7PT5#*yrsrFYFAoT&p;^0}dpJt*K_V zO+LW-eZ7_ISJ3zCX3Ozw6*dkk+K>INb%wlS;DQEsfCfRLi@1Kk^d^0m=~M;!xLUwn z+!%SrC;cm^8ZGUuEY=tyT5>;TmHd-zJ?9PHDx)p|BTf)4gNzZ}jKtI96sN27XbdAm z@3;K1B@vNG4o2}0gRuRu4~;bzu{nYotb+>XA<5S^$iF4g7NVMsX~RLf zp8hy)5Zcu2!ZM8f_`RRWui&P~QE^ys>bdoJ(gbz`X((zS<7gqa%t>{kl-hMXH__~( z5nEJEkix$vBsfML!bDfl=CRh@MpY)hcV5p+o{np2ihb+DeU-8K(fB0C{=4nM8zjAu96GJMYC2LWC_mdu8DA&W1C9a+8;WyFN z3Tk*}{Zknp*JNds=1UWHs5S!}J>)E(Q=a{X0!dspo6AwYu4ulMb?K#ZqFfQyj@Lis zD>I6-gGQ68Huj!uHm}<}p1h`{E07c&s@k!SFSFfxdt*P|u;^NF5E&X)?q5GQUQ@gl2TP(ZzPHI1+*)C(^rxg8_HN#)Fe*{v$+mAj| zJenA4L5kMn0h0cxY+DCtYY4G9+++)Q-;(P7OOtJH3TN@I(I6xR{l*n=!VWKmy0GD~ zN_(vFo{+H~R}nU>_4mk;iNMVEpvV5UcmJH57)GF}H8)pXtaICO1rd^@N#`;>UevUK zV~qbFZgNI15oF8Tl=36J#Qvgxx@DU)p$7dm68sOVzW2Vw>A;Yt8$S{3YH!l*36IrH z90QI8;mUzC;2cIdG4PRgrtwvj#S~=(UX&BvD1c?!1(21!80{ z27VvW_+pzW#_I--dToBTN$m%ys?423K1-*X?XZIf zBY(iMTBp4PNtVl1$x+3BCIELk#p2ro6$MjqmPOv9LS(c{If3&7z5q8xu#SJS)r=2D9bKI&Ee!5UOdR6s>WA>u0~? zVjbWN6R<>4$mj`t@M^iW7`q)lb{r#FGb~51%6+#H0+9*I(9fCTQ?Hnq4BqKOXVZ#aWr3!FH5FkQ!70i8F0zmk1FD6prB zQzi)1iwMmO#C-8>GcAXju=WLdOUs7GzoF{))hO3T0gl#;VaPqYR)22sR;&=RC?0-^ z%_uK(dmzRDq;c$*NO|y~v^2sfl=!X_msv+y?CGjObFkpVX52Pd{k=WU5&T!hD4^4W zb^MDu(p(u0h=B~SG?F>)r9uO21wO{yW4~u>QvE*VwgAfn8yE%T7AT`cGXA@J%9F;F zlGGfo98kE~tr5&*jnsQu?h*3>p|6` z380d-pmy2}{ynm3*UAF1&aKsrIGTM=PB<0_{Fm5h6@=Qqs|%@tua^zr(d>dkqxj#(QMt`9yN%|(vi?Ub13+*#pu;Wzd zu08cqaW#)QK0QOpl1BTsRV5(wz?*8SjBbb-Cg?tN~lLi~rTOtZ7g z(xK;czQW=K(|aUOd!EljJANdGPodX329J)ebywSc&zi=FR>7n39dCjvCf4RGPj*D- zJjevBduOigDaH=)@i6t^nw8f4{w_QsCfB@*tmt2helyadNYp0GRV1j|8?>> z(aB;mz}Q%S{aEU>g-R{#H0h&L6Z{Q#P?90%vvrq*MVeKzys>7ms~|~DjYp+#JAB=& zHCSjicH1X@GOQl!qt>t#0Wfw}OBH@h5(#1Dd+fn}k(zJkKp&t)-_0;;LE1YJ`>(cr z$=Cft#8DX*p@b_jp}I^MpBnyF1=2aM;f%Fx)|Y4`=Q#!6je-9vH^id#4F3Y8t>J2O z4QVrAWvK@rTBBDgIHAhpVn`>Yz6+`=9f#duh9F|A3(ew61XbCNacyflyp?Y}be5a{ z;pL_l2!fq5>Rw*&YqQh8`>(4$@s*n>jSeQ<CtCs)zv5%N0Qs*>_RwstV)X} zbxsR?eR-1zV2|8H9PS*3Y71aY4tHV{Uaf5I2DEP7RZJij3bBS!${P1RyeP%(D>NQb z%{CCMKc+?an{SV>93b_St;w(%g`qe<^b5mxN3^1SbmUj32jDru2&gn@eHOQc(>-+~OH z%h#l<=LNC)cbqk(UlO-n&gytBSR9ee8*xMyv$WqqBabF}4K^?Xg*gb$9lmMf%N%dI zAd#PCzLN@OQsDO#_~%`Vl$L4ttwnz(Z{$aop4s5OnP##SDUJa~XX_kA9{Rmf;!_8F zar=kac0WLOSYpxWC#HOE6bbyNgt9mhlCi8+f_@?%4Nsj%9!bo0Sou25HOLOKcJH5>R~2gI?G*p4(Y1&W=DJ1269x$J^~x&Bec`s5|z zX^3mb#g)GzdVg_r*5p_H_&X`Qm!~?QkZkcZLylAT!M@JCL>$@4lIP?Q;?V_8K}!a+ zY0B3z8bxqlz(HWztu#fnRHx5YO@%g!5&;B3Hh7&%!*@UP-~b%=tK+f z_!#ZXc)(*K9-2Q&MbNjO8SS#Im!LR&ICbByFeq}dr-GZrmyebXGc?68AGyf7PoHBlddXU)2 z&1t269D?n^(;KfNBew=?iB?3)1Z$LLhhAD?QB2o4yqn@l>pFn6kX!x0CfCq8=(Mym-IjRZ%FNIapv%=1u15>Uu1ad4FPZ}UIgfK3M!^wA&fh~?sF+bqC=`wt|Q zUZsI_Y0kVv1TwcC>Tr3)IE^;oFE12^&7~|{PexX|K$hnwv)~jr5v8v1Y9KakTy#`zA{mYsnem}*mc>@>pYjSBW3RV$ zkM`(E#GeB7L#pqY&(GaTh0qn*n>4?iDB!r^8))`Nz=JsOz7pGz5eyYs>HgvfGCgZwWewVw5PF->IASLi_0CuDup9N%A`qe52 zkFW#bH8&5KIZ(zaWx!jR4W*Y?4goE!)i&VOJ*dLof_4|9-05=zlb=+xUD>AAKN(Z7 z_+=|{zdb$E+jWrM3s%UVUVWuC)cas=HR2**MQ5-@ifx4i=fZ=AxDSRtt@^&;7n{~B zQTy`?SJk5jJCaS2cq%h(e#hnhF%u|5|g70(ZxTD@vwIZ^HCO%_Wt_i z)a!W4kFpXy$7TwHbp;L3iT_*#5JL;LjWTX)>c;HM2_&fek@;;GyzRl+nu=lD!>=1S`VH9cxBA@B3eGoRH^;`?T-Nvz?7<6 zf3mp+s_49`RPJMrvUM->R$w!41=C(8NGLYtJ19}32-}e-YxcV;_EG5GJ>OKhl%vG} z^ME3IVW(JLUqYX0@F+F)o~eHLXbv8)Ff+N&r5sJ)@ncMrI+4n+jW9=wgh}FKP%e`P z8KJsg?YKwAkjoPveJ!+tmta#f;|7mK6=?-oK5p?WMY26|SeX3p(F(XV$Es|l_Q;DW-fnKPj?q9$?&~%Xd(>Lk2pP2@q0C-z6vk)c)5AV(i2`Am4xI z&p3Ub<+yOOtmzi&lQz_GzUA1p$J@FO5XKeN0L~#gwM~^A&GGM$?}I zZ+^%O4pbyKOva(5TmkAGA#~L=Pwf=$(F{F?E1-6}976WD<{0vp^V2i(7EdVz+FiKOzx4;gxrbaYOv@??|RglHykbCPmkI~uM~KnD{`tmeYt z$u?Gdrvd-fmS}V``%jivU*?d$k16YN*65248)82qPM`X6qIRxOtjm)a%7vcD6c<8f zq71^AFpGh_d0p)t)Kv$_3FOS7(GX8UavOZ>-oY7}4&Xgcz--O6m_3*@emb@{6gPGv zcz{bP+agG_oW`^xAkF9+#eS=t!*yZyYm<}PciH$ifU_7BkzD$#=hd;=1i0Br(H2Uw zV+TNgmg3ciHM)HgR4SF&Cs-K8CULjiAMYp8i6@}D*t+#}M-p>}%J8I+{TkHu#e%;p zP3{gj1$`DQPdrAh5x5qBJu@li|KY9cGOXMBLhI_z3vYI=1#r{{-#*svSWiwYHpO+V z5U^Tcvmm}`f^@(JB86p^^b~#vGEHlV)~G%@I!3C^Vc%me;4NP+${2Yh(xq*D>rFl} zl=|+DMyR)Z1(=uba_F?4!6eIbnJ|arG{d2V>9J!CQxEljpYTElJg!W!BS>i_8i`cG zLVI832L{hL>MZUUX4Qq(}2x^ugnC09SOdJSl~>YJV0-+IMyJ=sx?~FDo|+l_HEJ zVfE)w0oR&)6$q`|TE}LDC<-FZ9jK>l-i`n0CE}~XmUvp2L*{f%(AvW%H0o8*ulC^^ zZGI$$RUn9vQjGb@gBdHuWrwL8SWeb&(hF-|$8xN_h-kp1#Qn=wGZ@NZ*kv@IYIbpt zwTK483X}VI2?}QSCvxclcXO991O^BPq3W35SNhJ=T<}WNaqYwzSH4PSC1W%dw);!t zz`b7xA1Ci?+EsENnN5hnal0p=7mNS%)nuR%kwnn9S!RY2=Q~w!E5tM58TOd(X_4mJ zjMqj+jle*am;`bW_)>hh`*7-Td9Pv8WRLh*Oa^|z_N&?+91B)^648eD8_c}F9w$Wz zv9p3?dZ*TEV>XS3_|kT$8?nVSk~U4`ugeiwQlze9y-HUQ_jVUN{Xgk0)7*oL6Xiih zWC=o_sH(2(UOS%=2pbh8L?O3oMtihatK2)=$**)|3VE-4wvGQ3%6+`!RQit(j^h2W zKa$evn2K-+8J-Y z=>o(}x1z&xx<{Va%X0rWXh{knmXxz_j}G%#e4fj(!$3ND%R)jKK_4qDYd^axoI=_(TrKrw-p1t&qrp0 zY?i)gBupbgy$-cett&<$`AFjY25Z~DvL-f21XtBErl~5P!Dn8@rxHe`~UT9}-{k)RSu#g9lN<7MjnrOs5SGwb556wL)B&JJI%-VLOVH12Tb?G*N=KxJ9;q*AnSs@e;L#H?u?AX~ zZaPuvDl`5FimoHcL?2P(XABiJVz zE*NX9#&x=47>ITIR;i;YtQbd!tmHK>Yiyi_?l#~-vf3dL^)l&~;#3*`BOc&tmNTP)b*ZwrSw>ye>h*1LtWpP0$B<^lNZwPUWj!o1^Uq0ohE-Hi5kxLoelm zfs7JQTEGZ;rvxWhY_CT}ZlWZgRrI-=ecn>!kUkh}gjZ&vL?TU<;kC+~)!8Kexeyp| zQ0*$x8y1YsxXWS0$oEw9DKopC%RfC`k4dg-rNP9cUCQ!P%&Er3jAcsvY;L;av7kY) zb9)(KyZ`4#pegWF!5)?cJ~S>~^m@4MFI4Q(qwFQ|tOy2u)6ogb-{JGRiLz1FV_3Bd z^YA2$yQbj#x-A66zI3={7X9f9jZ5{dN}0UptX4jF z)x>xV!6m>&AfOK;62vLQCslQ{gPc1)OcE*+m+bc=7I)(!Jhl#i)*Y%nDZN))-;Ml- zUd~Nzf-Dh_sF~5E0z?_~DqxJW_k}NE?2rAkHhGAb7XVqo1$aC!^!NwG3))S;mNmCh znu+3#>%_>`qEsdH-IbMd^fp9O#^!QZlu9ChtMh+MJd(^C5EnU0F)&)nsK?VY5Z&j0 zV+)$CrNBd6$$J65SgM}@6ehEvJDVO`V{cCOMd#iTFo?jK{HLd=HpNKMu$@uasij?P zaEF)6&M=hXL1gJMamN~o^=nKbtUvwO+O3D&07*c$zbxxByKl;Wxz})bd+h5e?2V>u z$7nZAFk#C34?$>W{tK0|;7J=qHwX=r5o@0Z3IMJ;-F@I$<6@{K5)OGOf2ku}O_r)A ztnK)AQp8%^2>CfdlB`sapDt+RhcFtYn#yzl>vv(Zv2&F_5v)i}CG{doj4B*?O0F7D zjhYFLRmu2+s!1|#$(eRh=NhYk)%0gd*q-o#1z@J=ylm*D*XR>W9DW3~> z>RvG1Usw(>zPdGS$jExYFw|BGhI0#NptlZ+&V=s1KS` zW(Pnei(<^^vCG95%C5BBpotB9qkIQ@aS6RL?bp}5FR9P=tj(zMB#a(#^}Ka_Kz`mk z7gmw!wE-cN3H{*oDrx-G_}@^VwR5gr9k2}ElpOF)bp#HZX}+%~iIM_rCf(*y$8ro3 zxffz63|~Da2Po2h}n#c^uqzLbQITbk?rSgQ?8f~3XwWu-|NvI@!|Qv zwP48p(GJw)_Tj#)rE;e$pDKGbZj6|E67}hJGlx(D0IaNXU|TVq=WkPgVw%j-+Hzhl zc@O#Gf|sdd94;k_+|O??`@M%6QS(FD_S_C!88$=}Oyq#>k${N<9F~?R*hf#}$gS}= zp^6BxoMe-o=%4hQBg;pt?O6Hc&igr^6ev|{qn>^bkUa@K zA&ky7ph$g`ny?2bA)Rt^|ACLX;1v+=Ev+5GWl)Y#FBV0^#Puq+H{$WNm1pUP^~Uh)}|jh*y-sj9#$y zvVhDtRNU-tw;IfbIo?Jf4W@z4j18)})xplt5F3dMRd2vM@y)bO_ou&%im)UNH4o>#)*fpj?d80CM~9?W#M>{$ z()x`#G)8_{!oB0oG?u$bQj@1(a9PBiWAuhRC%DdkT22-XzFxL1hhETZLPC#>|IfS5vZ4g8_f^YRoVO858qx}ryA z%lrn?mi^%IiZ$V4?F_nfqHhy_pwlpL5Cuiu{Ks?gw{;8=i2`Ae&W!}H9_sFI>itNZ8<(gAD|crs|(FL=?wq> zcg0vq_(l{u&6;1?o_XgaJkousG(Y2I`nhhYGH-JQjR2N#Zhkp*vd~PI(LSjYR&69qMddsQ?nMCB!!6s=Ssl$tMQH-jV<# zPp>`S|4W{P6hYydp?RzAfDAk)LC~G0g``fW@DBfYCnE*1XnE)b9nxzR&VK6wQ2(LA zdR=SM)qc$;yHLJ(S$&KfR)Vvnoo<0;(%s<_i_irpH-dSQ(XPr<6k||g zG__+{fH!XM`~ez38hEaH;10pBYuwPl>E!_*S9^D~9JT)|Tt&%ZU1+(>j*h$HCdac# za4L2iNmo?zAy4rv#{_{CkhWNe+(Nqad@L9Uc|=L#uM1RKkJHv&joMZ z6z|UIv?wIex|`>-i1YZ24a4`3HgrFR3p2l|Q)VVvSyYQ?$ABUS6jvofcyUQDL-4o% zo_jyImok932UtB@{4#2mjs$Wb@fsY9Q|C4&$my@d1Pmk~d%BUG6Y21R2NpL}+o4f@xuh{ij8nn!HCGx;x<75$HF4o)AX*d^EBh zZxI9Un99_IVqj@G^0|B7Ak)SoNCFH+hgEUOV$-%y`T|G{$fpUXT0E>cgWb}xmIr4o z_)CE}?=+X8YpEB@xuqi#YWey1C1=2!$eR%w8cKQ6fk&zS$=pU%WG)`H+BMzB?9#S@ zI?kr8V${iS@2PH$c%U?-j&e!&dBjPwurOIH{*?Gr-3g}8Hf~MFh%2~jHH|?;w&u#e zAN4R_2jHI;0GCxx;zY<8ap0lnJ0w+dp<@OgubM@M{A$_V9WJLdN6raSv7^5HynF^t z`<4IqbGW+YMelNXNGEXEnG3-6<(bM4Tmyze**`xxsUq zm{vtJW@Go}_aJ3VqjhAxwpV{2AfN{-m8NXUp?c;5?i;-r>$N_eQfV}fjxhs9id#xs zoJ#$)jiEl-TLZ*MvwA*)_g0C@E%pci4E!p13k~B-P8B-~|HDk0KZNuMYzHH1r(>@I zI=F}5%!%_%Phf6E#SOfv+LwaIRvTf12s{*hH5U)q<2HQX;KuO(M?0?k`Y^R+-#kbm zEbSH>rrHQ2BL6OSk~V~d_<@_0@ugfMc`->BJD+4R?IIP-|4-Yn)DA7f7-@o1(s$Wm zr4|gZ?h*57ETgk!2ToEhcfR(!I9&d6Fkv;uoO>G^KUG%r>d~2gpv%(_pKYXHtqvgK zP`fX#*{`Pk5V!8iA7-U@`uaZYTNr;%Sip?1#;R5uSe+G*8rg-=t%i<>Ca;I+0aOKk zT83BO{uWIpFPoW)hpBrWK8{7qBkkih($X-(U26U31l2^asF&y5 z;`pR-i-iIpE@akUym9u#Wde%cjr@j32%B^+M7Q@(jeTn9iI1@&ws;x!7Le#AvbQ`u zw_V{ZW?6GciJH06E~Mw!+|(VFX;s|f(pJ~QP2iYx4!DzRW%Hg>1C@i7>SE#MH%Sf> zsjt1;y5YY-UzdJ|-3>h>y6_hQiYHhymk+mjqYlbZ^KLje+~KQt(#b`klLiBe_L#GQ zVBxJuK!w-7W>bWc)N0Q)AmvhlVeUw-WjDd53;F7KrRnXc4EtmhoKjiT~uatc`=)59`>N_?5$Cf}pt)Sub zjnh`^9EhYNcG=x7lR`^r;u8xW1mtXdik^JXvaBKov8UThsJi5Zl-FoSulex;n8-U@ zXxOuD#+O{Xd%dK23XRp9eJdztpb0o^xf-E-N8sga#siX%9DgDPEOi#2>;~V0^=8zp zrv-RJ&ie2Q*s`sQ6`pU|ms5RCdwWsg1@+eq*GYZg0 zukHyc6mqu>-vaa1e@(eyQKJRk#6`6c4D7EQIt_*P+bzcvkJ<0!eU?Mfv|MkjmNf523 z13z}Sa3c=u4U7)w%bUD38ao@3-Lw(IilqBE8?H$};ODar77bo0i#6M(lFQY_65I#6 zyT{CMPkdgP+yQZTb`SsQO@XVOM0lH`ZIf;qCftLnV^+0wpDd+LcvD66calC~gNtsf zWza;#rH^}*hX{ktFZ;%S7e8|zI9uoR-2&=^MCRN@-KD`b=GX%6OW9*F_JWIXjtB{- zGQG_y9cmD>m!5mt&F@-2E8eX!lf@#IqnwNP z*-s#^bOKDOFKCz^B`Iv#Km8>W3nmT+f$GEyw(Ak(VtejG$ko_lK8%nW@c1;W(}4tR zIckou5_pWXie}T7(5r{ee{^X{XHU&+EnUg$WIceD zcF8a>(uWFek>53|gh)FgItdmxjTcgm+CfKAIWW$pJ>Q(R-NcR-X1kk+e?h)lEh3CD zy5^K{3z+xqb{LDm-WxwnXXxlSi2S6dSq+WGlUXf`^=;Cb@*+wY+&s|qm^?|#f4 ze4W5l>^v=vHCBp2tMQ7u`bw$1Rs`D&FJP)Sr#U1yW#Ss&KPddA_r^J+t|fn}Qvl$h zj5@JAP9+meR`PuXDI32){Tz|87>s!Ar&OHM;Fx{9=YmwdM18G{?Eu)=RbSUQ_}v>d z?W^@}i<}t_{>>6(GJdulU70dRHm)ClHYL>FAm|hi$IYpOC= zHnv1p_Y>j!i6F>t_n&^ct7uYg4qF@-O2S``#ogG=D9c^+*z{Xk&@COo!RwEYMj)Cx zIg>qVWq4u{NIKfEY(%UmE!C(7sc$`q>Ww0mq+0s1;oafKRuglpVJSldGnm-C53&$zD3u%Hfi9y zT?l}fX2Gr!NzG{eB8X(_WV2ymL0s|Tcu)6`ifq;IocYo)4B^WaE+bH#WoyA>F-Bs3 zAG(9CQE^k;x?7KfZeEmh9n;z__whv!8=zr zbUW>H$P$BFyOATBBWpSX+UN&HWu5_m7!JI)=UDq}%vgchx>8(@&)^E!xO^#4DQ1&Ro?RrP%cD_$sy;WVq;?@G` zUJj)nI$fJ5+#_1}gxC>S$WJu#XZ>tb`lQDfK%MJSPMe2fGco)cw>Q}k9KSrkVe?AJ zDL!%FRYrPLM33jTjH|3jKczkX0etghpJB*)C7emsgLYC+x#WJ9XTy9UxYBA%+0G03 zq-;h`!%vR2-kn7O`ap+VWZ3e!3(-gUNpVu7j{bu4UBK6dJg03j6|Azc{rviHyC-Op z1xur^rqhgC%=YGhro4`;9X91!xfR-UANuF?=|tq{rfy7%Pa|VlP)>=Pz~3oS3Y%R< z+R-?K@{~?x(t7^U1eogi&-EcwsAk_Hex5n&y+?6DhGFs!qwJTF-nj*hviYz@*vhD< zNbpHTwyZn2Xz$xLfXbxj73wqrvPWHPOXSwLL)p90GN@>U@g7zT&Vm0wkQHvT$3bMh zjkgSeF{7091M4a`!MaDAYF|E#DH{~h&6Hzuj4CM+7>@2s#nO;E{g6(RElvdv!*v(p z{2=M<&cFH?(&QEKN+)osJ#J+{P{U}uYvc6jDRa$1yY_-4>V&NLVuGTP(XzeVwsp8aC5r=}qAZdt5Ax z+UOxR$9PTY%a+wH0LlrLnG@TX@}Z-Pvdg(_Dw*qp%AHm!3JMrD%cue!+f3G^!|+5I zz&u`4b{4)NfUKv-v${IeSZWeq!2a^xiR*NN70x0Ch=VU`jCJM{cyje~g+ketT8wVF zTz_JP9XvjK-f!q+rpQM*v}g}Jmlu-2BVy0zr!D-9ygw_Eb_gv!doy_) z2s6^gw1h~ZP&xEVLkws^^Xz3Q_rgh#!(wgs2%JBsU0LFkUcD2ZJCvO35q;y)TUwQW zxMg~&KwdE#o40Hg=>}JiK0cNzeD6Rm97DG{vJl!5`yN(!XW0QJ0*LLsPAdbr5)}da zHn`%d+nFqsQzM`zP2?4u{D2kM?S-~sJAYKs$TXgVhs&WnU5JgQVL6`rE29sQkoD~T zm?UKUAB7XiOZm3F?GDNYi=y`De!znLlIHcMp?!CjLz3Ys9p2T9RkUd0;CAY-vfc)D znh}d76Ltcr`PHQ36%a9{-WqRUxE)AMj!z9vCOyywii8KvJw^Cz!G3#Gy3}RhPqvgb z(f#9YH~yS}>woSpwrQ36LkCHiDV)T_yXM(NEv;LpuNp#-m#n_?oT@ohD#qD+*r%u> zMSRPvH>c?W>P4J7;*Z)8L(QafM=^sJ;pB`BoW?#GRqVr@!x~X{MqPObYmmm9rWeDR zRq-f?avAQ)6$%x&TxuQrq^A$NKcZ>$!UZFz!lCsQtwC_vDpM|Qb>ig_j2?JI?8Y`;9m1u#0$RHO4PdI#c&e)etW-@2H_SRLAY4>MZC0yv7(=9M-V zggHD~=!bc3P&!{H>LA(~A;-k$@sRh-rP~ohwyj!h5_T{?8@|{;+a3m-AU;B|aBOBy zV`-Ok$U*iOtUvK7uMQex8~1=Iu#g*YlWXWjr`fO;ykf^n44K!bMw!rcB%0&`-Bi$e z$+HzR%wjCa`b5SIf>6PJT!6~+7Fp&+?)VhE2iWg6F7kncz!F~i^v%82UG#&5z~%Hu zo3XK?Lbi-jP36bNUVy#8a(U55#9I&J6Fw;9*!k>H#>lKgzqAp7w3~H6W5U^#9wf<9 zZ6P>jwj2Z&Gz$qXZ_MvM+2-x250;E*@d-9nNrPK>s;uJR!VhI_Iz;lbgI{0`!Y z9TZ9tVTdo*Kn$+b^V~fiB9R|ChWo%tCmJaKJKP&XL z0-vQ8Sv}bR#>q4D&j(dt$cVQFj=f74|S5J1m`w=80n1H8WNUpCWRQ*HQ;%q-#H;|?oYt(z%?%nxH~qB^*0@e|YE ztuftuQx%cU=Ew##p@Sh5T2`|ohng>#S{p%rd+#-DtS{usdFbHOa3q-k98H)Z;1H4{ zxuK%vPNPi49OI{zI25#Jj-suLGWk>ETr!^{5LO~Us;;TF=!T%|xj&_H7R?TvCUtH4 z5pRRfSEaxTvkII^KABu9nB;ng!T+zxKl;2PiCKJc)l*ZpqmJlcga*Tq7#U#6k!^5d zS5fL!NH1KGvZbt=5v6~`W)14)PJf0aH?LxTKN$-D-WN~O!~O!OI5QG8}_w{EP< z{1=`D`ZivZzVUf<6LLgiU|UL)xjH&Bt`Hio9~yx53rrP;!?SF$^qvHfqB@QI;JTq!D zv&fT_08oq}Ps-v+qgrcc5Aiv;2PyNbcM(>cqXU6L71-wVV789Fa<8@dn#%Xivv@3i zg+URwD5=^2l}W#!_id`*>5OW&UwoG}t1LCl+1%7Ed7NnHT{vSfdv9&NFo zFENc6Y`W5BY_$X2!_hWwz-VY-*Qy^t$L%HXz1PZQgY0AV*dmMi!ZB`)s@4_KK ziJ}dB5`Uc_BRSzxIJT(0|pepQCYSno>Wd4mTz zx@7k-BE_QUh$Up*SE-pK-yLI_QBy}W;>U^Nm|YC@)KliVdl9$?{1jyFp(eA(hQW`! z@@sORG&Q9A9A(MLe3JQKL1isF6JhC|?H+e8V)U&kD9)8`11QaA7@VO**5OAkCDQsS zrQCr#Gl>8;@-7D9TjFpvOXdd0R6gd??l2FJY6=Wgh_2ANdUTHYSvew{)0TiaWk^C9 zF^Z}YW3gc{pq#Nhv1K49?~y^I)B?|`JzSXzcO<}6vZMER6*7^XC;;|{kl7M)C_6gW zO;z$*%QjQ-WsQ}z@WG(&e_3KttWqk5x{)!4b_dQBJcIIP>v{hL0$-U;gg4wN_-%3O`Y1LgkA-mLWY zu4S(?VxN;7i&gB{TWb3eC!=EX?;@;SwYA~zePoK!$q zwNyompT1CFD}4B(I;?ke)Is$!)lD_uf~Qxm$>K$j2qRF`U_ZK1IydDcGKeGNO|C9- zk03F5=gsTW^CgbSu&3|F01OdvuG_Aq)ZUlVY-%ql6h+9&nBYRFrJ|=Jm)#@U#t=>a z7vo%k8ZL=1v-j-tBtJH}=)tu-15;#fp7rl@Z#>M8B1<*hB}@ROz@UMVo_8yGI>@e+ z&+_mVNfM)h$Lzw#Lx4gVwx!zcqXti0Ga>O@>U@rHH-1XSlnd?Fkc4R1oUaL39vm#A zu5~%_T9!oJD7YB8IP&4)xEvea9}SapIEe)qj<2Qvepe6r>dpP@o&+bi^}6RYuIQBD zA&2Noa76A3^nmr-NYhuB^&}RNr=C4CwX}L!V;Z}YM-UmFBiv`u?l9yOL z$UlF|Ynq|xNJP#+Lx!&RRc}p0G;*HHV53y-HZ}c(p8E5TGl))!eH!IOUM@O<8SF0- z$9=HBsau9h4>kQR0DeBH#MOAW%VsM4PrM#DQvHLK`L7{j>Mr2$=_8|Mz}7L;#cp21h1QFPj-4!6yi<3#2=By__)uz zEG^qB#GRVSG0~4Mu%wnt#Kv7h&D9gT7aa`!7zrq=;<_q~fLMa9zn#-%sw}cw5!LaPDXc=sTgvkV z*9-3F{)SzPr5F0DM{8u(K(VccO;DHF$!Mqt@XTUC*Z!|j_9U}%W55P(Oc6nz>%eY9kcU*eQqS?lWb1goDS&K90H-@ELSaFRk|}J ztTP;NT}a4egKw}V<-blw8XS&rr~$t}dFSmlsYpggJI7X2Az+c73d$}UjLi)I;ngS+ zdg7pI_9as}kHFDLC;=7J&@yhzwT@c{3ya!LE8Bl=g7t6KpA{4goh~Yw_S;A@h(y}i zs#2y!9bz%ydiSCgFs>EknzXRz-kSmU<)>xnUR!f5oMW1}*lZ<;hQr%hL{EW?lNgEM z3JPk|127ukMrD9Q3rJ(}WZ((dBZVtPPA7c>vJ&`}TC#Y_3sfVmi(0h!!>-`$a53YG zM%XDy6SnJeZkW@uhsYGwb`k<=fnxWB&@-XXL*J#X1XM3O45~OWFmuk61#&@Lr*5p>c+-)Fqub*6PQtN2*O3Jj{oj_ z%&tj+KQ%(vh^j(nQ^TEwhP zgWKKjf{h!6a-qG@Rsq3aK?ElFUSO@;sZYZ4`km^kiUvVXQEet#4n|nAX{s`qL@Ien z0%r!2Ak5~D75HtrO+GzXI9!gDa{A{#Ww4JZU%pO+2T&$weSesolfsz0=1dsEckc zY59!v(iV0N^YYDOeb*li#*}FB8&QTdT9=_RIs|&U#vepC+Q@A zgU$`sxKUpEa_2E8l492+#<11b*46-^nYyTK>00lBxxUccj~oLuCC zCjC#!t}fzdtjQq{lXZFc<0fG568^+9(niF+%g{-|SQK7c4|GS;Fe-~zKq$4#qDrPl z^~A6A^*4vuDz0}lcKS5pCgcVNE)If+T-#ZDbo~t#M(Bdgtn1fBb!IY34}T0jjQNVe zfLXGzz=l?^sIivxChXUGNW|fez~Z4rj_keb4kH3?lnKRb%i^HyYWhlRWUylFW6Z&i zAhffXc)kG%H%CZNZH86)XWYPwa@dBq=D+nm*iXkqYx$;Fp%kkMt)DS;DihB?2f3$Ps&+F~ReO zg*uU?2wR1HHqY%bh{Ce;D@4$OWcAY9fPVPAoN$Mf=y&@WET>Nn|X;;}*K)y)g4L0D3WC*|6T$*(;fF(#z zD=JcrNALjfBJ|+PC;)5fp^mFLQObdC;DElh9hbq2TECUO`fDh%l;Ac+aD=>t#r*cU zZJkSK5#53|>g0n5l(;DL!(wfNPm@U|KmC-7&5S6LUoa}|NXU;Soq#=T7bEvw$5@{P!&$cMN;%} z-j#U~+gu;a;Wx+9CSfXi3eEctG!DMskCyl1(*eW~_VX!}pE&i_PN9k6OD9PxuIr5T z<6Z5-$B1z(?vYq;?eZeG+|m)8+xzY6o7k^3IQY<^$|zU&*G?v{$!^>+CnZMr?kBW@ z=HMCU5Vb_+@A()Zo?^o(dzyDvj8TfBBmSnN?FQGTqyu<7P`!h?y@ke4n#*>4(*-8j zrP%MEbjrMS9ZFGC%z$Vb`@}KxE=9K#s(xXm_dzXM_koX_+qw4hRpN8wsyQE64*dQz zhzeKY?j9WSX{iL7zTTl-tgI1%SY7$hT{esMAgkDtS3Ak<4Ym&pmQxO%j`Vz_=QWEw zt9hjy0Rz3s9YR6mL_Xzh!G|k4k{q&ug5uqV7dxUzI2R9KNc^(z4u%GcApy>X%d!N8 zDuLQ?(9XLZ2tK|ZZ3;l{nja-`xFyt+qO$!AqSOM<=jrCm!6gi z#LT*qpMFNfljdoQ^BKE%ywi_U+-bad>XCw=2gG>m`O10+k&gga=j_nBGgd%d( z$_QV51%?5+Jey(JK+2eg*gWhE%x8hmj}%{YCFLZE(E+UmsSncYUqpi&<$i!seUs#& zMS3f!cM7BRMn%~fQ;E{-wg9;sauU7xwORU9FhRi|*`jkP2m=D7-1q#sd*7W_pWTKw z-jm=K`h8fyX9)UP*WgiP&$SO~2%bBdUaA?2y4#AbdVFYO%069o&}4t8LeFQXaU@r> z%ned?IqmM-{Q!N~z3^$+WJ#i-XBTp>g7&=iXHzInnZjd@8Nf~O$qAJh1)azj0xknTcE)Xb#G7?zG!Zn$>ZE}0WDy1D?&?2u z04_LHHiKb3b0;hr@sgDeCvpNILz1Q#8<4nhha6k`q;6|#k~^>hQu>p{&vI^f5$J<* zx15R6!pFy~hluvZr=Oo}Zx7XaQ<5H}%Af;3rceJAfMFdALd(0j;PSTTHPbNnh_^o_ z;-Yjx34!I_cN~cm$X=U_Va?2!fu;~n6ExvpA@E+x$jPem;+(b5c zLgCwxHBEc^iov?Y5%@;IA{Mc82~m+ZF^x=8p$bk4@pP z+pwEo9TA>kn3|{fM&Tbp%}c<`ui8*WsHtS-J=&o<*3kkf>ZZwQ9&jmsa6T=TVEGF# z(QmPuJX=xWhw?KZT#opc0bPEoqF4BJ5FRZ>+%6qdMpJ;8wiNcJy0dSbEQZdp>Adrm zoO8Rx*sP)_;lkD#$Jd2W+lb=RFtT>5(MG;~RDMO8l?q^cJtL-oy!Uu46CRl%mTH;*FnA+OjugHuWl=x-XMG4fFrdtL;k7%OwPpBbH@u zV6O^1&!kqtLFy_PD03|s9b=_I?87rZ3fPP$kFAjGM2q9u78h7vd5hqDOk1h8;#%Dd z+h^#Xt&kM4)-dZC;``BRsa-oT8;c<9fIW(ZX?K9-SqS=e($|qYWnX7NY2464xA30Y z8o6U!iM6TudSI$bS%(&RD3Wq`>5}n8Bye6AW7nTZRV5Jlr$sw#_&7(?pSTo-DC*Pw(Bp#oIOeO zvXM$-N4)PaL+ql81Hp_-`$j)rzhfz5+bn;@i^mUJ@7SNfOl*>Hhl&{xVL%c26=CcifAd9^X49Iu!{(Uq6k4hVRA?H7d533b%(XC1a%9 zp>jtew)R8+95N(1;6kHkzGq1u66i#GVm2CPtmXQOT5?(^7~&puS!Y0+dz0%*^tvvH zHs#J;cMfx+9mB3bo#*f?bp%?QGgR&{x(8SZ&&~-Q3QO-yVh>9X2)5G(+=J}rWPGF zHpQPF=J2k;@gadr93Pz8ds@RZ&4+Gjx@qV{QO(5T^fPMqE*q9^`MG4XIdvRiU8g(e z=wVsOZ?$4FquP4A%S`e#5q7EVV;oNZ@tL=W`A-w^Q@n6rS+T^Pe~Txreq8r)p|LrM zt7w`G^%xm&2P8ELRG>fndNMY>(P(akqJmtxlRdz(>#WY5B4{NsXTwf~d}z2*y7o(F z9kmke3}?j+=&WNGLDXN?OVTfrnSsN87cvdcV-ONZJ6iL$0>8Gm>6A!!gIC@GHS-+> zLR7dbcYzE3FRhK!hy1p--&dcGeu+i{>cPNjo!T&^*XUR@-}5-F9fur2;V2Z&c{jJSgk7*RefR z4@P-Dqg}V?kfzKfVyK~Majp^{)I9vE35@E>)_v&0nyfC_cXm;)OD6Q^xG%0DvH#8c zV+Ma?KBsOK$+O~%-~rN8FE_b&KMUSuaTR6Ji zcYT4B67xR^c7UO>?s3@+dJ5E|qBpejgyTC!w%k%W^XcAFyXSyly-*_h$pFP&-pS3= z?Y-Uzl@9#V3CJ%Xl+F;c>ptJuL=m&8;cs`A@61C=9k;sX$#1^KO@#No*AWcY3me-4 z?e*n5L@iSSwR(C!DTpXiTvC+i??3z~OYn#D>S zn!?4l8oFm?@`oBBx-$75h@LK@d1}`p$mW&}GWeMQBe7sWDZp6o?vj1tNSA943H$19 z{=WF_NhSK?d?A%yu)u@cM`aq7BfS%@TE*_i-Deo7@X?0U>;#O)CBo9~vu-`jQBM=3 z5cac)0Jtetjn~J;!oQ#~Ky6B;CO4V@NgAV@`w=1@NUfcg8lw*wut)vPcDTt%&OU0wPRiXXWe1`(c4@6 zfe-y$YolPV9osJ3@`8sFt?%m}@ywI?XPkCG1fu@s&{eQf^_EIXiIk1RidBAye=ouE z77P#x`ffltc%4pDyw*6zs1~^|PyA}GQSi3+ucm)EH_Zk0#QQj#T8w59t!o;^%_><8 zAp#Z}=37YYXGm8;2aEs|j59GWM&MsSqZ&01t$= z4*C-S(4Vb_C}v#*`6|f;k7H=*rM0d+%tfCn-XG=&XKW(f)ViWfVFK#M&>~s_13_v7 z#QR^yGWeUbs^dOMf@a2OlpSqA&dd|^y)pwrk?u&z$YfKitU$SV-h6Y}iCGiKVXIAfdB?;dLuA8kp!PYoW1@R*Jk z&YgcGbyAx$%_TIhfO}jt>~1d{ImX^_2h@TIMOsC*T5F|hbU(71L!I>za&9O~h$K>&B908r#dXE8NKx<-=`m1r{S7Vqs0P+FXRo6ledT z3DMWbqx!jnUX`UD?or`mrh~X zA^vHPXFwQ!yX6s+GXMH0j>3pP%-wZ&a70Y}+>eM$hB`QVu^yl1JAPH-y$Fr#xN4kj z98U=Mgf84^On6UR@2Pq)j!ix<+UO^#CLI7hC9sJ0FU6#J5`Ry@{yIJn>y#6zKME$1 zZotM7G8V>Yw_i5ejY11i>AE(5C%e6*!E*k5$#qW41Q&%_z(0K0*n$ci(q>zhE?D|M z2|qPN39wU?K7_zTWNQ(DkdJrUivob9oO2VSUKKwh(7HopyNWF>_;Nd&U? z&Ve?iwH17E&SFUz!b5-+sB5k$e(e#A=*|w-(U-%_poHF>pDXVlFR@m#$oR1(fs)Mx zTzowg08i*$S_VWZQWJDg};jE7|~ zw75ZcNpeSVr&tSVCzB(>!f4+#?X6>`m=N6t53pzuEJ*SgGKDFDVPIY$N}qTIE3 zTv&r9l=zpkh9@>~LEksO*NygA%v01B!`h=d*TN{V=8b|evV3oZ7uhi4e}W>}0fu-x z_jqqsvRp|7SgZ_bX6m(_G`{*zd1SIcIU)z$#C~-YmG;w@A*{?RagYCmc>p z5_6gQL={S!)#V}FIP#fn^Td!@t>d8c-)rUxQ++g&;9&54ZUqW_h*`LyW8bGhJ-YL1 zg`n83?ElUKJKAHHf05DVET`0&A;%kMJ0}jJ!84o-v2?-J;YRSF?wkA##B92{Asi>- z_FRN{L(>|X^BN8Q9V<9!ql<19TS=BH0UOqs0d zJ@YS0tKFD1iVc9~f>bO}xwX4bQ{4u))Exty1XA=#XCjz}r!XBmd^Mpgpo#V~IbYpT zP-@C$Bl=htkO}HbA5q3z>d(Rw!xTuP*VU&qmm(RLp*EtBi<%_;|sn2Cw(2JD`Ut?cuc;Y zj81Od0B`rxL}2mosR3aN^tOjN+OA2t0{Kjh;bCCT@1KGAi;# z|My;~o=!M*F42=0sCdPE2~-?K?>&>I0t}I3Zjv$P9r!Mx!O>cXL3jwQ!rykDwPVtU zBY#=Sg>W9gl+QP}93Rr(g11ovO1*(hm#p)_n8J8Ow*qUrOIDV(#vqmT=B@|fb(PdH zQa&~->=of9$WLMIQyyA*B@OAF+|g~WW0=9IvA7+-LO6;w{homGXuZeGHXRO@H_g8R z5DqR(1M1e?`%uEoTT)pcdue$ifUD@+{|kSwus` z(VOjoMxE3cG~9U5Z1Kz*3kK9Qx$~Op&-0dJhMt$qC}49}%m6GZ36FEdIH1~tWu|H7 z?O!l)s#}BR%YBHHk)*IhRqJ#$1$d`D81pc|830MncJr+xWqzF!tiXDj2QK^jC2v=^ zXY0mXW_AXED9>%4ZGC0rDwcfqA?j`(Q z!bWRZ|H5hi6RSnZEYhXEU4zA%MHA+kSH5osGNa+TfyaZJ$g&hbvsG#0> zL@pDq&a!bWgtZ*yrwa-rSiuy{0Ge_wPM&YDQR5~<5>I~+yHo4{x-CS&ov;@}5CGG( z)J+(DtMam%fo}?Y@!)3gkV@la7Pp}joUk@@ke`qHJ$M(0 zMp*7UB4xv4wi!}j*T*fKd{Jte$&i@JYUlM7?PRktWT6BQc_>m`zSnLpX}Dk%q3fOc ziy}*g0vf#ZrwM{tn}DdMrx5(5+A6J#8acD2n8$98wSYsmweeV_aJv+Aru7!9N0!}K z>c2rBcY9GL4+KVX3sRiFTG=5t^l9pewGJqEi(~utyW+ezHZ|SsN6bE!BV=U-E8}a0 z>h9WUnEKIHTTD|WjmF{gbiAh?{nN9BS{)_l0f9Eu6BPBZk1#$2hlu8JQVJA^LB9n^ z(EDMU6mBAA#iO9HavB$pI78C5hGBXl+^nvZ0vN3bOfdAvjjR3*Ss1)IVul)73%__Y zhfOOC^SRQ!`^0)OQ0NBc>1e0A{*Kb1@`>E9o4{=OxaPrb7yq}ia&%0EgCSXdyyZvA zs7{!R&HKZMBmNY>P5zz0__g5oXe-^SHW)(jk)3ortW&SQ)EX8SpLIAR6b{Ol$kDM> zf;Al*>(ynhh)#i?EXz7>1!2r6nd3!YtuUKN_d7GO?edQWHQK%z$S&k7YF9{m$dM+5 z+khyhE@}8Y3l*)!mZCCtcMFWveH+9%O0A$!R1xJCeIEuhv@HfZp}Ra5$aPlnNMC;= zfi6r?kn4s?^Dxnc?a%Ra$-2ndA9;qpQ&~>J`Na;Wyt)1iy8bjk50x-UrtM~Gs5Lqp z+l1U}sl5fn|NAl;PYSO|JP)9`@^N>UC)nK`swbwVqP1d66HDe7X2g5)cF=3cUd!%k zNC<<1Xt62};Hh_deVLBepbVUhtyO&6;XKS1a|Bjf6QS@U)P^?M}@_b28~HQv?Q#DSbXHrImEU+tX_Bz%D0aueN0sWXQf-tur6#q8Jy zYcmtdB?sS>i9{j(ees^kdGe&Y=EI$Pr!F&dS$Ezrwc$a zk+T4Y%8#L}GjqUbHljbl5Xh-eumiv$_4iHuERZsi-kN5nwJiahuP*{4C{zANgx^Z6 zf0julYde71z_m_C1qEi!&StE#TPbX0B3HohQ!n3QhEPQ3^dja~Ft2N#5{>@1U{T8$ z!gT*~(VC+|yC`;`Ya{QZT!ZMdK7Ru?OZ9hRxhM{f^`JGRF^|x%hH{%AaQ|~|geOi# zZzZL{i%xA^6!Nu&cNmgTJ7gb6T{R&S_~8 zbbIqlgkVLmWSL9UUpVA^5^$hB)8{JT4Cz`5@9X0qgdl!Fa`s+C{Yww+9Y164@!8xi z$5~#cA;3zX2~xH$+!G0Vj-oh#ooL_con#b3>(MP^8E(lO!9R(cPs9 z8lXr<$^ky~L&@0SbG)}#drCw!Qf@f~8pH+Vjnv0b3#zN_wdoi$4^7$sJ9uvm*NpKa zxTdG^BEtxSA~9c*nmRY!RZlb0ZtomjiRxm>x@!afA98tF7G5FZ83(6x7!KsDJezSj zTszY>u-4~}&0mR1#<2BN$&GlmI&o%dAlc$l)xQU+XcSpfg4RaqA;t~1iKwtgh+qtA|Nnuv?zfFU{|B#= zb|uI8EAj>2z+$f(2=dM*p=%Rrtsz=0+>f3xO69a;b#iAFO_&5iPqR#H37@dxusQe4 zlD7db(i$`Ar?C_XW2PFN5q&Zxi2nqN1t8D|mO9s9S z+*eU5k+?KU6+n<@7&D@vqOLo+NT}M@B^kbBBGowR=Y#~yDT za&P>==Zf!-QU@F3k;tm3fl8XHN_#?69DK-zV+f3{h8 zNJVepTb>>r)+@ZAE`{5Ipg#_t!B=O9%d$c)Q}B*gBi#WK`wT_Dstgk8FYVpxjZz&Z zq-GQChSUbuTX7vl2{Z*6>MZU0wY16R=|}y@5Tp!xTT^T@cn*}Xe5p`fXEr_iY;_B^ zUWG6_e#Gq1zJWS(2fO2?X#^fcZJ9w0p9hrHE{_-0ZQ8Xpg?T&f{1Kt@A4P%)1Hjeo z*W;Q4TON}3rptoWBMaJb)e=Lqq6uGC2}Zp!qS-y3kc{z?*+!$gmK*AQ_g_xOtk2H8rBDyX#fw1_8Km80)A{{15yVmjf8p#86!S9*wdyMDrx6b0JORt~&UB(Cyz=({1 z^8nmtl`*JX0{Kv9WE#XULLN_~l77xH{5T8>Y!u>oY1)+licTpB5LvDI;=Xs7#kHzb zx@ik1#=h>WmzgNhu@i;WTnpBeF`UQLllYrX6|j&vtq7E5RrjdWg=wNd;U0LN0!(f( zhAk+&0l2wT3nWl5-9g9#3hd2aA&Pigs?m2$j=U9-NDI<4EP~hL8h?5l||_ zoxVl+zj_CfawYEx2MCc^t{o0WyuAk&gD{q}#5w7d)^i?e%|g@c29t~y=L;+@@_{`TAp;)ZYo&d#hNhnzQxq4B`_i!LlvPLXBE zU?5U*NG@;J=`7v3Vf#AQb6fOLx`zO0e$~1WRH|V`>M(~S#<;d!orYY8eE3ABd^c7_`$D)nh1?;tu;f6CFaGcE7q`>YrcLs)T z+73(su=?CO3^?+epQ?b8OR*zW#0TJBPYW+=3~jSmQvuSq%!Vh{Fs=RYJi96tkOlFk zzpf-0w^T+&cy@OzrRcfrDtG9KWu(^^>z(vH^g`$EM-)8OAo3uvagV-Y0ACKKq8b< zpwL)$wlzBE8wenpVCaY21Pzc-9{z#V;XVA_l0;oRboIX1Gz|+fM352#MXa zw&Owz*ny8AL(pSjzF!sbQkfV)tA3n(?XnHTj|d+T@+N*|TLH*NuxDLqjCfu?lgvKf zvmQ)*sx#;!2<{j_^CRINFr3j&iRAgqn4x+ZZSW1WS+Lj-9HJZo#eCX;^qY>PQyKnc z3BWLGwDhi>TCkULbC~{lbS&Qt`I1pNyj*tC>r@<&iLKMEysB|I-WWqkMC*%im1#a-KssmSM}mC!aQ5MJs|#>L1MxI zsQ%IDOTj<3lrW&!N^gfH1O&+wvYxbSyyKoDh5C19@05{9X$Z+lEWZ#aawh;lKr74Ugh zi16N~ENWTfiyYFs_e22r(=c+cC5UErJR?J*&o{xFEpI=;VOHh8xM5e!{w+0|Rd04% zLC6Gk`4K;jG1$0XK#x4(##VSNSwl^mYR0+9S0VLd5z&7FuG`+K*anUtq?(qJMzi`) zXF=9Q&4aUb%5e`vE}QxljGCwZ!&n~r)MvIn?cfb{_;H^6)~3OBDSTv~@nus>R6+(W z6WHIrkW7`_rAaM4SoiH82_G_qG^l7Bwf7(nj5|HxqnN_+PkI8CNk1vtG5`W(+=9vj zFs1YLv}z%K@jD2F$YM_eL*zo!2`C9U*S2EpdgjFk(eH&0U28o1DIuM|gi~d0yegwT z%=)|F=v~Vo9<><#HHN9r_x2qZ1E|(U$9cE4UoF67?kM?%*8$Vb3GMp$8et&s29-fP zRC}2N`^<-}KXHQ_aj_VDSX!4JH*qH*hd#o=Ht?$ZGv)L!ZPAq;Uo>h2USa3xV3SV( z0ha%tSkEcsbB{k9v;1Iiro*tLaZ#~*r|)DKID2AM7h>u8XCBQ4ldHr>i9BVGc(wzM zuv<2^|3Bb<1ANW`K=blEDS_{8wa8Y&Bdy(?N6 zk0?=7P{P(l=Qf?tS22LD0=U&Gf6o+1ZZX3$)_2WFmxp9|k=` zKzY1a?`(kCX+P<<|J9!bhu6xI*%J+8KDTTr_KQ9)@Z$+JRw)6K(oueBcjtjn*nWv3 z)a@%#efW+PdGAsmnZeNyxZ_bYQ{9|IY0rMsW5>Z8aYPnCcl`E90PqzKoPoG)X0z-| zs4o3nV?X|ovU$j`&aU6MSA;GYk@*dLBh>9?#HdV$Omgc{%r&Sh={C(gt!gH6XX1D* zP^NRj5(QtUNPuvfaN4w}0tUL!!TynDz;bIt>W}e;=TyE4lAV(SBmChI$h$y}yO@;f zxxQs8%~jfWR!qTuI6+wDzw>UVIDU;Z0#h!u@$PniNk%K*ylv0uhz$Fw0(k-Mt~6Py_Rm1XtIf$;|~}8@xyBK}xW2ytY}%Dd3V17hJ8B zT^v>C;xSz#f(QeLfCp`pfP;JZLT$pNUL?540Gnw-{z7O|69oRGl{cxS-GnceW}aW`dkkQM z4Jvy?O&m4d1)|zx_D>tFeD9E^zzuT1(XjaBHse3|{!YgcLUJ)#!liQU|7yXjgt80P z-J(;r2Ar`l4}KfiH%S)|ojc;m$)@Th&?-ehRgdSg+B;biJ7DnOJ*K!6%Hq5>mgp{{ zR*$dmj@lDTo&r?}LY`AOG9DVk*DU?m8rDy*-aYcRwZ)3;oh9m%gJa-1MBCfGCm|;4 zq~m1DdofqB4Uo>r)>EJpiA(fKLTE6g9yobD9FSAcLy@I(DZm_?w*zrZ5bjE+bh0zl z$Cr`lLt)}CKA*WuS^Cp1M$6R7gf#OB)J9QEPt6mV280FC-e*jcyfe+LC>fNs&23&?fdj3h7=>ROJI>1^`BuWV)8rQ5nQ8(6;Ug?kEVt zFxlO*KO^UfhKH!WDHu!g2A1hFZtd0VnGASKgVbz-g3g2hiFJ&0>q&=sKUCW5ODI2S zQxovj@LIp4raf9VIjZT`KK=~Y1lOL(%R^jVdqt-dUFXl|^F2k{^FiF9L8IFZyQVq=j$P$jHx!k{~a6c>DMBY+3yLPHS0sQl*C}Mbe!14EnjgK zs0!IlEUZInBVpsxyb?LB!h3;uZsL!b1K-P{)jv7_e1`GdP58JL5+TeOrI=83s7!nU zS(ty9?rwog{~jioZQF{gu+!eTeqIkz<=%Y6+?^Q34;)Mzcf#2RD8N!9 z(S%f3_rAv;Il$XOB~onGWRz~K+m=0|GcuJi+;Ti`}O^~eW56sHsrpGWLl6Uj&uADfl5+1^31k$O}KZA{;9^ifD zM+4h&s}8-q+Fw`95SZ071GTSzpB2E^m@vmrV_hoeF!ia>T>I!#A?aK7?*^w*b^J?b93F9;>oPz3?~>dw0^A1q-Oj!vQbh(rB` z?^3icq7cISLOMd;>j80#M$H+3a?fOC(b&6`afKbhp47xpFnHo$b?r6sGB~rExmII_^k^>?GeG3k;-w}e+no-TXs)$J|&Ue95R{ulfC7p|o$#${F)%zmM+ z*NvI3;n##JU0c?CX3Lr+J=TKCqCXaUmEHUU@}8whX8Ked9~7IRrsEE{@HvQh{mm?i zd^6%6fE6O!^8HA$P~*(V6eVV%0$ME&HfOoXb@ow&X?rvLk+&5s;D-xyq&B+<_3HE%Q>AQa>DU9s|}CLfjxh_e7;x?%R~k1h%yr2 zvoHWRCYJ&H7|9NETK`4z6Am*n%6cx(>iDitYl%g9{yC&Sd=WZ?w2Ye`-Y`L zaIo~qrSzU}+W=%Pf7<vO0L??hwC ziV`@QL30K2defCysg0q%(B&pa@v&NlAO^n)tcyau>yX6k@SBi*jip03ORUgZSE8rR z{GpB7E2!)B&EroEWd7Q~WJJz4=tQ_@?>8Z&f+eG4N}E#6PC zxs@_6K@yVqdQt4^-_5nd9cNTg+?^LFyg#Y=2$h51g;ce^i|`1gDI)$=UWJ?YGulL3 zIywOQjxGyy`7OqxCGK)7TrJ*FP4-I+;dkS>)Qv7RP|hIx6^C_LD8mk|525oR`^ZR0 zdz+y}oyNgyuGlnAH|bqi&R4>aZ47bVXD81{>9K9Fm)d6dBjCTx;|y z35SMA0F3V)AG#gDL=K&?5?@5CU6A}#IMs_GW77YCijKaa9e6a(QpCTFF6G?BJ*(~! zGyIv_1X@i31v9HGmx_^PmHcK;Muuopi;$wSr>eII`%u7dwMcFXh6+%WZ#D*ziw}oI3LQIt-(%ti(0WLzIM_SMC zpM{|_)k^LfsWhW^#%4i)W7?%AU%k|DoC)lk@f*~TE1#-4d6smmEZ7I2xPs@&fE637 zG4Lhf`v_pA;}}72jc;`P<&bM?7cICMCPZouHk6y>@T{>x#><%ovvI?YiTHemlTd_! zjXrELgAb$dLA{6QO0vq|>j>zh4sekOa9A5wn?2ViMWuaqYq|zheP9Q-xxys@I~@)| z_{ic$7pjdk|6e>%E<8Q?0hQKs{3wrcVkZ7#nN59GsZa6ULWJ7xlo7shf{9MMQQ%wR zBA?D1qk!{OlS1O!3-#t&Ji^gx``H7Isx9czz^mNZQ(7k-nnI$|X-)H)%+1b>oAdkx zXz-2UX9qiwAh#@>kZl|#pz(vwu(IJR#Yh&Tji?yLon1|O(t;SkmM3cdQ1$1xp%$hN76KyXI z#m$_5x2^{)Vf!xZm*p=K3S-e7=osSg*ozq`j&5>y;!i+IbShAj5k69xu@i01nZ`l< z^>j+iIQWFOduE+;ZVOc?O|4UbrcG>);yT>vAEmwDC(VA&+z}AY^BL$E=F`62J0g1_ zW6vqvC;C=l|GZCKgNGbKZ;L!Y8^R)`K_sJo2#BicsvcJ2#94@7T<;K3#lw&G)fBG5 zen_R>>rAG&0#vtR&nC-B(nml6#kH1 z>qubS)evc@PdZvb-L~HIF(sfBvvfdCymIK5JuyPF8Bx~CQMLzPx#-Gzj~x?a%c9lJ z>L%d_-qf0vo~6=3cxMTv2>h`mdBMzRiX`isYW#*Z#q)-*U%d5-b)9BJ7Je@8)N5B7 z@_n^j{I^%ff-3r6&Lu7>8r8Jc;lBdCv5dXxC-G1|`y#38AB`F=Q=I$M%>}r=-QcUl zS-@K|UdXl2F?_hzxhs%`L%HQ@7M=c6Rj-(7x>dYAu?xE+g69P=)edJ+xhP07=h& zv!k3{V0ifd#~;#9qkIczTgu-lC3Wz&L!COtNL_w?vnnXAl$?UJG*NfIICFusU)zzC_DrMU>hrQB5q2fY}LQ~L~`3#{|nh9GXUlwCt)h_QIwNG5{%isWvXNtz6-a}w;fVN~}RSAiL8 zh7b%0oCBX2M_3V(55VUANvsu8=Dj;x1)g`FN6_4$+@;oWMjU!U&eL&|vHlZlsVPaA zTkO4@MB_^bvko2-A%mgH#Ny_i6(8y7=hY#=?YoNg{njnsBsMqT0l|3B5#U?5iyukB z_c+S8XexK6U`Su?ptZ`0k?x84`3qtKCQ%OeBHD<(?uPkTHLzd2W z5b(3)47f{k=T5)v_yBy=qjzd3jI`+pkvnbSr>7zf%F57bYLfw)wPWA*R4USavqQn*R_8k3 z=kv?QMAfopbn;`5wa&^^oN7LVz3Z*y9`6fRlg0x~ElF>kCt*JcpkFxVrJkaIS$oee zoIj`O5rjSugBe*}W)7SKVq$DJhw@d`g6_G;wX39@ezZpX;d|$GNlU`n&#~Y;7=I2FV;^mR+x#I5hclDP z>AzW&G-h(*c;u@nEFVUjd~jsehebO zx={V77TqtJi@SlipA{yGkd};|s85GkX~-(#CsBtRCo5kQ=cBROs3QOyN`Ly+o_(f}9k#fY&6I%sZEp5ya+nX)8kl!Se3688_LDIJ*RpTsqGs9#L*e1xlwZS9x<# z1M7^?{WA5E3@Lz;I2@HWPnt!|dC8{Ue5!XOylw#BqAN{Ad4u7_JL{}rizLP3R?)w; z>T4GLjGS{bSO^0)bND$vA6bs*ymsKBeFoijJonA;`1H>qKkV%BCmMbP`D=`I$v6RN z?)9g<9ds|}!UMNScuTu^BN2S?Km>j3*3<5zT507XZp$vW1n9PWIbG^hO=#o9Fb zD+F_StwdsN3}=bpNvfU>b~6D1h}-<9%`MmZ>*RP9i1gCNnj)%$RlzaerPO8XhlTN#VPeqHC%>O%k-|5(rpRU<#@){y+=t)GO+%;VlfpM%` zs%9NF*fB{D_fgH>T$tlAkdJq2d-l{Z;X4h0AxcY=?qrxbp?%UkOuwz=Vtm%Cf>i*4 z=MZ1*vWeLomz}LcI!;JW@@+)v%udDBw-K={!^loO&GSvm$kboM$BM?X?t$LgV~VrL z!xsB(IT%k5VMwP~>X$MxS3%x}#TNcnFJ%a9B>^q{H|e#3RA-d)e=# zj>T?AqrymKi%V69`$h`o#=Rl+_V-ua4ub`j9HfPl?{$qAeI62;dFsi#k#syTi3h(> zI1xKC4*QNRS?7Cb1=0E^_NAqhY>aXzV_jMmE$78WKnC zrkSjK0b@O{qP=I)v=-~bpXJpy&JITItj<3@bGIMoYRzHkohM14k{UXos3%5mVUcN; zt_Q$!ce8Sjp%y~1wA|*^{_9)t--Y4g0l3gokS5W&g}l5E^-@#+0&HmRoIwg%D79-o z*0|bOkBwv9Te{Buh=|`s_7>Go&NNE+7rW33N{(TD8)M84w4*`50EGoXBn<6m)^(=J z$t!)nJO;-N4_5JT$P0Iw=glfb4n0m2%?c&ztj9u-J>5PcJQ1|G%KPE({Czu#- zzZP=g(cPryKh0vS31bKBKJ)ziUxeiS_g%hr;>tVA{jMM2|hiSr!R8t34 znl7O7f`{T2jCI*%?&_A7eC6bHS2FtbnQ9kDYWcrJ_)|GbKmqjI_8zdhNoqE}E z6mEVUF)te{s4*4~QN2sHTG1iJAe;6i>I?I3>*qwhjf(t_4;~X;^jKNC%1>|@M5Kgf zD6D`Bo2r1>0`UMMY^hB8#XN$+qiEl@nbZu3P>f-`&FB&bUN}}&0B#y)sN{NAh-SCY{L%9u9A<(qx>o@qNGd zWE$wN63xZ|hDH|fGIlr#g&uM#vQ;-%U!HCAm^ zdNnFN(e-~lg)1L!H9ev zTOATz1km^+_iC5fh%`f9clDdvI4VlI*r|6>7(cjVIUpTtIx%N+?X(!*AVofqqR;Ah zIiJi7TP>oivf*AbXuB9SqbJ*Vo&Tdge}k zDOr(sMF20nc2j?0&WW}kw1p@M)?5VL zMs_G^nitiw{x7-d86oXO;P7^ZlrBT@^2bWit9@cD=|}M}K)9Kfj&dy}v65ou)nVH; zrUHB?ubbjVhz0wUI$_M2+S572ke0$n*eA}v>IX$q7`N>!6vV#>>2lUp;|@6VBdM$b z&XEAk*a|~%NCDSoAmbzBqwjXVYl$Zuqi2+)M$XXb^1L8jtE8noT*)8W=hjHy@Z}r6 zJRDdH`Jb7eDKXJq0r+k)zV9E@{LV}@rkCgOMhFwc+Qm(lY@!tc^$0jCz$d+jP>#7` zd!-KJuQ!ug9uFu4j?@vaDl)6`#Eu09vAvgv)hG!K=vG1!wUs2^1?Ny8u_E~rs&=wkYZQSf5HiX74Oafc%8poQUKQ> zNY1TU55kWzC6{+uI?R0PT-pJlMwxG#RTBlw&ZVZ?EjLNT>ND?z@vXjlEJBvKRH+Nl zRw$WZG#P8fXmU0J7=UGUK8Z)t?f#2D<1WPa2EW93t6Mn@hq)|wFcUSLZGn|-Wl1{t zy37W{kx_(wN{H|XsuEQ7o-)nBFSFWdp||t>jyrkNFj2h@1J4o;Fvy{ql-2!Dsw^R2 zz}4Asf_-S$?xD{%nnZk++mqg1Vhp~_$Jc_8LE)ag^GJY@`v1(#qMX34NrohfdgA%2 zyut{K`NvkMq%xQ_X6_Fpd56&9e$WcN6PUQ(uIFatMi6Kj!O}|{Z#}7Q{PNG)M+6#h zkQy@)#+#}MyBC5$RD5$unc8gdm4WGMZ)`}pW>%%dBxhcgS-3ABEW@IOiV=)fi`%A6 z8LFR~ADJ!IdTo-9ler3<&2SRxx!Md)lc3?Cy;VY4T|UZWj4jw5_L8vEj_`7BRJFxU zwcAG_*Up5+zeMJK7P+gB--o>Jw_l%W;QjT~w5-Kmxr_kZI@)5u0vU7@MPPjR4wjK2 z!id`%i}DDu3bHqB-tNtRMEtpsNjZgo52v5~X(yJ0_m?9G5lVLeRH`EAD`HJWka+w2A^X7)=~8?UIqjux zXX&(7@bmWrT!*O^l_CT?+0yV;Rg!iA0*3{p%j4RQFR)cR6i(WUtAO*7*%ab6x;aCdzYT}4nQxsX7NJmK)i{77|gM!tni(W~#} z==$8Bd5Hx?z$T;mPP%Ai;I9xs19FiluFohOX69jP2~jG#p?O1$eTl_v=59qezIM}T zduS3p${W5<*F!(e-QPa&Xlb|8?`cQcVHPwQZwrP2V3e`a$~Q<+R1%Z)Nm>K$^SJdG z%+8KLtt{MHL+C2LK6#Pk`w&uJLB0cxONkSy%Eq){-N8p_3>vEnu%||wcly?$pJ```Vb5stqdvc-K9w+t!I3(cSm=j62$pB>bx5wewBGK5 zm`9}U7i)CU)6njC4C1k?IV@FOburZz$>%t^T~D%i*uRr=IZ`dr!<`$X03rByC!b!B z_v(%LH3T>yb}cLC0#g;@W2SK+i8G?!AZ!=%t=Aj=knQ)Jf|lYIx!!Qyr4gxFVV?ssUhP| z(pNNqaSKs)g5+Qe>iAG^b1RhdqyF;dwNDuK>dp%FI6)aVDvod?7)Lp5rb%j)r#|-_ zy8NTm71G>P^J)ONrct=h=n^_YGCOAc1&%+5v^}M65!tM4s=J9R zwmh!~oP#yxJ){?hiSHiq(TE#4t_2$V*fS~#T`g9tOe*>w?gt2DWY62X?$_w}U;W z;PRSN9|LYQb4i!*&KfT(-g2DFwaABG4{|G1%xNOBInUMcP6ZbO^{16E=6il)ztb+5 z^YEia+84G1$%=bbdXRYF?>hOd!uLKQg%`^2Z8m&Kr!SgyHr5O5XX;wo^<33`!XBB7 zOff$Dgizx&aUAdJ8NmwxM~q$1;4Ul%;X&-i9G>yRfDM;Y>BK}Js&|^2=FT*swh-MQ z`#{bN&B|N!}u;el3im4M%ZWA%je)q6VUd33l}Ka-PWQ zkMO3R(?}JLq#ryIURt))KDsWm92+7H)4Pyt9`Vc(#R^_NInz@$e)BEvR@^Q6J<4%J6F93U;-g(yskOrVz^O-t1|i6)1YNk5(p`TQ zb8P1XHu8KH@Hk z-;a9b67-7|*wWPK#Lm$0(oRY7kL?k75=kev0~B2iR{rqIe8v3q*}XPBO6qc3Xg$s% z?W4g7a;lqM8bys&-+V%?#NmL!nMn?s?A_DaOruE!MsBY#Kb#0xlp%%l*6i zEj%Q|m;*Q@c;pWEL^6@6;Wosu{CTHOElCz-Gm}-txB_!v+HaG&?AZki%sA>D{a&edLGFR&hvC zyIrTj<=^0rPTh|Z_fHg!^N^-|9wDOTXP{9(8m6<44=lPt>-RzP&-lj2QIv#EqW zP<{7^h!RGZH0%(;sTKdSYOfQ$mp=XS`_AW%ELass;pK-+OAG1ZEbXiR!k?WQs8$x+ zchf|`WU3K;()iV$7&_F3nznzLeG_9LJpLQe=Xh^lMLn32jn|=c};Spvm(ZOYHqw*li zT7s+y-$e|8mwU z|9`M=ALY5r#K&uw01(^Z!{I`L@pmSTNA3 zi0O#MqRv^|LU4Wdh!HY9=yIkK9HILsi(gi%Zl!F^2Jhbr#tM%Ccqq&e63)c*Qc!_-gLUKLSLR_=S|PEq z-p^w|_4 z0;2>wBc|FR=cRJ;&H+?8^h#4M;3PWW6sVKiu+VVH`o{vb)DI+ZX>Q=F#MaH3z%pH ze;K7&Nw>ZdYaU{7IknCqC|QLF&PaDEM3h)EB)rLO`5)mgEw`7s-@B4!Vds%CgRk1y zA@Z{exLfk$qhiVJ-F%4hB=%0-LsvS-nSSD+wmr2Bb;71ep*{3(XKt5_r?%M3<{siZ zMr4T#JCLGsTVw}q-n;@+$kN-`ix+A&NNy37hGu`o4st%76SEL~9Gn-1rRB5kbk9Po z8IJi((o2T!31Y_I!}j{tu&)X6+jA~ki0YN7L~$<97qKs_Oa#LJy~I3OQ#UCFheo8A zi*pp|i|9*Ur*qknx;pL`vf#=A`%$?qi6{f&{djxQ~a_c$mwlng;QD^+s& zWO-$vKg(HyKot6JpARufmakmg)&DIYxs}BMAk{CzvgC~(qGT}@7J1d}w zaoUYftY6~Su@MZc?c0`=lwezVIaV=wkw8*Cpx>-iaHiN`En7j$hSH9d?<=m^W)Qz} zV1B0R^Skf`@iix@NR%Yu>J6(MNsyYHppYA_fX$gju#O}jpIWD3!$ks?>$=qu%nk?{ z@a8#W5muX`;VA>dT3-xqcz;XEdMFHynvtz3gob|~mu+J%eq=OT`D@u!DZBu$7yr~0 z-W`o9cTbmCKeB{Y%WK|)+A_yM8aR2k;wf4%LJ(k~E%bZnwmvd2C=pHUhesTVlaToO zB7g4~UXPsMaA^ypSWnFsw3xs_7Gu~nzY@k)fkviw28uTX9NT~@s`mM5V=GQJ=O^U4 zk|sWLx0Zi2@bw(|%*01?d0KO~&*ziiQAQs6+xz!#tJDW)>x)YrRM4|95{9%PSp6Y& zv~fP_bf=)kMzE0`Ir!-fQxLKCvxsggwh_!^GN6 zpd`&>?Sg4f6-(uW43Om(d$pzfi>BFY#7d|C8h3A2tJ6Tsm}cZ)uiQ+wU; zu=K+YMU+hH4w^;CG_vDq|BMqW7_)r9%CrXr0Aijx*(f0q$uQ`)Xx~Qwc8_?qL0JMl z=uZr{j`*^z(k6~t^1?2OP2AfR(92W`5E(vnYWCyG^!%RMP znZX`mW~4rM2^e&vlw4)iLg)%bAJz#Vv1b()&-9M9wfuLe$A|2?A5I(;3gxGJUsW4< z0_|!y6MdQF!qV;;r@Gsz>IL~6EWMOUKapwKmaTQjLzPW8RtN0;9j4u4Apca&uLflh zA8L0@JI#6$-(G^%bDolKq~l|>WAiWm%#J<;LejQ21VaA{Bh54on$iNJ0hI31X4&G7Z(>93e!0`J@p}pg zwl`WO5D%&Z1pm)7bHa2Q5LjM~y~*K5mc5$$`l`f^gNhHjcWc1~>Btqq zuQH`q<5ySLlM$>x5N8MZ_tn|;N(GIh`2qW#r9EF2-`pq9R$+LpBL_CaxHGcjFm4zg z8a{9-9DJ#*yLG$FCf~ILz(!K`A}R%K-b81Sw>@-UeL0FEt9$i<%q z=ttJ5%glb$AfUGom3g%5BrC&!WVanC7wxRB$nUey+Csl(xB-~A&MO`$-_ zVG%5c@GAtC*{HZ!rKVC^i<}WI7EMf^BBTe&^`CfWL8)a2b zRHuuPyy#TUfOaL`>!YPc_7aD-A2KS?6|7OdgXpjL!PASZ9GCM~u0J;K8qDwo-m;cq zv#Kw41w7W)Y%UYT+*#*A=xtrmR--p1I4)3cB;|&S@XOt(nYK zW1}QMThof5+(DY-;gA520?bpkOK2j;((>6(cdVA%Y~!5Eaeveu43>SI;F&Iw$7HHS z3qLxkkixTfA##V=q1D!WHu0|hJ)-qlvb%}^ML@d0I&9X89v$>=8<`m&>j3ZV-f}EH z!112Um{>rN%Z&wncbUg8ZZ!5*jD7x}z5@_;_d*)4jvB&s@6@au-i$A8^?F%WZYfBS z>-+eR=B3=mR3(^{w68$XAw7AbEwcF{VzBlxC5Q^8W^g^U{3;oyGd>6IKxnedlCo@cgL@hL%7c6~(6-|dVoU&uk>bD6iajSAr zRx-%a#SQfgWSC>Ar_fdM^GJaR=?3)R2B`(Dfx@Y(LC+#f@F2nG7}@U@2&C;8314W) z0(O%Lb;yiVT@`gGG_2SRZ0!6YsbusSK*C%SUWd*%fi7e^&78Kvc9MVN4I;lpw|Pby za_GCYj@23%F?`KA(DHQnj2%Q2ntjrpOPVkpe6qD2O1cbrqliggUk*>=(h0syFYO-g z;dvCC*&ix~EI{VPb;f(vX<|`-BnZKDOj1w#_`waB)<3ON7kerg`V80e*446o2+z1( zgD)Ldd|#RJAQ-04%5A}x(;UIwNY z3St4t_vJK9;n~mNqeQMXsD{`tC<|=^Rep>*x=&2mbkg~0c?@Ur#CSU%{#MjCi_Wrk zD`Idv_rEl*z;t2HRkel(lAsrM?s~Ox+8G>9voge>jksdoJxUQ-;VA|*qW#4@F*u97 zGn3{I{F{#Bi>rSOWwM`XFFkF&NLM+9CSg%H21#!r(okK{W%a;~1^%AMLrfRY*5i8UAV3fr~X7ezuE+FpsZCtX> z9B6c=^5RswWU1iB>a$XaAo8geXM<`3b?bpG>=w1sFHtBWE2S)~Kec~w>tEf1YJKsC_iaqYB zs~)Md^(RxpA4#nE$Efza(t4XB z5P;MrJxA5qb6P+KB6%g_u?ylzynDdsPHLr*XGm8GIf7+}-eDTdou4k2Z_n_W z%uLdlWx;JKDoP}}nJi)6hg`A*Brb1EqZGcX|yRZdHITi@Y%32x)Q6}8& zQiye%XBztHt9Z+@xx$^bIc#U}z<&O4C&w6pe`20gf(R07&EuD2`jW2FKlaDm>xAYO z=m9>di3XKeBv*DX6~Fe>zK<~K!Y%IvN;dnPXI*2_XZBt0mUdVtXTfp@F3P^YRmHAv zVr zCqq|X(9H*bYrxu^LNFxTkZkkV5;+RKe+^k2780=5w~S^);Bf$$E})8}dH`$caZT%< z^Ic(xJ#dN+%sY>og#(0zbtB219Q1cUnfUOiHm`ad==RxbM)ETk?6j&D002)=+Z^LQ z6Pn$|>zw!kN@6;zOCo=}YBU}-CCppsQ6mpwD||;NacDL-WKHJsXLNRm5zqCmte&FA z5WZlF>@8}@ich!rSFicC2gW;1vyp6<-#~=+V$)bUzO#bOp-7Z%3^N_+*K@nMciyo{ zFGiV@rqXXL;w>^O4L4Bac7yn3Ts&{cXp>#c4*w8Xj-vn`Gr`Ry0YI1Hz46e3 zbGkMu2*5$B@U%}-of|o>TRc&d?nO}&My^`*zcCkhhSGD(H=spJXuP11XUy!r--s&; zyY9Xak{~WdIj9KLr~8hloL~!(5s`@0sCkJ?QK(r5Ju1H>E66Uvm+p6{UGI>#slXL) z?qv$PN-dLEpx93#dc`_~#Ix^~I7&ZEl?@cq6b>pnk%LjtXRQux(@_P9n{MV#W#VZU zyTfcoWmb9U@9szU3Iy|0M~K)9dx9w&t}o&Y=z2jPz8X9rQP=T0jit%;&;gbD6q-h; zr=f3;l!}B?F!eyXVX^oDx+$PxfIE(|;L&({-mYAgd=2;7y}SoS@Ud^YeW|=k;<3g% z>Y^#_r~MzAF&RD{@tgXja57432%9Z5ihKzuX%OI=J(S3&PO=EHKo$B23<(Ftmm6 zt2bMt0*)F&OeMD=g5~V#78^!Y&vKN%Gt>(rxI|3(0K!X zrpH&z=p-Sk(I4=%}m~gL!l>3jN;2YTvu>>BF|=i&TXpd!YIb> zGmS~A|wxrJ9 zLCEh{Z-xTxO*DBN)ml!jNc74O&P|E?ToH5TpWKY;XsC4t;BC|ae;CKiP4NgTpkOF* zI0hl}y*m&zW<9Po?3?@Ve5^B;>Q$Q=#W@RAY2NFA6s4|`Y$}d|hCtq{7D=T9I4J`{ z3U&m#w)Z3>Uli$JGTdfqy}e_3>dUUrPjC~&hUT@3n5076ZA`KIz*?LKq;BEMn9N9z zMOvVJ=@>GP@7yrB!)q%7F_iCH)3JBR=+31uDI7tAub+dta2A$vbN?#v`MTXaajZuH z0w_PqY()19Q(`T!iwADUKL;mJ8A2IqF1+Vjf97}>-nSAa@gy}y5;mSoC>LX(BbILi ziP0s?R0SH8)D#Nt0k7`sIDVBYiR1!iBGcdGmY%sDx$ESBfXPEs+VTZV-U+f};#ug2 zDA?yvQqTIBTt!Dm`v0A-ph1sS*uW(C)hhB1ft)*)1Xq(coRjgM%OX}=wouBnIRb7n z?Gx{CWjCLqw-cn>rto7wo9ToE_crF3)OSxd@#M%`BDE4iFGR}E6T|3l4+nI zla$36K#3QQ8Aw)oioF9v6$Qe*l3#Xkbok=naZ(FfA-<>7#kp397V~1dhW$oqQJat*4_L*qUM`gFe#c}nmA#r`KFw7e$YeYw4S(8u{5OlER$10e zpm-;4shtW|J9FzP<Jt0q<#U3x3Jbpi=q+2z7Hc!5wXN^ML@E2~$PXuZX0j zURSx66bCEz_Z=2;O485bPZc8k@7`OA;h3&_*M+iHqoxW&g2>bmqE|IYmQO^d|NTsE zIhKZ8Pqmm?z8j)5>z$0xW_T>fzuR{67Igbo`p5&TA^1UUuS>n+VtJbU?`D?Ge)|dUV4%kFpM4 zMb?0-53Mfb$zFf5WLU1Z30*oU7|@GL|8bq-sgBekjZD2FxM)dNts-ac{Bbz73h_gNjBPrEI#Dl{V5IoP5CXF(Qruw7!pi~j>zh8du1F}K z@ys42Z3jl6(EK=z3S&8baC^D&ek0n#x;fq(ipMs+BnJF4VI6392&cq`sk(QF(p6Kt z&f0h56_YWm3A{cedZoa-iD3~hHH z<*hCc*FZTGDXvxAvoyN!JCTt*it;;E`Iz|#{sXI&c=3v<3v8#wEV0oIWk;w#E0L@d z#2|Ne689n}L6mJ3W8h znHDkv#~hN~7Uja^rlB}Wn^j7P+IMqob?5<8)-2eToXa~LfpS)wlwJz7E$BD#Gn?k- zoTp&EOo!AWw(B;b_ZC%b(6mL!Hpg`=Mg;lB9 z>Oj7)C1khtkmTxF8;jqMtHqec0Zv@jL!9;D@0%P`?E+l#=VgdsLcMxc`J{+y!6V7# z@!$!RY`9U1GFo-){~wN}^H_%h0s9l9!@f{(u?eKZ!Y+S%2*=+E&NS1`Ezqa!o%V)Q zvQSb)jScJY!P!ibAMK`ZqW1X)7}ZA~4bY=RHTOWd3Hz$#xK}9e$y6p2hqp&HqRlt_ z5buK&VIM}Jc(Clb60EvVqo;=?k><~;~}n3Rb( zi{A>UzQe5Lv?L<(_RxOZASU+lO)sn`Ygl(Xn|Z-{1J2-C#>-0@P#z;0tm{YVKW-6` zX@C1f&ZOqG5FfwCrqpZ=bOZM)*Ew5cG%PMj6D!axNz`x7Y9 z_|0NpQPiYiM2qH(*#CX!d}hmhC>U(4Eg=a7q#~ZUeO4FFD9LmIwq^w3|KUfFTfqbi z`?BVzA(X}1-WNiAM!qrQ{N1zAId|DJvh&Wn)ln;|sNM+&4uEc!ks;qeLR>lI2*a;R zW&Y^{p6k{Y37|L~x0_o|Kf#R#_A%XCmH@!^?dT0=3c$+0976c$5 zh|x;m1KM_#pzQSc;doSN%JgEsY9)gIB048>wvmOBl0yPy?#HFW%JrM4E+Y9t&pCju zGfaa$V4+c33Nk6@Zo3hQ%+tLN@v{^-W5Y0Q=V?(XAXa(ByGm{A_2l&jD(3~Om%Ad& ztW6#s0OZodG*3RZ=)7XMls`ZA5Bb8`jZ3;E7K_3cA4)Uyhb`}iPK6J48B|R^_&X=DD#i&IWi#y9BH7P z$&E3U9X6PT_ccw*X5(X1&G17 z#n9kzI34tP4B^ z9Y$#NE&A@~UwZMlr*_Kk9%wbql1HXf5vR^VKufk+p^o9FW$K7pL+=)Wy1>d`MU!Sg;6GfnR%WIzE=x zEO*KW02aQu#JvoA@R&GF9RE`30u)94jP?Zja3uNEd7b& zPax=QZcBBzrCSS>Sv749vvux}T9_dYkn%R)Z%NUl&8P}3)xE7`ip`^w)2e5=hci9Z ztm+w09aYgoTqaBzsMfg)HWmXvYJc@pBH#l^D3%di6mawj-5PvYNZ8IJII2D1Znr&0 z-Q*qt)orJsI@U#;y|V*X{Fb4Q|7JFxtA#_t`9dhN!!fw^f*($~k^NwzvyZ^yUiuM@s*O3Li}cK4pvhTQG*D#9%V z?AzghpQeMvlok}4v}Q`e+?5I9hO=9tp$;DOTN%SqFr>_mGA`+PVM%GFzt=Dfhd6KL z*_qnUeeOKrjfGG_ib-rAg3mit_=w0{Td4+T^dl)rc&(BDjGRePlhz8)Kv!ttVOl