From 5d9e79afaffc4c210ac86880701e337ad61b1500 Mon Sep 17 00:00:00 2001 From: EmanuelFeru Date: Sun, 1 Mar 2020 09:43:14 +0100 Subject: [PATCH] UART with mainboard works - the sideboard can now send and receive Serial data from the mainboard - fixed Processing sketch --- .gitignore | 2 +- Inc/config.h | 4 +- Inc/defines.h | 1 + MDK-ARM/sideboard-hack.uvoptx | 4 +- README.md | 4 +- Src/main.c | 90 +++++++++---------- Src/mpu6050.c | 32 +++---- Src/util.c | 2 +- build/VARIANT_DEBUG/firmware.bin | Bin 39068 -> 39492 bytes build/VARIANT_DEBUG/firmware.elf | Bin 376888 -> 378004 bytes build/VARIANT_HOVERBOARD/firmware.bin | Bin 35036 -> 35500 bytes build/VARIANT_HOVERBOARD/firmware.elf | Bin 371208 -> 372548 bytes docs/sketch_processing/sketch_processing.pde | 63 +++++++------ 13 files changed, 105 insertions(+), 97 deletions(-) diff --git a/.gitignore b/.gitignore index 03fcc03..b9527af 100644 --- a/.gitignore +++ b/.gitignore @@ -2,7 +2,7 @@ .pioenvs/ .vscode/ MDK-ARM/DebugConfig/ -MDK-ARM/Listing/ +MDK-ARM/Listings/ MDK-ARM/Objects/ MDK-ARM/RTE/ MDK-ARM/*.uvguix.* diff --git a/Inc/config.h b/Inc/config.h index b6dd519..c3581cc 100644 --- a/Inc/config.h +++ b/Inc/config.h @@ -72,8 +72,8 @@ #ifdef BYPASS_CUBEMX_DEFINES #define USART_MAIN_BAUD 38400 // [bit/s] MAIN Serial Tx/Rx baud rate #endif -#define SERIAL_START_FRAME 0xAAAA // [-] Start frame definition for reliable serial communication -#define SERIAL_TIMEOUT 300 // [-] Numer of wrong received data for Serial timeout detection +#define SERIAL_START_FRAME 0xABCD // [-] Start frame definition for reliable serial communication +#define SERIAL_TIMEOUT 500 // [-] Numer of wrong received data for Serial timeout detection /* ==================================== VALIDATE SETTINGS ==================================== */ diff --git a/Inc/defines.h b/Inc/defines.h index 127401f..4a1b9bc 100644 --- a/Inc/defines.h +++ b/Inc/defines.h @@ -90,6 +90,7 @@ /* =========================== Defines MPU-6050 =========================== */ #define log_i printf // redirect the log_i debug function to printf #define RAD2DEG 57.295779513082323 // RAD2DEG = 180/pi. Example: angle[deg] = angle[rad] * RAD2DEG +#define q30 1073741824 // 1073741824 = 2^30 #define ACCEL_ON (0x01) #define GYRO_ON (0x02) #define COMPASS_ON (0x04) diff --git a/MDK-ARM/sideboard-hack.uvoptx b/MDK-ARM/sideboard-hack.uvoptx index 3d397e3..da4809b 100644 --- a/MDK-ARM/sideboard-hack.uvoptx +++ b/MDK-ARM/sideboard-hack.uvoptx @@ -75,7 +75,7 @@ 1 0 - 1 + 0 18 @@ -233,7 +233,7 @@ 1 0 - 0 + 1 18 diff --git a/README.md b/README.md index 2dc4a95..0d0cc4f 100644 --- a/README.md +++ b/README.md @@ -74,14 +74,14 @@ make flash This firmware offers currently these variants (selectable in [platformio.ini](/platformio.ini) or [config.h](/Inc/config.h)): - **VARIANT_DEBUG**: In this variant the user can interact with sideboard by sending commands via a Serial Monitor to observe and check the capabilities of the sideboard. -- **VARIANT_HOVERBOARD**: In this variant the sideboard is communicating with the mainboard of a hoverboard using the [FOC firmware repository](https://github.com/EmanuelFeru/hoverboard-firmware-hack-FOC). This Variant is not yet fully tested! +- **VARIANT_HOVERBOARD**: In this variant the sideboard is communicating with the mainboard of a hoverboard using the [FOC firmware repository](https://github.com/EmanuelFeru/hoverboard-firmware-hack-FOC). Of course the firmware can be further customized for other needs or projects. --- ## 3D Visualization Demo -By [converting Quaternions to Euler angles](https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles), we can make a [3D visualization example](/docs/sketch_processing/sketch_processing.pde) in [Processing](https://processing.org/) as shown below. For this Demo VARIANT_HOVERBOARD was used. +By [converting Quaternions to Euler angles](https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles), we can make a [3D visualization example](/docs/sketch_processing/sketch_processing.pde) in [Processing](https://processing.org/) as shown below. For this Demo VARIANT_DEBUG was used. ![sketch_pic](/docs/pictures/sketch_processing_pic.png) diff --git a/Src/main.c b/Src/main.c index fe83cd2..d392519 100644 --- a/Src/main.c +++ b/Src/main.c @@ -100,8 +100,6 @@ typedef struct{ uint16_t start; int16_t cmd1; int16_t cmd2; - int16_t speedR; - int16_t speedL; int16_t speedR_meas; int16_t speedL_meas; int16_t batVoltage; @@ -117,10 +115,10 @@ static uint8_t timeoutFlagSerial = 0; // Timeout Flag for Rx Serial comman #endif extern MPU_Data mpu; // holds the MPU-6050 data -ErrorStatus mpuStatus = SUCCESS; // holds the MPU-6050 status: SUCCESS or ERROR +ErrorStatus mpuStatus; // holds the MPU-6050 status: SUCCESS or ERROR -FlagStatus sensor1, sensor2; // holds the sensor1 and sensor 2 values -FlagStatus sensor1_read, sensor2_read; // holds the instantaneous Read for sensor1 and sensor 2 +GPIO_PinState sensor1, sensor2; // holds the sensor1 and sensor 2 values +GPIO_PinState sensor1_read, sensor2_read; // holds the instantaneous Read for sensor1 and sensor 2 static uint32_t main_loop_counter; // main loop counter to perform task squeduling inside main() /* USER CODE END 0 */ @@ -164,7 +162,7 @@ int main(void) #endif #ifdef SERIAL_CONTROL __HAL_UART_FLUSH_DRREGISTER(&huart2); - HAL_UART_Transmit_DMA(&huart2, (uint8_t *)&Sideboard, sizeof(Sideboard)); + HAL_UART_Transmit_DMA(&huart2, (uint8_t *)&Sideboard, sizeof(Sideboard)); #endif #ifdef SERIAL_FEEDBACK __HAL_UART_FLUSH_DRREGISTER(&huart2); @@ -177,6 +175,7 @@ int main(void) HAL_GPIO_WritePin(LED2_GPIO_Port, LED2_Pin, GPIO_PIN_SET); // Turn on RED LED } else { + mpuStatus = SUCCESS; HAL_GPIO_WritePin(LED2_GPIO_Port, LED2_Pin, GPIO_PIN_SET); // Turn on GREEN LED } mpu_handle_input('h'); // Print the User Help commands to serial @@ -216,6 +215,8 @@ int main(void) // Get MPU data. Because the MPU-6050 interrupt pin is not wired we have to check DMP data by pooling periodically if (SUCCESS == mpuStatus) { mpu_get_data(); + } else if (ERROR == mpuStatus && main_loop_counter % 100 == 0) { + HAL_GPIO_TogglePin(LED1_GPIO_Port, LED1_Pin); // Toggle the Red LED every 100 ms } // Print MPU data to Console if (main_loop_counter % 50 == 0) { @@ -228,80 +229,77 @@ int main(void) sensor2_read = HAL_GPIO_ReadPin(SENSOR2_GPIO_Port, SENSOR2_Pin); // SENSOR1 - if (sensor1 == RESET && sensor1_read == SET) { - sensor1 = SET; + if (sensor1 == GPIO_PIN_RESET && sensor1_read == GPIO_PIN_SET) { + sensor1 = GPIO_PIN_SET; // Sensor ACTIVE: Do something here (one time task on activation) HAL_GPIO_WritePin(LED4_GPIO_Port, LED4_Pin, GPIO_PIN_SET); consoleLog("-- SENSOR 1 Active --\n"); - } else if(sensor1 == SET && sensor1_read == RESET) { - sensor1 = RESET; + } else if(sensor1 == GPIO_PIN_SET && sensor1_read == GPIO_PIN_RESET) { + sensor1 = GPIO_PIN_RESET; HAL_GPIO_WritePin(LED4_GPIO_Port, LED4_Pin, GPIO_PIN_RESET); } // SENSOR2 - if (sensor2 == RESET && sensor2_read == SET) { - sensor2 = SET; + if (sensor2 == GPIO_PIN_RESET && sensor2_read == GPIO_PIN_SET) { + sensor2 = GPIO_PIN_SET; // Sensor ACTIVE: Do something here (one time task on activation) HAL_GPIO_WritePin(LED5_GPIO_Port, LED5_Pin, GPIO_PIN_SET); consoleLog("-- SENSOR 2 Active --\n"); - } else if (sensor2 == SET && sensor2_read == RESET) { - sensor2 = RESET; + } else if (sensor2 == GPIO_PIN_SET && sensor2_read == GPIO_PIN_RESET) { + sensor2 = GPIO_PIN_RESET; HAL_GPIO_WritePin(LED5_GPIO_Port, LED5_Pin, GPIO_PIN_RESET); } - if (sensor1 == SET) { + if (sensor1 == GPIO_PIN_SET) { // Sensor ACTIVE: Do something here (continuous task) } - if (sensor2 == SET) { + if (sensor2 == GPIO_PIN_SET) { // Sensor ACTIVE: Do something here (continuous task) } // ==================================== SERIAL Tx/Rx Handling ==================================== #ifdef SERIAL_CONTROL - if (main_loop_counter % 50 == 0) { // Transmit Tx data periodically using DMA + if (main_loop_counter % 5 == 0) { // Transmit Tx data periodically using DMA Sideboard.start = (uint16_t)SERIAL_START_FRAME; Sideboard.roll = (int16_t)mpu.euler.roll; Sideboard.pitch = (int16_t)mpu.euler.pitch; Sideboard.yaw = (int16_t)mpu.euler.yaw; - Sideboard.sensors = (uint16_t)(sensor1 | (sensor2 << 1)); + Sideboard.sensors = (uint16_t)(sensor1 | (sensor2 << 1) | (mpuStatus << 2)); Sideboard.checksum = (uint16_t)(Sideboard.start ^ Sideboard.roll ^ Sideboard.pitch ^ Sideboard.yaw ^ Sideboard.sensors); - HAL_UART_Transmit_DMA (&huart2, (uint8_t *)&Sideboard, sizeof(Sideboard)); + HAL_UART_Transmit_DMA(&huart2, (uint8_t *)&Sideboard, sizeof(Sideboard)); } #endif #ifdef SERIAL_FEEDBACK - uint16_t checksum; - checksum = (uint16_t)(NewFeedback.start ^ NewFeedback.cmd1 ^ NewFeedback.cmd2 ^ NewFeedback.speedR ^ NewFeedback.speedL - ^ NewFeedback.speedR_meas ^ NewFeedback.speedL_meas ^ NewFeedback.batVoltage ^ NewFeedback.boardTemp ^ NewFeedback.cmdLed); - if (NewFeedback.start == SERIAL_START_FRAME && NewFeedback.checksum == checksum) { - if (timeoutFlagSerial) { // Check for previous timeout flag - if (timeoutCntSerial-- <= 0) // Timeout de-qualification - timeoutFlagSerial = 0; // Timeout flag cleared + uint16_t checksum; + checksum = (uint16_t)(NewFeedback.start ^ NewFeedback.cmd1 ^ NewFeedback.cmd2 ^ NewFeedback.speedR_meas ^ NewFeedback.speedL_meas + ^ NewFeedback.batVoltage ^ NewFeedback.boardTemp ^ NewFeedback.cmdLed); + if (NewFeedback.start == SERIAL_START_FRAME && NewFeedback.checksum == checksum) { + if (timeoutFlagSerial) { // Check for previous timeout flag + if (timeoutCntSerial-- <= 0) // Timeout de-qualification + timeoutFlagSerial = 0; // Timeout flag cleared } else { - memcpy(&Feedback, &NewFeedback, sizeof(SerialFeedback)); // Copy the new data - NewFeedback.start = 0xFFFF; // Change the Start Frame for timeout detection in the next cycle - timeoutCntSerial = 0; // Reset the timeout counter + memcpy(&Feedback, &NewFeedback, sizeof(Feedback)); // Copy the new data + NewFeedback.start = 0xFFFF; // Change the Start Frame for timeout detection in the next cycle + timeoutCntSerial = 0; // Reset the timeout counter } - } else { - if (timeoutCntSerial++ >= SERIAL_TIMEOUT) { // Timeout qualification - timeoutFlagSerial = 1; // Timeout detected - timeoutCntSerial = SERIAL_TIMEOUT; // Limit timout counter value - } - // Check periodically the received Start Frame. If it is NOT OK, most probably we are out-of-sync. Try to re-sync by reseting the DMA - if (main_loop_counter % 50 == 0 && NewFeedback.start != SERIAL_START_FRAME && NewFeedback.start != 0xFFFF) { - HAL_UART_DMAStop(&huart2); - HAL_UART_Receive_DMA(&huart2, (uint8_t *)&NewFeedback, sizeof(NewFeedback)); - NewFeedback.start = 0xFFFF; // Change the Start Frame to avoid entering again here if no data is received - } - } - - if (timeoutFlagSerial) { // In case of timeout bring the system to a Safe State and indicate error if desired - HAL_GPIO_WritePin(LED1_GPIO_Port, LED1_Pin, GPIO_PIN_SET); // Turn on Red LED } else { - HAL_GPIO_WritePin(LED1_GPIO_Port, LED1_Pin, GPIO_PIN_RESET); // Follow the Normal behavior - } + if (timeoutCntSerial++ >= SERIAL_TIMEOUT) { // Timeout qualification + timeoutFlagSerial = 1; // Timeout detected + timeoutCntSerial = SERIAL_TIMEOUT; // Limit timout counter value + } + // Most probably we are out-of-sync. Try to re-sync by reseting the DMA + if (main_loop_counter % 150 == 0) { + HAL_UART_DMAStop(&huart2); + HAL_UART_Receive_DMA(&huart2, (uint8_t *)&NewFeedback, sizeof(NewFeedback)); + } + } + + if (timeoutFlagSerial && main_loop_counter % 100 == 0) { // In case of timeout bring the system to a Safe State and indicate error if desired + HAL_GPIO_TogglePin(LED3_GPIO_Port, LED3_Pin); // Toggle the Yellow LED every 100 ms + } #endif main_loop_counter++; diff --git a/Src/mpu6050.c b/Src/mpu6050.c index 255fc5c..683c0a5 100644 --- a/Src/mpu6050.c +++ b/Src/mpu6050.c @@ -3230,19 +3230,19 @@ void mpu_start_self_test(void) #elif defined (MPU6050) || defined (MPU9150) result = mpu_run_self_test(gyro, accel); #endif + #ifdef SERIAL_DEBUG + log_i("accel: %ld %ld %ld\n", + accel[0], + accel[1], + accel[2]); + log_i("gyro: %ld %ld %ld\n", + gyro[0], + gyro[1], + gyro[2]); + #endif if (result == 0x7) { - #ifdef SERIAL_DEBUG - consoleLog("Passed!\n"); - log_i("accel: %ld %ld %ld\n", - accel[0], - accel[1], - accel[2]); - log_i("gyro: %ld %ld %ld\n", - gyro[0], - gyro[1], - gyro[2]); - /* Test passed. We can trust the gyro data here, so now we need to update calibrated data*/ - #endif + consoleLog("Passed!\n"); + /* Test passed. We can trust the gyro data here, so now we need to update calibrated data*/ #ifdef USE_CAL_HW_REGISTERS /* @@ -3639,10 +3639,10 @@ void mpu_calc_euler_angles(void) { float yaw, pitch, roll; // Convert quaternions[q30] to quaternion[float] - w = (float)mpu.quat.w / 1073741824; // 1073741824 = 2^30 - x = (float)mpu.quat.x / 1073741824; - y = (float)mpu.quat.y / 1073741824; - z = (float)mpu.quat.z / 1073741824; + w = (float)mpu.quat.w / q30; // q30 = 2^30 + x = (float)mpu.quat.x / q30; + y = (float)mpu.quat.y / q30; + z = (float)mpu.quat.z / q30; // Calculate Euler angles: source roll = atan2(2*(w*x + y*z), 1 - 2*(x*x + y*y)); // roll (x-axis rotation) diff --git a/Src/util.c b/Src/util.c index 45e238e..1e7b2aa 100644 --- a/Src/util.c +++ b/Src/util.c @@ -69,7 +69,7 @@ void intro_demo_led(uint32_t tDelay) { int i; - for (i = 0; i < 6; i++) { + for (i = 0; i < 3; i++) { HAL_GPIO_WritePin(LED1_GPIO_Port, LED1_Pin, GPIO_PIN_SET); HAL_GPIO_WritePin(LED3_GPIO_Port, LED3_Pin, GPIO_PIN_RESET); HAL_Delay(tDelay); diff --git a/build/VARIANT_DEBUG/firmware.bin b/build/VARIANT_DEBUG/firmware.bin index 79b0a606d807771a69d108016019c98576db238d..9903c126c7fb0b0ae423309844ed7e1646390956 100644 GIT binary patch delta 7874 zcmbtZd3Y4Xwy)}0vq3_D>|~Z~BrF2~34xGF2%QNNNZ14+Xe5APlOV{Vzy#SZ#ETYq zK~z95UcpBo#PFGmAt3m~t0*I&qHtx?At2a5NcZ&g@=o_O+~s@k{qbJD?^ko`S7)iM zt50>_YM@SiM0rp-vfQgh=8^(rb^}HM$^c^k=->Xv0XIS8C&KSjfWfQ&Uzlf}3Qk`9 zKRQ|kc6I-Q?T-J3Cwn#|5;L}>E!887GPvE_klEa%b0;+DN_4J+4^XYSMd6o2`|fRx zqw$vL3^Vf#w>aTQr130D!2>36`XSqk-!JrgYg&$jwSv>?FEMued+7C6)cTc5k-ObK zr8ci3hr6frC>0_tdS-=yY*CgdTF(>-Q5M~yshs|{o_XOD(%${)PVY*{mO+=bmoCsV zZ%L#wru*3aqRt+1+k_qTnKu1k_kj)v$-XlM8%d+IU=cujgMU(NQRys2q2q9 z?dhU`1?qbP8^Q<7V6J@sx+jP|{+m7{NR$bvIX-c*;x8egMlD#Q$kvrWiw$1k0IbcfcO)j8y7Vp4K* z_0q~OW6EynN>|&E-K;OY6;&X!Tl_XUijMLu!79CS6 zlNyT!d&z5-B>X8kXo-nG;zy3yR%~$=zTwluDN)Cn99b}w{eE)AVvE=gwx0H7up4xY zKssCF;?}CnOm+P!_ou!}`$cuE<)pxx4YTs1HJ{4&lOxtXQ2E6=2+AZ|9{!C?vGoLb ztxaKCYykrkQ_5>(L*vp{YW`72n930{74iLI?q*qFOm&x)4*tGaV8y(ya zh$E9y&VzdI)PdAXGMS#*hngmnt*I$dWirb6)caAOqa6<&TGI+s_C>0l8Yq*yscGSz zq4Abi2cuae5KG#C&c912<8R)*i;(3DA7*$`m6nz8EpP`^r9r}0&gMW_pPj9>pY)+t zC)t4nrpiL6V{gFkU=-AA#u;7%s+_6 z;CVB^LQ{uoTBgGYZfWNYs#Kp&I7cwESR}5VH4w46XPzC7aBWLu)3*+Xz@dVfuHvKh z{y}xF=-q`!I=FTIq1Pe&tKPEA;nY!q9Lp??{zQmu9$)n5!=L%)GZ?j~Zj!R{sJQ~E z$ja>eq_CDtao$$vQUaY8 zOXy&rjU=y6->7lm<5#b_B!|A@Go{{wQLN~bJ@0ax-ma&0J36^A^MJqHhV5uaILLQ+ zQ!l+Y45UuH5#G{QP1Jca)J*)lAelg-_$t%A^9DGd&aX%2n}7g74<}L=fEBQ?DSFi0 zrCk}UPdXa~7H!1ZH^y_>Z-KLNji8h|zE1sPjc0W`n#U-i8Ohs|d2 z*Z}wx@D5-LJlQBK{8EH>iywm&b}1Yr3Z&3WVP2D^rWgVA01PkyD1Z?V*+fCSpJnW! z&nC+3PqLogk|eX=%eB~f>l88%uRRWUy+EmZK;bob z@^%9;SX0<2_M=U-12)eZaW&l&&To4ID@U>Iu3ANdZcqPZ z(4m-S&gh{#(@wesni~Qlo8*sw?_3)K^BO<0#k*ldevw@s*uDBPbU|cyflin|O4E57 zbfQ3KGU&_>45qKFRz_Y2I)2Wq>6C(w8FXBrGbvzMV^DIbKPp!S?nG7mrM@)(tupg%mAdYOkJSd^^H$vjp}a*fL(x-fa|Y#kXZyF zel;>@14aQB0k#7g0G|PV0T|XGb1Gm2U?$*oz!AU~fa?GQ1jz*~0PF1K5AAW#9#@hC?G|Y70qu#<{t~qOXf#}icE`9H{Wf40D87ub7jz#WxSZ;CUaNky zFzQ>~!6<&jHlxg7fsWdJm;aoE;qwneEbi2;Nc2O{E>B;|_3U z$6UBQggQz)!lMsx;f`K*#OQDx*U6#(Fs>+yGY>uf-~?62A*ja}b%DB`uH&%d_=8o^ z`VVwP(VRIviqj`{;q<+tIsMQ&jzV=FP7ik{gGFbZO*`+WIqNth1YQi+>fkLavIXzg zS)KPYo$vyH4feo0;{Fp=2O!8|=nUm3x}OF$yPNlUow(|+zOP^| z$!~*(_KN@#a>@PSR%gcvcr6*Ae$7j{-&%FmHwLCqQKZ~EH|lDY7cG3lAW!8a41JrU zOGNg4zk!apr-M7d!@%2|&Y{mLIy>+OD$D0BW9kZ&gZU~avS0E;OV%A$YCl5l6i*K2 zWOSF75VG5x9-e)mMR+UN{3oPen^ix%fZNC?0rv@Tn^bNa za2`GmxWhiYUvY8^oGb^o8y~xU9hil{e00{M>D&coHZY#{B?lh`e*?HmSxXhkromHi zAL1Kq#YrS2HywwNez|svmB^F1{i(|msn3lMJy4@uJSFx^rE0S^OX^3PKy;Iyj%`+! znt~mR_v@iklfd~!iQLcaV|(p?QCk3N4UljT$>}m(Q$r}Z$zkRG;D=`N%R zQ(;X^O_dEMx8mN}vE70p_Z%ik>?A+=YKYC431X3-v=2$cT}i^wXQ}HVSvfQ|>^re5 zV?ndeLJmgu3{8kVDPA*8xxm>oX$-v#s|*h4W09O6T1vep5?h{)+Q|_*uZXIE4&=q+ zugKoK{4RY(Bvi=zUE2dunLUHvSHuHDVqknW8tz_Qyi2h1!XcT ze}2Es@C;+Pw|4s&wVu^v>oL?CuF5)Qb@M-D44=)qk`U+oj0Ixw+my&UKY?#?t;)9# zRD_&0O-6d%p-3CDQXhzHwV&*EzC^VLNMb<-^>cvG1-21Nz`2NW)&kUkG=^j4yN{1; zMdnCYGRz2~r82U`)I{wo;Pes70R$hSTskIH#M^^Q+m#$Buwz}Lw*cd?3f_5GubxTa z`k_)=J3bk}eRru0hVo)J^19yg%dDex>$#K zCj9mRAozQ(xG~-psxuCRI=zi#x_jX9jU{e74pppz7G!a$4UZ=~O3(cZIZ9F8HfrL( zsCJB2RO8A%r=WY+%8uYmWJkFjs1~)nTAmCt9+TDG$E~7ck6Iu{M9dx$*}A(0_8dnF z#}p-ZlC5@KM>J*)uKkiBEFLmx(9)#Bk&jlz_tEX@~e?W;O1biY#=e+k(Nz(bnmVVFCp@g4jlB?tJ#fAZ4-pGqm! z4+X0jMx%k2>=K^64YW?B*^tXBc=|Dngrez z2445oinmFmZmJzGXl$7Jl)-$m`YGoL2tq=u*5QZbwW=xjb8@Gu7{Avza5{_eUr6tn z#dtM&ab~)nXYa~n_sn+upmE!Cy)mw6JX!6ba4Z=oI9}lwiz8NJaRF_ zhaxE_LWPC3`ohAwL|klzj5B#jzk%HX2I%#hIRD{a>Ls>QzzO~CxOnDQi8Tj~gZ%x) z&q1bCt)1BOa4Tp9$l4`KsO77OwB&g_g3MbwD`qS|r`km0tY~jlwT=nb>9cm7mDpl( zXK7YMKmK@vbHu}oH{s5mMN*gL8{UV^U@n=pEWvO@l{P+-8uu;RgJA{SFDK(y$()y8 z#(yKemp{iT8A2$7cQJJ-P$;9-H`~2 qd#N#gYoR{&rn1Gr;1R0fCifL2O=Q(ZOXLQqpm#^=F|X~Gyu?l{CxpjqsBME?{UCZ*Z&K1&8NW0 zwg01|7O;Erzu02ie{UEWvNo2OF`ZPYN3`0xO~`CMtaHZH=^Q%yfnQLyxl!R4DCL{# zN8$}($tLzK`IVR>A;$A45oeC$^#ivQ?#}nRD;sIBR*b)IX<>p&tC99;}#e<>Dh1n#jU7J;gS`-OoclRT+#ez z+<PovQI#e5z)^X5WRt%ip+3*C3dnFw^mO-*Mc*VHG#o<&b8>$4aC4Ml|yPn z8mkZM*)BeryCBP4izIWWC5qiF$lQ3jz>Y1t@_fgnawEIZJAgX!)fF3t&|PB)l^b^vOBqZ7dhk)vptlPiz1<7oJe7qu znAp*PY`}0p*x|6EO?+Y+sXJCjS=WOYH@jgwZ=w^JY=&Z6 zyg2KoM_B~7JxU*LtRidU6RAC3QX3yR>;a$5NZfgGM!A7GKpY~*vV7hnD5-&=Ape=-_)4%|C`x)0hhl5BN zoe-1?C1>2}w2s{%kqtDByO26M4jak$bk}Gf?AFL8OxyC`_UNtHvYt1kr9xL8@*5K@ z!B=@@?iaz_>sTA29SKNu*;^QqUMEyyw3xYRV?xBst@5i)jrjd25NTHmwnc3tdxZobw?13DnlFM_;N@B-4B3Q#B&l z-6IEDd8@qfRY7rJ*6lN`9m7U4*lrhDbG9>qej(D zZfY)7E0CqBDV??ntN29QeRW9gL&pxME~F|1(x;bY;9GJrJ9U)E-H^xg-P2YuC?S&3 z6N#G*>(jF_*GR8CwWh;rZZ-6V_OT%IMnqNt=uMd2vgC7}D zYNgEm>{S+q0qlakw>+ER@cDTaGKYd+3qS%n`*1fXm3Wyu;Wsd8bup0RV5sG+WG1_@ zik7+G`jzyOHyqLshX3O3a?(zw=Ci!?X&ZG;9_8z75FjhRmA*AA{Vxg)N>{ zw5s-IxyWsWb1xsJrA35KYK6%CQOn;FT?VEUh&39~EE<{jA-`P9yTyKtiAjT*{j<1& z=?O=x$ek9SgY>8$L)ri-%y@~&9rTObS#LG7hA9C(kvk*~V9*A|@_>kHFcS&V2dd2u z&^+wTXPj^*E^_hhCjFqeMm15Yc>9^jYSrX*FnQNYu_64q7K8`DmqFxKs?AuWmcR0> z8S_AMwU=T7p&0`paHOmvH&5+^;&&E&4HVm{s?{XWb-f5HkFrv17H?!aF*e2l#a=<= zW_qJPywHNc{4+1IL_48JUXeQ~yuacaG(qG%pfkoBs_EG+lso%6@bqOa~MvXzoi=`qoS-_8f56&HoEx=!#R zvFi6kHd$Xp>}i?2o}NkF5y{c?G`yNTNH4>)$*7Eeco12U(KA%}J}RrB7ElUd)G^YS zk%#k$n9&n{tq zq^s3*rBn&>ay4Bh%>#LfnpR1_2l-_+eMy=N@;o)2Bh3N1LQQ`s%?7zlO-rR&AWu=# ziBbi~q@97c7!DvvOQN`5>5N z1B4R$_a2!W380lWvA@uM#FOMq)^xH| z_HX<1?fXC{TFqVCZ?k^{xiB?%d4H~byC=#yL$iogSXb+}`v=%Jf)ZAhPVWDWeVqqG zlkN+RcPQHD!QGWn-c>1aA4$qMBNlm+;gEU9*W3Pz$5=$Kt7b!xvd58NUH4bx*rsHA zvb{n*Xzs2+=7}qjc@LlsPz(Fn1CRmM<;YyH9Kz-)AS?zDz$bu<03Hzf8ZvhW3%983Ixj`nc~J;rJCW`EySj8x9tGu5jyNc%p}ZTE$3l6V zSXS|)(Qqlu+0|a}wE*(~m>Of`CEXsxhKahGpUSu8hyF$PWbu6cp4+8}t@j$BAnXMkT}1|G$69#apj=c1 z)U*eN@{D@pqa3!jwltX=-Vm}HhIQqDLH(5245FL8K?%0DS48fw1Q!N61_y_&x511w&B@#jTrQvA@8R*K@kLUIwk_g#@tq8Ulbn3{fm+12;~H z1MVnr>r`$Ua84l#xPuo?9sHWz77Zo#UG~YWUjN+J_)Abcwb2QsPfK>bzcR*)w8(u zol?A4;>_|x2!r76(R}b^Bg~kx#_#lK2_mLU77ULZdk&pZ#Hwm97^|{l! z?~uY-oiV(LwqCKOFc@r((8^Uz;xRJx0sk`G56LXKx1_Tz90Vw))V9fZJ!OlO#7Uuk(F% z_38Guseu~r`PxO^%uA%!3gl4UWZXzXZ9haQ%LO|l;oebM*e*|KmkAy+uir{ovly;W zT|PriXEZtPOVp%XiLqVBx*C3!Mc{+T&LQ(c=ZfvG9wO&I3a>oCCggXaGJPaFe=$|- zCx`NrsTx1Io^Od(Dwu;PxROyewE_miwz>RSH$tKd=s=^0x3o`C5E)ir#m4%I0*w1k z@YxRP)s3YzB>wP>L`1L^o<|ZpFvzESq=P13{Z)r-9l9t}3ZjffZG6T znX)-YIFWfC;A6nI0PH~QD(LX8k%SqRq!+m@JgFQu+4wWe`mO@l4E~G+cziyiz})a1zyRC_(0xfEj>9z*@kY00e*E534`u=%DMq8S=XU z*@uzUPy`VdV=aZ}6}}*ra$C!Fb*ZJs2-E5V&G*yQG9SN}U47sPR!6#791EtxRr?pFoWT#*EjP0PhTqDbg6^ou)Cv zG=}4!R~aRogGLpA>xcYgO{t%z^ml%u#-wP>Rerq2#B0n2{y8VI__!#UoEU3ynPerJ zgZDzLL}>zdL+vWuEkHg1kvZz1)HoVq&k~6A1a23vgo?_r_&AR=no;`gRHHy2cT0L& zCU9Se#kG$+p%x}-stwPa`M7#XnLt`A`IAJp zjN9T8xCq{^c21cnf$PKD%Fy`WhOtI~?gtJ)o9YJA)aLi?0NiKGv_iI3H?CBm$c6jMJmkol{+knQlyIJsM7j?j3Q ze`~DfF9Y8AC&Bq}+)v(~oZ^at>`0jTF!)tQrS@V^w`TF`_e7p~ynwtWd$e|&nkxXUbRroB8C7Y+_1yq1E12BhNo7z9L1nN^5 z`2LqG{!2*r=dHM+-tqi%2C{d?>)1>B&76e4CF^Gv;*aYu&EzoNN6x)a2*FjC@*aAD z`;sTN@>a~%XI1pZxU{}(mW#r%_8E~K&+)SsC9ojKS6k6YIAExI!oC9Z&M ze3{TdRJM4E0kJhZ82Sd7L}1HRXw7Lh4=59QEmQ_<^T^0p==1{=U40V z^JkFlRS7tqG*$J>iV_Ua>TNjh$;bO8uCri+cDFU3yCZQy!ZDD4Xg&?HQPrx!t|yy7 zOD5eHEu^lx$a{-^j~yg#n^^D zX}$}0&A#N+;yi;<4F>|2#26w}spnIv-mzpSh8eiOG#+mxfv+yX-;vd?p2o?fc-eps zPnJRi^D6uc@>Q~N*>98=%(KhJQX9p3+LerP1#wibHy`pJgMem;i(IeHiF5E?Zl}-7 zee16*RQ}lp!3$jpD@MWC`mE(UjHZ%l^XJc;kwE^kx@W!qjYGlImZkNdZ_d|;+*DQ; d7@UEpsa|kPBnj*2kh_pU9}L%HC<%eWe*(43%kuyL diff --git a/build/VARIANT_DEBUG/firmware.elf b/build/VARIANT_DEBUG/firmware.elf index 57067b064a035937cc190cbad6c9f3c785ccd21a..f54853f88479a71c48766fde3fd783d30207c50b 100644 GIT binary patch delta 101879 zcmbrnd3;mF8b3U9lBVgBl9tjmr9ip>rKKUX1=>=e6bJ~XJ*bx z*uToP@ix~ziIKmr681bH#IaW^Q&T&?w@C<=a8QJh_{Tqu7Z2$6rB)#(?w+}|B|yDl z1BHDA%1D&aC}U74dhy>l&@M6Qm*Mkrl!Dd&|H`C+Vy1o3|3^csp||1xqPyk)K(Ab# ztlOpZbV1!ctl2}zgMF`MMEl*AVV2V8{}ik22T5N6{zIFpMoD>3+YEcnyJA~nN5`drz3Yt6Q1eTqva zjD5PvlIHj+T>AX)pS2d)Hojk*yvka$qp6j)(6-T9qc@E{C#I2>LAgBAHh@-kLo2P| z{j;`GYt79~`eB#Mj}5DF)+X*g_=CMz)C@gfKNzjYCdy%2ev>{iQ6?p>Xy}A+pKB1Q z9u@Aw1`qJZ8}z#pr8gqpCOlKagy(+!twfm{xUacQ+URquroMkx=83cvzkKrjvzDB& z`)oC3wa#76gRAyhYfjg<1V3(R37&0k3BKK|)m+`!61=QsM5#=*R16<>WreL~YW;MN zR@0_Q){JWyI!a_rIwI0!YVJJLZ2n+GzOAXkBWtpoN=BB9{<=1OwM0NC>bos12<#qE zs?|K&l(AISbZio7S@Uw27M01Y;-j)=YGY1nO2zJmKmODj+O~~4AZxyEcBbT`0p>P+ zU3=ysggx-~S|N%-nbFi^#MiaQ?nzpD8z?uw^gylf$jtDgol89_N%O2V6Pq&NXH#Rw zh@_>nUfN=EJCp{TiaoL^4eWJ|X%#XzZOX1{nVK{2;cAif%F*c;g&?x_9hEA8!lvET zGV`;ebR#m49rdI{mC{YOrVl{>;wT-6%;QI$DPfA zb3?85p)7xif7lAKRIB-SqsaK_DCvr}jI^gfJAHw+lC&M59dD)Gb`xovKzqNH7NK zu>)Iz_td5Ov-~Z=JN4tqvajv>x*IBdQ}mO`vbQYPM|Y5YWsZJF2kDM4Mr#;uqEm+{ zH{}ib{tj|mU}SxY|KJbK;&61Al$XLw|Edlz{S)PPl;2Q(sdgUBSugBUQ3_E?P==$7 zMY#gSk`evc*FT6FEi6333LBkYw3aqhTTAOug4OeeoTwk_LOo9?@B z_p7_Lv<>>l9c5eXiF*Bqjw34 zz^(eMPH33v_4+-XWa5yg>N5Pz!B?B6SA_XrsI!aa;EPStPnu{7^PgJZ9Nc5#`(6_nD`{Vy@FgCSp5l_t)mBU&8*0OSS*X#| zb^0lfOm*B3{lK|p=pdGwM!ijnbh~d+q#3GDXd_;)o|5*ts&u(NFh%AfL5ou40Bt~> zzAr_3fqs`F`{1KPs_Z9!)~`&J-GJSas)z?uWiKm+MXi25Rpx-+Elsw^$B;BR8Xud| zB~zBQeYw$jVEo|6_PkX+w?>MC%2J0c z*-x9@s87t2nQbm@yrnk1_$QU3pHRt7S*Ts-Mm?sxOzj(J8C`SLn5N)|Etl1H_O0=Y zltjPvzUJVS=zGOA$5vUlPVl=id~T>6U2_xUb~oQT%u^$Zn}ZAV>$=NM$krX*1f&UTk!a`d@o+XMMitXqGrP8&7>`nZ*$d*?l$0xY|Fj6eL|rr!}9&7s>3_~h`Oxw%G^0$ zp0%b~{gy2;rLyMF`Y+GQG_fTb@Gte@-K|HX0L9eXaJN4lt{t-j3$K3!P&gp1ep>kN z$HFkN9lKT7e?VzKv0^HVLrFooVQ<@!vzNx#NNa~9vCufHr}U7nz?XF%Ototpd9~Dg zcZ)Q~?>3P&uO;|v9eYI>ME_fNx_TSts5@bDH_GcM52DS(xU-cW&JMUg0BC>n|l#kp65zpqf&+zrooctDsz=i zoA>ybTOD;Oi}-#@)yajH-2(24u~c+CM#>HKJxm zbG%2?+|wvw>bfSG7Fqh}JP6gjgO1pQIX>}bVP_UP2h2bHcDLQvoug0q_n{Nf&JUfU$L zN`E4tE0oSR>%U}wVHxO zDvX|r?`;jED1LFFCnAV9H_Mg{B8Wj z{$XJ6ZfFX2s7reEp;h{BOB7~;k4#-5+#hNl#K_(V5S3qV~ zLxKO)8rFORWa?_|rc4=R?2svi%!CHd+Ayxk?&db6_O)qACm*+z6<6r5^_1*Slq09fT>Z5i*;88eKXYWa zSl+?eH}<1cU@dr9&(4(tR{zYAXY`zX~wYr{Zo(1@{x_;F>6Yv-6`dM=Y;7`=`qqOF0fqba0?=|OC4;wyi z>6#j88HX9+qsGkY=HMrddUKvE49sZ2!nkHbLwV_k)h$7ry2Z=qN0lC~?lB_Xvvq0i zZh@JDljZrH!%7cA=A4>3f7>~%}#-cc@ALAePfKGM@1{Huiv!dLV|y=89uhnlC& z+!`M7Nta<=OLx~wd^J&bM_=)97ft{~q>o*k-l*E2y`D^(N)+fK6B5L~7hk-M(e)PHJH-tT4 z-Lj|Q&p#s2aV}}*{Yf0+VBkRb0HOYb5`L?QvS;I-F&t&$t@_SBGCA;SZ5X%b4dPHK z=GVh&gR2cIK7ZcV5{x^r3pcG!d&|z3jeD-v?wgGbNu;mre01CAYNLJK(?pF$Zm5m% zS)Xwaj;*y9z53^C+J;&IJZW$oaI1eqt@OS6=jyiBCoO~9*4m?EYpuy~wbt%!Ypq2a zYBjMTP;14WEX-p`ndLA3qf7CIS{ocM#-82Sy*Urcr!6VPe`FTphJZfy=g}d5^q%${ zoGeB#ns4wQU4U7AGt#aOr|!T*eLxq!u4?b}h;87Z%K%B=P+Y@&--eYOS^`M(U7I!w z^S4EIAAN59l+r_n+rDt{#!FP1aAtkjDTW_Ls~vVGC^TK}-7;1hLWe#h??Y$g6` z*j{V#S+fQo>GheGRef}H&4z)Ts!!K81^-)LG;G}-VkdyTS+DQPml+Ao!56UNeeEbl zl%}POKDQC0>KUws^D$#R1-bj`Q=s)9EY0pzmUe)4TYU%6UIy(BMcV{gpxzDIo@)6t zt^5cpD`5AwR=f9taswzY90`~*zk)Igl)$+q&xgEk25m}3Z*x-^8ZC{KIC>|iQZS{$4xiogy^)_v%4jDSCf8cU)eFWtoc_g zA||1M!uL+u9X^5{iqGHgkyxMhZ*C4wsMFu;D^qQmfCty<=laSnGG1?AB(K)KZPITl zl8I5DHpSO?#H=G&rRfhB$@YnFG<_3(H zYjuA=Iar&BNczb{`JVoGKRF<-M-zvs<>~WkEnQnZW3_(1A9kM~)a%Lp!GQId1LWMEcVd7`?2g;*7l)3RaLOy*{&l;YsUk&tvME?mr$1CImuu%5^yGmuL;Jcx z_Yah*L+Et2(27@~D5rjjdFRvpuWS@{C)!cgG&XsrI1h&J)t(wyYjtpj!U1v`mPL( zI8xXLpiD!N!$i$3sDHn5edi$A1(NTz=${Re6K!{*x%&;#3kS=oagD)>mN(BjE_w58 z+$Cqx6>wy^bFln1>?9I=s_Nk(@=C4a8B`!0$C_4@Hvwnj(~BbTckR%sq*9!m*m{BB z-=t@bkR9dts$nBgi%2ROO8Vk5nJUNYTgv3e|3eu=}O;Pi3lSoY%(HQ)=RxcSN2X~5T zNlCLz`Mp}JiDe7c~PWAl`{6^Yq8Z$lS<3o1^@izae{9$Cj$=S;Md7*_Q4NCW)Y^%r&^4xzyY>o`a+OJO)?Q{(#+j7x+RI0X)cWAaW<7J9ObzsH z=E4}K%aZHehG1K@sK%~P)(5}EUQ$HTB#{jB&1wVtjI zwrdXY8iK#6q}2zb6s`TkM`5Kts40w|>Vu6<(C($w4b$hFsNTgC{Y7Dhqv|HMp~vK$ zYT7(r-XEwB4sR({wPRD&2M4tbHS4;*DaYRzl){$5CS|2b>Df|ZQWl$(jFtf=2m_p^IkhP_kNf~BR8k%!WN`I5`2YOB3i27i@sv9>U z4Z*lt_LTbI8P!1b!AyPbCDN5!A8cyj-l;zLVYBhsPASy~W1HHWW+PQv+-6!V`hiR2 z$J*9L{jN)8N%WG&koN_R`pHY>*z`%Q=BplpQ9hKDfW}Hf7yt zmfel(O<(8hjb?eW@fMTvi%HqhxW=TMF)5oHSDBPAOv;AFn@q|_^+rP0Hr}Wx@ES1N z<;KQkrqC;<+JeT#CS|Wlnc29|q&#at1hBA+`3d7+#bqm z$%qF_l1_@$fw0iUw9tQqA@M1m^yGt{e36~=IJMQ39Ssc``8)czBWRmO?I{^+z!t$Vk1}EqnCgHX*ziRg+ zd3l)qjf%^QUxOz-a++Kx|I#a`VU6~-{>wBuR6bhOYq|_d`7b?t2GBM7q8YNQwLbW3 zi~i6Ic~1UWwdq=!E#<_jH!5U6lZpDE>*O`^JN>EaaNhUHqN>!{@&mhLNTbc4R&l@O z@UiCL0KI9U?BwX7NLws>K4}hi)4MH_GY6h)pwy1=pCR>Y!>aaLM)33Js*|QP2dfq5 z{_wzGbDnPwo>IK?pYN!Cdgk!55hG6QmZ_9FrhmLhcJ1)0VxRpypi~b)b=s^QP#px- zJ-TZ#4yy0dFIg&si#Gy2jRDR}t=)S#6I_ ztFY8WTdY|-jx+~{>c1>S$UW;{ZC^a(ug`zL?mkQJyi5)Vdje~U+4{_7vVGV-1>V*Q zRz0;$J}l8HBW}dX;4b~T8|97iUA_87`L;~gpI;#hA~)TH4KFsxV*>ggD`ao&mqtBv zr5vxl-dMG2rOc2x3VG@#xxs#>;Z-b#POsAY2V`M~A+>c_7}NzD8nD_#U&gw}!^g-h z6RS1_44pE^)g)D^gqHC`bb7i#8S^ z$`hCBzeZ|jfit8xyN+ill(wrf=`$9n+f?Uw2}2}(KHrTu1+ zwN=sWwOe6C_wLk^t9GSomotpjA8KwrEnS;x#E&*dn=uC6_x@d(~ zS*!QW)cVLb^&dac`o`4e3*i{+fZO=Ql5YCTnc5OLqAD*-`$jt2IE9GWS&OV>CVr}? zWovyMBS?B_ej6eBCD!WKWorjybX8}sRw-q)Ue!aJ8}~1l5LR&>2PanfA>2o|)AM~= zww$WZ@M$;5=~X9u+LhYnJ{Yp~)P6wL6GhA=Flfus4j_y+;j#~i;Z-HbqjQ7FU=a!Sh)2Hy>MDoTh{rdAC|r{XKYbU-R$+N749GK7v1}&z{G|k^ zp#`H70+3F80@f3wdW=PtT~`FajOs~PxF=sHqH<`_>MEqTg6*yoDIqx86#+qm?sQLH zDxz{HfDn%wwZKlqIb140P_e?v5qL_E>T?<-S8p^JB9A5lIy=YL`*NQy}0f zMi@~e2nsYg;4;Fi+J6g6fv8c8TFCbQW*lRPSfz*;N0^ROn1W{92_4P;(O-0;-3yWzp&U#0f2#Dmwr>GFMXg5Aw zG8^~|q^Osvkm$OP3U9FL$u76Vb6GX8{iC=pYs3R2e`X?@}j9C>H`|}0Y+#aGPHcai0ugN7r91K{^OS+U+nVW z8g=Zw06qq}C(nlRaVigXJ-=9uGF!b(qpuq5GZqKh%;)uQZ0AXF=3Zz412s|4>?P< zZzEA_5Bp=(3XOfRRC;b_3@f#sz{;ejo=vn`D}lX}nrAC*tkZsgjZ>Ou8nN}-DDZyP z0!Tv%=$f>@3wvRNAr=rO6Ix5{DXuofRw`eVLmsl76g? z{Z#2HRl~s#YaVB%&6FwN$3zW~SJA+5TVKc(D?~V|Xknm2Y>v^)V2QjE;?W|4AJ;>} z3^D3R)aBY-{ZN6H*q$w8b+Cg*P15F~W$cbJkfN^AD)c`JFuiw!-UP?5jA*LHPFmqu zOo3?%ndi8J?KoW_OC2?IdyN)=omGx0G&)1O8_0UcN^-7Mz2YH9C-%h(rSq7h0~>Uv zLY{R2|I}ml9!d`Yf0xW8_Lf&+2U_5h_x%Wf_o1H#Y{oDplw+at8@EsxC zC8BDg7HDq(cWhyZixeyzr->}qJ_ci{h~VG{7%+@<5D~n6vFj?M9YktP)MZ*2dSMy| zU)1#)6P(tCsac}Ync=n_B$P&?Xj=nfoRySxjwRKXK=1&LvvMS*v&V<}U8y4X>4T35 zw*6HAlqF4sKgeu`TR1O->xAu=FnpLd^ytEEQTl)sOZ&(WVaPuH_r97dunjg6q8-J* z;?os~Lk3E|L{P%D7pnrt5W-g1zeq17Y!{Yf%%YCruTd}FF}i;=WE)5tW9ZF_0X*K& zdyqCRQ+lphv~dODXxD7YPa+&}3dE#q5a%~YuW(+02E@|mH#ll@$(x`jBs+`!SQWY6%mLfX)O%=Jr(Xr=+Dmwt ziqCbPaG46vbq^dmM-z6sxaxC`B^>WcE$IeCr6^HY5@FhT`PmE6I43W0=uIgWPrx~S z448@A!5i!hbV5X~Jlb4MP`GRidJRLfx*kQ;&Rh0@>v3_(=)83a=qWBXmGd^Y!Y3Fo;2=Vd zZ^pnT)DINmjuGUEs*y8cD@Qo_l?@-mUj$HBJQ*0GCS zdh7sgWZSnvv$@buLX0gV_4xy|v_MzTY$I_=7$5ss4sxlI9{U7ABk8eEGJ2~kfgwMg z4|=-mYQoPRgh+;q%lO!xhXH50KJ^0L#T<5bwP!GU2>VsqNN((Fga^CsCHw~AQr9*beT#6J zD~a^C374Zyp2O^l+ZHg(Ugq$fNvv#g+<+%o*}$cUBhGA;W#Gh_-TYC~&2D}VB;(9( z&aNG&a_@9)q`b;~yo(8ryIi%2u;^5nI1E=a-Er%F1LE8RA>pirn#b7_6F|B%;08U# zc^aftXE{h|&M*w^hn(NzdP-Ps#7EryyCGzwg@od`?YlryjTEXCtM%Drx6mhXHqSonfd?Q6|F`m`vmu3UzlmsPG(xysE|Go@XohREx#! zHd>EEFYe!Luzc4v%I~F{0@rRjI6$~iHCWusY=9!9J{iN&vXY_)TW~cq(zc`;8cuy& znx%uK?a{p~x?4)fPIt=) zMGMOih{rFVO=VmBicj$A>W1vZuiQg**D|tiBCNTWT@AAV!f^U5g;qTYc0zjm&7Ipq z_77|k;@7Z_!ZoJ@;I)k2<~knm0J(*MMZ1nsZyo(4yFTg&_|`p;PZgF2L5g303RgQP z%yudLkqG;G;0Y=FP{Yp8qBF@}?D1h1zOCJP&P9a#aTd{K&b&oJE@CX5Pr!{_%*}9^ zWlDh3zrdVa%6mkZg|8KNo^=s{?-zIO0WWfyA#n`}9pOAgxEh46A5!H;j)pJ`Ur)~X z6ysCQkg{7Za{9}|iFkbhY`JZ9JSL6=W-HzKw~h^)noF1O8sV2_SKe`Tol0Q>;D8r-mGzW9x5St5ld zvSxrg2Hd_O-3pPl5VVP)jWTF-aT7=tAYEe`vG9d)(POQt-D4ww8^G`J1b~|YfUl1Z!in%b z$!=Ek7`jKg>WhI5Q16+=9#BM3@&>{&GKdIaXUee*w-r9#}v%@99?1?JQ)JH zU)Yfjlw?6DZwU;rI5t}I!r*|#vB{cu2%ju%Gi9&Yyc^C&adqkSH98(kVn(ll7``kC zU3)cS-eqamHO~uUEOD!}UWdSCad+(14IeB?t9#|Z5=)zgUiU(fCF!obX<)Ln&6mA4 z;FG2O;a++8$P3_-w6@n#)R-md?p`|)8cUn{UV}klaVPg0jSrSKjUuccXSvVe#ypSv z2x*vt986#y@W&OhX0`g<_^?|a!0KI-wl}cwx8#CrU4@I5HJn#z_rC^u7!eCE)~WEJ z^_fAYhL+<;csA@>?O6D0BQacIIt=gS3JYQDE#PURH|s}V))MtarC9u1d4Ok0RkOME zW5`6{8G*14fQq%d(%C?K0l~=2==~bG2XK_t`h*)o(LCU@KKUz1(LCU@K1C{a2e@ z9RSA^T#lirVBtxf@Y(u|M17n*;jQ7 zI(fin>rXh|$pb#y0K$n*9`M%}45|GL6x+*`PjvEt&-TWvfRmj(;IqB;A`<6wl5fBxswNcwy&;3&Br@=z-RmB5?Gty@-B6G6`1Qu@Li-Mp^L$?kdPn5>vrH!OXwbG=+X=ywS`v>2ZR<2VEXC1a z5|0LL>$Mlb`&mQ!cB01S$)IIt82Z26%5JH${uOu^WnH0W*7t&Cx4w#N!nbS&7{5r8 zq)_|(NEvFegI$n;Hcw^M#K_*G1{2OI6`?dlz$D9~L0c!8hRU~BM}xLBc^mj{HRp9! zuyFHe(AGuLkJZhiL0ebJ*0#eBYi_sFX8S4N$JhqQcWGcaF1BI?3pY;&Z36=ev$=UR zXe*I(ARa9o{5Sz&BSw*Y#CEy%1ti?>Q|wBObGmTHu_sMbZDn=yu+TP1N!i^zEVNyv zaY{{h4`6FgR_$BrzJy{^w8x-d?w)SP{BOHjgp;+NLRFp8F13 zn68keZk{IEuF-zN$0|2Z6KylJ1|aL*JWaG+s~kP#=4qm>Lg_r_=4qmBrb3=|OLAr@ zPGK**A0aYZA#b{QnrNG&%)KWZ>^AhNQsOpnx>b0%fkz=|g}X#@jctL} z1Gt-~iMB-w7H*y<+7@dAz*s6Am}mlmuu|$E9Ly_wyNP$Gv0bJ{V@Hm3+w~gTq$5ug zZA&ydGu*BYX(Wn>8W8PPQaW)+s_qBEoq+9Dj>}FQB%!YQ0?(>(X9mf^?(!}Gn|^gD<(ZiMUw{jKabwZ9BMu^t*B25a~ZBka86wi5lVn==cSm_~cc^-9}jElOKnGqx>W*{=*@DICe|q??hx#LqU!f zox>$>QPCyGBlOAbwe|sPH=;v#Q*IgBE4qw+Qh0Za9(f#K8=GThr%2q%(1f%8fO`?Q zOgOG1q{S^4j@g8;pyB@8F{jqhm^;SQnAfT?zg1&_sloksz;Qz+MB6wWi+I!(w?sG= zGn>lY5|vlFTS~}IcgqMx3oG~Ej^z`nYjdo43!hHzza1-;Lnrs&j++dZ+^} z9jorAUb^Gvc7Z4;as%#I!%7M#H{g!74BzHF?g4xYe@`lv9UaEx;%9WNl< zMx{aCK-lU07iAU_j&=5B%@z@ka}FT9m~dNX0(F-Vj(3(Z=%vHC#ct=kjL0%F5}cDL zw4AWZxrat?B%J7!3~mKsxAO$$R}xNg{z3RA!tI@zodBzhCOc12cNOU!gk>O_AodJ$ z6D{v^;*i97EtV{DBe?MIjKh6gZsJ`)bGm6_Gu5olAYJOD+nl|qaQ_Uzb|+3Bgxo@U zq_Dh%wv25HZnS)KF-?!5qC^cK<~iIKprH+ZZzN_!V%7aRCtYWq;nH{(SHa>Im?-x!-S)quao{RVTbb-Cg;EH9PA*& znauY|PjZf7TYgBmy-}N^gp-|>4D@5d9Rkj0Sj|ruQAZK`5)zgnzjk7i=p4c1o!ShB za4w{W(}bbsCuvKDTMn~)}{~CkP z;}%?Vt&rylinxj;LIy7bXmzGAf3@r-cIRsL+qy~IVrSr{#3{jUW#7aVw65(CkTF-w zre{D%e+ShN>1SE7^ar_nPR~JlE$OF0x29i#%7>+2i|X0ZPl6tv-Wf7>k-7^CrkzN6 zl7D$*ZThHCi$OiRB7HM68w!=+WEp1a_=t>hVS`s0XIq|as^)1`8K17s}e>p+J> zBmJq{icFS#P>{YIaftM}%u#w1Y-=L*J@gAxC{0eHPzls$L{I_I!!YuFMxTu>--yz9Vg;~}^B=d%aLLQOr6rmWCZTlIBH(4Hw z&c$uUt-9_f(QJ9)Rs-czg#@HqjkDtl)7-O}md_Moac@Fh<>%33pks9(V)ai%Zw6v_ zk7PgkLLt%an_1733URtOqgL|E=sggNckgBw`zo4!FHvMxTs<2dI{HymKFq=|A7#v$ z7r@EuJq|t(MNM&3n#F?_Ij+t0KEi$yYI56rv{3gSfaVYdl6{03o6&}mXqB_Op9e1; za1AuG57PZClQ%EBo;3)e3%y#tutydNaTuaKcy2l`AiQ=E+ktp8L|iC*NuYT^gHV`d zBEAlV8{4n&lV#B07N<>XL7-3~f>MI~B9-tyXp(uLt;qatmGJH}$^H--U$?@F*n7mJ zPYThqN%wsdvcd@Xg)AYmcw{A4$Gn;=?2llnBDYqyUv|*a=dxzVR;369M~|7!Jn_-_j>?H$%TmcQ79W&>NP1H+aw& zxle#LC7W(4dJ8+p(GYmZR?~T6$c=X)cxND$1)j<>G*^H&5Y~J*1E5PX7V-Y$ZANv- znqY{_LgCGTAChL97SQ&&AApvYjKF>cPzL6m1~bgU@BInyIg|Woh|I473U9qhelbMe zp~#|_VI*)gMCUgKh1X`%e+ZGkRpe-s+!7-5YlXraXOa^z9jK<}Hw}e1(IjVw$hnH# z(IgKJk@0;*ygKAfH|bY~==_eN@MfCi1tBuOwkW(llYCo<%x^LZZ*PB4NA{UwD zsu1}*MJ_SPA8`GnA`ip&9EG>kq<$ezZORD0JSn_anB>e5 znct@r-YF(|V2HdAWVHVblRhCt=hrTUceY8M8zS?Yn8LfjB(DpR!|(-6k-O9+=dK6v z8z!;by8v9$2mR$;0GFY^@SGk|qLX`%fHW1Px7%U;W6*Lx1C4##`zru;zHd$W!6LUY z#EUb#vB1ECo@UPwxgOA{nCmqG?_g7^OGs+E$Q>J!nhIbJ%;##JnZfDAFw$#MAjvo z$jf3Tg1~t}Zu^1q`_X?vrFSop2+Lh;8t8p9fYupsDsC`B^l5+znHTer zPuTZkb1Apo4EOoCHT90+N?;faT4k6aL*zQ z{Bz>m&zN{u>;QB9J%xP@Gq(`HT?9TbDI)7eOer!E3OH#%k=qU;wCtZ4a8e9m%=OHh z*aE#Cc;3{zha9J^Ut($T}Yz$a@_Va`2c* zW#}AkK-upwj7^TsaF0iI#{Fxvfd(ok9ZZz(hODAZlW2c@LrD^JdcWhtBj0A z=7nz^Xst^C3@epcrqet|QSrrxaEmD5qbKQeJcCNs^bq!E@hP{B!qD{A0>wxTh#?S% z>o7|b9|Pt#f}YwNt!u+5<52d-16Z7eLt;Zvvo96iB+z)5<{DnjL!fy;<2-b)LBlNK z%`L|dI zS0O#>c=BCjg=;*y?KLR%oU;(qjK@LvC`Zg;N~S8w-++5Rf;hK8+fbOE1)!ZUY1|Mf zngxrj9;iPB6#-MB-C77Qg(H(;&#vrA-c0%~n2Wi}t{fIk6*5w>M86+6`p!g4u1or> z)z$ZE>D>Q6WEk*({`+W68Y&`dD*C?Equ=ymis1T3Zu=JeoElC7TcX)hI$MNVHW<@jPU+wlDSlaLYRd=KO=I_ z1wdE5OhbAId>9h2a?bZfn`EUEr)~qPlm7`Zv(p#+h|VE36*{69Mkg;q1Lxhs4WFjg z|NT&@ycV{Trc$(o_{lg-Jf;9&wk-Yx$(DOsu4pY9Hh#f1zr?z8}t>>CIqO30);txaYI7=FIo+Y zf^uf)qbPO*{-H~vgItU7d(OCF0Xc-5STVbG4z2~K+CpOc-xQu;@|Q9B+oK3~gq=ZZ z+q6CES>SRE)OlC12dtZEg|A%5uB}#_pvi3vERU}~fWyVX07g?do(_c)mEmwP_+{#f zD6T1r7S5T6_EfMa=ttG#k*v$MOx#73(Kru`CZp?ug9-%16j;sUy9ywX$w%UOUdH|z z1;hu$)eghJ`K()YhZBlj0yKLIyTca>msey?!?Qg61Z5(OX_cj!DyFX@GZZ@5`xQd@ z9vyuzT=bBEu`);95HK$}v+%PXkorV%%JBjW2i0<1$7(mC19b#HAN;@m5B$nf;p-0m z@371Pd85*;ET!&p!PdGIS9QZ;AZqBe0UiLAHWfjNf`lifm*aLzFz*{mY5W9ei>V&EmjRV2EKWCd^|k}a)~;LfZXAQ!fJ1TKVv z1ezQs?Ls6&PGGK)UKPoHq&ONil-p!ycv7n$ZzSPe^sJUY27Uy%Kgh1xGm@#-vhD1+ zIgy-EEtM|>vU&TF0fV4b7U%p(;oL~};{u%G=M*Qj;#UG!eXfs+g0FcS6Lx{Z9{`@M z&N>T~x~1~*Ku#>Xw1K}#zB=X%@$U>|t8>!60hLBeKFRp!MS8RG(^i}U>yeuy613rwx22j>V0a{IGc+{=M|Rz@>>_tcWPTdB z13<%xe?XMv0_q33QnH7Q0Cpv?VV4591;FsB0JO@oVb|mHC32Pn;H$zTbO5xA^DUg% zhnGAFJR%B~NErSCFiYjG!0=ZU@N8h%djReS-{*yr(d7bTWIuMtJoGyXBU}W$yDR1a z$RyJ6)scG{@CTrM2<4L30q~vHQgVl#0LHhuhkXa&CIG{K2f%on@Og-w2)O-$Ksx|k z9q|9`-~F52Z3(@5KSClo_Z@~?jAd>ZzXFN(jxP-o+e>)A2az|9KSIRELHrd&-ZsM1 zm9nMsX%NqW$eTuTi1;LkHUtqKK-cYOP_32g12)b$OVt2{*Ca|nU{Xl!1uU1wXv-A8 zr|@<`)02PG|HVLVDFoEbs2qU08BGA7ZbrBfakYpzW&q-?>wsY;tn$vlMv475$h=7% z36VD{@?wygoHGWQbA@j`Xp95N;>fxErO>P~8DMTTL&YghLt4JU%A^H)8pzV!sNu8m0z%7HG~B zoHmb#&w+Ma3|19~JK#+^ARob9&I|DfPP*;fKJm5poQWJ`2F`C0_&$SlXvbK@sc{ih zz5hWCcnjgVccNZnBT36ZeYVC3VrJdY=uoA!`XXHOP znI`Aje{lMnoYnu}OfWfH|G}9W0E-dtRIGA2KzNs%(ue;cz1ie^^AFC;Ca3Wq96WVW zHAz5oab9QVHmZLfoJO91WGWU8Q;;n@cT?hn{~?}Xa<2LZr#CpP!-9~V92}{b(svlr zvZv|QHwBDPi{c&_Fq%}|m^tgH`*4&P*_|C>q3W-a)8}AoCq-Z{9UOZBE}At9&-avE zf3<`+U}GV)Bs{~0#p-(6TFL<;`gi1{ZNk0L>jEYsMlR;e;G)VMG_8nE&> z^&*cZth`JMr>fy)n&FXNqyY;DW8kc9F5O4orS|_r4X>Zkt1>e*oUl=eVc~qmum1}i zg~L>ZintgbrbZlwH%%5|RN>xgn6Y;YEedm#jA16vkS~~&49PA^5{mpf5b$le(8)vh zB8vk(lH|g54E>yqlZKo`tBZJxK4+tZVfDO%MZtVZexM}FJL4xHsj-bm0LJ3v0~^PG zcNjGmCm-0jOqu~akf+W&K2(GUKrmJ-M{OA%PA?OU`Qsy{{{h(EwJ^{A^EKjW9s89N zh4%%MQEM_(j{_t3O)ysC-r+l8N^lq~R>NQ!=08zz4g1H9D){|r_;otorMGp(jBHGe zH`=&_Kh5CP`o_T9;b}#lTGHQWMYB-y*>QP zRVs%sfp1iHwW{n_2r8#Lo7KR1^y^JbH!6PunY~c?GT|*V8Go7#qw-}UcOn?9yte`X zk4~`2hAJ1x!nZUX=ilaFRI6RRSCEW_KXCzRk&6;*Sj9#oQ4mp zpz)GAXOYUe*c@U-OvdTIF>+(T;JK|Y2>>T0)|HR03T|dDo5P-AjQB%Ls8p8#?yz~s z(SBgDPwqz)qM(2i%rPZffgVw=WVyyOTKHHPN5JP0&1s?PrwZ?Y3B*{H9#@)ufqOSY z{f$0CtbsDuGCf7^HjvmPxlaQKkcsijjK8JSiTta{R0DkM=boA=PiTSG5a;e5?- zmKz*yO6S8J_Aea6cl=E>GCL%CM;IrTXOw7r#4iJjT4ga+A|t&ht4>T7g>le+r(`du z?BrI_NF~a>v>`eHvf34*s<8tyM=h>zEz~Qn6}eY|!Nrv*DCAxvMFmlYEGMfV$TEUR zQSsh^AOfPm&ACe`*;A?bMGqy*C1g*v0}v|Uw?Y9+&5U=6F9DX>2{{stp1B0B2eL^{ zTG`K@gt>fWj%z=|+(|1_m5B2xQBbeOf0dFghHQnB<&xGoZKzVO^A3irF)$7&T&rB- zTLI~Rx=!G!*H&fD-s+m`Ps7|+D|@)ET({?#Tx?ZuB;TKc-yT!0xx_YP7pv2aqphx& zwz~cl(*JZli>-d8ay=aadCDAnxnb@~RqJ$QS`_fSR(4RL@gAK2m8<#o5GD_!mYqyj zbG=0#!_^_!X-zVFMY+lN?C*@}Cgbm;E0z-XBcHv=9Sxl$od%AyR1Jm2NUNfq})k*?CwmA2^KVDW#%f@nOsVzxjrs zDA?K#No=r$X0vBiz8CdG2Vcuh&|o3V!z?4Gjg}jMYn9WpyDHpT|cx!FwdNwLk{eP%T7|bCgK6tvQ zE~@^lYnsWdLb>EkJQu=D*gpdzcZ|usD46-f{t?i4$f{m`VSHR1(G4N?MdRatL&8_=E*c;RYDfX+(P=8CJ3HZPl&V+ZH3xIy zJWa*40WleC&uJE}JzoQEEXA&|80+Tg`3v}TcZOvK4EzPQcNeTNO%k>)^c0>yz6(z1 zq1s}I7c9ZOPL};GFSoSDP-fwJ*p4A<#89SUC<1Q8FzO$9T4?$-pZOZy#BdqlF)w^> z#4c%3$ZxP( z_MFz{z`3!#`Bq~(MM2ND5M8e%)3L7HucG6R=@?!0cFmYwE4;<#x^z0sG0SRMun6fN zZ!SldDh6iu=~$A3rp_NK|1P}^9NxE|Fr+P!N5X~o2@tuCIA9PZcG3?7&=qJZ2sBp-*G$3Q!PScabhfECtg3UOtkIME$&+)1oF0>VB!BKXG=2;XxJ zJqUBEs!pX{J_qA2PK;vO@$#nqlw#%;fH}Au?tde}EiVUiG$r`f0_oy8w%%fYB6K&nl7pBdbJgcsV3dC0|0Ta5GNr7F~jz6kYK zkTx;YdR$P?F_hsOJ5MoGa(_T6B_&Wk7PQ>kVL&Wm z>Y$2V4Pftd(Aa~HUZCa90*!NlcZF%KPBAaCi1Rn>r+w>8gKS!?oksDYdv`o~o~|l& z7?m2<2vQ@$9>(2NF6Pee(;*NIf!Sb}C-c%7m$C8Shgie;E;C+T^v#1TH-Stm-eg2b z{ne9gtUuO33FI&f|LYWyd#R#BU?KocQ4bk>&Qji~ps{scxIptQHx-nP2Wdl$;yVTR zfR5^77UL_YC7*$G6~Z3Q_wZ%;Xo?i$8({{god*q4j0YO!XZk`%h;h%Lx3a`sIqnBH zS_~y-(zwu9l-nF0_Y0E2;_NW))+8ZVVv5HNkB1ACm;vKL-%xfYk4sCy3KJz};2#Ec)8iVqfN-;{AZ@yQa~aeU~@*wOh? zyoCB##dR^b8ozA#3{o@&8N%av_4jzyPiwSG@zab|CASzq_PBqY`D2f^xAZVPnrgFM zFTU0Mbw=A4d!bd{W~u(>t?I`fcj8-u*1$;^l_$1D@b#x%>(RK=NO)RKpbKkKSPEj4 zuSqvf91=f8HRS8E8&4k+4}S8k#8v^GVyNILjFe~(TVNI zd0X~}Sd8dMJ9_m7%@=qNuMlJ~Gcr5uZZK<$jgBq1t%OXsmT<+Ps|q+08O*0lRiZz) ziayyYni@vaw<}RLlYGZYtM?4R&mmyQ%WY{GHQm&+(|4?ZFB8u~wwpR!R0Q!Y@#DBa zwHt(!5O_Cr*!Zrs2k?C2>WJuF8W5KfSBH)7TIxc)1NjoZcffucSSAqZ3=2ZD=LyifsW{>aF>=2L zWgsZIe*m}~KwdL|JZ7)E++vOPS;IOq{gyYO=5AesV{8cHu(UWN-`hp+R6;`!2j1uUD*9CcWFJZ@@)f^?JdlF@Um=OKcF(?09_=^ZPzjzjK*nrfDecj)pGWvi^!*4M4JE>X6^ z(?Yf`Yc(~cpS~KVil&E5^?QxZ1{u}tfH7XEq8X$t^p63-tHSYH$rMGv^e-y4kIuHO6H1zJDQ-ZyBL$a7Nk+1y{>a-Y_|+cq#4U=%cm6f#7g zM?i}PEf$qW#CXrX&x`%_FB#2$`s+>iX&&uZf4$R2%@h9>MA_s$oaoYQ;QaIf`nZi+ zR$tyZdAl<3 zDh#L*zHLgYf!i&dUkSc|NlSF_zACR#Hs%%S8$e2kOAp0-ZL7xZMfyu{*>@91@})`~ugIA%B2Gmr zjY?mt`jEfXzyu3<7()58iuBmcTGq7r9vB#`3}mz#;F-H&V6ZYUz14uf)qtNdqan~< zmdGpcpKFehIqYJ5u94A}R(mR|=lbe9HfyflH^W9Z_10ZaW%JQio4KJ{We2I2XQ@C# zy$N=HYLWi)W_%O&H`cO~GIykJsFv(?Mv$G9!Q;@##>s$?DGIM`b&%Q`^smrv4f@32 zf*wonZIqX1TfMNm2MjlDl-VduzlNJwg?9&T^r*O2H}78T=BvNC*~1W_8CK;>hOVoYHQO+Gk%&zJZSh-lt=suy04t8iN7N z`K$6e(PtrOY`FQL>0P&I@!GmVz26p05N8VYN&GxtsITOwy|2EVpUHjogIlx?SMuj< zGN>xItGb;*-Hf@JZ&7tq2OHZp&dqb!6d7Eh$~8)KEkvh)CbxanD!N9+eHTPC@6vlc zp!L>XFVN>a0EZtH=o=o;it&5eA3UJBi+yxCTH_k!dDb$Gw}&wrzexTCwbe~ztj4bq z^R;oVzwrcbHQc?AJ0X@RUAJnJi%O`~UPS|rIHIDNnux%a{r1ZKcTmVaMFSm_eH->V zu&=+qRht#yVppD#>~1UY)iJwj)@zWIZjX5shplMMf<_d5eJ{gojHn`W{Ke?(%qpVQ zauGD~g@w#hM1L^Rh1t&$J*&{pu$BD@@gIQ)gqRFMpBngPE7+m0ri?CDP8qrEek;MZ zA=l(*g!q{k_&9j)GsEPUhWN!7_|VT^Z1R=uo)>s}=5{Tql#73PTqU6bfuM=esJv^I zECu>+_*Hu6qY#s^+D2UX!7SJr$Cp3EAl_<<^YuHoYaQB_KnE(qFVSnT-_DThEz4em#!q(F~!a2bmzEu>}e~()xS%E;!}y-3J~uw?L6! z^wO{e!tdQ%9#dPOUmnv^t#R#PSQc9c3j1K##xv<+J>@CQ<(?3RccM|Ju8ZMc4rP2= zX<+B-+fnW+%_xX#t-Z7+NI)tU^jj`3sboj~~fjrnfop|FHHR;8hiC z+wf}H?6jRg0wfSZ2qB$xAPE6N2t7aosDMb5-b9)R$PS8%3J8b}Y6Mg)$AY40kfVr* zf=II=3MzI4Mf9Kt`+wgvYj(Dr^S#&mf7iEjP3GzIOj$FtX3d&~{PI{!AI`2uEyVFy zOWzQ}(Q)fUw->B9Q;13gmh{+GmU6@7PDiRN`; z@(ydH|8z2nzso9I8sQ-*XtS#Xm!qBGd(4>kq&`GyBXd1!5d9!(a1*F$8-VVFkdeNY z{9jfC*e{d47U+J-UP=3BY6I+#$-W8bQOWkFQT?O20sbH4F9iCTEH~0-1~kS~W5+Pys8(nUgism{{0aach9~>UtRajxW!3wc{2kdd z7%i)YlqHq2UnODQzy?As2@|Ut2(Qt?W&Hw#_P>zO&&=WJ#(e_h+;S)~_*PiCT_C~` z8ExfmLcA$?0FWpv_kAD?5v$DHp%7+>PB(MkMa&S@$ux$d_#LAb!(w;!t|jO*k-nakJa9Dj>N!f6-33b>JZfdWr$MvYbhHS6RFf{yVJ8l+nh`=P>$;CXcXCFM2r zP~%OJlw@5k+8(gJ{g1vX@gVyu^(BzBLxC@W=ns-i#H^8hRp^mGc9%ISyDN{#>|XO$ z;42`R;>3Ga}2J^yhwNvoO5^JJzLGED}^=g%o=qm7eo6 z8k*U$33^4ok{FG8EkVDOBgd*P9BQmJ!;IWK@#hCP_OKYHX28f*5Xs_XcT5(hMR{3x ztW$1e)`Ghj+!cz8lNG&YIRqePWUh6Y|M+jrEnwaZ&6ixeb1`w)2HG84+Zqc~H(mLvG5U+WRvx8(;^ zcBb#BIPy*4qd0G%=DYYVh`7_%oP3^C9o35#93M}rj_OO;>*J6fRYf>LetIWr2;peo zI`QIZE3O~UrH&eT4hn4>nH6w9>ZZG3DdibZj1)Q2r^t~$MUM0-a->g@BYlb-=~L85 zZ!HpuXWR=b>cLN-o#f+4AN9~za6HAgMoc^-FRWW3B}e+G=k7;BCBCiV^)vFq`tpob z6UPgyaT^{E(uPMFH)+GgrFNz5#K3Q@=6z?PlFa*$!lKg7*iiCse<`NM1$K89ksL-}|O?Rs*xU5Ta$9jjo^5MZj_+Z3&q=Sp zLusdej#4%&*}ne`*&OWh>9r2rrg`Xf7C@B8FCUPO^09R$`ajecD$U4V=5oJvxpT?I zeVIvqo{@bk_&l?jWrWF`<(UVQcl8jre2*LQO+CavzPA#ZJ?sh%c7-VOOb>CKGCO;S z-w-$3uKUu5djL)89YHNTQug;hL;U)K)zZt`N;5N|hiLU9#-T1?<)uKcjK%4Zug0|JV>+{KG^i2Mnh9R&jZCI3 zeY+ewS#jX@0UbFHv3FvI#2We+&SN(6Pov%$eE%}@dqIoA_oG=*fR?}z@ms!rtkyTW z*v$V8vJ6p+to%sGGDMe{1^UTi%s%5?v@gdvgGEwzeE1Cm6Q@r{-0@*y{qH|o-kr(|7~wxd$k`$hC*soXRhVo_#2e0cw4A3c3l?zP)&>6>mN$ z9{I^?<9iLto)IQ3IpMp-(VwimjC)8MEopHPgDM6ao-qI4*zxku2DLL#S$r?uTjsRJ;rL110J{F*& z9ME1fV@TZ;WHj?jCbK$-lFmkB&NtIX>;9XkYh?f2K~kCc&1jhIe@E4t3;Z&HXGxeu z!nG2A3wTZ*^p`_3r`!dMtO-ngqB)-~;-@^#ZJZA3V3SV<`9lkZr?Z*ngXqt|q5Kz2 zLcRnrR7$olfMqO};{8uZ8d=ZKbl*UBmFX-taU7>lrxW0XqGs~0&Fo-0pr||7ytVZG zS9)L`fVuny5|;&CaFX!ng>tdvm|5hZw=ZjF#U9gc+MVZ?n;S?wIZ78=ZxrST7$RGm#uoI7j#1VI|J8cco5+*A zN%F!3eve>9+X^vxX0}tm<{wrs(;O{Q9eaykWP-EQ{G3fUoOg=W_2wxcN#Un6fZQNC zwc%}G&{`%rn<5rb=SHPtMhqkCCZ%LXWD>hsX_*lnh%HxYX2cL;wbw8d~!b9F^TMwE%!PW@powl{voG}83Fn=*^|(aR!+ED|Jt2|oaNcQKPf8>&oOjyR7Ks#v z^G@4(N+QMKx;kN1o!;i0n+3JJ^Vnw*kk7v%0u#=tGeyAw(2UI#NBcQuznkk-$ zwi8kNZ${fGxII0GDB~71z1$ZuXW);G(tOj*I|%$SFwoe!LSk++6UK-xjqSKLFH!tM zuoK3(Yr{Ltysv?OEXCW`iusN0ls11+%!j7QUlRoMUU{v7Cl!*CIZphuv7KZU7K)D= z+s(a074|SyzhV?11IlO0A~Oc@(Uz|Z{S}MWjg!<$gJrY0t-0D%;?w{0Pmjg zYwpm6P^R1dTC`Pjvh<0pXhXc)#BSl|rD*;{v2*B!vcbXP9pp={qR*1iAI3`WL@Ja> zqQt-R9tL_X=mmEnwF{u1Y=pY1_2fMT{1Gtn_}K2B%8kxjnf57Yx_#=;NTBptm@veQ z82j?HBTRwsJMzcK{4}ow@eiP*bK$JVeDm07@qLWlJdIm{OM8KP49U`l`BvT#poO4A znEj0T+^o@}eXQNwkMqHdviq5p=a@&crleZ{nFn4Myzp#C!oglf$I$@J0q}R62FUJ6&&pX; zkHXkKX{?YXB}=K9WOrs~X>P270IodL0!zF^wxo@8uM?z7XTUv5U`mJAq4E|29R_-L zP3w3QDA$70aV>!RI$~79ui_8n*;?SC8Jor4V@dam&Y9u*3q zP7itkhJ@Lc0f(asdvtApdu=6LE@gVHAlw}=((hHuUbjLrjEer`w3Ud>-LcBFBJ^NA zxy&A{CKpzw+Xb0URj{<2=32goxd>C1S<*fD9amA_%ue=2(1Y_Kbl<4BPRwd%w=#!` zRn6@9mJ_LUIK<}VE;WG6X2(;pOzduE*Z8la!2MF!?)eI;$iiyjMoP; zRx4N*#2S@a<>OGdA2;pFTmth<+Zcj^bBrj=2i!4lE-pHbc}6G#etZU^Kgdxl_D5UI z<Vq{B>l6&n#vo$i8(%D_c%5 zN4Bx~HQ;q^Z2dLhCy=cC8t_ML?4g~X#fm3BLxKM|xUmuTgJ7_p!*2{mzacp-$cerO z|E=h9IB!RvKmp^!N>y26da_-DHN=OL?XSz(o0wPF=EMlx{x?&|ahOS~<284M{R9lB zMbVfGKhi)q(sQ%L!M1jsUn=&nsknz1O8T3W>SS*V1A-s2jf>?)q>&*-J4w+mrRZ=b zddB+ME!lxmG$c}sp0Q}vgA8W!tx-ramu5|toZfvW^%|8j|LLEKX(@KRa%Q_!n-Eaj z?y6iCM((DKcBHpvibjkx5^y#b^UYD#=CN3OM^$0dR=~AUGL1dZ z%X*crjj>o-{&OU>V=`kUA)X6#>2tF{_{G%OEJ9;4>+&&IQzi0?$wWIrG~-t#Nn6v1 zr=pL7Ch_NhXYp8V^EZiqLtM_Sf0uZp5?oH#x3gpWK0}8N$mC+-`f4bfb=L-xJ0O!A z3UO5ghos~qz;hNt9D7vNZDaZh@ku*frcXV`? z;lLjSqhJ7ly#%@g_>e#c0N(*X!B1py4su<^V_)gqHv#7cN#~5t+POi0bI!$vyWT0Z z6vE288fkVmaOoV=vMhX^`VOk+KPu>3n_|t(J9rca6uf#OoL}fe1*XRx1KFrfz z^PNcRCX5hv1pKs^j?-W$pL06d`H4NhF-1@Z3;n-8d4WZL(!=iHv9 zdd{5o?u0b#wU#JRcAC$(4|JL(7&h2xmgdM#GbLAbnyH1DeO?ef3+=wv_dc<@(5^PG z5uX;?O{cCxR?HIX5u}RckkmS&ned0}%q-n&Q77qAC{qf(fbz^BI|U3Q^E5JVdaWra zc>d7dq4NrLcF>a7BK#qA(pHHvMRr?1zw>1NY(6kvubKW1fix-nvq@pIS|#_hNuPdW z^`&wh#yn}RhfBkAK9>VmBg-rf%ZQ!>$4<& z7w{a}8n2dkBis|V-$njxGZr59CjJ5OIg&pCIC|KF_@5iYT<<8RVEv2UKiC^3%bh@erk7jg!c{Ji$vrI|7>>~5Bch| zD(uh9$S7R*QCpq?FEj3_Xi;f*j_gm;KcgZsHOA(Iah3MN{=Qi8Ft;^*7zOwksvWsN zK|YGSrfuZ#v8^fLw&ftlI9UMGqe#A0DwzDVWrmcyRm!O$=hmilDC1C}6eMh)wd#OckD$bQ1ZgSQNH5HRR-)3nDWH`Yq?M?( z{8Cc-m^v*N$k|vH#k(kq$?)5(I}LqR6lY`U>lNj|zoJ`bW2v@?xEyH}UPoMJUEw=` zXBJE_ysa>d8R?CRpm{*1Ve*rpepL_$r0oo8_kgsUF^0u=AhrsPK$VY6m$nsbWZgia zdt=|7ryor(g-tabyEnEJ?e7?p&z5Cp#6NJ!=dd_JhtIIZZB>Sz3>exPWM^xT zovlH36r6LIo@|qJBX=gP6*Sp2UC&K(Vo+JKnG{Hqo(fhDRXRu&|3nZnzkqxOXK~3h z3~%4&$RO16)syGUexOO_W&mtmts0mGFM`H);tCt-XIO7PHq~5BR&#i}^}> zSwMTf)Hc#zA-6(t9|&+OT<$t@&qm3V`B@2-*|SkHW!a8?h+@h{`kgH52bAQ6faC*F zkNQ!K?Th5N{;-lY(ucBpouGu1(H4~12|;EjyJjDw1Lu9JaRemK`x+X@zkM?6vKTHX zSUUELgpCeX(?an>l^qu&+w_-G^A0p&qeF6$NEm>bvt)cI8Q4()#=q#^A)kZ6kw10k z$#$%+i$hZMJ&Jbxj@f?P#|Eu3@wj9f9Y158-Ro$8gCzs=dUh3E^j|4`e6pv`!+42D_R@KnAn_T*Whg z&AE|nXyzKwilAt89XB=>Md0B->( ze-OYq7(l5S*TH!AM?tXHZ1)@Ge2F6LD&ecK<2zG&Dse@P9hdMZB%&d~Q^>np@SUfJl}7>Cb(L5HiH@gS>qV4El@ddZ z@qN;npM28DA}*cy453R$3)kX^#jZ$7GqH*@C8k!QfI{2Vmg z$d>ro@9zYYizE1WK*t2AJ_}kER6CPc_A;=k!17K*jD1=bWOQrKTsGVAvZFw4awJ|2 z6eWq(hsdQg^(1I_K)IV{l)V7THc-l51MrR?P{E^6Vh5*qfo(H)P-P#=a8Ewr2 z?MKLWCb4WOuulEZ1Xcpr15sRq#_N#lz6u1K0c7;7nxihwg6RNwB?l$I!F~B091J&x zDeQ=h!!=rJqReiG&CVp2MFM*OSmp|-vv)=3#G!mUP>}gSgVMghcL3?8iDj37avYQb z1AU&`Rk&A!(P0kzsjnh9r13Y#GO+97)*h(A*( zab|BJaOHj<>CHXB`^dNK`bNABK8|1QZ6$?^@JsFI{eQKG-obEPf^l+C;nQU`s2mJu z0eS`kmj!q*oGGLbmmVs-CvoYa!Y2}!9v%#*hc^?K9xDDLz?DY{hr^Xi)ym_y!dW4E z!SC%27b7pTr}@)Zj6{VSKT~SOY>|W16^XxZTn!nkH5- zUN%kqgYl+m;`QNn>q!OE+2jz?kezCZ7#siJCxoo$_(Di)5g3#`f0#Fi0uqP2UPI5fh}jER5}R~qsvUEsbH z@$n?Pl`|B$_-hjCll!jBm7y%-lqqkv=^Gz=cpvxs%^Gz=^bTe_O`KFfza^Mot<_bH-e<%;7 zd5>53Cg{j;t$NZREZw+A8f$zha9Nu7NagXs3m|FyZQ9pi8GE>P0b6*m23t1=Y_*fN zRtIdggDqScTS$;a-%fh^FXGZu3SgwZOq{yH&b*B0B$-b&(w-{oR=W1|sYcB9gO_Pf zpK3(q_lZm6Pc>pOTp%uuEB?@7V#+9Nwb&z8jnaL^tG(q-b}D7EAxK;9n^;YKoS#oZp|-dv+YheD*- z+oP*)8y%=Sm!Ye!x3rscxwhN;Z+3gbF77|>0oxrD8w@`o7LU>1eHOxOJ0o=$|5=F4 zXpO4=&q7!Tmw~IiRoo54WeI;4!h-k#xJu-U5M8((a@edFg=p`0N$BEE@ zU!fCT^tXf;$%My)s}fe+$BD~?7s-VG1m5R@7&#VwVPw8oJl2jIAS*Ln<|=WNHlFSp zS2d6>jiWMUn^C;0A*=F`*^r0Z#HV9*K^=GK?~#DXil z#qtp^g^`Xfmc{aF|0!D+%Sf5Z_0UumFcNk#ifkf5dOK1k`z3MNv5s_D1D-LuUmYd! zlriGTaduC0lla#-d!<<~mR@PctD-q>GatjDpi($))AMVH%LIz?X5p1JIfB zWtG61U5T-sZ$&Jx51DAk;49xKP;;oItKd-+Xx%tmY^w7fDzi}pEtQR-G8==5%WMpl z*_cCIW<&AU5SQ5)D&2ktxGJzqCH^sR+=JjoScu7XQlCD|&LZpE0{FZR&LxfqupB^d z0({?R5`kF&Rs-lv`La#GUI2zNz^-Zxi1!qTHZ$!Qad^7jM5Iiy-%FP@@w>^IFb4h@ ziA1n7gbQtIedRmF=`dEbnQF&JO6fNw?fvnh_f)&JKV>qeg0e_BeNjbnwUh{-fGoY1 z1Cw)1)>Jp*59b4)EAf@U^U9&V2+8F@Sq<0NY6n{P5@-zS3~8&UJ?Jvzz$&$?nTIkw z-9Yz;I(Q2@{?gw-I}KB%jiT|~b|Qcn02u^Y1L#K}3&3OmyM zD{a+Edk8Rv_W|Jbef?ymn)8gifce!}-VeQ3=~#L~g&6?6lK}8do>Tzk6yFYUbg@P@ zWhqjrMJ^*i?Wq8ayr&^}9V(<8g1StO22$oji7$X{hNxNRUxLxG^a;?eqmk_Z?j^7X zz>5Tq0QiUiKM4CLfl~lFPDUfArG25OG?=KOrew_oOA4|!LzcM4if0Zp3*ab#0W{>r zW$;%gm+G79%4HLvCT7ga*7XE3Y5sXaOz;f=1NahMQWyekbYBTXX7SKO@#G9UJ@i+& z$(o%e{+eOOSt*mmg&D|s#Uv3w)6NJRF^T!Z*^!+Bd5o}TPGYenc%GLf5-5!*|2$@X z3#xrF)Kmjs!_2=7(${o~J0(J<0eBxkTL9&heg@KPRX0cy9tPhEvxb{*7<{*yHFxAc>dWO z_3(VyyuibAZk6RukCXEP56^o+l{-Dg&zBF+2VR4R=lTs-;M)=CNAdd4R zx4w$q%vaoVC}3Yt!cN>Hr1v50HS7emGhe@@)Qj~E`jdLUkyNAfrlMecLzUhJ+PF;W z#Z9G+5riY+rbAvFT4X2qZwEE%XQkN(-C)$8QZsTFVN>pM@J8MOlTnUDA|m;2Kgxt+ z(UJGTP*j*iVk48tiIhlOM0Hh_5fyDRTM35m5Lr#l&8C9Bh<6}gZdDaT;cKz)AzuvAg^??U(gAr%=E)h+Z+3mO!s$`km36*lA>df!CDexXimqw~H zPrljh%)^gg4)g5HAHG?3=Bt;holt96$emF8R|NJt??p0lCsfQz?t~Jzt+aRaVQ-u|kcF^5kcBV~WTE_}gk$6OQhqq$IKvj=_EolfL`$@MaXVVRxE(ED z+>VwnZb!=(x1-gI+x8-HY?ZB#XlaKlRG*0O2rTl5mZaOUj1?&=Z@2XkEhiww6A@}} z$DYLN#KzmPPyI0r>*fQYlhOUDhpCI;R$3O?9;k#LLz7LHt0SA`vfMu48BasJ1!^l} zzXm?kz@HlMEp}zf0i;rRga)Q+U{$7uHn;#f?De=TGW&Ff2jfC-3q$lc+{nrjcdxb+ z`yMB~TG0$5yW5+6uU%b?~H=yyGmnHS0);J_JvODACNUiaX)Hoc_ zcu#7a(;9r4$Vly4Dqewx+AaR1)Uao3ubz?`DZr&yO5=N$MxFO$tv<7?1U-$~8dWFt zI|cMNNc~~dKMQgBx=iY&EUy*bD%Kf1FzZG^-``#q!wRW@2YNaCDYe9FE&wx2@|H-R zk$E{=&lO%-ORopGS4eJ_+;Vn>mn}R?ZaKTcn~$q4OKvlB>GG~v!A9yq=BCu^ug2D~ zfzq8mjdgZPWp<`9J2#awtE4{l~CTZe+Nr}yoVx55-g`JB<*`0P=7b$qD6r3#?C)g@G z2hz@#Y2O;7v(Z_KJ|RV~5o?f^Dv2aX|BCdYDXhj{JiL-si~q&Lax{uwpzYHhUVe&k z+GU()37qh-87amIm+=u9hdgW^igCzga0kBmvIq6tEq?A z>N6mu^W%nQGl_piJc_$Jb7@BB+r`tuj!%(I=z|beapD5^;-YrL0ML23 z_zsdIq~v-jdBuN7%8tKqBg-l=L^u6MSp;>+MW) zinwh(?!9F)KR9&gPn}FxIAj!dEfc%e+i}CB#9k?paINd9l87#b)teoi{ur5lMsuD1 z%~Gc{SVv}4DGw8QciZu$()ti7ISi7jelL;h$Mb>9J{ES>tNxRmrLZph*lpK}8}7E# z%>CkVn2D5Ta;2HQ*NV69#tU?3#rNQ-D=tiOc&w62AVMb48MslHgRGl-ZRWy3@3>m# zVoRLP#a^3bb0b96%IjX6bD+b-<;v?`xm4|0gy(j0+<(KCy1=_`hhp=)V5v;@Jm1-G z!!{rKlvFPf8}6|atY)3Xi}&cB1=B|;bc3c!=_Z-dEyQI?H_4Qq3#7DMrgU_XXnZg3 zMk_lb8<)y#AQfYv%*M2MD9f_BR2n}UFn*~t-hHt)eyKFR5V%pes1&B!2TXO9rk)R& z!rLkE^JS{awdnRV6=yWLPTOiPZS@Ck6n-RLx)*En(uemfDz2uSRD923QF@kWz4zoI z_Z7tDaQ&WKw7vznD%$rgPO07jo-SwpYOVfZBLMmKqoS3Ap`7vQv0oI;~m zTz8)xH(9zLB8ibpF|md@gZa{(Rw0+Qahkrq4$+OGA84JRbN(9kW?}^os%aZDrKEtw zJmT@J>DT1K`Ta}9ANSemol;3!8Zb6n8e0-Dwp1G1Pvt2}l3n?qOU1|yc6!<+Wl*jR zD36!Q2LsBLQaSB<@i>J2JZj6drSN%7%126JmX@k8TMA!(J&H8~#mJHi2h+`UNit}s zF@e{mP|iu?X4t8gb{>Fe-Yp>A4g-020(g?ZlK|c%@Iv%J!}tbJ_xnM@@vHd18`|*6 zSWjK5G`ax*`7H=gH;2Fr0J;;P{hSm#!(`@!m{DV;t*vIjvaNx~q+NtzyjAl{SfN(|8tJ3aMEXY@l(PrVu%xx(zZ zBC8TBn^}etd7If&FO5dtYWCFkzEQaMgND{3FH zW9#!?u(z4@gCDSe3Bl5CIBve1FzSo>NKA}j`^wNC#5NcAKWI0Dm1Z$!cz9`e=WrAJ z=8@nN=^IlFy|@_D_BC*EV!!Qe;I@$55UtxXNEZtf2~E*Ru}{3P5TpscHi0xlsFd7XxhIjf4WhV#rDck=D+)N>E#5+>oeF~MXSaCfHmyN| z{PY~7TfEGtHzX}S2^q~04fRpMC4~reVdcsQ{zBW}sP# zC420a5xJlk6h*a&SN7ZSmH8n7uV||v$H{+-yfxI;g6y;jCs|A?a>0AUCR9 zG8(d{2+S`FO6OOWf*il)$vm!oU96D$>YkpUStZY103^rdPYM#UzTxpK!)+j2p zZ%mSG%$*xN!9d=ihjAfTTnTq=@Dn3>xM>*WVXo(mfpl+$x@D;h3m-0qW5Npo$nPdE@fA0&VH9s@d~;vVRXB(A@EKQa+p!$H}GI1jP@6j-qs z`#u)zSBRzW+nq{clhE74!uU4oYo_ZF&w{l6uxfd->T4fGTnze2#M2R1i67p#bIr-3 z%`vUQd**!lxt5R|h{{qd}#H1(}3{l#4Uon-yBxfA$Y+ZgDSWvUpjd&|eE z`omM(#r?-HLhQ*=PG#q+PdDjLAngav!RH*}ClK>jts)t3%EL$PkXf8_J%tNrj7+?aOw!!!dqH}2Irce<&6LwMMi5S!E8;ZxM_DRX1{DQ|vC zhe^8p)#AT?zmWu{qhHL?FD1P@PyG6^ogG^}U3*H&cM+22i_%Z*#AN+6Q9nT=pLL}l zL}o7%3qP@ovaegBE$CHRy;iSh)zoAj&My`peu6rxzD`&t5j#sn=1IF(re2HGlVH8J zsh3&x+R({banDJ6S?tL=o#MG#b)H-C()xl=?S7`80|mnd1SZShj~EQ1TjOjYgd7A# zHH=@;amS{jIUy`Ys6}9>t@$4UPC)0KgpiG(>1BW`5vC)sQ`dBSXwUEE*Zx)`Y(dZr z98Ti>op?6-1q4k`0(=hw4i)fbqk9jg7rFGfAUb915H=wsxH_}JUyi`x0k3K(6Pqy> zJcF+{S_o9<7H+0NFl>;gR2ULb} z7*IK=a^TbjeyAIoSUH|uAfzB@I%P1h`uWeh*bN*=bpkpjjRPwK2UZ3StPC7j891;q zaA0NNz{;V)IIuEsU}fOI%D{n@ zfdeZ82T+|;!X5-KLW>|e;S@jqr6S}6F;aqPr9pHW;=rp76Yl2*4!{f?fEhRdGYm%H zAj|=nfdeoD2Ve$2M_>kyzzmxabOMAqpz5m7^zsVB+Y6x&LN&r*gb@guPk1E4CNwlpWz&W&ajS2OMnr1O?wCx zj}be+u`7n{1AGkOLxe97bTXV1aQxR6bWB>4u?=+233!T?<`d>DK$L%Dr&}5I76aR!HxNP>fK9&=sK^p#q^2 zLCb9id;;M!1kN5bo%ksPYy$P3ML37>Bf@!vpAlR+(fk`bUYt8)CyA%e*m;D?aTq+H zO=s+Mk@t-q?dKb}&P-$!VLO6OA|3E#gz0z-kJXg0VZ-5!H3rlTOepfZ46JNz1av0!Q;$F^O?xE2p142 zlY?**g68ur%nH2m*auaQeqeXJF+qaO%g9jGf1_3E_?y^FMexMP8z-#mUcYZ!|H!amKJ>x@!ID<(v=R zg`nG>jyWIX98lwgSt1PY!eIvPPhy)aXRXIcl#@W&N2C+tRFHvFKy8R{wi`GBbT5r1 z=mZhQAdE-Qok{y<056iI|m*sZp z(xHFho%cJ*%}dMd75*}NUXqRB*K$lxj^_ru$*?;QIIW{OIkmsCaEh*pjaPQmbH6z^ z+8$2K?03XXjy^1?LPO|x~ zc;4f5F@F{3Jx;NQvpoAgQP9ZgpUjz_ecWrtEVCn$QtUZ7-MV$NLg2L#VsZ9o|135( za#B+`1GMiArCexIyWB32%+Jr)lAIUX_2L^yw&UE;J^{&1b}TGTqg;NW`%hX=K0tMC;gC=pTe*dW&VwHo4DJHLU~BkBZ_$q zD{@`6L!5%z?~1RzPEPwj!RV5ltXb09#}Q_7VsdU_=B9Z%UCvJJ-$g~JGsnXjs(o1e zGZfXpS*m?rd>QH#$2{x{N`uo?`x%iJ=Ctx~%4&ZqhJ-oYJe;=LPmA?oPO^tnS9^`v z73P$BIDNI3-xcnZ_2CTG7ER5hwz+n6j(v4bO+uHpt@69AwW3v)IkmO7{|^G3^V-M6 zvT&zUBhGv6+Gb*RxRdAM+}GYBE`&R86+hCHNQv0fi1 z%t)s^gLfOYh&MY7$Z9)qTCSaxly5J{$?bwa%ctDrl-mA6OpSDsI&)fWFK=NstxCpU zTYGL!9)BtF8bE8}blcw4!c0o;(*GLEQU*BpMp>76x_uv(Y6GqAe2F+0wrZQ7*e18M zL4p&0`%90RoZHb}m~(%!E^^)g*uQ$rwij9C{eXRIBUk=`_5p>{Wuj|SCo7IO2KK97 zvrUf@6p9t9il7Q#A#Un4Yr)$D`#Z0h+$OD0a$asHePz{k5nG!&)2#AtBC(m1V6E;Z z%9=S>$MUwpegKzwo^Fd5%IjZg=GeC7bgzFs-nq{9bEa?aH_#N>WumO_=w*dA}4LENF>}A;I>gw~Bz}{h+&2*{r-oQR=n#mQJx{`UDV1GoJEVtTgNjXD` zOW=)z{YwyGefRqBS~=0SwYhu!UrEj(+d9`>98PgsSm_n@XHuM=&QQ+nvFkBb+u$4@ zn<|ppbkWXnwr_VZle$dSGMx9@oz0{?IhG`Ox+2Dl#%@nMzK2+r;oNEstrXFjPTN@C z1=zQlX6hELUsqY*JJb2yPUOvi{VTGWn0zR2k{w!R&q~r4&B;+>Y>v|^mNy9YbCwx1 zNvkJ}7Hf0Ra??lGf0W}4bgU{IL0#x1SvZP%P@&Vy!ui#r&>3Z&8!i4_h>IX$O#SX6 z=O^33Ec}IHr{2R^wf(C|FL4sZx)Nuw6+5>6REcwmi4$V$yLEP6a;yX6>i_J9(I}g9 zWqYS>#@V4cx=C=}Y@f8v=Bdevy2?0*uCMCuG;yrQ#)~mMop|fr@nTU=r_d^!AfE2& zq+54Q5Fhq*vaK&B2yZW^i?w{B=-tbyvKCJgclL7ftfP~}-d;{OD`j%Mx3^5R6fI#g}UL?dMr=7KVvDi7uDYCF+c7BrcK9YbP~}lYsHkSolFbMW_Mog z{OXJBUEO!kXuKgYWbW9x6U3@or)T|VwT{oq>Vp%wC3EOilO|1{z?UdSkDfAfZhptn zbB*rR6$L%2`d3bwKV|%c+2WV$olfj-ESV&fNN)H#*;2G2>^<8cnIIW>1+g6Ru3TYG(Zt z%bij)ZpN&6qi0VTJAQP>4taT_$6k5mgz2NlO&L3<{>xjOBr|Es%=y7eqi2krJA2B4 z(Q~gFJ?F}?)5p%PcW!h1Rusi%UvI%x$P>^N!P8I9r{`cqBDrtMhq2=Usdx)!i4j%)SxE zdxiNTx`)dosI4DWX>04n(r1ter(Rs}*W_}sm1NGdg2^Yvry!eE0-r?~jptWmpLGVA z+r`#r9UNLLK7H0nGrtv~+khPqCEFlbB!(jj;dG@|T)h>P@!~!*Qp8K!Fv~n4K4nxU zLY_lZCo-OcZn+r#97MK@YoBu#g~;bs;+N-~mNoj36*Gs~?oG(vxG-NdvZq#*nL$nw zN`c3^#ibu>p{$p&thwe-InD~65M7>kdWUd8$HTFAoR&W8fG;J${gr(xSUNoM|394Vk9mH^y+#i&de55>XE~2u@X^7 z^0*>526C=rJ$y<1!+hTE;o265em(|ELZCbb{;%qtL_cBuNUWzXdX+iK=P*;G>qlhW zNgo*Ib1K4RL6D~(n^j1j&!L~B>&Ivp)AeJu9+bZ%Am7o@&)F_k(9hj8T^E9U4kv!t z?lezidYmxu0fY2$u+PzAyUN7b?M{n{l+jPhHX{UBt{6oMs-Tg&D=IFF45=gt-`5E$zw1(%qLdO4dm>XynT$fNUvo;=31| zsCd#i^N^1-Tp2E0Mu?iHofxrtm*X_%4iv6A^7&bX&pX1Wc-1=`$3F%<&Pq7dqz&Sn zlmz3Plmz1gFTyz~3FdRHG8i9v5q@a{K2avfS&W0kS#WfKlNiEim^a{x>3Qf?U%)xe zW^`sL%ehQ2&Z$f=&b3gtFqq-SBf;c)Xcg>JZloCdPp5S%Ki9`Wt>p5*Kg3 z=pfZ$-v#jMYQ2r)ISn`>K=XsRg*LS}fd+g&@MeSBnk1ot)@nfEU;3 zYsb4x%z6cd#0$I`The;4bn75~PmLJ(w9`x^y$Xl(K&Yz`nXftpp2>iV28)5a(dgHS zTVBNgxlTO!s?#a-95}-U|2?bNif1ey9LS#8M|9Z(xBG}I_BbsOU5lty9|*-cSjj{F z!bbQa)Fh~PIP=>_Y~AB@GS7=|sCQn3zJ|$0r6_p~=}s0`Fv7;3*PNK9E3k*XPq?b8 zu)*PS%vmA+0g0x^z`6j|WE5(cwJjX2$v7rH1p`n(pdC4?R7Wyq<~k5f@>N1C+2zioS5N6_0AglN}NAN!8k8Rjq|Bnb`TCQFv-*UV`SGqR-+f2 z3_E*Ph|i*a4O+8&z{t8<@t?tqh)e+nC+i(zIANV<0?n{@t$B4|2IpAwM=oz{KH zUJtc}k{!D&Kn0FApFU7HU=z)VyYKd0mz6>qO z^3(KzfP-<5#)WwZ{X}+a4CCWO>LGM8*D1Y=yv-O!i!F>U98Z674YPJdyH5Z~qEJKgxJBk2A?_q?Uz)VDarOA`Iuc&1BV<;Gjw_z>b` zoo+`Y73^16CXE0)zPFv^FfC`8V&GP+34*@xZLEk@zwJ0KqRI`+P!GI~c>xu$&Fc{0 zP_4X8E**GWyDi>Pes+Dw$)Smv@2LFU1Kdv)J{Q#eE%8+s;j1sg*ItC{-DNsoe6kp9 zZ~aC1Jq@^D=DyA)1XmE7qVBwd>9s+0o#2Lx^!2tjeK7^=S3zIXi{vB6B<_0?hu+1U zg}KM7o##CV8%_Z8c_$ULBRWBlvs4V?Sc5zbk35924(WT}X^}ygKdnxj&uT}4rY|wF4fz#gGkgWIHhb z_zyYJ{sX7E|3Ao3*P9)+x^xC~z4=kMV4ZC~+YU}%Z;sUZT8_`YgXQoXyt#b4Rkv{Z zOoy-<{NV>qrmWJFwQ8~IVq*|(sA|#v!=RE%56ZeK$Sc79uMLD&suBKP?)Uvq;=}%{ z_!M1`%!AG_K)G-Cf5P)FlD`{64x!VE!DwLzojReL5s*5gTLTP2D;0y$>Hve#>x#kXvjBsT|0~5|LtZ7=+3cgVD$UgU~3&U^G6!AT&`i7)=f^2+hPdMw!S=z&8argl_&kr2gAqedIsj@A1e2r$N|5>Mn!gPphh?E`5)xqhRX zv0`7M*~dWokZhxx(UE+Dmul{5kiJ!1Mq4EJGR=J(D9w3{pFG+BZnsg>7l6JP0d#|O z!sP{M1YYAh<7Y2PQHXIf0c2c?HrKBq8L6x3l>Q8X?SSzG3FmJt!iBsL zfpo^JB%JTx_!t281eTE>@Rdf^xkeb*xkea&fnXY!FjBVjr0vBp0Wu?HIxk?2&syF> zKxs1K#%I$QtQ_u%`3>+Bl2*g$G=dlB{1>KNZM4})OeqAK$x&<$`4EAXgNRRmM9t8U zMDg^GPQF;3ACfHc;zFXt$DcY~ozV{Ft=&I!`inu4Azm@&7bo7&4J>#+l?E8Sh@jdT zph?`sf-T)gkdEB4WG>zd6YBgF7R9ztrI)jxCs+?8_Z*0&Tto0P*KUIh5N`O%ng32hNQHsHczAJ`ysX?8b(^PCg4&)({Bvcs<^1AH%sabW<wOC1ZOR-nh@dm~8*>>jim>=BqU-yaF?9kg$_+-Yes0@WDvRS}T2FSI%z z+VEwapQh-GUt(J1Z4|~)1SY`P^>&%|*5KPMwBs>;>@-1ZA*Q!{V+EHQ9aO~=xau0X z!y34%jA)s!zjQ^Q-;9-^OZYa7G8D)H4gII&r8G)u8fef83=w0XH68)&mXR`lxe{zb z^5r@wv%p?1nttsh`E^n#pDO7UzHkcB%NVgvKws}?!XGN6Y9oP<5g^2f_N8)zN0%`> ztR<;TfK?=g2&~r}0DiY6HH>7gb>@-gzmh3k!srx&ZOk(_{s@4n1y%Ycxcei5W31Wc z-$=-mibEKw#!iNIOo_o6mA*oC>Cl#&_2sfLyIEQ8r}u7KX}HQxL7b&Uk9DcJ*9;W_ z>P%mB!BE)$cdbjbgUDKg)+H=4rb}V%B_;97JM35EHFs|x1v2U{!N8=%hZ1NZ3!|D5 zbB3yO6Y>*gN-LE_B^_@=mEdm=TrP0Syim!SV!*+O24EIHO$>9J&vYN+@t)-U>lW za)*(7LV+V-aHNt9bYv4DN$DoWnxX4V?_Vv7Q`TG}fi{6;KZCjh-Ddwq<__x)hrC#X zc(LWQ6X(6dBGN2TJboGvVwwR?5{FJZc_B#vM+*Cl(>Ej;V6mt<%c=9H)EUf3 z=>+;s>gAJv%_FJto0x-jEk5ina~^t*^U>vU@R zJGm*6$_S70z26ykeUItppJ$z}V*goZNmmkM5gsxN>}u3KT55RtY%4 z>Gw`dA6M_M7X4E4+Nbj_?LQ@hO#jc;M*gQY?aN;+`s)PX;l;lEuT%Jc>#zTR=7b>8NVyxjvG%Q{u9A8hBQG- zN=FbiO+sQsZEi?*Cb!xzM8Ji@=q?0x6%*Q^7>rUfL}On_zI;oSuL(e&(JBOwG0O=3 zv&BZjTM!zdcdaIY2pg*w&{?PjZ4&}A_%Nc!6sWm0dn*F-!B|NSRg&S<8mbJ7HX}pY z@XqPM3hu@`hXAiGAc|CeGx8y*3^f51s~C(@0}Mjh;?93L$$q|CF#-X07>z_w%7n%! z1|$0T_s))QXq-ZTCZlr*N`R18X);Ot;-|L-=rS8+E2Y%OCiHJ%qSWxhw1p|r}DOGA!)ImgsT6~nD79Z`P108jAr2W7FMLvr2|L=YF+3Q~K z^qYP+zn!)JYpuQZ+K;o(K99W*g4Shho)(a-3$uu8NBNhyN1$=Eeo zK*GFJJ?9#jO$cz1usW$nZ=VAodBxyv@3XHAaIqy{T z<}7bzSHuyZM6yXmN0V&PT#|w!Dugo=nvnBjz&coIF z#GBDC&%f4f=^y_(T9pca>G3t!as>A8VW5kZnIuUgf|{B#vQ&Y(tY${&V|W#eXNfph zpFuz|NeUp!}4K+*Uvf5cBdb*Af!08cNNa z+Ytzx+?gPw&C*a{4jbCyrUfV$$#tOuVcCRe@c~l#KV51|pD0TCU;) zn@Q^s;1UU6E>2ID2zaDg)vL**%d|TXP!tkwtDya2>^UtUc_9=q_M#S$yc`M`+oc60 zyF&qEd-`}PlRb!Y-v*rtWBU-0JIU*zfH7|E009Ya;iXm=_khUg_y1_p`+wRzU5*0; z0hy9ShdO!KZ|b0!NFM|HORYh|1kiX}Xz*R!9SE#Xkf)V$4T<+B{L_VCjHbj59H!f@ z(#1(?m2@a~AL1Etc!fhTZE|92Y|BZikVl0a zmwft1`56TEJ<9UWt(9cvZte>s7q!9+2%iYAxH2e-_pph+XHw)>RKi z8EuQu67Y`JIpsZ@AB>tzB+odu4Z4RA#3B21xu zasLtliAY-O^d#IpqcvxRU-uaHb&rd`cESR3P2KA{4aor&O?ss7X*LNhi}rX3@L4S- zp^a4U_li-JR!L|h)hfB4Y6asb*F-$0StK-})A-%a zMKAD-8kbe9)@mecb#yDpHXS9Qt<(&;N~2yYkkCr10ykkfgMf-4p}tf={?s_DG~y(Y zYqUnZnX&T_P(>srsjZ?8;1(){7zs8!hi>&+5bBC4#WT^d*CXyAEKuLx&o&O%^I=FvdVP?4QHJMzlxsJ)sF7?zNG+;Wh)V@~fKXwRvXCIr#;T;Qz3ItS9V?Y?jAR4fok`7(8uuxU zI0=nY!DdH=dz3u z>n~T+%tL@fBup%ZAS31UhT?q)u5(4b)2W%!*A?tf$mp9^dH~UK*m9kIlrma@;01|I zujD$P7y@!9VRot2VHM(3n5cAb&qAY*iD+mMDpqqIa+;lqV2!@Q|DCF+K$W z_m)VeB5)2nGvQ*weq*L^S`5Q_Lzz|L&Eklylkh%w_y6i{uHh7_y+tD?F0#P zNzFG+;Xl8lPz%m;2q-@Z^;0cSVV6=!kQfDZe0r+8P-7{Ayj~@K1R;DY179l-S>eMg zvK~-cNs@;UvYmyEVVPHgp{;~%N4Nz+bw-`PL!KzZ0l?HUu%E?Lq8JGs{+kN3zoU=< zXBU44Lu}0vd$m7(&FU zi;@~ERn3e=m?b2nEdw)E&5X61;;HneHfi#-vV*H(&^9Wiy{6p{p2+fJrCJwWOjAsr zI0!5&JP0fcSA>53DXgMuy41bKzrBO|i8m0*S11!PlKT*JsTo_T1tjz|wK|wGhM>+5 zpc4_`$PAEr9VKa0(JGQ<2s{JOGR-lef4acE*xwU#`^?Z=f2N~*%;VAU5dvKzWdd=dMT$Rz zxZkZ5k0CjZfSt$do#JLj&j!#dZf10%vNMKc8bYAR=nRA$XAw@C#mzH30A?A;P4AG| z9z(XD!6FV&8rBYmkB+3~Qi$(Sn$;vbRCFxK3z|!^7a`&_CtaB*k-8xk#>4(HKdc=8~+}T#_d>m*hpwCDGgBh23il zjBZu-6C}?fWIGFbH8Y2jxsI!lIQ^(s7P*byHUv0Dg3o**nj~4IqA?O~4ydbvvA2~V zNy6$1>qk`&?R|#8W0aJ83*u=G)4i#qrh`!POD|CU5){W7POS5BV*R$TS!$gOlt}ZT zl;bRL@N~JE`xWA2Vw=oqYq1Ulqr=vcuUu$+5}Bq{2E)z@CL+_p|sjc z!|90GMG;j;Da|8lEEfQFSF8l3%XO4wg@=C;r?yP0j#TnERU38GNZH`?=c&SwaA!(g z`;2k_N|e%UW2pt)(6Va25|D5YOD$mR^Z9smfh3@6Q%No1_L6s@f*~Ne2SE!M`00x!lv8{)2}0lig*W**$CF3z&eS*D|8m*oCo0CZW+U&Ux8p0j1x@Q z9eOyC^#rNc(ZwK#b+ibHdaKN8XhY{4j$TZzSzPy~etPR#HK&M~?Q4an+_-iD0>^RE zdR5#6HJ9rs2|ne@vq~f!uFZb7!jjpl7A)>o+oZacsY=gbm+q)|35qLpbRI~pjv9wo z17;k4q{5?6qRXUOIcy=O=Rrd;sS@Lrag&@|=iaOipBTyiaum}8i7Ae=J1}BSQM57+ z!C=OJpz!<>b^wnf;ZmW%IBlZqDh1=6*|%3z?B(b~;}DE(qxvF}XBn*7`yU>SUa<4Fp6>5mFE-oByA=UBlI;Egqe+t2R5V7Cr{)_;l2$4jBjM^@ zaRgaQaay93gT1|GunLJ#!GngnyP&+b8daeN6zmN@D%2wIDQ5%dS3&#?XaO80zb9xc zh}VNY9mGw&2piD`&l-seBT-=_DvX3zd%{Sba3oLI$fJ#$bmn=&2A968A8mNERSC+P zN#`M;9Y|;sqX5Y=%_Y$_9v<)9VtD`p(vZBaqDhiBG?%1MB~Oxc)|N<^H`~sP%+^$# zrYKHrJgbn93byU6LX}joZAXO)1hx?=^N4r=<|h=Qp@Op}taHk*(*~5Gy+ND>9!_J< zny_xEJ4ngPnn}wMP)#H>jY$DXVwPSKmq1+CUbU^ggsr`5TYCvzd%T}mWL+{Z20`9&Z1x_pnj0+b>kPm;@3G)Xcin@;jSI$HQYn-*lhz@?HIk(W>Ru*o(+Kz^|7rNA5pm$D zQc~9OkC$t=s7tmO3HJ*}orY2`6vvG?wL97L38`SalU1lP3gUG!O7BBpUm|7xjGLdg z0F0#wsks`ic;VQx!gn$(D?HLHD=Z_kd=vrIMZ(?EZCiTSb;5|_R-7Sm!b-#3UPRir zmAx>5Wo6I`Co$Zvy~PYTf(bV%w{5phsgL~n#E-KPRMY?cMFuE8l%@+y~HN)E9 z<$^Ue#+nN68CYpGr85!G$ySt%@2P0m_jzBmx4sEVa+8WyliX5|OG*w*vF2L<>y;!%(x9T%Buf#r4r6PS zAV#u9MXO1+B4{1PUQvP=$vY}qO>$gwNlrGXngj9j@=$u6l(9kt)G5ipP+;2A6of@K z{xVL#)*>)YsvWDLD|-SqsrIGD_(JU~y&qyGiGa}~1~N@Y>p`~Y=ys4jI(il)qC6i{ z3^GthlOQuxv}PH|7R}uYqDwiNghfNKND5SRbWp+yvQ7Dz&tYZ)&q&)TTcb%jAdpR} zvk05F5t{3N=nuZx{fWm9o-9+{GDfnck=cglK1!D&&=4tAT06CQIkovY-D(SRx;2w? z4?;`aw5@fzHIPSqA3`fU+sH9YGS(urCbI#_mFfVp9zwtzm*ko6Xbgf!LlBfPrh`FV z(GKQK_zQg8nE#P?qzSL$A)vpL97oU{#MBeHf7S|y#qY6<*Y`(A_-U5ZG*lRaz_OE0 zMQFua(@oe3gBSM=U@Rlk!&rtjTbgU^Cm{JLg4kMOCLoU=!Qz`g6^a!jxdkEB3!{L$ z$i>vS8Nuc8cS*6yX>G|;j7SI^kwCa(PpXkez$u+uGNfMe%QiGsVGB!~QNT#T0jAVx9 zlI+%8kCbgG=0#5;JMB_}PF$#@2_{;gqq{)%>ZqxZ?O~d@O%rFD2BjEhn)h|oquIx~xB?ztfRK#>0kDO8jJ}c3^ zX(AARrKIv@oK4{-lM@9I(eb+pya`q6I7Y>yvzx)%XOC3#atlO(^@T$0Z;m*fl0B{`$HBxg03 z1!I$3zHGfd_rn2H*@R;+G#-;=uI z5b(kTi7wb^Td*osFi&ZWwk4}#$#k~idE-5>K2?g6U_DXb(JW9S}NeYffo(k~G(o|G_?Ql(l&(i?&7 zon0rnf5__o;yQGG{Ic=K-<}Xh72dzjFP!3bY1@GJ`pC$3aut8PKVpjee>|SY6~>-# z-4Qt}a8KZq0%NRj^6#|zR{^&a_Z=3#}5tAKlp3*~(cr`_nM@STO0S zKU-kx*9uJedVwML9B#8E4eSz_2KER{1BV2roU1NP`XMO5C%|Z=umJtLS~>Lx3LHoN z&T_$^0#|h!gUqmXk;Rl32u%6-ZmDuEiIwSV1!np>f#b;ESt}S+;5uDtAlltx%DD1b7ine?@?ikU{GPJz?8orFy*@hru?wLlphh8@`_7rhLm$vH3)vV z-A{#SmZ1(nuH;topc6hPFb#11x|CP;u$c0gz_kCFz?2^gG4^Po!v3DA2Dly;Z2Yvm z?0Xi|09U9gaUjQjk0GX<>rbV8a*4&1bAi8-dx3$XUa1Pj0@J|{1f~IQDWwbq=?9it zOgVRxlJfNeQ@$aW8@Y6E^uBDThi|-`nNdlXzEWVyxi}UCKW+cBa*HAN z)OU@f!pT$x=d{4gz!_={5Zkrdxz1K}LSl2&YzN+fPW)9X9%T_{=XW}>hfB#cgXIFh z^_>K$Vj*VM*a@Jq!cm`Nv2_bNlD82Atj0VAti%ZBeeq4 z!8(B{Zxq<0LX%)nVTHhyuN0W_wE|PluP=e%r`vdwz<i@CPEgb&m z49fgolQdp*oyE+Y3;Cq{^mYE3g>Dy*iMOa_G+(*U8e4< zOywUDcw(wyWtZQVGInS;XJjhox1^+e>PY`h~>B0~oJW|g*}hpmAzi&+u;W|fpL7kEv!r$zj4 z99S(B=)ewvAIadrb3)Dx&kD@+4RPzhmh|*46dL3HBMoQ@ehCW@Ki$_J5jayn-yr17 zs4QXAznq>C8foI_^k{XGzvL0STFFq8T9#qDrH{TM^ltl zNd{*3Vkr11gMo6P|5*lkg^<&st<}~(o2qw>#p)t{%xKFvk-;E8lVv@|X=|*-|2Knv zosiRkljE#@RNp02=GgbtN&K`>V1lLzHUaTuQ6uNU0C5rcoEIs5AuoWuNyslw%aAp| zPkDjh7rD?W&Y;j~qF?xrZkKjNR#9bCGSR;Y{7CPKe(4enuH_lh4oXW?A#goZftYC-&e#kI_`xulL4&}PGw3%8Ics-y8vZyun|Qg-Z7@Iv?eJo7 zQ3iut(<~i0BruzUi=3t0nPf5L{Mwk57Z}Vt5LD=77(st17MOCbdy(VX9g{<%asZT1*QXBdo1P01g8ABz^w9u$yT58P6AWjUtwbg^T8lffJCw3p^7HGpFHOmqvaOPDq1+ z#|b&#c{K9=ko&-uLe6*mRQYK#0fkS%*b*qP3YX8Y23SJAaR!24#F+*C9|50KC^*mD zX64l98&%Y%z6bp!z|ujy-DK}TJPL*Pp&&ivJF~`s>Qu8VW(Is?SIR49TTD6MX_oRP zyaaDB!7zs{-`+9uwgYn< zXBHTPM4N7Ev9P=-`%e`1VA2*^3h%gyaUvV;d@j<hBQv@ihHsavlHuLDbixOXuhSd=!3QEj7*UEDzM^DE-NK^Q08jdZqH9-Rh?n%Yoy{UL* z8a|YU`-OM9g9kztX&Le^qV`ZX;*)8&9$rYpyVG!SSVKDffHYidYTzPA-@M1V4O1m* zM%#F&f8RZrE%$;OSHn5p5bBOjcx@UU1-x+>Ukq}bc94%pgw7GS1)hz_x&l0rr#upI z?f_nbtEr+u|1RLMkhcru4^aOCyr-+N=lm3m_7iOen}FBg!nHUs@Dy%I$EJ1tVQ{TsK zUV*{4FLaz=qXx4^>t_!cC%6nF$ORBa0RK;Qx2!wX%3{3hU^;*y_zhUv!v z-+i@pa1JmoJk&2A*OQIFQ_jQQZQ!wn?*<+^1VcV&t2D3yj27MXz)k!#@K}^68f35= zcqWdRF2L+`dx0Ou+z~{jKZM9J(IkHXmQCEa3!T>A*Z zF&e;OaUT_6U?AG83?*U>w8bI34f4Tv@~u|wz_Y+TIG1FV!l74zT{z4(CVmU}!(O&Y z{s8<1p7oecd#FoQ0@=CzxA z;2yx{^_qNivP*%FqDkij_O1f%hH)UD7zMl$`12N+El&&7MHM8n`ujIp5V_FMkMldI{u#15W}sW3Fiix;?;c3y?t( z72whDz?hFVG$Yj!;K4WwKva!fAr9L>9z74~QN=w2+zogYnsiy9 z-wRmwiED^Gw5joEBpAIW>EoV5@o3;Vq7U2#yit^32{4CsRDkLuD}XzrhB^ffYz7{T zkyTYW>}>^(w+iGa@N>XkT=eqafU&s^UIYz1{uf~B@loJ=F*2GG{ui)p^Q<-~G5V0H zv39_?+old%)^Jx~{EGN5ADy~q8yx>KgDau%%Y3XrM3peX^}z8geWoPl*PGXf8kh_G z>qy7+pZE*bEAkI!NKw*sN^{)WG0fQK+R3A79d;(3> zJHY=Ad{GoHy%EE~6TqEwu`Y<668IeO1Qeh?C{XVCj`I|1cw(S`z6ZuCQKH_!_OQx! zt^qzCwsEdA8u$%lm<$X~176byuSW+C)d7zbZQcmXxq#^-D}hgjIM?xh4hH9m`Z$j` zyMbRrjZ_2%4+2l`X3vI4fn}AR0se_7z=h~-vdwz{FM&g*Q(g+Z5ig5u(e^!O^hM}& z!R&9|`pD1(xH;TFT39r`!tsN_$fv zoc~`2LmGSo_{30qGWrmBJo*Iequ1s-{|@{K&UPTGPn<$z5%f*3Z_^f?7MJOR*hDB$ zSKt#(Izt}TmjQ3YQ}8Y9BRv0?gCQMA0#6VF(XGIL&eNActbw_}qcCv6zM8Tv2R<#@ zbPMnj9OsR65c)fSc{fcragOs(z(>&}JPOqLe;*jH;ePUS^au_e0)801bY5WKFz`#5 zP_)KUo^<;Zsd@CZ?$?!Xh!iD#?xKRoOM1|P;1Aw!HS!za6FAJa2L|5(9#Mt!IqH-d90k5pj3dW^C%_>yUubcGkp3TmHzNJ| z0N({Ho9w{=tJiSYD<1=6t|-AT(-OP^+zSpC1qMGyoAZ615@0sjdytzS=X{@}r9THe z7JX!KFmSahQ18WZ9VZW~h;uO*yb9uBMT5P7-@v_|gSc>I4GjSfI*sbpBZCxE{}r`i+X zmx#r{@&WKKFvpu5^qFJ8BZJd9Gi=cwlUQ^@9(J6doCkb2#(#BxkjH5u81m%M9av7A z`vA8cWt(6iu$+(#1AYQW1!u|3@Mhq-7zb7o!~R&{HAAo(DRA&MU~d4PiXILUECl0D z%vjXGf&_O0%Nkh=EYEHmf#1ap$y{hW4jf;C)gFPp=YdDS0hX8!>;;}84(oqukK<3C z%|3v_Cpe#X4-6auUWB2Nos1>=3b-?>ltV2$ZKMMRDsdr_4?Gyxj>$m35LgzV6qpbB ziy&toyQTwOk zc@yvxC}5?w?>RpPHrXYi* zzz?I1D}dSSe+>K-2Bv|5+y{Ps1U6O(@Uxhb;TN9opM+dG@Dgx0G#UKB`5zhX2jeB& zLMaD>B|HS&7XwY}pi}-Eu#3YEL^<#UBC<_S13xiE-^OS9R+!Ss3@-+5fee|R`Sk|w zj9K+^b^b?!L1_spfo~OuO%k|AFKiJOI5+{g8*0Qf$rRuLL5Y|_E%2hT_OSGTr9%$_ zKaX*u!kqs%fq{inMfi`C(TQ)jrX_d@xUV=n?gw_4V!0diS>g|YH9}Z3z={o_x`gfW0H(g+Z?K6c{~b;p#SU=%0X3 zHDbaLWcUW~D$&Uf1Iw%5&wzg+n&cbc!@_>+&L|LOy{5@}b;j}6OE9j7f}A8)0<)Kz zPC5p-ZN9x9FcWyaIBM#EXQ4)8fy4I#zjg)oYYTe)dSKji3hy~>?u_HFJw`5b96t+% z=~vkq(Qkm|z;PHDYjeXU`Ubdt5i$&FjB~HcL?=8Scw?dM6P~7 z{jPTErq8XNzFv(KM3 zuYS^k+kZHz-=u}NPMI@(=aKF1vn`9r6-Fk_ol>`8R>P#a+m+Uo1v}U5bZ>SeTi5y@ z?Q*;1@U8^bjzwN^yXWxMC)SUZGR|i?Sd*4`#VyTh@Rz*ec6B+@HTaufaW8Rs&C=k% z@rwIB2v30IY>r~yw$bmh8)+ZkoQ=D}{&2+I9q(s52mQIbk*MiU*-p$~$LPT?vzM}|GKeG2t^PL9 r^E%?VT|L-wF!^z&`5(UOUYxUav+E4#;-7}gI delta 100591 zcmbrncYGAZA3r>^cez~3g-Zxps9*Z}E*h=O7V3pQ-%*MK!Daw#Nv-tXDHfcpDAe>@MqX7AJIGoSg)?9A+DU4L7L zJxEzm21N*o|M*Yi#SOZ>(kjI0ZPPcl_^7vSps>G$ zvJ+)D%3c(TUi|N6&<>dNgZMp!@__IEUpX>ROt*ja|IyGH=>7eF(Uk@Nb*yT6yl$7$ z-4$(jtCk@S_MMjExNVjqOW})uiDmW!q|YUP{q7M`u5FtVTzgN;{J33C+cA+WdtP2= z?Ym+4=E3#HD-XD#&XS^jbz3|6b!gjz;vmDDvR?nKoqSFE#iws?FOxehYjnD;wc8p+ zVx&9LYpq?_80ofbols}}*;>2#W&Lb>IWgiylSoYQjyzj(gSGZplV09IwjcHNc}tSx z=U|!XeeaC5k8S;Xb@9urwI7{trOmaix7NOMe&ks(g|rmP^(5^OXeBqc()zr2##U&p z-F03++Ck<;T5AhhT-y$uwik%n+`aY#Rz1=si?o^N_3)P7T8SZ}9AQIim-KQJe zz&~%$?{>)^A>lURzA8w#*Xl=HGROCNQ=6obXO~_5-Wl0bBqey|)9;`G$vKZoTT#SYGmq9$7w>O{&?J-5LQSNv(A4D`me{SEK<)L zcP0cW`sDN9*8~FFlL;6u3-08vT^7`0ml4c10ILpcFTl)E%@WDK*s0~#L6^Z z*!f$$?rkG$TQaR%51g)DeH1aeuKwdQ!g*JnbyJ#mu(xQ5Sg6(d8%4^`$4OVTMWp=- z+IJUdOG*14v`<@Ux7|$I=b*jUN()iCAAt7y@sIT(ak6dLYe04#Z-c74>67DR2W?xU zzBo?CYL7SS_s7X(ZEd5zKTdW{T>?Sh*~%C9{vq0E$LQ-N^_ya!G@3xd(})Aj`y{#_GX_!r6_D8HlpTH`!$?e~RtpLavBJjmz1G6U8f#%aiod3Ecmeu(6iOb-B`9ro zwk=s-mz=q7+pF8Oq`UOLI?1-$PxZRJvrLzHdaus1m;3GdyuA_6o0ar%YU{$ov3D}uZ`>g}T0|8|q~lICm*@_xIf z+5eh}ztL=jjX+AP_sX*x!M0gOJ2Efzgd%~JKWOKy|iAW{Awmgpi{h{ecwtm zy0o7@#Vr%U)4)1I{S#$>nW^8DD7yoD(jb17D0^9D?e{Hu`y`nSdQp;$!_TxN zITAlRljJ0@=eFpsWSI$QY>Qr!EMub{ZvF&WET2vEGE-#j&=!4Rviuk-mv)i8v{#z- zTf4{}+U90`M;DnKxvp8Hymov?2Z*`T$ z9lvkN+6^RBd^r4FH#wza zag!C}?)Y(Jlt7RgYinzl7uZ|;gPKl2b8?F8B2)F%DRP1K+xh#uOIJv7LyC8=syU&% z?3nugd7CjS^>ll+t(6C+qAfidIGXON6Xk03Vz!aB`_AhX-DM@J{k*&EpLF&4K;Gnd zf7%{`$w$_XIUh)f&y;;7nEihc%>S3*1F3R|*3zhdohnP(iu2CBqlZ4R{YcI1S}6`F zOa0Sie{E}{z9dbiwt28|WnFT?&niMcqm4V$(75T1dXIFO*!P~6k+l=cn*86iTv^v8 zbA?wVxV+YN&Hn3<%muX{FSBkO)CX9 zc}T8lXZ7w7j|`F{tu3|(^UAFof2&C<8Uy_YRVw#8^?*L1hs=na0wX^jw-@DkzpV-G@)O$fP!HU) zgHxE{v{~){e&_A)8ijPriO(`&!KwcW`KJ zrCyvNLwud<-I$GUInS$X=z%-F;}4rit8DTAQqMdIf}*4TyPEZwvwm4A?2#~>h|&x= zZ)YcPo9kNqubmI_W^RiE=10I=dZl>t4lH!H_^&w6>nHWmxH_?liY|#RoKpE@<+RC% z&sZ*(wcq;cL~R6=?c3TEep}O~P}Cl2;q_?CUvBpbQQN*b+AV5>&r2A1xJf336h2-l zYmd~uUo!#I@In+iwi3VhqxA12?DwHO1=w?@cI1qbm0Q29X!1XR$#O7y=1dcA&C{Fw zRVMyjlP}0y4#I6F;qxY&cN6gCCVspr%Ny*?MCZQSw8GmR^Kp~^&8Dkx-G5%TeLr1@=vReef*;{0_uC}MPh6* zT2$ZUKis%!#aD2l$zKDR%jzRdnaz-igv?`*+1}X4`|S$0{1eCws<)dm>mg%@%v#87 zYINTk#MM#6JzVkE9hwq*^2w5da=k2D#>K9yd#ElXb7V=|T1y+;d6KM8yACGZAZp)i z(N|^5p4yL1`u=R0DOc;iX3Ht^I=w7MX32i~iX7QJk~df8#8#AYtjb>159G*!a-iM> zE{1)#p7K)pkUp=c>>T-M3zJ>cc5XOOXA>>{PxU8z%5GXtlm32B*~xcT^Bkn&?aepf zx>{XtZLS2oTwQN&o(=dWbzRteJ>YrjI;VLS;MwXrvw0@q>FRn-^L2oysB3xi48RlA zb!_u=z*nm4=;jK*W$HR2srgzU#p+tvoLy6N$z=;y)Jn@`7@XlvsWr`hN0WYcFPZN< z)qo{xZAfEj;RiJ>{sEW+eP`v1BMOh!WE4lcH!jTCCTfQ(>bVz+3J*XgU17h!FuZVA zP1oWSQ>K@q{_w)!!e=29tFW(LC@6daSX+gic%gscLp3qQQ%#L{QhjINd7)3?y%3U0 z=%JV26 zqtu~9-XiQ>P==vQLs^OPB+45of1~8ICdwWf{tP zl-(#tP`*Zq4#ni;QR}yJ`p8_F6Bpk+W%|b8kWac6bt~LfZ_V6RuerC?3#X`Uqd$}@ zJNPURh=D*%QAY^4A0VqT*>7+84GX6O z2z>C)@@>Jza*Gumv%xK~6l%cEAi6=H+FvHxegrHU^gH{@uJV}vQhzzQ%OlOvwH90S zL3h$;NvU25wOwv*`I`Org5wr5jwN~uIG3;aRPeY@>Xg{Xvti|i*xY7)<^Wlu zUD~Yg8z2+4E9>>I2gspuuI2+Zw!|$rep#cv{e8&xJ9cf{x@^bVkni8t4(t6f5l8*3 z64SEfoLbt|)x6=;?;eP)(Cv--j)8K#JfKGw$WLRKO0w96olWI%10G|*x*Q~DXWfdF zme{Jb+anGhHQ|o0h=bgT%R)=7Z|?=T3G{INQK&`EYBEk-n*8VYLfYv`*~lv`&v5BHdxOCb_}rvT%La z5Sb)xyQdG4Qf7>4DA;aQh#KCa=h&q zB*T+K^bd#0tD~CyJ?jpiaa?}*Ow{FPkSI6^^LpiPK_4TupY855T#nN^4P7Vfx1vl% zNk+LHW0K?$CD~7+tSMO4wUTv zt^@%Hr9s1(9x*~D$`UYBalXaT>W&DGSQ?&)n8*$t~4nj^;1nsiAfRllTFGnlj5(Nq$pe) z!mA-L{af95Qz*+6`d{5xlagvuPS#y%QaYQIkLs=}7Ksi1m=^uD(K68&+`_dX&N3y} ze2xBZRAaGK0sJD?`6856j>1Z|6zj%D|C4oGcrq{z{+i}dUN*c~ttlJ)-!%t#jsBOF zod*A>iWc|iaad{azppUX)Zjl#?OsZqrW^dPDP~twbZ@J%2LDUV>_fN7d9GRCaJk&z zYxK9TD^$&6Up4yM)D1TqJGwdB+ZPmD-B6QKq$mykrk24bWw1#(+cMCkc>xWR8#jpItZ(f@TF zQ>DSbwZ-^7hf@GXIFOj5yo}d4NWN9a9YuqGV+((i5b!1jyutrfQ=D1Ri6%xW#*EYl zdfAooBkkHIz3Uh`IDAM`z@Gt4`rI*cRPwnNQTs%LsEw|FwWdSBS7o%FX~NR9`=>GT zs0=;Pl&{>3KdXtS-#tq76a6PZOd)S7Q3avzqDzMY5BEAc1weQ zZqrJWve%?s*R;ZuZdC~dk)QBdnNvtNccEi#2}H`N9- z%{M8_O-iq(xh7?yNl9n1e?V<1kYkIN74NDM6 zeWu^IKz8eRSh3H1?o+A7@JDcKiaueX>=rY!ansLsv32mS&qHd2Q!5Z+@Ze?E!Govj4=u#fHd{Zq zP-gXtX$*q%56XdmKlMVhKdP|+?w|Yoy&s$X;f=2X{`B)V0o#<+M(O)|J)~OnE{hPR zlRo|7Me=%Cq&pVN=^d_UxUM4DE7RH@pHg9|4Yyd+9y!+RFV^o`43~Q~yc$<9?C;M{ zV_%!0A6YC12HCih&_iyLaY5}B*u53pU38OtRH9dYUV`<&y?WSEd6Rr!U%gbmDO2>3 zH_JYue=os8Xel16F4gb7S@!0^>f1NV(b~ODyWKvSBIR_wXqmjrzT^C>SQ-uT>0d9C z`5lYu>iv&4)cfB#Upbu55U~n!S0b}mM(^&mTs~q8E}eYijnk$k=pU|@-FI8p$Q=%C z!;;edF zZMAt+?$NGQIh)Gumg~FPwJMk5VRLCaho0YFDJOT(ez(ZoyQAZ@)ihF_Xc#%LRg2Nn zlC`T%Hl?8{hXp7PSqA*t=BJ2J0%@Xrw|b@)FCdZu1$KHN9*e-A?f8C+6d9#wOhZ@qwST} z-JTv=m6TTfV1_n3>d6j5Sj9OU8d&8Aa3VZdFUZt9vQ)o5Q@c@)+I=ch8>jiQV91uG zokq-EBH{`dv}J31;YOQanG0g@mca<5GcO!)m#SREL z`-2OiQ!pI7?^4h;yY)V}5oNV(0fu8xT-#dj#5H=1uIFf7eC@0un?D5JejP3$Pd`QQ z6ZjDF45=c7j+_D%x)Fdybg+j!Zb6e=n7>5GlXz1A@Fc=pUV@ZWSdIh%d6p`c`w6~y z6TvCy=&<%aNXKl3byrx%0$LgC12Zg(u!x;>oe0aOMXM{H;tICARwM-Aa90Qf4Z1US z(n1lIvlN7AG$|RsAu+hzg`#{#O~+7Ea#*enZn%1*3&Z*t{*J>K3CmYC`CM0#(U*wb zwV8~5gu`7)Fcj9Gu+#M^y&OO|+O-0W4I4<<<$45`!wLw;y9QBr5Mj57tAJ6v47c2cDX+odF9C(RLIyOm(GFLBQrLbfxLoU~@H(3w@8aYVcH~9`6_ZOe z;5Q!voa}NlGu}P~IK}0q{5xL)PLG{5?`jeDK8nh5eia?)? zas3ZkVLxz8jCUcRBJ6+Eohmxpg{|s58MSpL9r4TnD=2v!uI?c)mtqa;qml2p zherBpO3d*xT`tfHF}qnEzpz>Zu{$1SXB$Ykqmep;m5$R<0sCP?Fv+dW)nZZxh6&Nr z(G&iK6)Ax{M?2an)=I(Y=lG}{kP+Gf{Wzq39EpXF<&-Ydu7E&^Lu1#CR;s0rdiry@ za&)v~J2?wAJH*B$Fhj$ZXw1q&nQ%LOSgKtCtVAX>pp{|EwQC`GQcKuK8>=)2+VriK zFooC}?MCo^(R>KZwFrVH?Qg?g5aG5~rke_<4)mgMD%1?;^-6LPuAQpk78B$mNs(25deiDCzXW?Nt8h@CcY1 z&qS_J2oYzE%fhp$Os7C#Z~e6d{Zev(&_sYQwJ7Qh_IPJIi4`{eVbS;Q&t)z6}u<1OOgBp}!K-yY4YPvAH135NJk;mg2!k%9N z!0f-^hZ)mg3-yC_!gfn4e$3l>c>W9sz@&+Y!{Y}m_i+w{7AiM$H*zv`yWYVhTe<_z@rVlM`+_p zrRN$=8)FHFyK+dMK-lLLmLb%b)Cq<EXNutJ=UCGaOAR3XuhC~_PMafO$bl!yqYWNYI^#0PD#bckptuLo*I zrp+h|);!Kr=r!RSiy%wUA>LU~4x;PsY|zZ`yo>&HdX-nMorH^&Q?7G_OO#KpwTO{( zBw?qEt3l@|!dwjkR$*~<5Ed8fyNb1%E;uJuIrLu!Tiib9)ayWwc?j+eb^7|Cy{?|L zxtySI*+6%$plepw<8alv@=I{tE-odVtE)gya1Ef$ZM;n+yN(jRqZGO+uDii?-bFaw zHH`Fo2xq!}p#N2bd%ApQX>{Fb)RpH7qtJagx|;OiX6D?5+9EF@ zBixmY21Z^=*y*~SLZyVGU85*-8DW>}DZ*C}ju)2wM6Q|z+h%kl=V$3H1GG!qeg~Q@ z3&{~+JaDZ(X`q(m8w8r|T3kAej(mc#R6&p2Owb5=S|Ayw~PWk*)^H)a|a-j z;^Oi?@`a;-vApjAcq?O=?uw%`+X-j7IbjTk>x2tk)iip9aEU9H^fw8YqEDX3 zjM~=9+0(L!Id$#$nVaJAJVbN^qV6Dbbk^Qj*gK z$xY5cgPv8Wf>OPQ+2qP7{m$DtSX5<4u< zHI?!^qhY#_Ya=VzOE_P3Sk!)YKtF^&9>dXcGer-?fNe&k?O=)4I`yQtw2r>E!@mT_ z&Vk!j#o7KHd+kz+bg)HN6yY~^p@^Qo9X3VmA`v}Vckd@UfAY^BC3kih_ zO9rH)7p=k-)!pj(}IteVc2h8}P04E8O)l^;WW;c-OU^0I%8(@kC)+15)(r23+lB4k6kl zj6opmbAY!`U=nqG9=RoZaR3Ba`08-i>n|d##eqdP->k}cLN1^)UB5s*av}G_K^81{ z-Cci!Ik}j-=pYMUg6(?UMFhSL+cgul$eRp_@g&$$d4Mnmgp^}cS<1l?WZ{do-A`b+ z$_gn{dz0fUkVjp@UJAaf-WV-J+T%1iSn~F$Rh6bOSLG1N+pnc+zc2j+q~C9k@eNrV z320TLJ+e$@dgLh0?iT6an(WyIn<@dm94gWq!2Sx_D+1cSQqdziM%d4Q2y>>qHW&V6 zSlE_Z*8_AxVk#zhS$!kqGCKkNn?NFf^9WsLR{*jDfK&kC1bP7IKp-1HB7pP)03HA~ z>=@va(IfC~l*|(8UNHNB8LOD3ntiIsyacqN)GP-u5`foW28Hu2Wtgyp3LJ|l{c9jH z79wK<`V}I5E@;z0n`O{g%`%W~0O?lKlEtT9a?V_1s%LHhuml2`TL7#EkiH$jy#V%@ zmKV@@Ss>C6n~W2tt#G`3X?g|j58%@0zgoG5&#ISx0`nm-LwTfuum@TAezi!~VhyFP zMsKt>l-1e6qfUR5XKA;LDqT&LvHwzGJv|1POjZ#H8f=NIXP8y}o^T1DJz1sR{ZP+t z#}4mDQ1bS{A(Zty2Sx5C5G)+;eDqIT~KT#^YZV3~5$t4W>05 zo;`^DfhKLQV|{N~2CkMij8|zt1d5e#L=dl*Qkd6rCky@616l{yVhUM<@Rq0uB5YX+ z>)OaF{hk#Tmws!ZhWBZBAZJPB4a;tQAJ>pEsLL`CD%NzRa~E*y9D<=&qPC!E@_E2v zR_o?y2!->!&ieEjkivOhXMKiLYy@yg1{6VIi)drFK0XYnljn8TCpUvAoH(!Z3G0@> z0h}>6;07j|?&Nu$ z0f#$zUT470D4f^Xat=Z>8ZGu+1Hds3mk&^sv#3cO*xB$`8K{W|cD6o-!{d;RwtS;1 zp4Zv>61F>eUT5n^INX`Us`?XlI(c4a8$dYP$@4nfK*BC3&+BXjgnjYOK~x?@#4Xwy z2X?kg*05^kf~}Y!UVy?sTM6N1(LAuTjiA#)M)SPRRz}1sh2v$=Hb6+Vq_b#ioY&bV zoB+)T+C+k|M;ntiW7r^UJg~D(K8dT{Ne^sSv*~LPAKG&Kf(wgj)NcI~NV`aNUT2%< zLL;3#ud~f3h|K_U*0z8RvcdurA<~OWg>7dcViSe)I@>NK88vB+PuO-V$tWDy+4c~$ zJ9%Jd+dCO>xRVEVwta*nqIh6ud-*R^?sR?zifupTT~40Y*}>DTXeMCz_5pp%13X9AjN2P$$ppY+q2m#L4qI+m{~!E_L#}&i3^+X!&R-&+BZb zN?~n`ljn7|AAB4X6JP`-n@uvr}*2fqX92BB7o2`EJj1h%z=H?`D&{r1Fj9#Pjky(kTdCp{ z#_(9rR;FzL%~uk`b3NN=C080#Po>LMgGR^jT+g;py99D$VwuUdB^tB0P{!U)SC?u` z&k`BSb3NN~?HLH3)M7W%#wu+jJo{FQ<++}1jkXg!S$0C>!M&0)0eU7DmSBIYs?<1bd&6DJL+M}?N-{1D+fQq zHc%b`62qfDTY-W_43GM3gM13J#qg}pHdt0bJY1-g+fN{D_$cC!*{;$~Kq7``eYSBL z=X4Rnvp(B+)mPRSp7q%#C@FgkkNRvAHBPC?F$39glT`l}##~OZa_tf5m&Q!BWB#{I z*4Cn`F)=&~v|X)nKvcx=EYLPZA(b&a3$#sD$if(&1=^-*KjLRu49@~>*J$T}tch7l z&b6wdO);J6T!qqkB8JCW0ZE#xQ9YlPsZH|@-Jch@Ews{H`F+3i$&DZk5SSTErXncaO zQtBuij4QL<#5>m7u2iG36Z_J3y~aN2#PdPh0*#d!)h-EWxI{=Th;}O}ojD{``hl<- zu-(dW*_neRkg6}*RsKH=l7m$o0if#Egq!DswqOe<8aK}eZFb8{z?NH3L$E6!*PyQ; zZW)CMH`sjza7!q}g41UMwAPWe8j%jpTm?K~cRU=J!g(sOO&nBZ4yYlwXucvWfs(SZ zVe=(>ao-Th%ONR~lW~O;GqFw$xl8K=A@@8ehu&|q08W?)Pr`=T0Xj~jrX>KB-)%$? zSAPjn@FdJjvf@_<_`xFRPV!%XXJNxZ4i{a5B1A`HcrRfHB?z39P=1RRo#3-R#vxwke$^nBxG)+9gD7n4jjDcRs1@+ zk#;Om6*{?*b}TijLojtJFzTws*SYc7B&(uHlSY|E9kz>InxdJ zR{9n0AXjhx15B)GuceiEuX4&@94j zR4e86gq_ZQXtA74IMUgfEvqCP&edpUZiitzSSS#`y{r77~tio*=x4aGdiX6&4eYcg`bx6XA{`C=R_CxfpE< zmv{ff;5VToVUZ)8Qw?870$^F<0hKZjDCHTbgOeHTlttW?X=O_>1?3(Ho|6YFA=slb=I(huvzmiqvnlRnaDk) z+l~I)M>xb8N%{SRL!GmkAcuTJ!kqtObY3SM?yM%`2w{hFG_&rF-w}xjXAc@ZN_wpG zM>gSY!f{4(-X$FGoXoy_pKwQK0cDQSp-v*Q4Dm{lU;M;Yen+EUa+4#RzEC13iCCTQ zGpJut+wT05@YjSxoTnK0ZwQAvCy@Rv;V|bR*7hB12zS;IK1F(jvmI@I-vzMKIgdH; z1L0`rv()_`VV5(7t^BbI#vk0~S(vOL!|hy4w@(vJ7D4Ql$W4fTI{qvUd(@~o)29Tgjsu&i6j2Q0}C zz;%)AqjSlZBj2>-H{pXNc^l}~@zQ)rTwJPDOqlHWlLtRnF<{Fn+6vW5z`sdqz?`!ROOdtg>ez7j%~NS>$!S@>65alPShy!Q^GO-S$GNNAFLx^XAat9 zI--H{3x$NobYMHbRERSs4Z)Bn!?|jSjv3Ar`zoBd=Mvp3CeK8IhA&0qgDmUeVmEa@ zI>W)6Opv7}C*AEsoaC!bwW~X=nyndf-ohgeSsO4uR*&K(QisHOcM(`C3ITFv+H%V-SS2ufgmG;1k$Of1ktm ziwMSFtGYg`FahY75ln(aEMGi7LN*R#@&%)AnJKbuJ#iSD23`b!Y&7m2@_dZd^&-1H zh!3Z;n$LO(J2XXS)R3;G^FIUCczysc(St4pPemD;zkt>s<}&^Sz&gp82Lqn#;RHF^ zhP2EVo((3+YZ|covPJd))ZH%*3KIboLg5;N8)Vsv0Ui(_@Z4>Z zI|a!6(>mcU0}BJVND2Lt4liu{Vtq@M`TpH%e2Ci&L@nSTc;Ja3z1E2cc<;h&0p z%p}JJ$nEi0fx>gbBxeW6`~yPaIcbuMNJjnzS@=hV!gI=`mj}f8cZMSSbihg-06Wqo zyBWZ`-pH4HWZY%Qm%9xOWVxpRq=_Is+DghU1c|BbnFxUSc);Wh71=X=0p=|x^9zHi z*;7RJT9cXma6oE@DJ3vG5dc1K$bKy#^&x=iu%B(k^f4EJXCHvxy&!6c<55b+tDIU= z4DETGe^aM%#vK;19)FLWiD4tFXG1!tCr9)!HKKWp+jBG692+9_XHLCcBd{*Db6$|u zuTlP9Br2$!0nS4{XB0MgCf*S}mPElPF+NxJBggnUM^2Y(^{RW(a#Veq}YMC(ja~9I2f#PEmD`WdiR@*~>sK z$6SzoyUF)#0N~q^il;<|q-I|zJP(7&+w@fz(VhT}GuTXnhH1pJ$277cP{~SF$$pS` zp>EIH01g3oJizBCAB5)^$nS!@FF^M3GZ4b_8R(p`-Z$u){V&7`G)|Y?uAm*P^#_o6 zi$80UvP8yjAhETorBBfb(dQAS?)Tx6H}!nAH2I%ec;+u9!+`td7jtom6VVEU4%3>K zL+Re|Cwd4wmS6~G0{B@Ua|o>uXPA$3$f!|qUpRTKqauLL^lXLl8n+M+qGI;?Qe2Un zGlgeAICOKH!NHSyPJEuDKF~QE9u3g@EBePK`I`W_Op#BSR?Y>;Qx*9alk9+3Dh~Xz z2y)6KD-u66g0xzUhGap^OshQKGK5k#g|UJB_Z*6>UW_r36WdvF7@nXY;P)Z>AgN{( z;%{(PZ3-iQ5%7N3!6{i84pbn2us=iDimGy_Psa&~TDS8h?fgTyr^|})#{rA}zK@kG zcRQe_guf4k0sjN-d9t%n1UnpSJ|Wij5aPE$6Gvc5G05#f4uZp~nWe4dYUsoV$fH`x zTt4Om$fK=3SW&fb94KHA%qieaNGjmc0KhSzC>$Va&cArQnHS6ez1JE_+yD{ECs9}C zH8;*7hwu@$%Wh@V^7ggm`Ok)bY5V}GoCpSgLm1&7p)pYHOg4o51YDLupA)a$%6UKU z2gWn8)d==LsFsf9T!niNIDEnsOm7N$a0+e=WoOG_kQlVd$NX*#9R|waxw9(Kp$Zmx z4(fiWM38`o7ZY%y$Oump_EWG-<(rgpRUvsCFm`Jh zuIipZN6fQdh0~_OrO3luD!7xVkj10Aa_GovI+at;%-F7)n1ZunBZLa~iK|Ia-ThK1 zd#W0^(d?aOv!{B-n9V+|ybm;cs>qlLhPm!gH^R%b`KUGTH4f@3<;ni;0Z%wF8J<)r zPmZx-pXyD65NZ#2awU`hP^rr|kF%0FnHzW#aFuh}%8TA)t69A#al{{lbakBAOX*vxp7dp@<3a=H z34XddN(}Jt^rfq#$lfZ9ma5G@W1kwppZ0ZEN6i6zi!bXj=6J5M{{rmwn-d58y3hy@ z-k%x9Dewyf=a>X>Sm>Jx<`nn=B*n1uZn&lk`)P8=h0ad|cPVH!;10L}KoHKqz2pwR z4OkMe;p+ih3ZQTk0IjNI_;dJOLCzik&jBd<1OUw9`~jriOf_ZNBE`=V9-BuQ@QMBZ7Yo@bkWe?H zOaSU;lm|fFj0ym#Eu|L#?_7SvNKn2ge0<`)Y^s_OD-w);(PICmtuz?p5e~b5q z_k($RxfXc3n&*xMQy1&ytcT-~H1fFOuK{0;Qv=-wG^-y+`G>(3Q2zpW+S48JRUaVE zE?{opn2NS@gVIdlf(!WR2;|8g2nY6L{Wu}bgQjOQ8o&vxJ4_&Xea0;WEDzSC_Fuv2 zuQ=FSA4Ni#(pMVNs(Y0o&nc60!+$vEOwJwu;e^H+bw7E5<1_s7bTU~7FR)Bbp2_+A zKb*nf(BWScr&JCUp0TE|4FTp%%ycyToo{m7|KuS4o@$eo|4$Y;hfU7t|8P!#!@4UJ z#|YLhrt~fUk+#Ph4X^$W$JZV#8rm8#lr21|rubWixXdyek%31VtzD{a{p?b8ALgv1 z?!#fC`1?2{#%z_YlC$Ta2e=}ct+I3w&M^Y;;2AT7Pu`#e^VKcEfQ^OFoZuuIR;x3a zRW}AB#3FwO)6s-~<;~uJMKRxEl;eyVkF?e}?xGqEm^I1?7gadHXCSJUiNVx0YME%% zsA@4_;h+zkwpBYdQJlo43^rb28b~f>D>QO?5oeV=E?@vZHK}o_Fyw(M@`Ua@vq#K-JpnQm(sVL~r zIpcTRW{Pa2(W_|mcN--Pqkj-a{dp-AeM^aEb_r}{xyv@zNpIOIpmP>hjb+kXHZGHT zpz<7br0}-FuLf=`R^GK4tHtrg^zoijzaMPRR9NSX&=IzI<3bAguwx&OlTwq@+vKQ> z10(whFkZ%eB4eK^!BI6|jjBcPDzAv?F<<$tJZAQGpRRH*gwGp2Pg=uMC*cDn zT8NOBDp4-+42M5ZZ_Yjn(JY*}V*WX<2>&BN%|Rb3RSRYm&wS|fZ{iQBCY0h$@a!cZ zu}iXVH+iC9J0t$8(vp8da*#@-SCva55AS9RxvACj0_9G}bhzUr$G0hnyV5?WPUL+~ z%Bp|K7PiW+3gXPdSLsDw3%jMVRTMKN0&*io)v-!t5XUS}Cq-U=G)<0e6%AFQT)j{f z``@w31O9P<$Q#Mvr779N-GqIal2u!FWj0Nj{T-r4Z+leiw5n@8zd@QO-9N)Fdu<*w z-lVmdG^CTKtJ(Q3kC7EVBQ37Qi7z-@T#3AB?vmq`6X}RD#u3^^meIC&_-zF=kKdov(#yLncJGuWf6L10SeafluQ)O=r zB=S_%T>BaJKDDy5zExGPjf3cRCF+JK<1MSXq%}?(wyUbb;h$0Uj@GKjn^mitQ9lMQ ztNsyI<^9Uu>4ZSlTz?w&?zb|r^dqW}7Q`uvd8}_bHt^P$-{U8J6Qle)&V|1zcwh42G(aKn}s@a}+ zw^3CS%(Pa=tjIJO?V*JE-;6#vLrqSG;#|bI#$*)!n^6e{=ZW!(q2>zDy{7QIe+zFl z8FydI@Uh~fCg;%r2a}XZ+7}=N)^S!dgdhEz;RJ)e)F_7XB_s9U@kVVTPo4Rkv#7}o z_h0kO@1;y6xP?7?&O#V}JYxpcZ`li6tD2g=pV6e34=q_^F=9JbYJ?=5JnRZx(~+rUZd zn9&;WpF@$=OR@ruIi?yjp|vr`|JfMdhyQ2|9vp}+(EWF7hA3JYpY8k~8Z+7C=3U_a zvnewF0tYS0`<`*!PM;Znyiur}jz#4;YdHCAw{S=GSgX@JOs6Yzv3lF7+WI<}t-=1z zbYMtpHA^qzwwT;ut=y_Pfk>l%?D*vH3oOi%d5h^pb!$wGxrMPY+^bgZHMY9N;olW*dJ@_w&F6u!#^fx24@Lvw`v6SJ^Lgi3yt3!+aC!*O2Yedxen!V3ke&cI_;OmFz#kH8s@(YdU1A=U#j zv$aly0?Et8fYI(uRp$s)Vbqzas=URh(uX7O?Elo+1Gosb1HX<&Ykv z)+Z-54i#g2^R>okio7sp$_gcE#o_55<=x=kW~%z+O3j#ED?D!VZ1pj-cC|E_hw%3V zgH!u1#lX~#iL}rZ{@~xjOTgf58}G_6M3zvT^Lkc+$Yq4zAWCeq*Mf8@&L2e>d|@o@ zsdzO6L@v!b2WWUb<}uK?)Xm-kfSbLH9RRqbZ|#9N&S%EU>u8=pkD&+nibSS*<7}43 zWzW0p0d)X0OXFI?hJ{rI>c6n+XM-(&;rWKh8^x$yuA=5bj*V6pxfWJOL{}<<{b9fu z?_(6sbzq5^sXwU(l&PIbV1ae5$QTQ@`SO9b0RETxR0XT~!44*ofgEXPk!aMN1&=KNm0t zC4mQFPSw;+kX6sY&O%+3FzoMQ2l}mI&dCGw7LeLu?2Nb@z@-%6djX2v8)PrB!u>GA z&CqY=?zJ8`6T5XYCpjR79eCb3O@*d|J>VVg+a&NdM%yc?2eQ^q;7u8X~< zVUGN0Ed95tSk3JN1H(c31qKQ)1At}9NXl%2vCDk{_CRESm!uIt!oFt|46yzL@aZ$Q zUKJp57vNb1fL%C5@d7unnIhvsFgQ{I<3ePonr1Qvn>uvXxZz=%Dv9fa{CDG|c%kxj zcs_hhha(eE3Yn8==SZH|@}-y>x=QX=6fY?w)`FBh1Nv%9I2Qm@FJldW)4HEDQYUtuwwXxIG@e zqC|`@o6=4QmWYXEojYKTMTzhYDdSsfED?jsBm`MPD$2&7?JObJmc0rli!-_GA-Kg7 zaZTClE+JT)UCO=#lOq>ERmf?@vn+gc?r*x z;$<|#D#k?MYJ9z~z>ViUcuJFLMZocI@^0%&?FxyH5sq7Be2nn;YV(VRwj+8F^0>`% z{i-#Z@i|1>mph?T+Qy-OwMKo1@Xgz_eOBKMZZz0Vd+kDGPcm_nft4Es#{wVR8Zl&2B z{LhH1v%t5l8NkmGS0^}cEB$DQb~nyBtqtgop1^&nA&`>qT6;mkQnkmI##7z*tZeCM z@Y7xBv&t~!{G|-em)2pBdmfA)qi_LU0l|#L1BCq=#7ktp1$GpokP1XPgZ$9U`U13H zAe|jx>83SkXKXB^@tF-o4XOVHMGS{z% zdTa4^h4fHwEE+I+{Vc_1DgBdu@mjn9TD=5@x~tRiSxV;t`tv&_XIsxfLaUmaTiaL9 zy;tir>@2iYcvB`);BsYZN2{rCT1{Q9OdV-8b!DrmqkZ)UVd^TpF=d$QKLb*7h|#K! z7_0fpnIX!;fCvzJC~v%0GDSZFD>5(<&JcRQP)`!{K{ zYC+3^Y~EvF@EBnrDY&hQTrIwz{_HxfqjqyY{q1#HCv8JN{U`pu(oYXvkKd2`>8bej zorLO6491%=Wg(ShZf`tLwKs^|Q(#O2qbk4AuA+0# zfz}_i_Y9gP^sE%Q%^)5{O8;aKgTnd$MCdIuP}xzDYejbQTP@82GbtiB6tr;AA`t<4 zmM?M>`|IcEe2@Nm`};Jv)~~;whu>%~M41*D3jr`vd3W~LXWpl!`FLxP536{OLWgHE zdexzkh_`z4>S4=bP=>e0dy~b?xV$BhUJa9|*%Er#f~d%zy>TjEH5YlzyO+FOSxteQ z8sgREtyXWhaMHO6R`ZQ+ytCEpV2I!Qe>2Nlnp~{RHs|Z5_iL{9FSfe2q}4`ZU;XC$ zwYUMioyuuS{Ih&a`>Jh>Sa&t*rYSFuwHmm#)c|hR_Ivf^u-`Y81N{nRV+W|o%Er~S zq2hCe%13KbARotA$U_kFKFrrsbuF#0%?$%Xm4UUb2H4StfuYJkVygjftAQ8t^|iVd z=X;tSWGMsVVW6k-faz0kBmS~5%fe~30Q%k4t8-b(-sDz$Ie|ub?xZ6zQ>($KR)g93`f(Wa4X42-4K9k``UHBH1F}2LA;{sx z)6{C9Md8@@&-Y{+Vk|Lz~q>d(qbPozPVk-5LN znmye|U-|(2`j~RhC=28B@cyNm!6J~khJ|O8!sW1Fbl5W*XSDgi4TH~W#t564s$LIz z*0g_}r!DP1r_s_@NP7+we_m;SPW(LYSkG&nX^wMk?kd#&5Qb72hB!v4R&|}oJ(;KX zeh?GHZ+ZF^{4MFD&*$&NKKlLqt?Z-k!msaEw7oSs(p8MIRgA7jb{n5;N#P1qKBO92 zf~qhJAyfrys5+K-NaNg|#`|sxSEx9SU|;=$zXU2*qF=X)u28KgfoN(H?getCe%VGX zOH0kuS8aq-`FZ;0jatFjtJva^$_fmKUzC+<+`_xR!TDyS#-+_HSn=#}125Cadw^Dd zCq7Dh4mj==9=^zjClJeF;0`?6P7T!yss7kAv-*$9g*|Yj{3H zYxeQRs3gHJ9TvfR^#F z*2Bley8KkR`x!a`U4s7NU2*Vfpf3d`-E(1>3XFv^dK{mPvi3%-a1#E~b?;EvmepNdaP>vBquYE`EWLD0t6C_!W`h1^D}A^@Um{WpK{sSCrFZf& zTr8OPt>O<}jcwWibQR-JX~yA3WP}zZuamo<+M+#SX=8qFo$uSZ@YzXy>+q5$w{N_sN2<;cE?(C|$c7L>8 zJ8i)i<@fJ0zbGGm;fwM?yVV!vm+lUHQQpz|MfsU~%`eJ3UcMd)#xKh6*o$w(FV=mZ zX&qwt^~MN%f*Jj$J}Vh<8DV_AQGf9>%_TSJH|*0ormK%KTH|p4PPVFVGFsI)8LjG@ zj8^qcM)fVQZ-s5FzHgtF5yMX{Mm&CN8#a-jT8wz|SM&rvwWw<^Ye_Of@A|Tqk;-}Y6v#y){`a{^ z*{&mS?~}n&6a;pfn?UVm1NsVtL`q-s>(3%pFl{1L4wBsf^lioNO`|`bZe@Q>_HRH> zD7KFaC;8RMR(=!tr-1U0kVQ&IvOhQs9D@zk`60ya?*jb|Ko^u$ELjUgw-c=z4r=Us z6*wm{Sv>+m-DrS+s4dbak^Owyc_#R#v~nN4UzgsVKez6Il%|x@XOb{)*9Ag%60X^C zfp9$yUAeuL;CYOMOJt9yP|wy@a>f~uSt9P#GJZs@EDooZQ3P61;-x^^Xc^0Zu!P?& zGn(+r;!KelOHnIJn_MYIBfeHK3%5IS`0NCO!{?Yee5%r0r;$6l-v*}jad`;M!T)WL z$P;ouV5|LIB2OyBZakEQl|i0njC!Rh~pweJA0s#w=vEt{RT2_&Qu zLI@DjNGCuDkc1YHl7vW;E+Ac`iH(hjh>D1HP$NargAJpCK`x4V08tT?V?jVfk9tr6 z!GkCs%m2PJYj!rAbMJru=lR3)F<+l=%9@!yYt~v`4qVR5W^WMlz0JkQoz@cT*|rTw zc3S`B$aUZiHFDjQWG9HRe+_&xVw!t}zxUU`6@HtouJGzza`@`D+sbs>Ou{xv+DbS# zSB2R8!bjS(B<>EeV?lKIM_aM{ZL9UDdoX2W+>f}-aPtM!%{Qc5p}a2LF$>Jh4ODnO z0v&!JNVCq^i3WCzd(k1?hL{HvHUu9j;NQ{QhV@Td`>cj{_gQ1i*h_{nT*CNj#Cb7c zvlT6>_ge?`kXCjeFr+1jm);MQdJ49jIIg9B5GeIBN0s`?4`iuV9}Ijbqw|0Bjf{bx za6}WkKC!m{uZOC=hyGuOs%D=ChN{~zI9@tbjr>#&RX0H^QVmr-P#YMk#4Dd#$>w5l z=u@lu3JyL|ZGMF$jqe4b(7<<7;@4~jbo=wmj zVAg#L^Nha&pD5-W)?TcxQLCK+!G-W z9EfX`4`eVzn@__SKVUwk9 z`DG`8cOQ6}Wv=jWkg%^7)&f}zExr(xmfo~1tV9<8=OYS6-YCeQ4#?2;_|itR%?OmK zi!9Rs2n#Z=2mLazGNr02(#T&1He)afDlm5wBF+}#>w(53(fO#=F~kqlFQy%}G7EK@abGBJdR$ z4@5COdoi+1-li2U!Zc?0+g=B9n=!SV4G z%uV|f_xd=AHyubkLVjze=}_WPKE8sv=`i9kKE8sv=}6-7hP6hV{$5`z?c}uHPEPCX z?G;Q5vzZ&5{C1hhB=M# z>`PJ>R+3kdl<`bsVON06_^{%^Gghm@*EtyU-iI;bjBKJ) zsM)lYZ2R8quv?*;gI)K&_e1(O5ZTAeMb#M$U?@!w!s~=(74p%!*i(-YvAt(C} z@DjjF5wp%(aiv~FO|plpaxE0A*_<_aa3$NvGC^7sVNjowZ`a(p>u97}4rS zE3SoW!V|zc&$0?pc@}XEtPoSq;y3(=3b7oif1+#J76qg3d}faK@5&x!WY2WP<-uaJ z%$3e{GrHWBvT!%L7V})*#id!{O7C-}ewiQNh3ppheplfoS3%27SH9Mj9}Jee@#YyB zn_O|AC@R)Gbb*^u8>algQ9bG(cYbhX5Ab6Vm==zekCGJR>Yh+~560J_AaiFN58FV6~gB^@c?u}*={TH)b327-j7#=*f3LD;KG}|r;*qD%|~$x%jcICf+vHAe#a%HJ^4F@^f3lVrCt)uKul@fWY$JRfY@E%Ka3Y4455$sK65jAzs8(-Tm@VZ`Bem-<$=A&S!Q-E2Q*%q;xZGt&- zsM9Q%bC4V}m@|)7e`h^vKWnM;w;)c|z0`Tf{893hp5Ls?GRfW^V5@$Z^#jeH4scNm z3~mRx>w}zTt|Di35GS4e#$0Hw9;4@>c#N>wTRTZEGw*{A+VKfApSj2{Gq{F~C^D{- z^xdFy*1&!REOR!wh>_)Eq*Kg=3=w}S(%kJdtTB17lYi))h;%OVoRupj)PIaw$R`nM zrRMj{0v7{*ZbH+@x`M9z2a2m)XR)iBWsC%$eX|N=IgSd}`7Bl@XZx z;4Z(7q-8}H@Zn7J?}c(#=#W|TJjtCpSn-)u)SYXZb%6_6)PGi!2(1m6D{RuCGHcHXqv>l(mBlS^JHr zw5SN8Zh2tuRPL?NKe6S9DU5r5^Wi2Z3Bq?FG)kwSB!tLVv-D|?VGttY%u+tENr-G| z8k;c!J4Qwu{I9mH=BK+q_t>HEcV!QZ2xn}2uxWZl&k%dFzYISlt((oivkc+1{2k7(-vN9u%ky@e5%!uDe z-LCAch!dpR-(mj3+^op{Rfct^$rEda9l_^ft(9ggP-pCjtHnJYds>eL3}}@Z2mR(N ztqr)>i;%f_U_EX&m+^D+z}jeX8_Nmj=7IHuB)s9+Jm}KIR+|Ub(~{XPoSO&MGm=OT z=jMU+tR%9-xp`ncCyBi9FGy^bL{T_553J`U(Iq@mywb#0n+Mhw^C84j70%5AYpeMZ zi1DgIUpBXam>=F;#CYu`mpw~`ZDxs$VnkWbSj|IF3=YlKa~304L$kG65>7OSX6t!L zsG-@aw^-T;qghVF=UyA1SHGp9ZI~@b(ucxrwZ#~|dm(-*r6k=f+CW9k=xvk>pvBJ8A5IcnOn?dWAzH)O&I5_LSez33#T_gFZVE3k5oZ_ZCs_%{B-ORTUe>2v|8SzXLGs_lThxEYZ1 zK=2pmFrrXq+%Z*r7Hwxv;q`3(MD_?&QZ|&#y7iEEjc3SG5L$>)MXqpeI9+$NQPr0l{ClQDRn%J>S0yWJ$JL(Xs}=$m@#qd8x)% zo8q;EWpJhj-?_~YhHTDv*_!Xux-ZnJf$Z^^ao$jnXO%SvDRb)~3}RC$tLp|8WxbWw z&5JM^mJVQ{wz9Nlb=MPY21yhaVc7kMvIf~?AbX65YkC{cW_h(|ay0q_$R#9qCc$}L zKd`1kHLn|x8-Nt%0x6cL<;Nj>k zz1XE)yzeOT%cOqaPQ=RvaVAlGRM zm!3Pgo_o_1ft=(rjTFJsr>N?b~3VxN8^qs*RRx4cA#XTyw-nB5d zpE2#;hhU0P)Ha5q?i}McG_yO4@;Sco2<;T&KU|}8g&We!9hbw7>_Mq`>*w}Xa$KI5Y;%Px7NpwTB7H8^ z)}Il67MaV>2%k^2YrEmVD0=MYn2b&R@urW7m6E?w64eX174GMTYdpn`I3{YC#!Hl;_1~cv}Gaii@N@cuFI%-?29c^joHt%+rW37nsxDSk$!g;wsCSzqLOJSFVcf=Uxc#D;_nKWKQgt%u zoG+oDi$hQH_iTD6##SFFMz(bHLcmeIEJYpc@??v>=xV0_g#lczC^+QSHy-!IysC>wE?X+NLQAB@T4JmoQ}~93l(x8e}S#As5BsQf@4Y`USeG;;LmV zc_nTvbiawQT&ZHIf!`RM^VWE&$YxiH>!^4Jik;-a!41zsp4kom73*yUUsuz37cJ))A7bp2gI$af z@oKgj?MApAwaI0?S9iBqo?$=Iaxl7-XOQ_G+;}7TXrgDZBqAd35~Z0KlwTCXGVNRS zsQ~I3k?yGg5>BLhDqsYT~kgZm={c-}MXG>Hi zN6!N}fzh)oCK8UGLv!Wm**#BB+3lUM>a| z+qr(JG|SCQsmwCjFlKefEzIg_Np*sQjyvgKj-+cr=g1Crjih%|el6v5%^38pknW&Y zlb$E#Z9!vTeGmWVMzhp!7EQp_iZ=wJs`kPlPX_X)s;Rsz zM)Jd=O*g*?S!VotQP{`s7RkGhP5-NDq&nqsLm&G|e>5UCx3qW?9V!g{3PnK;Z$ddc z;0?Ky5dQ+DMRQ~UP2bO1<_>9K@>7@@Qtu9_r>3AgS}>rDy9%WuaU=cbTo6;0RU(IT zX*IQlpYD~})F3m38|l6CVAe~SRRzp?1!dMN$V%Zx`tR&W$;xVZz$!V&Dp^~xLn*>Y z>%79*HSICwvguXUn>NRA$k@aOOb$>sTO*=lc!sAHa;P1bSMA^)T1~vyPunR-Tqg zPag$5Etj6o(-YN|{ec1)^_KQaqlp#g?Cgp zy}yb+2xBzOM20e5<-@zwDxc|{gEE>Pl#z?ej9gr1G~LZe+|}Ps^!KFG-xyNS|)NJ$1laS@su{Z{GM*0lyIB`vrfH^B01gD_l9> zBKbyc7rHBGZp_dNSiYcAb^QYAb5|K#jPZ1mChf}61A0R}16@0BDUkkgs7P4ltD^y# zPy4mhnW?&5t43)-5_s%9uC|fBm1EKQX0oy-K~WXxd^1*7j?DN%Gggp_`&Wq@>927> zTC1%1xejHuR$BR$*#@cV*56;6xeb1%0EUZ|;lY66VwK%;3YRn!%x*sihMSwQop6eh z!{RJu#TUY>>}E+TBYh6d1}bS{3>IoiJTRyXL)^GGG45_kwF@pBrPtwkh*9(rcN^V@mUvfaYUOH~A4` z$0E5fcv9&a>B+3^$x1mD-9v>mImqo)*X=Y0aL%XtOF;9Sud%=U?2`qTmGFzgWndR1 zZgd*{Ios=NMIlo4yYz1OQXT(m>8lzY-RSfM3vt+2g4vUQ_<@d5a(h7auvDEZRbLh3 z2IHry9C!Ci{(a;ZKT8+S_}J-Hsh*KS2-w<>`1r9~C3wUYOyos*r;qn4mEcZSz#S^{ z1|P3DCAh&A@cyPb!#6Q5(D`O4NoT>_NBYi9*M|ZhhjAAfthv3M?B_w(%t7^F~J5+4oUE(3t{1N<5VHo9;UukfggN-?GH^jjIO-E2P2O> z{usDA@}>lo=>hOQg3##7Yi$Ljm6R@xTbF{0>P0c2G($15!m~IFL0! zV9x7$FU;KcWXtn^M`RgjemAa?^P zdz_qEBBI7l=sX>sxKih9Ys&eEE5BWBl)VLPr7L=oqJ3cC&9+9_r$F}35~FME_@u+o zKzB60p~e}hQE8O@4#YcKtcFH$%53%cMa%*4UkGmm~jy$X;M;alobM* zJ6jxst^YySb}BUnNR81(#c&``LXrmC@)43d9%xq%zsJB|!OCA9$rqcKdcE zfox*^e+T4saA1JB$*4f(@1?;Dkq2my1>VmTcRk1r?~frqPVvsj?;-B}cXV_7^6kor zAbAdcw(`n&AhI|KraUGRR*7~dvven@bWnK%pvEyR3p%=qGrt0pBL!NM)AbpUs6lK| zMDo22CC`CZU5WgAYDwuUV9kZU(%nGterTh>dyV162p4dQn7Lqx1v`adZH)Yqz7~L2 z&#=fWy&2R`pvvw7(hjP)28}(?D_;c$Ua4gCc@|t=ng#xSz<4d|u#p32`x9VyVGi3P z<8h6a@Fvor{>XvM(nwI_L1mtV8b?=bIC5%_$6z*qWqdZWq(A6I(CMj}rI&;A5I6-1VQOT+w9{SuR;%ZdZz4DVz5v}0a^d?;#9!d`0O>tkJAD)J7U(mi<$6-lK4hIO zH~&sZc{XV|fGT<^X*qx@dOv9npr)dmUWP5d>^GT#VpM_AFG@Ulx&3#4PA9PYMsN=1 z-y%6=7pLgqtFMe$z(7UZS4O;*v|O$$`eV{^C9UY6Nk=Qs?NQ?RfuOG`lsU1)T|lc6 zB~{8IjR2!kp3vzZaS#f4pKZTi!bH2__RHqm;>d7af$xR00(a4!tiboe>F!I?G8{$Q zgFwr06y1)r4ClRYhSP_%3`fZ)gI2j82v@mRspvikXM5ZVaX;&Lm{>5vp5Z^sQG9N= zuCUjkfUmZ+fk!zL&y^9Lg-I6~;anLZ=3*J2OVz086g6hBj&81uuAa1vPRZW~t)iQc z=x|}Nr*~>!gnW|%VQi6MRAL@dVI;{g&cIZKk#tcQF6D-ys9r;K7)dgW2T98?l>BAT z2m|?>$!;wn3?6whqr+Gm^;0q9Tda-kV5%^p!`NOQ)0M1^=rFcdN)>2XABrv~E!#`c z6G_YViVkCY-9lQ15*_BJgSW_#S4eaiTPVC*_oo(;9s;`m_-Sg4{u7l_DbGh&g}JS3 z^uHfMcs7#SYT-CnSZnnE$`y7E2(NL4BMiI0F8IWmn-| zv%Jc`ZjV}&o%XI!Hq+gxHPuXag|e1EB`upt(Z7^rYum*P#s{V3~(%I8DOR?;G;vu`(y03{YvQU zU9Y~Rm9y;uXYYDhJO2ted)F%mky`EST`z0vj#^PN76&HQh;d`>ghE-b4@=7f)Rf)- zVX2vVISRt4Ia3AZr%t`ZGcfEf4ckk@!BA9&?WN&N(z3$a%Me~5Ez6_i)-Yj?voo#t zazw{*cD!=+d=o}LVVHLHd=p0d0BPy!`6evQ%cP|%C2u}lEFEXJyNd5uH1BAltA_iC zW?lDmD9bqSkj}3eZWx!zAAxr@VLLwq+UVq=>9l}pu{50;Fr6k%cT3flB67SQ;0Q__Abt7(iuoSu%RFro;Lic+ZmA)r`RWy$xMkUFAcX97I-pf1=Up%1+Sw)}zB; zBx5Mc(BXgUVcpyTd*+o%RaS=1>{}13N@w=1hh_VWnXMKF#@j7MmEbBjMZkN#^v>J# zs&a(%-eROKiEy2(dKS|8&5)|W{UMJEd%n@>&jQh7f*qeFtGJ)^ax&nh-$h>fNiQQt ziJK?b(f)<($X|x&;_i|GP0iE+eHp^yzBx)y3SWlE@>Q#j@MQ?g-r@>q%c@q=(WGT% ze;LB^KMz_3{8fmq=T4_s5jTX0=!pnIMty_K>Hw70{By%aS=}JBN*%4UQqpOpWmY%H ztagB|d@~2GZ*sGms&Zc3nDZxj5T^%9j3&TKaO*D5f+rbAx{Tu}JgGR+-8fX=N|$k< zfn|Y}EO(49U}j@Bm$PDzIJ#mt$%_52KrTldR_rQRcG*|Th>kd_W>q#v9NDYfY?SPa zKsKK_fqMLl7=NXmFi1u|TKdF+8}~XLEuD-dEu$SRvv{1eoC!xeY@S`9)et*Y(qE1h zd#<$mn2SWjB>S$b7IF=C#Mb3dZ`mnF6|34hVzV4^<8+=!YzE$mw9NB}&0^h3TIPAg zW}Z)iR(XCV>0RRu}ROLNR96M$p` z8A&7s$WkJF;OZG5-KbyM8`OuO22}wW-;jKj9c}p|*~e=G#o1)CI1^DuRh(K`oF8GO zic>3#6EzXEEKaQ~PCjW_93>w@S{A2PhCc_iD$X!T*MXMB@rn9rc1pJt7Uu@*WC3En zAHf}kykrHCkSl@Q2&6rcIY0&jk@}_UL0x-gL-=&Ni8)yIt=~-6y)l?y;xkW~<^w2( z+J!o$B%QL@;omlO;}t;Ltm82-Rob_u+5=aL@iVZ)zibMAP0ISB}aeN!G*s2Dr|FF{VRnK2`-=z$@vq}%%xFZ zs?caO5gJ{sjg}H&4i5k^GEeJ!K~-FkoCk&1zB7~om}^QVFcKQf0tFP5TSKC5F;-NiZ`K+%Alz0q!>JT7pjW4QF?>gC^Pmi#@t%+EO_1M zWE+r?M0NqWo(P}tdW6VPAUlYh0CEn#PlS2B z3S`hZAlrC@_XOfB{|OX-oaAkqBv#F`TU&=GiRWk8N!Ij9;=NgRji#2 zOq~XVzRHNu`+Oo9%+J9Y_cf0+Rm`HPZndYw$rWslUdZb@C7JVK`b16*Hrv@Iqngko@IxMcdxcX z{YSx7z4jiKdMBFq35LVN8Gj}636L*haBPN@)dF!$PPJ>{Z)3vd+9x|3JUCq zzd%8E#D!DD+BtUHq56ag9$cyB$s>YqrCI$Kqy*m`X7!j{ynzwW>QJ$WnQwoClY6+4pVSby zK%Lyf-F$U&FJgDP7u^A8PcAGB+{o_>d)~;u=~`R8v>{@!mFbZRrlfu3jmW%dm?UB%n~SQO>_qc`m~oTc8i#D|yvbhJ zwFuRSZxzs+1u*M6ynsvJoET#E!(@_fQamw)-ZJFVDU(9pqi*JZiIT;3>$Iknca-L( z()?jqW!E4qaEY5$*#|ob|6=?c7)sr@9hxtZy6;l=afApiaqMPBJ1k?zI>xZWVYVx; z!yckk@5p{<)=Tcp05@j^b)S%2Gxu}m(N7X&(iNo7F^XYQf6)wav)@ig z`+}_Yvb-o0sy1y6jnw;Z6en{}v3T8Y$CN)!$k+XQz7cQn#(ldf!}e*&F%l)f+6 zufh!qQ+Og$v{+*2`+s0%X4nhE(UTV8aG9LMKSz%!kWG?dvq@rSg8myFWXKH1gU)}V z1L!PC-w!%#1kA%wH^sAoa5=S|{SuGY^u$-l!QxUY>$FA^*&NM{$wpS1!f;OLT3F*@ zHpa39_gwglh*>ua0T#$6pMjf77={9Qt7A($XW^Jo%0k2Y6>8!Rbff$$PSHssFB|^5~ib# z*GLMwu=HG`k?|Tyo~f}#8d>flM)#kK#e}7HT!d`YqwG}wm@SqqwZ~b9I*6~A+HFes zFczU%j#;6H{bo2=I4+q(de4HukbV_r9S-SofeA-r8_I66kDB_`IS0XtH+;iH)~$AX z9;>RkRUWJAzFZxvdg->nqb=Q=sDZfK3U?q5KXL^eb0FTiLY}C4>UMRa>Y2ObiK@Tf z6*xlu7P65is|aoR^PYV|^#zrZhFh|_ho%@^W~S#9gL zOdN$4-!k#gY8+o&EVix23HNE3Va>-v_u_(3H%@QB1<|1eA^?~8)T=ST%5i6-+&)_l zIwR_O+#O_U*J%Uz#Iq2xoK1KmCoN+4~cq!$9xHla6&CimLS{5x0) zzEJp4&-v7K#W13dA^AdEqt@EbK_$otqNK;ZpfjkxH5&h=9pf;30aLiP=W<5bU+~g? zWWfGkURLV$+I~On{b}DbzQ0Ka>0p?3uLKr<;tl-_ifg=Ys4n z1ni%a_HP92pO^Mu2HX3Mw9Tx(I&T?Hc16hmx*|~}sFMzU3OHCR9pI*!kuezRvc}R{ zumCH)&!QV8O8c>}?V6yHcME6L#v2+I|x43um#lkIKDL`rrx!-e2!n(hpk&XcAWr0K7`-iHNDRrT<}FIBW*FvVb! zHyu|i!o7d)(QqiB(A zA`iy^CHT%2yd>-1!>*_V{-ds>j*|Tz_Aw>d?+WHHlbs%R9wpf63Z6nAH|ss@6iQI< z3JN&rZ1AwPm0*J__yNJ0_j>qMXeGGU6PWQ96Q{>(_)^5rNorz@+*{!Fivu(~gI$}_Wcw4~FS%(qt&~`mwXB7U< zyx$7g6iJ(t0h_m^&Ebn}4s;fg58LshLl#ZBkE8pc0rz92`;BqBUWQ8J z*hRXdTrRh)ixvt0!*)w+?jlk5u-&1e)VY`+8IVy(* zlt)SBw(&a0FsZyVkYj|*@d9Y0Fo(VBEt~Z>2}AvAX}URJ`j*Z5>vbJm$qn7NY%cZg zA}u#`-{RhQoUsdx?s8T1woT)&LHAfK9(@D@VLjXqK)n~>>HmdJ0p3C?zt0jagDCun zt-D<2kE{*$XtORQL5IFv=KnkMlld=~`S-hC=f7O;&Cdg^vR@&yzaMm0x45Xh&&x6Zp!mqqKXUw5*Yi z(k}Ey+SRdLKC*P@d<{IaZdxK#We6WxtlYs+Rjxj=Sh>4MOIIJs-Sn0>f#&ie1FkqG z^#end_7jUs(0f3q%O5f7?!famiGh#WrGCC?1@Gx)?)5hq-WO%=_~Ngd`zd z8$}^f|3Gwxq*m}#BwrF&WL<%H)F53X<1u>5*TS{8%mo2SdnGB{$?6OVRA-tjP<^04 zAyVyK1R&dV-0O-vYVQeAJVobl`U$G z2>mx-3X6<^H;7l(+a3JbSo|%N1>tYAyn9iHI0O zy%U_SOWYMCil$GK_2EVrA?it|kKS61dcx_Ww_hVynteKDm0{~83pehIJe4-A%;nAKJf*VQ<*c*|xVNyjytx z=$;9s3FziUhV4@f3u9bHj?ptgGD12eq=btvcG;~8U6qjj(NxL4eW__SGxMWOtdKh1 zvD7rI_?|*0@0q~pb$J7fj7AMBUY6G%j^Z`<&^-I%qIc9Kq%0?>=($>eZh*qMIa+ZjcaR5= z1&uXQ=+*+O6_O$)d7vVpl=am~c?3xcA6#o}7FAUbRwOWr&OzbBOBeCMe(aES4c1SQ zHGvZjs$E%Qs2toJ4RbloKy+_~W}@d2;Uh!nxJL+Dg@N@9iW3!B7VNrzv~phFsDmr7 zC?Ze=xKJ2TjHr6aZgN@g#u$>YH`s@H)|i*a={);}gTP!+kyR+7iSyC;z?z&oYX8so!GQ?}U5@HY`h%4etnO;A6(#Jf!;D zXz}8nL)e0!DPA~ackZgc)!Ms_`fLI|zJ?Gs45AWcbCV~hUi?dzatf}btgd}`;K zm7@AnJ8qi(!nXcOxc(v<6mcVgpA%DFVmhd=f9X#M>kmik@9*u%P!A<1WvcW>q#I$M zlBK@HwMKmKDMrMNIVuSKF)Mtc+FQrG@K>c0nMUQ|g(j$;z4^!eGFCeVX@&o z>gq8$2e6Dhj9iZ7>i4%F>a6bUlIev#|K8`R5dNJcKw&&m{ceB#F@ud=)fwN@NI9SC zuQ}+?M2s#`wXMH)p+B2(2z=`QffTbR-aoBU{n-()P@l+Ozan0Lwnl#mM}H4Sf2l`* z{;0O6I=?vHP3ee#NdU|E;UQge{Ze!(#D8pR%Xk-U;MNT6EtX%u8d|?I`eh2h*Ke8D zuc+29x7P2#*6+$brvoWdfx%S%wZs3Gaj-#W7y`_Gtf9MeP zn`89LaP%v6Xvq-yM^7Whil;xb)2wA<#lg?)qTcT|H{Isa5BXEGmjB^zH2)i?UZ+5m z6{+9vK$>rvh!`&h9J7mZQrl`z>XB>8Q3U|~ytsb;oP6=@F*~#NY`(V9&k*YeX!S`8 zo^u!oeSPXc-@(`SwDoOg`edJ4HbrE9Zm$hn=AJgKpDGT1Zs(NfhnJ|wtA&3{_#YlL zOm{C==A$2_(T@=o%@-xd?d+JIc-x^vefjqx{$Da*Tz}k7PSv;X^nENUu&wl+zm?aC z?Z@q+?3p)d4|B|HVEQ>R5EcWNE&mQ;@IM3i1Aw=w2Ka~Dr-GzRPlfac?+W8QXvfdCHTnvYKn`n~+#;T*s!fEFAEeiU#V zfVc7n_~>@t>jASnA_ENPTA%zFm;Vc7nor#u0ZRbC0ccYLmZBoFh38>INw8feZml0V@HTPaV#a1Wt#p zU(w`i+<_s3b0dLsBY|@xfpa5)b0dLsBY|@xfpa5)b0dLsBY|@xfpa5)b0c9XKo^SB zBc?__|MPNgByesdaBd`UZX|GSByesda1PX^BR(522e34VPkbd{72v@jelYK`p8ks+ z@w*AyF>%hJ1kRxZ&Y=X(p@i)K&ZC?|37kU-oI?rcTre=@5ja{|E!YI! zWYqH$sf1Eassv7|1Wu|1PO1b< zrU3`Uon8tekcu-W?Tl7qFvz*U36;PJm9Tn@_~R=((ZdOJ%NVitTYI{nQ{`d6Q2<}_ z_9fsOfQ~+x7c~}7eF0(tS{}?R4&sjoJ`pepFas0f z#ggyr^e)?h9ReH$90O?Y)Zo0Xy%OjAF6Vfp(%Qco=k2xwUITFE*4E@d2v`HC1FQwC z2RsJY2+(@*lhH8%6#&lonoqhCFaR(ZPz9&~)B=V9T)l?3PTI{(KObG41o#jTkB2X{ z7e2JgCr|gyM%e%-0G_LHw+_H(9JL;GXgdtNmxK7)W)FBD1HJ^v2OM2PSMK-j|8EqS z$zZ^2Jim86Kxe3(EyE*@D*=Zg}bS*=Oug z9vyLXC?w0=Eja zH{w{N@uKu_e|O@I3gvR>Wuh1YUYL%WySclt~1oD@-RIjy6(60}cP zc=xS|H&O5NHO#S`TWt@QNA`a4uMlUIhf5^;NpZKwY2Aj)Bzt#~89mhwO|h@f$TTg3s7)6T=yll_sn;BhiqpK?sZW>}8t8Q|$LaAcC@Q3mX3cD*QX;z6w6o{s^z7Nw3Q_*K zjI+;*m{2Fp!=;@4pePG<;yql>*)NK*;J4?J&i*9Sj9zcYza;K8iqEbKGouIPW))}+S=_^6W?VkbiOCw1oHJqA88RBpr2+6TnwFej(u1qiyQrfQM&_GyHfnw*+jn7Mv|&X>zd`)AP*=FIbOX=%SB^1{(Z zTwdBgh*9BAm*Ne+pgg$Fw4d|Q(V#XxbFb=t)%ra9+MEh|L84D!O7DPCum0XhA_qH%o(7;hS_BA=xN!{DF%I|rv6{V_z zYgPND|3QI^So?3{LWI+~2^X^VzgmdSkxrh6i&^_AF)Pyfpvz;iX7oTEqpXiLai-nz z;@W*L&P=$dx_^%o3w=&m27e#e_a>N~1}3MbcAsu{n1Y^|+a3RUT9GPDu9EG)i_d*d zif2CYJ48uSr%h!+ciUH*m)jkMYMYDa5_mnx{6A}Hw!8P11$O9sE13PG%MJ^$xxTjV z5>GUB+Be}E+di2nK4|I;Yr=)LeI%(NC(3DOdbr%SpKBP=%!#wD`p)8-7$>>~*VOhW zwi#`OHD)ayigDhyPIeZPS~%@uxU#k%#eQj^CynkR>RLGct&Ls9KUz4+38%Y4oA6wyl{x8|JojZnFJcgWK;I=rtT7(Xw2O+n*Sw zrnxA$ziFhoIJbXlq`649F;;7RF4l22(2UiU%vHO6z%)}UGWFod1-$(kb+X*yl1q8} zdvaU`*Y);=Acj%a@K9?f%C;iP8lFjY_S@EoGI2wilW46jYY=HpAE%bfZX67Z(LT8R zwlmF?Hr;h_T!-78%#`j^wGLP0b~iI6PmbX!o*qc;Y+d8~%0*t5bBDE~LhQ(L+Qx8w zZr^E|X`8jZ)2rd1S-QH@M(N}5JWn)B-Jao#{V;XMH za|SyW7VMuEIVskmG2&lEPG75RtmxIr8EauL>+w$L-^<1}%r16*vaR)F#pDvF!7|2) z&9^n_jhwHH}P`ShVM(AR~@TpLc`PLm?5&cUbSDd@kaR29Np?%yV}QXGcGMP zS+@!=;D%o+oaT-dcBP2u=OkD~SBeh(oIRjsGo2qz3+tHYW~0>EH;KKoovapIzu3=5p`Qkv)!!t% zS0h|wu_(P7)nDds_~~jV*|xBrX)({qw6N_|KF|5pCni1}5|0zVPIg3jRYgIsftU53 zws6`cG5f`kxP}c&onOt+apR`Vo}XVlZob&F%;_A~cjknvhR&Zbf5E(l-dvp4Y%LnbTu1}-09%SftGhUi!Gm2 zm^XRmlyUPX&zs+{>29Z6Nc5yxbENgvbEi$7jSQw;J-gw{`<>eG$bMD*hm5P5Hk;W_ z7M<2Re>SfyA2?33Yp=fQs+p4^Y$)8|EC>0r6X*`zoo$$(?;K$L5(d# zjg|XShKKpQ<>4uAT|^0d+n{A+yi0PjtrOMToPHtlZjIQm)rl8dw>eF%z4>C#HeAe5%!9c+26rZUf-Z8_r&Xv>zjal{ASDa)&W%}+;A79iebF9x{S;*&1%eyz_ zIThjZmH}nl;o@F>g_QXm-bx^!)9-)c>pMifsDF7tztGUPj4pM=sW{k?t^!QU z?`(Gx+b}bITS*33<8!o*yv-!u+wR24^69%xGK<>A+C|9nZk{f$z6m8;p|>ipmgyT) zGOK|X%k<5vU>QS4h_-85U4U~rz{MT)Npm$2Omj65Omj65OzT@; z+Me5Y!SWrK(62SpaWX?L9~@-PI%EL5dWt`GII&%cbJ?H^Lt5WQ)0uJ25G*&aJr^OW zcQ|ngxEXHf+h|lF&A$=ip3j^(&m@poPCWdolPK}kWn%lQPO>>keEO=B+xHN}`d%43 zEoptv%xxFh$;syuBLzCLVJ}k`2Kn{nV(@EDY$$PgUrkhR#mKqjHODC-Pv2v6FVjIj zUNCN6NF*+O_G|Qcyh6MNpUr8{Z9|yIi}g^1_~tby)j}G!)5-KWK9s(fDB08QN0m3|5)$LlJsb}s{~%5hA`P7$lnM)atqKvr5)Rg@_NX##fDFv z=zQ&#>e}s5h{uE0Zh7@lue3LIQduK$foOEM(Qf`dte8&sk;;2;1c|D#H8Xe+EtY ze#qN3HltZ4UU-21ga58if^kJ28szCEAMyG0L>iUBK52;)S>29rW+0U5+Dp8wYdZFW-%(*d@B} zLQ`bp=*KVMwi6#9qp%b>9RXI-5V2~Plk6crX^41nmy_eE2maL%@y#wLHTDp2oNNdT zE2OO|k-Qt%E}ubnszi_7PC-Z+@H#PJ7bg9g;?doh=4OgFb~~Lz_CoMF1#MOI=Rki| zC8NiTUcCnqrig3yI4zOfrIM#qvU`uy87qk2sj^SBdJ7AQBr)hMxGoddAjz17lfFko zu{DSJHq3gNpA#|2s|;7QA664CXOBtZRa(`HFWz#Zk^BV8IuR=p_hR!0X$jJaCt#S; zRK1lg3>VBQt6w-mHOMdeZ}^q}4S)21HU9FSWY$<-itHInrpKWrr52l*AqBoX9V)@LC!4K=B&vJ7Fny{1|B@~VRLlR;AfS)S3(f0aj}cTK>|pUo>jNHGa4o|o?Q&g(l=0>f z^%y&8{xJ!rIk;(>H*yzg`vNftL9=z>66-Yg5IfwM0%P$@^s!zu{08k2vc9dKQJj`#xZV-LZd zK10LmA&rfSv9w^;lE_H8M`-o=v|$Nt6s54aKo zUmmlO(|!+<{9^!YQ_}iHELeEm;w-ao)txd}mxVfnpRWg1bIOzqt&z1I+%|i5;u! zXbI{kcp@PGkBju7Fhd>D(wD3913vx+0yMt}IPKGCiZ4HQ3S>2611<3rC#{@({jq~f z^P?YqG3&T4rRBvPXHFFled4tAOvNvE+;!ak33eQ&iqAfAS`Q+Nf2<`!FrDJk`lML7 zFGBUQ3Sas()zM^6qm4X8#wB6ggkTriCAazLPSYzdp&>Gs1j$L4UP9}UW2$)L5Jrw| z9dPCrZaBlI07zqd@Q*`STN1|>;oz-KVmWdCX>-#0xd}ZmvuU*6B;cCQablae=~Ju~ zw~2?49Z%{H=joOM=FZFn9^+nO<11CB}vc&J7;x452z{`x)p=plOD!=ZB(N<*R z0NvQb*frBCqXH^-K_x-6$AXQ{!4X6b!P~?ehw+B!M-~ zzv+qcBbej=jg5HqK|gJ-t5qNT(>-1noA;H2v)2a$wY}Ekedl03+=GsjPekfVf-%d0 z7K_tIoXia3yfMx7%cai1YU~T5{HPO$w!P*k8cBvrG)_9WND&VCR|UAZE?@Yc)JObB z^=Z297`84WPj)(Z7_YZLqysZF@#!V;=R3Ri8PDc(2`4pW)ZdBJuWTPRo!* zkmL#T7=ENI62D`oL~=$*jznil)I+@`G2%7+Y!TyMbsYYBIObgG=l#7ZfN4}QsRcL& zK8UuC7~b_p0TaAN&lM0`sRT^c2L!~9D*=bj;LWkFtFj`r@GvD|G9n-$ zHcAPYd>0T9`&kK?{2CAt`&|i`7@c$`#EJpPok>kVK+Hc(Nti4QNQhmp1WYys1jL?I z0w((c0%H4>fXRme0kMyjfXShNfY`B4C_myl2K;Vt^|$ThmmGx8G&c{%B(5gY9l`;KF~n8FZOS9y}pV?35D z^J4NOK;=bjlM*m_Iv^nStP(KU91swzR{|z41_Z=-Y{QQNx!KC+LGUCk%gBWHC@wA| zkAqw;6{?v`bQP-C5u>_kRBLDHxT~EBfHNjraAVsvI0VbTE?|{V>Nl#GD)Hr7TnW|y zij68JWzu+w_2RYhibF@dCl4K$qup(Xxtoo&)qHB#6sUf{bgIPj*KI`loy%wXhvNI!C8D$B z$&QmBh?PzpSD9&qQeMZj7GN5eGf}?tr0csEPpr-g$r7KB4ha?O!$Q1GJcd0SU%eM+BSMPA`mdZWe%|uA z7XS}T>Hw<45L>SVOn7SJ;-1uKS*hswat;RBtVs4KYs2)j4zk72AE_6R6&XLPy!~5T?uqZ zjh5BHmeuQMIZ#?wGtrjSfsg{0expX4n#M5N;X{@PrG^RZz}4CD7|t#L0%fufpyDBR zObM9K`Ne@YT2=>JR zflG}6s_F?`b$r}HNk=qFRUOeYpTtN8Fm9$w^>RL#p&SK@Ku76qu4;biK2TbiW6H#$~b>U>gg}bq9ek zx1dH}f=~|v9OIrX{&mE@0GP&5CaSYjpaWBC2u9_vNL@Shf$uA`4xa}!GtA4)43Uy6K77dlsyyX2CmL14J6%089y~?|C7X zMCCIQYiIR09b$Z+2I3JE?~s}!O5jmx1_rFYP?|38K8X#|H=*fjE8&_pl0pb^&CG4X2zIqSa~KydcfEO9Q+ZG3B&V;2(vxg>D`m zR_zVoRgYvafVEe(j@Sq#V8Vl}O7QQN)!Gs@+-O#<&4LydGB>~UTGMDWoJOM+mkIL< zYX12k-;^wOHGms?Z83EL5H*u+5*@+heZ^(M%!00&fQ{d%ZZsN2qmQLgH4|kNSUm@f zjG9K9D`;~}+SD*nHi6-hHXEgMC=(?Obk{X)`>KE~;~s;KC?~G}be6nYDc=tu&h#(< zeV55mam5*@bIehoUn(w>6M$1<+!?1p3^?ob5V2>S#ffB|13Y0C*p+B|^v<$G^i;c2 zY(DG6re4eoQgDAiL9hNtr-kogJ!w1gV%~qURlGkF2eixUn9iSLI)*13faL9fmjn`fUu7@$HNn;=zsjBCK?yQk6J$>s_4b7Ks6H36u3Rn_L1Hgg_v-V%?a|QGtQ>IKd z0+a$VW(ZSVjeHIwU9p(t0F*AV!AihnWh{5#u5MmWU?Hf6o_q70w#L`0%FIzDammp%===WJXJYLDKHrwP$0IbjaX}jq==MX zoId>T>)CuDWf1@&Fj*qe;Y^k(E)za|5_F+8+Eh2%3~RKhZnOyu$&bOsme%5pf{;|P zZ*WMgC=J0c@x?tuydtGABvO2S!3h`Lib6sgKD*#Vnf`d_rvTXB+aVnVKp$r^8Xy;$ zM8-;DzPXMF1A~%oZ0-mh2B2(A&H+?i5%WsjDkgkTTnUIpQIKs^F=Z4NS1%tdx4`A^ z5~j3Q7u=km9G{=l>M=QxR59TbC>Prw0+$b>WA*q85_iN`S;K zACy-<`N;fWC1Jv`=i+FnutF--u5}fH8jpJuB>?2egwNS4b7J$9fC(SIR{~&u@4ZUG zguksX&XK0nXQ$Gggd0Uk0P>i&lX#bPOh*6^5)+==z0|DO^pcLXHRv{il{Yv(1tzmug9r=EW6(gaIWUJ)ftQBk-zHgteStK-(T!!3^S^;JB zfyx*7Pa~ndNY3hPF0`6zO%hs8HpTS-hqW#Vtt2aO+l#SCuuDSy6omlnaY`djG6{(q z@fzmt)B+M)G#<6rY;fl(g%}AwtpYdYXF;edPN2Vwq!rB|!8WsyR&)gE)W`b;^H(CT z3q_YH8&PPFG8yX!=|EK|x_aayi83uEVKtNM#r;3NMMA|%2KNpNYw_x7U*DfpyoWbw z>6f)^a1J+O?e6r7vRY@H&&${o?(zNh9g`)vbvR#LF`=KI<(J?U)oEFNUIt7u(+qe) zmf!w-_U6M`{)K7(lKJd^Eu6{!qW-Jde&6%s3=wDR@Y?!*ukg7pxPOT?#g*dg_5Bv= zU-ZEDN4Pntc{DBiI{v#A|LpPbPX%1W@t~eWNFIqM5$2X@0m;UnvhSLQi#z%`;phf_ z+Xh*W;=)HgbqarTnV(Nd^Ke@O|JV78vG`yG61tsaRDU(pNM`h>m2M2bLD=;MqghC|T0wj4b@hyL?5SI$>P*BSNl!Zigq+2R=-2*zVW~@bmHxd*L zQruDF8>JB^p>cgk+9svKaix$Tu?opPjwyvwl7AqjA7>wxPd_8}o?5(bdmL{!+T6yhXS!8H*Tb}NMhiB)hhQ(>o4C?)v|5@RMk z65t>GxuCh2O!dptWjD)%wUbQ>zIMsx;C2FFj0owu($WV4GQWmyV zW;o36Lc*mN$!;WGt`t^#MNz1W!Ca|yVkEysO82JOil_xO4{9+9wZ(aU2H;F2{+h3- z62}7&uEa^MGhdYsk)TVmN@dGP_||cMuqiAqSBOVmbo?vhv)juGbdu+4mb4i zFAe(*!9jeYgP#|6ZRX=)6!f!|i5Lmr2^ZGd0rnip8{WbYw}x%H^ZnvQNC=c8WFVYyWy$xKvCcI64~eN9#6W;ZJcJ{ioi5(NEi9?lpeH@PVd&-+(Vi57$0P zrXXc_RcSTM&|Pu>|C{!V^R(@jKWMFQs1Ra7yO9Hiv-q{)R;!bC?(yS$UJ_Th@g zSuj0(HxCE%PjRpXU{xSNN-`Enn`Lf>7LeQ%32cjb;FKtZQj#*Hbgw#-)LJR6VQ!L< zkWNRU{n8rdU^IZ|s55D@5{Xq{$-7M6y5#0s!sTEku8!`uDJBnZTF4Tb6&(Ohi=7|- zF3oQr?kn*-g{@lR`l!RDxG=*kl&vp{KFY&$C{+|LKDAyq|08*9`k7cAd2Jvzv z{EkL46q?ux`Yx|s4YT764BFK&`xX)uN%j~C6q((Nl;z!tGjY3`y#WAS8bdaA>9!2M zVo<@cOT#+A=zx`)pF#7u3b34{xhgb_q(EiMNjf5>doxskwPOR?jh+`tV{D8ms#pRa z?9F~yXCDDsiInd3t|48o*)M`@(b=sauj}kKkR3Y9cF>VWgLe@etO-=Ou{9tYRW|yy zQO07Mg`M0*^?8h>tLgJt4RhVKfP`C!B@a+?`e_9c?k%P+WXyc;#BnRuqs)4C3JI$q zM@eM8)JdZs$hj7vClUrC$sD98xaP_M*;BQ~bdXs{;mRidRpIkZa1+v~5c8`2H!a{2 zg)T@iM>1b!%SfKqT$25oOLAIsNwOxZYLhfq*%(Q&=Gv-eLNQyFNsu%}%J8OlsG)}i zw|U|Bh5odFd!jYCLj^(duF95?yr;P&+~G~vl(|l-f@LIZk*EojU)mc8B_4*P+#n9W zWUyRERn9%}gk~ZzstM3aqj9fZ6rhG-`C+>$iRw>39>IXV|7=-0SuPgxT zZ7sEXWI}4U$wZc8lABnvjG4B*r6{mf6-uzs2dXQhGtA@0WEN%z9{AR-#n!mR)`P{i zw#$qi)X20rg7c7YuDTE8fX;pZQldOm%mG=Xv$Uc8Mza@-Yt{&B@h!xE zV5+)oh}k_zMWoz)^j##*_WFn>|=sLqlcL&7;FJ({kkV0dxF2}?sUj=0|_Sln{- zh|ZcY0*^y_hT4_wok_wCwdrG2}tw|UtoCyyL1?FiJLsu!-=C_ZB#Z!GC^}mZqr;6t{)Z0kh2u0B}zHnyT^u3ArUDA&~VQUoknS-q3+OZt*EdM zi9dWE1g)5;^TR=_P5wU6^(KD+v@rsaKa>g^nFj-BBvTm46h<8@xdax)%xkKth|C2S`5AToT>l(Gk!6avwuN8Itx&v5cgH zE<2|FlU5SKdBB5zq7LdI73;nawi^%KND|fAz zaIIJFS}&nnZ!;c2?#K3(G{MsgTQJ*A{=8bQb;gOC(|C^D56*k?e2-o&w@1In?YI@0A2NN6q+?rrV*GEh4vXmQ+$>nNOX(#TtL*y^P0MFkwI z4z1{Fg_~u1)p;j4B zkXQxRMN~KuD2>t+Lc{eDHM+tuo1fd_k1+Wup!b;kHc;A@T_nn7igKBvT&5|f`akL; z?#bU535{g8HkkS&gxKS)pQs7-%qB=RW#*5pa)3P+RmNR{YDhvg0! zUDBgUH$fA+SV9*2XWqUu7D%yuZtO;XPQVD;Bf&Gtbd@b9xleOR7HKZYQ<_UM`EC}A z+MJe(lr&DFEmb&6aaz)4qMpbJ!0U*_+FDiS>FSW-lO91rh$N>~b_hu}BA_;Dj*2Em z(oem>Cm@-s0z->HbS;OFuxc18B-JWA#MJO6vTgn7rv!_ei+2Rih!T5_(YEj5`M)(Tr*L67>VvksgmPWWoK38X0@rhFsn@s zIiDdlz+n2GXBi~1XlUBzA@?S&U|IZ@#;Zs;G)VYa4Lz2m!WM8@N75Zg4f&954)$Q+ z&HF(xJ|Q#Uv*Uh-Ym2`K$$uk>O%2`#Jdn)dt}AO4D@MZ2R+6Kz3h7=|J8C?S#CHfF;HM-b@(q=xv#Fd8cXISY}p!PSF`ZAR;kL&P?s6>E7fcyx+> zv#cXv9Y?|eLvjKMW2Ue%v~rbZf}|-D*}7D?d9>d%Jo0xe1$jQrzaTu3hd2Km#DbL; zn=x8mOAGjQnq^3ENODAF%Sk@bT#}=jOY)iKl5k@pF;mgfTE&W!yr8lP5?bRJiq|lw zi<$1aOn>Hnl2#_6n9A<5cMUj)kg!1g<;U<|qFPuMR#y5QupI?P{cyj9Kj?7^=JxQX zY~C~6Z-7rUU|#!N&22G~jwp|@NYYtlVFP@)4p7o>kT6b2wA%{jHbJ-Dm9YxgZExDP z!bOm9ZChdM#RWeD!`u<*#(jJz3@f<|FCpnYoo(K*C+Xw7`x{e%k$?mV8Q=w7LTTV~SOJF=+w`vr93ZEYy6G zMTU*9V%#y-e?P6L`BG0k>de4??EEW?u)bp~UK&mr=NB}o!mEIkXL$8Uyt44gasJ-| zp5GP5USdVaj1ZW6!IcS&nZv6RxEJswf$>>uZ<)ZYQ!o!cY=RN_!);I4@K(P`y0B{CJ)1Hhq51YCXv&GX)?2E%$x8XHl?mnPOp;$Ml%?0KcztfGGRjr(yZn&?2 z)h8|~aF|sYBrxSMfhnIMFyw*S!U}x+>9|)UD|jmfrh$zD(*YMEvNX$Ig$le0%==Ya zfeTwZIrW@tfcqs$ z2hBS=OgXnolJXe>Q$Ew+z&2t2C9VJ!xI|PMSSm2(TmUNNGrKrUIrkKj^3wuS&ZVIs z0g~>5O3hH13e^I$1x^U840KI)u%(;Bl)o)7%jaK~EaygQdhb&cKyJ@u1@7aAa`;PE zgL1#XG`P4|c=K(3%iv~AI!iIRa_dn$xvm$JZvt}STp`~k76{s)>+@n>Cb|E18_0;cGlc4jVamCd%*u(6Tg)Sf3@)XU z3S6ZpF<1IY%;ka-bE%@l2U9SYHcB~HND>Ejd?XCRVlIZV1=wWk1!llpCo1I!1*V)! zMWx&;ahUQC!8b6}X&K8mJYR2Dr>s%41hKOnI5WtiT9?DX&zR{!IWAgaQk= zHP-dKWf)|{_9$2ZoO?f>`{4UCX(<0p9fOpMxoO?nUnB4A!l-FK`N28$l z(}&&J6a}xJs}T)k3%uJlA^5fhbA+7wgH!N0F)@9l%A5LI14B~^ED)FxFBX^%D*L+t zKdmDmu2+H@{&WTB2uyqPxpGO#p`aWHOb2TPrku;Kq&`<~Sxo(nS3697u0xaZLjqGC zaNV0!@UC%~3S6FNR57dW;q{3REzyj?abp?nAq~LJ^ zk1I>k4CP(Cp#!`i}MVkg+%!dkgo>jw-(r< zY!QC62n2t?@UK2qq%atCc=mdy(4!6q{Cttsr@`zS9A^1;H#&S>9pyU-c?Am$6pWke zD8SDhNrzKXFh6Z1<-2bTAHLf!xSHQGvV8iPJlNrpb@-VfhOFu>0#(GQQtgLTOHZ6zzG zgWNKQ*^)~IrhHqulYg8M=%V~@=cD2Zr@#V>hdBJ#Is!N(M6mo zpSc1mLeV1M!@xG+LKx=76y-;RJQMd8#8%!=KYD|fs}MgTr5GrGVT$}#Hqm^cpl(*Q zcGM#L&XhHvT14RD6oabCg`D~;M}(th`vpx`rSR8}2p_1mg%+CGW@qg;HXfbgVQ6zy)$q_h^?=^LpZz82X6?+*Wrxoo3%mR zTO|Usak$`F$|nd+IX{Laqmx-@A6yryt9sAxuR9- z?iZN0@ZIHgvr%#8`;AK0Efbh>E>4!VW(rLCe1X}hD+Ij;2r-n71Xmb8DYW#|h9E}^pqSwrvV4sWW% zU;`oF1$jeYdEvojZPwn$kY5fw0Swe%JLKzR%`f|1d}geAQMetifx+7E{i5jxDBvBa;2m9Iq$r2!XXONXe*3$gsg zDr|wm<<-ee$mL~L&KB4*#bMT%D@dgL#59K~=erS7ehfIU3@UK_mc?|yHFg$L&gFy_ zzli|tpFOVm5|5R${E539W_iBdBIS$ul8|Lkf$s%bOao^Hrkw9#N%@Go9j2VGU`hEL zfhk`kFzv6rJ8%WwucJn5MS*L+o?4mq9-J1yfDek5Ujs6|L!ys>JV-~JVL6n2V$eh8AY&(OW0DkQ%9UudE4){0C9o|9xW_Y*W=>G{=IPm_H`nblb zH1eas-7d!Re1*|HXTZ2UQ=idU1HV4T2OggHFa_?t2$KR@psT@cAU}fEFg+^WhEL(IU@cSe6H4iH=8~7os&ugGZ!8n7{4<}D5JPZ5`o?+M)*Z}+y0;n_& zUIu;-a$e(5{|(@mL<_wK+~yLzNp9qy1JC!p!U4bx_*>w++h7$ga6kj~Fe`3=1J#GX z7Xs(~1aG7m1MPt`(5D@b)X&fvEejA5S0Wb&IQ^09I*RwYbtOq_Sx?nf3Z1VSkf8X9U z`Paa94$8&552t|tUA0)CYm|wn`Wr+O<^uP}py5jqbl4WyPCB`G<>OM|dw--aQCP!1 zz%qbA#5jRhoAP6Ue~S}?J<4XYJdT2e@UNPv7=6+eHDU`i!6AAd6rK$DUa1b?VHUU* zbA%Zq{|0`~xFX|&8GX`1#e+oR# z;P$|2vvCd7&(x?d8Kcd_0EagMUygf~ZALx}I1{6|%mh3d_*(odz0CwL75E%3J8cs` z0Next6;h6XmIF^im)VKvS>V;zh$h|$#;FXvziA3=1OE6T9G1qxJHYQ_UTAOdm%tC9 z59b;EZ-C_($Y_*|n*lGuJispCOj`&%4(%WHc~>yL7d5yJcp~Iz05vA!!1rQM@`qb? z(Inv2m^oFG15X2vH#Bn8coy)>7$a;E>MsWVO=E0QN(}ij;6O(F92kG=<7)USu9wM9|FIJ7UN+`gU5jJSIB?47{q@AmiEs9Z^*@hQA9-joW?l*<7xWLM@GxW zo_A8TKu_S#nCWPdHMkOZHRgUhiYtJng9*S-icww#e62Y71i&$jdOPUv!yBmHE*Oj% z2Twp@7@D|~!E1qA;M{OEF#_BQ+^QZH^KwuE{|E3$RNyXCqkX{7qKQWt{e!??iwd0r zc1IOnF$;c#>(;1`>+!qq-Yz&SGX^^YZxVfcIWW)dc1&Cg{8fbOdEpT1>t67d>Hss1Y`%{QQ%n}-N`7o1rFn-rc2Rf z-$H&4M@>f)zy%nsS707^O1DtpwFW~5&<*$Pe%gJ!f`#5 zEdu?Cz>^`@eT?lGfNwAp3j>%1+yRe!H=2MR0>;43o?^;BMvUu&96W_p=l^HOK#fpA zH8X7nmZN$nu$<}k0N)^L^da>zXeSv5$AJ0!Ss^e_-)De%iEan&B{+AOE(p*E*w(`ES2PvCclQ@#0{C8m?*QJ_4c7yvMdkqCc`2^} z&H4X9FgD>sb`o=P#W8F*M4PS<9l+6l~eRoO+nUf2)Jn;IMp z%HAiy9qP5A4gJ2rvPEtJ4&>Ra0*osLxEqHNz#H%o z=0#(03h)gGfHh_SzXBeL7SP9aJ#PW9Jb5hvzUfADMTH7H0sIk;5{@x;*$a6%{_aJS zaxUjo`U(`%Fv{(5z6*FY?gh(CfxiID8vGY9f0!?XoP+l7z_Q8D0-qG~MnN;rs}H=? z*t@tHj=xRlbL+4d6k4<}SE(>q0xYNAfxviT9Mw1uEH9~s0guGFWT5Gi$-u7&`!j(5 zh!)8<0n81+_*l$*zXrY+M}ZyHA+R`IdaHm>qKh^f1M7h0&FfZR*+PE-zE|7_d`^8a zhJxCZ0zU3`n_zC|amzl=1C|E60-u2aHI+i%2e=VVuY*lM1Asf>X$rfPU2;9}DKW8) z0Dd3$ju_h<1A#Xa40*r)Et;;8xPX`sxxD>e1iSsFdo3n)Y~Y;fLjg3wkZbR zhD#{?Md$m`kjnt31Ghn!Ar9qmF7V5EBGQi-_8+1?=9wHbD3<}>jsQTsfQQ{GU{~=-5F(hTY+6E8x{#Fh+R(r$Y}<*3&SmZ3{F7o{EX0w~_xCcy2YC+>G+hz^8Bl zQjDT3-xnBvoL3M)ns+_$Cd?Bhz?7E(%c*-TFfT%bo2h_^rh?JAt*hbx0sgxV&zfoFh62m>1_M~f{pV`K;LY0>BJ z18)*%yRU%9W01}<{>}iO<^4a(t3lHcqpSW6m}pF&<^jt`Di;H*hekAjF6#`;x56?_ z`Tmsu0ynQFpi(Ol2(@?!q#wTnhf76^&S(0@EPD)E#39OCdxNI`5S+H z`i0$kde!4^uNpsnO!b}9$9L)0wR^W-o7=DQ7u4Il<9YvR+UA#k@0Vt5&fnl~Xt4SC zEB+uqJ^RtH?{>c+i;n=fc51s{RG*I(@r6h%fZnhj%UoA%_j9uN`v}%%t=sN*Osfjt z-|n~eIoni)-*5NZ*5{2wRVD^W*n}lYcKEr_x@m|1ldLDeKKXCqJv;oOtc5Exyi=El zPb2ToIgsIP3wQ1C+xq=J&hU!Elgv&ync?*gTfE`7&02}AnLaNGuYSWXO22u-+QN3ID98UnEMKzyN2-{{ssR7b1aZU diff --git a/build/VARIANT_HOVERBOARD/firmware.bin b/build/VARIANT_HOVERBOARD/firmware.bin index 6107ce63f901976b6d15c04f3ef9e4cbbb3c8080..aab0544844f52b63787aeebd42bc0c130743a3c0 100644 GIT binary patch delta 7642 zcmbtZd3Y2>+OO(4GJ$|OIC60G%s?0t0s~1TyebKv__S1dj$nx@UT(`+K{mVSV=5@1O6>^Zcsc z`qlfsRrOYN)!UP+uTmepM!C@hME|%98D7svhHAiGz?*=#0q8&e-U04im46?e2LNdm z|1Xpo4ug}k|3^n&u)FrZ*tY%`o|LcdMGTluuGAu0o}A$&WH21lIFf2LMH+j}J>)So z$ov{;H@s9o9&d}YM6iTknRGl_--7z#j3;<)&aT4u3jAJIg9WT*Sd}NycfT4H!S?(J zHD)Lz`L+9}l&6B!_2}1Ua44GAuup}MDTa<=G;DGxhSnUN#cOYC*vSo~y~pgXyCr0@ zFeUB9z*WoJh{~%#Jqr<7*pk8El9ha1!RLBeC&z$|{m4;}hd&2m8W6 zw+4}kRt7pHNJD)?ko+-zqI;+Gh`FTQ^K^47&Ol}(ga6#zsu`vuI(C9T`e<}RS}R|2 zrdY!^3lis*B<`LFPmy9tP~zrDW@nVCp@?Q?I(6)gfY}*qI;qyW3-f4-jSpeATk!Ze zWI-%ihs@ZN>Vlb-*W176fBpjm#VtB%%(jLYrlthLs6G*P@yPo8$A^ot@y4bsCYHri zd?Pk#Shsj%lWZExQVO#VCci@AJiuucZZB|)fuoJFtU+O32j*#DqJfE4m>s}O7gH-= zE5@ld)_uZ**^b~alhIi#+`UH$adDkbV75YvHfF(^jugM=i}yi%@?Yi=dKpX~1txbp zpzd`T=w@IMxOv~Rn@2QGF?e6F)5c98YuEvz+fK3Dg5UGq_Cc#v*4yW)R`n|E(MIs; z2E{mWB`B^5>dYo*opA4-=6024cR{juY)7-zHTIdJI)AUGI)9(*vXj?%^j4jprlIp~ zZ}U{sO!P`y*C>N$RNKoMPg@ik)fTDw!c$=Dyl$#}k}b;gHm|+zSf^vV2f$nU||s8_ z*qec637$VUCVKw#yLq70?Ov^2$9DK*P1+(1(gFV_UzQ%xlXZwL1uO%gC~QLpY+DKP z4*4*O#2@4O$Hj(Z=0ZhjiR!ef^6V!KIFpdXZ4d7BOTQjn$CHL!J%C$k)V;LBK@R~sn^f|k1X$aQ<*J% z1d?O-z}2sC8o|j-+Y0{V)55_H?bcL=VsDVeCiBP^uyVJrhP^x4ISgQE3}vLh(Rr@m72WuLr86G*cu9b$#ed0GfAPYTR~p;~Sp4&?!J4v_tLa?5Oi zYD_itmYXvev^u0~jbCkB|QGLbwtAUUcK8r!@Y2*t)A`Cvds^Z+2f z@V>ho(VzP;I}AJxNJ;7h;J!H9;xV65Hb|z$Ay3be1fB1-454a6$<0)h9&S2d>1hLMaK6 zNrHtrp*Y`?(mUnTpgw#AWzYq~@8Y1Rw0C zbf&E?5>6e=76%_}i%W`gSugp&=nei4J>8&D_#P=5G%l`Ph(0lS^!~cDK6xb?6fXw` zl z$ZdgbW@FELwAIs?1SZ72E0wToLGNa0LlMm)o5<}aTv}hMk3ixFPmY|fx;aq4Vz3VP zPZssNvr4tqzxvEY)4=)^>=<`@MvW0_X}-sqi0vV+8+mg`&$v@yDEkcrix}B&i2Im) zK4eJDda(G(YbeTMuKObTx51zzt;5|~Z=@Zw%l&%DvQ9@(=k-u4^X~&m2a?l2H{#BD zjr|v2uo4+`aOT7TOn{1GapRU$c4M)&cS{UtPVyW2Ev@XqQu?IE(X30`#opCE7*?Xt zPs4e-BPf?~fx)%N+~tlQrMe_e^urRn8{}>>{r~dqfj8zu=;Sh>4e%LY8(i%uHR@^? z?>0XMsq@t+kSLHkUG40Rpy6!-XaN|Y15f}xAo>^u9eyuirlps}U6HiRw%!tVQSxA0 z+h5@%_0&Z}KAv^VZG`SSc!}E&=bE*)57d6+VNo+JOjbiBEpb^vx%`X28(^i!rBGk5)-S*t^%m4$Q0vXXp-cp0g$;BrSj7xv z+!hee1gAs!k$|B*1|{sD2_f!?5aK@LJ?E|G4Pf(>K*s<&uYk@T(m8#I7PE7B@>qHgTt}Wr&xG4{bNWy`hcu+m#bbyuV<_%HCS?qa zk#7fir9T45N!dBFC1WHtH9)@3uuug7!e{R%8yq zUC7?dzU~*qWw5=T6U(7orIgD>7s%yGxm0`>>!6zaDwizS)OiNLPf0pC~%u!~NwTzv~jYwW1tm#K!wAaD0>p((EgJ`eJ&s zhmA(^JIn^mo3H36H(Kl#`$FZ&TDl4ut^)?cakU2UD7>g;fc1a_fX|n^k>Mr?XazDP z0MY?70BZp|0fzuz0&W93uSAAaKrx^aum?~B_#AK>Kto4U0qX!e0Ph1%0-6E$0D2fe zA|Mao0L%k)>kQ{jgp$v-NQBNB=6=ktlYbx(P-8BfIOmiPZ>q@F(P5RiZ6`i}!@cjZ z;*R1;hk1i_38dMbti>HsafkUR>mV~?HFyi()v7&|Fgk`eoY z?GfF84{D6IyD2t_YlRiN=N)tR(Yc4Ala(+S$~yXPGSsxzXUuaVWZV44;lLy70OgBd zpFY2FDoEH`2&K+?Q&-Tq3M9(9z`O{K6b&9!(!R0O-Wcxo1axr58}4u@bXW`ZkGE`LM;U>ii1KEhU#&Rr8?lKLPihq-IbgE_=FG;A>~7>}wjSCyNaSQT4Z;eEe3xwnVW!L^b~@~mKh#97NU4$uIR-qO zOwSpJO{6Mk$iz;nJB0ckqiZGZcqqI%BgW!G(ay)6vCnDFL>d#}n|Nm_J_z3=;;(RB zJ`PcjI96I4;lKyAuqwM~3>nrBq6k?9(dL@;Eg-h}$)Mb1>ZC{}=a%;0Bz9vp`fiQ1 z`I0$>!C-Wp4v%aNw9sf#i^Qdp%ehJM3&k4|GcWLpR!Mv3(y-QSkwoPc%VWK^+xLEb&s5f9%?uEMZ9Ei99_M^+`=`2;m0xFRro-%UFCZ}}UN zXRC-x5W_#Xg*g5cIb}Z{5GfdAa+^bPY68EcVmadwI6;}}HK+^RmyoriPI8YEA&;5> zX^X&}7UfWc!=edIWaN1}l$1u`LcxExT~z!C+&zU$dfTgbZ&PaFo_+{|b*5q-cKw~w zn5?Q^_?@%A2jvB%)s}NX63^^*4-@Um)Z}FnxKy!Fov14~jL8AUB#u^@`6`nj7O2c@ zm5CNds>~#ni4gNtrdVafP`1LzIb?VX+z(~F^NkzwHUU!caA!YAcD+tl)2wiEaV^w+*`sX#ZP!? zUKcj1Ucd8)qqR*~uQC@@W`j_rGGD38TEU|-XH;f|uvTSG`ol3;B0R4!(Cd74ZRQHA zRi*b-vl+rlmD#H@j|seItTH2&>4X=l${${wOo1FJj!$%{)g}H#<0++a^4gQ?NzkXECDPhcgE-7a*|du1ee#(Dp{{HoN-RKoi241k{gp>!rzmHPt3%%!C8%TACq;gt2zE)p0Jq=@~zIuk6!to?&)_nXUSvPAHb#_60VAj`$ zE<@mZ(d^u%Id>j@)FT(3>DwhiVP4nNT@blAf)^~z|4xu~-i-JebS?>=B+9~FKI}^@ z6*;fcvMa)UzpO^&zEIjaF2CtJxNvN-!|~5rY?8G;A%_+W=zUOWZN2PPEZ+gkxr^Qe z%TZvthy1o655GXtoT*(Fz%RP#&VTBzLT_`(e5bifiQLPgT@l~Fh>FN-&H*@+G&p5s~8qHW+2c<>sFtfe18#eDU(%K>k_Ls>bg7J3#A4 zGHc-~%2h$WUAPnvA!8OT#JQwqQFlC)oL!XKB?$~|WA0zR1z$GZNodhX-9A{SB_w}w zlCDmX<~)$<*DWr`_$P92$!5HrxXX;4Cb=MM2Naf*gJs2d3gOB|blMC=PPsy6FYSk) zB2O(Hf(yykrRg}9oLM@Gx+@UFvy-X63H7s|O~!aGS?}6nXbUt!26SN=Ni5G!sE`8O zMLqyuxUNF^pM&s^Ai5IvOJ#jo`9)pCggF%z^XC~!!K$?yXsT~oWs4%gswb&!FW1j_ lu|OMtRZc#jc2rj6sL&Ad1vwNmrd#a~l{r2wt=iYqZujbUR z&N)?es=DfQ=dW+kmsZnWGy*XhwaDB$5Sgz7ZUBA*+ybEg_`3t#J)P&_HvpIgw*L=I zHp}3oi}U~H#0qv9|BG$G|KPD@es^r9m>wP@V#w5-i;&s8$KXz^HIj)tO=^LUu^1fDbmE{G^6Gz z8i{XqIYJ+=#SL9kx<4*i7z4LNLbhlonl*64rD(>m>yLu*x`CU22;c2GzQYj(*&J-e z-SS!kcSymNv0X=)})ud#cq~U|M@h=;kwU&GJKTrfIE#+b37tMH301dbaUBnsn*<~76z8JH%J`|cgt*tlWEki^ z5!o1RpbJC>>UAQ1BW{%UpwiJ^ao0EDR4bK>>{gcg_*APQI}C?$GX={oOH)RxP_eJv zz}*X~e2c2`cNF+lXzrk>^3SODsz_UXDZ`Gd3gb*cdsSE4PQ6wToW#(aQ=+)z;$`9V ztCo6XUn-z1$_6v5{m}Jcg@J35tGo=wt&<0^TZd6FCV#NsoR&2b@vkRs;7IaE!GRXV#dNz^nkq0*pmtmIAX-UQdRR zPPI_n2a-42wxrxzRWIJYLyMg|x8F~3R@Gv4zcg3r4hGptA-$_X{RO zN;C43pLSXWoPpdyD=k{tNh@QJ+qu4Ya7)gd8I8qd4FQz(M0b=P?K50L_8d?49J-#e zQCh^#OZF-%$6lG>r_x_-AyGkT-n$Fx7;CyK6qjStY-n5BLL!0E7PVNs))ZGL6#J!@ z{VDETV1mrs3W?FMW$bn_-7! zdn)d(n;z%;xH-X>ZDXo-g_hHR((77C9NsS8ej2>Y8#(l&(_yYKE-%p476zw77*}yk z0LPpD>_^S{Cd8D7A!aN9MN-Z+saeKdP1m?3$6=+b17};2Wu;);l+G5jrSs7onu`~a<9Z9>HEu59 zI^xf|bxsR|mh%r=mMtJHVh}k_J>()Z?OQ>tbc<_$6`J<8bcAkFu{9}{J`==+NeT29 zLHu}93f&OI^OJg{y$ed-yPmrJw@^p=G#S%Hf%NUP!>Hi7OlLzrUk~E1k`fB%2YoCt z7*>}Jss}YyQ1qpn+nZ!jrTSKP>CQ2F>LCa>dt z0Xc4;CJWw5HWE&?rqY)LTyBjUIzVu+3g1qiR29bV4w#X`8)b?mT$vQcURkQ}k`$^V z#Z;>BgQN=X%|Qx3R95&1HNO%uU;6X$U#uBvi=dMm`uaauf_cFG@{kLypGR0@VM2qYkvY#nVR*BYg+J>OrNBouc3x2XhE-c$} zAXI(qMMjF-r{d}MOsKwZ?+fJxdp{s2sW>jh0o6e%gq#ayEUr(Mz4^N(dI z?l<`ynecWSOZE!I%~5bnkF#Lk+9Qv?En}u8|F+eDei}+H{T+8!7oNW1ECSp$bDQ-G=a-=1e0l7odS}v{? zY;Xm9aoT79T-zVdI^1M>jzsAEl%qF&OTvnynEpn>#k~rFd%4%dB(G$I=dT6k5{{^> zKZzX2z2Y>h{2=)|7>?X4l^!qQl(g9ttWa8f#JHe?-LE-sN=r(kB~$1G%4Jx3m#2x` z#RGz&6+@NUBm6Q6!A%hx(>>7Rtn?!LIyiJfn<)>J`#d+ON*7Q0| zY-GlZ^u{1QnPKa9LaE@!kCgd%b&QajwU9;DIM#?2{sY*IPVTJFxM3_C&&qt0TEQ&< zJyBj#%5cc3@P}~E%w&3e5W6xTi>TGzeAf6uW*C(^Kry|OUuoQM({C>w3)W|~O`BV1 zg<6JxBpbd)<{!b|^p5R(77U5sPI4(r{L1_p9O&IUdLvl;+F~xvXRr9fQ`=zB1zCN) z9Zr81PM-~TQCx$t8Kf|fb_f$eGJ^E6V1i_72plz|0M7ts?CCsg%A6REGA5ml28}-n z=9H;(x^lEBv3UsRF-EyMxH4e{mJ19Vqw6J7#s)JXjf%QuLg^lrr-Ni^Nk4OipS=FH z@T5qyk=Y8)vjH6d`FpxUbBzG!Eu1!4^@&iMC_t?99Bh8m97g4*NTj?Th=H<)WU$AS z$G9eXKJYyI%+XfEA1JO|K-^|Aj5XJHbY1axbRn*fO3GaI4#O-&+^cd7gSZW%mjVa7 zWy&7m+Tx+OKEl`jbT}+o02$b5_?-l}k&MiJ;98vpaz-mxQB%Hn*Oe-nZ-ry87-C%@ z!_`?W^FQhJK5`ga3H1wly_alaH$lBcuUq9lY&e_6%3i*kypZh$C#%fI%1=NU3FoTJ zM?eY7I6~%WN#+v*K6V*90`z1!hYMJ=3QT!bLK`SH4y4;6vH4Au`LIAS>xM()yb!YJ z1N?P~SdbomeQ0rBv-nQ*%KSeCikm8&YDH85n-5B7B{GZ?n!+(CL&InW=jR2QZ4bjJ zfaIRG%Y3s$WtsuzwG{Y0Lc*3atq82m0c1-U z;f5InWIjgRwD3n5g3R{?r7c3Vt^`+%aSjbG&-!xeqIcrR)<=KYZD)yV zufK=e!EBh5QxE-XI#+iVyS9T)mZtOLPN!=t)Ou;P?{*fsHu~e;lXQz+n#JFC7P!`c zPOPSLbmyb4<$elAFh*?pm1cr|DmBUrLH)p^@COtUR>ZA^G(_ch1T$Q-{ibqexsS6T z^7u{(+LvE6J=W}SIb7A+5wdp{GCSZHnGHA!SO8Dz9>6KUEkN`PWKIXT0M7tk0&E5x z16&5&0d$`E95Uz3MCQ?e8GyBb!+@&*9uN(kL7Y<9zmFTD z1=serNUQVyXT%58e{P}Oe}3gB|4J}C3VW4yZ&+sVA%y#7?OJwp8XbgJEpc zEdyk4IWqpVuxm^;JZhuG{-v)qkf(M6)XGJCtuU?gZCIhtT3}Dpw6)^yTG%SBIJIB0 zw-2Z!idHZ<26x?xLBy;laM5BCaEE|fu5n4gg^TgPHTbD*#77(WH~?OkJ@mQ;n0jD# zpZ4lHH-Y(B+Z!*|J?MKKaPL0I>hS0No-o2`FJPvB_YNvQPS8G8h!k_nk3IckaAkiJ zw3i6DrauEho`B!zp9Ml9VG`Qy@Q{}Tm5

Yl_Sik0XkDQ9t9HqTZuUsv&O(CGTPC zRlZOOtw?wowcS!RvZ~WO!{-s!1b9pPQzf-c;TzPOkO#aCK@ZMZ15^0^(88da z(<)zwmkmga>!to2KJJ{LX;s{9Um4QsuHr)j%E{OV+G#3?GY1YyJfbxDO}1?_F8b+{ zzeF@F-@9R#Z}+N*Ury3T@ydY%JH4fltJ|>czLuj1{>`=c?*milTnQVUPtnf@@C4^~ z@nrK*?l?%-JtZM|Y)Hl<2Q7@h@hNH+hz7h`R2=xX{0+V_XhvigCG_n^=09n|Q;HMl zxFB9yJdd6tW8+{4Jx0cvgIUVdIBPIPbtn^^4MrGG$O*0-(lzqy-%3y(TjG<27c?^?8wHAS!ep%`@_$sw3!}t$6smP*l+Kuh=XA!cF(NOk zlXS+ZGk4Wzbf!ROuB%UL47rbCP=jG4KdVpaN~yZi1@%dt>8>-U)iFBLS!cdfpKv3a z$VVyoHf!^WGP#f8qZ~!9S&2WRP4!2pi~JVIL{U4^<0wcTM!;Py@^7o;t|ws;`HS)> zmdx9&-QyyEPJYlP@pYOXk^h^P))M zTvm#7CPinyQwlYPBu=3%a7xMFa>fhEipX1ZrK3uoZWf_42bCP1QKZm-8eq%hxWSfZmR(*Ba;5CVa_rabV#gbr+1C1t?WN;$?rV{#foYUNhkUJ*o9i5a& znBw&?eXhB(`Y~5B0)JmRpB^XS$IFT%`$`W6mM!6}WuxqE3gWf~5f>9U?2mmgW|54s zi|&eVjCY@)+MSdNwZU3M{Lk{Z2ujlt`O7$J*bCkT+HgpaM1GF6O!E_3np$b8?sac4 z6p1QnvCiz!nWv?NI&z^j=_Sq7nJGHMNVPgMQDk*bneJ zfZCHstA{_-`dffFEq1?KoNx)*27!lPAx$P82Dn2S@VaZu2mVsv-+uOjA6oN6`w5Hi zw2H8-?Z6r|mj4ym(!u7i?#rS3I`BImYhjaAEHW|h4+FFaXO5_esD`6|5?~5`e?&j3 z8vi(=H&xvjHF9wne&_Mms9&&k%s6TfetAp@wYu?(F+4@Rg`1uzp=xp1lfCF~Rh;$Y zUFxUC)NvUURn|EADKAZR!)L}nOSR&Hr(dL_o@;D)`fGDk4!rc+tJWKipH=t_ys|1e zDoJDBHZ+`5_*lHZs(R4RBGGv-{GXt6N%SSs4*tRpe?q0gpVL~_hkNh6P^a);Yi;*0 zyyxFmT~_XP{{SC(iPjN3vASo{POY`|f>*Qr2rMVoya$$p!EzJ+sJaMV2L4f<9yM9? zu{l*ggk6H(p2bNu_NdXMmzwqAXJACb@UWVm@de_h>t?j8c<+S>KeEtHgo=xO#^T~h zcx89eMaYw@W1YdtRpBg^-nnIBm4S;i7}MW7t?+sH7L2 z^xlPQkk-fJJyQmT{T;5uNjNYiG3=%$#lN6SjRh~%QdAq>K6N>@4)>jAZMR`6q_BWD zr{M|H%Bd%D-L!&sXMk8ZO(SnlOQ9y>SWj=tjY~W^)J^=7XE6P>gb#Zjqqj(nU2A(# z)bqG#`bzUL@i3%DNwxUf>4otxszJUn5ae4#PYL-46he?+z((>krp`DI|D%~Zzj4uA tXCywpcq~13MWgMtVq=H1B+mfF&5-v7YvJExHp^iU(dIHE1-u2C{srJbna%(J diff --git a/build/VARIANT_HOVERBOARD/firmware.elf b/build/VARIANT_HOVERBOARD/firmware.elf index 959cce1b43d9f0749c8f3a14d9385a006fd6602e..d22d54ce303fc9cd746deca5c20d2b8548f004eb 100644 GIT binary patch delta 98665 zcmbrn30zdw8$W!`onaW3!2!`>T!%$PP+|bX*KkM6Ml;J+rL1dd zo7v)$Tc)|Ctv@p@{gtg|wn^GXWwOKn`#tv#TK)d-`}w>te$Jg|f1dN4^`3iYT=jAD zx6d_S6BYc!TwzZYLVUcnG$tlG^==_p0znZ%;vfGsUOb@NOLpD-bc2sNkM|Y!^(arG zJdN@!3dOGddk(bcP5O)Y+>FwB-v7Vya$hmc{?7kLL#Ltl)&E8J;{TwRE^npVrS!Bf zu?i1sW=9U}uUZDT++`VP$=&g%SY|&=`t9J`@7_05$~8^n1Ir(&T-b82({@V4$<*sB ztv%Nbcp%TUWZ)(ft>ARcDxHettoE}U0 zggOxu?g`Jal((-7_gHq0tF-=PDIa-Qzua7o4|}3P#Kh+eyPP-2Qogo9FLcS~BR1As zVjVvP%H*7r7p)n#wI?fEEwhyC^^LUowzZb>)%C+Ji^-(LQ!bUXm7wL#YoukIylBg{ zlrO2*kGW(Ir@bm_*Wn-SS)#nd0aQCckBE}FT5`QUHcGaL8eiKM(XOr)F&-7|4YeNN z_tfeSMadC9y`f3$u*=IPoxCVhMQn7AeCgyxOV@x$0?PBNoI9O|J726E_Ew&y{A5i- z#p#BIia+b|S+A8pQrl25u_3l7H0JO?PtHw60p;IT#}-Az95AtFHB&rVc~qS&kF4E0 zM8u17v0TK;n8ae#Zq6&YUswKoCo^N|Aiq!I$%7^tbn> z=R}lCE$WDjv6TDjzrB~L5#^eqY(xSUDB3d6tcvy|Xfr_bL`Rg{73FbICV}Dv#i=N3 zK^a}2Sn_C|Ow20x?O!I#uhe#pi7whz^T(fBP1B|!`(^pO24{3STDDL9*Ohr2k)OWz zRSIz*RJ((c`7p}v#}VlLpbD6IaoH1qVEN4DeqA4%hk%))P7wVxe?rC z%57Y>-jth{>x_m?9|W7$FNEOjwE?j)MZ0VM{L}K&3dg@xLe^}BSRW!a@r(eF}_<@mDftdQk5<`!gy z#yneTJwJGPKzXxjSW6i>$hj&!XI-}M^zKUQ(SlVgF8M+&yDM!+S6t$!-TVwTKSRyW zF!R%Sv|rYS>n5H~DG`Zzrv?w&T_uu7w-Jfq%PeO_Y)WxT$xXYaT$9Pz{m9&$3}o%a zy4WI_5?dHnCSwwc8!m`M-{qVgko7gDoupnnq)Pjmy0kJ0eDV&aRV4T>kKf^m?vQIF z_V&6P6t`#xlS%I69nR>sxkx9nIjiobvNnUY-<@K3rS<*g+5K>>Ivupiy=>T(hIvhw ziI~=dTP)jL)^hMGRl?)j{a3Y5`(4V7=ww~dH>>Bmm%VhP#j?k)sfS2>__Q@Qp!`Zz zM2vNy1hl#8-m-L?@Qe%)o?J99j{hLtxYTX!D*vHYH6s7J@@k1q=6gO%225_7V12Hq}8wDQku zMEp;uNmsPRqCBCah|DctO3fTnS-qTIs=m-7x zR??+CQlkgAmMyfEHG2EjGESRYqvy4j?GwgB(093b$Nt|%6YUfuTVKTpvSJZiG6r;x zVR%rDz5)6@GHaIQP-DoBu8_S=$wG2jVvdX%s6t3o7JKb5>Y>F1-NsQBlMnar8_bUZDE8E8Z%IZu&`P$YAe@`*Z13UYszf7RVWoG zf1&(YRy-hOv9R|<>4!2Hr2yq76ia;QXJ7v)%C&&NAS;IQqWxCrTcK}-e(`{J(E~n1 zc^&1{Jbk=J#>r3g6&~4HX6d^;vRjkARU-b6Q|tg2%fyi^{V$Jfr){XxTSd#L>*_1x zbLuPpsGU+2kh7=CF6t|Ou9Z2Yb*&A^IlrpD;(HVSvCcNIzM^C8u=3S?>nl3f)mQvp zpI#_D|0&DT7e~v^3H{;c7qdtBo1+J4-!;;V#!Rl#Pen^lXj|}(o$iX6ys$y91w{+0 z(%ZzyR^IAL5&zuj#GD5!0|m3_xArS0DNNX&tnA0iteEe?PfpCy%D>fT#K_n_r=aG$ zycm5$D|a?bzTL7*#!{VP>`O*JKdhvtsve>ZezUAF_VY3}SH6BSMy4QXGFJAoBGHw4 zcC73I!kk!{hL6p$vM10d96$a1eBpVoOqO?rxehX+ zWiY5OE4jh7Yb#^0w!Cv{S?pV??{tfogIU*j*%DDa884HxU3K~g@iJRmU8hHMls!Nm z(os%s-KWlqp?VrM3luV0uPHAtU!G-esOVew2?9IW5q+>toqoBaTqx0e3DOe_)hv|U$mP=7B;CWWtr&V|$Vf$2Ht%L3b7LhM1wGRZuT8!_Iea%A!NR=w?at;+}b1T6Hz(??|iX**z~-WJI@!@RXmC*IvdUWLoF8m zX>}D3n)p|!Mj`N(CVmD3>>1!oP5fl7HzzPB8GYzj?TVa^Ilg#+Z`F>*^|cy_>#Mk; z2j$mQY_F-Sc(-y{&b>ML5Ui`%S(}j~)=+h8tynK}q5wUmbk;+1S7mn2U`%H>RT&yy zaCN0Y4-YqLtWX+vLStQ}EdRq-dGex=89C_?TBgESpakaPYJ@QZqAM!3oDhVOf%_RP zwyt7^ss#;C#ll71F-q%3$j++#3No_XRb|U*l9QD)5Zu42>nbKzws`KNivrqvDn(3- z!KhGWUB$qo)z7T>3L#)LLTFfJxGA&|Lg5g43PRhfGjh(aV9ifMrdOrilvx8AJ7gY! z%mzIqMJ8Eg`NT@ScZzH-ck9=u$ZlAs?@y6lIZ;2HA}7o1^ypMz&Gmv**)g082^;)1 z6mIa2=?|vLKH81d`Uj~pUdyi5D^q2jT%=#uO|}ict$`y)l&4i6uC$4Uie37GZnA@P z=ud*{TUtLCeQino99$Qv>-_p+z;o1fcKxk@XQ*pY{cONDtLvotS%4>~>)864fJdwA z4fQhs7pQA~{dB-X)OAq(G{6JYwSRpP;J)hGJGTB7AU)MJy}oPNz(EBiE6Sy%00aHw z+Jv(Dir;GW@!e$)Us*MFw&hjT`MDpKHB>}lf8e_;cMQ!vR+cn4(zCuKWfuZc)GONu z<{pNOO<})nACSAZto`74Q)Y;we!o3CcPnHrs|Ek7?OC~-fc>JdPqz2UeX`6wc#5f! zN)6xT_qS){J`ABRmC)PUyXW3tCK1w?HHR-~p6W8$j(L8*xW3|!dS+UbM^(jRGMQ7| zId@^1EzfiRvT~>3h%T>=z5h$w$RqK&@wwB~1U7q-u%Acig30T4lAO2aaw;S&p(6 z50mkM1cu${2k`Pnk3#*t9D| z+gCli8Y=eI8J#t7klgAl8eSB!#PU{9bPL>f>xFU)ZgT2>#cDbnjS%>1;jX~Ja*Gv> zw9X^34g0>n9-9u`nki#!rvP87(mQ3!_S%7ZePpIAY;3cau=?^~tc(M$Gk zsns7Yv&C$g_hp%O{JWst_wQZ5bJ?CXLEjzMPUv6tl6@l1)N%J^*>Xi~D=W*!%+tH{ z#vSzh8hvDMIaYhIQs3QMe&S}ol7pjgKUO@zfJYgy{%jw)!u|W};)uX9f}^|gf&*9K zkMv$ya$cyr-Z%rK?z%$ChV|9cHhzmhHUqiQQoHZ0GHI_SYJL6kp@L(S%cYb*9Q=;Qmz{%wD) zkB+qz{$8e)U#z#Uw-lmzM0uY>D~0_iO0oV%KbaK#WnD;)mII|qy}F-lpY;xmJOv{K z4dRu=91k|lfjrh&y;Lo{H5D@&42UZ{-PTl0YTynb89RiUiWlni!v50ZdjwYQ8C+8_ zpkbEMv*tL!&1#roT3K1ggMylhw1#OWWr<1Y(lFJe%rhzN8m5?(B9qdpVWLTyXi}Os zOi&c=Xb@FDm=10jYYGi9g=E7RlaganD(i1FDLqZfZ}p=Gi$+`+X5imm{$M%Exx6rs9oyCc{XKrEWwHD?V6lg=#A5YOnG> zRd#AB{#3M<&z@G+FDcCM^nER~yD4?U^f|?BZ;GC|#@L6oY(tO9IaaGj<;W*|UF&mI z<=9d+6^Zo&%&HdGcFpMtN=$u!lXA03ao1;?l<_9TS>MN`6quC2`d%g_&!p7X^-vUU zK8;@RS6%vZANjE1tHB=LaQ1UuH&e}PQogH8F)8g$$`|M~spvEwRW)uOYbvVijgE4n z&iIU|wW|F3yXA-+X6q(M{!q_da81R&I^#3Gu7>HZsi>-HX*&9&hIw+EdHSh_rlQOA ztQ?uI$LGr1wG}n`3%N2obV7|kwlOvOkpMkyS^_T>iL~gJ!0=w)>_H zl<&#lKWciYuAN@3XAYK8K^?1&Faq^)gXJvW3rdN(s;PLU=3ZsWXraezR+)y+RT)WJ zQ?t^foG~f))T}TmCrrv6HOoxOTP9^e%^fD?K$Ve-nKid53cTKIHqqpo#iq~;rrMaA zg(l@mlQO(!zDZeYQgUnNn3VfXN*`4nqpem{8Ew?9M&F(%qgoW3_{^&5L$#b&`iJCv zse1X8D*b$(Y!h`u)!`p2SC2F;4yzI|H(}!Ws#&Wf16un=Zi=snnwc)eQ0q=Rm~#?HB#Vda{# zqm|LR(2op}0m&bMY*FNj3nC^FNAayKFyVdOfyMzhkJJ z9yA9F$4r#@`tL(=emO_)JWM9ZIs3*9lPd%4ZxxNsdZVy-fd1`BdAIyppLV^xN$%3$ zxn2&C5AJi^ASh+RQ^0NGD->lI%gOoY@){l`sO-AW0$H|-J z5BlPYCouM(0{u{_L58W&P6iOaSINbQ;NO_I17gp^_z=i ztYa8GODNt{(`2T;W4df6 zz4|-T5mHNNXI=N#=Re|xshM6kUG@psh<2Q*_njeI2JBYg#71!6@)>fDlo#|rXUhBK z!@6&lj1Dd+#vK95fI0e>S=fx+pjXV28Nv61)N_s^_n3|2;|cl%#2^Rgt7qdtG(vxC zw(O_$l_RzP)a)C7t86djWPN3^e9(TW`Y3i)XXffH=ExrIc@5PSpH^1muDW;t zpKjs_mZt>0t7PA-Ir7th!2F5x=G{CcTF+i2@34Tm@8}|#6{^>+z*c6>ef!4TCC@G1 zqa|CT&T>Bk0e_i{dyU=Lx|J^XXm>5%H_566S>B}bYmmhUm|20^P_Ev$v#GX#%I%vqDtD!F zvl06CW{t}Ecp9GH?6Tgqxl(TB(tfkZhxUcG)b4>1{palnV`q#JMxRrfTaS&?CYiA; z4>DqTIIhv$(^eyv=Iv;1Z+oqWRX(H_f1)LXT@Dq()yk3es6&XTG5SlNXgwVdWeDLI z;Xn+LQJ?7t6SNY!c3*0u_N{b`ataZ)y%K3kh?=R#c82s?k`B&kB1EsKhx8epwf&k1 z*w?;`wnhTbUrW+vNBrp)!YZ!d4%R9^L@=S<_4H(|v)rdoP1feg{rkR1)^5^9FNP_b zSNjnS5hcPF!lbP$&50&~G7ZGQec8yWb1-5R&QfGv3QGb$0uRK4uGy`R!b7;#vIUqu zW+JW;)?09Gs=tz=wf99@gI;(UXtPIf33};Hf@feoXfvrIh%OET3SJMuBAVNSo;wHB zl@F^y&#whhxF!(Z@({>YVR;zrLr3eHSE1aBy zr?`-`Z$NT&NArYa81deOF%i;3dGfhNlhKoi-Sq+)nS?`Kv2@jou+#M^qwGyM(zODW z4e3KT%JnoV7?MS}m8&mx`x5qu7DX^>mm!0qA>hhF7$JiR3Kxn9$s@e1<#({;3mM9& zg>3l>;}}lFDn-ype0m|Js?t`p=!9t2$dGZj(%=||GoBy}GMou?Yjxd3M-vx-Zg(+) zkV&liDx`;|f>z?fV%m(b-X9=*qE*ypDugW9g%4K&)fN&IuGQ$EA&Zo0m|#bU%E6^5 zvCJb=NiBr=^9O$Z!dyA%Jl=ZLcZsi80*?e_y_7v5v}<_@iywh zTD8f9w>G3BpTVd|KtmV=+V;aG-WrmjW$J}#T2!}K%vM&%&vcTd5wSa-V$&K(sH28% zvNalVI*M=&>8AzgFQ;kl_!c2}kH~?eX%R9|38Xuk(avBk5u8lNrshC~Y9sVtA?@S1 z%XKWL^l;4!fjozXI73D%)qF=46L!7Eutz#}lT)I77mQka*dIe~*VqShrRP4zuvGH` z%afjJHqmk|8}`m>p7peGxAr4!oYy>)iLKIxg7>rLLmIL{*QEV8>;({xu(ETh}GSp%>xhexc8||2m)cke=EHx-J13&A>(OX|< zuG`9e_=vuQiiL*6%GPKShZ=4dimTVcTgB>(v zoOUZ(#_q@iDP+7>r2mnD>AfTLMmc_EM3Xdj(jvz~3QSf=vEzQW;}nIIILhhvX3YmX z%N&I?I#pW@WR+tnIk%`@@rf$arQcb0N&=d_!cR z_7NB*B8Y<@pwBSUS_EB$P&! zXj%?pgq4&yjwRKXK=1&LuyQ2DvB&%SU9KXhrQsupZ9g7>vZRT?rNNK|NkUY-bZO4hcO2(vjcT*I2lf$(W2rpbtNK%Czqy}~&L4T!Ce z6Be3W|2F8&TRF3Guq$$nNdeo;)Cn}LGe-sJdX?}%6`$)0;XDuczn(&!?|;O61@ISUt3h&l}ek-2@02u zL9bwFR@ZZg+PQKsxE>cbjm~=(fgbH*Q#tSDq7mmhM)>~j(2aLJM6VAL?&P|T^woru zUEeeQQo^Y&-(?zos(M&KhUEL_8vocxevUg(S#wCN%h8GfGJHpxyNQ8Aa zn3kuh`?x{Q2D!N>yw4$gx^9GIcwZV4F4if$KVhqD66piXPV^wWg%2Vl)D?#ch7Td^ zbj_wvKH*5$2+9-?j&i+7_y)qQgyj&C(FL$=wsrVImmc0n8`AVYpxIn(Wn=#v{`e4m zP9H7S*8w!!5L}v%4Bylhxl~CHe}SNp^zfG$z17v6A#X_sJc znZx(Sv9hfq`nK%8s^;p_|0#7oc97g zFD$2kM6BBdwv85=XGJ`@6C~A05l<5|8Y$vgR>$f(h-<`iY$T7XA9bH+BgMHc5PtC( z;P$QnhP|0G@h;y4#=Vt7om@9i`DF@qQ7sm+gRPXTS}bCh(Rv(u5wEbp(p}pq|7ta^ z87?p4jo44Phib5hLu`Odq`nn~qvc(S9&W(Z%t+JhGKA#R*Q8ilTbd4dLr==qn)yg; zZi}3j1Z(aR5jlM~j0pE)5jlg9=3XKqXA;6KQ*X#d&ay)i8n;fwCpC)6RT^^$DUG>= zpfMXVk@I@s+T0nr;7NSC7m3J)CzS?t7x@TU>8^y3o$eMB3Kf<=sk~$+m2Hu?pTVcA zBeD~@bT`#q9Wb9q-a%M%FP;dqKEiPN28EWr1o`H1k$1L(nCnH{B1EoW9npAg0N=&v zZLVTpG?0}HEY$TE_3oyhR<5DgMMvJV8}c#2l1ERg&Vym+gxM^*H?nH)4r=r0y~s(s z@6o=p8+&|!Wj-FAw0r0p0;pIG<&FCpNKq;zN3rpZ%J}4HI?+^Z_wS5#M zeDb!hR0w=iHvSXLX>zKR9q*vE-g0M@u;+s*M#9nw~Gv|AwCN#<*%BRk3AGP#o+q1inm@tDcJ+h9|rlk^z^vcE|D7W}4Af5NYx zFFMzP))q9FGvtSB^AS&%LyY9kwE%@%*vBF-a>M2*A(A{;55Gf~NmhL&QnG1Ap(GYV zE)kY04C~S>67K`amj;>>H(LyN5w63@c?ujdx)_XrP`*8U9a=TqArHLKc{l!PJl?a!k42(;v`e4jiTo_))|o{7MVKTOrC}BQj5fQ zL7oj$!xeeBG5FBjGE*e>Zz=3cz`OMy=8!@pX|Bm#lmb9|1z0%N7*RIT8jNf{35GWeKvVPsZ-g7~k!&WZIY@g5v;c5~ zKpOzZ0VH+;z*_c1|6(thZ&>C;W7f3?B`G z+A|Q;l;B^Df@!8;sxKIM7>kS<65YPE3vn8yr6AOO1?C+V$69N5E+{OHN3GrOf@PMb z=`yV=)@PO`HEGv_#NxUuZ9XJfT&vS2V+LbsQl0iV!eWVP)x9~G%_A`XMfkL|O`x$f zsqH=vbe4z}TK6t+%@VOp>pmYASehotw3%?n;%=YzH3mFOi}r2EVni@yOwm}clbrvqR!341Zz@IIT@UloA8QX?3XdxqcVr&~u#43g3 zC}>YYNY$jRXlk4o+s1tfnvt~e1YwUhCTvwL?BtQLZQ?h$+MSHRHi=bVh5XQ#<9A$G zOrv&d1(0Up>crT#pfxJ#Ja260w>0{y-G4- z0=kuLpOTEgk+JPHf_5j5jBWd;0uFWZ$k=v(a99M7jBN+;J{nT{87Q_xl#g=q#Mt)M zQNXR7JTbPta{vkUIC)}h`_K1)QO1d}Ekh&Qy_z<9YD&s|kP&BTtKrb<<{7ey*xfusHjz+wjgLy%O3CRif_+;* zZ4PP}>26D<9K}g?JBSR>?gl5-&2wejK*dRS^IX|BSkuADbn{%mUVQR>-;?RJg5 zH&?c}kD)Hr*gf-P3!XLGmTTJ~cvfq{vu4}f+DJrpUTeX#X4@+50C+!ZNZ)qU*gR^s zY!5*Hw_DjQRo2gecTLt6YG(aaud)qNRs4lpG%aX7CYEg8EEsEUrmhc zJ!&xF@LLgb{RB+1JZrYKm9eONOLf+4i`2pchqR;O&E zwJ#yzK1s2gG|uV59l@S7R<)JY&C_SwI3;Cw^Yqy^UgMM+=kCMSo}k({*L^+33bjqp z&v#F;WB#{I)c9<2l$*!Xwn-WXM3I}v)3(V9DR$pa3sV$Q;^y(R?Pl#Kd@OVGc-l5q zs{yjg&Esj?Ey~d|ZXQqDij>YKH;<=n(-gAJEys@-G)9@O56rcw+at5@DK#8aF=LRZkwwm0eACw+O|N!!p-Ap+d{1m7$w4i ziN+@gE2Y-L!Mw7!n|SMT+l^{8w&6&(&DPi^ZFoFwTcpvM;dZ%SBT597gJ`#s(w0L~ zbw3au0BpB%T(;#P@psideE5Nt86*e0%W(k8wVvC=N3PcWm~aCfJ^k|ViDvL)Haire$0L%E>l^?bzrYh8 z?5nt&2+JJuBM@*%4#|rDte+osx&li z9d2qAH)_mj)R=2(@Ic4sn3n+2CQio!o}ET45{`w;rgFDP<(2MA2-)dwF`-al<$;c4 z$yn;z9JjxNPbUv_97~l$Cl7QScNi{t1mf_SPI;i?ShkLOagIBi`9h$`6CKA2R#G^5 zqT{%W;oF?W(STPnu23frbR2inPb()6bR754V2rTxK*zD_6c`S+axx66#<7d`?}H_i z_^>3v!f(!m--VU3jhwU>n^$KlmTNiLHwZeyc?P{iP9ZEKW)@Gy;R<2RIT1ZVP9c31o3o}R;OT?|onO-X48nG28oSv{!a>ewsXL2su=9Wq z+jAVQ010t6K^kzb0yxz9JOe5w>~LfFH~77>ngN(Nmr2s46c<_smWn2hGmD->En*yZd(qqh-`a_(jAZzt?_ zuBQA_!Y!OH6260QOXmxeR~c>P97}i^>8*vOFPb2HDXJ7IA93Q;&53(5A=iQn|IYug zB_8D}pgA9<+GA9+I=3+&I_Wm&2WUCDZYp5A^M2AFCmly;2ho<{+rSN#&n=|slg!X2 za)omWv-mu%X-2cYK)ThL%SygT*k^P8#G1WCA-nTk)@C!|AZH|nwh#^$;U9tFkvnff zFEl*tCd2fwhp=?2eIewm2VUy!#28o)6Nq%{deM7oR*#hTUkuBZPyTR~XS7 zgoB+tW|Qv{4so7fa*h!WbuJ?PIAMqLMrQNSc4AS?ap(Azat#v ze2imju8R=opDBAS>*ba!(nZvLz5{`6kr}8DjQBDi1 z`4iz*&UZMVekSa3u4UA}5RMZTwo3RMv`{Dc*KmX$G56+MguFsfL=@rtwc7^`zEfSbvO>k##}Aywt^6M2SOKdcQUrP0`xa6?tR2y ziF*umYuqQOd_Y_)w6ra56yU(PF96#`%s?oZc7o+u8hRLP5!XW*dfA6MX>mQ^%o4W& zIk1YD&G;}ino0+5#p1>wRuLD?+{NvMSuHLeGM2cWphKaA{?xJ}TS-27iW>nT5oc$P z;&#KfCSsPOvzbD%avX)e1RLw%%}hjGS2TteHx5^eh*#-bC7F`|3*W$tXA)nLOizG? zuj6%8={q8sDjd2&Bw^lsAy3I>ijalLwq;Ai+e&^Mnu3MNt-9`+P`12qtAX-~LVWnr zJj47{VVXODY57bc7WW_y`p-j$L&xf#&+2~>%06g!Yp9_7QX!%4mNalyAx?J^k|Dne z<=!UJJ&0ZGTqyfqlt?I=I1?Q@^f^>Mz``%t#m_4C;aGZ&gAdpPEO-~klgM)(S_{seK zp70(p$?y8fKP|wSt?(W->0kNjAqz=<*Cb!|lM@yBgh>uTH&gZGmjQ+Mza}}xPv-Xn zh4(X)oZ%<)D}%y&&LsQt{d9hf5a;$L{T4r&-z*f~OD6daKlvw;Q_4+pia`JRxCM@G zZ2&^MqrYSWIEMbR&Coz6_vV815lBZGNh$e0(Ac-VQvt9;erYoMix_9*(NZU!%sbNuFh5a?$KgkWZVBSv0?Atwzi`|Wo zPA~Ceyhll2?8hDT5FEU9+YJe| zF%J-(S~4LPn(~>perdE7@c(S96VK%3!;Vvki-(7D!{=BSlI~y_k2)TMNj$4dT1oUV z6CIUY0_##&XCFgQ&E!Gc2q@eqNpW z@dl+4ElN^r*;dC?<#=ooZ&~Cv$3+MSSYE>#lXRH!+Z;$VD91>7hqZrMMWgvj3%sfD z)(knjjG)B`SkA<@%iy0Bhb%Opm1YU>~kZ^(h)|`ezd@Q9ELxP$LX)>{F;~< zDgz#21Y96eYt2Yi<;I#(3hxCpq0fVg<7p~lAA!t^)OrvTRR=;MMxpO8vrMOXQlR3i z^5Yhf!G|C+*|8O3GrhvT4WDvDN(+qe`9L`=6VQNg9bn-vDu|R4kUvL9O}P_*j{@E` zfI4IO%{L@9dkNMJ(6}T|xrVj@G|pCw3>u~k?@o|t;~~Ej{#1iV*#mNSRKxow07kRj z&*zP(NO>3JzTo@3CjjLE`oJ&H8j}I0bC7QYnGb4I@DmmJ3y?W|RT*T>{-^Ms2aQu_ zDBM7lQC$Fu>wR03vuo?VPTrs?6q62}W zy3O4taJL~6VBxQ!h}1PES!J3(j)GpydTxQ3*^4t)0G3*)dLjarFuLuZ$VxZqQ7mpB zCnC;n4{%D+RHfGwFXbezsZH$};90Yo$_1ei7hQP4W=V7eEq&TFoH?kS@D<4Qei$=? zoE6GbG0}HOB1O^vuzm^IIdlLNvd4oMglGk36(QJvyaa+^_7?C}eQsd)Rpiy3g}B2{ z#&;r2ax;)0^^?amlDReA<|mI;V}Q1O9Cpgx0q7|p%MZK@6-D8YQvk=KT4Ju<%Vq?i z`^f)>uwnU!PKFtv4WjQnb>3WZ2uHJCcIzx$Galsx{G?J~yO9$7@9SS8XUx!5hIqZuf zM4i86&Yx9`1_eT^f3WX<8qCV1cM|qZ_>>!XYu)WM`@yHdtO1{IbgMBW$$Opn7KZ+r z;`3;%o4P+R@J=`tRNdhV#hwZ@X(+@0(x(V=Ou}S5fRg8eKZG@{G&e!TbT0U7h4%L@ zK`4`YVul6IrM;_~;W5!{1EU0vA5aXwP{2{LghJYF=syR*{|!8zVQ~~)%P-9pslH@$hSTh~ydIMkJ3nMzROy*Z`OQ8Obq| z!JKgiU_^4=Ja*VFDw2_%u_aeGuCK+yk=o952`2n8Usms?HZ%s|GCb#OW8d@!Gxb{1 z;if>k26K+IlTQ26V> zlcuy{{(C5WOX>5zWOe>#;6GA8oz40A5BQSQ;a*RbMoZ}nKI0zPkH6$gP-nM(e2Xu6 z9y@uavLB2YGHU^5AXyxIybHed$SLqKACkit7UZDdEQ~KT1tvmL4EVgg5Qo6!+a$6u z_&0K|fYuM(>`MS90>~wIpwPdyGTqt6YOz1SO5(b|+nw1~F|A$3Q+ z(rI{N@XQ#5xe~NLp_{!JKyU1~bIBc83Tzgzfg9RGc_W}fFM-5>_u%t8vW@}>#nx)z z2>^ouq~^l-wf@cSwus)nvk@HUJ|Em-DD!r22}oQz)*2+Xm+;;RA{UO$Ceeph7vB3o z<+|~@UvvwIYe3|x@sXeS5{Mf?d>vi)vO%<#uJYM96CsKuxjfVx}Nl8g;wv0){k^a0;miTAcZ<{EX6 zpS)I)BS2~C!w*tn2s{N1!=!Q{f4`UF26v#n* z58B2U!v@axLA!0|3iMGR$0c9iOj5JUnLz4dd!D?Jv%@E3`vl*2RpV6QI8DYl?ZZ+2 zY2YlVcL&~ORa;a5$i3JgCQsv-a@%=7G={?ASMmNhwMtzFVgD^)CMTo?(DdGo3UC73 z2osG{=>quoJ^@Y%IC~Wb_wC1Uu3}1`GNe`WDns5kP0po%aXv9Q)^^InH9D6}PMd#m z>U}0F{a>u8)<(c1{>6y_hXLQLIQg=V@b)l;eg6`^!Q?#tFV5}c_+aOif3Y^1N+SK-X*)A3A7$@TWBCBZ<9 zjnJaNcpE0GUhGvRfvA$`y|3j}m~Ri7bTK56TcAS2V{gophQ~rRE)0(btUOLKJSvAK z+^ZSJnVcL*UBk;{!=v(Iz{0^8IBlDI_aVWo$^gUbYI;?%4hSS{)L~#CUrXyfjiYd& zs!t|2;{(-z#OS8Q9{sU}k-n~mog=iPc7QR-^GY3qXoOiZ7TMW?Sy?Dm+%eeIwCf; zzq!rE9ee;bFUHhp;2Ff#j{Y_qcl5KGa{r@FaBf$Xd6ojIat3|`xG{J7Y{uM~mmJHC zFH<@E8f>Go%T;Ch8glYGoLddt1Khg@;jxOP2<~d-^Mn^qzU;vq|65FsQTaTPQV9+# z@3o>?co^~@CBY4{NR0%|9E)ll^6C7^XOTaHPDSNwVPvt9IC14}$8To0daIN%KZycmK(fc6F z`Wm&m6({Z{W8Jk3U+JwPWeYewc1_(2fU_HK1~4IsjFucD^#Sb7{6kGpE3UBJ3OESs z1K1_cA`0A&k?^q+#rQH`_2(YX2>4_5B5NH)lW(KsCkpTD!w@yLrJpL*3BbKwpl#)(6!jDLE!j^jOM_zoWF|3`q7@iFrqbBr*b8g8RJUGV&}Gx#2N})70Sb zru5M$ALtopNxAl_+;FhUkOC;LV!SxrM3(s1& z!cKokq$_*e`x*AmTA8a%2#JhGIR5u3(X+8QgI1#4(i*1?`_wC__>zH{s{IOwm(-|# zxK^Hh8SkTA<$7gr6YLqTx&Jimt+%p^A5^YSq5sQ;N;DOs#mY6e*oNprb-M9aqwA7J z*K;9#ZLN(;U%=q<$(xit0SPoCIuj=z!`@A**171MBI8L|m93TN&S;D-HQz2w^4GGh z>FQSRXW-J+LYVOH%v!OM&3UeC%|AVg^HnKNxfhSU+Yd} zNINSG=WHRnfie*1N$} zyS;2^t6fll$XJg!<(a?NX2V|)Fe-CKRc3!;QV1l1-4iJuyzlWsRuNfbR>AF|BNtvu- zipM0k3Zn%_wv0*Lc28C@?Lth(-gB~rd(R($V=Lyv(eKR`W8*v}eJ5NWXMe_cUmrM+6BZfQ+w||{bj2QA%427-H|Be0N z(0?T=5z6cg{-?M=@%1hQ!)1OxeGbHCN_K1XiBzE8+zc2#yD6Vr8hv(CKFMJZYwW-6^_H94(Imyd)Q*YNYM!^|{!=&|3@+Q_3}H*~sX)91 z0V1~%#RgI0COZ!#ZffpQBp<9M;K>zs)(~tgdRM_$-o^ObZ&XKS< zMp^vc<9~^Pdtr4%G*%gW90rWxHBRB!^`}OeJ(WX?XZ-#h-mO9mY0Eb2p=?ULyJOzx z_E5S$qtP-IB8Jk_8u%TF@Z^SXfo0FZ<#%`-v=jg~F2g8OjQxk=^oQ+SV)-wCoVo|P zT;{F@fZZML-u;ieoXTzkMAb>}6rTT!p-k>7+-IIw+|y~`)_}AUw(|qy@shj}pi7eZ zmTT@RV1rshlD9lt%zM;Pz^{77Ezf_!U^sLB$v6uJHw|~;{TDVTUQqW&;5|eNKlu;g z6b~4j1-yBt#F2kUq}~7q%^8+hCEiXIfod!v9kHv-egUKpS*6_ohEd=piSeiCF&@+j zs2KDMY_mako4&5C4-IpCp8{{E%GF0Sd=#XyFfix@04(3bDRUIY_V~FwXr7e(>p=2` zVared%hKVWG2;d+&b$rqW}9~k8zD*O#ujF#NWB3J-un4_zeu@&IMjV({WZb*<;74Q zxt_&?ni3W23mFLYd5}&r)Lj5j&EY-@eTK+#{A^D&VkIU2H$;%q9_Pv25~m~sVAo6S z55VYS*haM^n zR{jzmFi%mHy155V=)VCe6;TiT1;7jdUCu)w6aqnD=kJH%{5NqKQ3bxAHK-bhR_dFb z`ZI)itH*Hhx*^)J?K# z+2DWPf&Qaj)y6vk5W@(6(TC6M!!7V625}F14}i=cMwvp*WDJQxdl1WC4q5yacv=d) zUW%P)RzX7~e(ww=tWN>Iip$cZRl#S?(WWS2V+&I8!4fvUz#4_uNKwN275v-`U(Z4b z>+37{FSsm0MFlruO=bzYrJxiPmL_opcVY5j37cB*hFb`hChZEQVI;9MXPc{5;n5nAk4Egi7q&fkK?JhINOZ$e+M}|g3qX!^2O-AVT_n1FAY5Ve3 zXyrG#tlzmx{f6btd$j{rUny+LFCGu#OG(@CibDIZJs@n6qv*og;sDrA`G#}{<0Yv3 zQ49H|>1nco=c#>aQ zuY*ztJh|v{15@&)mD6+5q%2{diY_mb-vhfESOO5~45)yn_Y2UbLZz#pk#Yf)#h|48 z0iYB>YCQlA8Hs>i8I)2QLXqsvlnHU*)gl1hBEj!2^8*)(p!zs(yY6zhZJ|hO5sS=p zi!*rEg`zu;rqirh`tmiJTTAGxZ&;)C9mHWHH>zx|K{oRl-iAGJ+VKpA061*gKj0-{ z1M9WP%HP7mJ2eS+dVs!QqBGM!=%aTi)e?L^QtD1+Pr4Cc4?bN5fjR6se&wA-+OSLxForRiegZN2wdA+i=q0!dYjkc~=w)!;My0OvJ&R%+-hqX4Dd;F$) zEu^!4Mm1YwJoix1^ivjkhk?*Vg_C0?Q)B|uAAeYDO*&_knW=(_No(P_Rg&WAxVZAJJNCQ+w;TKBBeJmi5+G^Yew?`VM{` z>aBms&$oN)zdeHQ`yYpe37DTto8U`|PxH zpz&AUP8u{z@MS5|E`WFpo&1tP3<%}_n1G(lXNGA%gE<$>dcT!;(LC)B5c!ij;ixbJ z=poXA`{?V}BF5%@^n+_Pj~3TQ{|cXxUC^`H1(FH@Ffr-#`{?11YKgtMfXJs*dV3(f z$xPOU;Bcf@y_@xvWeF&6G^Y0%i`l!A}7948je7WuaXkHP<$I9zt^j>kEC&Je$vR=vvV+Dv_%uDQA& zfQ^pQpbr;#CA`sQioc?rw=tcm7S5lwV5h&Csc+G>mV;+dt*tUw+!!SLmJwuI6=V}^ z#yZ<68LjYS;6^568iRf)Q+KYz_cK4BSQBM1uhAg;uVJu>GSIKlV7S7kG#ZR(G&ud* zES&pC7P`<&owi!w7seom8li`A;KXz+Fj$;n`A&!tXM;u@cSGsfnfeLF8OVhEq%556 zDeQxkg;yEpUK;pGDQs^v@Jpis&$V&os<^zWbr#_@!GqM@tgNo>fww8u#KH#)hSkl= z%7?J(Ga78O#s({IbhA}6hQiDQ^;NvBrq>yrtGRA$(`YII({<;qbo8>)E+GCL`38Ou z@U++AooCR)G1H+RX{9qnS|sYpel-U){fEc3NUeQOz2XXv~_n-;LfEZd+>_i>jhznAQBtupYIlWN(Uk(Z8YQ}?~vx@C5T z#!>pZAOma+sVE_ci<2LnnSj%Ee4|e;fF|DmPk5B*k0v_5^CY4d6*>;KI^Re95^x`y z41}~b@Xa=~Lto7g?X8?2QrH8Rf{(j4#gF&%6Rz@cP@HB%b5K9m&(FHbhkkl|Tr;#+)q1R5eoqTk>)IK5V1{FD}*G_!HZ;OgS#T6!8)AFu>;q(h7aHK&QGv$mJM zQ~BLA+_m7B_uts0?pn4!uff%zhS|@+vE2gvT8+g z-^*LIep-{om<8~|_fe3D65$K=hL^RU5i)+~U;SqR>L>nh+u8UN|NNO{{&xeHb~eUs z!&Zv_-N5W!D(+Fc@heMmj6QL%`FsAMjlbu=d9V6C|CoLL-}84g{+@sMe)ISI9S3Kl zWAOLh#hjwr+Mv)O2bsE0BD7Z7$vozUy{Yf*#FlRfs)CP+e{T#Af@ z-Q5!;tNQ&+YhQpKtNQ&+tNQs&s~eOUtNQs&tNQs&>%Hg{=Y{Q*KH-3te^`4H@G6S5ZMe6boNOn71V|u+Bm~HwlLZJNfg}WEHwj@itb#1E$tI$5 zKv7Wq$L( zJ+*XIb$4~QEB=(?k3fDT#R1%=#Ur7wxbojAe+%SMDbJ$#-A6#{|n&V}%C1-Ac(chAr&ScFNXrZlO zl)IdarJGwBJ;}JBsg<#U9>(6`GV*wSX%02>A3#2vTz0{aU=w`ntb!lXaexD2;;e$v z;EnD&0z|A;unq(vdc9c?ft(0&_>k|lNC~mMO``$T?-+cRD|ooP1OX41L=67?-I2=? z;S%xc3syzP3b27++_vK9W8+ut<(JO$AKg}xn;vk>eC$~JK0IX{;PXj&ki2f zi~i~!*VowUxc=#{^0+?oik0oi59oAXhaAlHVK%?Y()|$PnPt?sP=EZQgZSmj%s4|$JTTI|As5`h?sZ4>YV$3H7-4K zz#W&a!2o&oxb(*XIWDFD%^jEeVf5m-H0f`0T)O;kR-M^Py!$t+!vHxvB`<@UFdJ{i zO6?&Bsm_XV8jQ>uw$%!>icuq*<{J!hSz{%W=z)BZb!@dQ&PG@xf>AFUQ~hpbNJe?aLPD7_H$u>_Z? zoB@XS7Vxq&flzobM3}FIs~_WfWCo!X`wYDqe`1TPO}6vhu>N2YS8m9k#NIrvWAS=32&O9FvUs zSi}SmhMf@bVAv2m7=ABC-TkZO!oxTSFk`>@NpQyg%)K=FmoRh`AG-Qy!LIH(#G$L! zcUlZPA`j}GpIe7)^Y@lEUs@NcwLoN{)dojMqTyX8uK(JqN1y-nYxm1M9*7cr2SoSd zawcy+u4i)JW2ey0*}l1A{kQIydEP{$SNPV8kG{1Q2l%q=*gJ#C z9Zo#j$EiJb6!AD8UzQy^hIoRHFUyV{Pdw4EIN8TGo&>9FINuCv#9nppOz$i4zYvL~_thxZ_`!;EO^F$h7 zyxcbJOJvdQ6EvfF_uI&UzZ8Jk#9idwvGoyxk09t<0P;hrN3xM*S66yDNqL|BZpOSB zWDh((_!p|;22ZBk{dn)&Ua|N)tNmbJyf<%Wc3W$3(j&9G+s*EF8trtmljJ9^|J&*R z50E+AYQ%frS?$L127!4!y{&;ajNb^p9V$Zwe?7fr`*rY=97giJG@4O5m!u5-dOE)W zWL8s+sQBLMT<>EM1G;9^f%T~CJV0~YrwP`KBoC34H6zL2T<4PPTqqv--Wn8moi%x} z_Nz{LBG5J}=!@yMU!nFZ$;l*Tl#*NpG7DujXqC-7z1iF(aWPtxcQ(w~^gYF`5N?xH zzGu^S?`GGzq<52)H6qE+-MnVAMyw*_wH&@`MdkNa(u6#|{nV^kh!NJg1_pasM6I4qTyH8pPy>5`i=A5#U+qXxJFvig+y^b-p zMl?ZY<<^MjXj57v4l=E-5x>GVFdR0l2vOo;1a8vD`CjuC?aAvoUOglkG1?~izp9ez)ga`E$- zDPB8m#rBTKgyN&t?!9j9CJ85cOx19#8YSV4T1d5RmIXg}?_j4)5&fezXQ&0P zC(o3|(F5uYPrk&FeII!86qs9~ADQ79i^r{CSVfibNoiRr%fp5MRLqg4mRfFjZds+?dN*xd=SFP3EbMnZWs8T{O8Ocq=Xd? zvMJ{qH_(&cB$~1?Dn_h@XnI-~oE7H+jpBKQ+8B zVxE0)&_F`{9&ni_=a>emxsX{d#~dzcK=I58M^{BrR*SXc_S@isdDd17=B+xZAYT1AMErxtSLCy7hDpDz4`< zAfEz~4ZuY$Y&hw;6Rd4;TM=aSH}ZFb^#KF#E&l^y+nY_L)N6!ruq5fI&u*~pL~+X~ zTLoELZl`=ui=Kt3?>ewwRPL>aKY6ESDRQspjsYWoIfQRRXq5AkFCnJAS^kg*PecG> zI+*2^;1OavnZ{!nCmmx_8vd)>;!`mRaYUHng$w*XtuTz1mn?gvY5pkU9Q(0A9xixV ztIaQ1hN#ceL0n-T2ay`JDjUR=QnD(l1vyx2q-0BU8`@l@Y|QBIDY{x2nbEsRU8Ahb z=(kC&Rc2=NH>9prc2@Lb-kI0(ZjH#Kcj4&$*ou??dV1^EzF)> zF^vJOH#2acXf^FR=32)R<;q}<+1lxK@ z@-m`$f^9u4iOeXTU|Ww!A~%XB*w&+x@JI0k+j>kAB~d)VwjP&6X%tSdulLyM1l!tf z-tJ(f9K{oC>uK{T5K~lzK4an~C&rQ}oM3-?*P-BN#hQhUtvmUnEh9Pv0&eo$A zLsz4-^_V1_c#h822~ zz4#&0Rv-F|I0X>pA3+K9Q`Jc1DdD;ik6j4qzfk4=KRh~7#tB_71FMiq2S z4s`ynL8n205utsKnA*nfnpRCc9~JP!@xh_b-v#vfQZM^wabFudHGLV?_?jpFsBLaC z{U#8h)N-@L*KO=BfgK?8uVRs|G&zZJ2V`z9MTf?pl*K zSpC<6_bdGt@yiqZl`5(KJJ8$&>Hi!^K9FL5K&ALi{41eOcF$jcnsvSSU{w|5z1je| z6bODD97YtujPqi%#N%!4teHG^%^%6%j(W<47Ow3o|7f|$J>ho@t6t9aueVJKPKkqe!lgp z1bhrdSfAh}iB0gP2G>Pc!1R$#`Zim1G_40gof^pBFyHf!0=Z0Cb3`(qE`e+oWlepd zqO6~$wdjSRue>))^)!oX*7f<24Izmga8dCxWi7JNK=zx$z~F5YN@l*$KLzC}1G$6b zi^*{AKL@Pupz7}n1n<`}iVJ|0P@@;$Sr!jgugO4)iCh?u`EC#}44AC7xo~zsIxA+S z$qE}U#eF%@n$2-gKrcs8SowWqr)p++E1*@ztrpafCuH~eSAe_|{3^}sbu~D6;g-?s zW*|rC82MM+TAdo_hp6`)LrVJhP?;un&PD^4i;7V(+2r(_t))Q5~Nx&TDTc_ln`5creW75w6q^ zhRIQ6;BROP>)kM$LxhsNt0dJObHtrA$`r6@E91~oke$**A21g!x4aWlSeoRP~V{lDpTP{%trP;h(xH8Sw zA2ogi8S$gWucg_e%Z6}dh}(mi7q3lJUs#J-%nv2TO_q{vl*IXgTX7%Zza6&-9DE(> zs2H7Ym*H~bhIISuIh!FeC)(x((Yze5h(qwwqloqs?MIMHkNZOKidNjne3b?Rq!RSt z9c0r@aFr!p4Y27doaf=0Q^n_9?WDGn-&^uCCI25HI>Sy1NdDg~>JI@w`&wr6clqT< zvo1$27QeH8LTz6ztuAK9J0yb{50V)-;u49hgcEzNhXEswM z-3Z#qj3nb1lLg?f1YO;1D#Qe-;{7FHGSd~%&Dx+;>FY7l9MoY-`e*tc*#-2!B%NCZ zS}xvylk`x~dGtS&6N*NR%)tzAkIdacK{h~QHeKT8z6Y_Pc2oSYh&>5OfglzvpNC#NS|N84m6()wcTlzyHJ7C3Vw16U!cM%b;80q_%ms`x9+ z0E^!rhS{>;t&qhr>#}9f3sUu2vhOMC66mU6FOzQH23?pLjqAAZ|Faj_tv8FtgZ?`N zMI(SjmIJ8*(wRt4Abuby)Ncq*Z0T;dSDo-&S%?9UsaVcEBbFc)j73qGLs!L8Cu4aU zw2X!Bk1&?=RV*JuAY(aAgt3HU{VikZ2n4f%ysB%S(EX$V4$P*uXw4FNfSh18^@XZY z%xk`8GZlZsoHIo#ve}hlGZmLYv8UX;cK0KYKTf+|`htNE7YyD;%Q=R;4#3lc1S7f$ zy@uxp8-gA6ilMxBmEQ7g58G>Y%FD;8_z3eI`0>UJBQa7E(J?DTOqQKwt`t48?5lbP zZ+TPChzZ{ECgH>cZ+VYH7Ty@1UEr4Y%aA0-JSslVvU$tf$+qv}0`{I9HFzfGxr1jX z)FlVcEqU(X*#{E|2hWUrIe7XC)ZiIcY^Rv(MM1GW#EOd*D~j#f9x({m?1P*!Bm&H) zA!vXe8H)P=IkiUjqI_|x*iPsq+1VD^zoFi;kQy1#H?miW)DjG2wY2kEFM-z?`-e=@0U)@DlQKbdsi54Ok^)omUz*TN_gwAs`@MjIVD z!{~@Kn#>IO)?nDYkA^nujck5k$=qcYk-iLm7%RqN_{o%+?~;CQSD{K(S>(Fh86u^p zT@a8;^MaYFTA3%C#;nV`B@YG*B=sB|A(K5##Z)*f_Rqt<(&<9Ql3{H%%(SB;Fp2CtZK^NL8_2%))mSyUSW6H2`_~= zF{)Qd9wI4&dW~dVB}h3;zE1K|lGm|%-XQrpNg3gr46vjMlZ>q9!Z?L6ZwSCl#;fGISAA1s_ z?8Ldksev{>MjQKlEZUhn9){Q0_Xj@1^%|F+*V?0^YOQa%kBlE9*5VMq3M~>yvYF4`d-7B+M zA!Z84w|yAh0A*I|nhglaY(R*W!i~%~^I?^utgd#gQbMd!v=zIOB8=|5RBL{pz^Zr! zRWS>3<0T-lS5@(S0%OJg0;9)e4D0&@77d#gj2?2@RrF`1WziM=JLv56v4*!Z=3^uC zE>_AOnTN?woCZ`y?2*2+q~AT#Z`M!6Qgb-^fU2J$U;0+Kk&{GscP6|tQ{U8H4WDXh zc4tBvx?iVitV?8F-zBps2c2!qGQ3~52jZI*FuZ>NGjhIUc54!VLJqX)CD+p$>1l%N z>1yfeQt1h*%AOah%o=IGO4{?SK`N|V5YU}W!yeiphhzN}?<`EaTMvqE{h!^kcJ zPYO2zVejhPDlB>gJob~IvXQyE2)=)6BkN^46jgbCYQuWTml^-khIOIh{xu*8BlA`c zKAV+UlWVp)#O!XV8Eo4J+Pu%EH8OV=!)~Rrd*8KNsqE@0T-8P}yE`}rtZu_5F)~jw zw|TU}Q|u>Qvw70Y$SkMbaOJckdcG>d@Q`564Tc?{qrOVB)Ya@8^fQq4+)+uVxzdgy zemYkK9X-sEZB3l4whP+nEZ4-zYLmy#HF2%gwpQWmMa(dJZ{PzS63dkB8rOE2v^6rv zGQ?^ny~mYS2c_ARejh9I-Q!BXkCpk#u5~Jw`5Kvgs@c3pY5weL-V?hufR@cGk+c8( zO4rEzmL;E|l+)2YR1MAuaXTyMwvqvy_No5jYM%DB_LqP9WWi-6{H$;p*e?<{dX9aV z&Gn_C5UD!CQANr8jb<+Ial?dRQ;z^y;k@~;FMGz zJ9{NRu?FhBuB3~HeeCqAR1Zs`(Q7%&e5a4E&{cvvgMxe>l-K+GuHgEhUJ9T^iL(ZP)T~vXYS*DYjD6?GWfs1xKsu?UaFY2rLxi-rc%qI! zQ3-l;8=d)f%-Rd^Z3h!*6JI;6TI1~)wrn3%W$vZ)`%Vm7_gc~kESsXABE1UoK#*~O zjP9)p(E~wGr-QxHK^5s=S+;j2JsET#4t~EOhP7O9pNjb!L6r3e?{WzHl36|s)SaNp z#{zj3h`%3ZTsFvuP{yDZ;0>3eO<=Od^eAUkTmTM-YjD(Aac^!JG^fVwz<{`qmpq%s zcGhK{D$D!@+~*!;i08`?PvUxoD#CP0*Pf$`FhkPYNC#xMpD7uIgHa|P;GZIoSzPfi zh`BroWx5r-2@o26c&sH(F}$lNy&{I&pv#KEyAsmAWR~{_)dH$~7?2N%j0Mtp2(0lw zSU4I7^Q|<$CdTfF_AiToybkidNyDbiD;wpbzsR;mFP)|_JCpCRB2TH4am5uBCpO) zOr8S`bVuVWYVhk%c!RG|`8$wJQ^izh^x6iEIB0Z4BvlD01HO4}RHgwr5cFO`Np~q} zFe;0QOcRg8Hqd>VvYkbZp;DvKs2&TX7bM-`wQ8K?P6677!|#0XceC<0#5@6`vQNP4 zff5h+2FMZC|F=K}f&&9iP4B~iw_VLAV&0`e4tVlgQ+?i#_hNmIwn>Z@BkOTp<1yf+ zRJ}E(S29$ef~OndsV|x3FM@g$l>Z>qIELjwNB8dRCDZZcVldHqoSj#JM2+FnL(FQr zdKA2mVBB8|%J~`ge}Yr~Dv(90b5L|QAC6SggG(gM^1T3B#Xnfa{|V^9a%0Sp z==UMVyHw9H{o?d!yT!a!JTgYlwC_Z*wuYPwZ?d-DiK4feq-8XUUQ1d=qv!`o%V^$- zVl;1&meDBrx1d$-??$QIYgKUXMX~ZDYf(2=Vw4y(*1j1(WV79W7l4Tg3>U9`O-WN2&kSET;T0$7y zhGfP^vNkFkF`Z-8ffZAR4kJF2?R6eq$=ZmIWP9C5TGof6Un4EsOVMAGmZ8K)vc0^c zK+E=ukIbQi;bh3eAwH5Vv;nkgv38Q)4|>SSMlpW8-Kjidq8h}LF#`{l`++A%z7HdQ z(PPMxpsmgI{t;s(atcZ3;#qrsYHfxhqP=M3r$&xcSy|#KqE)Yn{7iT zot_Pmz|@+fByMYn+Zj$*&nF-k)e^o41SK5rgvdcsQf~ zikdQp$HN(I$MM?J-=8uN4GD;@t=#PczO7HoK_!QBf zEBnW#GM5IZsoCbzGjh2UxfsR+kg80S^n21WlS^eLRg;m)dNF9Koigh$g(y^}TPRiI zqjO*&v&)p(O@)EVE;E>&s=7>>9hy`2BqiHU=W63^YYEbd#Ga{k;t1*Uki&|KpQ3#p za#TerpNAaTra_-db^&yi&rck;Ru+rGX?Buw*(hDU3N=;Rjnc^%q-AK0GKbDs!hiBR0W~S_%znQFiW8@Dp zaQB^Q-il(V3qRi}NzZ?Zs5y30jMRQp@;Y813g=+)k}v_MfU@vhs;I(WBsE4}fZ)&L z0K3>^+gw4qya@CXN$&&g#~|q;4s+-T#K>N$Z@AQQ&2TlS0M3jM%215qWm6dm4dwwEM&uG8vw>7neJj)x zp`A-zs$8R0?jS9LKAeR6cK~D!F&}eWmoR(7bgjRl+2+jXRgbtJD0AXI$Kt`Mf za+3E?k0Z{iA3^cV!CyK~OrC3ZvF3~utLECt)~{p5=DBvh6*o@oooibG!U^j(+Yk{mJ(g>uP$Sfeci7Wx~IgwRBk}gEvybF{Vi6Zt6a_hjAdJBlq@&O|B z^(qm1|Aj~vGmOTpK7vo%`QalKKB{g2A;aH=@OX1?Xm61=-A)jBvu&?jF@8Hvyfn}5 zl9MoAtr*wA%w0&^H{tPf?2ldwmqk!uKWphNwp{=ZUFO>{*3j`Hf4-e*O&ZTy=^z%& zx5GU5Bd>2`#l8kS#roo0J3=(gw<7{`VXr#)O{}07(G#)}Zy9$=3?}k1kPCoRJ_h6- zXtP&cLtUz@(JF!ntseqnWbc9^m%~OaZl`6^**A(M3+?qjKFJY2 zLGA%@V#bNMi){5INBCsPQ%`b)Pmx4&44>o(pDKw|!?#AvzQ}GiKM@g&?44bHz&PZ6 z^f)pKZf5gt>tSOvo7{gH_qaH=$o?9S_IN&yT)ou2)1K*7ciP`t>fUJ| z1as~T8M#c}X)nDPciIEPx?@L5|Jo>Qy^Z!&K87?gFCMi}{W8mz_#GWP$S>A-vG4>B>851GCyVOqVv>gsm3FO7a`~a)iNJ%8bREf09?2e{KlwXG3*y}~( zW%jZ@QD`7@VHmUx3t%?&Sj#2zv@r7=OevZ8mMsZ-%aYH1Ob>g9y4g32sLSmx-M*qc zPnwrY^E+Ubdk4Y-m$+G*`=B`Ya=T-PZ07W)L+e#i^=+yS6RR$_69S9rXQ#t_lII0? zB{$`oWDIAaPk7ocFLBl*837;_+MQ;Pto}=_6zWg5*DZW#8)fr!oXH^Ei=nrhHln`Dw!gu_|MQSie$TF*=(0P z>F^;s$dVa;3A#{TH_VZA(gLgpkHb9Dhl`MZ0O88&Ie6)bM_KwCIkVUxVCAgT2nH*1 zW*9lo1X)JGm9RE1G#N`A_89Pa46|t-dS%ftMtLD__TaV(@=|%LJwr7MvHN=4Y{PpD zHE|vKQsM6mG|{qPo_-O8&&?M93fP?jUqML*(RNM{Nzn)^}o zgZIHoGK zwu4L7+rhUT#K{M<Uo@>^S*ccAR=H+ukQ$UT^ESuyn)WrQde&0Q~YT zERi?bd<#qdjkbOZ%VB8oZ3lC1#MZ&r#I-ltb%9FE&*nW5<1nD9yP21w27Byf$G<0n z_;=`UnQ|n$S6=*zT7+SC3)DNJ4YHoo$XgouUL${K#6KVRgQz@IBNH^TGN7^bK?EDN zHla^vAMA?=rbS$j6%=krqd&`#rpb_Ub?Uw6^E+McM!2rTwR_{lC1d)IYWTUfKt`?_zu(NC)Wc2;f=Q!3WYo+r>J7 z52b@*&@uo%U1W6MkM3_i8e;#8YyYUUALQCUF70QA+6Rp8cq<-q_3mG!Zt9^1(EC&g znxumju7l0e!JTw)6za0Zx}RVG>%8S`b6J2%u+NhfMu8jA80V_67y!miT^_IQaOVc zu7QNL)DLXFBzYk!$(yVeb%K!#8ZC#p*o24t2EU}RN8KPdqQ z-J@BCc<*%!_3Ja=;2N$~z+DZFOwBHT&B5A*#_Tk=DV5k7RZFL=lOZ$gi`#^+r zu!j!TLVuWaz;{EN--g$Nkt<6u*mdx2I6L(}Tn8t@*{QQ|dXjY+)Th(Fcnn+nu)O#Q z62mpfrp5FjyTxH?GYU31-|9}?cf#L;SN@ooO}kv(ccktT=w=S3=DX7Ct)y#P>FxAY ze7AUfBd$xzJT^+Z52zEv?cw18uLR!)1x>U#>|wuCg2O?kg7T0)cVNuE_ zJI#hZd%$Lqd3-N{xNJL0vl_A)Py$ol6)%j27MYhQCN;Ct!Q<$V)elG!X1~H(AZ(-N z5Unx(Ak*mEjph1VnC_3`7);Yw&{du4Z(-~OQ!f#_1-3it6VFUySCTLo22p< zluynP%w8gLwkgJ|J+Xb*HQp+X*SN+h()cqNXU<~Xr^*Z5Q7b~6iP4+vF0;R-pHq&G z7!)Gj;rcn{Fybn0*AGD$#V^w4b=Rgu+MIB0UY9nL&$PK;e6mR&(bq_Y%R?1p$&~kr z7%|LI();NJhIf+mes2d|Eu*CIoiJ9tX0*IS{VZrX)F)!-LW^Pj?5u{39P0lGp^-(& zAZC#@7#NX0BZ07egCoCDJf#$t1#Zcv$-Ixdc^AmMBQF)t-)?sftf6wGt2{v}cTLoR zMoQ(HOLd^pGSHQvjbgcv|8<+SJ{@J;AWivUSJh8mw^{3NKvi7{e%I^ezDDsJ4~w8UV(Oo#9)E+@LBw^xce^L{+3nzDt3qBdLs0C z^vr>aS4{!+9i$&GlQe7e*cIaIyX;JJr-<8ZCv}#VtEFYkmC*c?nycjn|Eep+pv}a!!xRJ`XRNf4?g^xhYDv5$H7<`|X z=ZoJr+ub|A4+a0NIP^~vc@&6m4UlJnI$L$#yJGwhkup#j@OLOy-()3{9lIYs1igRl^rh{%JZgEQcCs`Op zv4>X|kYo>#!MOV;u{JXEjs8heBdkYKDvFXN&V2^^FtUSo2!(bz*Ir?oZOlR$eC~Bu zn1+>jQ#Ay6T7WxR;-v@eP8kJJ=I9O##vkGWlTINt4Z1*|xa}c3sirvWjL`7yn!@-t zW?N5XqNqk>JsDYf(tMwae?IzMuQOPvq26NEleQlpjb>#!?OlI{5!SQio`>vB=IFD^ z@1Pm`MX^ih#>xy<2}-J}EUPtc#b8~q(sW(q8=~$RJKo08B`d2KS8`nilr%pIRn^wR zIw)xM#cFJ=64C!dyGvthm6WvBW6xl{FgtkbrIc>1PGZ&d&No}zOV!qG)w1nzH!?Jc zKH`aYaH+2>RDVc(s_gZBTjRyu-c~z|)1m50xnFA$up=|d#L*V1DmttUh^o$LQU)?E zYP{^3)nRBy20j3}B=IN+)>}<$xiA(myaeHY(heUss5OUV^uTlIu^ydBdmPLjg{iJ2 z=y<3^P@TgOv>RCHccQATU6!8K_P&F)%^C z6MD(1>W$D-kouvy0ciu$W8$KZ?Ji-NY1ln4?)n(_%O3gIPVS?>V5&cQsz0WxzrT98 zs~U*)r(pFbW{(T=03I)Ox~Wf~FeD7c@>h=k`a{(EW7=zb7~UgFY+xjHzsIFNpS3Cr zTihwn#&&5WyOHidx;zKh$&nrirlq;+E^Y8zRu(Gji34_zz!blF9}}Llke`E!E>xdY z8iX_h_V~1>_YtK0)v83MiABfYv<0{w{t{Xqr&rG|~=>LaxJ^AaaOvmpF& z@u9zkK{}gfboy%?WUz+ytJd|0TlB|Z^hZ(j$7}Q_f%I2|^oNJ&hreWiWxR2xE_p+h z>R(cbe{(4h828?<74*xP^}Cw&OPuxFo%L&<^*f{W+ottPsrMm+XgJmHxIP}Fb%v}3 z%Xs)%o!@E5<(2^|jMG|3a{-oNzor!{tJPH{{Z?A4*6?5O$EA^FymmnA>lgY>8=wNx zZ(7vvbEFyjJYIMiF56~njTm|eFH#!x53%qN_6zElgz49hy-};~D<47167r{0-L|CV zYu&_mhj5G@K4ecQN%>QUq~BDdU%tZ^^k9^dKQf=eqxv8_sGzm)C1m>8^#g9Wx=P@ z_0#TrR9?*e#LjN`sYu)C=a%(DyL#gZw|xwU54{OPZ)li{Ti`rT)VJ1wqKQ!L6U4Wl z*qbBu{@BV!ar38kewluXih9}nhuqXu%VH{7sIFD&i=O)8sa|92tFijRu)a1GyzDKSkJy2P z{Y^UTW4Jgo7;bYHw-kMD7nyAulQ1*_hITT%^?*jP^e9GL&PRkvfM7JnX3RA^0dD~g z0yO_NjQ-mI+X0E0xab7Hep6SD_xE{s0Coc22;m<9egxp<>;TaI@FBo}w|gGS4Hyd0 zg4=*^0^ofY-pwKWoxriQ^JW(y1Ax{ie;XmIBHFI{>utVQR?$aH>(Srh%7K z%qw^r(2Li^dTRjMF=u1W#01X71kS{SV?p3lEKYu5Cwhr-A{MpBZGR;(PRDXeM#?Ff z(=mb5F@e)DfzvVJcn~-r(`TlfnK=t%QZqt39wiwMGYfG)94$>Vz+aZe2aB0Gk0@ z0XlpxFu0h|9&}0`7Z(HzZ=d1n2wY?c|2G(PQpaI>0E`51Nuj-v-yM(%$OYsB{D2}r2|(*@1-=LHK7dOR%_n^T za1ih*;0WL-;1~eUb7(!$;~P8awi9-$*!_3g52R8Y`NsB(ZGX2jMddekT!7F0o(4>x zf=UGF3=)Bl12j%U`vaB(ZUfu_kPnCk6{$npufQL4eyhE<83W!0fJFd4Evo$olFRV0C{NW%L7t|Zyy1U4Okt4KoI3Be8& z1#jGJ&1EEy&<(d8v%PVo_+%X6GCY|j=hI3qEw2XXo~KhTExDZ3G;!7l;S~f-;0`PH z$V#?)q9nPVltV-&F|H~JTuo|6#JS~;z_p}0FrHk1!vwG!@CrcJ2Q|h3xZ31(UhPGv zFuA%UaCJ#2y$GWipa#GdCRdjPt}Y43 z7Ku+!+E@6vtjt}kAb)Yo{8RRf$nfsCz-AfWi^6WsTcWnw8PZal<7AsH9saOCG0k1# z$3N|^J#kskPRqAvruOVvP*Bh-t#4W(p<-rQmu_}!xqVT--}Vi)SEN=|G&eWjWVhKc zzIf@a!xD+{`$71+!2?dbeGdl8euw5*JRyu9=-T~pFK6{h#fO*bsZ9KwIzE5}zX zwcF+s_vCw)Hrm$*%I#&Tc4oO`m3wZo+l~vO6Y>h|2+b#vUjAssh@};|>4jHTSa@6s z+YGICTprtBS$LDN3C`!Zyl5E%R!{*=lvQhT#cQ{SebDr9 z)oULXzlA%A;avIJt0F}wuhXrPOJMu%NHcy!K~9n7gcR$uNV7wsWruKnjKt+T^92&sR>1}^5$|9Zq9xlP{ zZ6Xlqq;L^@?2F2(J&;_FDK+{2}~EyU0$r;~@vaeIftxg@s_hzp~f-r-!9 z+pF4(2csOnhf8z&G4WZH^Iqu#?alb%I&4{-yE>S5-kFv2eg`w@jM};)Q5=tUD)V?U zWQ!!TryV`iUXqGNPP0=}3+?6k1r_+SB2}ex)o&jY!(yD&zFhg+Ydf0lhNt7NE4sCx zzYKYh;IQEtfxV@pnVMcP>|)DO4tRQiYPcxINgG-?z5@4I`~?*iT|0Lzuo6Pr^~z*3 zQP?l&@kR9o=d0JsVB@V_o-NJclVc*0>al_LJ`(xXT*G1*|g?PTL^QM(iCa#WmG7@-3 zVc&%-*KUW}SSEJGJ439)eMLlqlaj>q3;Xvlv+KFT#@j2(b)kosi^>Eiu{TdO>}HSI zJ~^W>C9R;$U!dE9Cm;3`9y1{~y`rLDUi#ox(HrIBMi^Ts%Ef~Tj^B!_5Qh?+0;{Y- zM7MKt5_#HT|J7@z4d{dN=y9W|LY&*qY2T42A@+A(Gd-=x;B8h4@Qk}iFRaq_W%5XYb%d1m{R-riy2Z&cPo$IVAHKI1l>6*ZE2>W`|?EaX}cWX_{HCfJY zb_!1=>|YUfO8Q>^OiV2H!c^UV@2wSg=Q*7dczR(!ZJF^iwfT`+@qQjU(TUoY&iT$r z$BL^H^NO5QtE5icSmX?{n(D;IMb0D(7Xy12qdy+0Yq3h4A8iXu_+NTEEgmk(?O(;L zQYS_1FLioaAJvPfK29gg8P$^6#~E$n{kScGGUo-y+S$<3uRlimTrRlnT{d3ek9jCK z$a3**AF<62-P2QaQ*a^PvaZr;>sWV;5nF1UBuW1S1E4U zpOtx`cw(y4&uY3*oSN!foxoL=y)D8_xKh`6^1PPor#Zcx_FPig>)MzJ<43ryI&Pl$ z_yXrVYvcTul9|rsmUVKzcxtw@$(p{PWyBmO&a_T15R)%-o+{v?$^JIhG_lkeo^f7% zNpAEQ#<6`$+ffRk6JQy$qez2fRiD*u5!}E6Ss#Y zh?%RLw_7S#JLj7@gR6#5mbwiKX3m^D0~W^Q$+PD#DeN_QiBVNsT{K|$u$tM+W>257 zNIY_d(>r$5j777j&K(8Dv;|WaO&78Egmq|fu5_Bs*b%j(C!bqCWZ=k#s)ixwjuiK- zaenQzc*c^+GcQ@RVDbfv7a0;+JY((!lb6g`yrku&tDJvW@zdumoJ_3+i)PQ5k8o!% znBVgFTBpoRoVRf44PM_SXr{6z$>iOr-m^*pe?5T@ej$iAfnyItrFAFuAJa6if zMYESrUb0~F;`67@ow}$c{CeknE0$`D7F;~JNU~?NEWg1S8`kp0%}z;_=(gGUqor4~ zvm`8X(A=prSzAjNw>)^SlM^Yb-*MWv9DmG7HqAy+_mb1a!)w8f$zsqBoC!H>B z^i4OdTq1^$&Bah@h>yeK60*7S31wd<9t7JwF5Z07nQS@TMD|n8$S`^54R?>7L~-j= zPP}T-IC_T>hkBGFFop_P>j8kGI7KxG1;KX2`xa1kcTiR1> zeg^R#7B4*GbQ+q7lOTORuF99V-W=(3m?QbY`*X56NON}P*$(s=@Z~aE=%z}2k>28@ zTZvvV2&sqqn8W9{I33#)=RD3kYf2Xv@XN&J7AGY@nZBJj&=Scr}rwua+{O!&)I<-vT_FuWtzsp#ErAzrfJ<2+ua)rO40>*v(M5IXj$` zG-jmlAq#f25)z1d&9&3y_&pI6=$d`91RjC^-I6!osJS;UM(g)kE3U~xcqsiApZo!T+OgJ?17}YnnB_om+TniV@-1qZaPaF ztY_G2!6Rve4=p0?MVp;y0jjL25&1iv_HBss(kV3L!E-{4-iZ!~5eY`_W&}#ME6FQ@4nvqz;JNcfs=k@hp<0129XCRqr#4toC`=TjxZv zLJo*iyPOVEJow*=(_VBsz)7DMF-#+a7vcF8aTSx};=vc40cNiF?nS5AGo=msLXGIY z+vye21boRr^eOiDcwZ&**$LKiu$DMtOGY7Jh&LbIfr zP6Zx1q?6xRD^gx|+7BhJ?}ww3*!gA0Ctu$mM|Y9F^nG$ogDrJcUScKu1$3U&VJ{#p z@1Fz50CT0Ix{#X(*s?)GeX`L*Y4+1lns_K3qJIHI|GUEwga1fBRW?On9}2E_0I;m2 zc>#YGa173CoU81sb$wFCi~7`K?4cBmR>b}Gxkk4NOK=bMPr1<<5r^^tEd0MkV ziWAm^UFBSDU&BgK#iU$sanSDcR)+y<5hFKHoD@S|b$WQHj-3z7UUj;gC&gW_Ivuif z03$;@0yR8m(dx+LTG8>8U=P^N2JtK1l!&y~oF3!J(mN(t|D^TK2~G1HihYrRQqCWD zH6YMB41}`XG+$R=iMSi?+q2#EW(!siX`Fw3`Whwy;y4HU<25HGg1Fp#A*R0L#7hxQ z$NIgFDVQRhl3k#2oR+PB-DxjP^<5{vAJzC{07Oaa7nq!V0EX(aP~JrG2V7c6 z+rQy-XWH)#oXQ}b6Qpkrrq8{B%a7n6L@Gmoxv^WE+J@6ruv6Z|Ot0N&-Rnp0wxPkWhbX&!VqurQ@Z+x*#Li z^!a<7_LFoKt%B3g`GEZOXXv-?;?W1H@&iNsh66Oe1UT(?OcwX-af)O$;)=k*Jx=#B z@_9>!`e)|{mU|fMxb$I->Mwf-tENq2{5!bJx(WNku{CJLJ6K9=5_i4hbQwVwf2zMeWzJR|O!hF^$Q?!^?Iowf)KC}NrQUF)Y2F^9drbp1R-HwcpGE7z zVv|_C7lXy|E?7*%O-HDu0!ZUR$F997?{V?TUZ+bHS^Q~B(!8bA2%a8>*&JGLdI%pi zZX6dC?>e2}Z9I}JtrhAGN^)bP_QnJDxVYSQ_BoxB$kuzU&@(uC$dUKBSiKMHH*Lkvb*A_Uhyz+2 zS|nZq%7r?Lf`>c`fS}63|m(P!}{N7|5^HH)ASYUPpyz6)?y9i$F0q1k@h@FyH(8o z0G)QLxb_35Q`lAt#Y-RHtYNEo;RC0GqN@PY^j_K*v4H?cm<)CW#3m^LlPRu%*fb?z@`EcN_NNjsv3lz~h=l== zM_6y{!|=KiV*Qka$plwGY?2Z%S?LOhU7-X_wz&dg+m(RHepf*3BPC!GIP6M@eX1l( zj<^D1Unv2TKU@JZ3%BM_5+*wVs!53LQUWI2HK+u-F~35s{|vw_M1M08uc|2~k-fx$ zkDcN`B=8u;)@D;uu_*_D44EtfD8Iy(C;^jYu7KEbC1A3`6%e~j37D*O1;ls{KY&bh zzP!|&0sxB%!#J}%R49}Rbxewa3U$rIsBRi{+L<3WK#Kry#$+e%ftv2NW1|u*yr$HP z?|0!ofEJI|#!c8ud&1^&bY`(YbK=(+-|bak6s9XJ0_P&w1LSL zipzvIU8R1!0A^g@<(z1=(Rq;x0QZUhJz2^NG%foD^rWW2B10xUiDjPBCX%xms=Nl?^%sz1BCk z+SO}2CHU{AqjYvu7!_hUD%5h6+aTobktJ!^8!U;bAC?HHXOWIzn+0ls$#H-xD6wCa zfC*z)0v!@JXDG|MP|LbzT4JdPmvv0EWt|(6YZ)-=wW(>0pzdaFpu1I?)-lnht&z5x)@xIQ#2g=yX7x;H77{4; zqs##yP$qIyiE-0f)V2CiK2OT)0!-`ksXLAdcjq(qx@KZ;DFKs?1zJFi8~9)(R_eH)w5d!I{NRLW9XFHbkJ($ z_S@fJWk{cRf0A~8o>Giw6=76Vzi5av@egZ@)v9Z{Jqy$JH*p=LgZaz%umW5<`1puwfWDUSJ zmYU7$fiSm_R%Z`f4{(f|wg;Mt-32g>QA|{Cr$7g$)DVoyUy-_cLVELB*_(q!SsP&V z!Oqfpn5{t$tSv^YYb|)t&=9CD^jSv?l>=v5jn)C8XsuSG^&v-P9VIp2m6cGt56Llw zGWlAf?waKxWb+IF!vqsn2AVFIQ5A9Kgvb7=!GyVit1~(p^d4vY7~btiqg$ub-5i{C z^-pe=nTeZ@I-LVkaCWd902fTSrV4SsMaB{F-4~8O;s{V?S5A4BIQN*7 z9Cj4EpT)vsxCr($P%Bm3bj;}-VL`1epreTU(rFi~T#=Co$RRT;0?tV#r;3;_ok@Xd zSX}6Exku8#-bmCslSqJ?k%%QI0Tb?@RD%C*S*I;gyRBw*+AL&zleqj1== z-UdLwWwJ@+f9>>cw+ZNG#bt6Y;5$QfIqnpS&c~g8;+wCXl^w~&J2t%cnMHOj8h@kd zt?cOiv!h)rRv&lT4?L3>qTtWZH1X~XZS-fyp&9->$?9tTTUX=%16QryhiUJK?ccip ze;8@t|4pR-CirGnwQ6;@!@dF59ss)aJ|xNAjdO{Iw)uSUb(>R_ICbaB{^4(Cx=`Z1 zn%5w`1Ay7-F(j`5L|R^0idfYUmY#(j%IyI-IG7Xx)R9Z9ObM9m&KBo-!V2XBi`;1q zeJ0rekFn5*_@iSp@u7fl45qbYkYESZ3c3Kv;FSYVrfMXE6so0k+a16nF;$ukN;8I5 z4cf7o+7Q-7og1BS7FBZ>_BsG!+lb^rg)(^vpo;Yvux(1ffXOabK#F!z%)OE)#_{RWXG5HptbcsbOT_%|TB_P&M379amz?u1TpW7<{_+;`LKq(OW zNC}uQ?=vm==s>wrU{dWW5Sy+9Os;SR#F{FUqzTEru0)rR_wU*(1ty8E0x@PNP7Mp| zEu#P73 zE*45R?&6w(i+7{KJYr#FSd`d206q3(@32U*unwgE6hi!al){R{Zess9>AV-<;~?Jx zcock(^d|t$JDL0{(FP`#%&U%x1F(%HX0r!K2gPT?Vz}qU>O~{>O9!<~b^}zS5! zNGj!%;YxB4+`~%3gpr-u&ToOU7r+xJrgY;Tn!W&M=sV<;T+4*dP@HMM5nMiajz#Ep zBz*Q9sDAuBWYta6d!@9N2_HmPo`}7y1Wev=1;7H{x0HklAKExGb3WA`;*$@!|68B0 zxdPo4>5I?4qf;^Y)Kwt%r4k^)L(T3WLo5;i6DAz6&Wwf%HBzBrLQo;3@ebq4!B6t) zK`j$LSFg;86#(Fu2_Lps0$>5}NF`yybM!NF)DP#gqv?|Iy3=+5c}#aoytJ9=NdQ7( z!i}P5o9&gV{${31H8AGi>C!eAfQXs!>3kIzF~1TpDRKqGN|b;}FIPaUR0)`rxdLM4 zg#npKIdDGyuQDN42|(^ls$IeV>FiA4tSYW`zq>iRX(j~(#1>_+MKFrZprRrog90j^ zb9xYwSwKK&TWm?An2iQe2^t&^j%~OOK+vEuVhk}{Z#2djgT@#&4(L@M=AsY1YKRl> z|5feUyH3lE@4eH%>Q&!bt5&TVcI~OEwqn{L0D*`e`W07~wi4K@-~Xe@=sRs{O5_9r znTpg9*dl40cj2u`lq0Q%h!UXjoTs6wm%#{QL*yG1trLj`p=}GHm`r&Ob(HQa0%MEF zR+H{55toby(@C=A8bryyFv;>F)@brPP|_VnTD{|>$cdAiA&F&E7qZT_e^KknGoGBg zK>L$?JRYj=iOw?d5zX_Vjd5Ib1)(H}s&9clZQ|80L%y=n)NsyV=E3RNp!R$!CizobSqKST5(_26yFyKD2Tj6 zunLN4V*>=PXqqa#!LmdiCs-^PGC0oRS8^ZE}blDb9EW+?53XiJRsxk0g+% z$YdK8nSWy8i+^NJ@1%*)M_9H9OQg6WJ*2RyU)Vd+B_@GJv#R;wO@@^fk&R-j;;yg?E{*1z*I1T_ zOcbXPccxWvX*74eO8HatD##EU9Sa$6qaw0gY)W(CyIBPhnJHG#)*81Fuqz_{Z!6qk z6mpU1T7ook&5Au>B_b|qT49gEecUKyMXIpPX?_Sqy51T8%|u!^0SQ}bBdwbWnPsDk zA+Mh>#jstKu;Y7q#)z{`kYzUNq*@@bia@zURLtUXRl*ry6-1UFZ~K|KHd}vG*sU=1 z%gnfbFX_&=bZ|x6J=}g)UL5o(>)GntJQk#`|C0HHFBP_Znd#ECSb-aZK4ob9^UKVz z1FT5a+U%(ubm*W;BgJN6!dIDY7?}N4rtf!ZZT{6)nJy*Yk=@td<~CZpwdND#l@9A9PTZIeL1r?-&j&!r+XjhG&?EWU=;EqPN6uDRYsv& z^1}3zu)dHT$YDb4jKZc?Vf$!0`i%rCMnu^bSBw-E8HJpP zQ%F6PLcLMQi#UbUQz^_f3e_UtC&*LLg|=;_!BgF%uiT0@B9#BK!A!i{+ZszXG3+IScFniv1y1f(KN z1~5{HW|bG$+vkZwR(kD?ZgT4>saWO}a%(OaFJ#Orl;*HY7>e)OK24| zlr$@%G{si_mG(>D(sn!Plm;gy*FcWfDrmC@X5sMiaBQRr_xBJevWRji&bNiagWpmZ z0;h?91rg~NTadysqmUPI3Z}b8rW;5@`w98?Pr_3P$-Dxl*(I#x{fbz1Myp0-5}{Ra z(bA;MSs2zz(h&sb5=<|%`3K^8WzZf)#br=$>tYgRMda|mR2c9rg>G;TCbSMN3fk`3 zUD135V1WMdDAFAaE}M|2h{skmyR6Fe*zDMfbXvpqk1|~gm$nVp&($78|4q;V0{N6+ z9aBtO4eg6 z%QB~gh1oUXfqH1YkD02oKFJ_PGGm^ z#X)7WqB~<4RW>U+!PuE7QbULp6|Ezb1s8MYTG?C|0hDDdcP;K``#Raaf<=yI8MY24 zx7xmDJ>tbivsUD86FpnxKFbw(m{1xt83&ivarxxEeDsZ}GCnuS^1C73aFSN9fb=7j z21A=ghg$aWkP$XI5^{=-j)jc3QPqR>Jn6w*uv!(F9I{oAVJ4cqSM+^x)uL|lgfW;E z*-Ef|Rk0_nKtwxl6?bBBwpj%cZOP@I7gBM~iHkc`s*raIUN1?d)u}Xj@}o5!PZJoZ zM6}~p;#_xAG_m(sjZ&l?2+2XbPhnYEcxvITF5y*?HuQRefF+SG(@ZHu2AOD9WR~TM zTy41`w^**oI?ENYyMra2=_ZV>G4}H!YYDA_Mg5zVL-%PxXi$1~GL!DKnb>Uvd=i;y zicupn+m=XV4#AdLu`NbWBci%VD#O%;?7c$J0V%2-)_6gobdTGp>kZO;CyG_yf$k!- zX5i8NWOAC2*1NHiXn>KjU=bBw(X3tD?(nd0`TaPJXcv=lRzB3*s8Sktn1$+6twz%p zzb-9h@|NV5L|U6llZzF%mmHl^QkggX)7s7eI~!JB(ncE{k! zhp{n~oFdfTGp3uy64CyAw)Pd%E`GG4+sw}jw5{K$bB#dc6oM5f_UgGjXeSBOY^`S{ z+GOvdStf~y_Smxm#R^s+a$6!$?1b4Sg~%|1O`+I1Rv%|SOQUbypljvK5A<~qVh_c0uo&vLGQA0 zZARGMWRNuLRx;>gGRUPFhXGsr80ohF04GMHpC$g5rcZllWU29rTvd2O&!<@KP+E3do)lUH8Fs<2V* zemKWQT@^;pQp9%%bk}t_vcWi0qYRpi)nssa6Qxg#VpgusH;UPMh|+nj(j7R_vfL(< zNZme@MBP@CN)un$2bClkZxZE|Xud7I^RjPjvW(F|2fnlGuruzk%fVr1r(bM`!p0`l z|7%=wqAn#-mq(`8#do$^ip!mn(Qpv4Ll>`p4-IJ z^K>f3n@P|(E;`2)H!sab8x?6HaEd8ShU;(Wc!6WX)QFk%?Bw^sJHZ@2S&{$CQOph` zNt-_y8*!&7Ss71oSn+cVzObJqx%W zA=D{siWSIX^C<_1gUTXpNLo$6y2yi56s-|?$V9UuyDeAbOUo6}+F$QzNiF4MNm32$ z>77BUkWUmMG|Y1b<6){%ooJYwHs`+-rW5r3Z7%fvIR1BN2A9O|1|1Q{=Rog@<9o4@ znH!}>GM7yH@0R!@khgjT+Ip;LMFS z3RTUbvk15*Qcp0?FlAdt;ETNG_&bQ~a=?z)DXJFl#WHg})~6KRx)b52~`dD8TG zUm@*0sY10=@a8s2dI>>2M^yPM?tals81;nWTpib&D4Vj9xdACFIj&MxQbuKY9f9f+ z(QeRbTSjKP3oFj0;=Lr!r_v<1b=cZs>?H|O)?T!d%M)!!{ZA$2Qd(5oQm0M@5`QXj zkQ0%#xPGMYx>3lBIEA!Tq_Ev6REs!;^pKW9#YAo;)EaJMbj7tf`Xqwllc7rLw^*D| zyo{GF5?J9=`u9B{nv@QLG1s@h1Ar<)KqfopGs>bok*a^JD0r9FU4rQ5!a-4 zk~UJo?={k_h;|J3nn=>yj5H@AX>k)tVYyMri#Ua}iKMVBG8)y(JdL!Cq_LHt>en9g zJLC8_(6(eKeika*eiM1=GG4ljmo5{hGwq+Wkv6!0mOv#boh@?OwPF4LxRY9)m|BgS zi}sgTX6X&iS)%f_oN^I$MI`Em4W-#=(j%-Bm3q^!MYB|gcC=y{VeD`NMdFA`g6E|n%(D6y61Q)!ah4y0ch z%Za%O=X2Lf&{;-wCP8zSu7+xl5%1BtROb_ebA@8vIkT3xemSp zzLHAMwT#mKAm&NFB94nHD@I|Lqmm_eHcB@q))j3ux_Ozf$?|@(|0%bXu?11KbR9Y( zTo%d0M+xLCQo2CVT9Ixhnic6`xgrBBS45kucmswkJ!~xHM69K{)KX5CY?`Dc?ugKQ zT-ub@sVc6l77!E{Z6M&H$kir#mdF}{G(_((?5xPsCYtnpJ>Kj=Aic=(CR!^pd@eVO z8kn-p!+~>*Br7u4L~BLr306n3%Z(r_a+8VHimV}69mO6nf~?4sCR!`9-Eu|Voo{Lm z5|!^JZj&n3)>L4vNI!xVxb}1fQIVa$ip#I%1jR+IV|8+6Q_L2%zSKEiq}?}~$8{rt z(PIRp#zyBrZnDukAe(G-C*%_oo!A9e`6(Yi&Dn=JQXh%Mz=A}ShP#gx^Q z@T|CmXNc{}r+l6x$TLGts($(-iIwh3%tw z#nQ1S+xdPliYaRP=EEWay+K6#@_5%#lGYQHm#9?Q2My(A4IRsRH*_iM-7L;xLR+5L zHUzz!#1p=R(2lnlWsWJvazcACn@Da{4-;zzfy-c#=5J{nfk#Kx7dDL!|5v1aV_qZR ztcbn~QQRfOecLLyTGW0tc>-xf^nHoqG-ksZxGLiW=tM$0J%3(SQ8hp#S3Qg-F(ZaG zRvlTcvp*Ke^#t!B?o{A{V%G7%;f9qJ8BHkm!YS~mxKbJ?6G9z|hg7C%rOdi5v5i}N_Q!t(6ct4o~gHv{momy;&*^d2Whu?*Qw#^l1NSWa{`%(JVLNu zDE6Wih;%m{phjeX?F%BOSgy!;f=#Jd-U>u&O*AVq$#O*=w%kZmJw_roYE{XiaDkEgN?d0Ye^Gr;2*<-5+C(tc=t%crW*&_GFY@2HH($m6WC1bSBR(rY*)}S^Pkg%T1-5PhfNukyy&*B6XH4qC8EFo@>o%TeM>hFDD`!)?vl0a`FULx?h-6 zNM1zJVt=dPOd#OznFahU%=jCNgGXe;v4!&ogcVwJ)TXejKMRqT9TT?M{Nb75^I?CT zlzwWgW<_?IXpP86mMfyH)sTbj5~c%thMfx2zZZ5WjHu(qtj5Z&=Ag-nR1oA?wpp=b ztUzRFB5-y2+`mdW#HMt*uc7-sfy-l&9R#{{zlsaHvd^ATtrqD+5dZqidlxP}D?F%A zuNAz^;n#{k{rV-?-fdN_C_H{vsBM>DJu7@G(s|G5vBO&*BD*}?7rev6gTWb2TTcI2 zBHwuOQDA*r$;o@Rz-rp=o}62R!m($Eol47B6vm$&4)4>%>^_GP-&J0j7`1TQPo80%Z2%Cu?o0h7WDN=kdJD6Bju{HC-YbaMD?$?poa zQ^KQ4{#LkBWLM!AQ^KEj?$V>U1njn7F)OSX)1#D)=g3&qSQ6Nb*MNciS_cD=3qy?j zBqFzgRUoH-TjABIVNbKRUx~D>-Z`kvAWMBSyOclqyS!(y3tD+^)RC)FwHDrC>G$=p zsdNuZKGws?3!A5f9U=+l77Ky}9+rHWhh=!Rhv(t=^&b@NzVedRAeEyQO0K&^7kFlN%+%FS+yhkO}mqaYD zG}w&%ZE!yrZm7*1m&&EDFN`>SWzgNjl52g6FOPa1pE9JN6)V2NQV&b6RYkshwTC6w zG9zF9%n2!$T>h-YC0cl{auP9dbP(; zm96oxJl2Xpmq7BZ9+q5-0)6=o4@tS>Le=h08t%DcoWWw&Kcp1EL3G+hRsaKZHI0je>yF8q+m+;2E8y7zHEa$Wm%ovaJ9$RQLUzew&Qnu7)w!m6Fpl0Vk2L^ z%)^pvZIds*$HT}Y^N|*((04E8(z-JzKWZ=XZJu0pG;2(%FTCZ-6c7DYdLEMLlO`^M zk>66F;>Hv<%nvIfm1gqTR9D8Y9+%?N_L6p&Czt-j(^CD~z3AWL$)#U;Mxq}DQ}>df zU#ehw)TT3&1O`9jmHs@^3-`jX4svC%!;{w|7k2WCi}Ksgo~lM?(+qx4xOgF5Xl0R} zRm*y6rr;jFVK4exxP?3XtY2$9tcur4E+dZRzfG|nT=X3mU*Q!G%fNOIn}T~-a;;PI z(`%)fj~kQGvn*I!RDj5qSSx@01XUhZ23m3C%Wv|qP%WbkBgMH8}YN$o~SqCzh+kjT2M3 z9MU^>r@sRICE!mz{kdl&SNUBH=q0j&l!(jXU?ErwFI)-rLf6TEh5UD5-$Bh1a&kG8 zVNR06a!7NO9F~0O>|9*Ms}SXDBu`U(8>#kKfy!ya~BnQ{psX#a2f9c z9aeh17j#(iUgxJ+a=lRX<uyL)(R3w^|e))(^t_BjMY z62&lh1MENX-c^M8#&PTPX})@T*A}>63#>X_?iEy6k1-(p%Gmc4@r!em2=1dMKgDv2nbWib1;D2`GO-?L-8|)kW0Q_~1x$3d}bMS|K znSB%Ec6holW6#}kXn*j{Jn|S~XJ%(26w3iK=R?Op-@2!4YnmrY8qE6%rI)bQb#_AunY2jETM(J|f) zKIk~A3=d_neH$F$`FMj2fDZz{z{B26F+K`>C{LB9$M|G0cPZxAk;h~?@Qe<;bAuPD zN+!X$o@XZ6IKhSBd&xlKrZV^;cs(W18Bq8}@VRtIeKAXYpa8yx3p|ahlCKAE_iFS% zzb5(!MA$24LRLO6X<1@()R$n7j_+af!7aw z<-Yb}LIoTI_8k}n?$4>UQCEC2a1M;)7+2j<@O>Ge*RE6s7&x9LsG>xwflfTCjF1oH zs8N$C{Z-(uy5NhO=q7M24yy?zzZ<;ddufwA2tI+wTvg<66rP1~BUMN~2EPG*kGDY1 zz~8~{6=g>Zehk)YKh*igW9#4_;L9qRzYwQy#nY$W9ELg(r~vzcKWKvkauD1L{2n-( z6*Kz7xS1Ll5traZ@Dy%S%yCPG6TrW&VdiHnpA4p@dg(QmI_*qw2`>b;Dns-afq%>e zpR3VT;7&NyOL82z6MW&mTyeUAVk3;tTJdH!R(K5j_Wm43vB9Un*U}_c#PUCa{Wg8G z1^yWPAp=b%`Wo221TXNKupMo8?NqKfork?)=sQeuNF_QFtWlE!n>HT`ew$9G=i@42 z4xDQjV@fmy{1dN}HVE&-G!*G0*N1$4hgX6R)Baq2V}p0V@Y{3)_%iwg#ANs@B7dQV zblAz@GZF+rFa7ICr~DJx&)_ZaLmioRN(rT}@Axu*NL|d}FTl~|UK@4eQ@-~y^ujk8 z4gmWGM}Wt8WBZxlrZRU_v<~XP50T!DBlEz&pvI1f?JWf#z)(Cgc3@=(j=zIiv+7)( z3J(h?Ou@s&vB!6V*HeX4;{@x#mw6691x}BOR>7aa?Du_9eRyt@;MTz~ur7KsB+y8ACivf}fw8fH8Q>B|N_#S)*Mt2U`w=+u z99{?ZoAA*H#&Mhs?uiX{+dl}}#1}W}WX~Y)#6WR)EPoGtBFF7r!qnKuU_ZlF`!W>s z=5Twg-x;jqd{$h;J;5i^NnI01gJJxdxe=}eW5B*aeNFjfo_D%)!CdfC+8q04;Hd{+ z$;rkHG&sBr{FIl$txC_G>@YO}@(tkkxFS`49F|e=7>o}o;XU#Yg+G9O2i^itVJvs! z#7ELEw>JT*f!*LS3|!bZ$N9c^veRqAqrjJOm@Y*w{S&}?0%e;tDhp15ac?|O$bmD# zACF^lTkOy@@U3*h`q;pE;MyapLLPfae+k%k_!_X^iEjb>1J_;PajrlS9zCE0^wRlp z29JXmF%Xfz8Hj!ho-x{vWXkZ*;1|3qejof9O{f}>yu1^)HKZRMr{5nuV^k{d13nk5 zJ`gFv5Ew5E=6oEN_+;=x4wH?s!PCJ@#&Ei%&ZK`1_;PO?m=AschurD-hu{mzU{{>} z2C&~}?gIbF9u<*kv&UepucDX634RCmtMsoe@cZC}o&%q?kT+5z%eg@5hdmv(9n^W^ zpRRy=mGZa)iF@LKoi{)r$0JE;SJ8u z3)H4m$tdvU{h9b4E1U(MLK}_+tCP+GkEu*g$D=s^^Gj|_8j$-L{t(>Tooujw1NfKR zO^+av3J~1|J;&w~97UIVuw12guM!GD1d;u>&yoWYkZ z^xJWPb9LIuqhLQ6|IUrWV{w8W;2aLQD((e7+AG0P;CoLagZL;I4)z_&gPG;ri~kJW zAMcseLViAYU~=x@{{IpfvoBzK6cVU}KL#H#2#4Yf?ggipM}@KCORMxd{e^5@`> zd92wOr~f^8mv;g3KKNA5re>hReru}g1qw7=`a1u2g)yTly{POD{=gf%PXKq~NpttO z*Pa39SFV4Z0zUf){)_^ct7I}bAMB5eOThjW(+cnh^da5InDhT_Fn;Lu@<+k`ar`vc zui{r*;7`EUcFy2@_O(!X(tL6 zgZuYp(G4Y16Rrd|dn4oREz&;#UTM;E{HqNghf#YdQ_bTxe+K-i*M@I_@AOU{pMZCJ z@(j<&{oCy>VE_3+4{%pr_#6@29{|3YJ~P>!|A)bN!)x<1!Tzn%Ip8zADqR5n(8Je& zfA8Uc1N#>=8^N7AruTkZz##>WvT>FD3C3|pv!7Mm$+m<22L>M~0pox>O1=QUF*H59 z?R#Kx6IO!1@@nX0@Iy3FHm-pzcuJ38pXBs76~>Isx2_C-Tv|EkxS(No%B#_%^KoyVSh`m|HC9&)3(S7a@ z`;_U?6LX`-E3PNe%(q^2e|R`^#qYd7?Ab^P;|#9t%9Ey-ca=RMVVlI zAzU9GQaXB5;qdig-|)AaGQp}sEv&Na%bDPmD+@nZANJ|6=A1CtKA0DdwDdm;53COl b44Zx&28#=SM6>%xyfSzniTlw!=J$U9WR|vM delta 96708 zcmbrn30PER8$bL!XNF-|1_wkLa2pmC0bv9b#0^nLR8mk&OH)fTG#A{LmeDk|UCcUG zmcC_HmYFM+npU>?rfIunWh=H%0K@y{`Wk-JbuV>&{zbd)+Rj zyHkZ#xLLD8N+6WsydP6R?*&8 z=LWu`PQTA3NBZ_Rwn!dvZrSz6ev-K&IngVhIrft!JLG{7|NI)~i_U{xf2tW#Rbuh~ zueK?0vZ*QXcOyOotrJBPTv)mpNL{QbWy%yiR|A`Wrc>P_e z-Wb2sT!&^>`uH3u*F~2Fuz#yzk-^dtpwLYx!adL zYRcVM>`a7B$o26x+yud`b=gUm1hIeU`EBm0L&pu-b)oIyT^HJ)p}Sod+-{g!`=1)^ z@I60AMcS7w`#Dk!_<4xs=(3{1h~*=SM-@gU{inuyX4vu&fBy@xk^FUyr}E_*;T-CH zxaj(mFV|Sb%Qc#3K;g?ZHo>c1`1ld75Eug-rLInOjZxQFF|2Sy(SVaVi|6ew8oKL( z@Lb(qq(?8aoEFJB71@imoia(PjD1?4TrP8xCnZ$N^xID|DXcz&f5ys@HP(o`iU#0%;bhF3gk>YnH_a1C&msp& z!xEOgRh>9&_XXkJ^}mOF+MiN9fgX}wG2+}qb6v}xIh3$0JIP)CqS2fdk-p<3^YC!d zb0=VBY1yEsPlObQ_`6?dofLw3BE&!9Yz+)=-dHUT<=ce2Bt*E!qKHUYxQ7QTl`@;j7!KwAr1F3K9ft59a4tk$n?E7SXQt-Iap-Z{eGJ+RVE1HnQq!Me4C; zT9^|5vsQ0xD_s%agSYQw3pnbiC$^Ju+K07zK|7hCy;-YY)lQ~pyK41Y+R097k3-OR zu42c_e~K2`2}brs4I?N_Mr;_K>0ZO|UA6jq&@Z^9cA1wNSM11!?0zK+$z|zYnKVR& zaFepwXNOS_Eh+3~20OP_cej_rhn%fR@}_&60^ipxDbJtu-?$M!TS`_WiDbLAg~p*+Z_;vpUFLa=Ly~2N@rmkG3#E zh)f!yLfCgf-_SvBnDFUKw&J>KTk!>y0LuSR{;sYVJa>_>FGaZ>Han055bITOjTHo!KU1h%hjaznaalS^R z{&j*K;3xJhydO!wYf6DpX*ps`GhI?TcD!lH+& zt;sS8d{4Sp^C#(#CduS}PN@0LEkW1N{H2YPZ?Wu@$yBEpyAr#(^fxq7YO3lW+OXHF zCncY%W@{De4M{QwIqQ}z`&gyFs!5-lEHgp)PqNIz$Ejr53-l>Xx+_Jdg3v!j(UIRbiR9p!b}GmZM5jxsy*zDAMy z>dD8@+rO|`KW++~ZkX+tqN;kVSNi{G_?WeSF3HO-B>jsU_1I4GBbfN9lkBej)u6jO z%S`R_2EDYiOo@KGL8QKZa!=j)bFz2uibH6YJ37l`ZF_^ht+VVDxf<-BPg;UJe}cisA$BrF$io>-RrhUz*uq{?BeYpQI6 zD2}DdEbY&Fy)ji5Y46wTMO|b8$hUTpliT^~tr)2%QL|7XJ$jwr?_XYMZwmBp_ymD9 zbU_!KP_L(?$%PWlmnP%G#?_{JUshfYrpb0`TD{GfwsPHG?Zt|NT*3R+8to}2sR4g0 zlk$6=ZcUdJ@Vg*g_DOySQ+c?5Mp{yYg-!!JCqi2OzB)YuT2O0xUq0bijKU!vebgVbt+YmU|G{S!y zyz{7KeFf3Hp+G8P6t zQr$auMv1U}R+WXY`P$Ds4$N&Ap|@0se* zjz1&zo*tR!i#qXIsP<84vGnh%c>+)fpzSr20a*b(Q)9!9Y#?T+kto-p%-h@YiW!Sz z{nFa*L^LGy8hgsD#jX9Ct<9l<{tBz3II1`k&2e{)8&mLxdS2sdGqD$Q{Am;E6-@!H zmMu*`OKQIHRj{X?YcN-1e)8;W18i~)a^5}Fn}2YzyD2cE zp4VS4#Nyhi-jWIRO#Esoh^#bRJSM={%%dY<~IH9 zcCQfr+Z$rt!vAQUPr|^S2ALdI{A7jncdI#GosK!yi^9N0;d2VgZykia8`kCpfV=+W zA2Ge;ju+3AHw1pdL|KGv_iVuOJFOw`jfr<_2=Pt=e#*qVG}yeGfuA(-#D;F(P_M_^ z;0v^ESmEu0xws(^*Kjqik(h}a0%5qKAxj$qT75$x;leWSo!(N&HDKoM=@o0C8fdB) zk4mo#&|h`b`J=8O5OSf&I}EeRr!|H~H_(5nrv^Rz*sSrX()gs#*AV!%M*3&f9Q#Sg zp5A;2eN@jd-cYQBVw z^gmEz^S1C7dWV2J1oXW%2~U3blYqAUf=Egz9flfRXb8mCZC>#uLTCu&LFmbvXj2Hw zT2eG*{;EMH>Uw(5tYFPMLZ-6DZpwTQ89QXoK*q1{&XHMdg#XK?$7;enBT8EOEiJH| zBwL?x9ZH@f{F!<~j_fW+>N&Zxn|w^aAy-b8%k_7OjnwOMWtV8q?`-@RQMm0otatA& z`)MCu&=+=>soJX-^v&I6iQKLK)?Idpu4-b(7XIBA4q}hn6!=YV*F$!eL-avCWC!1c zhPmi<=NsnW`nS6J8!7<*rmjCX%m!SouHQGz0{o4-e$_A&@E7X(S;Gv#AFJyJ*t-k= z`|A2$!*sy!s_R<~(*VDru7?}S0pmso*H@AoZp25Gy6$Pnt{yUU)Z!I>X&Hra7}=0k z-55x3&~16LpvB}`>^J=jYDMrCjsL#Tvv?h3 z;*`vh7kU)mT`dv9n7V^MYVO)<+0o%cVxOvL47}3F)C&K4Y-5@N+iSZPFRZqexbI%( zcM1;X8MVoGe_^?~?W&gB zXyj)Yc?D+gY&N?Nl%1gLIpH&9eh1|l)k7BT2s(cVw8w+{Lj8?i@@gxVfEwN1TegpC z3XH2!XCZac{b#ja(ObsqlX^=VLsEVaB5mY9G$L4A_k z))?5;^gA{T52Fo2_fFawI!tb}qK!7VCAI)tni>PI*6Mru$RyiZz}sr|(|u$oZE2Hk z?JFmB9MTl)x7cD2xsyLjPV-9W?Q=7}#z1dy++zBProayU&c3pZt4q_jq2oTTQDP&` zMNBfp+BfM3`eIf>75ZU6C~Ni1esW-&*BcL3+mg1;`=VMq`d!$ryZ1f%;<7z!!@fJJ z9ntUYC;P=b*vJ*$vhBRu($rKxF-QNZA8y`q>ve0P9IxGYLBGCGeiF}aC5O3iD^M}m zfX5oJUe;f(i2v8n{kQ&dUSz9ACqE8V`EU}g2N`ap-8nM%* zFh!{gG&D^yDTOBGT+?+XrKd^xrD>v~a2ZEb0}#r$P2)|Wj;7G5rfW<}dy{gaX^cr} zX;R*9x_X#MstY(8^}lex?W=3xI*wC8$>q5|@S&>gm%!@+PhuY{!s&7(HXWr{isl44RmX)I6_?zoIzaI7)^$q#+l<JG27>7+;TC$!EQOy%WRE<#K9(R z{pteuHyWR*A1gC;*mSlr9UZM_p5o0sy`fAcR_p%3vQ+kCxG&N}_q66p$)N~$jK zweGk=&h*`;qGGP<0*mYKRHlp;np3~VG`z3YNJx489VTVFNtsx`!lZ05DOc4mGbxXn zlq>3QGb!t8jZ_S*zgbb>^#-$vdetv6g>Ey|vg;R`lm#ZGOZ|M4GQ*^}>*tu1$tET4 zlC~OGYqXW4UY{^rx)O>_d|>VL;hJ~%zzFXbs%Q7E)z=P}?OmC*2hY~rKiag|xmF~N z!<4bNPJe5-O!GN_4@YkZ#U~Rq!oO^QF|I@{^KNvt&v8c~A~?!ARU6ztF3@Vxu*ZuM zPK%`eu<#>x+O*Jjm?44N=cIhlPhYrbXCLfn%8ph|s?cYTkRhJuK(;7y;75^^4yD7U zu~gI8E0-8qkIpheuC%%F2t%yYGfU<4uxVHorl8Ew|5J*ivuXO5r7}xSt8$ddJ3{nF zu9Bg$jAb-+(PQ;zKV`|l|iSoGJk%NPUUa$5gy>nOD;^jAoou3OedOAVabUY#(hG4QeCYzX!JZ|081z;VSpe`-_p zwrN94h7J212hfyyU7tKnc5e5AV*hl?r&OPY>g4I0pgI7moAsxs$v(Kl_+gq%cidFB z%$rmGdB|xvyg_d_T_!t5(bMz|p&ufwEA%U-%g*sV>o)&l7cUm=I~7(foLZp}MMcZ3 zMMYEed#B4pRC&jA*{!<;x3|gVkH~)id-??&;MEo){PU-d{n!{dUwatvr>EWq?8lBT zx%^S-``>y<{iL_L32Az1j(*=wau!ZK8g7!);tFeTDi8I_^p+cvxqr5P{cP+}uF-eQmOaBi1Zl-=MgD6x4m2n0aTVwq!}P%wIHUVr zzqvvV(2m#Zhb!c0?aBJ8)^lVhDR0#K%$4`r->N%|%~rcP`Ui7mLHweo+Q9A$wSkj$ z6@&TwObF~#(CI3wI?j`yhUg(n zxOaip6WC|h&f(*}B<=8`s_9lO%qqS5;To-N)mpoDwUndvpTo499owRX2!HcWJRNnr z2I_OewMCAF2_SvZ!XiYeOV`hbYd^_{s?J1cpN2|r)k`h41ys&#)vTONV+C) zBn`Do?+WSNB<-KmLWn-Dar(Tj+RIvvwJI}HTPp$RhqJUjg;z?7|-6(Nbv{7Asj zqXvx@Qdlf8pl?qFJt$OlBZY=JAmn@ztpTAS_y~RF3eYvX^+ALYW3_ApW=~p$YfI}r zxWj%JFKY&ZvGfxxz7%_xBOR5NCAm0KCe-wa4#M#51w4h3^QkV^U zYCVX;HIeYP-H@^h%bOuUo}-H8A%Z(@CO8?59MReb>G-X%?uy7-L@U?$z>MfdSR_om zNknARqSaMEaRu95-lQNL=?a6OL3buhTr47TZUrG0RZ78USUfKGqNrHm=>$BbMC92J zhN}k}F`}mt?>G#Mhyvxw=enAVUPSD!tz`5j9O+7ip@=?&ovu$AWnaRvt`(?kL_fkV z*CtqwC?wq0)t|ck3A;s`au~JCh@oD(E<_j+!w90C@fT4-cv;);V96IToKXweb~ocF zBVv^zYzaJG1u0dP4x&v4=xb%fwd-l{8iq50APh2`iF9jqjiaOM9s%9%VgwP_v+8S* z9-0coOq>DbPpLf6^&ckmb1Ia$ zIF&_wQHg*sm3098RSMjXc3n-GZ==vAV_iQ$E8=^OiSaHZR7Cth-6^6yKPcWoU0ACQ z*TGu{(viUjcp*2 zjymcTDIKSy9QGpyXleS|JS{%8UxX03j$FhSF+>UEJ6h4sFs&4v-j0V_0~xL@(oaI# z$B|gRDq6m>>_8eW{23=ME1~#TQv5{VwrdsW4Kkj z3K(80s6{O!mTNac@U)irC~d6L9H`S7EpaljHQGGze${+P%#BEbChbRIFNAPQE4!OY zrw;UzbSl(L=PV_;1lRT(5f(ehC6Xis6aOS-sKt(RQ3ihAwhzQGVMqTHEHz9t1DA-^ zoK>P;Wv)BO)A&gG8IeUsB+DZ39coy1ltp?*Ph^r!W`|K$v!#^=k|x1&R75|yg3?1( zV=7oUs+dU}Ab??Wj9|8k75-~x$SO2)D)~RSXOpSH?&N^JLvDcP67E)lcLMj}0vl*u-WU<3f z7dL2I;BJ{?5@VdI?a})bpn6o@;%LXlo2I0ncSy!CT_JlM43OVAq zm%eAJ{`8&*V++&1s$RT-?+N0e27V-n$B77k#9ZxcIOZ+K!;EJE5!C-1A`3OVQ6UzK zFb;i!%4j5xGe~3xJ0ZU#Fkc4I&#=_ zxQ2roltDmRS~+SuvUdmj*i1zpk82oPegy!t{X!pSPD3r!57i0VEot~Lm-EPi*Ytk3 zSlar6_@FPK>)g*hfb(rE@>t$Sff8B#8m@7Xj>48;xjME)4vM~nkZ?6(BjFfC*yKOVX^6jTF~AgzqkeZmR1(aGm!O&TtJP{eHq8*Y}LSl5noecaBCM zI169-t_TV}coi7EUEL|9vo3|`wzp&Sb{q;u2VOwf2-_{K{eZNz?gG=YiMkIPrx(Li9kwR@e2U4>mi_z3>)2l#EDM3Mv?V1!1Ra7KKU)$GS#R zW)xwU>uJJQ5pF9i2Z&rf6SmFlMlbB9H}%!7X!#9jwr=PfLB_*3>J$5E$-e%e*>1!o zZgljP668`PJ$fraBk9r4FnX)2HACJu67&?;b%dWk2$575H~i5ryaN~;{w%;RGKU$i zHVkGLVUMdFYqIx7Xyv+AkzPeO-}R&qNsoS+E!kVOWc2>thy}L^=s?j2=K}8QV#7oq zqM<_9Y9u%MHNpd3>j=L=xY)IkM&Be{;z}U>ZNjB!lkJ#cTUt4rTJ|!B?=E6x+s5=e z%*y)M#xZ82JO@sU+09=f-R$Nykc=_AIRlGPxp%t0q`b;~tm`!8uU2g$EKO7xKN(ju z-7%}eFiM?oLr6F$f$nyGifJUp>01sY(V2#8lJh)B$8a|0}`|0zhK*F zA+9jyv7`7@jTEzqpwUP%|6z5kuFr9ed6JFfc3n^1r`Sj-uI~sx{SM$xt`LU(EM-z% zzKM+cISOUC7EpORg)&u(#q3}!c~pzV>@-@BLoa4G8!X?&uwwSc!gNnp7sMO$GT{Q% zU@-^S0KJj=wiu3HociuuOFLi7!C!!5=fG{L@@)Txt#$=P;%u?y zL-3ifSj0}-1)CyaiHMy}NK05MVs9dZd#Gz+A$CR*B%v|uW_(g(Hn~cpf{@afLkJpE zArm`ybPOiWIA`qqDxe9AMC^iNN(IUb30diG5g|L>EhZExEWc2B$tqmo?&d%6>FR=H z#on@u+O7_m(_?QXtR*bL%MY=)5r)&(DCBz`@^LA#%lkphHN%IShS=L#N#T079pDuV z-{xwW2zVvqigf*tdUw!ITi2iM0k7Hx@g!jxNKdP4!LXM(glLsG7OA#pg4#Oq1ai{p ze`s#modY1mG8@mNJ8imz0IG=dManTBGLr7O5FN|TVAMulO(&YFjl701vVq#jafEHI zgK>}_PkFoRK?EqTB^)j+Idn1McG&FHli);}53%r##kkgT@-4AJXH%%)6Rs4*FK;ls z?W4w2<;`_9DkE<+ys^j1a>91kbb3?WA>5^-mQra_y&`8I*Uru7H0z zlg?s{NM{j_6_(==^2ynMFw~EzP{H6rEPRo&(@*p=#~|=c%g+57!aSM`vGA43&fVy5 zzL8wMgPA(BVu6s0*sh)GsJ)m+4IviXOSn5-$v~I#fFi`QiuOOCxur$Cp%1aFCgn+r z+-!*OUCmA}(}79gOPihZC~@nTDg?gi+2s>VeX?B2w8vCA_ENCr#_w?tm_C38 ziX?X$T4iba%M=Q%F$hAne=p(BQ?8QWV{1D*)JJv z>IC_6pvd?Z>@Hxx7t}5lnf0J`2MyLtacw^0$=bt6R;~vq;)Oi}m6jV1;qKmp_o{_B zhrZNJb)uG%Z8H`nV-^Ja!&DdCaKW7HCNfrmbOlI721#20Mj088n2bpVBP5dV#e!!E z7n;a;!Q|fdZ?5!-jKe1T(aYE>2OpTss>_(NP-K4v-dKc_{TG1A05WO;Aa3!kA#Da& zC^8}w42D2WQ5gh?mvkARFI<4#18i2TT{GK=Uxm;c%q3vvnoJ8{?iCpmOr6rpbP!p_ z6jSBKpvrejWgo~ZVQGaTmvK<~gd5E*dy9;;Hbx8^4V{b0EioA{U*<>!H`Qc*d>NDZ z`2f7NaF=-+z(xS5u(kx(kvm3PjFBMCq0bk>ljh?7aouAEOJM8-qjSzQtbOo1o-&gi~^klM_we zW(Z=L6VkUa0%i=!JX5lJZ{#AQttqjw2XDMjqO?)B;CU-Bx3DH9Yu>=syBbg3_D0o$EC95&!cCl7}W*cpSv zVO!22XvU((zNr8l<8XN&MFk5_>U7waSB&~Nc{*(CX#_kDJ=0cTxZ>fktruatlZV5$ z-h?Ba$#m6+u+z!IVOw9qvCb7X!2JljoID)16%zKfb@r!ne?DDQIeaM<<+tKQbh!(rQ-dy!zblZV5$x4#CQ;^g75 z?Wo0uy8*m@0{Fk}0B87Ocsgu5PNN>ci0ysGmJfKYu$`cT-cFtl+dfQ&LZQ>m=K3fH z@PHT|4%`J}tnoY?HW7O~4~I=8GQQ47r6Q%|j4y|M+W>6_Y8V^efl6M*@x(ib4Az!|lN-+i zW7`nL$&crOv2B>P4xHZcJTSHm*ElQ-<6mb8Bb3;{_?6(>N)@L#o@dCmGHnBBzLIzz zBHKnQxzhLxRJu}CXmmUek!_2$p^zJ!z@BWoMPu(RmI-$;)LS)n&k~uyLuA`>?O6z( z))F42jaAwRM0Q3?;32YYjkXs&^kKV|y*7A;{4DkaAhBDjte*n!lB_FqtC4lKklnf; z*VbQw!j5!_BuT;cVZ$nG>|hsVpdAK+ni$!8)L_D?wj!`4&B-U6hsd@LvOOx_MjayC zlJUX-8d%MF9ThC%doeei0#P?&vO;qh$9DgOnCTW|XUm8CJ-*v;hqpgLjvGF{3wq37r zK$OSx;Mq1=Ar*TrCZFJkO$S3luEkc@}M3s1<;*SU51z_yl34)J`~_749tTC&TX5+C#{_0LtMH*(`t)Cm@oDL3V(Sv+#5a02Ox&5yCB6VhkdQ@RF?f z8-x5%5poatFCemr!5~M7j-hf8{6-dipr09~we?xL5F7kF#duN^Swc67JgJGi;sby! zY>x5-+>FMc1*iQ6?;>W2a7-tp#Vi$$n+TaFHI5m78yd4pOpV#i8WqhNb4(4M)c728 zJ3_RD(=mSyRTc@y0wz25J0^Q6YHWDIp}j++nT)5((>$1TdClP5Kf zTMd^y+i=`wI^{`?!}kF7QXI>jK5Sr}Gtd%_+gVBB}8&Nom)IhC;8`8gfj zNI1+nkhwfo6PyndUP8Eya|pH;aw*}q&L%3~Ot_s0X@f?LPDGs|<$d@< zvT$xeL&*Ed70#F05Npc;YR-IGs3hI$oP$P}>wIL`oO7x0z;%G_&QdbglO8TY9)!8* zQg9>XHcyh4d#3%kQ#cPg2J2e2JCWLO9G>MVY4t zVM2nN=r_S}%jdeIlNlbiQ_A$PgRpd}W4WD#O>esiTb$Q0-aUj(&-)C|6PWjxNVgm9 z_X^=K=SPg_0O4?FwvP??8j%R+Y-Z;T!jaC2q`yhn;jCkF-ueTXh;shPY`#N!g7aQB z=260JjOx5cxUDmV4vrIU=d5NmPcWeNBDx0MH&uTAGi$kqUHOYj)?YYx(!*)q^;n$? zsPQGW?atc?e?>UVIfIG+nsB(&O8ObX5zdwL_6p+0oweoBVea9pHY8L zIMz9mx<3$hIe%#h|MEv7ZJh@>psESGoq4RDQ@TS` zqr?W=XjZIk1YPNAY1QM9JzFsDDZcVihS(j5y_HnAK7eAY@7D3JNsZ zz@VuSCnIrZmJ$ack@B31^${4?MAAHTHdCm*%%jk42vektQC2@u6_SX_B08(=t&q$~ zh{ebE>pC-uFG%Jm#8Qj%tW=f0S0r;4VmS@~J{B@h#Xve4j;@K*t(Cl3nLiB>SK}{tS`N z6%rZ$D(m@$LY(m*uw$H#Wzn#IhbCc2=jx(;ZGs zPazh5aV(8TG_q@p-2C7PkT0DFBywET+FX3$2j263}#*%NYrPK526S40w*C zHsqwi5`!oZo*I+X*C1*3Y?1wVcb~8)B8#3^5yTTvm|$>2Ec}9&@EkG83xedmihR^0 z-xDMsQ{)pS`N<%e-|P~ePfYSFK{CJWB|N7|_QB`LAe~<3X(@Da(hL__&*+`V~D{@iYfj> zkj!tn2~V0yt`Cy=#W&&cnBc0$_jK zYw`w)?DrH8_4j;hGCwewnmtuy`%TU4MicPFnw`BSD1~$7B+zI-I~%|ou%A5zz;OVc z1Pt*{axm3nG$S#1s*>Xd=|Cris!@`j8qfXTpeT=9*gY6Fa^sDV&JAGO2`WeQj~LP2 zi@@gC5b5hUe|3ub6<jc2yA=cnZ_Mt2gt{jR5$P5t&r}`{r_Pro#*Lth9flx-v?7E z+Ksg!vw~sFc2vR}9;Ib2B3fahW3#5iyqx101ny?m`!`m_z`qBcxr2+wTotBPS=MzS zY~KahzhK3e$(s*(hl6gk%1N2L|7b?bGu2vlhvPcsczh=BNaQNV8xRh$@axE#ljv)e zV<`l%Qj)TrwO_5G(JDuI?t!;jr0h7np(DaaH$1DUEJw9r!UqlJv2t`b7CMX2W)GTgBhVjp?%@Cl!CBj+N|X`mdIRv@q! zV&U%ui0m^UBSRwlXOr)#0Wi7?7DGc&vo98&M$ot<`}$r&v|?OxIw><~m@_;skm#h` zAca`?0|X+wEy!(94^J9^P5{;f`TSu5Ov@m51DU%-6Q##TaruuLoOx7b&@d7pQ&64{C2!fQN9{V=K5< z!Cx?hqk8UFFolJ2=&XzMp#FuxeRAV#(9Y61gw{tg&Dof~jL!66BzeuFB8blL^oDk7 z2WW%Mro0tb^vxNK!pH{l=VUm;T?XFf;B&HFG&9!;|H!Y-_UZ=k1u z8-u`aTmu<^S_}!WZ>!n*(rsZrANR^*&8b8Mu>Nfvgzz(_&YMdXVJA+rFglpl{98Gh zZMake3M(O$yMf8y5J9*b6#A(-c|*iqz-1ZKIk4?k&e-{!tYlKN5hrMJBLmBA>%&k7 zi_btt(rw|NY_q!Xt(5rzBK;?`XV!(YQH$o!tU!Y*Smd8zPyRqj+B1ZGi?Zs+^qo7O z{osReR$v~C=AJSn$=go+3Woln;`_cKLG85-LK}2J)g3-o{40TG7Bc=%6fUpnG8v;! zo(ew?Yg%P-7ZuZ~a2wVEt#Y7eC_?F7fET5~=E|0>CQFRzTfo=^q1}qXhwB_OzNM7X zZbsj^3j(bn@ZmoM41Q&?$k_n?U|8mWyICn$7E^aAs%f{D;i{%@24WsgDx4-2E=B%9 zw*M}bvS-rqbB9LzGpgLp7;#{!oT1J}4h?)ean;Pz>R9}HLE?v^F7S5+G}9z zVzsA;oEk999RoI9OvXY)nm-NwTULgv2ZF^$DCiTMQ;bL|RU~b2nrTF0;8zk?k*rgZ z+z;G{WPNiaE6qrvVe21}Y%m$jS#u;lF`zZ_ExV|sq;$ng2B@Lj_%-h8a@C63C7kdZ z^sM#<2L2uJfseCmW`r~KTIODM+^*rAF)fvQe3^?_Lj%_;3$rRIo2j}k4>z-_4cy0m zJqrZY=dx84%gI+0a<0O+1J6`vUEP(wrSd6XmO9Ha@K4EC=UhSlJ-$qJPS!(Z(Nek9 zXWUK(@n?Kp)H!I6aCQD>sodtvx`CZMPdT^%gT3Q9kZ%fqBoi-?a0;A?-0;c1929<| z+nfRuA`tx`(Fxl>aP2s=mgB-(WAycH2U<3`eWL;JJ#{a+gS!Bm1#ECGfDHhA#f5;h z%96n)_&iS5SO5V4Llyv_T{rDc3hlcJc-u&rBB6L4FiYi&zT(Ff@VsyEHUQ6opYsTm zj6PQ;`>+q>qTf*#(IVdaJK`7z)yjt%pBx|l00Vv=#BZV8cQb&l*t>ek9{dup@xTVZ z0f4VV7rzgH@qU5N56Iz>RULu90Tf`%o#TS>OZ}VOZ4teD`XV^aeOuwRoAmL3z%vvy zt{wXo4exhhTzE!;$d%(nkoXjc*MP`%yutW)T6P|Ub1}%*LzgWoL0|B)d9RQ#fqay&+V)PyW zb?5g10IpoRVI-vT9^ZN?JfDHA_Fpdq>FX8!ThN)E*9|f!i=1 z&R)kuw=%(ayXSx!!#=c!F@}$aattp-+Zbcmz}Ex!<=(>;=y>QLsO|zGQ%x@?LaB_c zZq^{q4ks1+L$K8_HPCvXS>Ms|2ceucJL1lz>sW06)&qGl8O(7UQn7a4S_}a*%W@IV z!6KMb-a+_+lOuje26N*AR^TesfOF})u+cn&f#aDD#z-)}R1CaY^^Wk|W(o%kVb#3K zj%S_8iB3^wF5zr7Iq4}_|2ZA9PZ&zCn5;qnQaWyOCjN_a*5oYt7YAEU74SWZQ!4uj zPk1|{a$5~y-zB~~nXJSAvQuJmKK~bIzR5ZFFU~4(m@GRQl1nC&wb7JLQZ&{ZJ>IDJ zOD3y#Gb_k>%QRFPG?XnopPSOt3~AZT6wbjOqq#-Z($5xE>o8{>wGKy!VQP~!o81-r zFHWERles0Ct-5J{&qcUs`gGjMs(xLdRs;h!HbQellWmxBve>KUg~Gfj7{^7&gkR)h zZ@^+0Uw@S2lp%RTv%_(rJ`N1S<2dDAdA#-#k0z|VObDf};bns1QF$?7;b07$wN*Ve zF>E__1G32Qx{qF!m7-9>Mjd8%YBM!rxCJU=M2)i0~exx0> zDeS6b3_DqdeE!2+wGx#i6!G2>(2dcZG4Q#g24@f`?V@oh6dby~KWtkm(+eW~+j33* z!$uLq>YoZ0`FwX#zN;j0fMni;^8VP^oV;t}`0od+#^&T*8@EYIh^xbZqYB>++}NzV zXESz->dkM>?s|EeFL&BH-=zFR#T%7ENuqNIW|hL@U>kGgEvl}3jFnZ6R`p4P&;qIVtVDdQ z{7b2qR=z}dunH^2Nt0nzzC>id0|qPa`3L|H7JgR}+#rjb?@cWxgu87VT9hCm>$p+7 zS|xMz}`h{>;0bt5rg-ML*7e}Nem?9CV}c`PUR$6i$ zB>Stx9A-$!fBv%^1Dl&eFI1r)WH?m@hc~4w;ZEc)W0zWWndsSO(N!UwSzcA5ud`Vy znni8OYD?^ra@B!IMF_`ijZeu6)Ky;7EE}$5xqUHYuL)rU@tC4S{wZcNU5S>W{gx?F zZoUlBbY->xqDE_XRk_nDZ}cpMG!LZjhAdlc0XuvboPUtG$t0pbd3HgNz2YTB3-*c| zMfOoJxVaMfpE99sRS++s0TCP;n=B)UwkqDoRlE;y>Z-G{Uz9*}h7#otGDF<~`0CVs z{%6erH&{9SX_bp|ZihJIxY#on!S!uyl24VrSP0}Rd))gO_CB>TRq1dl^78=6T}t%% zWE|%zQSNAs!-ie-&JO zK%S#Stq`qHuDQcDMCYhVe-BZg;d)-P>!Sao>pR)%S1EfZl8pb9L2l&4W7xY&)jAKU z5&8X@AeRzdmWaWn=G(_IgOyA$JMP{>SWLblltIWPDL?K7n>btm%qH57T?5}eJRSM4_{3myC|w(NNe;mHZXqy{Wk z1J^32WRfOpEXKLz3=j0g=iP+3V7lZHC26d_3o6}wxZ$xcqI2V*X39l=9{FT1y~v(w z9I6?86RcY=ve3Ql*5$CRc6-yHtad>mBEKIetrM43rY+(?WibDN#o9d6T$_{stj!1i zsLfE+=1mnD9wl5-o9~Qh`BdirP#4@}vMw_JBG;&jPo;vaf{QFvCI2oaa#wTEx1eHj z<0}k$7+YYMg&W7;nq%H$#$1ty&D&n37KLgzCwsXWz<_2iw<<2`&tz^g*@K$dm2>}* zYB~5K2a{xe9|p0pIXq)-VQ!4@HmdNvh`<=%kD1|>tAMzMM?)6X_Q}g5G9GYc8Ekn; zK+}zYj1559r2)-AK&-92@3Mf{^^6{Sp9*M7b3pf-0r@UQ^dHmZ#TGPDWCV1`IK)3svBUaSQtz&i`_wpFyeH?g=WW&4|g^drq)$@A(mMV=FevVr-nJGRG`{i_j7%!-X7(X_b!G{ zkMen}*=P2@e7^br=Ckl7Zrx6+_lYH+hxJ$6p3@rZYuw#@rP`Wh zXtbTMW!&g?SIS1C^}xyH29VCcWAPRM*uh;vnF{Pb6ekC!y~Kte z1370UbTRX)^B?oZ1KT@n5`&MsoXT(~8s^ikQBW5pOzv3RXP!~a8ZwhWnh)miOaNC< zU=3Z8{2*NtE5-{Zh-kKFsd(QoPCS z`PP&@a+z$l-!$)Oi?{x0?Z?X`ayo%w-Z!at!hNEI_fz>G8xuik9)dpx(yOe~DF9bc z;2GA5WIk5#5-Y|FDXde@?WV8h0l}6;t~kCogZHA!RW0pSgER~VivI?H<$J^@J^+Vd z?TaA$aoQ(k_zaLdU%>$VKMe$(nKxMHK;o$I#F#e&)c|2cQtYSTet##k`Ksvx!KLdbzj-bqE2yAAM+ro`dNg3W6 zr0nz1=ax7d4_DPqVNNUn!x^?p$^Xoc=P1Ni-o)aLl3q5#|mi-B6>L~dv z0Gd0fn3tQ(`AZoLrb(3WC4mY&cb=l^#MkZy<4eRM8Bq_mB?xg1fUdr0AQ1@(5BS5+ z!1C~)a4C&}K#*135(wVa%h>~2-s&;h%2`yp-F&V+7}}tQSn3zz8Fuy~CfTzY0Oz48 z2A`{eXDeuIoyDa2j3pxHRZ~M5;s3aR$>#{%vP2b@{fWtjC8}Rp@GGS)+Lj${Ed)!{ z__9v;V2PSg_H7)VWS~S1DEq3F5G+ys%Z`A_5>{T;g!Pmq?8dSceE(<#N{f`T&gk$g zQB%wCZE(TTqGMSkx&TXyc4b>2#}d`ItO7<^qK1?O&@EV^Mwd;*2TO~@vRU|Gakd{B z{PJvMz7+dW9jjOxg{$#cmN2N%Zlk!z99>MSY2;W=?Eu#{4|0k3CNoY33t7R zYRI<~66u;rXK%~C5Q`G+X-9wOe$C@Mf+zQ>%#7?BazB_G`UStid@E$SG=(Y-UEKjk zB9-}+NlNsdX3=MwMUz5k`e`M~W|Hq(Y1PwL*vDfG%8kkB#$D7S%Xh7S$B1_!+eMw} zDFVJ#0$jbp^scoFg!722GrptNEZ|oXS4T5PX+X>)ZX94*Ytck}PL}q7eta!{bZa-@ z47>*{Dk3n7oJ`Ia)A_&sE4=t2?Jn9{9d z4_RhgDDo1LC3y1=6>oMaPQ13_2<@U@x7`jJ5wpg_Qs1haE-U~V5N&X z2A`=kYZ%NfO3t>PhlEx+KQFbn-n33@@5_LeYJ$`d3S6m7{n{&N>g#4xS1MB}$w5-y`xvswvn6~(I8rBbkvVu0S=OM7K3x%r9AH$n9R_;AWH;svP?)m5QJ`e1 zFuhiCMQ>pGfd{mH@I$nQZ>xk4nYUDisAx1^FjTKA#6F{yy-1_%V&3z=LRVZq#j#LS~ro`3A86$ z;(*a0akHM630fb}ju|vd_&F)^di2qkKB%?n(i_aV7=8RbH~%l%Tg;n!T-r^lE*RuDP_MZhf+@ zC2LtJ`Wju!>a~Zn!Bs{VgcOufgX@tNqXt*0E;zZ_=2#1P7%=(Q^wR&*we-nr-Ow1Q z47i#Nywhx8pfa$$*?_m%Ko16mtg0S%4gM#*GMQ}-Mvh?Qg)&kLjf!+n}}aMbTUbW$ti6u$JsWMlCxigM0$p z^*QDvQQ@sH*BTCznuGod+RZ_Kep%3S=%t17va#6<`);=3riC(_3bTfrXoU}Hb`#U= z=9L2d;fJ+0y-qTk2JL>-XCW+N8;#cC0O@kx;BZPB-)x{sBaR!V{B;HTA28tC=7z>E z%0LDT3{?g=^txPaaH#M=vw`254OCoO(PC9mHT)|V;ht^+b)QvMzsD=-#cJM)Lhm%J zKC7(kfmNT;V9#o0aPx7qo98rR9Lz{lF9khkdcCRZW31Kl8cnr8WxEciqwPvNpZF^B z4SWXhyr`bS{uugD875MW>&lx%9(Jm#iROT&+aJ|pwS_(P_K#v%f7Da&%g-Ns>J#`` z(^J2VpOFRny}oxQ$wOZCAcNd?P%*p0Cf^s1<78bSi<4_f$MvP%53OQ0KXKwi4M;Z__rWMVor zCR6f98De8dm_`A|H0s=UF73-uvx!2$S=Iehkkz0zOvozB2SOlq$LdA zf+m!osw7N8yP}nm1g@|}6+m|*E~R%q0x=oebHs(8lY*U5d`m+NP>X~dNTy)8_g?|bQwAu?aq5pWra zDCScdmWWx!e7MgNF{3zmvlH2_m@g=@L{t>>tx1-Mxy5`0#S$^Jm`^QPB1((-CMrwB zeDPU0Z*baS0yl4PrXw2O-z*Ce*zn^orK4Wv(c0*xD=eY<3!Amiy59~F+nutC+{g!r z+@%m}hpddj?83jdk&B2vpiH)OA1baE6f7Ay}|!LKEmiCBhpoQYTqVg7Z)(9=TX zO|oioJMB$P&wWArx`p{e^e)J`MD%JsX@~YJ0>IDgtKaIsV`p>a_&t37(7$6>bLDJS zR1QD%U%5+F?&jV2AtU^>{>m!zr}ZP7e_H>&D)rO)gI)^$w7#SHr}cARF@IX$v40l2 z4}V(!mRImo`OoS8SG2fz{%BvF(ngzcDq`+hAep1&{|_2kMHtQ3D?GU}<{kbC^X zq<(Zi{@1<*`tOi(@TVc8_Ih!}PebZy2ekI`2Ytu^ZM^R)WLNg#FS16=A=p=e{Jlc_ zM|rTnoq&F# z*uDp-{$*@4pI=k#oB;G&#Xm#!_v_KcFnG|#vOw)(1^agZ9Z}M-g)9`Eqnb7Fm=&A* z8fc(Zp)njnooRr-$tcp3=x=-aAxdpdPsVEu`2KjtDN zdXdnLgfTxi6T03&!cdv{H2j=xCTHOZwqS|6N6UH^URfMYEh`eV$mA=4w9v8!0AY!| zPi7s)CyNvRU27r2U}=#j#b~TjR&hTjNpoN<27?2`Zw`zR8ULIh#^`5X)pAqu^j=t> zl&_&;c*T&&7I^@$)qX#brxaqhKdcWtq~(+zC2gCcrP$vj@|;3a?OzaiULhHF?h38j z72>gPA@YJka_tj|>`+L){X~lX_8~313pb6{J+dRBEwzs%vKQS8;oCVmS@+3-K<3*& zPSKMNYxw=gswWO>=P*0zbqSWXRl8p|{-2CFZ7uP7rz6_+=Kt9-%^b=P9%&xRt1ZS* zj(<}PWy@PynpOR$HJ$E(2YFwJ<*OCg&^=G&{tyfQ)058I^ec{P?rZ#52D*$vY%)Ub zM1BTk06%jPzX!NTn?k~lf#_}}K;=ep2+eI3d(b`2X5m=@o23{_H2)s?e^`4H_^68X zUHEL>>1>@q0$B(U0%RxYEQAmOgs?9{!oCv_5R_fS4Q*6J1_1$;LW~65#!*y6G{`6- zDx!iQqYeT(h#NYH$T$j)%6*=yu1<%U|Gjta_jP`6>fP(DN`gXK9-Vcse({U+^qt&6)MU)1+N?)~fk^gWQc zqa3uv%A?k<|Lf6c&By=kX!P;N!O`e0jDMGpMs1GC(Wv*a;AqqhV-`oF+m6Z6X!9|v zdK|}{*fzgFlFm0C<6AU#sT&Vu%TX$Y`*88-8=l9`kYiO##rP47%zv?6Zeo4+0+_Ym zz&y)~rZ8_J`bw@CblmDU@LQ@C?ML&SmTK{6J*8GewI9*Oc|W0BnI%mzB;vwMz6Z_N z8G}-uoYT5;hOyR;Hu5vY-;P@e*3k-a;W%E$lG?-YEQYg{P|cBVlf>uWbFi3PTVrGw z284h5Pr|_v-UZ87l#rKtbBBX>FL>EE1cb*zgtuzpN+6q{Wj8g%y(g?@nd`uK5)1@j z@vJ42Z~QactU+;0WpM}4=k^M57~07%gUw8g!b;4|gs2~iGEik1;?fDLgR2r~r6~Bs z$}UO*O7PCI3_jB77~C)#=$q+1s4xD?y2g?RO+S76F5?09{C%O6ffuPn8&_Cob9}yi@x8B3tM=k zc(cSGzmrGGzVEE+1Rg0(+Dt%HZK_e4rfqo9sr`K-@2r*B|IcUHGsY$KeU*&Cn~A^Sj}^ zqY;w_T9$&e;Ug)Z)skd2Nm+`!nb`u6S!XIm&G#18hwX*`dn=){jMPu#I%-Q_lH5a5 z)`%oOBPo4J(#jWyzPI}LZ)KHT&mj3zXC~oj0Ttx+^xHOH`;}xblG2eRr-96(EvLeb1!t;-x|7l75V&tN=;w3+6SG74S9l+FvR5pR-yP@l4w6 zwFd*kIpmJbemFf(AHw4FlE;h>BO7+!^tlhxLJ+wh^bm@f)I zD@k}FGcqCBW?6_Eufsc%A@YB+u1+;y6wfS4+%clhrHdDSvQoWGsWDb@ zBV)wpKUu!4uQ6e`CrMsn)R0P;)kq>GaxW#5C6Q`Gcd0M`S)DrKTWa#`s^pj8dgW*I zR<2ie{}NoUG;`E?rSe~LWY7K8G9A;pKhLf<=ia}>PK?Lv+EO!CMxml7yX=`DGS6h( zztzt2e})<~3)m)si~8AbAriAqC?}qrCZU`~m)R8r?JA)K5N>bzr~ zmprA1N1SsWqvEb08$qIfE?_22UlAJ7L~wY9mT%Vj{>ET`VFcy@_$zo*(z0d?J21S@i{zDqqh|3i@rGrm`T6Q%a}zCo z9IPv*FKViz8*ZNmk`2JcAMCv77zGx?>>6NoH}Yb^;xkr8C;1-;Ti>iLrQTL}>?cV& z>bwW6B`9tgWrrcdRO2`Pq(z$`>T&|?SCxA!{1R`HT!-BGEC8x$KZNf>Xp~2wEQILh zX8DtD>>vh2Cz$0wqr8OZ7N+qGMmxtC*arXAed|Qb0$ePWdf)=Td%GG&{TH@9*fh6_ zBA5M)|BGzIf1CL^%Mi)aBkOkaG>Fv5PL$jsB}*dbAZKf-lx&XLPsyFi#*BK5qGig+ zjJlrGUCPRg!lo0$TCU8@C~Pw^tUo9_D{3VvQRB9o$E+v1(rk&-sdIKzoVe3%&+MAS zTvnS22&U;uYYXlNB0`>CT924~$)*v>(@X17lb1G}NSHb7&=B= z@s!6-iskTXZL?UmD5J@djQS5eb|u%e2@$p&`Bp{R>I0IIZ!U^J6Q%SL&7y3z#US$d zeeheABE$nxHa{SFN3@;h#0gZQ`GXu2m=(s2DPm_6yEU5sXcN1gwJ%Hj-o$R}e-1q{ z|79E){Bf0zw`lnef<6KPjtE{NFn5@~D!q+=FFJJIYLp4w1@QkR9UOxJRnQGNj`_X@ z?JlH)4hI>?qbBDL{;&!`Fk$G~(uvsI)DCNt0o8mjjq#H~JZbt`gYGANWIrqRH?>pK z#!>CZK&&#W4W`covRJ8oo+%>Y?AHE=K<1S*-#cW!yFurEha&>CD;CMn+`B`lVFfn? ze4Y-2aJk7Fk3PPffx9)0!k3%MxbU_;DfN9vx(F(t0f_@r^dXRH9+u7a99)J45P!oOmQR*6A+JL^Pl89sKZ=nnYEjt(D`LXDFxTUy6k?q zrA8_>e)c^Matru{>)}2M{QU^uTH^LS3;GZQKHdZS90-10en%%WPZLGALch3aIU$b^W6T~OG!Mp4QWzZ_?19fW9 zsrkNd7|3zTnq!vv!cxd)P*&RoD$4o=S}!if;8=c^rG0_bU{-ft86+Npi>^1aHR~zc z4YFGeT+`b;HrOlOTcMmQK&~PAY6_hD`hs-?s=h8jz64T~52TnHCBuN>bz?@!Bp`_$ zfn38E{pA2Nj0)D~%W$?$IxAvj%8JBG*6{1Xq1ddefr6?>HcDsN+3FbHBxse*MtIa{ z1q1Uj-%TKwfZs#&N|u4M1)P#~K;EQdG>imA;2(t@y?D_<+gjb zrCK+)%~JQ|ceX&#rYED&IJ-OWNVIZKcJ=_?=Xc^2Qoj!$0<(H3+Xe(+H?8KDkX?nU&GPKd6k#< z`TMaFzVwF(#CV?-8@zFHsQ%6*4&Qz1adlA+zXSXP4hSw_FQx>B@rdL5P!!%C zxTU2W#;~wY!-05kM{v_LtDEH7wn#IYk%z@0g*YuHm677-26&K@N-WY-=MM} z*os^-#?w~-|FMB@Wa8Z+*g+$epa<_DYuCb6mUPwArmHjT=9!7~(aGkA3;9DeK=tM3 zLETPLHySHdBlB^Q-`-C0OCNu?=pzsOY;2z9U2hiBtj>|^%kQk8!VP1Jw8~>JJ0*iT z^pQF69SJI!ozl^&prf4uN7*x!-Br*uhbp(b=*4fmM!)STXw4w-JrBCe<&|`EqV)yd zCX zd(m$)(@D_H>Py>;@)p~@r2l{_4bY#^H(xw#{!7Z6;7VMMT;TsI>3q-~=zjpZbPzEz zFR>jD$lQmcAZwsu*4`M*{eXGgkK7m2o2=>gr0OBidAp#WkG)p^z?rL&`7w*JO-j=t zK%{W=T+q=rSqe9A&p`QP=Qz!H3hmVmTDQxM$j@Ay5GrIu2iw? zf^_4~z8bL1S~haAJZ|c! zI2MW>AY6K)WAi`^mPAx^f$(M9N#;l~AltrE-$kaL5q)nO^j1hcCpvH! zc{H-~L{$w)4wlFr* zd9}zqX&xPJcsR_OwcVq&(aAp0T=8Hzn-DV-_1Mq{K;D;}m zQL*lper~0uEbngV$*j)J7ClPre7}rvb|5pQGTUTLo7EjgGpo6hs)K_LSF()rB)uDS zp6saeC7qAc)($NwUtq?24P!3pV$#=2`6|#Djt}C0ejH1^H)@#S*@JI;A=>>g@X0{- zs+#g8NEPzU>H-9ayb3e(gBxQte zGr*+oAdB;u!#fmr0$o@o7I(7Sq-;Qg2M(|Kh3fFSf%S^t#QK*y**TVFHx*xXw!cMB zf4@xi^uFbRo*wn)=rGmO50wXcderenmg?!ly2_s3wVPTqbgz_ahU+T>YX_odt7y+mHL}ae`;=X!ba| z(kb)=)oY(X2{SCrZ;%ilh;pJKa)4$o;HzktOw3NIf-Wt!T!0vI>f&B5@=0 zK_7@2$|{+|zqFds%un~qY(|Kg!i~(+H0!C%s)A-cLo(|bVx@2+b4wnqS}Ch#L913F zR;{!ZyOJV|^pEpFoQ-EyM2*nrGT*{pRmItO#(F2JB4ao!?QA@Y_6TV?Q!Dxn(z57^ zJ_S1aYPf5OS;)w|nw4@u=3$niHTV#qo(US$-Hl*R(KD_m$Ca*U@0T(`XQM`8_?PPp#EiZAS0*y4bShujGR~KX(<-d zU;{961wAd5p1N0PPs^mI8qm}YS%RUx+a!}x0hf3?a7H$wyYT-_-oqpL$Q3g9xM04_7SI*^gLt-qaI z`8mt?TT>bQq@dH^nl=RgTT>alwEeAVLy!v3>nc8hAO9GZ^Eu_`>7bwILi{`z;^(;# zKMK$5%F^wSd?Oz(FEz}&NcojRkv2QGp z{t2iwm<1l5%D!C-PXJ->YS|zx{1H6%lYp|3Ii?W4e`+G@WhxX^qyE%{^^zwuzSx9y zq2m4}T@ps-6b?R{lv!=iY?C$6D-} zImA)RfTKHD{YztI6-{rZvs@Z0t4JOvcf~eT(Q<`P&o@NjAp3xSGY^18%9<|}RRJ%O z)<$MK##pJO4+o`{0qM`QJsTr)=0`x4?b#Tav+PJe#4u+glb4muhn41qpytCdPx#S} z9g5{#|G3gMGWW9R)0A==I)idMEyV4NfZJ$>_oG+!j-cj`-iF@svsV^fR>K8_%fK#5 z+~{cDA%438eL)U=UrNJ2qYE1y?_}AIdCM>d@~6&FcOehe{f|l26H;|DyT^N8r;#dq zwo-jhs{TgRk}7(A%F8aUO7)Z!8vc?h7WzSN0*)3Xc~D78+&rT1_VUFxN^o~TP{_jH z?B(&L1UCl+OBl~J-YG%BHA>K_3v(aiJ%Ga*vjxW9N1#&5qWi&SrI}Twvg42O3My2W z-pkH4#>=jc1z|~Zy6)?JIq14?AkS1r*~!bVfU00R1q46y0M7KD4GJ;?f>kVVqBjg{ z<}AyP7(g%tqZ2o+neRp)o{9%4O`x?Gp`+^Z-Ds+`s>G->j9uzrG@Ex0>CYPI4Wvgm z(65mGM+5x>>2lKVN&EDkelU)(Y=HA5`Zhw`eo8t;dXCC0`$fAPl z`?=A#B%w(6gV)^;snMASTMfjcDZV|LdyvbDz?%VS7c$GcgQ^8pJ`l(*BBOv=XP+)?*_7qhyZdCNW~*S zGU0%I?H2g%@kG2KyhH6st8$WPG1N{VrryIjp0T`5s(3pFsi|n z@M|>O`&H2!$ebE+2DYfBv1LaGbVt6=sTbW%kQpa!5e4aTeYW5*3E)6w$ZQ)zjep8OGhUp!_9p zPJmPXCXjytDfFL&5r;DE6d`gUa29MI!+JFO6n*jSUCI3s7MbO@ftm!WVik~Ip^Br; z*ay8HtHHo4c#PgluT%$N;iEu!%!XvZd3_Jq{h|zftz}nqA`Zqf-eRg}4&WN)(V*S| zmHh_vIF8~PBWLk*AP2CFTcgYRgFXeF?wVOX0vsFS!cq)wfk8nH0hn?=D-=Hr$E6)P z7kw4Qk*)=FGvwO!tEfN1YiH6|b4dLv>MhV?Ny{anqHh45E3fyRmh$za*d&7IB+6k`_{eN)B85%%ZSk&ePYQpeXv#%B)F@%54MwI(gs*NUzn zEtkHEo=m#FBi#3iYLD{WPP$pKq*=a)L96)t$@uqz?k697>mPLla=h!bujvs9qwIQf zwm39O&)f$iSzCEmz?-bCgOT($h_sAG(X&a*XcWDgw2bCpB%^tjw2Vf{4}n&>ABt4D zSE=CMk7VV44{=}XT!ff8+P=nrKWD%Nkz9-Lw+CR>?rj5)vOO2b2*(Y^gexOlAS1*K zE8`1LLsfK&dJDQLx&<=2&W>JQcLcvsIu*rWzf&RmqHtV9A${#hh(%JyE->9ZY4><09BN z6?7$w9v8vJSwUJBUeQmHmW`w61EggraS?2s??}tWQSyRn(6Z~tMX)ul1Fc%8Sp*;d zFkS+qe<>b}7;Cq%W{ndMAoagIP7Sf0G2ix+n{4MtsHPol^gkL9as#ju`UAr8#(+}v z(yO6>(iwOi^MDG_w`+P@gp}{n^c+S1uIa~>epK^H>PXtV(A_;p9Id7_=zRhFr}wA>lAY%eW8 zA}yPty$q|xNFA1v&l)NIInmBG=Zn-yc9Qb+Y#0mlE;VHg&xWx8mq<%b&xWypsiU+f zC0{&BEShAu!~Mnw;pqw)(+cV7I5Y>!v$a)WZ0TmB@vq~P`6&6!FkP!9;F+~EGT~I3 z&XlJ4QuS3~*4RnIBtJ*;XM$fUgUOM>U`Uj8og+gvhh}hdtC=ISdl|Z2_M>yFqjN~u z5o9Ib4bw49%!Xq%cYfn$secSQ{>IHxYRBKWSqIwjH*S`r?-)4V9CREV;`mb>=caJ$ z!flg<jMLoU1lIV)r&G^c4%JNivb>@Tp`2Cu*OcIKf&O=tJb=9o-y@ z<@o#0Tpjs%nF~&S0*Bvt_(k{HPlgP4yv#Ow5@!;eQ%w(~8sy<4O+bqUyw3mm}ahrkHk(U0C+bq`iLI1~X`j4&A{y&j)UXA#1s{N(^ zog$RxsHIE8*MOL{tI#;A9gbSeY$=S@;Br*n?Rt;2%>1au%)cisGgtEH$)IK7j#{#C zpjF|HNqQ`3teJ8CB1TWQukTrfqtd)&O+d|-l{PhujgXh+0(qTCDv&co_-swHDL9I$ zU)~E;H&9np0hw3d^eQ{f@;}ET8Q)Zg0)Kox7G8sZGOFSXm&F+mD^;A~vN$)9mc$UGoBfk^%G&7eNJvi{OcJIu_K$H1>9>)sg5PobILndbc{hPv?bosx7sB=WA& z!^_)}cM1LqS#p+HO{^Ha*N4Nye3P{@el(VmvR1g*QMEE(nifq(sfsudUu&|_t|A=| zXXZjlzW~~I1I%xR>pU0-+-Lh&g4qMB8e_Bo0V5k=8&K5Xk|u21o_%pM-rp?BAj_jkal{eagsh7$0k^Genrh zB_KxjK7F&LiYt!yK&csgKu4%eW+c;r%m(5kawCwzKq{zx4%&%ul1p8x%+e};BD7uy z#PIn~L-Q6iRRuJ4rFcgMZu3;}K1B+sN1MgC zASZyN6FCiJB9JTSXd7BG11<*9Qi|4J#lA%C9n_}%Nh0+4I}v7`K6Gk`osWFe4!M3w;g9mo~DJ9G|lUFsCzmdp(3 z4JSg&l|<<4Nh0+ADUmkJ@CRU5@F_Xo0#AjH9;-mevbjfzU32Wrh{92-jMsD${<(JZ zNZ_ z-POXuRmQIjKTQ2jd`0~pVm-n76o~AvzR_aBJY3oOm9Bi5FlL{;fIM}d96VaAn`gHj zruT#3VUlX@3LGnva5nO_oHe;q4+;F0kv& zCq?eH_RFn#=gsrQSKL5PsgJzQ9%Gur#k57i zyXcu7^atGT{%%q5E_xrBbHB*^>*ZbaaW~*Dx}W<+qPz3cKnYRaif51}wvR(CRPJTj z68WwnZ*SsG;&Af&5%(DOQgk!#fZJ#n?;Y|x?bah=Z?&@Hv!veP%I<6W7$xlzW9efo z@ut=H!%?;y>~rTIo!<-UYa!6j~1n@Lq;lK|@^&Y{cf zpDB9Vp~ocvv-Vw@_e6bxOB~y5;vDXh=ukn`m!;X%YXWyG2XukF;Fu%n z-$Cd2uEuzaLY4FZ!iCu`c2AYTsH5f&UxT#D>-Ot^rS>uX_7X;v_OgZ-3&RMDW?HIpLl}$V~8gj_9an!kKIzeWhGWVtsN_$){f0aze$UgPix1@r?q2mL#H@t z*ayXz_t^R^EA4T3>h~J_5gz%Ll@4oczGbC)jji9Zaspa>ufeJ{Hs7+cb&Xx^kH(6? zd^mhF210fJ^k#&Wu@8BGOZ*7>Yo;969+lVU&VkN44fSL+R+cp@fM76DoDz-n(Z~%z z(y6>oBM)n2U$(|R3LqG}H{h7a{$m$JFeUu%2qaG-jGTSq@wIjrv|j?+pOp=LS!L-jF@TkxrR)nbfQfL>K~~vH zX@HqHuRDu*tH-G}!!uY$)31pxPMIvuy)4cL)GC*LcLa;qRpxmfbUuslI9#xg zn7usN@Zq}#Jl6s+3J%Qm8y;3uH}DH_wRs+D^cd7tg)C;D%J(3!?XMg(lMZg70}mV&N(bXu zx-idvI8XubR;CIdOgdN-3?N+EKS%q+P#-Am?_mMH4ciDtt}H;mp#8UD?9(5#4mvm! z#!l_M77pHk{!}_BYAeRykLw7soli)GQYaWj|6o@+81_C~@W;fg^A)Q0OFE z!|oQ3t+$)1AX25+%TvSRdKUGfo5O=TQZBk##rUMKY!){UTP655Aec#u6K?iCB{&ff z45i>bH@lS*ycZB$qTp3Gx{E&`c{L!3MPD?$tr)Ik5;-pGHl-Hj*lr7oJ&89vEM&?1%%_Z$!1R5_X zHOvG_SCU@OPLwF=8q)GuPLlMapz}E$JUK6L_%Cs{L#Doy;Qa<+i57G^15WJq$R8Gb z*2KVgmV(5*%UuPF(!JoB!#l@=%_8$CUkGv8uPDuJkWGUUnDRz^!Ej_p=8cL;&8(}z z;~0^(3`im7y@Cxu*hY0BTALyROry*B&SLilJ8^*Ql^?s<=6w*L9I9zA5jp8}d6{jo z!KFKY72~dL+g#V~25Eff^&<5FyLqSYSbwd8%1=n;r9tIZQuz(!l-ZG*sq)hLx$DL3 z2kh*Q^=ynE9Gw#=`sCOy*vW!DXV%{m}$n&SBDc35-=I7$L88Zvrg`@EVw)0kDvEZi9^+ zz)wJEWKq(GS!AsNMx^t4AZ)I{aBdWJD1~Kyu;f!@-lv0k=gYjmzd?Mu(Qav0i(i99 zijb158+BAsGO8;<8%1(^|64YzbL(vV%+xc9xKYW2z$;*nHRD#1_R2>+G~QD zjg*-+zgcHCQf4-jw9IUz%1kGD)*4-(Dgj>g>!;e<16&ptl7O;X-!M*=^F?iDniDvkL;AytZA(s;;iVkeX<_)0L-mdYn^W-(qWr?k|{wp703HVn=`Ld?pH zgfLL-&JnXk>SjBAay=A$_hWGQkjT?O{z2p=AWd$^_2Df*j7lzT`D+K*058%aA95e% zl|*Pdk_b&_68Qs=#kY$;Zniu4BQUirg0Wf4b1L6D)aX6X>A49=FHSG#(tpIlc9@+US*L?~ikO;kHK(u3X-2 z_SP3}qgR-{^@({5PRtP&uJyU#$}yLsHzy+czo9*N?e?m!hc3MX7Ou{eiXR@c+l$s8 z*omHwMt}HrrPsgwl)b?$aZKCWEiw|$Syl#=5hysy)ICYpM4*t0kyR`nd(F-ed!ELY z&s>DZdSVqI{tl6-fTnIb!o9L!$xsLRA!LHs`kvj|rwiIpJG!s|Zyi-_++Uf*3Mmm2 zp25pRIyD5y9I;5=i|byU^UToZVE}k#gAM?98zW8JJdFr&nt9)7EG<>v0nzX3rX#+%oWH{=G0q^>?`YSr zb=R-1&n;8ia`hYbYe92x*Ix?w0(3EG{dt4(E|4R4`Qz+b0|sV8`D3a-1wjUDP`~P1 zf3QS<14V!H<78LWGWtt6`r|qJdpq>QUkbo7p5DlU%l!2lucZ|KW=VxVJf>?#zx`Lg z99X|KSieqKzh_v#q*%Y+IKDz{Lr)E)xq-AakRlr#BKWbIEMv`1onfyE5plv!i9h{@ z=B$B9DYW)ih%!jZpZcqoZ0n(pj_pXXKr{5K0k>7E>IX|+XVGtCyih6Dov_;#=bY6Z zsDT+t{!;OO>tOYUE&cAU#3Abbsc(q*_5?ObmJbmTpV$kF?ccQr{gM{_-WmP&8oFd{ z^T#qeRbu-mcDm)O630HVi+jD$)C_b!{X{)AdCc-R92YwtfjVSqCvP6xONDc%Zs@4x_QzCYJYG)5WUZ8DG1s=E6&zkBz6MDyj z-anx4x9j`Q`W7*LvIfVG7KMMaH$~`;q07gLV}G;r%Jkzv)YCnD32^R-PCKu-jjB5?#NrT zXMI6ZU(=?A9!FTV6SG9xXLg@7eR8Bv$f!4#|L~gvD4!!%d}g;Q)0e~aWi@?$PA}W^ z^*(*+QD65+nJ-R#W-pC@=|LS?E-otcgXe|w>u)+`7n)7RCgDRe0AC9%-T=AcmCx-A zKj#TT9)QvCHz(EbtORTXJPA--!0Cb2!ADTcOKqi4%m?2pilm00QpNp_|)|P zq5#VQwD}b9BY;x@);TIm&W4-`334VxscQnT11aGGKvaE+Wf(C|h+@w-wy%O1r$qv% zMFOWq0;fd+r$qv%MFPJ&PT;&qpP6!o`373NMN079paoF39MTJXGa2O zM*?R@0%u18XGa2OM?$*}MmYb;I$=1ee%1~rNdhNH0w+bCtxn0~BuU^TNhrjeSPUou z=oX#R4V4Jk1$YCX`J6vFcM>>92KH?egSAX@m~SI1KgNgJ%Ct%mUBwp9{^6mm-{D= zlQJQDH~w*E=B!NMY^)84UkCse?SsFuvr{<-bN(gB`F9AKC;)ufs5*LyaqbmMzPD>c z%{R8k&nb8rU^#$qYFiCh2hdT6@?HjiH(+mwJd}4TgdbIf+dF_*KvO_GAQ7Pb1_~qU zzP0=N7!v~_a4kUK`}A~)bxI!JW+)F-H?cugqTAo?%F%p-&>6s4zy*NLhU)~b3A6{D zlE*ayVJLv>1imjy%ZYPkAohG~XO^x5whgcY@FGBarv}#x+KM>W4Fs+cq_uwrHlwWr ztOsyKpsmTD1DFR`2v`KT0dNywF+l5`10Ih(X~_VtBs8CNDj*Gz4#)Aa*fPkJ5 z-{P|g^S-lFh3`AtN323r{T*29cXp=O_N^W3=M$*qfUSUY0G$ONJ>~PGkJg~zfIWau z0jB`TlNcrQl{)C;S^>gv|oP1X!7xI?@GL;rR8t=r_=*XG&YJo~ylJ3Oy2 zt9^$KX|3C~N^4P&R+2l`upF}k|9RGq$-mBy%gaw2Y_IT_+xe;Fy7Sy)JLKEp%yEi=FdWaWvvPm8=z=C zs8Vyg_%X~$GY^RbkJHusrx@XJO5I#q+8e~Z9%o=0mzVZO9)=o~+77kZy?b}drGnv- z)Ba(7xRdVYs?%OCa>JcOH&>qab}<0__FR41e+@U|Hrw$qzeX0d$a0heu1W2Gg^T;c zo%U`nOzm2+C)|loKNevo6kwm4tWfrD`&9lln8El^rJ0hL#ZZ3uGr^LlbC(X^}u)R{WiE_%^ zToT)Nh{;h-c|R_T?RCw})VBF{Y@R(ouR5h`+m;30*IBWufLt%z&;M@}xRAF0BEF1r zI)!mDZU3v8XdCVL++0xGe-dM&o%c&0Zf?d6(gllNM&Xb$486hcDDFB>Q}T9T8-6ZEvp<_s2Nx!??b;&m@c2Vw{m-T;$uw zQ|epAI_*q1m-_b8_5GSSj-Ac*yuH_Bw!Nx#n+cX%g~-Ld{a4$JvmzRLjaU@#ylpKk z6+N0c?c%x2w;#fl++ff7qEy`2%;`Uyi+%g=F0)yFcKg=8?m1)HbnSq@d|gvK39x^2 znQey*9An>9Zdob|o)g&jxXtD%?Fw48$uIK-4S1Gd*Zn66zV?~l+(}B|d4v6i+icdd z?Pa#*UBuMpjxU^N5cV%_v#of)xf3s*!#`_97x7keC#N6J9_-gWW}BX!Q3-my;HiZD zp~p;Xli4rLm)}Vr1w6H|zau}R5x=}#lqERVr1Dh5emLC35Zb=QjNG*AyS1H=RiLeX z-Nc&-&ir_ufY=X5m~lSc$u@MaACTzSw)JTD`XMcxTWmki8SHlq^f8Wx=s7%ju>We9 zn&wG_{Z#|alL`Bu4Kzzrp9_94?utIXC-&l3(#Ar4{vyT060})vKa@d7AT{-HK-ob{n&8hc;c?w#rY-Z_^{EK%4Kc zs9%`wd~LVmsROnlHrL_t6atT(rnc#-IeU5tf3~y2+EytdbDXyEJcqFFHqG>Bw6hD9 z^_4l!ueP;yu&Bs)lC2*Hi}CqR%Xpqn*e_US+*Mi?7xq@=JN0_N4BGwf<6D?f7J70{h?yIVQrK9st+rn~vM`x$r+FB)MmpP+abNOv= zv)NVCF@JWyVq(jJ0v+@4>iW;ioDn8ou1* z7v1(r+e}DLYo(iohj)G7N~ft~ofLD{s1agOAE(G#h>v9VaWbv|ciipsvuAZy1cv8J!%v%I6l-o8$EYy9YXyPso6S>wkD&v54hYx&svPlr4A zI@W>l;@UCJbnEDNaeR!k-NH))?-}b9TGrvI;`Q;)8Y^mg{fG(9JjWV6z5cDq_!gTr zZ>E@arPIy&Vy4)7rL!!aODua^xEX(k9+;+HQ{QK*Q{pt|ddgne#Ec(vMX)tDUnADd zaK>3DX4QW`!@0$>N@t5X*Ek!jt+VSrvz%Dd!d128+0OIU#yR59Y$vf9S4{R@v8LHJ z=;X*8@#}0JEUEL75hDy!#;QFBm|6LZDgbI@!l^Xq%fbz0dL7E@Cf zIN261v8`F)w1^Qe-R88788&Uf%*nHc&73-I%G}8dri$aYIceS=Rh5N32Mz2sa}oFp z#ILtGC!?>OH*MO~L556*)*rv!nQDelnly9H!h(`X3&qt-olX&bW=+0o*uu#Rue-K> z+fsZWPAppHTx`E!+T^K|N;>*{lO|tz<+NForp%mttucGvb(5~0ws6u_H!hevY5KJb z>Q~(5d~b=oO|E2dY=bMN{>2rjlKQ{h?X))QTd#7aSYD}m?X+3bCoP^YN1f*N&phtLN7TQu z&GDILu9*3{(>k0NTDkJF#B1B|qJQ6Z$7A|L=j~2T8-1^d*ILJ8ajWk+@oG2e8gb`# zgttRHwjEEn;MP<6^Uf*U?+xGKv~HsBJZWV|bS7KhfYR)(VkX&K?(ovTW)Bh%fNky+ zFYRz9Ss%0$$uBsAU0iBx5CsRFL~-W}PMrC&c;E%B;YN$sUU2eF+O(37W2nSn5lX_UT69x6o&22b~ zS3s|a*RvEKkm%t}9p&W-Ln?r!pC=C1J1wFU1Ejn)C0g!u`nu%ZC>dsKrMJ{N;BBXE zGR4}R2x?8ScyXuG%EhTz)q8O~+?)%;9W<~qf%otxt~LjI9o9Yh`i2!Nh%|p9^(80K zIu|C&UUJfyPDENl=|Xs^fkq(qp5D}f5nfM^NbQZ&H}5v30;rG4`^A@>R(|687FTa? z>}qqO*I@z4*SEZSkUu!W>r_U{doGme+hCPa=5=&w^lh=r`T90lPwI~d>X!uXn_X_e zOM<+)qWPiKkS<=^9C4t;k`#yHgLC^fNbm(yxG<@#=$bTho6cHvpxebZ&-n!pF1 zY=vH`tXih;%*i|kHI~Jfi*A2*nujwldB;vX_YMxKd4G1IvdGhS?;85lMAdaEHh9ItKE;~Z$(hBkE>rM;4J&IR92L)79MZqgh>+~wH_3gw!Zo?v& z9Xf3)R4K=8#zn7SXs8nRzvATk-vEni5|)q^OIqJ=478UVp2*(=y>rk(|G2}w)ODw` z%)Sc+k_DB1uu@@ng`8u@6&yIUPp~B}`%hnWe8DC=_$j$iBjhCm;iXeO_`D%z@5Z3@ zhFH7X$#K7oM}|HA^Xu*--wRrlC?5n_#T#DZ1@-O2YYY@EbkRG1Y{(X0PM8?*ngtPqA^YGuV9^ctt;PcCS+z?rVw) z?2l`_qRn9^K~%l&#JX$1yJ4W1{<>4>-T?f*!D7?vPICB8;I)J4mj__@QIMNKMyccR z0!aS!@e@k3jG9gbu6rAsiF|#p8a?I?N425sL6qtH*QhQYQu1&iU*FGW2LkO6e*P-J z09zefp_!{L+t`uT)4}j^ywYn3Ce$ap!N1ekg21TwV>b>}ARbEpX9o@T|4(vG1Ui7r z9i++@YL3_U$3!#G{tp~Oz#Fl+dM$-OfxT_8~H4y0@$71al zpY3xJ%>ClxKBu*tS~&4(^_G*IMO^PukeZ=%>Yax$bTwl1uG%SrD{ zQ~vq@v?^oMe3mejc57OE_ZFgv!WNRKVWR1NC*6z^o%cH#1!U=M540q$w?AkaY}wry zY?N5L-$`gfHU4yEM2VN+t>h%wr*JNo4H4^=wB9IDi9y_br)!yWm%W^glp2uZWUTqy zPOCKP>P-}(jmgeH8BWqhzKv^I#Bri_EAYX@c~za83PNqzW|Zko7ojqiiZcEfzShNt zjI(b$&9g&gEU~5wf$IiVF^Rl)Fk75V5F_8g`4H0E1N4(f`)j)=q+OyKaQa1fqk2RJ z>jolY+kcR!f~W2Gh|jh=E$F`FU93-$j(yi@6|TkG#N>CK1hO}R&2$&iG%YTHr_d62 z1FgJ^Ujpu09dOd3wf+~7SBf6*V!2gwz;WnrI^?p}arV3V04}yt7u!{K0S|_;1A9`P zg!KoNiTj|6H2a{FM;BucI@v+h8nrTe?4T3lrz_sx(BnDjeV5VuFQebNjMh75bTN5@ zB-G#G%jhEwbdId$4+4zP)@BdZlY!!kiSGq^$48gx>#aHZhz#g&g1)RPW1`sg9;P`K z4%Y?FzvrZv5!dg3*ZJrIAZtS(xzuY+i?bL+T;#QZ}}3-`QM+~XtG9m1kwo_OI9 z)@@|*M~{S1IyFG!I>axBaFw1iT#IOR*h!uls;BLEeS$Wco_ZM#k+CF1PP+UuS`QQ2 zf2w$Gztg(;p4ONf;4T^JsQ}WrzVXpvr-$bZ zORc^DEFAm6>7KQ=N6dfUY0*Th1U-s}V2K6K3-4n^wMTr2q*5#KsA2gv&2d)xLKu3J zQ)oV^0o|>$MadDT)dX$FaZ1|(m7Ac@Yp%iL`4|<{f|k1aksS04E_~%OMf<3MUL(GE z?g-9Qw3t<|#i1bw%L(^-zZGgOxZ0sT@2`dG>HS!j>miHa$WJ@mi}TCt4q8z*1q6Bn zmp(FdK)hiWnvve%rR}vIZ|H^U=?!4|h{;7D3;-9Y_Wi}l?m=8XZhN_}%Y!D(u~}D^ z>OKV@$WDMHu9=Rak)@aqjbMMI(f>9h@f_5Hjq^XLvmBwh{hw&xW%`%X^cCVy^!?CD z3a`Pebp!5xMv3=#qmWC)Z6BhiFA-ZlbXp*J zZfkg2~vRfY<~jU{Vtl5L-`y->71`Jt!geA|=Qj$wxr}v13ZW z#M4RVP7LpCp#_uNpnw?Or9uId;-G+7i4ypkmIfunx+w{hkwF2mu}Z)s9@p_ylMrhT zKqgGMr%wrVW8#C8o+^N4`0AL}0HDkSU%3#QjyZ*XAf9Q8ug!d^hy(ytCY1o?msl?) zVA3ZjAl6R_m<$LChz(K#CWC_lVl@CiGST_++VfceSWFm3N;Xn zhd?`9jyt0(0C2`69ydqL;C^0X16Ug=MJHgY#3Quv6JR|_u~Efjb0N`@TDl9Ymz9*s ztx`HlOCJVFcW&dK?%bc-*J*w~@CO0FH^?U*TZG&H9^)3{Cl6V%Fr%r*Sldr=NM(w7 zC!A(}yslIGmCD*LZ~JZsu#uVWmv}*)gM)DZfPAJCC06H*@KmQfIljXtIZd@!9A z@WFHkz%)j5W2$`nr0+rS0X`Gu+81=;)&@v6(! zSyX-M#5<$#A$9RXKUY_=rk5*G9FA}$_<6&=6#x#HWCB!AAeO5HOn5WDaTjT@tk#yM zF{Z(+TAP8ZYp}s)sIu`ZuS4q^?1pMPW;Zlg(gxFEIy)*13$Yv)YB?-uNp7ty$?#2q zl9>7l0Y4`D9E`&N)Buy6098<8?v8$DU37t0%w864E)Uvv6v>&=RNYiR2+O#3k z2GgP16d^Ik#nNmj6Pkqt%Do*! z*hVE_@@-H+j9b@X!NftAR~E#W7X&&dz17_|)~@kWI}pnn9gE-K4)`ymyWp6_P4?VG z&*NE#!DE;?b5nij@vLLR@kvjo0W@REef41LSm^Z>tP#t7e!5~Teo1MSZcwR|85h(s z4Me+CM{Dp=0Qzwo=VwjRR!H@u065ebpsJqWQP&_H-5^zUM9+Ly;7I`EX3FOT5H}wk zP>zB{pre1+97(6trh^8n;2?egR)+!T4osB$aY`|c>~XpzCm{Z@gP8ca)7r1|LIn+y zVU3hwjbg$^0e^#^Irl-%Qi;d_fN6|k!VDz8A*4|(51UCE6JZ-kB_ixVQUb&u=t{xK zrW+LKmW5RBGz6*(ec2I1Wq)I<5jsE=t-)%9 zKIEvZqoih?^k20Z$qt1wsh4PQ-Eb4KSq4DAV8Y5k(*-ihAkLgFDtji(4P2ekcCdDc z&0jjrT++MP^`+C&&kc?J0PxC0E@T>P8l=??(qK=ebg;A?%7nHYS{f#y#8x;a065N= zRB@GL3?Gd|EuJlzY}m&CwLklA5Ex4Qd95sGnNmLWj8fE2p(<0i^edXTNe< zxb6e`s5tZ$uIN1q^l?D481l8#EN1Av*06gmGPVJ7$jk}{ht!$YV$j!4zwqtA_XC=X zlQ4{JUkfwnQy9m{n`DkmZ8R%`d$UZ7>=|qtlAZgn5N@ z3j^d}$r`Tn=FWyP0HS7svs9p?nT%IlCd@44KnU9Sjp_!Yu{4?@jjEX_BVNCezo3yZ zw83T^ZLXF!LzyU>;GjnvpOg+`qNKqt*{*#b6|iNjHRytgKt@R&Wb^L#Dg(#{Jg}1Tk|KE}M8@vC%Dr7^s2kLVF2UZ=c zRyAv|M{WSC7Jz=c8OfRU#vtOMjoJ---KbP0PTg|Z0ep2#D210OSE!cK?N0!fhN;pVt~4WQHC#Cs-QsZtspbmTFzmf{ z;TZ_8D_1NrUEWIWWFD`IH5JK?3T1K=K$Y-TU`v#M$-1C`*aq>*_fDFhJG=J*P*^7W z0m_)z0VQC+#o(&DKHryR3Nrc37D)73W#l20w&Db-`Hn7Sb0i=i4UL@h%rNi zsVk9N*>?cIVzLXMbcr2P0wx!N0%Bg}gb6ddEPrktyAJ@LOx6RGPhyWN0TbrkICAc{ zk5URung$h!6)ORgp+Nz$SzVQ67LtWQi7p}cw|xabG)ztdRHhPxy7;VA}q9i(sNvz^BS)#Z)mj;{a2Ah!$Hq{L_!2vlBE-Iv(;If$R>X-b( znQ8iWAc|c8cJJLt_W^LJgvmP+9nR#4;xhRFU>gg~x{rW-t@unBTJS6tx6VN>lB_Bw zYXGV~h&`$VNV>@GR}LH0GQv?N}Vh*;i+=t9QD)T>|wfO^RO^p3?Pr` zQi+$=G2ID3NKCki@^Z8F0UlGO>L2-^bh$5X69ARRgnQ!f+L-+zOGECYTc%9h^UZZbHO;FOn+aoSocTxK9s`74-{GFtbt)4kTNTP=R~OOYS7%Thcf~GN zY$h}iKP0-^ig~{};o{H`S93r2*Y;8>Oz@J>&~oqrn^eVOlGj+u&Aev;C=3%SH;$SL z=cGb46Rps23GbXAY`63pJoo0-;r-I6iV1x*_Db$YNa6MAm!irb{8D+MNW(^!FTKloPNkzqppe^)po6{`JA&jYAY zT}SLUC1IjX8!F7*8NCUBn3*h*=!m6As2eiBmor2^m}!6Be^^xfX(Rt5RS>ebwD!enfZsIKtIjTyx3kpLu|1 zFji4=#HCBgh3&30(%h}>f9Kf;#EDBzdUj(8R`~y}E}8a$`*U68=7IZfb2YQ!5NUHz z8(is^^IkaXiZ}lYzarOi{Wo!l#s8)L0n1f(d64&?b+r~FY*!~S=6fegyl1u!S(82)pL?-Kd$ezT6d#U9)n>stfot`9dILs9%PP$yVer{;K z1b`hAqo)o+hu@%39jef93{c@$>0u}nQ*tiQ0c!sJ8FC-HL97= zxjGhgJXAO(6^1g=3XStPAr*!(`8&YE-8`mRx#5nFSRLjX!J23zmV~+H`uVzyHvp&( zCd{nyK}ChVQlXlOR%oaWD(sdDLz!rWhWMzkQz{H&@)m&cG5x@gf6T8TK<;pVM>b{^ z6B>sMD_Y961I4KjyNr@WMoJygG)Z!Cy!}M?y926DsHVlZUNI+Q~70sY%(4fBaG6SeUKt}>z za8Oj@Piw0LT=qJ0x5aR{?ya$OI7x(wC>gqo4 zWOkq3@13XS)c>4Qr%qkEy82Sp1S(6U;G#_;+LNQa-cHLD3R0LtFy)X`EdNB3$Bo^q zm=Vq{-PS#xI#{n=uOX0)h~Bg|NjC%EIIFa0k9f=|y^UK>KvP6-)s}nFL18Qk=FnKU zv#Mw5 zm1o{TVYifYmnO5VO;k2|3nFeWmA_Hg>=cS3LBVzJ#C02)&?YeU`a!szP!SbF*UDMh zR70!>oK};_BZMx|71w6Y-3!B8$u6h`*AZN=^!Z2PnKEc&nesxacec1h1ra&?-zqHl z8-%>7^pQ2|ioJ277^std#qslsgC*6X8u1+?iJ;+B-?LC$!1TzNtv` zpiH8etafl_4_GRq64s^hP}|x}$YiPggj|-XTw?JmqQTjrkn^%bA+U7w>Y!yKV^+2A z&B*iqUh&pM!`fZWL_y>pf-kjV_j-Yd3SV9wO4&k?@1mCzI3%xu@cC{!s6Eh?8e9IbBWt`@+EslfC^wEnT^9hwveVgdbo_z~sv5zi=Ec4OjkUM-- z_250v`eO?jEKHnZg@uq?T{L@iWqk?NqQ z1(F@ib8%x3mv^FEp%@fwFUhP=$fem6RlPson}F9MlL?t~{an$+{+8D`1JX=zhh#QG z=x!zqZX7?jf84ipV1Gt*W)eM0H75|;Jcy~o>MEX1oYOyUNc6gY^;BP3kSQ+OByx@C zimdcpk=YrbVX2bnI6`%FITsuQ+TI}kroo|CD$Q{C@uWN&%I=l zK;6b?UZO3~{)vD<4`ubn=s;_P(x8&!aF zo&D@|-(woXeT&PWm}gK_2BVzSqB6MON7XJzIjcqG#TTk6K~Z^q>Z8hQm&>cDyvDh_ ziYnImKB~Rx+I=)sVX_ywAMQM8(k6bN`lvG4;H+k&i?;ha-bo8`^)VlP9HMllRi*>) z^(?i>QkSTxM31>d*_mlhYO?Q#Ph<2EZCd zsE+2jf*g|o>J4K7`U?p`A$YEY=Mor^ra{_$^f5?Zm&3%#kQN`64WDmzOHs)^Yf7-_ zw^vM@dtr-34nU0_T{@Y`6}4E*eW=J4IO9QE{E?R-uxT zNL{+%ctwd9`sf3YhkP_Ryb;*x@M9HTMM*A;dgZKzlwJpo#G+2j>$M@dws*Y29Xj<+ClP80y&E8I#1Ci zkuO}dAkyIG8%-joxM)E{D>Kazlv`?)B}p}==Qq!Cg<__VppoA_%QYrs8Ytv9%%t!T zL66{8Lx;zvQpr}1gfo6~qZ^zAer>c!ZoTAk!Zs*I5;W2DL$$)4*OBi)Q6-HeTH zvT?o7yqmG1rTOkB8_E5yG$YzXA0W^UBC^RSAo8T=iufAOj(6<>dMSZ4BD-C*$q}EX z0#bC*CXr^(6;a-5yD&26rW$2R;_}AJ6^d3NZ@XM!f>p@dP6`VNYA;dc!F_@yp*kX? zP?ae}OR_qb{2Fh-8TvAftH29nELxJ)t#s!(`G_{r`2?y-M5dV(h}?3HU*&TPabJ7Q zdF>VR+H1~hujp&9blIP|W$zyC?Kz1zk~pjmD&2lg+-vQ$VR1uEGG#L7V*+`K%yiKv zk*hsdL{6FmNNHLK8oH!;e;OBEL0}%R3sOxgsfgA%3(X??IyQ&8ernd>LNIr0YEE>e zGglCKoZ#+g%C?N)vPd1l@kbD;55QUHpRVL?a#wQ&5v|OpPBUqei5r8sygTLTi&i1; zPPxK_pkQ8%lk`^v^(9f|uXy++kHC1GP@Zexn)f?%R(8pfv$7*CXJutnmah`1E)nhM zo3~}+_A2n=#$4P<;$kk%a{E}0J9}AzoYjd|Hha^S!ef+>3Ad=W7S5ewj|A?QI98*G zq~-M^g~3jtC=wL%R*}L`r!YYzDC7sZ6waT>1&3NAY;Uc&wz$5Zp!kY3sco?|q2yI2 zU6n~!WzuDXLeOQfl&UZB#4xP=uUyDYP0meaw-a({v!wSD=<&fN)A^;CXjgA)KDU## zkv#msNed#{pTabeq;EKBqll#CO(ca)PN66g6!IpL!p6jDOxS2N@-~u2Hw>%#wNv=0 zG=3Vin8uewW!pB9NmpgkRhe{EX*$>bSsQ7a^1U!dB`KZkn);IT|Hqx&>g3#N+FZ1M zFiXb>&JvZc1(*NCP(-+4*if3C1T)g)xisauWR0n!tas)LBHB>IHD=oXa&coW&W`C^ zTFj-HFYjTG6->6Ka#kl=nNM;e+1I5ki1@w4%fw#Vm`gLCl-Ns)xirgd1k$n2a%OJX zY_5$7I?ISYLa2z637etXF5KK)m+E5#sfw;6?8P&dF^7yCuq3MMHuwPl;QM*_N-Dk3 zGD`bw%9H$G)3~UzViXQJDp_{@qjc@5uIPHFTa*c(tZ0+{SGm2MS`cM3jEl#{3ln*` zn?TMYXI!Lcv&b|TEr_&uuEsTc$1U23bMmdKYaLxoIYslp2@{ zZ8rhiounYL+C`g19w&Gm#h!D5g2*-(Z5G*1@H&cp<^%eVG`1k@lPfZx%YoCf*FW z%SYQG+kEs*$mc#fY8E$D2uwSsKw5qDR>(arI`K)!HqZSM;!8P6L`9>kh>Um9Nofhk z*&d{P`jSwdiJswXO%gdPWsCYOvgTbws?FamwSO!AQKCKhpLDHX5ZQK#^ET9mF^ zok69tN7UM_y0xZyU~Av%foTMd-<6kLth_V-sNyG3S%qsU9lU zzY>_^ioEkT8uRez>Pt$08W+ElXb+D%0{vP<`}X^e5d0PQFs~3;+8g8!0%=6H5z5m@ zVHrVX6up zf`T%Z#*2gw8Eapd^@K)@h(1m5MikpXKp>)xV#=-G3#Z*F6h)L;87bYb38g+0S*y;I ziiTzT#(R`_LU?egVNd^*W$)5v_7HLWFZY7=!T9*xGW2Ys#{8=*Z$acMg3n&D0j-I)^m=K>PS|C-qc&^A@o-1;X=ZYv#SEc8BbM@fF@ft;B!#k{)SI#=CbWbKQ z$cso??(cj!%Lw>8YFR~8`s4&|R&E{=pPs#u&~xoO6XLGbhv@|MXLph+h>Ri;UWpvz zq6HD<=bMj*w}+Od3}g8Cs6ITmom#_l+iTB_7r5^~Pj$yoLF9ab{3^65w!jNSv@ewx zgsRkMp#RI1*ZPz}w+=Ymu_lO&Akejko`2asEX(wKk&9CPlIvnvk_WiD_+bCvM>O0?Sj!GoP_t()I z$y+FMvpyDO(dr^nA%tSxA%*yCI5{<-(^)zT@>O|AQxl^j<$sMp(V~6x|YL~&% z|H@#=`_<<9$d7XS%3A~VqpG~u7_6i_4VGMs z*dY9Th0h4a9qF%38bKvpVq({ zgC$>QuncTASn@3fOI~|OZclQp;Dzw>1zb18<3tQ8XyLMxrwUDn=2&vA7PRtFLvt*7 zy}@$eE`uf4syv&1{9z6!@Vo;B&u~}epcRX1lZ-DIxs>E_wyxa zF<1t8zobmQ!C=X??$4$#jLfl1Z?I~x-_hL52nnR1O{)Ty!nLDvEV(whvhvnrb1Zq^ z`f@y~zSMqxJRq6R81rKW%>&R0gXn5Ah+d0axW>pg82LXS7q)|TeI~DtzCl7^?VDH; zRl6bN%lx#(&JGA3xjJ`Fc!R;WlR@}ZMW1}F!sr_ko>v(?i2OM4P#9s5oMPnC*S95t zzU;SVI2~i=WenfEn+%qLEe6ZLc7r9?8X*WjpT6JmIhI_DmYg{4PFhUma2R8>{K_h5 zWtYWocEDO3=<8z@L0=B)V-;m%%=;Y_KJ0+?wF+xM zU#qZqX9v8i1J=hXtiC>0;mRMHpr)Z*p|8Q}0|ywa64V+j`A~x;*B31y{QOZd%3#Us z8@QF|Ww@vVZZQK-S3hHS=EJzLxP$(Nh9vh;9%-?cb!hpR9PinQ zK`j9b`bw{5Jr-*jQNVKep_6kg{ngVALkgP>mV#C}LHPM9+-b1nT6pEe$oK8U!Kn1Y zrSZW@?J2pMvRTsse||$QAKHl-eNG}|b5tktjYcl}Lr=@~akERb^0ZR#%Q)Sf&`IKk zak;Xqq|oUPW+5`t!b>0dOruN515>Mm`O> zaFAcvNrpc*_UDwz6Mz2FS2VE8uQIx(Ou@_bS&blfHDd7fo#<;Jm(|~4uzHDBb~*X% zv_yT+&J##MAJeb~h8isS2!rKNy}^=?Hdyj0XP4$&N^>vm#96K0L4}{M-Gv6rmR1cp zaVme)V9B*I%F4Ncm0`)XI4hMO<(hA3&T!LdEgiE4#u@x@>9|&o7nNa!Vau+TX@q3L zLmJDmmgoez(r+_Z`dXV~TyJ)-sQPUoJQ3 z>}e@MkiU)mPhf4PuUV7q>4kqUXI8WugKzhXMS^F*J57SslXAIApr^V)pF0WBFTvJ9 zJz)*x&8&>x&8&>w^jw>w^gvyU$hoSxIH|996Uxg`wPG z2~+FOwJO5>Dx+7B_u?6ytwOy(ALOc`#nW@F66+mVE8loQjwRPC);@o-lz|N`v4o%2w~hmC@BOZooh=C^C=;-$8~4f_3eY=690&R6;QDa}>fa^y2x(fDA4) zcx`Fx{8%5#_+oxMDA{Nvn>w-7U?w*z+IWLcst);bT1~IL#~Qix3kI+5ppUq8=l9}X z$$A8rWQuY00@&V<-d={u3Oqg2uZrTX<+xu5tST5~CjY{l@`C$mUo{Vu;q&v|?uZU} zK?nTRRpt6)xgfOZFYkaCOBaw{f1J-y8%$UOA9ldAI+S2`2fS`>>BDQ7RSl=~ zSCW~okm@MRDIIVV_zNx!l-XX$XMmNLa3Anx;GgvM$LwB}mC*w5IpDpd5B{O#d-K9? zikAtWmDx+8J7Ijr)uS9x1}nk$^~>>Zz+ddka@|z^k_;GwTft{CotmD?-v&Q5gvVYf z{ww&>Du3>lLtXLwE$)Dfa&l%TgJ5i-c695%57+OffKO#ut4$3|2HP6C7<}W|el{bA z7lJP|`ac1`)Z&Ll$^Q}j|4ad&0u$ip*bfDAND z3V#Ru1s?1CAbc74emWqZ5OQsP1$ZkHJ`JOi-w1xq)Lu3EI2@jp>i-Iy9>ED; zd5fdxVf@8Z(N^%g2EPUVfGXFcC1vAW=k zvEb_%Mk_TtP_LgL19Yleq=13Lsp1ioNHx%hJB{Zd{~kw)nn(^@0G_G|o~jhw3jP@m ztI33~1)qLI-Xynxf52U^5vlwE@Goo8Cx4gV7cjyD!Ws-b32sdf*%~_K2Jo4K*=8}- z-vl1WVOArI!`r~`b|=HMjo$@RYu#E>{3-bNl(->vxSE?$t2k;BcU+R;elU7*k+30E zI0XDT4m6R0j*26|FCB(Fb>IZ>|7AWG#*Joh9~`Qc9EWCt=h7r$9JmtvSr^{-N#)mp z|F|EslhLWc+hF{VCb<SO&Ij_+SV8B>2R$c`lB=n(#N^7Sm)~z^@nw-vjFlGW(*h z0_k?#?5ZRj_k6FN#vMtO=AxI}^|s@1<5I^lA#&EO&Mqcyy5MH@)}mtfxM zq3e45Yw&ZX2L1s486zvi<@XmNi8a{07b72S7}~5Kcz$&_3c5xIgCE6!1`gHGQQ(*w z8 z-38u88)MJ4;S*pkEV?zN2A>7%#OLMJ(W~I?8SWZ=2G$(LAJ&!HUxEukN<1zt!GPZM z^15(xsEm#P+Zq}R{ukrm46tpo%fQ_k+gGIaUZl5;S(G*jHFh2H8H@vmr}BFe7$ zgBO9V1Ixiv^Kl`G9)$5hH$SOY4Ll0|AtM#`oxzRZH%%Mv0RKIQ<+aGAzY}~3a^I%a z(bwS5m|$pJkOL~om~p&&l{(Z9d^>$^j!Vz^UpMLxIg%1`m%{aGu=V(4u690x4qgG)d@^*(zXw0cjLJEv^Z%_d2AV2v1Aj&vss`lHGvJ+OKCoE^ zxEUPe{|^2II5g1*;KPpQbeop=OYkcr@)=Rwhoj~c&W2Q(JOB5Eah*Bt2Z8^CP8CkK zqruOR!N;jX-v--0GYR}Vb5zU)&n3f_RDU7Z*689KC$5d#U|eb(XwMa#{76cm=XgUg zs7dFu$iq)FoL4&Ne+WK@f#w=@Qu@eW!Fu0CHKwy`PewRRplfvgm%;upD!ALQnQH}A z`8U9}4Nn9g$yj~{1|&ZV{IEH{?}dZ^OqEijPJSNpLmTsvaW>eVORfaF8qxV*hs`Z8 zRt?IhNOyt1pbu~?Hk5Y*z)gGo(IX zjl4-1di%q$lf)rld%ivjTtNxl$%zb(17FHvc&i+wioXRO$z!%DX{T!jU&rZORbGeu z02O`sAf!%^Uh{z@ZF4Tp_BapY|kCb!S+gL z1=yDODezNf68aK2v2FNzhXfyi`!KT6xm}Zd-9bKJA37;b<^~#?Y!LWV2D0&K4GjnD z`MjD$N7+d53uc@+Z6A)m8PouFU6sy6!Cu?#qGrxCr_VXapCf}EseS_f-nW^erA_bw zbGlZlJk0SHA-6Sf5BNpnz!Up${5?t=%R{y41{6LxIG@MA0M1Vq+@7f4`@J*(dZvrpj6`ggd{wv`7C~>Iat>C}Q3y?%RV0?Bu8KfTl1#BJa zxgVAaQ7!)&yFdAQZ?KgQ29Gr7j-$b=xGA_8eU)$=cJu{#N z5@@Kr1biF@=A{O%2k*$v-(90N@Jp27B+03vRp61F?UY^_KBM&JbpAW=Iov4jmv+*( z!2G)DU!NqZh(3jJA|sU>iZRfIy0;@?AF!Pv9Rz-YJ`*lfjspMI^y;&~_OP7>wly}_ z;KZGLV7z1utN=g5+0G5cIP_0oJC;8Ow)cFtfNcglz_x}y>maZ0A4UJ*`%L1hyf=(5 zYFSE7m8c5qz#o~B@My5j;8gIXYk#oMyt4|ej*MH z*7;v09tfkq7%4shY-ccI!F_7-Yr7`!EA)Xvs{dW^l2N>@pLVkOV0%B{I&d?`eK;zX zg8z<@_snoMdk}`L;`QL2rV6)$uNz2)X$|ZEA9+B2Hrxdsx%Sc@#XqX-JMx%l-i4R8 zUU>P8c~@S3;qZ|ojv9IF+S;XYp?dA2^!0(CXV^|NEV#YgWZ|@w|JxMEjNQllJ0QyF{x? z&nepQ$1YKQ=@Uigf6^tIRqEePbUWs+DvcppIkCMovppUXZ)vZJT1rb`Ro8E+ijKIU u^kjQn*Q;ex95o#6zwZ1=>D~5t|9Axt0D70Y{~SAy{Va~&E;X)-_x?}q3QS`F diff --git a/docs/sketch_processing/sketch_processing.pde b/docs/sketch_processing/sketch_processing.pde index 6bf7e0b..41a43bb 100644 --- a/docs/sketch_processing/sketch_processing.pde +++ b/docs/sketch_processing/sketch_processing.pde @@ -1,5 +1,5 @@ /* - hoverboard-sidebboard-hack MPU6050 IMU - 3D Visualization Example + hoverboard-sidebboard-hack MPU6050 IMU - 3D Visualization Example. Use with VARIANT_DEBUG. Copyright (C) 2020-2021 Emanuel FERU */ import processing.serial.*; @@ -9,40 +9,32 @@ import java.io.IOException; Serial myPort; float roll, pitch,yaw; int idx = 0; -int inBytePrev; -short bufWord; + +String data=""; +String check=""; void setup() { size (1400, 800, P3D); printArray(Serial.list()); // List all the available serial ports myPort = new Serial(this, "COM5", 38400); // starts the serial communication - + myPort.bufferUntil('\n'); } void draw() { - - while (myPort.available() > 0) { - int inByte = myPort.read(); - bufWord = (short)(inBytePrev | (inByte << 8)); - idx++; - if(bufWord == -21846) { // check START_FRAME = 0xAAAA - idx = 0; + + // If no data is received, send 'e' command to read the Euler angles + if(idx != -1 && myPort.available() == 0) { + idx++; + if(idx > 20) { + myPort.write('e'); + idx = -1; } - if (idx == 2) { - roll = float(bufWord) / 100; - } - if (idx == 4) { - pitch = float(bufWord) / 100; - } - if (idx == 6) { - yaw = float(bufWord) / 100; - } - inBytePrev = inByte; + } else { + idx = -1; } - - // println(bufWord); //<>// - - translate(width/2, height/2, 0); + + // Display text + translate(width/2, height/2, 0); //<>// background(51); textSize(22); text("Roll: " + roll + " Pitch: " + pitch + " Yaw: " + yaw, -200, 300); @@ -52,8 +44,7 @@ void draw() { rotateZ(radians(-pitch)); rotateY(radians(yaw)); - // 3D 0bject - + // 3D 0bject // Draw box with text fill(0, 76, 153);; // Make board BLUE box (426, 30, 220); @@ -80,3 +71,21 @@ void draw() { box (40, 40, 15); // Blue Led connector } + +// Read data from the Serial Port +void serialEvent (Serial myPort) { + // reads the data from the Serial Port up to the character '\n' and puts it into the String variable "data". + data = myPort.readStringUntil('\n'); + // if you got any bytes other than the linefeed: + if (data != null) { + data = trim(data); + // split the string at " " (character space) + String items[] = split(data, ' '); + if (items.length > 5) { + //--- Roll,Pitch in degrees + roll = float(items[2]) / 100; + pitch = float(items[4]) / 100; + yaw = float(items[6]) / 100; + } + } +}