From 4224d0f4fb018bbe8e4872c61f50bb5c4dccd6c3 Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Wed, 31 Oct 2018 15:41:51 -0700 Subject: [PATCH 01/31] Added finally edited pixy_parser file that seems to give the desired output. --- libraries/AP_IRLock/AP_IRLock_I2C.cpp | 103 +++++++-- libraries/AP_IRLock/AP_IRLock_I2C.h | 1 + libraries/AP_IRLock/pixy_parser/pixy_parser | Bin 0 -> 8344 bytes libraries/AP_IRLock/pixy_parser/pixy_parser.c | 204 ++++++++++++++++++ 4 files changed, 292 insertions(+), 16 deletions(-) create mode 100755 libraries/AP_IRLock/pixy_parser/pixy_parser create mode 100755 libraries/AP_IRLock/pixy_parser/pixy_parser.c diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.cpp b/libraries/AP_IRLock/AP_IRLock_I2C.cpp index d0af466ac1..f30922d924 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.cpp +++ b/libraries/AP_IRLock/AP_IRLock_I2C.cpp @@ -32,8 +32,9 @@ extern const AP_HAL::HAL& hal; #define IRLOCK_SYNC 0xAA55AA55 -void AP_IRLock_I2C::init(int8_t bus) -{ +#define IRLOCK_SYNC1 0xAA55 + +void AP_IRLock_I2C::init(int8_t bus) { if (bus < 0) { // default to i2c external bus bus = 1; @@ -55,8 +56,9 @@ void AP_IRLock_I2C::init(int8_t bus) synchronise with frame start. We expect 0xAA55AA55 at the start of a frame */ -bool AP_IRLock_I2C::sync_frame_start(void) -{ +bool AP_IRLock_I2C::sync_frame_start(void) { + printf("\nSYNC-FRAME-START()"); + uint32_t sync_word; if (!dev->transfer(nullptr, 0, (uint8_t *)&sync_word, 4)) { return false; @@ -65,8 +67,63 @@ bool AP_IRLock_I2C::sync_frame_start(void) // record sensor successfully responded to I2C request _last_read_ms = AP_HAL::millis(); + printf("\nSYNC_WORD BEFORE: 0x%04x \n", sync_word); + +// printf("\nSYNC_BYTE BEFORE: 0x%04x \n", sync_byte); + uint8_t count=40; - while (count-- && sync_word != IRLOCK_SYNC && sync_word != 0) { + + int temp=0; + while (temp < 9 && sync_word != IRLOCK_SYNC && sync_word != 0) { + temp ++; + printf("\nTemp: %u\n", temp); + } + + while (count-- && sync_word != IRLOCK_SYNC) {// && sync_word != 0) { + printf("\nWhile Count:\n"); + + uint8_t sync_byte; + if (!dev->transfer(nullptr, 0, &sync_byte, 1)) { + return false; + } + if (sync_byte == 0) { + break; + } + sync_word = (sync_word>>8) | (uint32_t(sync_byte)<<24); + + printf("\nSYNC_WORD: 0x%04x \n", sync_word); +// hal.console->printf("\nSYNC_WORD: 0x%04x \n", sync_word); + } + + printf("\nSYNC_WORD AFTER: 0x%04x \n", sync_word); + +// printf("\nSYNC_BYTE AFTER: 0x%u \n", sync_byte); + + return sync_word == IRLOCK_SYNC; +} + + +bool AP_IRLock_I2C::sync_frame_once(void) { + printf("\nSYNC-FRAME-ONCE():-"); + + uint32_t sync_word; + if (!dev->transfer(nullptr, 0, (uint8_t *)&sync_word, 4)) { + return false; + } + + // record sensor successfully responded to I2C request + _last_read_ms = AP_HAL::millis(); + + printf("\nSYNC_WORD BEFORE: 0x%04x \n", sync_word); + +// printf("\nSYNC_BYTE BEFORE: 0x%04x \n", sync_byte); + +// uint8_t count=40; + uint8_t count = 0; + while (sync_word != IRLOCK_SYNC) {// && sync_word != 0) { + count +=1; + printf("\nWhile Count:%u\n", count); + uint8_t sync_byte; if (!dev->transfer(nullptr, 0, &sync_byte, 1)) { return false; @@ -74,17 +131,27 @@ bool AP_IRLock_I2C::sync_frame_start(void) if (sync_byte == 0) { break; } - sync_word = (sync_word>>8) | (uint32_t(sync_byte)<<24); + sync_word = (sync_word>>8) | (uint32_t(sync_byte)<<24); + + printf("\nSYNC_WORD PROCESSED: 0x%04x \n", sync_word); +// hal.console->printf("\nSYNC_WORD: 0x%04x \n", sync_word); } + + printf("\nSYNC_WORD AFTER: 0x%04x \n", sync_word); + +// printf("\nSYNC_BYTE AFTER: 0x%u \n", sync_byte); + return sync_word == IRLOCK_SYNC; } + + + /* converts IRLOCK pixels to a position on a normal plane 1m in front of the lens based on a characterization of IR-LOCK with the standard lens, focused such that 2.38mm of threads are exposed */ -void AP_IRLock_I2C::pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, float &ret_y) -{ +void AP_IRLock_I2C::pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, float &ret_y) { ret_x = (-0.00293875727162397f*pix_x + 0.470201163459835f)/(4.43013552642296e-6f*((pix_x - 160.0f)*(pix_x - 160.0f)) + 4.79331390531725e-6f*((pix_y - 100.0f)*(pix_y - 100.0f)) - 1.0f); ret_y = (-0.003056843086277f*pix_y + 0.3056843086277f)/(4.43013552642296e-6f*((pix_x - 160.0f)*(pix_x - 160.0f)) + @@ -94,8 +161,7 @@ void AP_IRLock_I2C::pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, fl /* read a frame from sensor */ -bool AP_IRLock_I2C::read_block(struct frame &irframe) -{ +bool AP_IRLock_I2C::read_block(struct frame &irframe) { if (!dev->transfer(nullptr, 0, (uint8_t*)&irframe, sizeof(irframe))) { return false; } @@ -112,17 +178,23 @@ bool AP_IRLock_I2C::read_block(struct frame &irframe) return true; } -void AP_IRLock_I2C::read_frames(void) -{ - if (!sync_frame_start()) { +void AP_IRLock_I2C::read_frames(void) { + uint8_t buf[142]; + dev->transfer(nullptr, 0, buf, 142); + // printf("\nSTART: \n"); + + + if (!sync_frame_once()) { //It just sync's the frame return; } + struct frame irframe; - if (!read_block(irframe)) { + if (!read_block(irframe)) { // Try reading blobs until I get a sync (Nope! does not work!) return; } + int16_t corner1_pix_x = irframe.pixel_x - irframe.pixel_size_x/2; int16_t corner1_pix_y = irframe.pixel_y - irframe.pixel_size_y/2; int16_t corner2_pix_x = irframe.pixel_x + irframe.pixel_size_x/2; @@ -155,8 +227,7 @@ void AP_IRLock_I2C::read_frames(void) } // retrieve latest sensor data - returns true if new data is available -bool AP_IRLock_I2C::update() -{ +bool AP_IRLock_I2C::update() { bool new_data = false; if (!dev || !sem) { return false; diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.h b/libraries/AP_IRLock/AP_IRLock_I2C.h index 862274beb3..beee279b2f 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.h +++ b/libraries/AP_IRLock/AP_IRLock_I2C.h @@ -30,6 +30,7 @@ class AP_IRLock_I2C : public IRLock bool timer(void); bool sync_frame_start(void); + bool sync_frame_once(void); bool read_block(struct frame &irframe); void read_frames(void); diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser b/libraries/AP_IRLock/pixy_parser/pixy_parser new file mode 100755 index 0000000000000000000000000000000000000000..a897cf89321d075807e6a639a3c67ff80e4ab42e GIT binary patch literal 8344 zcmeHMYiwLc6`u9RiQ~lUt&_A)(vqblD1mz8B#qjhR|Xh>H;9~D1FghG#5)|(N%8PNls7so&`J{}uCy<*QxJE)BdD9ds=cGZe=ymx%!+_=#V9@Y0LlZGQD;rsb=%Z!}Dgy)nbOc&PfJ zO9x4YDoC#(tf2zVepbRiz6|~-;URjwB}+ia3le`9J@;0?6~%9m!_}fj3szo@=8_p} zNSWr~Sj-$sW@4%2nFO&cX6CI}&N9=nWJVq8>5jIWyTiM~dzIPUd)SO8a*5$&-b&

1;+cOn~jy3fFHrtGno*Wv>=_(%;B}Q+pe< znH>wHZ(LaL8^w9!!rX&~?`7lig4IX{FR!)@u4RME*_$}{3W=%0PGj=m_qo=`{;V~g zIrt;u=IUt3a|ZpqT>UNLeeBKzJNE7@nWXWsc>lE_lHeM7_f2Y?W{J5A3#AePU*r0V zR6o~0J9IAc*~rQ6;_oAU5sKBezpd1vXkz+Mq?JPe^^35z82zCV;KU2Tv zi!~GK!A%c*V$W8+4Y7U)J!2$S!*Wts_Yr!|kiTq8MFPPmtJ>>Un&c3%tn(#$Ca66@ zR7C^9=c}TD#^?NRw1-6yeHh; zw5z3{**!aK;1-tnT<0sF>z%@W%AIfycH@3!VWJ%kemY5FojG8#U#+md-1tg`b?C-d zDa?->uThv+H@;e7{kZYk@;YM1E#n&sELa5>&o{bZu#{J`+ytYK=&abC#36sb*I96>umJ%TPo*2H{Pg% z6>;oRi_-kQtx*3cEh2V}_q!?;Q0G1I3z2&due6<|^Yt5%$9F)p^z){! zEL}hE5$>xnzqK@g28w@3))ijkO@xQEE%(n^jW1mfE!vJ-mN|p)Agv$oI$5vfm%bNA zm$5Ur4F0&-_pZ<92@frGM}33vJF4zd*e@aSW5&r-ypQrZP(LS}<8xjGU|MI5?9eEtlwMa%|ijjpg!*9C>D%T_+-k zJI&4`9VT6Zxy9qk?0EP{r-@59IS=Mqe?SCfy_=WPHU~@!rsVQ|We1h4bTSD>gvX z%Gq=THM-_ZtTke8XnFPYbD0$mlqicWp((&i4j>=BXKeU&Q`V8 zm#u+1^$<%Z2gxU%y)Z>kg=uZ4X}wl>iT($O^KyFi%6F5kvay09FNbNCb(W72!&@@; zW8__+A*V3av0nk+MHQz$@-tBEGm!V{cTmH1%7xKC@;FfVkI%FBGk1ja`K$o_X{mtD zP#YKC_IT{jM_zxDFwViDkGv2R=MfUo#T&mCjxdgid{)Z&EzXtn z1$PxOU&c7TPJQITpy(e8h$rY*Jo?C&LE$g-!GnI?qmSCs2t4_f0HKjH?nuTX_^Xq;n_C*prX zuRM6r-;!>-R|q3lJ3Q)&CC%)g!C` literal 0 HcmV?d00001 diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.c b/libraries/AP_IRLock/pixy_parser/pixy_parser.c new file mode 100755 index 0000000000..dc04b4fbf4 --- /dev/null +++ b/libraries/AP_IRLock/pixy_parser/pixy_parser.c @@ -0,0 +1,204 @@ +#include +#include +#include +#include +#include +#include + +#define PIXY_BUF_SIZE 32 + +enum message_validity_t { + MESSAGE_EMPTY, + MESSAGE_INVALID, + MESSAGE_INCOMPLETE, + MESSAGE_VALID_SOF, + MESSAGE_VALID_BLOCK +}; + +static uint8_t pixy_buf[PIXY_BUF_SIZE]; +static size_t pixy_len; +static size_t sof_one_byte_index; +static size_t block_one_byte_index; +static uint8_t blob_buffer_write_idx; + + +typedef struct { + uint16_t center_x; + uint16_t center_y; + uint16_t width; + uint16_t height; +} pixy_blob; + + +static struct blob_buffer { //Frame (full of blobs) + pixy_blob blobs[10]; + size_t count; +} blob_buffer[2]; + + + +// - Write Buffer +bool write_buffer(const pixy_blob& blob1) { +// struct blob_buffer* writebuf = &blob_buffer[blob_buffer_write_idx]; + struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; + if (writebuf.count >= 10) { + return false; + } + writebuf.blobs[writebuf.count] = blob1; + writebuf.count++; + return true; +} + +// Blob buffer indexing swap +void swap_buffer() { + blob_buffer_write_idx = (blob_buffer_write_idx+1)%2; +// struct blob_buffer* writebuf = &blob_buffer[blob_buffer_write_idx]; + struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; + writebuf.count = 0; //This is probably wront. But helps me get rid of an error!!!----------------------------------------------------------- +} + +// - read blob i: + +const pixy_blob* read_buffer(size_t i) { +// struct blob_buffer* readbuf = &blob_buffer[(blob_buffer_write_idx+1)%2]; + struct blob_buffer& readbuf = blob_buffer[(blob_buffer_write_idx+1)%2]; + if (i >= readbuf.count) { + return NULL; + } + return &readbuf.blobs[i]; +} + +static enum message_validity_t check_pixy_message(size_t pixy_len) { + printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); + + if (pixy_len == 0) { + return MESSAGE_EMPTY; + } + if (pixy_len >= 1 && pixy_buf[0] != 0x55) { //checking if 1st byte of the message is 0x55 + printf("First block not 0x55 .. Message Invalid!\n"); + return MESSAGE_INVALID; + } + if (pixy_len >= 2 && pixy_buf[1] != 0xAA) { //checking if 2nd byte of the message is 0xAA (Combined it verifies if the message is 0x55AA) + printf("Second block not 0xAA .. Message Invalid!\n"); + return MESSAGE_INVALID; + } + if (pixy_len < 14) { // Looks for at least 14 bytes i.e. "sync+blob_data" = 2+12 bytes) + printf("Message Length less than 14.. Message Incomplete!\n"); + return MESSAGE_INCOMPLETE; + } + + if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { + + printf("2 syncs available and size >= 14..\n"); + + if (pixy_len >= 16) { + + printf("PixyLen Greater than or equal to 16 with 2 syncs, calculating crc....\n"); + /* check crc */ + uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 + for (size_t i = 6; i <= 15; i+=2) { + uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; + crc_calculated += word; + } + + uint16_t crc_provided; //Getting true crc by concatinating 4 & 5 message fields(original crc) into a single 16 bit + crc_provided = pixy_buf[4] | (uint16_t)pixy_buf[5]<<8; + if (crc_provided != crc_calculated) { + printf("CRC Failed Message Invalid!\n"); + return MESSAGE_INVALID; + } + return MESSAGE_VALID_SOF; + } else { + return MESSAGE_INCOMPLETE; + } + + + } else { + printf("Only 1 SYNC available and size < 16, calculating CRC....\n"); + + uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 + for (size_t i = 4; i <= 13; i+=2) { + uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; + crc_calculated += word; + } + uint16_t crc_provided; //Getting true crc by concatinating 4 & 5 message fields(original crc) into a single 16 bit + crc_provided = pixy_buf[2] | (uint16_t)pixy_buf[3]<<8; + printf("Crc calculated: %u Crc provided: %u\n", (unsigned)crc_calculated, (unsigned)crc_provided); + + if (crc_provided != crc_calculated) { + printf("CRC Failed Message Invalid!\n"); + return MESSAGE_INVALID; + } + return MESSAGE_VALID_BLOCK; + } +} + +void recv_byte_pixy(uint8_t byte) { + printf("INSIDE recv_byte_pixy:-\n"); + +// Read 2 bytes + pixy_blob blob1; + struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; + + printf("The byte inputted is: %u\n", byte); + pixy_buf[pixy_len++] = byte; // Append byte to buffer + + enum message_validity_t validity = check_pixy_message(pixy_len); + printf("Validity: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); + printf("Pixy Len: %u\n", (unsigned)pixy_len); + printf("Pixy_buf: %d\n", pixy_buf); + + if (validity == MESSAGE_VALID_SOF) { +// pixy_frame_received(pixy_len, pixy_buf); + pixy_len = 0; + + if (!(writebuf.count >= 10)) { + if (writebuf.count != 0) { + swap_buffer(); //swap buffer + + blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; //Extract blob information + blob1.center_y = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; + blob1.width = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; + blob1.height = pixy_buf[14] | (uint16_t)pixy_buf[15]<<8; + + writebuf.count = 0; //Turn the count to 0 + + write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) + } + else { + write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) + } + } + } + + if (validity == MESSAGE_VALID_BLOCK) { + if (!(writebuf.count >= 10)) { + blob1.center_x = pixy_buf[6] | (uint16_t)pixy_buf[7]<<8; //Extract blob information + blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; + blob1.width = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; + blob1.height = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; + + write_buffer(blob1); //Writing inside the buffer + } + } + + if (validity == MESSAGE_INVALID) { // If message invalid, wait and read 2 bytes + pixy_len--; ///----------------------------------------QUES---------------------------------------------- + memmove(pixy_buf, pixy_buf+1, pixy_len); // This discards the first block of the pixy_buf and makes pixy_buf have everything except the fisrt block value + validity = check_pixy_message(pixy_len); + + if (writebuf.count < 10 && writebuf.count != 0) { + swap_buffer(); //swap buffer + } + } +} + +int main() { + uint8_t input_bytes[] = {0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x17, 0x01, 0x01, 0x00, 0x69, 0x00, 0x56, 0x00, 0x27, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x17, 0x01, 0xF1, 0xE0, 0x09, 0x10, 0x46, 0x00, 0x27, 0xE0, 0x00, 0xF0}; //array of 15 bytes of SOF + uint8_t input_bytes2[] = {}; + for (size_t i=0; i<=sizeof(input_bytes); i++) { + printf("Calling recv_byte_pixy : %d : %u\n", i, (unsigned)input_bytes[i]); + recv_byte_pixy(input_bytes[i]); + } + return 0; +} From 9f1cced2842c07803921345c956f6590da99fb59 Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Wed, 7 Nov 2018 14:34:20 -0800 Subject: [PATCH 02/31] Tested more edge cases and added a feature which tell how many bytes are needed to complete a block/SOF --- libraries/AP_IRLock/pixy_parser/pixy_parser | Bin 8344 -> 18208 bytes libraries/AP_IRLock/pixy_parser/pixy_parser.c | 104 +++++++++++++++--- 2 files changed, 87 insertions(+), 17 deletions(-) diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser b/libraries/AP_IRLock/pixy_parser/pixy_parser index a897cf89321d075807e6a639a3c67ff80e4ab42e..6ea4e6c399d4ef05080a115d9ba1e474092ae28e 100755 GIT binary patch literal 18208 zcmeHPdwf*Yoj-RblT0$?0ZA|clna7FF;5VA7|DYR6Ach~Ra6`%$s`#`X3}{CaJQNo z5o3sgcDrb4p+&8=+SSzsG^j!9P^;Ub^?{YPlm$0{+SFImDrUdG^SGIr4DEjQv!BoY zvnQXqzw>*Z-}#-#J?GqebDL4K$f9XXB`dp%5!R6`DCLr|`zo0MC}(q6Dz1~+Bt~LM zoF@3?0)Q*hpfs(ZUDB<9q&LSR2=Q=&lv7Z7NYEyEiNLh+f~p{6Iwz1G`MTpmjsogD zqu@sA#}0CgC!Jr3OnQ$>y+@^OIPudD6G;H=jQ+?8u2G=xOrdsj6&mQb2c63LVQiRjbMLtlIzdN=4ge(`Am2#M@J2)Z6G47?b>$qDET z?NCo)pUv9Bp&)a)f+2VPdRKk(dRL>{+d|a(W_N(K1-!mcBlz_j-L6Kj&)wp^#lu=X zt*!oc56EPPbORw*tJ~{ii)*SYt6Zgpv&>v+;pNO#y>f}G!4vQ_d4nNOVC9mk7QfH4 z(p}d=Hkw-fK54@xL=y^%o?t=yTX>(Kexdq?hMWdm_0JryH=TOQ8c7R}^QMw?y^Mt# zziQldqzJ}tIZhS5T+;2j&IJ@*;YTM5I*lRa3ke>NqDPOf{wTUMP2y}IiVjE3G#Eus zGpUR{Dd}W`>aEiLD7rZ%f!P;DS7V=aejY`So*$1y(N&#E-r4zq-PvtBm9I1B=Dv_+ z=!moPXZAyE=<>Tk8k)Kl*UX9K$PwO5DyNSRAx*uVaB}tZ5su$NIECzVAIAfPlgp={ zSt4UkpN9^18m&bfomu2Z3WR3(j2R3&}w(DBB?%!zk!`)dzTErxNJ%qPK~ z%g1mt)4zhg^WaxjXV-x9VE+QA7ID7*RVWVzU(XW;N0Gtv+3P5K7h)`2tPe+yeow!77PXX7+oepyBlS43x`jGhA(~Xdzob#|TNL-ZO3vuUMV=$QK z?8*HOA>GEHQ#%p?x6>HZ&c5e7Y`YJ1O54^R;_96rWM%HP-34mq-acpj5ogyC=fUF^ zs5!Mhx*j}kg}E(c4pMPOlzY2n;CVZqs5UdvgxnXD6FZF@!esXM#A*$-cjUBG?ivdyOKUdV#^ zqF|oCA}>HdRfNKWQk|WHsqHDeK4;s>S7&!^t$<7Vo!zOXEdF_u>lf?Y=r4o*DSKT&(B z^Mp42rLH4)*?z~Fws(XK55m)CK~H_jgYcYSo<9iBLLfQ_hs$euYo19M@b$u6B7b=K zH<;y@i1O#1U*Y^dO^x%38fLE1ACL``O)cQ;$$6O^PU9gz zeHhaVCxj*;qFuQv4PU&y$h-X-Oy!$2e{%q!sxl-Eag{_@wMp|j(_nFbDz**=g(=Qsx* z%=PDR7s>MPDEnAw;eJeO%JQE~U(CgU@AC?@rP%-5fk_Pd(DuMI+1T zZ`6#Fn5G6SXZOL8_qbGF=HA>lc0tUBi=v4{lEXUL0O%%w*BOy*~`nj2JbRn zYjAcaO`S%rV=gX1glw;lp@{yC$@>=&5W^kQneE%ax?alMYrMwYc^+j7cY-Jw{18dg zEY+3k<=Nb;0W$Y4dF`%IS>UfEV%OpR4h;4#<5;(GjN5tGv@=84xeRig^Lvvsnm9dW z$4mkv!eQe$szcr9c-DqObf4dhMhV@cZHJK}8nID5$ zX)@==GCu|LQj>X6Ec0{jo1AXZ^q=E?0`MvBB>*4eJ^}!Wd7nIt6_{w9w?3!XVHhFw zXArjjuTbf;&5HC6k_(txka}l729iyuY(?X2jU6MT|S~+rlEoUCj}r3-Ipc5u+P$>y(Jm19(qy#JCr58}znA z@4jsj<9_IT8^3=7{X3^3#yB8r4i#NfRCfxCjfs6y?=q;lhAt#I{*5oi1GCCi1AEn z#Q3+Yh_QE3#MlS9{m^?B^yiT89f%kQp!YoVUVy(ZLaz_MgW$ace-8ov4CTEH7=gcs z0e=pEUjh6D^j?MDYtZ|5==>7DUx9uEdanb%0li-Xz6rgz0N;k*JAg-__b&8)gZz8Y zIR-y}n-(#CcRXVJ9)2DN{}14u$c-5PF*;(Lgx)FO?}PrI(CY_04R|IqVw{Ek2l#ym z{zqt+KLQS*UH%04G1}!5z)y=K#%H+wZf?V7fO@X8^Lfg)Zzys0tm<%fb4Khex*oR_ zF(&T#7~QUui)d$GhLw%ORw&D@l)Vc1{<$P7ED~qf;^F>v=&i6qWLV*ro!v{QV~*l? zDRfK+v|pjk%N^t+tN41w>guj{Dppls?>2Q&D&LwF5L{8wb*{SW^P1_W_+IniIcxux zKf(Ow4?}v%drH5i>#sFkpD*nCW5rO;F=yu?%{lkC;WM-sy276b&TctfStqT~d3^z7<0`u4nQ^S|(!@sqc=}g!40{p7{VP9w-cyyCtUk`Xg zUSE^G1ZN$(RMr(SBSo_zg#aY)R%aIL3fi!ulBX$1gBw=C>`Z{>ixck z7=?<8gbFK`Ez+x&Evc`^paUIwNWLi3YF@?O}_e|?rz5+79B6? zZd5ObGb{b7GOjFYUhCbs3AXjc0goF8Qo^=BpnJX%cDGPfN@nXDyeL^3yiBimx73GQ z+`RSc1NDVStZI3cz6b>&7Ruqc059{kY|=~g6>FAOCGzP?loM+jCb?%dL*5{lrs}t$vMs2rH)!_H)zk~Tp-p;Kvj<(J z%H7fe@dkZb@jOp!8|WqTyrQeoe!^{^O$FFiYlnZ=0URD5g4sDh3N-uDWpJ zJe|?FlJzMsFaK{1jWilKiBrX*mBw=2SW>%k4Q$KwH{{7mtWMfeuSt zg7Mb*ZLourBew9vp`inS4*{M8dmJo$1(M?_dkY&HviWDU*pz`U~;f4>>IC z%tX33;`bcNqqAjJk&$($r7Au77B~cy`2UFCyWl?xX!0$4xB&5Y;^#(OPQ~z#oBRWy zUxIj19EbI{nEYcP-v|Cqx{ey)BCJ+yCJ%QWHWl7QeOOq7; zO7K6zQtyEn{cm%9iph=Ox8V-vL7r7+WZi42%*eaPYGmj=NtGGXw%VK-#djt5c7E>s5bW%L9V+Jk)Bi`{{~`h%*o#mqmk?c&Ck1g- z%G01c?58=8(lc^`$rq^koKrp)WophCC;7WC)On7^A0@^A?5iPqWX5*LK_H7^eRLp$ zq@IQFV;SK5<^}i+F_CbJ$Wxw#xe_WM&9EKv`Ggv48>N7nCuQ~71(Mz&9Z~c?nk$f$ z-+dfocs?zXD*qyhD>+Qxyncu$C*katk!6n(g8y6 zoujtT8bD6_6a?Gnt+=u@>VCE_?#I=h_MephlJZ$;DTs*e9Od)U-lF_hl-JX$V8Av+ z`DuqAGC5a2(fTnb^{_9|CE1{GO0e8adqNc#5oLaU|rJN#%^u{sEkgj&wrCY82%T$04$IfmRLV zcE@sDZF$ES>rRxt&po3{j~yIrW!{n$0pVM?UKeF17_4 z(X-wld*vb@fS#>_=SQc2nY@L{9Q`6?@8a1T;C6Bs&prpmlyT%pIyFHd&@pWErKm#6 z_=|yzewG9-B7xDD5OpF^v!8&4l%)BfYNKugA%`D<=g@?x<=l^wEICJUwdULkN)k(d z7?Srwj#n#-lCpKwzUg{WV0e3 z*Fek@#5PGBYuCnI3;N}7BkkYG)c7ZHWod6yegfq!Xl< z2jNx<8A!bkm+Q32H-K?L^ByOBlr~%9`P;I&7F#3$ z1|VbOyiBw6erw%+{8l#p?Km0Yr%QhSt>^*|Lzygc-@^i51bhNrZln3Y{)=P1da258RepL!5mS7|Zr`xq0OIvm|HPeqHW6B>KWK z&@9_)@@q4My)psVD=2p&ynKm*YuR4Q@}JBUELG35QsVd2MJ?MGvhlykij^S!j|JC> z>CH|JGU;k^VjUH`RjwZR#sHey&I!1gT*N!$I#H}Me@HGV`0fHi{{ruG)2XlY@IJJC zW$t7O%KZYne*9>8Bf3`j!Ygr)u(oczE}8QsGuKAm+$(gi19AM*Qi2{iQ4(eSP)Mv6 zW&KECH;sQeL0Nl5SLb^Lb+5aPq`Od zZQ5L1)e?a3T#34K{5{e{fiyu~Xu6CjNsQK}W@J088RIiXYhzNfus*a*VGhStAfd~T zW!8*&j`@yi47VgnhX=Myh+tkJK&+HY7yQohU8AZ$kAf8P`dLsE>$$j8BuJ4afO= zF-((J($8ZsP7epgMlI(a6O&tiN8Hw9guK%fOL(Fq!sQ?Sn^tvZ^zY= z{0d!%HvDu!r==*{o@1%Zw(lzMwI2ZXPP@IyQju*hTeGI5(=sKS6MNTG^jb=CELFrV zDtTdKJP9LjvCPaS&~b~s zcUSN3-Fwb2vB}*iYHtw@&#g#rvO zRMK0KbN~$n*Yzbc`SGfYdIlaJv~wFJ%oS|*2SPA~w;`!V%z0O=cwMwT>h2@idxXaT__dd5D~cLZj2=ADtH65Ij2R`f z#0FC@XbpvZp0Xy7&lB+019b=Lo6E$D#(F`MUeL&2buGXdddO2B@&^inp#WmU_{lcT z#JSm^E97_alWi95E3Y~%uJ;7Q2xfQ|;8M>9JPoYb<85jViJ*slL2r}KgR^)FJYu$} zy2fy|wS+|kglV%JoPO!A5HUxTUy}7bkoS{ikj+$bi~gK zll{)?bBS6(nO@u7;18fzz!^~u>IytZ-tdPIF77rLAt$K&%Mgfpkp%1M=>s1Ou2%7c zin-eS2#*MHkeP81FC)jyr|8P1{Pkqn&32(kP^VDOXrR&NZon8P03Qg< z6kwJBct1Mq3kN;miUH1|MkqI2hj+8Xm<^~P)zqSu_#?LHnFzY|?L788u6R|OKlyX1 z-VMiu(*1;L#aYpL1P#Zs}H2f@NJ*pqSXNSk4z55&bd>yulCDm56kUTN)we_1p-nBNF`!f2Mr`fDOXU9y zZf6XelA!4m$m@z@RLXZAJ3XM2|18e`2SJamk#O$EppUj(!0d7Idx;K9 zYW`Hy{mYM_GyD z`330Yf4rR(+~;CF5e3tkBl#15BvcCeWa(Qp_!TdA?GE6X>-w5GVrzl5risw95J+jsdG>GD*OZjT zF1bOOWm3eZ00v5;4Uol>IV0Dzt?+o!@`@#f%UHV5MJvk~pRt5qxMpd^lIp5h4*#MK zBy4V6hErN_E?mxBi))ruR@AtbEn2j~Sm|0>QHd=D1aV-1eMm6Oqo=;!D=$}{Pi58wCJ~NE7=OWL< z7la5!?B|58hM?btH^&<2Q$yN2(YcF@R@>20qecN<7Ys@>d`&DrbBr$ypD(J`r0*IN zeyoUU#O||Wzo3jWIbtWn3WJ+ku|)w41q5tXIqYvdfi_l%_xn7B6_wQmA$OC+a9&kd z7xv=wT5kg@B&^vTY-WWGn|!b*AWkJXr`;0>di}l_#06f!)8ZxtnQLnau|gi6LSze@ z{6Isr5h|o{3L!u57KNT>IWn6YU_@a;RSZ#~q4Frf-RiA}Pt>al5qVaK>7f-v9yCu~ zxCxSOUlZmMiF$pFewBCE)df853d6U=9+gLwq9?ZhVV;%~nCh_>5lQW16r3RG3Xp7c zx)=y8&6K{{?Ekq)r`5RP)?w=R5rU-PGXgcQ@$tI}9D0{R`LFhE z3XYYU%6}!N;Ck@s-3*1R{hflvQa|2*NoKboLorqQeKNo%l!B`K`1;==^(&>E+Ak`& zF-o8660d&`XcQBMN-H zRb~{fAU#Zq)>rEy1xsmz6qQuDinIrrXnpm5l7jL%l@cE@etss6#W;Pn-&U}nDi@XF%YOwt3XvQ(=DuA0zlC^tg)8_Lbm?)c z(pUTU-EzyTvH<~m;&Dykf1Kn)kUL%R8 zk^H~PieIA!mNXJCORxSAExw-TE)xpLYT}I3S9S=-6~QI#r9xp)o_pv(>Fh*>L*0L9 jeo$?X>~O;S-jvqGF;%&OOMAk^`s>Ps#8q($aVYyQ`(HiZ literal 8344 zcmeHMYiwLc6`u9RiQ~lUt&_A)(vqblD1mz8B#qjhR|Xh>H;9~D1FghG#5)|(N%8PNls7so&`J{}uCy<*QxJE)BdD9ds=cGZe=ymx%!+_=#V9@Y0LlZGQD;rsb=%Z!}Dgy)nbOc&PfJ zO9x4YDoC#(tf2zVepbRiz6|~-;URjwB}+ia3le`9J@;0?6~%9m!_}fj3szo@=8_p} zNSWr~Sj-$sW@4%2nFO&cX6CI}&N9=nWJVq8>5jIWyTiM~dzIPUd)SO8a*5$&-b&

1;+cOn~jy3fFHrtGno*Wv>=_(%;B}Q+pe< znH>wHZ(LaL8^w9!!rX&~?`7lig4IX{FR!)@u4RME*_$}{3W=%0PGj=m_qo=`{;V~g zIrt;u=IUt3a|ZpqT>UNLeeBKzJNE7@nWXWsc>lE_lHeM7_f2Y?W{J5A3#AePU*r0V zR6o~0J9IAc*~rQ6;_oAU5sKBezpd1vXkz+Mq?JPe^^35z82zCV;KU2Tv zi!~GK!A%c*V$W8+4Y7U)J!2$S!*Wts_Yr!|kiTq8MFPPmtJ>>Un&c3%tn(#$Ca66@ zR7C^9=c}TD#^?NRw1-6yeHh; zw5z3{**!aK;1-tnT<0sF>z%@W%AIfycH@3!VWJ%kemY5FojG8#U#+md-1tg`b?C-d zDa?->uThv+H@;e7{kZYk@;YM1E#n&sELa5>&o{bZu#{J`+ytYK=&abC#36sb*I96>umJ%TPo*2H{Pg% z6>;oRi_-kQtx*3cEh2V}_q!?;Q0G1I3z2&due6<|^Yt5%$9F)p^z){! zEL}hE5$>xnzqK@g28w@3))ijkO@xQEE%(n^jW1mfE!vJ-mN|p)Agv$oI$5vfm%bNA zm$5Ur4F0&-_pZ<92@frGM}33vJF4zd*e@aSW5&r-ypQrZP(LS}<8xjGU|MI5?9eEtlwMa%|ijjpg!*9C>D%T_+-k zJI&4`9VT6Zxy9qk?0EP{r-@59IS=Mqe?SCfy_=WPHU~@!rsVQ|We1h4bTSD>gvX z%Gq=THM-_ZtTke8XnFPYbD0$mlqicWp((&i4j>=BXKeU&Q`V8 zm#u+1^$<%Z2gxU%y)Z>kg=uZ4X}wl>iT($O^KyFi%6F5kvay09FNbNCb(W72!&@@; zW8__+A*V3av0nk+MHQz$@-tBEGm!V{cTmH1%7xKC@;FfVkI%FBGk1ja`K$o_X{mtD zP#YKC_IT{jM_zxDFwViDkGv2R=MfUo#T&mCjxdgid{)Z&EzXtn z1$PxOU&c7TPJQITpy(e8h$rY*Jo?C&LE$g-!GnI?qmSCs2t4_f0HKjH?nuTX_^Xq;n_C*prX zuRM6r-;!>-R|q3lJ3Q)&CC%)g!C` diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.c b/libraries/AP_IRLock/pixy_parser/pixy_parser.c index dc04b4fbf4..9245956473 100755 --- a/libraries/AP_IRLock/pixy_parser/pixy_parser.c +++ b/libraries/AP_IRLock/pixy_parser/pixy_parser.c @@ -1,3 +1,5 @@ + ///---------------------- Check all the " . " that were replaced with " -> " ---------------------------------------/// + #include #include #include @@ -5,7 +7,7 @@ #include #include -#define PIXY_BUF_SIZE 32 +#define PIXY_BUF_SIZE 17 enum message_validity_t { MESSAGE_EMPTY, @@ -17,10 +19,9 @@ enum message_validity_t { static uint8_t pixy_buf[PIXY_BUF_SIZE]; static size_t pixy_len; -static size_t sof_one_byte_index; -static size_t block_one_byte_index; static uint8_t blob_buffer_write_idx; - +static size_t bytes_to_sof; +static size_t bytes_to_block; typedef struct { uint16_t center_x; @@ -36,30 +37,53 @@ static struct blob_buffer { //Frame (full of blobs) } blob_buffer[2]; +void empty_pixyBuf() { + for (size_t i=0; i= 10) { return false; } writebuf.blobs[writebuf.count] = blob1; + printf("SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); writebuf.count++; + print_buffer(); return true; } // Blob buffer indexing swap void swap_buffer() { blob_buffer_write_idx = (blob_buffer_write_idx+1)%2; + printf("Swapping Main Buffer: Swapped to %u\n", blob_buffer_write_idx); // struct blob_buffer* writebuf = &blob_buffer[blob_buffer_write_idx]; struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; writebuf.count = 0; //This is probably wront. But helps me get rid of an error!!!----------------------------------------------------------- + print_buffer(); } + // - read blob i: const pixy_blob* read_buffer(size_t i) { + printf("Reading Main Buffer: Reading from %u\n", (blob_buffer_write_idx+1)%2); // struct blob_buffer* readbuf = &blob_buffer[(blob_buffer_write_idx+1)%2]; struct blob_buffer& readbuf = blob_buffer[(blob_buffer_write_idx+1)%2]; if (i >= readbuf.count) { @@ -69,7 +93,7 @@ const pixy_blob* read_buffer(size_t i) { } static enum message_validity_t check_pixy_message(size_t pixy_len) { - printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); +// printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); if (pixy_len == 0) { return MESSAGE_EMPTY; @@ -82,6 +106,24 @@ static enum message_validity_t check_pixy_message(size_t pixy_len) { printf("Second block not 0xAA .. Message Invalid!\n"); return MESSAGE_INVALID; } + if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { + bytes_to_sof = 16 - pixy_len; + if (bytes_to_sof == 0) { + printf("SOF COMPLETE!\n"); + } + else { + printf("Need %u more bytes to complete a SOF\n", (unsigned)bytes_to_sof); + } + } + if (pixy_buf[2] != 0x55 && pixy_buf[3] != 0xAA) { + bytes_to_block = 14 - pixy_len; + if (bytes_to_block == 0) { + printf("BLOCK COMPLETE!\n"); + } + else { + printf("Need %u more bytes to complete a Block\n", (unsigned)bytes_to_sof); + } + } if (pixy_len < 14) { // Looks for at least 14 bytes i.e. "sync+blob_data" = 2+12 bytes) printf("Message Length less than 14.. Message Incomplete!\n"); return MESSAGE_INCOMPLETE; @@ -134,23 +176,27 @@ static enum message_validity_t check_pixy_message(size_t pixy_len) { } void recv_byte_pixy(uint8_t byte) { - printf("INSIDE recv_byte_pixy:-\n"); +// printf("INSIDE recv_byte_pixy:-\n"); // Read 2 bytes - pixy_blob blob1; + pixy_blob blob1; //%%%%%%%%%%%%%%%%%%%%$$$$$$$$$$$$$$$$$$$$$$$$-------------- should I put struct as prefix or not?-------------------------%%%%%%%%%$$$$$$$$$ + struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; - printf("The byte inputted is: %u\n", byte); + printf("The byte inputted is: %u and pixylen is %u\n", byte, (unsigned)pixy_len); pixy_buf[pixy_len++] = byte; // Append byte to buffer - enum message_validity_t validity = check_pixy_message(pixy_len); - printf("Validity: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); + enum message_validity_t validity = check_pixy_message(pixy_len); // Call parser + printf("Validity Check Call: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); printf("Pixy Len: %u\n", (unsigned)pixy_len); - printf("Pixy_buf: %d\n", pixy_buf); + printf("Pixy_buf: "); + for (size_t i=0; i<17; i++) { + printf("%u, ", pixy_buf[i]); + } + printf("\n"); if (validity == MESSAGE_VALID_SOF) { // pixy_frame_received(pixy_len, pixy_buf); - pixy_len = 0; if (!(writebuf.count >= 10)) { if (writebuf.count != 0) { @@ -162,24 +208,41 @@ void recv_byte_pixy(uint8_t byte) { blob1.height = pixy_buf[14] | (uint16_t)pixy_buf[15]<<8; writebuf.count = 0; //Turn the count to 0 + printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) + empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' + } else { write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) + empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' + + printf("\n--------------------------AFTER EMPTY: "); + for (int i=0; i= 10)) { blob1.center_x = pixy_buf[6] | (uint16_t)pixy_buf[7]<<8; //Extract blob information blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; blob1.width = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; blob1.height = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; + printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); write_buffer(blob1); //Writing inside the buffer - } + empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' + + printf("\n------------------------------AFTER EMPTY: "); + for (int i=0; i Date: Thu, 8 Nov 2018 14:13:41 -0800 Subject: [PATCH 03/31] Resolved writebuf Buffer print status issue --- libraries/AP_IRLock/pixy_parser/pixy_parser | Bin 18208 -> 18256 bytes libraries/AP_IRLock/pixy_parser/pixy_parser.c | 6 +++--- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser b/libraries/AP_IRLock/pixy_parser/pixy_parser index 6ea4e6c399d4ef05080a115d9ba1e474092ae28e..9756c81af436eefabfa34381356209af471b972a 100755 GIT binary patch delta 3298 zcmZuz4Nz3q6~6cFkGsplEA9>LmF2h!_=R&lqPA*R48Mo zW@9&4S6pc`;?K$tg-O4m~ zhI{Wh=R4o|x%XZ6^>!L;r$-BD&{udyTVo;OsPTPxIdLvs5@IVmOGnK|KAW$JIA^zw zZeO;yJLOc)FWX+cN&!e&4xh%}=DS;5d8~;H(E~QK3{9Wo@)OBA^NFTC> z%Kj6H2!nhW1)+_f5!%YD1v?+!QzuEzu%Wjis5bP11+9{-H1z)UQJFLJ1|_)}@Jjd_ zaCl}sS0QA3EY$EkgmUv?I%)f@1TL=@A+8wY0zi%qz3UV_p9$`}R>89`Wav?yWBWBG z%>l51aD=_4vC?*SS+mFW#T+n3llE3qaqp?F4sC*}`mh@@E+e>JOSKY1&j0{D!N5#* zAe2q7xbM)yE1uv%)p^mVIwN7ky!>&|F71avKyXMh3eN=vPf!T3bDAWZ2Xq1j1$GDi z2Ft6lm!Y@6wv=`3OKqWsN_0AwtNSK5ZDO^$XI-@>EBThQDHU3FO9%e;hjIxM$2m9} z_r4MO^Bl-wHR8HO+$V@jjNw`U2Y@7zsQD?_YD8>vMV}E*cNsq-cvNQ432h=uXdP%y zfOrGI;|dM^I}(}90Mks0m5BBCf?m2M*TDvSePDqck@`GtyPGQd;C@A^2SEq^1Gvc4 z$1ug8Mwwp&i^%+&81o*mVR7a0Em-;~#FvAv4~iiZr{N4Cm;-}34Xu9z9f)gC>^8Js z!_eN+v*@E|_v2FS)3cFC{UARMdbrbSw7d6(4K3>huW2F~(rV+wa9D;Opur0p7Q6x# zysGQ0T%RBJM?k>+F!Y$ZSff6NzQ8*4h19|N^_HwBB=4C=y=P=^Gn>-q>!*{V-glE& zetdq~`!mqAUjAPFI{x#fWJvUk7831byW&@IzfWSvHQ9z^;3Hk05H#-lED)bwumRja zs6Z3mX^+V+ZcQ0tfGzJG)EmK`$7q7p_3$eZJeMdp_U{lvIm|5AfC@#F|T9j<>tre59G_N%@5Pb0DEA_-aT)KCN(AQ7SwttX8iE~je{}cUltm%)^joAN!DU4t!kM5 zU#V|ENgHsOR1JkC6|_t z-j76v-mN!ezk-<%$9BiID$i|))3J54H$PQtB~HP+0@r68p7|=zgUyBbuxo_Cydt#S z|C5yGl{qQ@j70juw+UAGaLFsM9)`93UL-OH>vcAp{zEQ&m+dyMq}9x4e%yTUZX^OH z6dReatAoEo?4~(8`798Kjd3Ix4{#ge)!YYuMaB;l>~~qkbliV4Yd^<*tYbhmJyfqPE39oa0nSL)VfqL7J#nkc@Dlvy(h zLKY!|wgaXbYJDEr9wI{yZi%iAaf{iFyyeg2{sMuDm*oV~f*?`_{V~99B*FyaRS1ED zb}ms7lAZ(fR7r8K@P%JWKZkN0T`SAx0k$PSEoTwM$`rn_mxx83BKng`X(1UuB2>>> z^NU><#vxo6{Nli|9CL#~J9Y3LKjy(CFJLDXzJ8Z!Gg^AEEY7#nl#W6B5XbpyOt%sG z&QqY{e4EWLCm;(UrP4x%AhT=;8NiG|jAYecXS(K*`Y>=3n~hH}dJX38z%3e+4tA9>O`&@QquQUl+DYj+^Q|!{j3f+enmPKjUd}>X6eNi>`U7i@bF`oB zT5E$h*SEHX&M|F~jgB#UQ42l5-YVJ%RI@OjV2uuU``QsgDd)F6f!?F}+7eR_9G{p3=V zl-hS7)_Avbx{WEP*jhbv(}n}oIwf=~qcVprQ>x5T*7by9ZS-svi!}Sb_mZrhdC%eA z?|#4U`+a}zy^oCTr``MMfh^kXwjI@GS%^Hc+#jAZjwULb@XC(StLEg^rhZ5EO5soW zd*|kt|3mvhr@E7ZA!VC|1a^{3_Ka~uDnn8v2Gb}793}T0)QihyiXd0jc zBkxp;(!a#E>sC?P^w?HRSP(Wx5KkTTK8}-?JYk8Wb>uj1;3f)6&i|$)oW;~O0PdFu$ zl{{R%D;|1vNe7K?oDY^TbC`p(XxlSEpG|`zwxiu~+3p(J6^HFw!43>cWTM@VftWAb z?%pt9fRw~+VM3JD<)9NgWGk_KaCbDs8w4Jw@6K0&z-$sgSzsa8-w%4_)E58)K3|-i zBT`>O@%XL{18`qL)VDzg{(fA7)W60Q4~Lj903tL0GR)iq7#8PUSpo8rW+#cuK&tqs;;W6}in5F6C?U~?NKP-F#`eDHziFn%{Ki^s+ zx=dzFt3&X^Vex%HgSXT#xskA(SICBH}8X3@ZpKhJ`6;3U+16(7F=3a>XduH5Ka0piFZr?DgJlJRf0-&YnL9 zeI`B$6m5GZReXCjC2TA@XU9)~0-hDL?Z>k8zIR%q9jliFKb+O~!(i3D;4J`4!l3pSICA~YlbY{Q)^5Z z)c!wsn-6vAhAf3WvDV2j_yId=C@g>FKmRNB1eE0S%C#2`J`k$wS+E!uCX~7+l)9RL zC0LiNaj6|_h0(lzE!egR6Ho&j9NqmSv>+Qz+k9}l)K(NbOlDkM>iK9`%ucUjK*SyR;a6J%!6AF)Hkha3#X-1P$V?P9fHxMh1HoVBKkBa1a zJZqAkQn5PAgY1=*eA?@|nDR4@JE3P6X*{i9Pg||@gs0PLS5ZBCcZr?G9n6Sxn%)Kq zt*X{)MJ{5(fHeL!n6;|9kg^#*Q#3)bYzQf*;HyOw6=ic!8Ly#9n?e8W2tss!MJmfl zn2GKZ%E>5my2p_%1?31`K{9R@<0g`*zJrvhb1Fg}KnCqWm}+Ty6SB=C!x9vUZY$bl zunQSETQZ+RL)G430tsWVr4jT;V0Op|6O3O$2pqI)shW_)G@z$yin7Y>e?IYdxYyIQ z!M*tado(j4O+&FVm3!)WV!0G6`;$^-AxVvdMzQwHe5dCV2=@&9iolVBxxt`aI`}3p zmM}>Vc2ea&<1}qVq#w)T+;yfz4Eh$@aqe2vWi&ne80a|nMssB}vJg_JEMx>SONEd_ zm=Wi$B<7R60y#q&%?3?A!n!&424cBlP)tG=NN`I*MMA6^0TM~8z%1%8ZYO^AV0;?x zRWdxn#XYit5?3?_;Fki9w zVXg^MbRrK7+I0{plw;qd9D4&v{{qjwpa|x1KwFqT%ksT~t03Z~kgv$PkS#~K*CD1= z31mjcRr{c6BVdg~{uIDUyNvLJ73b9<=Zu#T$zt7E+0^D4&5Gb?8N0arW9u^d2;m}B zkw1r-iyXl@(E9tLHZC_-6UUXrdj6T+9OmR+%LqHlO?50z=?YSvPctL=?bLiMs^C3)Jx;BJu3z%G=~D6_54 z(>lzGrNh&>zKo-r*eM~84zL-aNc-k;1$u<7D$U~-a#&O8I;vsEO5qsTOlgs}F8J=& Jv718be*vZytC|1+ diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.c b/libraries/AP_IRLock/pixy_parser/pixy_parser.c index 9245956473..5ce930a831 100755 --- a/libraries/AP_IRLock/pixy_parser/pixy_parser.c +++ b/libraries/AP_IRLock/pixy_parser/pixy_parser.c @@ -1,5 +1,3 @@ - ///---------------------- Check all the " . " that were replaced with " -> " ---------------------------------------/// - #include #include #include @@ -49,7 +47,9 @@ void print_buffer() { struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; printf("Buffer:"); // printf("[%u, %u, %u, %u], ", (unsigned)writebuf.blobs[writebuf.count].center_x, (unsigned)writebuf.blobs[writebuf.count].center_y, (unsigned)writebuf.blobs[writebuf.count].width, (unsigned)writebuf.blobs[writebuf.count].height); - printf("[%u, %u, %u, %u], ", (unsigned)writebuf.blobs[1].center_x, (unsigned)writebuf.blobs[1].center_y, (unsigned)writebuf.blobs[1].width, (unsigned)writebuf.blobs[1].height); + for (size_t i=0; i Date: Tue, 13 Nov 2018 13:12:44 -0800 Subject: [PATCH 04/31] Made changes which prints the block data bytes --- libraries/AP_IRLock/AP_IRLock_I2C.cpp | 43 +++++++++++++-------------- 1 file changed, 21 insertions(+), 22 deletions(-) diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.cpp b/libraries/AP_IRLock/AP_IRLock_I2C.cpp index f30922d924..c320a40c44 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.cpp +++ b/libraries/AP_IRLock/AP_IRLock_I2C.cpp @@ -47,7 +47,7 @@ void AP_IRLock_I2C::init(int8_t bus) { sem = hal.util->new_semaphore(); // read at 50Hz - printf("Starting IRLock on I2C\n"); +// printf("Initializing IRLock on I2C\n"); dev->register_periodic_callback(20000, FUNCTOR_BIND_MEMBER(&AP_IRLock_I2C::read_frames, void)); } @@ -57,7 +57,7 @@ void AP_IRLock_I2C::init(int8_t bus) { a frame */ bool AP_IRLock_I2C::sync_frame_start(void) { - printf("\nSYNC-FRAME-START()"); + printf("\nSYNC-FRAME-START():- "); uint32_t sync_word; if (!dev->transfer(nullptr, 0, (uint8_t *)&sync_word, 4)) { @@ -67,20 +67,18 @@ bool AP_IRLock_I2C::sync_frame_start(void) { // record sensor successfully responded to I2C request _last_read_ms = AP_HAL::millis(); - printf("\nSYNC_WORD BEFORE: 0x%04x \n", sync_word); - -// printf("\nSYNC_BYTE BEFORE: 0x%04x \n", sync_byte); + printf("\nSYNC_WORD BEFORE: 0x%04x", sync_word); uint8_t count=40; int temp=0; while (temp < 9 && sync_word != IRLOCK_SYNC && sync_word != 0) { temp ++; - printf("\nTemp: %u\n", temp); +// printf("\nTemp: %u\n", temp); } while (count-- && sync_word != IRLOCK_SYNC) {// && sync_word != 0) { - printf("\nWhile Count:\n"); +// printf("\nWhile Count:\n"); uint8_t sync_byte; if (!dev->transfer(nullptr, 0, &sync_byte, 1)) { @@ -91,38 +89,35 @@ bool AP_IRLock_I2C::sync_frame_start(void) { } sync_word = (sync_word>>8) | (uint32_t(sync_byte)<<24); - printf("\nSYNC_WORD: 0x%04x \n", sync_word); + printf("\nSYNC_WORD: 0x%04x", sync_word); // hal.console->printf("\nSYNC_WORD: 0x%04x \n", sync_word); } - printf("\nSYNC_WORD AFTER: 0x%04x \n", sync_word); - -// printf("\nSYNC_BYTE AFTER: 0x%u \n", sync_byte); + printf("\nSYNC_WORD AFTER: 0x%04x", sync_word); return sync_word == IRLOCK_SYNC; } bool AP_IRLock_I2C::sync_frame_once(void) { - printf("\nSYNC-FRAME-ONCE():-"); + printf("\n\nSYNC-FRAME-ONCE():-"); uint32_t sync_word; - if (!dev->transfer(nullptr, 0, (uint8_t *)&sync_word, 4)) { + if (!dev->transfer(nullptr, 0, (uint8_t *)&sync_word, 4)) { //I think this conditional makes sure if the I/P byte length is atleast 4 bytes + printf("\n1st condition FAIL, frame END"); return false; } // record sensor successfully responded to I2C request _last_read_ms = AP_HAL::millis(); - printf("\nSYNC_WORD BEFORE: 0x%04x \n", sync_word); - -// printf("\nSYNC_BYTE BEFORE: 0x%04x \n", sync_byte); + printf("\nSYNC_WORD BEFORE: 0x%04x", sync_word); // uint8_t count=40; uint8_t count = 0; while (sync_word != IRLOCK_SYNC) {// && sync_word != 0) { count +=1; - printf("\nWhile Count:%u\n", count); +// printf("\nWhile Count:%u\n", count); uint8_t sync_byte; if (!dev->transfer(nullptr, 0, &sync_byte, 1)) { @@ -133,15 +128,15 @@ bool AP_IRLock_I2C::sync_frame_once(void) { } sync_word = (sync_word>>8) | (uint32_t(sync_byte)<<24); - printf("\nSYNC_WORD PROCESSED: 0x%04x \n", sync_word); + printf("\nSYNC_WORD PROCESSED: 0x%04x ", sync_word); // hal.console->printf("\nSYNC_WORD: 0x%04x \n", sync_word); } - printf("\nSYNC_WORD AFTER: 0x%04x \n", sync_word); - -// printf("\nSYNC_BYTE AFTER: 0x%u \n", sync_byte); + printf("\nSYNC_WORD AFTER: 0x%04x ", sync_word); + printf("\nSYNC-FRAME-END!"); return sync_word == IRLOCK_SYNC; + } @@ -168,13 +163,16 @@ bool AP_IRLock_I2C::read_block(struct frame &irframe) { // record sensor successfully responded to I2C request _last_read_ms = AP_HAL::millis(); + + printf("\nBLOCK:- \nCRC: 0x%04x - SIGN: 0x%04x - X: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x", irframe.checksum, irframe.signature, irframe.pixel_x, irframe.pixel_y, irframe.pixel_size_x, irframe.pixel_size_y); /* check crc */ uint32_t crc = irframe.signature + irframe.pixel_x + irframe.pixel_y + irframe.pixel_size_x + irframe.pixel_size_y; if (crc != irframe.checksum) { - // printf("bad crc 0x%04x 0x%04x\n", crc, irframe.checksum); + printf("\nBAD CRC 0x%04x 0x%04x", crc, irframe.checksum); return false; } + printf("\nGOOD CRC 0x%04x 0x%04x", crc, irframe.checksum); return true; } @@ -243,3 +241,4 @@ bool AP_IRLock_I2C::update() { // return true if new data found return new_data; } + \ No newline at end of file From 9262b4c156d749f7727dd79b874dc74fd8eba94d Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Tue, 13 Nov 2018 13:13:56 -0800 Subject: [PATCH 05/31] Renamed the working pixy_parser so that it does not get confused with the refactored pixy_parser file --- libraries/AP_IRLock/pixy_parser_old_working.c | 274 ++++++++++++++++++ 1 file changed, 274 insertions(+) create mode 100644 libraries/AP_IRLock/pixy_parser_old_working.c diff --git a/libraries/AP_IRLock/pixy_parser_old_working.c b/libraries/AP_IRLock/pixy_parser_old_working.c new file mode 100644 index 0000000000..5ce930a831 --- /dev/null +++ b/libraries/AP_IRLock/pixy_parser_old_working.c @@ -0,0 +1,274 @@ +#include +#include +#include +#include +#include +#include + +#define PIXY_BUF_SIZE 17 + +enum message_validity_t { + MESSAGE_EMPTY, + MESSAGE_INVALID, + MESSAGE_INCOMPLETE, + MESSAGE_VALID_SOF, + MESSAGE_VALID_BLOCK +}; + +static uint8_t pixy_buf[PIXY_BUF_SIZE]; +static size_t pixy_len; +static uint8_t blob_buffer_write_idx; +static size_t bytes_to_sof; +static size_t bytes_to_block; + +typedef struct { + uint16_t center_x; + uint16_t center_y; + uint16_t width; + uint16_t height; +} pixy_blob; + + +static struct blob_buffer { //Frame (full of blobs) + pixy_blob blobs[10]; + size_t count; +} blob_buffer[2]; + + +void empty_pixyBuf() { + for (size_t i=0; i= 10) { + return false; + } + writebuf.blobs[writebuf.count] = blob1; + printf("SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); + writebuf.count++; + print_buffer(); + return true; +} + +// Blob buffer indexing swap +void swap_buffer() { + blob_buffer_write_idx = (blob_buffer_write_idx+1)%2; + printf("Swapping Main Buffer: Swapped to %u\n", blob_buffer_write_idx); +// struct blob_buffer* writebuf = &blob_buffer[blob_buffer_write_idx]; + struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; + writebuf.count = 0; //This is probably wront. But helps me get rid of an error!!!----------------------------------------------------------- + print_buffer(); +} + + +// - read blob i: + +const pixy_blob* read_buffer(size_t i) { + printf("Reading Main Buffer: Reading from %u\n", (blob_buffer_write_idx+1)%2); +// struct blob_buffer* readbuf = &blob_buffer[(blob_buffer_write_idx+1)%2]; + struct blob_buffer& readbuf = blob_buffer[(blob_buffer_write_idx+1)%2]; + if (i >= readbuf.count) { + return NULL; + } + return &readbuf.blobs[i]; +} + +static enum message_validity_t check_pixy_message(size_t pixy_len) { +// printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); + + if (pixy_len == 0) { + return MESSAGE_EMPTY; + } + if (pixy_len >= 1 && pixy_buf[0] != 0x55) { //checking if 1st byte of the message is 0x55 + printf("First block not 0x55 .. Message Invalid!\n"); + return MESSAGE_INVALID; + } + if (pixy_len >= 2 && pixy_buf[1] != 0xAA) { //checking if 2nd byte of the message is 0xAA (Combined it verifies if the message is 0x55AA) + printf("Second block not 0xAA .. Message Invalid!\n"); + return MESSAGE_INVALID; + } + if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { + bytes_to_sof = 16 - pixy_len; + if (bytes_to_sof == 0) { + printf("SOF COMPLETE!\n"); + } + else { + printf("Need %u more bytes to complete a SOF\n", (unsigned)bytes_to_sof); + } + } + if (pixy_buf[2] != 0x55 && pixy_buf[3] != 0xAA) { + bytes_to_block = 14 - pixy_len; + if (bytes_to_block == 0) { + printf("BLOCK COMPLETE!\n"); + } + else { + printf("Need %u more bytes to complete a Block\n", (unsigned)bytes_to_sof); + } + } + if (pixy_len < 14) { // Looks for at least 14 bytes i.e. "sync+blob_data" = 2+12 bytes) + printf("Message Length less than 14.. Message Incomplete!\n"); + return MESSAGE_INCOMPLETE; + } + + if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { + + printf("2 syncs available and size >= 14..\n"); + + if (pixy_len >= 16) { + + printf("PixyLen Greater than or equal to 16 with 2 syncs, calculating crc....\n"); + /* check crc */ + uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 + for (size_t i = 6; i <= 15; i+=2) { + uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; + crc_calculated += word; + } + + uint16_t crc_provided; //Getting true crc by concatinating 4 & 5 message fields(original crc) into a single 16 bit + crc_provided = pixy_buf[4] | (uint16_t)pixy_buf[5]<<8; + if (crc_provided != crc_calculated) { + printf("CRC Failed Message Invalid!\n"); + return MESSAGE_INVALID; + } + return MESSAGE_VALID_SOF; + } else { + return MESSAGE_INCOMPLETE; + } + + + } else { + printf("Only 1 SYNC available and size < 16, calculating CRC....\n"); + + uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 + for (size_t i = 4; i <= 13; i+=2) { + uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; + crc_calculated += word; + } + uint16_t crc_provided; //Getting true crc by concatinating 4 & 5 message fields(original crc) into a single 16 bit + crc_provided = pixy_buf[2] | (uint16_t)pixy_buf[3]<<8; + printf("Crc calculated: %u Crc provided: %u\n", (unsigned)crc_calculated, (unsigned)crc_provided); + + if (crc_provided != crc_calculated) { + printf("CRC Failed Message Invalid!\n"); + return MESSAGE_INVALID; + } + return MESSAGE_VALID_BLOCK; + } +} + +void recv_byte_pixy(uint8_t byte) { +// printf("INSIDE recv_byte_pixy:-\n"); + +// Read 2 bytes + pixy_blob blob1; //%%%%%%%%%%%%%%%%%%%%$$$$$$$$$$$$$$$$$$$$$$$$-------------- should I put struct as prefix or not?-------------------------%%%%%%%%%$$$$$$$$$ + + struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; + + printf("The byte inputted is: %u and pixylen is %u\n", byte, (unsigned)pixy_len); + pixy_buf[pixy_len++] = byte; // Append byte to buffer + + enum message_validity_t validity = check_pixy_message(pixy_len); // Call parser + printf("Validity Check Call: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); + printf("Pixy Len: %u\n", (unsigned)pixy_len); + printf("Pixy_buf: "); + for (size_t i=0; i<17; i++) { + printf("%u, ", pixy_buf[i]); + } + printf("\n"); + + if (validity == MESSAGE_VALID_SOF) { +// pixy_frame_received(pixy_len, pixy_buf); + + if (!(writebuf.count >= 10)) { + if (writebuf.count != 0) { + swap_buffer(); //swap buffer + + blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; //Extract blob information + blob1.center_y = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; + blob1.width = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; + blob1.height = pixy_buf[14] | (uint16_t)pixy_buf[15]<<8; + + writebuf.count = 0; //Turn the count to 0 + printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); + + write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) + empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' + + } + else { + write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) + empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' + + printf("\n--------------------------AFTER EMPTY: "); + for (int i=0; i= 10)) { + blob1.center_x = pixy_buf[6] | (uint16_t)pixy_buf[7]<<8; //Extract blob information + blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; + blob1.width = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; + blob1.height = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; + printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); + + write_buffer(blob1); //Writing inside the buffer + empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' + + printf("\n------------------------------AFTER EMPTY: "); + for (int i=0; i Date: Tue, 13 Nov 2018 13:16:01 -0800 Subject: [PATCH 06/31] Refactored pixy_parser to OOP so that it can be ued inside the ardupilot firmmware --- libraries/AP_IRLock/pixy_parser/a.out | Bin 0 -> 8776 bytes libraries/AP_IRLock/pixy_parser/main.cpp | 27 ++++++ libraries/AP_IRLock/pixy_parser/makefile | 7 ++ .../{pixy_parser.c => pixy_parser.cpp} | 84 ++++++++---------- libraries/AP_IRLock/pixy_parser/pixy_parser.h | 59 ++++++++++++ .../AP_IRLock/pixy_parser/pixy_parser.h.gch | Bin 0 -> 3053776 bytes 6 files changed, 131 insertions(+), 46 deletions(-) create mode 100755 libraries/AP_IRLock/pixy_parser/a.out create mode 100644 libraries/AP_IRLock/pixy_parser/main.cpp create mode 100755 libraries/AP_IRLock/pixy_parser/makefile rename libraries/AP_IRLock/pixy_parser/{pixy_parser.c => pixy_parser.cpp} (81%) create mode 100644 libraries/AP_IRLock/pixy_parser/pixy_parser.h create mode 100644 libraries/AP_IRLock/pixy_parser/pixy_parser.h.gch diff --git a/libraries/AP_IRLock/pixy_parser/a.out b/libraries/AP_IRLock/pixy_parser/a.out new file mode 100755 index 0000000000000000000000000000000000000000..af923f1458d7558a87b0dffb78fb95565b977a3d GIT binary patch literal 8776 zcmc&(3v?9K8NSI92(Qh8L{YJ<6iz`7O9Bys95kC`VB!f#c_>w3*z9h|YLd;#&MJ6{ z#>P-r1S49Ct+raNR;;aB+oozY7(0U6indl;wT%ikSgi5INqw;W{yX>I%uY5vwx{Rx z=FEQge|-1;bLZYWbN^hW)h^A?%M)BY;%q@u$tYV>p$vtmstTY&l#9{$JxxpzBO#BF zI@?}h1FUu#P)#!yD!m6tyz+co;l?S-kC7uJEKs(bFkWdHgMYxk$kDFJZwg&-Y`~*L$KCX3r6OB z6+DXbix!`9T&4OOZd}?_{EYk@<~GLa7L?6xjLd0_H77UE*<8M0&VsT)A|9A0@0;2u z-(@S-%AROgd8jDnNw`Qy_FXStaNn*OQyxe4Kubu}!a zc+a>hn1?Mlz%nt1bsu!oa_Ao(#{bS?^i9L)r$X%MKmkDF2zRK3GHp{~Cq$xe( zjR~!Z;tF#}h$eig5pKBDs1L;&5o36B$OxIy%`q^fP#yov`OwqM^WblUoPjj!NMp~&Jm4*m={c0(niPv+rH>GADqZrF z*l3!mMywGSn~N|fCLoYPk0|FQI%`ezQKBHjP2j)()X)6kfMsfo+b)+|qGUG{-DWoF@rThrVG?YiWrTh@d6xxvoq`Vh$eJ5mDO5d$X zy|6(~y{We!>R-90c1OV&gsblue-kMBjwNryD_y(|oR5m8R!h~r5Z3BD3hn^viw5-6 zVe@2!ej$knef;`#Z+)O>>NT?c^*t2zpo}JCDQV$QR=~o}6k%{QrN6eUsik{L2O1mwsZLOtUz1Pyd0c;0eQ)Fo! zd6u>f*EfZwUE5%3Dd2UhENwgR`stRo1Guxq(ry5Df_Ec$yE-lHCU9=X^)2XkAGWk_ z1NWS7X}18sGsDup3%qr%rQHVn9(dme?{?rFz#p7sX?KEq7p@<|es|2$?g9P?{Ck0W zzhY_k0e_5s?+5+_yq|*i0C*3A^U(X2_Oo6~dw8^^{oH41zgTK%zl2{Gc)x=F5!4^; zx3tH=`!#rvBi<*#>&CSYwkHv95AZ4U_Zy&vc%KIDN4y7s&w%$Vc+Y|NTX24d>v`x8 zg7*UOMeu$P`~!F|0sjcz%fMH_`xAJ7M*UTAUPGL(kFm7B^jg|q5oa&#Z@~6uv8BB= z!O{+acNp^9(Ekm*KHw4HJ4KfEckqwmdKdP8;JLg9?8kF?ANT>D%ZI>^N-XVTVRdY! z=Wcae3D|3OTqS40(;Y29S}^){S=Cb(W^GRarqh+5rPE!oz_fNCqR*csXNg(R*8#(U z9yx{DkNQ$uKT9PC+P8j|mz;O?)`4^y6Lc2Z=p2bQE`h7Qqxd4UhgGl@D$MmIB&DA2 zn*(E~-O%Gidx92r-(3iZW^T0*!3%=t*Q8z!t_@-EDP+$`-)ayO#APrYYO^(>}uwnAJD=w=VF3)l_Z4{QLwh?{u@Sd8%LeX;>K z88@^USPtw1w$Tlu(DxISyen3Tyv@G6Q^$=e?93bGBRzdHuS1)&$w8Ie{z6QLo&5KI zl1{HAU$1Yeck;PKV=pgk6X%?=_>B3}r;(cY7*5d-Ke`7l#Jw2T2k5VgZZ+ujZOgA3 zKhkq{K0=ahe;w-L7BgO zqj~*1MpSxdUSFVlOSX;Fz2)trmU}B&z2!k~Nzgm9((8vG{42eM^8G#nW496Q*iVES z`~MgIKH%>Ge*de-oOyS$Oy4S0#@Qgc)XQESPsAGa5`NHq{A@_@Mfzo^LHm&>ZE&hpP(TbFD$lm3N)`GJx-^A;wh zSbAk?d7z|hmaYB*4SO(q`CRXG_h3)t^KiD_BTOD}hk?G_c^*2{m_r4b`IoI9DR`b{ z>qiNGe%X3V0iNIvg9lj-o?i|%`W+*99%k#uX4Yf2ew;YS3&vsai1EUojdK3DvANPnM*sOQ4{(z}o1DRss3 zEcDdxR<-fUcPn(CDm}kXc;BV=a`jsTLmuYCXZ%8eAD3MIr^&#E&Z`pH&d~X=Ncx{J zWd5A1^!$F}KG(~3hR&Y^^ttjL*Fo>Yyz;r`)pYD5{v7k|M)*$vgVzi1-?u|Qje~ID z80aTroX=7(4*87(`(xBj{z-!OO{VNdzY}w;(*v>{_8P>Q(tmKh&sL_lhVj2d`VZY_ z(kdSJIE;mVuDlQ>*l66`>rq2HKFqgrHQzYWxzc~~ka1ot<6*Bs+$i;4(W~aC{C0!6 z1$zIWTc&os@?WXuKSWt>mHLcZrt;`8?L0G#{?IV(h;XZ!Fq8H5fv_0NgBfO%5vEL7 z0tu%`+}P9@uM0IA5i{PJFha@AA{=jOX^fiDNMPZDMU+*`;bb6b6*EGut)VSOwApOk zBI;X1O;IC~Y--v9ibFEsX=b@nYAX8Gh<=dV2n~`kdW^SHAj%M2CN3s<%znJOayroN5Yio=(!OB_< zts+Y(bAS~UGIyu4bVf81GDFBZo`-vg#F~v{B1)}NE|AlIih*n&<@hk_iMY{#d!uZn zBWdV%%g!$jTFbyf%9HOF!zr_ruDA?}%g#8$zb=vBdhTqen=SK|;Y3o7*S}A=+PO{g zrKy9?T)ED{$nD!7n#%o8(zV%via=sZlNqW5nyofAa4pu1+;EEsG{?zE@hWqF5ZARwvXEL9oxY-q`(ALfTZdGCQ)8L@cXE0Tn&*!uAp`$Y)^Ly0+ zk&(}paFInd$D-JP8lBmg&)@ls+z-dkevFrbPiH`uGv@(CSgCrV_{oRkS88zuDm13d z=W_!ipG&!a=5t)vD1N1Ckk1#48=RSK1HNFth4x?0_q>*B9{`Ep803E^xT{i zdG0w~D^&m8YT)QSGZz=f&-(|>Z;su`r%!w;qg_Vs*S69bAvb@tN)#SvM}= +#include +#include +#include + + +int main() { + pixy_parser pixy; + + uint8_t input_bytes[] = {0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x17, 0x01, 0x01, 0x00, 0x69, 0x00, 0x56, 0x00, 0x27, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x17, 0x01, 0xF1, 0xE0, 0x09, 0x10, 0x46, 0x00, 0x27, 0xE0, 0x00, 0xF0, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x00, 0x01, 0xF1, 0x0A, 0xE0, 0x10, 0x55, 0x00, 0x15, 0x11, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00}; //array of 15 bytes of SOF +// uint8_t input_bytes[] = {85, 170, 85, 170, 15, 1, 1, 0, 104, 0, 82, 0, 36, 0, 48, 0, 85, 170, 144, 1, 1, 0, 229, 0, 86, 0, 37, 0, 47, 0, 85, 170, 85, 170, 23, 1, 1, 0, 105, 0, 86, 0, 39, 0, 48, 0, 85, 170, 23, 1, 241, 224, 9, 16, 70, 0, 39, 224, 0, 240, 124 }; //array of 15 bytes of SOF + + size_t size_input_bytes = sizeof(input_bytes)/sizeof(input_bytes[0]); + + for (size_t i=0; i<=size_input_bytes; i++) { + printf("%u, ", (unsigned)input_bytes[i]); + } + + uint8_t input_bytes2[] = {}; + for (size_t i=0; i<=size_input_bytes; i++) { +// printf("Calling recv_byte_pixy : %d : %u\n", i, (unsigned)input_bytes[i]); + printf("\nNEW BYTE IN:\n"); + pixy.recv_byte_pixy(input_bytes[i]); + } + return 0; +} \ No newline at end of file diff --git a/libraries/AP_IRLock/pixy_parser/makefile b/libraries/AP_IRLock/pixy_parser/makefile new file mode 100755 index 0000000000..96a27f72d8 --- /dev/null +++ b/libraries/AP_IRLock/pixy_parser/makefile @@ -0,0 +1,7 @@ + pixy_parser: pixy_parser.h pixy_parser.cpp main.cpp + + g++ -o pixy_parser main.cpp pixy_parser.cpp + + clean: + + rm pixy_parser \ No newline at end of file diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.c b/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp similarity index 81% rename from libraries/AP_IRLock/pixy_parser/pixy_parser.c rename to libraries/AP_IRLock/pixy_parser/pixy_parser.cpp index 5ce930a831..4a5e6b0614 100755 --- a/libraries/AP_IRLock/pixy_parser/pixy_parser.c +++ b/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp @@ -1,11 +1,33 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +/* + * pixy_parser.cpp + * * + */ + +#include "pixy_parser.h" + #include #include #include #include #include +#include #include -#define PIXY_BUF_SIZE 17 enum message_validity_t { MESSAGE_EMPTY, @@ -15,47 +37,37 @@ enum message_validity_t { MESSAGE_VALID_BLOCK }; -static uint8_t pixy_buf[PIXY_BUF_SIZE]; -static size_t pixy_len; -static uint8_t blob_buffer_write_idx; -static size_t bytes_to_sof; -static size_t bytes_to_block; -typedef struct { - uint16_t center_x; - uint16_t center_y; - uint16_t width; - uint16_t height; -} pixy_blob; - - -static struct blob_buffer { //Frame (full of blobs) - pixy_blob blobs[10]; - size_t count; -} blob_buffer[2]; +pixy_parser::pixy_parser() { + PIXY_BUF_SIZE = 17; + pixy_buf[PIXY_BUF_SIZE]= {}; + pixy_len = 0; + blob_buffer_write_idx = 0; + bytes_to_sof = 0; + bytes_to_block = 0; +} +pixy_parser::~pixy_parser() { } -void empty_pixyBuf() { +void pixy_parser::empty_pixyBuf() { for (size_t i=0; i +#include +#include + +#define PIXY_BUF_SIZE 17 + + +class pixy_parser { + public: + pixy_parser(); + ~pixy_parser(); + void empty_pixyBuf(void); + void print_buffer(void); + void swap_buffer(void); + + void recv_byte_pixy(uint8_t byte); + + private: + typedef struct { + uint16_t center_x; + uint16_t center_y; + uint16_t width; + uint16_t height; + } pixy_blob; + + static struct blob_buffer { //Frame (full of blobs) + pixy_blob blobs[10]; + size_t count; + } blob_buffer[2]; + + bool write_buffer(const pixy_blob& blob1); + + const pixy_blob* read_buffer(size_t i); + + uint8_t pixy_buf[PIXY_BUF_SIZE]; + size_t pixy_len; + uint8_t blob_buffer_write_idx; + size_t bytes_to_sof; + size_t bytes_to_block; + + +}; + + + + + + + + + + + diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.h.gch b/libraries/AP_IRLock/pixy_parser/pixy_parser.h.gch new file mode 100644 index 0000000000000000000000000000000000000000..d6ce4239147433410b7ffd6742b89f682f564ca9 GIT binary patch literal 3053776 zcmeFad0?c=RUg{6*&$|!7%&z~z!!5bYDuHTc+*I&8To1?SuNd}G0R6w-I98y)vf78 zi){=99y|zyK-dC-up|V+P9P8n#KwL&fQ@O-GFZi8bYyWEND}L%1-|*d^{<*bh)a2j! zJB{S|kq$renc{ecgEb#cLzlnLs9h~DKEAl%C}nsOH1e~Y-#fdfdxVq`?wO>K@C^6s zqB?5nOBeoWP<01F1S`(+WzTq*#52us?4?njQ9J4MJHzf#B}earz|Y2CQ8b&oMRR{| zXZu!B%*=ltM&wso=J6C^<-i%rlN9X57Ydjuy4=3Z!Xl8D9 zc6oN?L*exS;(f5Wy`yR@>n zyfnXfV}1#QxrG~x%bmyPmp7PqP5;)~TCv$!D{kCaDb{xG>~1yg&CGpR@Rp*ToD4fB zt#PO5kJ@Kll&?NNyYP_+W6QT(?BCyQpnQ}5sC&}yv}cY^TSLBxMMeE?zOu2iQEY7O ztnM$*B3yluNxX-6qLx@WYtKJ=Z02a@qdsb8i;ePL;*Tuu`bQ%G+ovelyth}M zY81`;+iTLmt9y-Nb$h*N-d)`->NEAH9d_;=2)i&--@yB|)j4|B8{0d3cU(Vh4`{&f1g3#$E#>jQvFGI2r*nbFA7AlDN_n?jhrAn|D@GfKBp*`Vu>{b_E0| z8c)INPGkS}&N_Uh7wE8JKRN97Tf^(3*By6;tseOT#|;}-!yo}Po_zs($@3%!%vh9r z^h>ajvIGpo#FYPBw1(YQ8{Kl;IXmxRunHeqnq7E4f@p??4{d-A;jO+)xgHfB2V3mL z8or4lyZ5_c-R+NAL1nX&DF(Lm{Kw~KmmXv7DPP#w+}_-0KgS^4+1|R(8p>oET_MRd zD~XxVx433tewF)z_bx>5knwtZwds2p+Ng{iN*r^Ek44(r@~5p)(d{4gChgAi!S)}U zDT;_x6hdTbt~|;ckdsj4`DHd`JQmB0&M)8KYu*iiMIoF@SzDQT@*e!+~_>Mu(G(gfym^H zI&rg#nG@H&dxQQ-Id!44zdJ&{EB*=$;{N1nrq05I*2aKLIPc>6#ti&FTq0QRu-`1| z%ZrQkVxGf*or2;^QB3+>q|0hl5rkRd3?yx(Vgd)}0Vf!S0#myuL!q&^d8e_x5B{@u z@7^qhiaMEI7&Rg_#4-ySxc(T~UOW>b0J3wyMo8+{3~V%Y{V^6^1BH$YfyVdT`XXPg z152l0UxuaQlBb|rRGdNAcPzC&&j!(mZoZRTJ^%5di08k@XX=l!Be79rKw(%!!om#5 zTJ;g%+}%M|IUSd5lfzH@V_+>IFE{3=a$l4*;l4~pE90Qa7p&fFY!$nEjg3t<#mnFu zT7m;7>L^dlE-%bsj4jPAEZ?{>i*C9wJG-=SV{RF8>&U6fB;0`zCo;*_ABk zk`6Kd#Qfr1eHN^1zFx;$A?7a5;lCxkcxfILdSh;JmctyJi$g)X6z113o>rb%k$;U9 zjMa}q5RNLHKgXxTPOCj?9e2EZ*X?&jx?7%IOxO>bGhsjTPe6pJuYjM{mzU=jmKGMl zg65VNW^b&_&o6=})mN4w$AID1*`}O9IUt;{sVsAITV_knku4kiWS$mp&w``Nnv%Yh16AK&oFP8Jc z&COf48qNJ;b!+q1HfN>aA0#Iy!-P6QQ&XmAMd|=-cY0i8cKavA(V#yX4<|?C!BC`F z^bfvEGoyTol^Ktjm%_i~W;*k@Wk&sprIn>cG|2qI@*?D&8%wjxb+Fr|g}HgiK@gE4 z2X$V63~k92r#*%O{IGQiW-vsSRG6;Mehglt^~EWWvUK1rvsZq6a=zxjEoN9NfGpN# znNv;ZxvqLJ7gv+v3*BIi*3YP75tB8$j>|=}z{-NmmKqVc-QC{{oMCZcCS?7o#I+^*JMNvqdA?sl|SEY)W@-v4oiD|uo>3eMz z6YNZ#2`i75cVD!6lTI=09CwDD{*f-N7VERjonv`a5J6-smndvB^-~$f&u#N_FAUky zuB@GP{t1+M8Crrx3gUCi%Qse*>+GEMW%OIjFNCMGqnZqE@L}*WJcY-fOVp8Z-6z`s~siXGP67I?Vd!#zqiDeRcZ2u~l-D z)>#`}s$RCV%pKc1#s2NR#_D>L?0^$X<=tN41^Ik_F=1+)rj|I|w0{flk)Kkk^cm6T z))sq$hIR}~)GVSiBAZe6k!w%%xLGtOtJL?!^PubUx;(9LnZd9QiUwL;1nbJnMbpHW z%W747X;}*29TpeTu12Awi(dY!&Jc6lXe^8e5(ukS%T{(8*V*QlSu$-imhQB3RUG#Q zEebF7#o2lKYE;e)t2Z}`ry6_B&7JL;`fOdee2_-imn@qq6UUp=f=76YrS->qHL6(}Xs_VZ4%B2RKVKNl}fp1wdfKX+Bm$zI~Sxw&3!K+m@-0s#9) z+)QRoNo7$fW4M9kQ_{8JoXEnuLU62(i3syv#4=!gi|Omw+H2g}#Oi3TT!eAVXj~_# zde%XPQC79DqjFLz>o3e$v8+*H;F_hUt$d#s{d$?Ryw;p;t%C%7baQ)ab6cdYlELCfV^!vk)Z=c; z7AcBSGA)J5(dhttE^+lSTVVp@Ldi~G)U&-4{#4V(LThIfNnkwg&S2@jRIjrmI+2OH zGjXos*HJzyhi)Xcr_u~lPvYk|6t8CZthH|;DLY40r5g#*BDz~i3 zm~^aQgrZ+G4{mZ>j(b=#hs{1A+B>&2VrWf|l};{Z^eb_f-(r8z-Y#s+YjoiV+?t?9E&)D&AM8LQomvc4yF~@!)>mdGYgIEED5!CjXUfjtixW#8DZ}uSWwgOKi$yV;&CEU}|Ez3r z`~!s6W<%x!JF7?x4a}44>#XdOJ2>@6xs;(EU-=GqTg#VLnRdBs*xg&bb!QceP)z6) zaT@pbw^#3AHCoP2GVaT_l=5z~ajV#9Do4~V7Bj85Im>R~OBts4dbI9jg13<1YA7dK z0ln2tsZRF9O1(a}vb?akfK>og&$CO=fMcr~n@#i3gs;>W>+?|e-T*@>D=gYf^+lPV zV|$kMDf$c3)xm7pwUn`;bhc9APc~yppPOug1m&$TSXWq`^8Kvqg5rT2nYyxESt^%~ zo&zjLqvRzaW2hy{4_f2d4aVggOVEbTEiQ7G13Qem!RUA6Lh-1iirdW(K|Z&*6Gzh{ zw-?7*PDiE8el|OJY)fUi}W)lYvfer1Y$Cx)|5{-Ln zjop1LoY6zdTJvfW->QpIjS9<-)VhnQ9usYCg_WdERqZQ^+NZy1%PoeFN1m(Gn6P;6 zszrTKE1O$uCFcaTjhN?HrhYRK2=)+~cn*Cq73OXS>NGzJ6|Cd~c6O0`o@m#^YX;*WzwJIu+ zMk!>S!-N8wa_Xk_rA##LmT{M)TP-HE5BX7ohAq1T`>4K^CHGr#?4aNr)j2ls;EX1i z!Y9?nNh|D&=A9Nj*mU3DJD^R zPhr-V+c>Dh5P(He?&zc|F+L-=LiQIaY#848_UfOBC6lELDe7F8=hxTCOVn3&f5sHf zbya0qA`5wiwd>Hft7_?8wwt$iutS>c;Xt*^La-(^sInX6NoyH)ilUmNw66J*R(I|C z^tVO8QOc$lRWDy#&d*X>-`{o4(@w@tBxUqd1G_Ybv(`cIPKFEXI4(}vY1l(qSdERc zh?Eciz_6i=D;cw^IK0KTHeao+?HF?umAl5wwZ7V^$DtZuy@&mPS!x`$BeOG>>zznf z__X#hw;oFvyiA(Xhu(p`ZBCkgDlDk-o2hdM>d0ijT6Rk*)}+qtWxKoa2OBC@M#;5I zS43Z>pEjebNWa2?%)l1Vij?ig-PQdy>?Aw|3kYmrmFrWymL;qR<>c6bYmh5gPUCs( z7MEFNU!uU76K#?@6}I*c*C{4VR+m>sK!4i1 zq+BO++R{XB-iL{wvhb<;FcwP36>`Y7_Ssupph%#VE@Hu?KklBvOl3H1U5}ucSzfBo zal$L7Vl&CaJd^2^dPY=Eq)|wPMQpIZ^v_yKvSzfip=NyJzN0cfn@Pn*8Hr`jriWIU zh)rb`l(NSzOu)h6GYdErCYE~QQkTjeF1pHqahOHCyA%dAPfvftk^NE|fNdn3^PQ`6 zir6&OEPI%2HKHf64#V&+GX$Q(j-bQD@swaquuMrp`v_msxjO2cQzm35pmvVjs%)F8 zlwO(Rgaf<-${!WY&BTPv`*xb2V-~a;TrZAW1chS>G>aIz!r8;rg|+>Sge`LBs<1^y zPNttVEHw_e7A93|R9F*=zr(RS&!rz*r&N)RVaO&BF7hOaUqp; z**ko%^?cYr528Ka-Azg#b5wpL6LPXveg`(=z*SfjSA%XpJ)YTL247{5stJoN%HIJK zEIC!6lO<{c%LU~UQ8%Wt9o@Jbu#QnWd&L{2z~$F|rYBSyve|e=vDVz5xlytq&wSBO zLm}0GnzN&J1Hbf$laGh>EJCtvW$6ya_;=}@yr9Z@b`y>7spuC@`!6gxs%JCS#ImU@ z1_!GMaoXYUTHi1C(3h*yCi;%SGY@=PR&YI_}~iNo+;W9eK8a z_Iy+%2U|K_&M#7OU^bJb(w1GZG8wHwX^-ldEGJh4FfUojs5a4`rVpNMo>Z`pwyQYb zY5mJ0ArX2)>vMxFEb+h;issJ2-Wpg1*^I_!)6krtIBK0^wJlaFY?w;#gb@afKxV2w z-ZW(X|NUzui+>;28p8^wd-M<-x;w6Y-1uw;M}x3qaaMbxn8jb6f8r3=9N|2F7Wi|6 zKa2cX;?FXFR`A1MbBr~|SaSjyYmTwz7>kI2ZYIF^jJ{HP;R|ao>h@uw({0ZT&T-NL zdnYfct=3l0&wE`}w2x}#>auq8U;|yRR?024wc6SXUQj~^+A8)NH~|Hxw*)F~HTIh| zoLQY8>+SVQ)o9OHNbd(SFb5dT}*xRXXY;FPI zhdNI7l$tC@aWH2a=5wwO;|$)$&TeB{{RhJu_IYZu4^qsblD(^5L%Y{*Z`NqNxk#IW z;^qdnt8EqBdp+y6>EbXH z*ZAzb-#V*pbq|L)*HXK4vsgP2bzSXFZK(1bwLfX{7~ncJqTpn(bNc{^++_#w&*uK>{z0>LcXJ~Ou({!bY@&zV+FspaaJct(c6Y_Oy}e(% zyS;OJb^8{dcUL!ogEt+BSGx-%hCAXo*xuh;T|-pX&Cc3taT~7f<|gY)9Xjeg*k51W zyA^rvugfkuy!YAX9FM5UURuEcAZNgkD4R=9sI&HZs&c>JJ2Q+Oz>B}m$V%mqq`GQXx?w$SzX)PX$FeC2E)rxQh!ih@XhriO!BDoo4|Vq*rwP|fo@)`J0gdC2;qPUA>3Ni zdukQMZ0;-Yi|iCdk)u{aOQ374u{g}@TDSL*s&D5SowqLg-hJIaf^&eAVVx^F`fVu8 z2JlA8s|OhPz9X#ooh>-`uz#655~z z8YX7Mb1uACor}&fKNlR{53ElEVLe`x!;73v#jLnM4ROOeG>3txdwOei$8P80YF2&9 zY8Gy~yIbHChdXV;_vof`y)NXnm2fmR=S9&bN0%Nv#RKW*d?Z_?2P|bcFF1WtbfO532-h-Ph|OS1C5K+c&SF`Gg(h4kU@~dFx!jnZzAQ$t z9Q!*GaaK`LI^?;iXjGN(FW2X^b<1GY9#E|99&p^EOi^WFd9fZh4f7N6YM=Ug4FP^AT2&k~sr zX5VE&DRM&`h=z5s0a@mLv3?&Vg^~s$!zSi%&nINraLd^`$5foVUR~R1Ze(atkCOA* z!sBqZOJ;f-z6m3M46Tv|I@J9;C@0o(FlFE0d@3rGzGZ)Pd#;iciIucK%mu85LtWfF zfD-Vj%_d|4NR{_(R`+R>fn7q%N5*fhvAJbmLz;b!H+m~MEh-(=o2gxpZdZ~7t(s)h zl2~mJMC?n}w>H*9GV!BGUfsC4x_+mb^a5lECkVFJU{Q~mISsvbdvmKo++5$gV*~1y z0X7fNc8I)dQr+HxVd#^UBzBs+5yRB%ZtpZB9vEnlek*D2qxbBfAFbl3PsX=-uxqId zjit=p3jHoP?>Z!H>#++Vw?f<7*^fB6W^o_KTx~$opgOdjsj+`=|7O#6zsB9212PXB z0k!G)4Sfm~kQ~r(lpz)%prmbg54!m64H0vV$FA*Zn5=ED+5m^Q!APrwTif2pF(LEv zjmGvkXVV2wO%D4Xq9lgYg?G~ZBF-4O_k^* z+W1(1Z|<`0O$xFuPh08s{oNhgBZOvOBt-k7P0UVDnU`QW!0m=S70ZWo3c%n;1YKO% zMg(iDa8se#ya}-R8SLu$4@y40YQ&_Ut9os9EXtSVHn~Tga0;w|Hla`5EA-!U6 zzw%ztD&e45;mOttzl6*!H&xg^#r0E0j!+RjlgeIWZx7;Y^}Wu+PSGlVCd&qyER~*n z!9G-&DZ512{hf+L0_wpU_X0!^T9;kNYQ%dRxXY)KTNOPaf!@UB9f%K68CJDWmvFkq z=EUwUbObiB`#8tDvzFl@Q1=v@ySVcp69a0)RZ$EjV}>!HpAgkbHd=GNI^{7^vyo4X z1No_qOf@qO{PHik&rVvE75E~lh+Kj4vj(FasCF$aDD=!Y?qn(^Bd~*185^Y8rUR`) zf>kaKjoQraZ`t8{AU7-7a0lB^X{}eHA7pFbsg1i$h|RW#KGn>VvsBgS*lgUzvbfUo z?*^4wQmc3Opy0I}E4zLZqOCAYchxywh}Dp&@5(9+O4`gaOsKYEgjh*6x0EV!YpL9# ziL^>r5n}Z{I~Bvsv^ztav#T~U$9~!v&wwyRiJ$F@}EjBVU zt`MuKW+y^kE0(DQp;nT}iK<0bR#j>xft)-ErhpDushg}siLh0XQi+)aGD0P;w8#}V zD(qI5-!(VISHxAiAY68<{_=}mMKz?tQ9MQjH6bvk7mK>s-&G` z7ob%~A&I%zRa!=#DViC9h6=1IUsP&EB!FVD!kS5|W|YKAra-LFpr~7QcLRWz$=2#7 zH(pB#MJ_rjv8>L(j-U;Xh}&yh2kVVu8;ZOFf`Z%63yHWxvlYFc7y&rTBeyFU;=s=M z7I(^I2d8{hso*qf-qIu0Pp0&YZgP7^j}t`iaFk**>OnqO0g)$K>ICvD4pyUTgIQ1m zdoh>qGV8kZwt-VGn&3P{t zyiCMXRWPm6_gDAw5e{OFgHI*2Ql&{L5N>TXqN?ze?3Tms-j3|VhXi+)URPP&kt1wOr zf%09r0u-HLd-Ij6+=77u75mcL&0=)}J1l>9u$v9+@kLc(I+j3o^wpb*n7@B-yJ)U% z#1S2ZeXe{hH{f)edmo8xHzHLcz1FxHC!(eqf#SKck|rcucDEa`#?OTV6Ol`9GvU<( zM<}8Vs}M_eS+iblQ=polXzsF6f}ZH@`}$qVY^c(3YAs*TGQiXvrh6Q|tRnbl-^q@R zb?sEYNK5AvLzHA&%G1q$p^&Mf#e5B(g-#mjuS-wdCWB4Fn8S!)WtUVpKe?U6oyfFl zyrq~}-dL~dt`}dh4lY|wXk+a*go`u8zbk zu?;4*7BLmlQTdfrwl++l(C%p-AjClkX*43$J(Jvy7j#0XOiZLY!;WI_t~8P<9}RSN z?o|5)n+rxa(W;DT;dV%Dblu-<#G;0JXsMx=+}UgL&RD}An&6Qs+%CUfd0`EMEf z9`422TW2MLrrU_pf$va@DN2KNw|jv-U0PLfyMj$XYbuB;bU`+9W;w9U;m+8dJF9GJ z2lk+SEFo&;=GK!=-3t8+{}+>va$+rx&j%xDzsF32Zgt^$j{b!@FIsX#QLWgVNB)Cd z(&o;_P1MZh&Xzv5^?_-IvkgkP3CRLNpLarothCK-++U#1?VUAr9d5}oFr}K^E$s9w z)Qb+(4Q=kgfB?x^;l!b|A259lvfaSo)9w@zcgmdma69|D zl^G`{Y8tE)l6+tc;%Yh6mxOeR$g+dsEw`zR#}oVuwj7jL1r#?SPjWAj$afH5y&$ms zKH06thI9@HTQI*0RBV2_O1ZOoi*p8&5*L1(*zW^`#4DGOc_4Zo@Jx6?@hDGrOzJAN zYhf%wXDJ?go40POtGTvGv#<^K4p{Bpy@^}XBou+%)D$6oLG#JY-Mh|7p-=+sZ=waz zlQ;ng;b0r(*=W#Kk-38IY=c2wesE`ZpIfk+0Lc5k+|Z>q_SXFSr2&GMTt_RLolFb- z7Fu2=8#>xy>*(PG*OTL{w7l5eaX>4Fb$GjSjB_lc+!{SzrtaV&*RSESc1@j`;l>7#>0+g2>0&|Y2YTI z=rrDV8LmESos2XHV}=Zr{EV?3L!)!p;kj|Ck{0fO)u<$1R;c6Qb(*H;u6)O3x2?rJ zrmHw>T_1LM#W+SauKd7F=aTwKXM7YKX%XOc8T>AfQqRDAk?jYQvvcxcID4%T?v24m z2{d))(EEtf+t5qkv)1roN2{>kp+E`=5aGu@+*~y3k|)l1o88+z44lNz?;w zw7I%b$yzAh$>Q=kirt|ubw<%x<964@qN{*ew025_!L%Y_CZX8nU;NP;&WMgN%v{D#@Zb(5#8nUGPKAg4n0RjSLn;GNGpl#qq)Ncl(+IET)C0L zl?b+a{mB_)wR-2L%tG@}hHdk(*XpyoG>`h@VUG^EwTOI#^T6M#?!y zI32J_Jz^(qPR?PePsf#uzXi)>n6zy*&Db~ zHL!gc+F*tV^2m0hhSelyZJ4UUoDj0;_FyR257dM+a!uprj2d)++$e>Cm$T1R9FV`5 z2LZhk;za4@83Hjm$Bcv70utSR&D#r?e$6$A2WS-7c+-A%n^%end?gUcv>x`)K%l(g z64ww;J%c$T#f*W?Da;3WmeVlGDc0fi^>*RjB~e%ns2!~j%p2U8gWje=Nf|_^j%YrG zJN|ryaD!?M60K~J=}y`f?9L<^?vbe-G!rF??Y9kqGcR=zB!|5)0@}z+a`87;YF>A! zdIcvjtF?a_T~_QE0qw4GGr@k83%KMd8jh=d--eMBbpo?!u}ILT5ZtmA_rQrRqE;OA zF*w`BUS~8pL)Uh&`C#h-XeYSAll?rV9`re#Dm|EfI|p9jU8;LS<9dQrLs*VD2O@Y^ z**!`MZA6iTAw-eTG7XAgD;GmdvXNDw{(oe2y}a$DZg@ir6_nG_tDkWe7k$m zxPsaCE1To_*5RlfT&NdE1K)G5li&gyaWt@3=W?ka#U8wI+NXdX?~bYpy=zX0*t>;< zgwv2fYPidaz;FV>+Cj+SY6()&pR|X$8rC3NPr~>L#aB;;6H0L@za-we}n{w4q;N|1eTEL0#D-(juVS@_2mv5k}CFbq8y{WhBNqELU-V~B>9b-MvklzlCBLxSt$b{>*&T&hggYnP-h zsj1t>fxPVDV0N`k==q2&se|j|^8jwyhALZy^*$C#y4O;0)21O`AyI{fCdtd>pu#QV zL#ejcc!f`zYm(SqhT~$zp1pI~l!Z+7pj+No^g!fN$!p5kI{vLcCpgeT&1eC5y*|%Z z`Wsl8Bxz-thyo**ut;fd6-HfBGQ{Ommc?s3TL*WxJz9r}1hxiotdN~e6nh%1;=xfb z2^b&pjtpHGNtQk(Az?9@2+D87!{*WBkfIVojs%t&aWD;CzE-^L+jx^lv{&cLDq**= ztk>}ZHtv0HHDGK^^L*G}%K)N>a;V$5I+IA5(IyU5;uA8_$l2W5#bJL2LEnu>I3UIs zcqNpU{N#XmYOr$Laj5x87E`JhNxAEV=5>-OsQ1e#a%{x!KI#V|u>Qx{OZT-10UW#% zP?4}qL)xZxH40P>Q@9|FRaO)(df9;bjaJ_fq~jByz|_Bsr5ndI1Mpfzw^NG#DfJW6 zWD41lJJG1r(eM&rcU6i4{Wwp;xha!9-yaTzi3_MOTx@s7 zo-5)UTHIoQNY%HP^F$1#yH{XR!N59?PpM`8_zp9`-;?@SgT548H0EM?30X-G+F~E2t}oA zJh#D8p-Gn=zT(ME>Re3-@?2<^sE!UkPRZ{QB~#pkPSkp{(~GXKaOZ5x5KWkDb8huz z5DX~+=XFWc?+UQWUZLYrx;KU_DBdYuI>y@k!5dKeK}-m7upt}wh&|w_OAykVsjH9c z6is(|96Xxf2A;~WD)X^#K#}W<#bG4L82ZiCy}eDGo_PD-xtI{vP)qq#>6eQm9b{T0 zw}rqGrFqvjo))d#=5dQSmjG&!qX9>d<-t)JRTQC0GOoH{oq#MmAOkD#0*IFsLhtg5 zabY9n4vwbHTR7ZyL`jg~&1K$oNr8tHg3wAf$O<_MmQvOLB*kVChYf zGm}Tz)u@Q0%~)#?6wOF)U!?-ESsmYY+eZcoz=nAcRs~UVR}!f*7@}}wwuwTRVEPuUaqL%g%pU5E+}_X zz)8&l)-SvqgNV6Z;{_lDyvxFYqQLgBh-y+Ry5KIiB#NRqJCx0fVw_NMPyVO_t#?eM z8a!z9ic`FbH(V8})GM*m>j?qc>!NkoEyk@Ac|Y!nIf0(3kSF#($hXCP*6EMEn;TF{ z#SWB)z&?q-N8u&zr^CB(5o$+*Mpz@9wU1k8xY5E@bRAv7&G- zPC^pJK$XZLS)p=hR)`BZBFCK%*^@ev-6-y{MLy7%+H84JlC6>$XDd+SYz1PRtw4;j z#XU`F0Id(%nHzR^;oK>2kS=p+ed3%|{h|z3JfnP8{G#ku{Nh}512M{GAzfIDP|doh z#91zBQC0&n%3`2JSqro%OMw<;1^ctDF1Fp|_P(+zrLox?Go(0=AsjD>3LUAWM!77B zQ8r6rlut+GmbUMjfs}bU`b_5KpjKZFV)f-9R$kt3Ro_lp_4P`v6kf=c3<$N71EE&3 zz+LmS_}DzBWaUPyRtag9mxEY&HE5L=gI0O%XmV)Z0aEqFLae-*)XJ+#th}4V%FC~+ zg$Akmav@e;PHN@lBvxKdV)XLvNH)jCu%IkFF2RXq}bn@<5DU9ca;u11)+jzpsO- z@|YiLEXzK^t#B5`*%1Gv^D8CFfD)p&Ds5ntsZt^lhHtmGa3=2<|?UCMoVIp(UPbc#m7|-C$w7uA98Ld zz<4B|%ZVhf5DZ2~iC7doYzLO<)A z9f2Wa$Y%o>4rb`*Q^K>WYarUjF@p(U&8%ze6%c`#hIa5}I?oSDx zP2HO-R?@$ilKYFP<-Hi?qsZmKW%IQT@lnU9* z9D_6oFMb#aXXgW_Neb~!PGBYmfkmx{@d|1_^8*c4)Xcytyw`{5C$mMF(Elj=0=GAR_Dgky?M!JdLIepB1$ zYy2o31cY%Zh~qqgBPOFka2mmk2MLiBTq%`QQv!QZl1e z0=te4VY0~}l~hv#+AvAPbOP{0G_nn0USs=#L`q(Bn6RxQz@#j|NpRCdfJt!MK*W^* zHo*jUx)vt!;hp+l#r^mQAN5FsU!8a3DuREv62K;yV9FhC2JR0afW)a;zoI`#r&pjT zcHU1W@o7nyo>S9yLGp>qoIEY@(sOF!E=WFciWAe)4t`UU)(|G;?pcfb3}Gx1C+$T- z(mq`Fb&qu)B97S`BnbiHPX8!nAtXr)B~5#fz8oP^|KW(b!I0Y?Fftemi$|nYBBgz} z_o^h3S5=aDRhq!7(&&T!gE&55QY_#kIzC7Pu7K5D66yS!N~a7dO-q9vtD#>gHzp6p zK2GKbPAQI>REQ@hQ%49amu8nW>H?<)&~zUqnT=%%%al?fs=|`sou;48O6Q5>bOe}G z32+kod^kv&gE)-S=F5Kt^M5nAuKeDF8kiSJb> zS;%*Y5F4te(ag6V5EgITnJgL?x!xsI;`WLQAqMlq3heL9*t?T7HlWO(7&P&SJK5eAY@{0JVLb z{Zw8-;42gQDh-}2evZ%5wGVL`d=N{_*hFZjsSnyo@WC+FeI1{RRv+SBoMF|+R4LKn z+c1ufd1N;UnjYaz0w(?JeT&4& zyayJWotR1LXa-g66g~4UsWAf$)MRN;QnO*v-7KSlRbqG4o<`4SWYj*%CO>NDGXwgR z@YxKh3M13LPT`Sh;frzm(Of2m(yOg?f$lliu2zQ76RoJ$sM53Pbo1{$2R$2pH08ac zDd~V-od_;4T;?(pgrirdLtNX#7`Yt5C?L~o5gzn>_{D{3G3b+xGnx_u^la%!&z53p z!_gyKQ{XuHDyK(2#WeG^HqDVA-W7hwMGxI7m>-M^Qo{R zEH$gClUT_&h}G^vVl`y8@~|q+ya~i={BA$}O;Y37vc6qjX&+{SJXM^#o$IB$G^!I|DHnGLz<{ zS50#;tdEUS9u8eC>&lF6(F5`V2DX^zci82}GqmZ7B(r#y70pgUv6-g6! zXtj;f$>kGl!gd=5&b1=x$re^fVl*uyRVFEkTu#aNB%eIUQzK+rtKCLDPKl5Wo)4Vt z-nydp^OcANZ?zIZ%w__1snx(2Cz%EYF`L50Nv0Se<^szywwkt*r$(rDAc>GIz4%l! zq~s}YI2mWN1oG4f*({xmr)BA6oXrx*xi_4lYhPC1pyYgnt4!bKBr_%bD>)dFOw#8F zKFJmsGf*ydQnQ)q_H(I|nhh?qNVNgLr7`Q|qfC0IlWK*6F@v0a2YmA3rv>k2gZHKd zpJezJvIBB1J5{L+yQ8^)qgMN{nh~L9gP%^0tKDV*#NyV z&!3M-ofiDjG@t5pfON8zN_zIKQ`62CGuy&Q`!bvMWj^0SIc$^;uMvpZ;)9+^o75@6 zGx;92^7#fmoA$JP=URCx%m-pVZyu%}xA`XsKq(sm%L16=5UCV%2T?j!Jd=~F-icmXjk4Jf8YyzP{aYb=Q zuA9#7KJk`f?^|764hOx{%1{TfI)mVr>s-iTCZshN(p-|7sSza?{Yt$K=~Jz((cxjP zm_n|WZ&Q&k}5LROdlWV4l!6KeCTx_lv5RryM;Xy%1nRpcuVg`e6?ElLeJ=E9KF&47o8*AH8CzO>WkF@96aX|Lk}6o zkza*xlzvrZdGK4Pa*@(6F-S_^xA1n-T+XLSE1cpYqq*k`)pJU2)N?ssHPj*%qvLKx zEzM+U5q&WwRq@N@RqQ@IkFMGeB;HjPhv}!SU7g5+#IgB=1V~u7 z9VKZ{28wM{7{-!^0#m28Ya-Rl>0^x8Q&bB3@2SN$0^JtP7J#~$lwO}+vVsI}+ z+dmo6^iUzCU4^8i{zyox&l)j|NT}wM)Lg;rA=mB*7iPq5NLWwp0~WV_pCwRc@syVqs4 ze_d94(`B`W^}`xTPA{v4ysVb;(w;f)jxPO2DxyMGNDpSCmpw?#p&ul+&=2Zyz{F1Z zL1Lu*Anqd%l4gF8v~e%xMjTQp;8 ztCS>?SVBhi(Gx;q8L6b?-5DE84OLA$wX*Els;bmXwQ8z$qveQmohfUkusy@>dqPM` zCX}QUJQwyi6fE9Vi47V=jF~V&jkSiH$#S zEU*xo3?(PO;BUOsclS>oB!_Y8m|QNAJ+xZRo1diZ8Z zB_K}2B`21!<&ZlvACr@_bC|87G&$v^8XZ!SNsxqO3Iri8Bw-~9Qet^g0>v^W3HCKc z#$=Gni&GgBLE`!ajAcx~cwsrU1!Vkv^{8 zIJ{0p)<8?j;sYkBaoLMYlH&FTsdb#nfqhR)6LbM>g5v>>eZ>L^qbt$IS89^LfZvwG zU12AKaeQ`baQFbnk3`mwGK(*XVYnriJK##j?l>NjN-$?)lo-F*Q4-SN{0MA49%1K> zWRr8`T3TFeg+9bLUP-$ETj6)^wC9f#ZRSklC{=aym4*3jwDTTU}lUluF{!5qlMi{a4BXRO3v+%4;j+MC)yTsZ1 zQ%KLw65=t%2iLH42AN%+og~&F4f9pnOAM45&M-q^4cvErjn=g!{jt4 z-ZxAa7NAs023nl%l=hCui7-C89$jRX1fHBO3Ov;;3q08_4AOfF%ryn(mIA`KXA{Rg z8#sYhi7;0EKvWY-Ng|zce>QUhd^~6wMd)~7)l1`nRT4qCtOly6lAr{Rnf7>y@1n-J zBu)xWLY(W#lqr?;>_8Qdyw4QwHJQe}#3P>+zG#UH`HWV4q94Yj_B$%0qw*foWPo8~ zl$V{k>CN9gsbg(2g>jLd&(KuHg#~ZA1W`i4t)(cJ5w%FieRahQN;)z?FoOaVJ0AQc zd+|&Cmw^MuCvwyT$&u=E;Q{P$G7Qf zjF?j1uj{|CevI{IxB*!r#MfLNVVNqQ^v0{r7rm9DpPeq<(WSdb`b~E3Zpq{j@Bo+X z$rl=M@76%h^h92`JbQqTTywD=QMIXjf&&hXlQEAQM`5t7n5DbsEhA6*qtouOw1^|R zkGqG|Dj6GajQV$B5k1B?F(L|?iX0?_mBS%E%po0YfD`;8bn^2G;VNSR{wiYvSsbdP zz}G4Ia)+_Q5z;eJq{F3+J?OW)8Zu>@w}j6N53}c7yU3= z!ew9j;e_y^B7Ye$J<&t^BV3t^H$h{8RsCQ{8RBTno0*T~>Siv7oQpTm2gIvw&kl>D z$q*l;r@}`AmGfGHlc?oP=flWw@L`amY?4#zIJ$x|5f>(5NsX-mC{VQiL6vK&FS^6A zZtUSx!FBQ!K3C+EK5*d^Ef+$(J}GeP6S;s?19+?IhmI;9S2D4%k=x{DZANbg_TpU8 zNYJmTgK#)uzi#8!99Ek;&)IJ6POpO-jZX^SGeGE`;l>h{4{m;q9nb!NSEfWahm#3# ze92?n5_JczD;0PlJqalJl1;lSNp`Wq8_T`gT*=_bUi*mM0}d!_$K3^Wk34bg9arj* zw(lU1Bkg|`m)uQ+L@+_&;%RYA&dPhfD}<6U$yk&wtgh~H(dT`nSdKClZo?k30_h%| z!w{bi`Rd29+}aJdt6S$PBGTsFc5AgcU&lZO9#xD}K+J`-rrRb+aODm*5IpUJf39PnA#89i?7>U+jjHzjtG)U|ZpxnX*`Mgh33^QV) z+&Mp-@G}C)Q|coNVUqA&gbRM+DoMc;t0|N|l@vtMiQhKqcOOkUg;VPf`6-AIJ1V<6 z`w?I7rYB+JQC4w9__1nuyo&7aIQGP{y;JXpY%n2Cp<%qivWteyluSfNfhgxFF#=*&H)8Zd>`VNvQKv)EROXFr!1~L9Up{x7y{{COX@Yk zm)RhdLaJdbAb;t#Liyf=Y`DNrF0)cPc0y&>1=LP|!nqhOFh&su;p}n7c5FyJ&*dU5 zc;TMyYe-J#r(KFiAdKWfD#0TRPe65Qu_F54(%bhi6g19`O0T zqk&sI$Wl|t;hQl|py9BT?L99dl>|9S6+zYnpcXWIa*@RN6A1t`JaBja1IZ=ESP*MK ztrd`=sPSRA?xim#S@#guMl3~AN7OVVuqtDMLI&rYN-5PwpGz2A_9Y)U;Z9)&4+`XX%Bz|4WKbwvd9L#%}`l{r4-0|xrYco0g{`jBV%y4F>a z<`9}{Xp>slPDnyZQjWs@gHEN$e`M_&bACnjZKu-@sCS2_x+ z*>k#~Ay)LR`_rlUhsr`7m*o4cB^B3qR%y`7Pkz|1Zicmyj04cJwQ zCFyFT3bE`m5YPO#7|C1!9gBAYH6K{Ix|J}IdyjkpMBeQ_n5(hLpkv9C3{QMsrA2jL z-_nS$>Yz{1H~nx8X8wnmFQjVxDnI?A3xpt_o=dP?qJrzlU9a*~jlMW_2BLE!bsT^D zCjH_KTCn_Z4MF(24M0cu1RUYxYH;g%3XbTDH-e&=*#3g@i8?>1USJZZHztn8pdX!j zC4j(V$o$yYV8zh)*m}1+u{Rc%_=KDfd@>dpRU-C|PBG_s9~hKG;lLvX52a=J3bYz5 z9YxP7G11P-^nK*fXw0ctJ>4s?_1|^#`Up&)Tm)h(LzO6Ehog(3venTw*8SX3g47$n z{#PZ+_y2NaD&#YCviS^|{60fo4rFAanvs|oWh5n+8A<46MiO$Fk%SyFayS_Dw1431 zddv|&yXJG5^(-?s#XDp$?;kRn_YN7(dxwmR9hKx5jp{R;5X+1ja>!sx4;f3zAwwxS zmk|-drP-sfs8fmrIdU!|2%gIb$hnMwoXH5xEi+X@YA!2E&*VisGMN#2CO1OQWJe@s zQ-16oWom`gOh!P?WCPSpCP2+(0ehs?HsDTcCKE!=Ucwko~N0COxH=-yiv(3H(xvMw=Q5#2*g-WU)?g`Jmv&0d zC91CR;Be5UT5JrVQk2_nm)H50TD53D*{wSmtK4M9UM@bM%@tcr1fOhO$-*Nnq01!< zNusV*hb)LDkf~*FT^&&YxDUZPmFKq9*93Ynu{oHOYfF5)=TyHAIf=JL`4L*`WF~IS zFV8r2Bo4i|CQJ8X(Z$Z~Snc&EN|D#Y3C*|hbh>bc!(!2Ry5%E1%NJ17Ch5@t+-HvN z9!^Z4_n>Z=UHuF*S6!uSo`ARv{#(u$2!Tx+eqq`fDn-Z{D1qX>L+G}1r24&kEZQ6N zAV~?|!SPQDwih_YfR9?ymF`MjU}O2P3w8RnCN@A%SM!_;=Tv&4)(93!PCsbA0eUfp zwoG&jS|b-@d`$~_0KA>;$xSg|OIXkQk5!Y*4Hy@~Z9TgkG|7Z0C!oh;2-oGDR?m5# zQrx*bb)SWoJy15oWu&sYbeoK##!#(=nm2Hr>Rj06fJQ|ywDjEl@ECdklJSr&%S+!y zFXcF<>k^j}mVxoFz|gUW&ke-DNd4epb!QBIC2oy2|3PL=Dj3>zcY^ywpMJ11AxEzs`r%-tS5eV+H*6^XI zx2VYml%nt#A^1QL)e%FDiWPm0ic+dw#f@V*H7Ff;^ zssqVuH^DCrW%*DVeuSRyaelX`yt}gFtt{#wYbo$>34s5dbyQ+<5#|A zssn?+r|`z_u|5z@x~?7^!{$c|(fJ`<{|q0*6)Gkq%;5uE5JCw_oOru@510GVdRASJ zr$Yd#Q3$~}ZuPHcgk^*0B6-~|VEEF_3H6~-~!3)yv6^P=vh6C3N=m%%{ zi{O+J`6KoSbchH>2L({tY>8DaHgKo~)-R`4DBNGeR%J?$DYCbjMlMMvw)2RiyDz%( zOSb+UCCNm09&vQ)L^_#F9jQQTqg_Lw?Q`zv$t-q+cE2 z>)ufwcJv0t@)QXgF7z##?A!y%y19=}MSKS=K59p@C9BtUKzcxJhzTvW{`+b>tLk+p zJgV>5i;~K+#fDaVU}iPb9>A0z>8fGv45S2{qVWiFc5rinU_wWgGQg4rmYmdp^XGy5 zAnWoOSNy_6Q+~l1y%W6;H8jA=pbx27x7@v5i!+AHg{%o|N*@JkzAWErbZ{xQM; z|4V;uyZOD1b#r@Rx#pfK@pv!<8CC@PQB(btX&YUweT_lHSLsu`B)-czuJH#~pkOQV z7(W+ zjL(VjL;VMTN>&Tmg!QYBh^+gLIJArH$C!+~yRT~EiMQbgzt~$m(%&d7h!pnei6_es zm*VKex?8I0BZ^IXIdp5cg42hb4R%geER7O7yl+EYD4S4_Az{$?J$lH5iCIWp0nU_yo$}dW(pR+t3b~&iMy|<{DJYY7}q7JLb4$8^jfqO7L zc0zUreF_CF<1NG^`*3Fnj%zpAvG|K*CsF1#prS8 zF7@GYPszN9=>)61BXU`FUBRx;xt#+8QF=Om$|@wHc<7#qhnjQ4hY}ASV!_9!GtGk& z0s($U@-sPvtrA^eF!}(y0lciKJ@^S$6s?{v{a`9xqq#I^iQrIEJWoDrJ?wBI30Q35 zR2_#Bx$e^oCdeRWM6p1Z+JFQX`heOsyGL7}8e5H=#gG|f zs>vz%;ZK$Xc*=?ZPZ=0^Qu&Gp#|$6CW10}*)9=oj)<2>8b~d&CsT8rSE$wQ%?!H6! zlrSpc!h*Js^WRF5C91QdMS9+z)?aeyo)VTEO>|GfR@H@8R0o<-94-j+s3(ZsQ&OP5 zO4L;@1z=u>q$Ei}R9S+Vf`}vjDJkfkckrPcDipo)t~>I^w%w7QaCA=z_51U*v`W`H_of+=EnJRMV@S)o{w@l(j9VZSV^Y2JX#22n(Kby9?aF`atrw)ML1> zYiAHR5e3$>1KK>E9r9VD0s@y%@PVr*R2{(wwFP`~+0Q3sN7yTmTDZuX0uKK8+J|lK z7~+X_M(n^~_B6c8`BJ7kd*}nov!pPXkTjI0Mtw8{C$fH#pZIeuPSl92PWME0;$k

Rgq(!Nri_1~5AHGB2U3Q$wg5?{%iw{lUz|0QWHmT_^Nv zs{RB?Ev~&)H3(z=QTyvoGu8U8#@rJ%=9ZlPiE8%N)$Zv`d_5Veag{BxF2DwW%v@qy zO~fvu5Bm019ZVGlKnF*&Ym^yjvg~xOfJ5YdNV+&?yoNgvBJD>|peDhOlwQK>%t~LP#odSsZ^bi4LQ+Dtnhap8kzdI|N-_UEeYO({)A97YX zE->N)`lQ-9Oxn>Qq47H6Dj-{vj}3(5HxltX>>GDf+7WiPM@` zr=LR6$z4AHgdI@XiN`s1196&DTv`N#K=J8^`}g#hgILC@gY?IWfEqjeVTzVtWQCx| zhq&PywqOU22M+!sEt&r0*Kd0`_M(q+WdwXds}xiPiVsUM53KK zSFlk;#z6arBS7b4>;Pi|b5F4Kb7=FRic@Ko*A>7CwTx?7Iz!XqCP8?{%TppQPu(+W z1nj9{RVu0i{vVbfDh#)=MmH|XycVKr0YH*{D)&Se z!DK}MlloIQjxGxBn~BB}P}Q)d4wtXAKx0q`=>Nf!>$>%3t*8rUe6mTNklmQ9_yp$ z9)17xbjWQI&UrwVQz&FXkcM&0faijsI$;;*VHhl~^nv~w_D+aOo??;2=a?Lb)KSUI0xT@?z2KfN~*0#B@vyDrBXhu4JhJ z5{@C(aL|H(a%G}>%9`7|vFi3th~UnNY-$vgNe|@cV@CJ^-TuzQ$gPpW{f6*CZrPsb zMfl@hk3JZXkcqR}X?4IKbqbX~m^%3*DTv?|Hq!lRp4w=DsS4_8UHW^Y1li5u4-%BU z9DE=Uy;FYKm_!T9tW;$V{z(dY1heE{T)tAy{HVlNbAq2UesD-+MY?hL2iBJSqwNVE zEdLlAE2s*+G0@)=h|Ymnayy_n89*+>;{%H+KCtNGgE!*g$=mesfZ2ld0&%I)jw4G? za~J<1;PG&9#;k|~<#G;QnGm_JO0XE5>=-UMuUz(Sb`nSCCCko@_5zU>pLAgGmV1{D zUvxW{36X*c{K92}>Xs^yivHDtOa&;i+zK&d_fWnl;p@?H*F zmIkI(o)Vs(@<@YBoChu^53bS?XcC%dwWD)WH6H%)!q(`rOI|#>K0Acuq!0As(gGV< zy6%rpI~)&i(yuhM3U*d-h-4w&Shq729{hxiuxehz$aOi$;s`5qY^K)mcg&wt`B7(& zZvG6xk89Kfh)FUXnB73Y?km>4otoZ*=pKlxx~Up+j6Y~j`Qxssg&X4sbxZ9M0c2Hn zT<{rZu`Ey7mmz_+rQ@@6*(`8Rv@u+g19^aPK=Sm4%ca>e+HgR9k9(p$yos563dLy` zvBXyu;&@oEjfZpi3m0R_O;ZVB)H+7dq7Wn$e(Mz{^XUuKsQ#ix^u|T(g4A%h4jNgM z_M*T^Q-rv{exN*Pxm%N|m_IYl7Dyh?GGGR>pjcYR)oR&7kEM zBg#Ed$>PFza!*e|oeD)X3F2B-0+r#;emYoBd)sL>lBT_KEm%H#>t!)zuT5Y*CwI!w zR`nQAWi~j_qmJ<4Jr(#x0{w@59POTAApj_9Vn%LF2jKNrcw&A*aCAvz4-Y@%UHJWa zZ|7X|*H-x3$x4go+Qk4(=k1(pUXSChwFpMeHE-Swhfa#l#L?gG5Ved zRqYD*&!BHOT{;do)Of%Fi|DKCSJkd-xb2a5Jo08o+~>$!9C>#mZfxW|jl7)^_np-E z?|-^~bU%YXQ~td@KZ(Ks&&1!eZ34gd?zP%~tx(HQe`m^N(EsK7Uo}wH!0+9A@Liw% z8MWH%eSLbL*FEb%=pKjXU8RQ(_ez65#o*W7mvln-HyHfm2LFWOXZaVt+4#TJ;NLX( zcMSeLga5$bKQ{PJ4gPb3|I*;M8T_{f*It>H|5*mVi^1=1@Ov5j-Ui<^xMA>ZgP$~b z+u&Ci?AyUV_l^I7!A}`{*Wh~w`*i*DzVZKLgA0R)22TvWGWgYs{p)J4HTbg({u~qk z^9=q1gTKh&*BSfjp0vykzhT4Sun~ zy9PH6e#+qc27j`_g~5jgcMLu?_@TjlgFnmQ&oTJ(4E_Sep;^Aj;IB9Mn+*PDgTK|_ zZ&w`Vm+vt6I}HvQagOgY{;xCm^#=c#!EZ3wrvFCc|0aWf(%`ok{L==%)!<(@_%{sx zO@n{S;NLa)_YM9-ga63jKQ`Ew|4)qn|7Y-@8vJJl|5t-;`hRZx|H9z^X7FDc{8tA5 zwZU&Q_-_pU?*{*^;*ibRPfq2id4m@XUNQJZ2EWwcn+7)wzO6Wnk4=MLZt#-^ZyVe) zxNUI9;A4YN41QqnnZf6ZLw$}6zA*UO#DA5+uQvEK27kK2uQm8H4E|n&zu({=H28-N z{!xQpZ}1xpev`pJY4BSN{uzUR&fs4#_?Ha+6@!1x;6F3?FAV-Gga5|h|6%Y)d`c=W ze6+zIYw*Vz{J6oh2G1M3Xz+@`FEaS028WL69DByUY4E&27iKyf79TG!M6>5(%@}_U!geUXW!tv2EWqaPciu1;E}->245Te z8pUCL{tV;)r3Qbw!Cz(Ke~rOkXYltJ{Cx)hfWbdx@Q)b$GY0>h!M|YeFB$wR2LGDD zziIIA82oz%|AE1OZ1DRQX@C6y#i2iZu)!Z<@N*5GHF)0OMT1uiev!d1RUG=mO@kW- z-!}M3gSQQC8QeDb#NY=8pBem_27k7}pKI{v8~lX^f3d;eYw-6Q{DTJnu)#lS@aqkJ zqrq=7_$Lj1i^0Ec@NXIXy9WQh!GCD*pBVhiPfPpjvkZPGgWuWUcQg1s4Su%4s|K$d zd`oc{FE2Ovj={Soe$(Km48CvhCmUQCJT!P>@Rh-@Hu$v$e~H0gX7E=U{M813t-;@I z@V_Vx4gL=X|3`y=*5IEv_!kZSWrKg!;6GIy+V{^5{!4@3X7JxC4*ctVT511% ze}g~B;O8g~@Bc94|2*S=)8K}|w+(($ame4c!7YQ^2A>%GKyk?LnZciF!hg2$|6Jq$ z`38TX!C!3fHyZq}4E`2_zfE!2U-?eOA^)#8{%=&wT}k=(CgcB;#{VtG|JRNGZyEpJ zHTd^U_&+rMf1=oDr}oT4>0hBd@2oiF_uY*Ddnyj`pKbi>1}_-AWbg|OezCzXGkDG5 z4TCog-ZFT{;Gw}2#i9IH#{bm@zt-R{G5E_2{z`+t+TgD>_;m)q!QdZP9P;}U#{bO* zzg2MjP#~S=`20w1_%M4yq9P+KJ?vB6(&@HZ$9{o!94{I5;;Z!!Mg zX8gb1;O{W_I}QFWgI{Ox>ka-fgWq8A8x;qB{U+o8pA?7k{*>{5v%zmM_@@nitK!hV z{>=FQg~9*L;J-BZuMGZcgWqQG-x&Pg4gOn$|A*p`-}mXH^7X~TRGzss_}btrgI{Iv zs||jQ!JlsMYYqMkgC_=mror#0~27j5sUvBVM82pt6f0e=i%;2v!_-hRQ=LUbR!Cz59jT92llu0vKX9gGoW`GF; zVPYLScI?=(W7}odve>bs>ngSt``FpFu~ydlKj)s`8D^d##JcL<`Q+uxx#!mN?z`{a z`|f@3MVI`NOMclUzv7Z#b;)s;{F+OC-6g-_lHYX6Z@J{RUGh6FxyL2{(;~v%q4H{l6P>)SuS};m%Nip&UVSeUGfN*Jklla?2<>h zos@k#OJ44h4|U0hyW}HX@}FJu%`W+` zF8Owse3wh^aLM<(e412cX zU@;g58^IQ^9qa;oKxb2lF9Y;|g`gjdf=ys6*a3EfyDc}I-8^Xpa(1j{a_Sq0$afjup8_J)3!kQ!936lR)8_E z8EgYP!8q6lrf-SzgZW@F7zP``7O)-c0<}I`S_@bUSPNJS{Jt#EbgSGa+QB%O_E&ND zfW=@8Yz4c(J}|Rg!WDvHuo>(Cd%*PD#D5;>2OGgQup4x47ysFy7mR`}U?mk(8Fx$l+7{*89#s2>q2CeiBV76) zoBxWtB>jyL@20N!JD}ej?pwL^>CmUceZ(kF%JubQ^Jl|b3;a)80QaZuaDV#Lb$|Mw zwv8>kwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvN zwScw2@5%yc_saT(-&LV(VXOtL1*`>r2NvkNP1@%NHy&-)g-!c<`1e{L=Dl6Qe{;)8 zCft)v-*0_c#a|@+Kd^4*XYqQCOE&N0@)^gwSOn{TSC9atx``_@2(%~yYxRiXA&~=X35{%N6Pgz zYJm7>;QS4g-uyxI2M(Z*BK_ho#~8af&(x*ZN7Gw8KzP+h2GJirh+g9vh=Y}Xpm2k^ zyU+g(f0p&(VvNB;ue$z=D|TFAl(Adn{O`2?SfgLPO4hk+{p*H)!g|tf9zIL_seaXS zuwtKGIR9Ui9AnZy{^r#BpN;e@o|b&Q?rOg>(SDwe^P9D=)T2cH+N6A^Zkuc3f56o~ z=c9c*4dHuS@i#-?41MnLE53i6Fi8D6V-Wp{t>ZYw$p1!H%K3YF#&M<`=06G)zg5at z{;0HX7rE@$^jFbmBK_+gNxi=Epnu{q34f(4d=KXu- zW2zr0ytZEhg;)K5yZknNYXNHkYXNHkYXNHkYXNHkYXNJ4U(N!4j6Wjl%e?BnJIefw zjxT<>oY<6phy~Jbl<{N3|LtT>S^X|@9(8`Y0{Rc}{9@>VBaA=QcR;^A!cSi;^UJEw z!2I&(2!BDPJO@yHE1r*>^N`HDotZD=R~=s#;`z%5n7^4cCsiLiNAiE^kvS$`Z$%}2 zTmODYZLnc}X$uTie=}~9`u*a`GB5wpr>X6082b01AG;uRezp_(C!k-eEOq{;1J4g1 zub27VS6%bdgW016*XKtF*Z$S_dp4*d)0>{#5rD_w(7u zvwqt6f2{4Icz&(V2mZMKI8*dhE`Nu#U%TS@!k#6m&!3B-_dq`$)cb!M^b_Ge8PwPTzhPM{57O)nu7O)nu7Wj2qpsRjMC!Mm^0y@h?4nxjY_f^b(FT%UMdmAKP zxBFmn(?1-Ozrp-jy|sX~fVIH?ngtqf+3A0}eax7Xol^d`I=Rop!1yU5ci*vz@#nvH zh+$mylf~T&d9eE9AK?C`;qo7n_`|14x*qt?{EN7&zyDcwuPNv28So$A3!ob2C6}!3 z$~g3|gKvUwgFWECKqpPoT@73dTmxJe)cD=}Kj=3c#GgBym8}JS%NAIBeYtMd1Jl8c zKrP!QxGpllEx~Pm;_GE7()|OtCb$FA84lLqx{rX%z~$h@U<-H!cr|z}cmwz+@Gsyk zU^{pRcsF=2_yG7Y_$c@o_&C@FJ_V{>e<^MSJ7$78U@kZw%mXKZyMda|Js{`1+*Lmq zry$(49~gc*!WDvhfiuC`pckAEE(8~W`+~3FeC!YTK+p#Uz)~;>E(R;XC14dem>sO% zTEJSsTEJSsT3}TyP=ou*Qt)!{3h+wsD)4IX8n6|-7Q7C;9=rj(5&R?gC$J6tGk7m} zA9z3b0QeyI5cn|I2|fZo3jPgz4E#IzIQRtE1wI8n1O5Yi4tySb5p4T|^mG3L-VELf zwu85WcY=3=9pHW78{nJZTj1N^J75p^Pw-#hyWpyv``?0}_fVeq!4JR>!Cvs+;K$&n z;OF3fz%RkC!EeDKt7DuGt`4pVt_7|Gt_S`fxB<8kxG}g1xGA_9m;r7MZUJryZUt@) zZUb%$W`f&+!@%vqao{fC1TYVr2u=cb1$P5?2loK?1oOek;1qBwI1O9~E&}%h4*(AW z{a^{W39hRQung|yU)wwulD-!yk#i z=q9P|8gI`%qK{o5Y(GZ)#h%HM{HRATBW;9nZ=RVNU+-5EUcGm3DRTEt;;-YVRR8JE ziQKb(s=J0y-*l%HrmuQs*WoJ;ull?vS6mL&e_uvt%6aQNa^>kZKc1Ry`W7qquleXc zG}WK~*i>2l{o0xRf}H=}yM)bKh~0`eU$yi4YcF5sZc>ieL}AAs!u)KxKKcqo&Rk#0 zot7c;K;>$FC{^E6lqxqDitL}9>h6xOVp!^Rn7+2;NBy;&DD|n&Bk>eJBK5TOQDOY= zqHo+_#r3Z1$yE0|N8-;`_ZL(3olmFAnh!Ud9ut4v>!+5_E%!bm{+e@B{b_ui8>YH< zJRs%D*jn-#yC?O!)NrfH%rzvQ%=;uBW%p*Oc6P^CxbDjB5WiQ>TXCBB>lr8I=vYnU z%;#2~@75Dilf26RG~)`5j1Z$&q-o(^KPDIq$Spi??x%l(%q$mD_Eg zd{}pDf!~t_@`t9j+nEoi%39WrMJv9(+WrpzPY63cm-~)}^FJo;u?JQhullpJ7O)mr zbql0zwc_h>)noX1e0I-Dy+3zg-1hUN)*ox*%+z%IHTExS0c!zk0c!zk0c!zkfm924 zw?w~Ti(gm&q4&WR=ci&5anGJ3>;h9uWhH9?YXNJ4U!Mi^xtu&oKI=`*+ z$2!le&kJ-uUgy_!9$e>{S9L!4*JmMDj__P#pm}(;n=90RP4xU*=KtE?6sChJ``;4x zwzq|8Su!u^{b#EGH0X=p5%)gmHN5II9`&be?U8UAuZGwBXn422btlPB%Wz@g2x0!t z!r1=8=77w1pf}AFJ4dNt_MZ#o-6)49uYZXl*r8|3&Wk_{$D$BKU2ba z#Zs;|oagvxk@G-zvfZ9kJEWf?ayyuDQmWn^elR)xZxY^f|Bs7juyj^cul1?5T=J8d zC-ru~@Ti||ea56g!np(d+T`okGV3nls4q>6ejVrM*JdW0pP$D99T`JY*8Rla`(fX` zjcYvb|FG}_l`bP7-}}uRD;&t5b^nc8;Fh&h>)*ptfBawzmFQG6R`Ac@?cn|3W8e$m+h8yFHMrIq z65mGPrr_q_R^Yba4xk6z4J-ur0R!O4;Mw5C;ML%tz*|AJ!)=gn2k!vy1n&aX|J{)9 z1s??e1^yfS9Q+zwZA~eE8n_O)KDYt6F}NF82rdBqUWzqJ~$Pe4i(F8woSO>ix69dHA1GjMBgTW~v2)87H|PT+8GBsdCG|6?HMfVto<-~@0Y zxGT6jxF4W0`&gBO4;;LYIe;GN*zU!95NHw5k#I0hUK?gq{W z_W}0<4+Q;SDOdqkgLU8`U<^D5Yz8j`F99zDZw7A%JHUs)$H1q+Zt!LB4X_9N5L|sd z-1otC!1cimz++IajskT7 z*bd$eJ^(%nc7gu@UjknTd%zFCPrxaP0nP#!fct@d zupA75wO~CM1rG&}0FMGs1WyOg0WSnwz?;BZz;^Hs@NV!)a4z@~cnjLoJHUIv2fFB+z}iO?hK9r$AZ(rB5)=+2b>Eo0QUz2 z;9{@}jDRPACxNGeP2gGJ72plvE#TeY!{F0k9Q+sf8Mqqy_5TNs1}A~j!3CfXTntu$ z5pX$pBzQb{I@k1C9lA z!ExYtZ~~YIP6Q``yMnucvq3Mo4|o805LgNZ!Np)DxCA^5JQ_S1JPkYpJR3X@ya2oy zYyqzTuLiFL+rXQ^TflbkUhom{G4KiSDezhFpWuh!C*Xg;Z@|^iFJ2p57hE4q2R8&W zz-_=C!6I-DI2T+5?hE?BAXpAof=j?^a4C2kcrth@csh6ncpi8$coq0p@GkIv@DcC{ z@SorZ;3wc0;8)-`po4zI5O65C8n`;R4!8lh5x6&#&jDm-Nhk-|cG4MFB7WHi``n7eCBVawa3~T_S;BxQ~ za4C2=cmmRC1Wy7_1y2Xh0M7!?0j~vb0NcQu!P~&QzD38j=Kt3Kk5nKo1*8|hRjlfO8EO19~Comfv0qzWr0!M=$Fc;hf91l(aCxW|z zyMtcb7x#ob8Jr3hfHS}%aBpxHI0u{y&IcEQi@<%s{lNo49~b~j!63L8tOS>URbUOc z6pVoNU;}svcsO_$cn{bC-UmJaJ_vS#kAjbZPk>K?PlL~b&w6=1D{tt?%yv#eg%w!uY+%bZ-Z|j+&>||3%(Eb zf**q$W1PJSxEZ)PxFxtXxGlIHxILH!?gS18M}nikF<=gu3+@6=0Q0~};BMd^U_Lkn zoCfNB>HBi}j|~5P)3g4q1*`?E1*`?E1*`?E1*`?E1*`>re-2QLOM1Fr!83f=|Y4?Y4u0X_@92)+is1HKP_41Njz{?4Q= zk+p!efVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_N zfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVIG?S>P1BU*$}& z8N38M9XtoT5WGy-8P7KFA#8qiN5k-IB6qwl)bD>(ydkoFhhwnsc{n}df1vMqwERo- zh3^Vit+4&Rvi~UWv(|iRe)PK{n!cu^`PT1;xW6}|`DlJm@{|9*um^1VK;-y`!hz!H z_?Khs*!8XCuLpFTO^tg7SO|7KB>q|-7G{7R=$jyS?vp9!2kclVawFnz2M78NidwF9 zq2#}J#BdXzejlZ0XOZ&`5WV{E94GD>I@wGf4cIf!K$oUV8?0;Xv zwH_?)g;l~H=$o$2GVvGhD)BZ~i@tAnksE78ZqA21O&Bc{R?HOUPZq`>k#swYL~frY z%!7MuI@}MHc>S}XpDOHZ5ciI~MNV5y;u|#oUhzLzIa=q6zrpO;^>;~kFuS(Qm-v2c z`F^Z@^Y4}K0w`PWz;zGmb);wYD7598F3^tx5?v1M7 zP~>*V8m}@8eHZj;+0u^nK+c2gTr2TpfU#}Gp9gXw*pB%8kfUG|m~pbilRjL+x5B*x z>_PZ$$j(OMzZbF};qwtb?K;sHLykh93HK(*d5~M+uL5!*;%|oRhun&AUGU$g@j)Ml z+zPn|{yHG{L7#p->^1`S0y_|YHuU*mA@pI$X&X!UM#!0vqwv=P_ja)RWbxkxxfTAL z8^k>i;d|jPbEM=e53B$);J*U?J&>EB_d||?X{Sj1O^{o`4zL?+*7PB_LDu?cX)Rza zU@c%R@cXhr@$Q?M{!Z69((ma5GtU*d5DbIOU*J2iUZ? z*a_xuA@0q+65g{V!b6T80sC(y?&({D{}%t}LebWERhMe&+@-tJ|1i2mb%n|oER}9W8yH?D?hdY#w&UTiK^TU+Cn|CW*p-Fp0YtN_-ieX&DRgJK={9OU1_@Cmp`nO|GS~uaDQsUeaOLm$qzPx9bhl~W#WG1 z)%z6Kg!@nj;dz^u%2)AukK(B zYyw-rHq|412jng=4)%iH7bQOq+QD?NN%IFejPiRR=Yw9*560jxtTNaHYCob0{@Rd! zi^}lV2DuAz9P9<14xDE&6ZC-jV2j!ja);&*atv%z|6pA61G!7xK}Y+wV6VF0i+q8Z zO8E0Y&Ii4qAN0UqJ{X333~U0u(6>PLLvDlI0mfn9F37!*<0^w;gm=(h#vrFd&IFs_ z?tz>SdO<%J24kS}JNPJ(b^e?-&$NGeWZeUGjO zam()KM7edY+ zFY~N^$h}*O9EIEp|9xQQ$C6GV7zT^Cm2e%9d%*Nh#J?YG1pDB>4RSY_y=*&E{%$Zf zE7Qo04dUJu750G5%SHBYvaRvga)`*ShYH&cgZ^+~`Vqp6BZZw{G$wNPQNnJp@o15o zjuG~N&Buydc$_eQeaUAFWbg6fp0=U5JD-XjvOzDHF+uE>4_1IpVEA&;_kb-3*9k^X z7JV<|7RZfXi+gyHu#5@21@?hW zuZer}X+qEEl5Q~=Q@$>G|LMXuu%b-lSWwsn|9xOfg}BEnh2AD%TahrcPtuF-C2|W` z2=|V#xOXoVHp9Ig&u2Oyd+@xa80>+2`hO&TKNy}R@w7qi2Awa&Up5#8TfmA7C0wWK z=ZM@3Ipa$S-wXGOZ$+OE_wX2zyDk$p!95f8r5$n{O#4dW%kUx|uo&)5kkd~Refkx` zM#ycDTj9S8>;ntGmiWD>PhrT-UH01gs+hJ;}=PL;Eu(AndmDn7j|B<;&Qmd{nq5Bi+)}^|JLkb^J^_& zEnqEREnqEREnqG1V=WLL>X>m<;V5Co6rnrbOt|-6A^P6W;1AC~y0?XVr7&He?|>R# z9N|@7RaUGf@p=ZxUpCyMdyBug=4VwC_>K7UZvs32M)GU3X)RzaU@c%RU@c%RU@h=# zw?Hxand!SrKP!y>q&wf?O;_Fz^CKR2xSvYyLH{;yfc|h4`O82#9IOlZsnY+o#MAXV z?dShm>}&I3EnqEREnqG1`?f$D)}8#mOZnd~UFP|jDeHc+FG!VJu|6SscIxx|wj)#h zX-V47S+Tq7qgSq6-*b6tIvP&tIaJmkRGcaP2FgcapJgHNv{WNK1}4o!-b6(3VWMzy)G2_w{lJ@ zkl*-mlJB15h0P}jyN^vRPse$w@^7V_eOTw~&ad8Q-R^F=@XFNtX#8riL(etB_R zy2D%9THx1YfnuyX&^+}{c2fGsF|0FayCT)y>k6mg`*u$Cr|!z$LFNlvw_17lJfxcs z4wR4fy(FFve0Aog5`T;ooR0ff2z~x` zqEE{dwigMbn7@vJam}CWJTz^9_%{-U;opn%7(;&OwYDZ7=>yDHyYn}goc|NWqvakf zy)Klm73FcugN3(xYk}Xh1u}-99r%R`*;pv)^=LZ-IgIuxyt(K*(cY(PJM|0Y@5d&i z`HkXzbn)Y*JWZbpTb>hYI$pH9D*skku}*3^G~arkRe2z~?*oOnFZAhsJ`?dP2a3qL zTMPUOED%ROL$lK9lJk#|`W!}oO#OKV=nq$*-=+TC%pRoO_7Bp}>ZJ&|f7t`JWUTml zj_UR3&H&_!{1t~A!25TciwDVP3+$6NfIVW!cL(xWfqq^)yh2^kIaS*ZY}Vewm@uv_W0*2R4YZy z?Nc7ww>GpZ&B#Zqwnuv1{>s{&!R*q5{I+f(%KWy{J$1`>j3Aa zk21*Tcd%cptK98+|Iv9EtOx8_#ddzM^sHVi(07@<$3ox7)4Dj(8eVW&M7j6G?T~ z_`WaOPC+~^G*IVX?+79Nzbe;t!n6IuTEJQ$2PXKrnKeKV4gvv@U(220@UceL zY;#mMi2DKXo(FndtUPC)!^fE8z2@jRN^S#HmEtiR0wcn}Y~kWyb+ERw)QRSeA2oiQ z<3uVC3D%T5PEC#Im(~l@>!tarEH4X^+6jgtLDp23R~v_#>QW<a-6L>F#Q6ND#Mc6U|)K2sI6g_y5-?uCHZ4={_CqNYbZF!XG%=D3WP$-owDWCfhsC* zAQGuuOdh71)E&p?D+`9|0?y)UDR7{)Cc@W|0=oh96DH^~U#?6{-2A9k29KKH#Le2k^K$G^(zn(^a&Y)Sc*1(zjBj*)}|Xl@l*vOOPtx$r%fqZFyEOz%{RYb0bPe>6n)rXdFo86vgrll-{-3)71jGl zFchQczI+v6`(GZO$vb?IKhU#{7p2Rm}_Ck~8nUy8A zf!gJcxroT6gkC4kzY2jf9qmXZm6?Bh-SdTBQZEh-xSqlxbGbST(4G~UtJrat*T{8V z#*GI3=ycYH=+EY-q+43c5t2LSnSW_#NdA<@aV7uxeC46Q;s}+unwm1liN8=WlnmHDE?%4$8goF3V+Dp*y*f0`fPr}&SKPvyL5IjD})6)b-Ee>xBK)g;$c`+`x5 zaB;9MSdBKZ-xt;2dU2;(ZuC`4B6Yzks_+B+s+N?kR6jtlgmXzG7^p3+p!_Wfa@AfM zG0jOrUsfrZgC5G-A0Y76@>4cAe;a(^p_yGFd&B`rN zGnc}__$P-dx*7AeSyfV3(?Is6^T%)+O6zL)H2HiDr4<3HFX5^{9hKAlBRiXdFQ)oX zNBIrcMd-$ii{Z9I|9 zmYg$(@SzT5SM#UOx71MM@pqg(gb%8{5xR_>l2AcjD2$v81K@t1lNE2krun2Pc5i6BzBA z2sy_@Nb#8ni6%m#iI8X_B$^0`CPJc#fYL|!u?RmF;pC1@dK0ej0~xlLoV%fue3({= zI%H^068AB+pPN!@>Zf>e#(Bohbfi>{BUb6}zo?w(_lOxBmB-~uev{(M^-xK3Cgx3G z3yk%6Ca}z83neknLnSA9qK6VEj)Q)@`a`(!!kk^$vPt0)Z;nZi$}uoaI;5BM@;p=q z&95gq!Q82G<@7tsoUu|umDyi8`Se8jf2M>}JILAmu3r6fpPzq7#>tV>Nklq`NNNY= z&jY)96l7J=_lL~f38O&_)h#%ZJnI)xp|y*>c^U_50)=2 zr}ldj;kfYhOQc^gYT_=_raL(Wqs9}Q+&r;NZk}9k3A&{b{wBGPV!SQ zDmQo9%tX9uU!`2lN$H~gj^AaMT>djBH^(!9JSXyHa`|1E>emF%`2KX<{`ERh_X!?x zQTeB)rl-{MChDQ99O_T=F>Lo~!`REP9D{+&uk~-NSYE@U+Bw5K5?*EHF0k`BBrLU< z9(y2PN_AI%uOBVG#sAY=?{&1SPl^U zYI;h(Kk)fgz1}aFa=(#!rv8;bRem*|NLVsTQ$OZcj(HH(S4PEs)F>g3Mfn%56YBr& z;XidgbqKCr47FbQd~?nCn+CTg2mVeOXP7}Y`K0kP51$j`=k2o=IDC{#H<8E5`xVTa z<6u}!{aG1F7GXdeSuPn3AioX4kSQ5;8_j%|j%Na!l@H}3C6gpjf4i24raUezrHQlt z@nb_IxYTiCdsPhOWAdcM=6G%2ilKaToFs=Cf6=(2938Wej>~BDN5iqikNV-JTVAzf z<-;8_e&K-vewcpZetbR6ps2HqBS-WJ~Wxgt8aEjijxN%VhkE@(c})O76+=P#9co2!rC)Zs(p z3)Ir21O0GWILi?~*}IPCvAT|taPi}W8jfmHIj0a^E)$Niwp6`d-|F8Tz69wE7S0`y z#^)xYbMl`_&Bs9g)W7z}^nN_%T$&G0I@CS)oVgAk!*7v8-Iennoa^whR>3@TxbNTE zA5j0wvkK-qe5kzS(|HabDqnHu{th3QzH%0$ozimA^=#UKDztOzKNQRvUsqG%=)AsC z%Uy|j%;QdWQ#-5P=PT@=Pt?u>DSeBIW-st9pz&#S9XE&?PRH9Cep$e0+9hIXO?bIO z!DcVu@V?SAnyPUE@Mh+LosZ^=-koN_Y>Ft@{EICsn?N~m-^A;J#;ZrcSgs36EObM@t}_X z%s7qw!Cl68I`6LIF^$)=P!cwor9aj5dY!BPep&9XD%bL)3jIuDMpS!gze&?kCfW@e zAF-Qzoa7#lX}gn)3~D^Ppkc~oBXB(Cf671HRj=d1gg=bSG@Xes_(T|7#{o1>GN(x6 zRcbj^*7K#|)O}E*V1xQYx!nHLE@L&{@Td0wPChZ;klat=Aj5XAH9fpxrKN^CuF!Fa zrmOL)tjr!R2`B7;akR}PzM%#5cst!Fwu)p|saT+PpI z|Ac>0|LA;`ElW+O3jHI^r>3X*h}4SzF#MI`IZhB9wTC=-49pjQS?I6r2!`OkC+;!7utd8W-1-TJkH%SY&~qw!!U#`<_{k@mLtWgmyPxTn-TpP6NR4@1 ztzv@OFHncJ{bkux?1_RQd{l-)!Nv4kuRKs`dJG|Y{>*;;drlj|hlca{X6v7Z8n2I^ zXH!VJt4Au#45E0WVa4JcPr1XzXJ>kxP)%MEaU6udu)M$tVBFLApgcd*_y;0Aml;1U zO5>+9-y4#A==0!sfSwD};STRV{mmhKsJn)3+4RmKd}uh8%jYGsZ2r)B>cN;AistFV z^~Q%KI+i8j|NhX zvpxO@*F;Rm-sdZrIi37zxio!xT5A5Jr=^CfS8D%%Rhc|D&wpz?Zu)#)lOA!_0{ZK_ z`UQpa<}9M}&0bJQdc)Z>6aLIYPjXL-N&mgwMeV=(d?lt<8PdhC;}ds!`f#W!BI7L8 zhihxaL8nr#pN!pCr$JlmpqNDj*|Lx_)ZWglp74 ziawuNDPh)5=@^hn^NG|tQhWcP*BoXZh6XyrpY@u9!kMWd9iI(Ep6vT&ZmhsL90 zSq*pcvvVCjRHpoy1u`mYIF+xhpXczQ^3%u7bNEnMIsB@54j=vbk{L7ApLokWhmW(K z#qk!Emkv$u`cLONeB87;&1ci$&iA{U%yanA_`ajxh4gf&Ug`Fy?!Kb=wA9QoV{0BW z7Zyo%nmI?P*Q3^3m1&)V@j&fQg#YSyUoxKCakqb!l{8*Q_y$m}W*xUz)YX*G(A^>O z5IzwHNFqZ|Y5~qh*zg`8<};x*hJwsGZ&EyJeZDj8Ocg0iG+?{AqYOOLU)_ zU$kEV&3E_~n7>3`KqvZV{_%Pho?oG5hvtvk`f4N3UO00mC++i1FPd3E>#NNF{h6Wj zU{(m2^%TY*t*a4nCjT8npV!^q)&ZHD-Y;+0&#<_la^|fu;3H zYB$AO9yVFkc`hoKk$L$G|3Up+?=2yiHeSIT8&vAm3<37 zBaL~sQA=NNl8?qwG>)M|$5T5ahG792hwD6(&PR~R%uoF*bqq8T`cX=Zv#|Wr8HIJt z8cyc{l?diUWSTjVuL$P3%BarrFN6w8r_%iB)S6!op7*-fRpfYNeT$YynRs5M;Xz#o zpz|@gI?rQfrD)zmpD(+@X}L5%Zm#M)mCPUZKTp@@^Saa0P(7U- znw+iV>ybtoX0#d%8PN&La$~01n(W9n2BPkBHVa`Q4ier`lJQM1CY zn$}$LPv@y?YK_{V_1or;ZH$)dcS#^ZEj{%+s%V;)SY6LE*nxV}Eq6+4cy%YW|GXHC z8KN98YpTuiMrs#m#T~T|=nR(C)blcLDv!Bs&^qw2Sr|tbUx0H|jtni9Za=TLLVEw6?Bqw)j49&#&)RA)K zP&-x5EsxHJN9v?SE~RCU*Uly!{NHPyzTbUw^V_fRmv$vNfKnUOF(fHe0} zatYVhn)6;=lew%W9C0G00kdG8*2$Mw(bNL3XXkKCZkP-yoFShta_1Ap>)nk%EOl11uYVvJBqg=>xt73|Y@I$44a5(4+@-W$j3BB<^vWbW4A!$h;4Vx7b zhUCMLd=O1jz%=m?O+3-C#1oYr7^JV_YuQl3SLKk$@_<(=SQ+&%W&XiT zk5RgqCKGbJG;PNAG34}E7I#xWNH+C@$vG#Qo)VLD&V;)u2+1ru$d-`fbD{JFeD#D z(+^{EewbVUqA3Tq?Kn)MC$fT?Df-`#omn>VpcykV{F!*_P@jb5j*#|SP)DB|7(

IqLUv)bHh}-^)?Im!p0!NBu5EyTRm)GC4z~+@LE-VPq?o4(kbC`IDCVnxSaW~~-8U9RoRKQXuyOWtrc%li< z=Hv94oDLKIIDAQ|Y*r{i$D`zspqXEz%_Ko?_-XS*X$AGbnCz2DkMWsRHOpwf8f|u9 z2cj9j(RFJAM(T{SL#$>!^(W{Q()B~+_?R3YljCDX!gSr%)t1$Zdo}+-ve_^|tmX&| zDWIXm8!o9`!m^2&$kDJ&|L8u0jt=e9F!$?n{K4dUUQP`I8>$=wIaYI*6KW@d@Dcc1 zh5*apzD(WWp)w*f7tC-)z#&FTD=UdIGePqnW=5kjA`=#s5!%TRt{}b4a8ycyB+Cp( zWh6pd1A`>XOh;Xf#7EOYW=5p0M%)7>vJV88HO*`Dj0T-=^aq2{p!83eWM3n5f0<++ z>l?zIPAkb~nCQ^3oU~-0@(5iaQ6^U#L;i#Moo3ui_jA*ar1e;JJcrMoIWM$-(hQJ= z<&Z;E9;x4kWPd}7u#&cOa0NCr?sBIIp($P z@dao*kyE*>EJ(#O`z%>sN9`8xds`;kLwVn)=}%HWyRy_gckvcY1k z)k;&TC_bH6n#qyVZz2AW(NzC>NF85NpTPA0gSEA$KgR2BIb0=e+u@8}A!Qd(+G zfO$?&?%|rs2tV;dbDvn>VFq8Mr|0$bKarl(8=7^t@*JOCOlN`=^!&-}pfxn*l#!K$ zX1z2}W*-JUA<_L9)LxtOOxL2BsHnnxX%O?JbbB--$#Rq*+aBq9Dhbi{S-LI*bmm2o%n3w9 zG)rhE+Enk3UuC&Z({p!c;t)P)TyN$LH64Ab-^+S9+Vq&hlJcWjA%+k1jXUb2QJ*DNc>YhlY-yn{!g;xjD6iwPy6@j?Hlv z6%-dOD46EV56&}(#=jI^bseeNNA&}do~E0Ss@M5`eIDa}Zm#~6nnQhVJ{Z+Mre7R= zox!l(Wu24mztH@vopR8is(b(_{>(?H%f>5S6@wcA}S#*TQ&1arai(Oq}y+@TuQTf zRWvnNO1tQ5iJHDX&)4!PH7pHVYWZ(<4^NVLdzJNk`(_uIAS!El^Y58Dgb%$A^!%z` z(^0B>U4>i-H0?<{-0Pe&c`XN>H+i5!&o9k=Uh7xqgkk1A0L5uSZC^Eg&9A1Ta`7Ef z9&PS4ebY|TOotB>d4_at@OmS@M5y1#(@2I!#>5w8&vZEH^qYyN^03St`!I1t?XBr} z3Td4ZCU|7sQmDUOM*o!8FY&m^N27^4x*7N|jxwZ#HNRS}?@L|xG!S*&qsFUt^ZDqF z2h?vwQb_ ze|q0jcU>>0=R0?t?1xsp=0oLy!mD1>SAR?E11T>k(d$%3hitcfX3eJ)sn0#M^;Cb_ zero=dvR^MJaX-;^T=lsyh+fCCOS`{btG{2G?tK2(^pDVT{!XaJBj!apIg>>3*EPkX;i0brUW=h z`%_@Kxhp!3=0o?MX}oxBmKc}o_*}UV`Pd!{G-Z_~UuUvoO3S0|2X$S{&+YD;Su|xT zX?(t!1(V5>`qzGwj+=NL21lUxeOc8-{RmqA!0S7xe>9!@N5t98DGR65iWA3KFw5(k zHMyAkO=f6Jq$vY4f6miyG=DA&7tQ-mOg`v=Aa#*U|B6Vf@y!jJ$lWS(m-!sd3;$@G zQ^}^}=ZjI}BLC6TEVGcIye4ek*CFefX+EbmXk3iDb{;86d6{^meu43?QPHHJSvWyl z#(&U!11~2@*n!gJX*zN**C2*v`hXIy<UgQOu|v|S(0!ZxpuF0T()#44Z|a=c)ZM0euVSu#j;`-U@C0bS zgf~>sxK?T|z2$|b=0Y_8BK$Lr6q1Ywe%vplWMo{<@nL@7^b0wC8P*f! zL69N2qq``iNA%oZH2EfSeER+uT62Jz)?_Pu_wPls=M+w!J;Na`np{Nds(gzk^9nGp z&w%JH;`%_G!GG{PTRok=f%=sLxzjv}NxbD6S&u)EKXw03z4R5C6(Z`+{Yc(=r2Q(9 z`rAqMr*!uVDZIIrXn5@p8h5HX>aP7LjYra@`D#j?Ynb-8RIk+jDfLTv8GWMtR=rZw zRoP8?sA&v`Wdjbqc8QyH^Zq6N!@PHi{s{0Of_~IKOT)(k{m9*Hi6Cn%b};pd zS`_VXYQJCeXY>?6*4LmO*3Rf(D-oyE?i*zI8&^8UeHH3fO?;-xRKS^EX&L>J$5kt;t+0_vWnWQ zH!?Por!2HSLzaKi^BR6y;w0WDXFRRozXkhx3)p#9!K^6-^T;k?@$~i~k2`$m?Sbl% zdFvXlW1K=Ebe_N+rS=QPK{3`v9WSUq?Z0V1NpGb}4X^9V68j_(ug1gsH2H7y@)x4Y z3B4;HZg-WnKC7G{=8v>o9%M}YD^;He=g#M^L`F6&tOcwEtOcwEtOcwEtOcwEtOZud z0+X(N>;v|gzWR>ldDje{|MQK-TUQ-tenG+BzNrgoL?OSEmOL_r|LTkkH~wkd&QI{? zFPOYw;e2xMcz+wyWp24s^vB%(x*3-=-z{=OOBxSnoa_%peq@^wX2K*dUDDt1neEJY zGJTrJ58wXRt=WI^43RHxShNMpPNB$OroU$%xp(G^y#4hfk7aeo6p?Sud}0Tdy+tBV z-p{uy%e{Mxyr{4JXqNM5iG1k&SAEQK59C7%-*|%Myg8!pF4^Y-mh&4#K5Wc`&#~MC z`Q$yGx}N3kCeeRA^OCPw_RJM|tIsc9m*vGu0eR|h(SZ+K-q#RpXIjw zMIIIW_-`!tHHvJO*Wp<-yURWdOmdP;Z!yP?64uiEWN9hQxblt{`LSG@Tc_IFznK9`mH9o^nm+H~;Q8T% zY<6;_%C!ELULqxLs1^&TY%T(FO7d^kF{jA%AU9P`&L8jaNY>L1j+FR#hevY!EGLI2 znF933FAI-TWS+lFl#lfMd^=gD9UlF%Ol+pg$^K<$N0Q#`@JN!)PLCwn?6XLbsU=C3 zlk>+rK2p*%J3W&9^G=UcIVHT=@zJlBh3@A6^8Oe889CH1_xqO}9!avypC;^8X|@dX z>t)ABvdkAvl5AGSC(ACqEB=GcJZ-;!Ga-!q9{u^1eIWe>pnV^_u|lh3Qu;KJoRS~2 zpgdJib1O;dnH?Xga`O40@U#IUMNd0GQsk8SC==O9dYAopzC8K-v78*AtjmpE7RaSy zI6WoO{%v~JN$0ZcDHpjvep$D>GTnbE(sxeEoXFwZ(H~CIo1K;^GM&(VS#~@o%e-K> zU#9*OZ7rSp&gs{3{1r#L^GD0dD86Ig+51ndFFxL_mz|0I@yX7^emP{~$G*bE4F>lU zHJ5Y7=_AK*{Qd%W{IYRt{uc{AWPR5jqJQS0hi+s!9qsMZXHPzi<>IBHKY8Tl>$2>P zxZ|Vtn;xw8=Z~|OY!7O`Xv;#9UY^?~?$4yBTpzvl)IyHGDJtKfLU??U%Vd zOHPmbTf9Hd?BC;8XPIA8dt%zCJ-@6mD@3A4xXZ&=L-P5i>Yb8*(x=o1uI|a{lT3N; z&mV#Llxyh-l#Wk=tT?rqm%ecE^Gx9r@bT^aP|2QIrQPEvZ@9wevF z*MIW);hngtdTs%~d}{+UK5E7IuRs61Q!Y6??~qFgZwlD&pX*oh^=}@aC*_aKNA@Va z?(#o!`QjM=^@o=oxcxG>7b)qP9o;RHUfrIpC9c{&;eJWruZt zd8qwJsXuZKvmAL3n?ICg;yYo~b$fDpdCT4Tmj$c+@sW8bzKgGVHG};-2fF>sj!xO9 z!%wc|*B_qyhvm-ntR{1%^!g<{zGLU3eLQqGcm%OG+-Vk!t2d#VYpM7V@{D6kv4Eo{!x4Y@T#$S=oxT=0j=vCgz zC9At~N0)vlm&|(s_^19yiI|Xgamf>0@+8Rfw|Vt*{xf=!lqbtE&7sqImVEB^=7Qz| z*5~=9JXy|U7M)(`vm7&B<#eaZ=WJE(g}ivv(NrsGKI#!Uze8A{U-%xn#}Km|6TOpu zmVEc|qLcQoG9Ipy{P20=Fhh-_<4k^U9b?~C%*Uu+602(4!omv%1*Zt$*>W>i@7hc88>Q>|aiyy9nLC?@Uc!?Um)2>gsr}k@K@? z-_dE4&V63s)cvwFUy(D!5!yXsb81+ z)(WuL*(33#-+N^q%W2QAIQ}zxXWzv7jQOitALg)kC*!KkO#X|`ywJ?oHoYeC-+xf> z0i%CX;tPcu>sgMywc_-(JZfK+nf!Zi^TI2b?O#iLn_peC56f*INPN$JxPhtPPOr#W z&RkYg1NVO>e;S|re7fa<(tq^quQ%f8@;;aN52(Myv{#=0hee4U7SEJUG%ckX9 z06|-uCV#AP4{Mf+iI(p|I04g<0ba*T|@l)d{gF6qs>JN z#!4S!tS010{&s|=(oaLC)O&vx#pIOc#j^1%TS>K%B4IVnjT>qZ+CB1~+ zEB=Rvk3WjNw+~ryeiHr{q}G>#>O+=O%+Wa&FH8S#yHg)6V!1a>;@>QHh-vS7)?RUX z-z}fS7k)+JbL-u5ma{J>=X8{>xW1@=&A4!tYhEQ6;CBxs%%eKo*^rU8OzEat<C>s({vCT|ITF6jbw0Ixntv@%mgDE>9sl85q_n4hFs^K0zxk{9 z9O*xvu=|{K*r9N1&2PZyTX)(tCHz44(eww(&+_qSo34AdKlOZReoijEr;HP9-bT{T zdH?zrmV34pS>qopefGyc^{?@(Y%)RmvV(@b!TvnkuRMNtdV|UC^1J>2SiP3#vVYI{ zjPu`}_xmroY~vFZn4s<}%a2D4zPm@;BxEuguWYTOi@z96iwt zczS27Jiec+eEUqhD8TlP?=9(%d|^l?%WWH{*5_5Vm)6HMI1>7)tl`)EL&V%LGxm`5 zGSAuVQubG|r^p{3J#940O?$1}9(sN>{_kray1bu4^3~Y=gzp8%hTf#duA^= zGLz-BMN+<3i*~qxarsv@ zJ&pggGxuoY_*$-)@*Y<6=0_~&M^+xchClV}f8EXgJO3u(@BDb~43>MkMb65hfie9m z9v6A^`g zJ|BHoi|+5d=}+Y8GZ*BJ^-U|9VJy~t+vx!gpZ%=#=X}0}^qq*}Io^WVWA~7J7;D! z@TXh(y}c#}9*L-V-Vw+1Uws}q|GxR=1w^#1Ox|Zp`!=UdnMu3pW_c$sAb+0d^vP4E znok^=2uP-1zfA8B&Z7_PB6dojUU)%!GD}B}q{K~l^TH(xU_^?KzpunUk;mqYn=mdf zcl@{sB2Vo4vYY?PyF$lzGPZMHUs^v0x*k-&&3p6z$niBkD&@^`yevA+uKuk1`c&Dx z1u8K+Oz+2BufR-TXM8L9)A6R~R*Apy&QX_f{7vhu{QA=Pht$m5mHo%pU9tZeXH0m< z=(p4Sqkr#D9lvROY7dpoJ}0y3OJ1wh#6? z@5Vb!`yw3bzM9`#=AqeDL4I(m{06+@m}5UalGE$<^J-}F^8J^8v97}C)EeX zu)ghr)ayad?>Q%~-^KduYecW}!_g+0AKoOe)4HsWekJ-duGz=j|N1Ug|7JSG$)s5; zJ~3f>Ju>YCrq_*_&s-+ts(RX(N&EFw&--|JA0NM6g!fhkIT8BNerlEyo1Xb|s5MnS zd5J#hS@!A25mYV>_T-(b@}rOC(i^IMwEH?(&1GVH)04G?{kSs`rjJ+Y`KYg^4cg+> zL{LgEzNS6$Y7Pp|Zx{+CPGHp%{;pD3A16DI6X{cW_2u-1Q$4||*8o*ZYD@&kE`=A_ zt=9-uAAtw%3WWo8X3m1+;POOjLd*1>XFj<#&GSv4O<$j2Jza3Lx|6mga&@HjkSy^# z0mUVuFH4mzIr8_0h`|F#gx!}L;=hCnz;bj)i)lN?NZC83%U6C1xjfEttj;3StW z^OY>G3z{^jeDq{LXS_LeCPXP!{9r9UCPOY9RdRTV-(=1BH*!+>Ici$nTjPt!zT$*T z5%Cw@MqPO9#vHKsc)5QZ7`vNVX&MidOMAP{KEvN;IeV(K*D7}wta!dMf6Tu(VgJso z73&{Za--ZIFP8XYHyu*I-eZ@DtoIXb&$*k&`o>!%e;rHKS;}(HUqoJhcjbL7r$4Rt zzts6}_k8%zFZb^e=X|-#qq6&cspVCDzr6DDj9K)b>o^_fIVpeXE9)J>Vk_i<%B$(i zcjRVGUQj6g=jI#FyPm^0y}WXJYWTt8xB3;Izkd6rKJWhS`TuG4_ib|ZHGF;xm&*Co z=SO)Ti(Iz)2Y+RKN4i{(d_S!(p|8YL$Om@HX6*L{>)SUJeP_odW<2cQD8)a$CQrVo z=cDILbia+zEx=ST+AmKpE|E>sNgJuDbu!^W9e3vNq?haP;@fUw?iizW($@*79q4wSOP*hq>G8qzzwr zdIQC`Np9sM9KLwO4-0?)HUBZ^qjjW&r}{%H^0c?Y?P02YR30cl)IQPdhOR#P{^2!# zwGVyYs)l-Z^3fG4=Vwdb+mXxLIqQd&_lbuh&vN+i#DT)ExIXot-ye2;_n&_WujQL? z(b47seajTdk8|2*r*ru*)_dw$VoH*5t^!D(Ouo}-C9ICA9@4xB#xDg1i z@^+BlIeVtV$Ix@-P<HtMpMBwq^@S}X-(h{m z%}8(lf@#wVrpv>0a;NeI>v#zV&6Vp)r}f?2g<&IQ4Q&Dh z{z$*9ydkl|`Sb%XZsG9JZA5>3`=w{I?93H;{;OZTV&rm>|8!~LG?oi1MgDNuOfz#+P3W=nQDKelqlS%?48B!piXjIU6MU9nMz)?}6f<|nypd$)KuV};; z3o`a7qQM#q`mM6pX`E!d_xFAOe9t}41C#f>d#zp0KKtyl_S*5MJWcpxYkMi*!(*mD zI|+IJCmbHyt8?-az#>=qC;H{CbV|SWIr9f?y08$#$Nb26Z06?eh+EV6`5f){()yVH zWuBjWZqq$9{%Y-F{QcO!XnYnmf#08CM;3kGyeBcny)=oUZ~aM-*L=pDzDC4ozo}b zCH@oN_^gK&wm!*Pf54Yc(MJ{|4#m*B~g_B)=p>nYeE;@jp>W|(wXOTYK#uq z@`ATt#qi-M&VTvP-)}`6cK~DGtel#O;9O6f;t__O8FMfYT!L{f4==$*40T**!~AvE zv|lTi()-qQILAlxZ9HFiB7SJz9dySdDC+*1+b6LXZ1{wqchgU!>HF__M%wcNoI)%r zqgGPWlD{n``L2!34~u!WoAf=;Shr{M@_HA{rzYg$0W|75^qPIhzO4BT4*$a9Tb@A5 z)6RJDM{m?4?ojJJlxWW2h=@xctV1*;)Ar3b>t3ybLiYy@Wv8I%aX{=g!@*brcB z){o&01-iY1o}SYDYM-1=i}6qMdckK(!gR_m;G|?vc5))T6jaBU&(6(F5TdL`Q-&gaLSQ{hc5Aa9&s>VQC(Ed3VrBsH`$X5 zPdo=>gy%u!Z>)FZq-N*p%OAi)b`1!a9=rqx%+F75=s1mQ6kv-2!HNcXF$QG~s(y$% z;5mIW(voNjxckYc@4$4&mU8G@2#?X}5HO`zzoFtcVH#eWFvw%i4%JDiV+_^Ff-UP!TptY{v7tb(k17CTLxGB4rB=lc@yQM1 zA-I7#J}ZX!)D1m83pNxmZy5ai_T)(Vv^O3k&j(Ii_N65!`c64z5|tm=1NpKOlG4aL z2+9MoSO;Nx5ra7q)Kd?1kB_;aci$aqo(2v6PVoySL4t#!bLjunY>C?m$XH9yEFC7CnkdrwG)1RFpatoG5qLbW#w+&qbl%fclo3 zotBu(TT~!_*~!V7x!DPsG)n^Eb5paEVZJ6OA%!xu@wPk9$MnXIRq0L1%FazonJEgX zJn_(o?1b!@R9>8aZXKz-sXU-LAcIgTAE=@90QM@+oS8YkL?{GRA@Tf${1Q`rr*kPF zSGn1kEO#PAvGZ!`C4das<6v4v+mYeT`4|w;ppD*8?t}%xOv- z^iNHm25k$pD(R>I`b(KfIzo*0pV+@*3A_C#^Uy)p(?J{T6-pK7*LmGsqCnD0RPE33+3(;j$pV0{WJjb!fxt^q1k z6!`oqDr)D8{WPX$QT}4=GSj&hydGOsVPI?z4GUUWAIqn>z)$)-ND|ri&=?5rLLq|n z5g|@3@^kP=H)v7k70+J`IMeFT4%5Rvznh##WY_T)yCuL z@h|7?k9;VK`Bv?Inkq>h$ok8d$I*O?M}40z{-ka)hHtxs`Jaz=-HNz#1>@E)r(w0x z8eV67!Yk94BkoZ9Gbg ze5l<{_B{XDd>TGHd_XeaxIS??<==ZKKi}_WXHfm>9?IAr9%lk_XmrgDy3F^9zJkd| zJc;S_$FltMf8T!v;uhT=z#2cye^k^!e+=smUgyoaoW_4qYgv9?*Xxht{opvp3$8!; z9mFoRUhYq=`VMhe_g4ZRCS&;(o)`8Nr|Wm7o!D7R@*}x^-n+2xTErd7URp-hvH7(% zl`zNhLV6Uff4SCkeXTYx_JQ1))SQkhtC)gXuzu837E~6|vqC)f*nxihbuZ)e+t<&i zKXGmXd~tK=i?DIf)0G&$bziQ(dxg){2hyii;lan#9M z@i%@LzkeyXGYAK(coQz@Z{P`4U{cGN&jpj#6nXe~^U^&9u*cW<;Kf6ch*JI;z@9sQ z4mu2~tejT{I-x#Rk_i}nefMrpSFM`91?A(CIel!;OGn7yZS9-vUk}0Gz}d_nKCu|P z1zPD~e!q7&1%E>vogwn*rqnocY@zMouxroXLo>e?MY1?SRkcQhV7@A^K7ha&UrA8CXhq{KX48iWTH&i=nPx^x4CY+BdurgSr}6 zznwqm)5Z59A9$4crGpm!fml=aSoZMm?HckK(ylObuAbK5oWwvoU<pt(C>agzU?N~2mRw>X#Jpjh<7pn(qAt` zhi_&~4&7E}Z<~nW;u={#_JuR3euj$}L;5FRY_eVvfK!X%l_;#DuMFg)GGK~6!8-CMuWk4n8{TQd-`eml8~)CQyKH#34gX-nKicrmHvEeXciZsq zHvEST|7pW}Y*<0vKb(3^^!G*DE2;m|J_z1V34F2UPkQrR=WzdD_$b8-?r*~f*zf=w z9%#dZZ1_MMKFEd#E1a}+;?MYJe5B`gF&gJI+`|5YbiCGzW19shP>N!1Vt+MT7VkbE zZ*+Xl@00jDbSqx`8@hVTPa^3H+tO>~hk5NK$v@+0=>KwgB$0e{4bQ)f(HLt1E3VV| zWC|Z>l>9JGRsIxZzpJM9yN=POQTVt@?*9n(%whaz{W6;0>G-!iKMo&Oy!bB+=;cS# z6I!G4XE;Wq;jdPzmlxw!9iL6{m-bkG(}{O&=JF7Kr0y_352+u<^XKp$6@HAyGt+fD zq`Vl{hpjl~Ex{QSpSwWHgK?nLinTJqnH0WN&p+c-b$5uvqe!OSnUSo{Ssy{3%|?)cw}N`txNRrTjnX{@U6lz2}mCt%LDv^2l<1?1$ELgtJg7Fuxo5pmF!{0zAk5|4NasfS%kn$%h;UnqmiJ$uHnLncbPF4Rz zpTsY?C;5GUpLGbzN9Az(B83-T^#3wwB;_YK9b^g@*HsAhSXMJWTt z###S1RGC9H?Vl`{{O?Z;n~a_|8v{_G9?=FS-4b z^606)*?Hr6!63GxL?2H}dN%f5g`XYGwTJaD`sxGfs(CNAraw}AqR$?`VByCN|6>fs zSGSP$|GoWE_!7c+bP3~}XOH>@vHzmp<43)CiGHac-{1EqHGpj@KZ9>Low{nxm-Mbr z(kJ>v|D1^jyovF|HT*OA7bh%Vj^XRB=J2bBb+-}zip%%U<5GtsZd>us^htUmmA|C- zkVhtML;ZoT|5<&J`sTf{_w+=Hzo+uMvHk5`n4XwxS-;e;Xq$g2kx#zhIr?C?FR;#M z^%Vb<+osU_(sILpmVUdwNLbSM{ndYS*Zd}quX^~LTQPriLB`kLbt%2ioyy;qJU@{a z{7>Wir{Vvv`t0eG`qZ)h_UABv-4FC$zIJ(gdPHAO`LWB}!^``fQn8KtFYR|ar{~zg zs~^MkdTjpD{;B?+(r3?4Bz+Qo^c5wvKPBcKPVc4nJkp5i3n~2H#wYqkK2mz5{H9L3 z^#F|D+sx@1*mpl3dfx9`o;~RoeT}QH+JpK$s(x(!y>cyL*Ile{Qu}fm0JJIGlRkTX zFdSYzg%|$ke&0}sy{p`seo3Fm+x7p`^6E)m;V8V_{|*tth>G~LmXCE!i)Ur zS6o2tfADPn{%-zo%pwdQc#Y-3{)Z0w@PU~I-nYyDe~q*6|Bj~iy58+Q|B|1c(j(>5 z6CX+5&Kvsd_7joDgU;bGU3l5+Ph-}z>+rtk?f)+S;*YW8BbJ|c_iME7tF7nyJn^9V zVW>Yjy}EBJ-j6 zIJ^m$>|d&2sN-UVwdjNC{m|TCD>FpXp5AZh8l>t^VSU5a41XJOV#zKfCNyGm z7*9LPOX+CX#QB@>spn9Ve~Izm3vcHB_sfiLZ#tRAYk@Y#p{FL$dT!@mjKBC{{SuOY zp64IFDQvtDvG*0mSKl{00df4Bj6eJG2kJk!D}R zNBSBDGcLdAO8QUTQ6sRWZW$`BG%OT4#$igyBJ~cD(3H7S5<)6 z{cpxcoi%9$;*K{MPc43!s$%<_jI)lPM(tlz3_tH-D+W`0)Y!)O$)&tMwq+_~SJx(* zI&Mm3yz!fpGf{ukA^f}^{r+LfU+Y}vPi~z@_0Ofo$Ke0643@6xn}l+||FoUPU!})! z_&{MPv`FA0v$C+bx*GTM!)dW#tB7Io`YUsQ7k|6e{ffhsV~qBoXhE8l0~>T;J=4B_F52UI9p&q~ zIDFo!?mH2O)PCj%e)yZ(W9>KQCk(hbhl)pVqU`E)K=!J7o+<)*r1fp zXFP&;(_%1>ttg~gX{;xN)B@P8k1lRP`Iz@v{_o2+(ED8a0pkrPWl;T%{*ZCtuQBl$ zzI7y*Pt^~9UX9rQ5%WhOfa^8edfVGJ{DHz77T&ZT!#8}z^6yQZO!2p?{dTA$7jgkD1pz zi+t%Ye*XquxP$uRK^NoOuIt-{y#FD_qF?%tooB71{&L_1=4TA}{5}j{ca}B0w7(*M z5(a`x)<2rn`pT%n`9){A;DtNGH46Dr;NGyZYBBxI;d#EiQJ+uE!P{C_A?HudM{wOG z^Zm430roDkUNf7*#|@GBW~%O5qw=>uMk^$~RF`Mmt^EIw(Ta$#*XM7!DQNnP>%$nW zgm_oJq=#|4Ixk|3MxQ6m{h*|;l)`JJGXKl3YwSCskFo1*#=b;$$iYJJJxeT`KhIYk z$X~=?G=&#eaIzH-Hqc67j7HTN&M)Njp}jLWd|_vI5JtzkJq3F5EGq!_ouon8|CSUL zv%N2b7oH>(4=yXjpB4GTnp0E5FCf~Nkw+0-Kk@SmOX0jZil05^`c!(+Ke6l`#9K;# zRq;Y_gGd;RwZH?74;-ZwL;I}w>gpQmKI+(rUm14m`fH&_kuSvq;SJkvj<42NU0R7p zrP2lV=im|1>@Tyd+Lu3P4xABAJ}}8XG+wOxFg?Iy+Q9CN^#O)09r!I#*y6yD!jlt4 z;jJDHNk7A`)cdiBQe7JneZ8~Sq4pkCJq;cZy_VM+ROa6_k_2CPev zV7Mnhr{J-`DKJm;{LO9b!%bpPiuKwke_Bb zj}Q-`1mjOVeYpQJ3u9DqR8)e0o?^pasLz*?m6WX0x<4Z+U+5Us!0V?wEQ9@KssLFb zycb{_s~@)v>B*vlR-^<7o8njgs^mCD&FWoN)0BH*G%;886a7~i3h-$g)|i<8sp-=b zaR)c22l8t^o>7yhDft2WJ@Bt<*k4yeOIli0Spi)>YWS5uEWMbZ{1cLrvPC__H$8c# zjxhe*vnnwV8-0Ct@du7+Jhi69!psx_>l94{)k5};v9;c@V{goLB5dIj&+smh?_%GJ= z!Fa+{UZU@Kl>lfz!DTZz%Lb>kC?fngl_0x*`2JZ0Bs>j5KpwuQ`9($GVob#^{1_X) zNa4cG*&6=Sw(vg*&%Gwphv_%;?VX;2`SWOV7sn{_lP7Zof{#)d*5l^SD>Urmg+EiJ zXK(*;9A2J?9$wd1Qf<~K{1jXK$EXL0^#{zC^%O{WacE)i9HTwI5`Ns2<0!=#eor~^D~u}@x0HQ&AdH6^v_&UqCZYupUNKAZ^!37PA?y5VZeX5XprYqv0AD0bJ6^W! zO|YLNhaC+vt=ZfiA`cGYOY;?t*y6t(aGm)ElvgD<=!4c5Iu;-VJPfu9_5Rl|tuLvH z+pXps({koiqRGsvbT7 z4uGY(*2F(pNb&vs7gEz69k0SGe~SgsF5nRG(^*?+exp_A%c{x$A|?th?C-NbMjof` zI6UJPydSOnnIoTHU0BAWP)(b@Uow3vyf5(l815f4^QXe-ef-3t{*I6&~)rb?|RAKh&x3N1?7^F>br5 zg<>22-ILFtXyXh?kK$!N6P8o{e7!?tsNXpD6y*?~@w~Xo==#+ll}AS|eMk#WZ+-=M3zZ6{ zhgTtxhu1;pp*CQ3G+}xhbWBNwty=~2`4zBw<23w*(yTkAx2&382VGwLiHeG{YCa)A z(gzr;yB@yg-IxzSjppg#`c_s=ubR?V-o2)sIf z%NxiCd>p`3}YZ@!8sGh}}0k>+c#Cw;B1yTa5IXYlL0@ zyK`>{VEE=nBfPnW)NMMS<^mg>`=Ttek>1j4Qv1M zfLl>tdk_9%|NV8vqsRxIRP8^=o1eH{|C&=D`WwT$RvGCt*HC+SOpm#S_IdnY^zG<= zp5wcza(gD~i@DR#NA0nyaV2->pN)J-@q6o6?Y9d5?y9r)#qiO0IhXIaKy*6tt%^T( z-nglV{dYTux5sD41CKmE7v4Tlx z?5xio{7d#2|K`f!|1lGxO5vF=@kAY;M5trH>o>lxrTm zt^M(*kJcAjpJ4vF;dL~!jA~Wk=_p}Hgc4e^V$wG#SGPmzyKvHfqx7gv*m`>OEzdr< zV1qSzP(}%uuYe80hC^l3(Zv{z=JS%fBmFkH|AW~SB9TW?a+${WjJ@I<#K0^e+rLEt z$*V2lcu#m;Kb!}(pcdw1R0o%4U3@TLDk`I47h_|{##qlj__L7|u*Q-pU6O3BOzUSD}4_=DAcLc8wNq#ZUczqt6d=mbaZsYju z_6hfYaLI$n2j6F2)>B&4dW~Hl&Nt7&;f8vCbY7t}D5dU(S>CdaS5Vd}h&C4baOh4j(K41V8J z>wUEc^t%ny-87!-i}0V>)*rvJ;qPtuR~x2}KIoP4>=ZR$A^3PTUY}#@uk-vrIz;0h z{1}b*KX~tx^ScW$xmr+PkJ9%K!&G${)Gr-ZR?OA3A5uH$d#gRI+9!jD{l(axNcb{X z_N~)i$lG`X>W{gF>)Z6SALx4%tYJL*g>#l6U)qmxM$TKC5I23s>toL!dv*q5_kqkW zyZ5G%h+T&bbKHKa$e(DTkN+8m>;pM)=}7 z@LR84vUxqV@3G3BUfK7{a9n%T^;H?_YdW6G|6kuHQ-95?aeceyu~Dxe-`q#qD_FoS z3@jFVuCgi1?nK`Im$WCvvUFTw%5dE4(I_`lrEtSpO^69r_~bYw+0fgD&^5 zKB&1UJjTp7!G=!)EcQh6i|Rm+fy=3%_4A_-k3jvgr*eFs{dvxLh?~+mzRD>FB_VE~ z&U{hfotGl6OJ^MW>mM}U=)Qo%f3*7D8OX=0{qBEvzjGbprhMj?z4O{Th{G>%`Cgx} zlj5)2!uZ9C$y<=`x{UQtf1#Y}XX&fVzxV4(`tWxg!Fc;wXHfsU`*+4$w{NBXKwMv5 zPyYGFg-@cs80F9C_0!&?=a)K|`QjJ$(D7g4bpM<2F)x2X{h_X{j6dEr@dFIs`3B?Bne`_i z?oj?VL!*ZAM1}Had3Rs`aOCTbK}R3dACb0{$&r+oywl+&-*U819ALT4*&2qFMf|W zPT4p8{NS6^Kdjrvd{*)2&m&*o#?Nn`{ZIQDaou2kAHJ?XzY%eZvVY2*ci9lco+Fqa z@c8yC5WCJ~eC0=v(0q$Of${ETk5m2YOk*6%_S}o%+p`$g>|5B0IIPaE*Wwjqh&=2{W z418-C=Fj^&V`V>us_3fRaXfq_z+OxF_f~vfZi)|y`GUkSJ@3YEnD6KPr~~;Jb>7Fre;@e};x6T1{F7bDe;{rf$>C=&om!4K<|xLa zzIZDKanwM5KVQ0kL=9r?K*o*@)|Y;`Hb3 z8nO{_=|a}`%iQy>N8Gp%<5{z3?L-{z$9U9>Rbym; z;}NoI5Pw_Z(E8XDH=c(2Qfpa1$s6vSK_2|~Vs}wF5GMb+R5$^;V|?sl0ZK?gp)|X z-wpaJGl@w2y1Xx`Dt}I8MaulelqB@;2_C=n_DRZ1xv$6c@aR-2knyR^2vGT%Zc_Xv z7iToS&CUbw!)koY<9Xd-FT@W6=yTI@(!j+Tn>3or<8Hk%Ha#xSD8R*g*9x=M=q>qi12TYELuU)(a z^#|PY>h8T@egOUd!5COgqL}_94d9;*{7rx8b~5Nsq4t&e)ad zd-U&ySeBn5{y9+j7eb{dp>_@42RQzhT#a#jKJXt}X!wi+dG;4a-r_L*kR0&FPl4e- z@^5B}P_RTu{?pKRDkqP^n^%yLH!lz?EaDVCU^19MzSf4#4)2gRJG4V=c7TWTRp5?E zswepW&CE&DZ=yeA@_(#*5CmB$UfsM7c(_wo8ITDBcz+gF8Sbxv*G0KJ6_ghUUdQ-T z)mkD3umuPC0+{bMy>B9)%SkrYr&uH8F9*E+!U8l!hvfwr9PFtZgmd8qOEmGBS&87p zIG5fh3=gh{lRfDPiEx9$Pfg3@(ENNe5~igoae5wv$;OBIyi6$Z6!2FJX#jaVVGVsG z(|29r8QE!Yj2z|{csw2>2iz)S9E7v8Ef^h4qAuadIk|EWh~d+6=p~{%h`|AvMV|Z- zqLq}=pOT(1EeBk{V-?2mIn&cTGbnW&e|mC?UZ10$WIw=u^-J+(<|b!nCeXNr6=+zQR384|B?WmHy@Izt{u`r2-n@Xx zyrF@y?w%Fur}$s2r17VL$xkz-*L=hr@I^lGq=<3hh3SJ76k(6tf?=A@f^nH%g;!^A z(+!ko%nA(53J^nT$%;VqAy(=sep;V3=`Vok%3AQbixHqa@uu`p`-;loVq;rVc|dq{ zCkSq-^XEVTtHQ^krVGu5@C&cw%K18#eb!8@#$lC(-erjy*qe3^1QhN096Bp+87|K;$43+B-O_ytsIt@|RhH2g*YtvCg8!BJp721~wlY z9@57#P_Y6J0$>YQMxzE!uj0|O1MpOvbdx-o&odua2z=#2?r2 zlvXHE0@DZK7nbPmK^5j1CrUr?)sR50EgT+;8>$#38RZen8&C1q8s{}4ErCD)~9zd;jC2;{18!KE6uTU)b=1F5JZfE!kJs&ez+6 zeL$!5XD|r|ZCl{M-}WE5Kfn3$QkqX|JAlVKnBGMu2dZ{?OJ@i4JapOWOHg0yfh-T- zo#|+Qiudrc%L|tIN(wI@QwX2@cKu3}Yl$}LgCo1JZN}@rm#?!JebIs=SOEPq@Fg z{z9;~tlEp0{I&NxWGd?G9LoCC`2(;Z!~KgYvQ~zJl+Pxj{O?PUq>=K&Rx-${M^ui@Wu%AX8!J_y6#MVNQ!N(ds~I919I{qGmn z(I6M@^Y{v0W()+E#4qWG?=O5z3OSw(|ilKbNbW*1HA*|UBk`p?@Ld4!w-x+n=@or*`oDfJ%KM+> z^fau!uL-gDsehKf88DR2$VmfB556RQ_VSnb9*8=$2t&F)V*N|+yMpY01KSy&RbQ|j z`RMRJi(lds{Wp(3fd1_M;=hyss{gkaVEnPlpV7v-<6lPH`L$JFPwnZ6FF$=5hL782 z4R0@xp5#BAltJ>*s(&l_`=|11{7L88pbfuWzV7UsLYThh-<;DoE9LD1mRU z9;d!y+a{jxx9bz!Q+}==Je$@lqkndeuP1q_-@@;UiGoY;ehi^MlBn|PweV723AKBu z{nB3TJ^d11^hY(>Rz_=-Nk@AJ(oUTng6HkbK)p3bp+j+OT|HQ#{yBXRpACJHXvFPR2M zyyPkjZ6^RT*WA~hq0=YlKqjnk z_5`{_#iEb>Sr`U+d!0w;vmCDg@hJ@Z_-gVoemwrHO4I{}{Sl`5u#%cU4#w3yo6BGP z7c}es3uw3i8;8aJ02o=p)soNeCzKD&ZR7F0YCQ;Mk7)lsg~Ir0|2__@D(B#NF)$wS z!TI4eRdDPxgkk$HvHn5~d@<}u(B%QwR+!F@$g}RJhI7YiU=N#qz7CvsYu><%dwtCt za+JM*Y`5KOzbcF`tH2_t3ipfRDcCUIhBHC>iU;o3Gw&!Y$J~^;^d$~RKkV1n&Dr$* zJu!Z6Pj~+I`PG!QM#fd&w$l1<{7S|zpT496`Ls zP*@H|pR_oJ?&pV?Qan%0&{y@cs%2-UYc)x0K>~Q?;I*R$@^VY*x z9@{4p8n{ zc(g|>)aZXx0J2gvVTrE+EL5W*-s5x6p{Bj*Q`${i#=oPAIvM;Je@bEc>Z5;LY8lPnSU8Q%tiG0ITj2D&|bF+9~>?P~( zV_y8##5~A&>YDRuJmPIp^0ovlv`)`xAG9`8+Z=A?@Unjh_|f@%^(B{Kc+W>%UM3z+j$91k3*i7&SaN~WA+cZ$ z9_&-?7-k_&e2t9<|L<1$s_Fu*s1PQYYLqi5&{t%ICVgn%YSv#|hh8v@_+ZV*k{XY54`Y8JP+`a~sv6XU@-2V!`|m56y9sf$ z@~?&Ap~cnp5r!62Zj3*E2K9$EWp6xi=Q+otyr-`bUzI7om_0Dj3|EvoFBJ5tCX5q& z%Jjd^M7~S;`viLcX)!2EyAS;7a^$;TROtoYtl;9Mc_$zrA0_dt21^yl1Dnsd0{Mpi z%&)s<;SR*^WX3Pv=<1KSUD+E${1ycT|5`2r!9Wnmal+Z_)^y6n7cfr<_Oa#1i!ySq6qjj9a z<Sev)E|u3cs^jx&AtK1M<2j=UCuhH-=(8C{2$9-qV+D1vhQ47z5Hwp?;XV9 zk8S^s><^oUFmCymo6;LTl<^%8kNFbA`$x0B&)gHKzP25~{C#^msekKIc(6z#G#iMFS&a9 zkBCb*Gk$#5Ge;tB-NLxwoOsHAcqgZK);?E|e6yNwcz-fP1Xth(=70Qn7RA@}I?EqB zd&z3#Bu(?VtncC>*#sc9m@C_?Wk9g4-92|+*|LCMjWO3gF}WK=|`NZ`kOC*f7mR< z?xQ(;PD=W0#NjcFf19)CbHp9WzVo!y6`K)9k7s`H^rNVL#EfJ7{f<8_MZQz*cUib) zE`{$>{sVLFsr~}_xC=S_PorP?8F7cg)osHP5XUZMzPaMpI}x`lyz$1zC_kY~nZK!f zSy$OjHgX|9h()c`AWtaGk>JDMNb3c zAx}=F`G?ehF>bkV^1T?o>1xL3?QEv?zxZnzAN|5M*X$fe#VNPvGxEK|e2im0|tjH4cAOsGZv9u-Y$hNZSSXA>TBS!(ZO- zBI-}ow{!TXcOJF~`B?Ff8nnbmd$)8PhuEXOch^q3mgdi+_i*@kC$9Jo`RKzK zKl;$e^nSJ~od0ym66F0uncoz13e`97FvbpFDLs_=x)(BbAzwd<@qpKcPMe zVcfm$uB{k8+Rb?S-**%ub{)vygSY!!cR%9hB<2f;Zu%B+>NLiuoiUI4AAy57{IdOS zxfc2O>C9)(9QFj_hIGci-N5HFbYw8z{q_!8k7z!OOaI5vA)sqLq}n_sOj9^9(>ktsxR$|zhvr8YR|jDAr6lJf`cE2 zULmyKr7ZvIqdyEqTw2C>OJy|07p?s19`n;`?%%2X*Ei1IkL3OHIJ_^f0`~qE`Lc_v zYs-tlFX~Aer9Ci5rSImecB1}}itmDB4oyMaGGEF2%4_GF{PRNpvUYxvdH)Ic@3mmy zP5V`zJmwPm-f9&leWv{@wH5O!Di>Ag8&q($(j~?;kPdji>*}Dq7f!%bLI0*=u^txj z(AD?si@!~Gu>KRXf2I62u4YWmK*Sgr!jUma1-XhuF|DX9AG~i?*OXB$gL;kD8m0{~ z;3^I+2*K+xOoTyr=>MR9pz1Q!;i3IF;Bu{|jE4v?-v$L@+)(z=K8lRw(Xx_F*6=2r z-wbx_CVN=0P0B-iOm&OTQ`LQZVtJsYo3eI8d03!K^x^&)u;TY=(U+#aiE%Z(#r5f| z*(bUXht&Bdr;T`W0pd=zpXS1s(&&9{e22piJ$(n&hw!_Mzq)4&^?w@PW8Ajy@AN(I z=wSTguy5U{ukJ&}x20!1gt$$uXT3Li+r5b6mA=XS7IY!*Q2TW}uNKn$KI-R~J%|n>~C2I5_3?KC?wF(A>7`4SUQoOUwsVY+wMN$a^yX# zy;=FyIXQ@1a=83fdk*ptU(fie-^SdAxcO+7-|+b@F2unxjIY1CjLI+d7{*Iqe~J1Z z!R7q^?fxP}?Pt@m%rAN@gTBx1SjN|d&+b5doeHnHrhYl%#<9%by5^@x5yz|jO1US` zPDb2tJoBxG<(DFkQ~Q@r8$E;C({^z177h0&R=rL6am6wI*ROBNX6Zm;u^74kO5xeV|FIn;x^$%Or_s4bD5}Hr-rgM7UetF;{7~Ye~_`1;t4M5zj z@Un_yZbe-8D(m0z;)~Q@31)Hl>3KhnMZWo7j&IUcyx%d^!~EK;5ibxQz!aYHlXFJkYBM;thX<3Huh zom3xUA7uW5wO>z0zFpz>2By~|u3N|a^)>Zw#DRwxhYH5h{6W`QtZ()!lfOW|w1xSn zzj*0P#I3OH4(r$Bqj%qhIOiVE)yD@x+Ie|8?*5m1|L7=gpk|rMHiw_Oey^U%&L>Mrx1zE`GjG z#1+tdWfZvW$MSgSl~Sr-Eef|?9VkJ4q0_m%Zt`|ooYYdqW4dq zhT-GY{=KW#q*8lP`V)umyJF7}o>!alA74=3G7#4lk4r4sG>cdY_-hTvRZERyZ;*k12-tyfaS0Zj2#eB}r zenG_XYCNp%*xrJ;eJt}A9`qNDM?21BJkC9bzW1?H7+38coQmNaM>Br+_;l*eyWEU# z`Rp{Tc3L2T@l!K@rSDbDR2BZEtEheJRP%eZe-YM)>7@iYv=;^Advw==YBZR>Hd*7t z{4$x}>&q(;eo-kH;1*M0_zzs;fib!?5Bc)6m|kca+bWqCPFVXF)%Z#L@GAMh`NyX|1R zjhfZe%(nh0Qc_d3SU2`ZY_k1FUiWw7$;-wMwT@w1T~02Rx3L2qySOmFSx|<)2&KO( z{%~?rv$JLxw)0p?@n2v*IDagKO(ts1y`~h_uT3t;b;mmp7B6xhU1{>i1N+;m%D`0* z(-1$5FD6WyL?02j2lmAI;J9agvFc#LXr`tNTtchhn!esmtv2YdtpXGB8r`9?o?rCm z18)w@kD~W8)A~AWPb@0aZ@_s1W~im-`m&~;os^a>>67x{6G)8m%$b>SZgMv4k0JX` z=?()9n7rF-+5#K)*=~Tb0+^HIN()~&-48zYqeo0piFoRfng2&W{ZrSs#} zU?Bh;YD0zL{pY6O@`E5Fyfly;pCI5>_&Pm)){kk& zOTr7Eosfz4MN9&p0h@jDvW+`by}{avgyBENMtqEo^*sqM`X#&-LwI$Acw=~q`q92h zf1eblJ_DvfVg3CRUdm6fq*$<|Sg@p6@Tn(rf&jzoth>YG{MH&bn73g_zeo^YBuL83 zhGEN}WPrj$`N|E(u-#b&U<|2MHza(W1w-l;ww`u@^#%Ono9xZN-U@ApO!jEBd)kC) zceM#yf@@amBk(6{@%9e+wcQ~5Hp84sBWyZwf-q!XzAtkAg4}@lA+%u1G%$H5H{L(; zhmf3}oX9OE*~iUF&W2sRxmnO8=vY-?_`Vdup3LfbI!;N-p+<^6wc zud-bp@yY4%Wj2LROqb8kUg7tahxP!c$W(@{2-BOHl7wxN(hqidKJ*D~#Am%@Jv{-& zSxKDE=w$wlgn7TDSpQ-CXhEoN_XG?nG?iCUa$>qKH#x(TF8PNCkdcs>4co?(VCD$s z*GzZ<%){bBYneLzg8l8nQ4zXJ9X<_5?+$3VTM8{ECBK5p^XJl;KsttMjXh8u=fn2V z;)R;pUMt0m80=Ye2>nm%9jo_z@NZ7xb$0`Lc)26t1#|fs293(TQa5l!4CXetofVEG zs)O<&1EnfB1V>@q;LGRw^>k z4-O!u^+SDgCO{uW_gG+H4ukfWRmEgVqU0ewJTS4!L>|9j=$jF*fI84b-dDk7)e5}J zokHu8QOZ7og#P#6|4QJ0CGfuz_+JV9uLS;A0{<(4{~weYU9QlCo<<5LKQOU0=bCmBEeyf%D>GNj^ z=O)8UOmbpcW{Sz5yCgC?N$KBXl^5PE{J6P}@w@)5@_&sp9~AkG&U~xzBj!2kcmJmJ zXE^g(vP%DYXFg8&?aq9v@Pp<%#_tz?vNP`*qv9`j=9@)+l{4QV{J3(*_+2SV|3+s% zUie+ke5vpwDjfB<2*1>s4-3ED%3JFf_{f5RRIU%VP)W_<->%=)^BYv@7=O3uFL&l+ zr>XpJb>;)Y&ki{1Zxw!{mA9rpJ<*o|6TJ!3$d{Qp2ldBD{a)#)zg_h2vg+4$q^k6f zSl}q%HdN_fYUOR|1J8)LaN?uxjz(7>8mIJcx5`U^ZqYxe$}#@f7#06yEAJHlxf#i1 zQzE+Yw{)b6zuYP>VcepBl{4QZ>EG(iN1dqj?{VhaMgKL`j`{P5{D>MyK2Dwg>>hEe zBVRA_8P4);^8PP%=Cxs}e78IEp@UTZ2Gv^Px0b&rD<{nhRWu_Z9VWr0Z1J~I^p9I; zk(V&B$0+@?t-P)uoa(8gM>Dcu1tKexT>|Pnd5JtHFAdHn#VLBxE5B~hKVp$%{I0`Q z{xh6;kMK*K`BLH6JM&(blwX}={M{nI%9(E$`K``;^bsokdz^W<@Z%Oc#_tt=wlnY1 z-_P3}<%1%>(JF6!J~_GB$=TUi**<;#Ql3vxp3g3;yzs5Uk67XuzcyUuf2lJcBm8=2 zK2G@U&b(jvK^Hp4pL&#fzU!U&W|7}+^&OZctM zylaHi4`;qp%6HsSi~haShl^iE+8p?qIi@b$-aPp$=fy^OxbPcutSY~ak>WRPb~nk# zOa69Q4@+W+^@PjUKw1sBPV{egmTwe((6x@~YmbnB zZx+}bLSeWkU(3a>S;uD~(ZAHHUw^+m35nC8UkJ{Jr-3uwtZdsCutVgxTjllgk5%O} z$a#DiCF94*R(`Mea}&T-?OxSGbBTPpO&~66g{6 zRaSXPf80yGKfijB-__{&e42zWzuu8=5q`Zh-zNMnXFh6u@97JR{Kgv`LzWvQ zd74|~cUk2nfLHk0H#w%iIYRoHr>gv2<1F8KwBk29^9>UJpqm}zkC*w4RnB}zg!FkX zKZ4)?JvaC1OPRL5|Lqe0xLX|K?~0&5R^~5eJIiaMRQfbAUFonTAAghjU zk>75W$Fj$(LCSwyg!E-3z(6iHZ!q0Z*n-61o|G`5n^~X|vV(O4RgDQ%-3l);|ZFJV(DDm%c z=0n1dTV+YVCH|bm)Z`@J%(UcmF~5}TX&n;(Y^%Hk=n(zaIP+b??{ellq^c~{qR5PtUpfXhc-IPdqn>(XFmRDRX;MU<0IcRWxj&nr;NPZ zWG@|PWUQk zK3@3CoOv&p=i>YAzrmSzi~QZre88>bH#zfu(Z9`^k3UMuf9lMqO8h@K^K}w`-`5?> zw^ZUE;>-txALY!)$n)Ryj^p!9Rebo@4oALG_@N&<^3B2@>&%CQKdlE|<`KsWZvMCrZjkGvzK^Yn?|7N_H-$Ss?z6v%4=LVN zGK%V7IBG|qekLC5;}%yG`U)z+NEbc(fvubmc4zo-lQFn^(XU3YdOxd&TfQ$6pgmRb z6Gu4m&2K6G=p!w>iXXRh_-cy5)gMI;_MBpXtRir|t>o`H$|4_|&h@&hk@M#-9IfpO zGEzQuM>8LnrsNBcA$j2?{cY=ceBw_$R-+A-YJQ?g$+s8qekK2B$7=hT^lL*|zxL+7 z{C>ke;Ql7QU6p^_yYl>YSe{>p;#;5N{i@;a9hT=8II9o$3&0ISH0TYNhDl!fFP%zW z8*m`=b>Tkd_$7bwQoowQmiNP}+68wJm!JFDu%&*Ks&=8iOz|IC`7RZISom+Pe7EA= zbCvv`R$e=Y%P%PL5B$UuzofrTrNjN~r;hE9N9E7G;xkMB)c$~^v>X_fgH1DaZN*q! zl*4bS$PfJ7A}>Meg#6p`{jF6#Ugf_<#>W?ZLE~e4 z{cMu>&-~IcePJn|^lu!?CrXWsS$RoDG#pb( z?aP5bI?m6yg@4YO4+x+6lcRi>ieH=Yw&q3~I)CI5ex)<7 z%~kr>I`b`XY$@hn`%3GJ-w#c-|MPx{*6`mAXYAA0-%TNimH%}9_TKpo=k@DVe!~&_ z_R4R&uy@`wEUH)e8_w(BJO51Y{DvbA=v98(83P=7DW?{XJl{hcpPwIA%&2ttKa8gb zZR-PVF^YfLnGeE8o8^Z(%C`tV!F^=(f3;*OWM_z+Y8Kr;d z;f{Rw!HR#+nGZ?*UU`IL`8J%R%0GU%Bi}0gE6#ko@UuoZ%10lf(l_8p$MnZZ{-!(g z9V-3xEoWNv`-gM?$8{6;e}Y9*`W^(8O8P%izv8kvf5D`)Eb_vq3O_o*k*^cJILX3y zC35^)4bM*nlT-R0W{Teh+w1AMb#wnKSe()qx`cZA;)EZq)PHP3HJ`a&xH&=)C| z_=WFOTKCx7i z&c9t;KSTGwSN&-{qJz5bN{zn_zEj8>EG~7gzx`_&grM5z<-_6{!g=h zUs_cC_gt;&|5MibA5wgMgW_MY@}fWfJ#HV|mw6oX?~?pASjUedALvl>L$V#^JB7c& znQv45H}?@t`a0Yn>ENtpWWdSA(p%C*Q#u*MCl z|NHSzec)3K7e9Y_emDH#+`kj~D5+Vqq&{FYewH9&@c5r1{zCjul=fh)Dpa^eZ;RU z_)Sr~wwvcSv=?UeHMbAZBh>frXT`rctM36IC+#mOf&bh}Pw27p9KT=QVVsW8=<^-< zpiA*Z&U~uqUt{IjAAwr<;Dtpvd=pG84HGX)V$}Kkd_v27miArJ@2yh&Pku+fJy-FE zlsNJ((SMUO-zoBsS$TN=a27ip=qzhDYK~vhCBHFwD*iEZ9OI7@{uC>}mwtz}A&etc zZ5*#Vj9nu6q9OSmT#4F5!Q+@^<~WjFgvYQw~bvrT*?)=J@(d@Z&G>&DRUuDCHLR8S^QiyFaH8hm+gmSP(T>kYOM8jxXUqsLf4lym=zpE#7yX{ESwA=nB>nY0=nvn@`df~0)~_|F^uKM@ z9~{g6_rN(Pr~hK-^t(^nOzH2+an|n_{bTxD%BT5Q*8jJpU+MR!sQ15=pO5=B+xiF< zChUg1i{D2#V8{OB-M#begO&YX5Ard}KBg!A%@O#RhkK9T)zUj(AAxs2(!0Dj0^hQ_ zcllT~zg7R+ELFbN@t^xcmal*RJV!pDc=vPXTln@)e!kK7^7qGGF`L#GrGMOYEc0+O zJJlEW4!`E2XT?;goPij_%Ez{{SQk1IK}5(VUceX{shGrTY1O| zUBMsu`D+~wmgg%xxHqQsX?%Pa+_u)ARmGOa|+&G;n2#BQ$_XVnpYl|w;pHO~PRX&_x zxj0Y^j=4%Ib%xa${u`Zxpg$=*f}$FB891o``z>^q)ME(fUsqDk+F2aZr}LF~^ix4` zl@St>7LuQfvaT7>z}x(NDH zBgi*K;A0#W94JF^`8Hh2=d_wy!&n=ey8*`JlH!QS8ec4 z>5sdu_w+~C^)9bn+dJPO`{$uZoyI5b2>JsN__j4h{7&T)j36JB{x_u0NxnUTe0YHo zzf<{Yi+kteBJk~zo^OQmk6CBL@034(g!mgH@LIso@05RcRquQ#g8qgG_1_;Mf6Wp2 zt_bmW^(22L_ZwWZxc}*f`orTdw6cV8x#H`4;3*LN*HYU1`xm~wcfPv^-shX<^}?QI zPjWWwjDcQvI_^!2^D1}d61~w9p=@%@a@zw$=lgFWzgUQhtszn2wO7U3D9;M}|r z=5ed_gsDGTdytoKZ4t^(TjgASDt=muzv%Es;Oipr%@O#R zkDT)-@pttg&-o{x^F?KaU}6o2x5MdEdzF8}L+rNnCAH8|b^N%5!e>~1Q|Co9l&p*P;Ur%Yi#Cd+x|0L`0?m@qMl^Q>v zXw@J5CYHw4u((0`>wC~Yb-)(-e1y(*PJdAJpTzp5e0%y`q6qg1Dt{8Np7SSm0KzAp z`ZC4uUd{Qim+z?4m~WV&r;nOTng7;udEBpM>+=J|hkxbsJ|ueW3OXX9N~zH_9FFWcWz{!MU`Cn%(zlMApf3(h1 ziAny0cdGX3)c%woS%36AWRo}Qhecjw&*Z@oSy=`ny&7nw|Ne z@b^3OA>kij9@{UxWc^k9cq_GUv9r1TN&p^j*m?IooDO-ud)2=yto5gUw5|LG={&_R z<*zN^=dM-h&)>?g=X7fiJLgY(NbxPsd`P8Rd&HR!3;(GzudPw#{{{0`*~;g#vF%iT zjmvo5ccHy}DL1gby@AU&R_$hx@{Lm8zo3f8UjD*|6yKBnx*qfokni`soDaKx;a!Ti z*N=iY&R?6-Z+eCT{WR(~yTMc~~L>>Iiw z$a^Em$49WgDD8oV`I+>zsW2r&hNxi5=|k@@nZ7tFSoPc1gS-beV_-Y#Sz?`E>qD#P zhLZLO-rm#ajlc&Z z@LGiRnJ)3~*hBdRAL>1QF7eOTgM51g`OXM@Y6SZve+0fU0w0RNH$})_*fxJG^;haw zO9c7&2=-H+2z=)!y+5Ds2=a}~dzTNMXPrN{=P#`MQ@A0+IKOV^L+AG{9~j&F{HLc*lalOAk z-4W6s`&jSkZ;OzAcLe!B1im!_9~0p8h0b`luhaLvGlIPKc<=d(i@>Kw;KLD~kNbk& zpKo0R{jpc}p8ik-d3OYPZv?(8g8op1`saG0_w;u~kS~oOAB<4G?(*Ktzb%6P?g)JJ zlfCCJHUi%oq5NBp@BRG_M9|+5fe-hfAI|qo&&A_bQxkH0aC|{B41N+a?W@z8*4=}= zw9l;(;*X8sA6TpC{rPFW-ual;-k(ou1l}KkuZzGpN8m#d_>KsCu!r*df7rVc__&Fy zFPqEU<~9Vvl8|7a2~L1uZiU3bX%k{{fH}Q6oY;`V*l}WxgaHbe+vTduX>J3Bn%ga< z70?#9e6%h{F;J+10xlFVN5S0R(`rVe8O?e%GqTnT^6!^OtEV?J|M!3I&1f`|QvAXD zb~5qT@!P@e)0IKqn@PT6aDI{*_$z*F@b*<^kT++Lm!?@C?fP#9{oXqUZ(m;q{i5HA z^;7)8`;Id4SCU4bw7;@lTt1Oo8SLMbsr)SmFTXv5eoqE@TZZzjZJqj)dyC)SnfU$S z?JLb7ugD+t1fB;miNkTE-On_&B#-)7H8$8eMOIp+vn4VZ-Lw2|MJ#hmr)*6AHE$f((lS(pJb5o=aj>D z8w8Dm_B933x2I11&{8I938HU*7A;Ky#qcbwJBIo(0p8 z`~Dtyeq-f|Wia7Bf9dM^r#4ijUSzqrzPdWqD*9hvn&;Ep>EYCa$EnXs!9z5YX8_EU zvf%wL3!N9dIAy;|s_5P$)qe7mY>B+^S+RVy0S|x){>ahM2E3R-@JEi0Hg*t54fp71 zV}wvnj*d2V6w1lb(Z)_fIXODo7%7yKqod&oSI0 zjym@a(;g9#-E$%<@%^r7t@srn!NfVeN zdeY4=$pI=|Nt>sM9P%x|b#z5?!G zuUPF}T#RdR3-;rY$<`bL`h z`6~ANPw<>(?ULp5>BpZ|)K%BR2%rhcm50AIYIB@jKx zzxMi$D*L@jQ_JARK~pBrg#kQ#sb)^<6i(k?04}HvU%w_tZ;p>R_&xdn(67$PeJ6P2 zU;v-ku;68;_H|FonNGi%{G<>f+V*MZ{S%zNzX06Y7BYYG$rfqs*OKJI-#YF%h;zw48z3h50cNZ^GCG&>KgLtltuGb z&WHUa%Tv$)6a3IMG%kaWFD!))f<(7Be&PEo)$m~k{5U=~ySwRm3j6PqTQT-0ClquM z|K6IB)AlW{U$KC+kbc~S%4-{z)K|l!L-p0CKvzi0rSiHJ4Yf`7D*{poh@5N_r2Z?m zNmIY)yE4@c?(<2s{Kh)48?0}uUU|~8I>>5^NztioDJg&9wrR>=H6LEJu%xPPK746n zX*JJZ1<^kzoj$y2VL8rm3u{hhDu*96ME`-JH1$_its0~NMD#xyOh0}7twewC?bFv! zx)4G8OSi-R(ZK63JQa*qzhZGMEN@)g2;T~US6NiM<0r}weoY(apHvRSRr$}s-~U)# z4V^>k+aJsA4}j2*e_(m)s4a0$q;kST^Ru}9b9UhHr~keQ(Y3c`Io7`-xPBFRi5KWs z68#4x^e565)DitBS$%RwAHnw~E64T`f4`-aXv6$kCC0bah`{#o&|nzPVg1oU{Z%kH z=06`pD~G)zqCX|DzSq1)3DKVuT;F3}qnzl&bMnr3jr6Z6{}8p``}rHAjqr0taD9*Y zjU=gmZ}$5+m_K3twwGhM@B286ap6Z3DgP5;`96JO+;rtvd5s6(%D;vEK9Ez2Vf482ojLyS{44Rk>LwUvE?>gWzZ%oA|GpVezl!Z43ZBRM zp9Ix+l7l-x%(o94IK3Pj5F5ZEfgSpz3da-L^Njvj5SpDL61e;WHS z!4K~*bia?ZD}H~1qfhujL_UX=)BF!B)oV_!t0JF~Te@Pk-HW7^H`c+GF?=`YFlT(4 zTg&ly~Q;flIbz52$laQ%e; z2gauOC+{ypxcmy@pHH&o6Mhma$@t#UC;mg^HAH{TZcKa);OhfpPv`w@$>(-U-FYL| z2Nk$|y=Oc37m`~Q!<+2r`=2Y$#qGZZ%crn%mmhfb*W#tsP4G6Xs`;zt*Dl3#B%|!{ z+WaNe;~JMYHdHT4tb%t30C)H&Tr}ao63mYYzn%PEkdl;tFfzqo(Y4OD;E|nEzdMn$ z#p*`$7nq-KUuEzUc~6@6r!eT>Q`-{JSgD^h}cW2_8 z)Q<>14ZAb#YsJTn37DUC_Dnq)unxX{E5~`y*ayo;@0oi49g+7E{g1GG3Ma?@m0XDP z$CG=e@(1C+7xSOE9>?c%d#1j>M*Neszr)Qx<9zuCX7?5}!q7hTbPK%C?6hh+f0=-f z4cPIQc-omCN!~J!dH*0OA1%V|n=+m$pU90QmOmht7giJfy@dKL^;kZKmD~B3w0}`G za1W2?z@s`|5E`Y=Vhc-e~OP8t0hIP=)a+i?88IU(g)gx^ZszV;`a=L3@s6NUU( zD=_{~CW`Hg+nGFPZ)`EPf2ny4m%r6Msq#tw^5UOgzp{35?ZR3Zi@Nv;4;6K|{#*7D z)^FU5?fc}ucx3@wzi}&;KPQ$~xbZuQiC+uj>c;Q4Nj^CV_n*%EN*9(F-izb^IaW^E z--hj+oI?6_r+ov2-+i6uF_Y`;&*bNJ;y;h$_HV_?N%=)^!_1DeWWxdYkW)U)|2Yqo z!SqCR{mRr8Ap88;(X(bxwck+>3kNFZ&Yn7b+BCSoc*Nnjl&UHsPkombzRcjf2Yqim zzN|`}jK7%YyqkJfh5hEp$um+Vl>EcV%Y|n-_A#D1BxPTczq%iB+HDf~i;kT5XT^^l z{i0j2{yT@H>`(Mt?sN1jvHgwD9XZi2#&#*eTVsPmQ|%)8uLhTI{MoUuvD=|3`;+p^ zar=#@v3x&PUV+O^G~)UDcMfI7Hz%4Wd3 zzWuLnHxOy(e)bc;_8;rtUBth3n3|IEa`=3R;~#s7<&fSS`2k{iE0O(7W5x1z zB0oti?;!Hi#PUuezfdeMGI9Iw63Y{_u>3b-xkbwVi&$Pl^j{XsyNLd~VtEJV&wPBE zkiRw*pK-Pm|K|N-{XSx!C&c;%FFJX|e0C;dA0FQl zeEs3zgX<6S_$Pet0aiZGESpm?c}ki6jxP5V@F@$FkoLVHZeNnfKNibNeueSnAHm?K z?Mq#K!Sw7xxWHJx0Y{*l7=58&%Bb4#(jgVaBfmHX{iCp2Ie(LapUC-&lrxZ6F6o!o#*nu-1>R-e@0M&uLI$VvMS6U#e^e70ELP2>y2^5WO9{p-c@7W{ov z^K7x)Am5+5SuC$1-@m$_m2>v1Yg}Hp@Z_bd+292uwUGSq#B5=HEGP9p%a%{<+ddLs zpKg4F(Ep6*o$-tL#%%oLIXiwZiGA|f?{kszEmHmnary0}eV3=vC-Ns)IcJ}Rt5&Y8 zYnWJ9OX_v~|FE*dVcjv!z>{Yj4qdWm{wd|3_VkOrLZi;T0fh@H*qL0vv+Wnu->_(6 zgTH<@|Ie6um@~fR^_Ky|E9w_D5P~^*9oz(MY*2}%KvH>okD65%9k#1Tgc1dE;<$Z?O)fhbm{6^Qn*N7zjVE z<@Z!G@)DTrwXf@p_t$f__p#q^BNcScb@H3_U^RX|(ur@FwN3wWd7=#4!s~E;gnjS) z8#$%##=+%@8wQuR)H>HcCKTw*Upw=Ar2MuF@4qM|{XZy(+E+-v@A2#7gyV-|BLA~k z-i-4fI+gwY2Wel?Y>e+)vAmPy&&^H{)}JK$BgOI-A|Ef7cjES&%d6P(VIgPAKU(qk zM}D=y*gs_>XMUoH$Oo{zVv%9r*&x@SB}Crld|%KsY79Gf5jnx%cD{o@vFkFX{${M- zo5a_@+q2&vX~lADHJ0zs$~%jk_9vRK{1{G-_1orSc`YmNBJC&NKe>RF_mKMW^EJjV zSUJ3wF=anQ>i;z>FNB4xDf_OAzmKx#DXA6d#6BfhUiT|!ey#WJm4+R8L|%&Jg}-y= zzj_~KzrT`v8Lu<7Ncl}h1?aDvnx%v1^0B^!@%3JG1~b3ViRB6W{g2*jS$P+h8wp(g z)9m+Moc9YjA6B&Ia;8k4Q3el?loQ^`Hu15;fA3dkGW=KI<3@o~e&U6*VC9_sj&8^Q z3O{u0S9g|UpTt$%_hBA#nOej6*V!}=BXWBEg@yc^3)9>Ve$Sh>;fl;8F+mcPZy zO)M|G3CsV-$`O{MUt{@t=cf22^Gh9A-v1jc--ea^1C`dvt5bs$p?x@y8nxo@6BUy06P+rScg(>&ULckyi2j{ox&4??q1}{Ui{-^c z|IcE136Z}fmX{Lw7h<_d@moA~=uT||DgSl&OuX}_^r zEHC~H%byaxgiS>Io`kN46C6VtSme&#a9%6YjkslzIcaiq}SS;@(`p1gp z9Yp^mvAj9M``Ic+;p>A-5OaOt@;epx6UQCo43AU26p_OE2Xg)XG<*F^&Zr>Q#|Ksj z%P%1H|3oZrItaJ#II+BEeJtO&QdoY?!B~E>SUy1J-)88q7~#F63bV>M|M_`p3T`7 zZA18Zo6#p{we9KjKgscZ!v4pY>3k0)Ir6>K`aiz^FuriEPm|-*$Y*2yLs)s$^jUyl z#mTks_0kpY>LBto3LN5zkvb{k8b`Jd$Yeq&eACF7qO z+^-s?Sbk!E>WO+HFX_bk19ge(*6f|7Ji*wtWil zHu)_~D8L_SUklc6#oOd&pD^+^e7v2=N3!x1KTE6UFK?`~A2~}6Q&+-5xl|$WUl-OZ zB=s+6^}DgWpnz7WdWe~jfvisgl*{Kv&|b2}%#dhh#E7+==Eoc!AR zxLDpp} z=E(;$<+oz|9SO${=IIBg<~N9clKR{6dFF^infVWT{~Y$<`5m%8uo15hOeZJH2YESJ zf9L3X*LSe%-{4oOX;h!cm#tV;O&7?emE!{ZTA)h`hZ_9)c>NfsPgj+(`ow6 zFj1HKbNWYr`Sue~bbVhsIcXx5r`EqX>x*g@tS0q}<#hd#Sib0#LG@vM$l&s{`VFVl z!}^}8<@IUw>-iJ7_Q62Ap#hfXxC_wya_59J<=g9vm;!ixyne@BKa@u9KH$#Fp?%P} ziRt8Z;GN4FPF~=ykn!uUtXniOt^HE#qZWDBN4f6@an?UU{r2*uLG9x`K~#UkAoUab zEW!rn^~w6HG;(|WPU;E%hQ+l_b`hL@9W2mkpwVop;XIQ^Df3WuR%NP0b@%l!0d1D&+Quq3v!-w^k zR^#-WMt?~LefoGkSN^j34JShvwdj;aTmdJy^LOeI>s5G-Y+5;9fSFcadP=Qbg+Pwi zcc#Q?<@+>bSpSKa@TM!jRJ=Zvt}o4?KVeeZ_S*xvRfCkDl4o9@>U7~;`{4~f@Nn|d z`AgtUV5tSHgUC|_aPrhU!n_3xCbtWqa_8H1RjX@P!i!$)mmH-$gvwKH!L6S4>Zjy2 z)${9^CAOSCyr6GkeQh0m!5@|5^|{;`R1RjfUn~Sq@K)EtQ|3PZh4(k59?pkXbu`lN zr}OJ~*9ARTzl*gESnFrMO^g27*XH*6UV4Tj>)!-lU+uJjxxONr1)E~|t73U6S^s;& zBB6c_kv}GucM$nZcKtA^zil$E|KP>K@;ixqnONRU(a=KFfYNWE$FiM%eu`kMZwgRf7oyLs^Tw~r(Kb&AkG+cMPOmqA{_egBaEzFJ4R z?=!(GHtbnTl*WDqSYB}}i;w@lVhQ*CM^b+w)^E+AU!F#v@RQ6SZ_e<2!|n|7^4nQ_ zr2VA+x(weRG}3$@F!g)!u2~~T0-(t{|MxWG=GJHR; zYX{u^gPVl@)tlk_g8dolFUatHz^)APX0pELl2e84Gc$ZYusF^8^@)9q4Brn-W{`Jg zC_ho_+}|^yLVFBA{DaN^bB>t-AcW!1EKbIU48#dw<-kJ~q{L0Erh5w8CPv3!8E|DKgX{a&(u^O;7W zJh?qC{~NKqoyZ?sCDiXB^7qB^R+67yUCrpT_JO61sZV53_vhua%Vy7>1z$Me%x5(1 zNccIODW9B|+y&cr*%^$SD<9%_&fLj!kD4}zHX&6+3(-Ge4Wm!WH^}|*OT_ZZk+^-= zpDEODCh}**a{HkfyPq~+5wG9vCHHrJ!rs3@Qyo2neBboAgPHq_r2WO@{?CX*nD%uh z9Q}$b@%ZQDLsIvz$o(JZ`{c`4z-#%c>*(uas#cy_=gvXcb+nQDLmPAVhurrkRKk}l zj;NYj1}~t7S1gluk!>5fzxCdsO#6tuleGWQDMEQSksmmfk-PlUCx?CSZm{dw~+F`nklv)`}{M0`kIsu?{_5nkFx8_ zU3{ret4y6W?=X12%z1@SO4*h3_I01IcIqfFaeTZtONg(Z_}^Dzc_E3fjVl;^w|=`@ zo-w0r27KFOPT6dGiFoSfcpAzP$1(Uw`H1L0c08l+)G}9uD)#_=w7PkRKQbMspqFs+RpP=6%|#fC$MHto?GrY z!!tndBKCXiM5g_u30(x=GgXY7soyg`AbMn5OxEXrBi8q<|HmT?qUmgVN&P1zh4t@W z>OMcf=#%z&w8nJwU;JZgGFC2~I<6!ag3GJl( zWny`P%r9Nf$_YN_`Gv`I?QfjIx7W%lr^A9e&tCzVU;BpDC#RH>`L9dF^K+G?{qKwA zt)%>&#PfGuM81ZV_d)~g{E{TkS8vEZzf9VP2>w@DeIl^h&9Bg|?`8y3dKR4@Wc#qmtSli@LP3_i9 z!R_0$mWdy7UMrCwES7f>`7*J*;A3a}*L%@g;rcl%&GjLvzc=0d4L+eI-S>;I96gN3 zpYYr1;Mn=YlFq^99p?-#@5&%Y_2TPif)D+E@bW9}8eHCK4K6nx7t7)KS^E9PROS+X z9??jScl3LodRgcnO+@~pSWa-p+t>oJ1!4=t7KkknTOhVTY=PJUu?1oa#1@Dx@O`vE zo`JMrWnW*b`FO5Hy$olrCY$<5y>igZ)3kuJ{`(uI<~vEFvu{7r618pIel@!ht=N9V z5^CGnerk3jTCx3zCDgXD{nYG6v|{@aOQ>yQ`>ENDXvOv;mQdTq_EWPP(TeRyETOiI z?WblpqLuse7l=Sn+Uom{ZvDFYO0Zp}nE%-Rt}`g?#Qu}({-Z#;M@651PhkqX`t>7) zTB%Chf9TpT*Y&9{sO-i5tINNN)u~Qw|JeT28|3$5|IzcGy&4NVu!s-w>zElXujKmL$PwXRO~@$0tVg`%{hZ-1p~ zT_t_{BeyJ-9ew=Su3rT;)zQaK%Tn3X=U=5(s-uq|(ZUq=^y^os)T0vH-(w7gU48zL zLakIKuAkaMWiPfLQZbvWll%5_p(yR><5#NIRm%PPk&8uTM<0K#*Pre7tFT6O^v56B z#;;p{uIp1SRrd7bSEW{}6W32|p|Tg-PsM6fC$=B8h00!RKNYJ{o!EZV7AkwO{Zy<* zbz=KbTd3^C_EWJM)rsv#ZK1Lk+fT)6R429{wS~%FY(EvNQ5}8zAzGNip8ougLZu!R zef*xn6n6FTBZXS2O7`*7wy5l7-+oA?*{+U$``x0HcJ%8Nr z*3!41Zv9%#*L-`n{r+v;_Geo^wx5m#vLC-Xtsf5ltJ{8EeWX=D_Tyix`61*#-THOy zpX>GOwqI92+xFLOf422=-G13_{|~)>UH^^kr(;3={#&Q^FvefH_3P>*tpfDN&${*N z>TAIdVf>Zt_UqQKs~_86#{${Ue>$xn4*65pe|7bB?We1++x~3p>*Ckd*TtXh`m^2s zY~#=M`gPkM>+4uRfBdUcyWM~4{psuLm7u3R9Pnq`{&D>}7Kr^%$9i%6#r~u1KkMq0 z5ZhnJdU5>5{uBF;js;@>(Xn2ffAWkCl?>R1#u$a5sqcSCseYoA`}GqfYFmB$YV{H= z{rV9pN@<(@`m^1BC9}Co*|(qD6s4WqzyG8J+f~Xwe&n`AWk=utRBEL<*{>hb#whIR zw?EtUD}eT>L1?&C)c9@!uI_+@Kk&)2UXu?0&0%KiE!0duG4 zK7Pa@lKZKTU#>p>Z2kHXU!>IU+^=5>uJ7dB$B%rNWDe-#m#NKvu73TE9gOe{6T9HpQm3x5*Hls zXzte^5NMjyavwiRgDlu#ef&n2*S};Nf41w7?H|n3#b@Qd|BG=2JsRKt32G_vc_H|Z zxZr?C~qBLje*Po`~fQRGyQ9w(H zPs@J)q1%34eX(7F9@Y21TyK9+ONr0Z_djvDL664u2ep*=yzJW#i5nL1X!hG5u%T&A z({DdYQ*yAw`uQ(dJ?YNU$Dgj`V8^qM9|db@nzOQRzcdXCcsRCyKtrWDO`m_1rsQCU zbHDyzIMbaK`)@kS1UsJl{)2)6O>>q${xk&#Jgi?o3Rsi)wA`;>j4SBTIDZ7Sl=!^d z_a7t%7VxM({(u#wIZeNQl&0ihhjYLFU^vsA72{85nPA7WZ$A{Qp=r+2Z-1JC10L3| z9|f#Qd|K|;FUA%0Xzt@jL7@uI)5k9?Ht@lC{1(_$!V_cr3C$AtpuYd3z;%gE%zpji z7JMpdtl*efTX15ULwRZ5fcL*N=ktg4{a=jWGrpoUzrU~bf1U;}e>fd~{CVkqi>;sT zZ2xh6edI4x;)p)~5|s%~)yFR=RN_!vzl5;_r^faZ7)9bxY(FGnE&r+d_RDtteoQh) z^zqBo=0Ep)(0}MY|E#O;H>$*un12al2~LgeCoqb{q3qjFqOpQgzX$nCfGYSQef%hR zWr8!a?>|5E_Uq!;)fYI0#G%-KvTc9e`g2`h!dV5U>gQiUp%RDm>qio``A^l4U)}n3 z_5GM+j_Bi;sm*_G?$?j}pd^my`@ckGf>U$9ek4E@{7~-uUvR9VGxhmLqGAId)3^T* zz5c+a7M`eYe_^qK561NeHkI(i*nUE@1U{&5KNPqw(TV!?i%JcCOuv2DnO_$4Y6oSOamk)Tz<59#xl?fQdb6`h%V{GwI`KbHIL4~|uIX71xhB3OZs>EjPv zmGH#u*Dq{V;Dg!E-+`MdJW;>>NLX&rgK_=2ZojzwL493xo__wzw*5t@f*;ezAG|Kn znc2@jNYt#r$CSUHetB5mPgnbXd&SwL{_NoIZ_IA}9cPgG15+(LQI-GhHQB8nok{A? z4*zxMgj4^ahLLX*)Ba7dQE2bH_Dt$`=hfS!ekX6vbB^0G_(Nz{=l5C8Ha&mI)cKkI z)6btMQx${C)3-k%);nNB#vYODbFGrD-_&fsuD)*jZ`EwSuD)*j+cn!CSf6Vs_p{?% zl0VY*e+f=Q{8QThPT5p1esuNgHS5>a=gcT=zxy=(C$N5!YpM9Bbo<}dY`;%mZv>qF z`887vm^+$YpF1(l&s^6}1Iws8$QeH*raIen=Skzgd;>0jNb;|%|32@(>5v6GF4=lt zp?OAu?^uunEtin|ucqH|sh)oKWqSG@4SM?BD~Wy(Yo$L&pTG2F2a&|}2eDH6b7K3Y zw@na9Y`-8@N`FrF?T6AgE`TK4?GMmI=9JRQ*zriV+aK4@&?EgLwx6`g7=_q=j5(x# z#P*Xm8KV%}k1>bzkJx_FCSw$0`!VK_{*itAA?Y@I74+{vc}tVu*RLPRSL)Hw=TEnO zU40K2h28AiUl+fwzJk#_DzW`M#!%SJzWo#$?NQNhzo#&TUH$x}P^m{nA3ySxCcmqX zU$=f;eR<4Yjoi1t7mfUW%s-Mhnny$5e>{aL?CRH#6l$d^vH$4WFWdT*OO?Is`(JE7 z72b$W_T!hdL~X0zezkguR`&g$v_x$iw;!n)4r}S#Ppf)(`+c_CpX>GKy8Yw!>sUZP zespR#;`r4wUz)Ff1TQrEmF6`h&=_9IcV0v`*Z{hIIp&U*U;+e&m|2=)^d8~B)h z{zQT65}lZR{GwI`KbHILN5R1g&eZoGL7@_d^y^0wwfRrg=U=yeU41_$nIp0NWBbea z3x96xKf3;tZGE0mx!?Ny%hku9tzSRli2+8|QDoO=OPf+YiZ9 z=Q}t1_4}G6bwEFUkyL&B$@=!=OO*Sa`}mO@VD9Yf+dpnUM~T!=egBoJ&UbR`KR%O4 z9niNQlB$nCS>Jzj>(|xi5y}0I?VoM?%kjmZt?$2liE_W=`sM7!pB>wew}{;DT+d&7 zH8#}mRl9uQ(#A#Ado`6#s+zRVxTUqr8=J;0S>CwUg4&f0d#$Xgub#hXTtm(L`szjF zR-Rf{-7vm}SSg6Ut+7|b%KFBIE2~!4E~{QOf2mu5zW*W86s2vh^QUh=C9}Co`u1~+ zQrgLW{YuStm9pP{F3W}uV1(Q+14jas%^9HziRC!TKfJ=N>bZq-+oA~;aE$*{aV$358hvt>-clM{YVQy z?)$$M{1D!MmFxD8?Wbdb?DxMqt+(Hwr}r1@$M(~)Kop+u|JZ&y7Kr^v$9nPjDfXY(e{?Jm`;U(G;`|f)PwYQB7Kr^v$9i%8 ziTx+`9~}$C{-a~PIRC`{6Z?;j1!Divv0j{i^!*2E5um^RNVk5i=7(_q;D_G+A3FZn z|8y*%pFebJxBCxW|JBux+plAR-0%N%(8vC(AHT8vbu19uU&nfJ{Kozh`;U$V^!*3v zR6h*X@5SxcAy9YxxM9G`zk@%~sk!gJy8frDFS2UzWBT?FUYF?1+^-*rU*@<>34Ad2e_i|Q>IbGuc%nXk!eRp-jN=~#ww36_+_zt@;}@|K z{Fr|H#r6wsZU342_D^>Omhe|5IHDiFfvs4#oD9FqYud*nR?| zNF0joCt)nXsj>Y8Mv*ua+fTw+f>UGr35+6fD7K%3u>_~a_7fOI;!y6}4@sc)pQ?ZT z=`T~}Nbc86MuU(#UQ>Djj*;#ws4GxlFy`^njxKRdR6Y=7P-WPWGgf3nS=jJ5pd>gVrl z*;-BFPrBr)S@OYlNHFA11CJ@@e=4w2kXef)Cu@n^^RgSUv>Z+-rdT!q}(xnDmANb+ay<42N++0*s$ zv*pSD(yt%MR>_>7{rtr=NBT$h?I+!2Mj`j@j~G0%KXRWxS;Xx5xsM;QfFytE+_Gi#YyjHpTD^M(xiD5V*iQ# z$KwvtyRrYo{v+))9);L{V*l~DgY<6fKe7KvJB>#n_Mg~)JnkU9oBRGF4Vh8M{`DWz z9O)nW{7F~IDCpadDNg!F_VFX>HhUGaZ$EEqMy8U$9pKX0z{&m~0TfeS;+Yp zETDh=ugjmVz7G1>fA!<{hi?CDsUZP|LfEq&tJ#(kNro-0NXr1(_n)}^It1$T7u#RY{<`+l)z@kL_hI~@Yd>9mUHj|S zpX>VBwqLgE*X2*Q{krE9O(ewPy!uPRkUTEaoH=noPuQ$YSZt66?6j(=hocbjGYtv_J? zAEx+M1OLV@;qY%vi6;NQsLTHY6#qXw{LAKlo_{pV`LFyl=D(BTZvy^1LgL?yi2oi% z{tIuy`Tr4$|3$n1e|i_C{MY;*oBxg5oN`ILH^0v22P35TZ&J+vJ=@{&|8FS%Q-Oc9 z$&O0+2~M&_5%K?$F8_~G{5`;%>9df6-2u|KC#lrvd*x zA@OfT#Q)2>{QsKbf62qYZ2tH0&&9vXJK4!H|LuRl`Tutm|LMSg=eUsi|EbaR|F0;Reg@8tM5Zg-QA@KRx(m^B<4j;{1QO;dih9 zpQQL-1^ngz=HfIU|L6lY{!Nbminq9OL*oB5`S?%q@8bU>#s3=M_q8)1{s9iZ#o-?+ z{z%0e|J&oSz2dzu;s}?+&M2!h7-^P9Bo~pRVZt zF8(fx|8>CcYiB_GeIK&%k2w6q4(@ii;D3tZf5U@c*8h3@<}k0^`0M_|l^YWOXDIr=i~nhg|KEV$*Uo_W`qZTv8ys&fCQyKY-X4{`X>d#rziHUG6n(f?iif2H`}0sOvp z2K4{dQ&{}QozeKeHvVTQ{yqlu2kRBBBZ6C7ou;TyB334SR3=aSE6#x5x-`CE7_^m@( zeCAzFxjw%q2SSQ}ZT!zs{2zGm%lbc$-x%iji|@w%{{qGTA>gm*XL%%aWt#shp3LeY z9{)$IT+VArEBsp|o&O#Gck#bS@%ICMgKsCUG82B($o7B6-O>2JHvWH5{2zJn%lbc$ z-{Se_sS7FoRq?lv#`phvDE^NDe}^Lf<*Qi!tqS)3Px9lT@&B_F{olp^GR6N1;PAFB9Q z#oxOK`~Pbc{{Z0c;{7xr|DC6@{2Q~`{FnIO(D?s3ivI87@1^*^0Q|mo2E<=^8jBxs z_=k#rZT$bD_`mevm-T-hzd3C2JI}wk>tCOs_}9SthvtyhKcI-#KfEfx{vkE;bk~2r zN%5}*{JkOJw<5y-nj(I8{o}tW{xbo8%Vy!Me=*9~{5Mqb|1U-S?)tyCD1HR^`$EER zMufjt5x=|s?QM$xEWmGW9uEH~BK)r_;&<17y+iSz4ftC_!f!={{|!a_ZvOA1_|F0S zB@;(6_pwOaW}5#X=egTy(Zv6oium39_aBP?r+~jdB>v5a@c&y8znlNwrTEVU{N;rq z#eYQj-%`Y1_c4C{;XR7~Jiy-;5`HTp{NE|!Z~ZHt|NSq;e?H(J2noM&cr@{EjB+zh zpdIr3w~POMioY4~S8NfE|CK0mXj-;BOBJKZ@x2_k3OaA5#1m0)Au5aQH_N z@xP8P{(g%8B0K)~4X6LNBEr9}G=As)PvS(J|Jyf8jd${Z`pxoT{^vVxo(5-?Oyi&8 z(~FpK6S`>~=6Bm6+EChw|A_K`u^s=D!r|X2k0$@Gr^tVC z4W9pdo#Our=6|~RdAfl7m!Hnge_7o85BiMrtC0Brsr3AxGymg`e?Fo3F9H55L&|?< zMEtL>%m1eo|JT63kEekA7oNfLZ_bIv|5f=%&*S+2AH{zu@ZS*<|0p8`R&Z>(YC zA94Jb4shj$l>g6_zW>kV|1T*17T`Y_692~ZX!75Ny8M4h@qY*W`*;e-e-p>QF*h3g zs{Fh8|0|0BXTX1FNc@`-@xPHS{{s}iu`cCbHvjYdTU`8OH=>&?$G=s8*FSwj@m~)7 z*K8e5{znnfz<=LIYU^K$*0TBE$%te`8NMNPXY6P3&+33@lOLE?}Zfq+WhBH{8s}1b=!m!|HhA_>Hjv> z<^Nmi|Lb`8m(Bk?|0q}ZUx)I474Y8`68~mI{BNene}5w$|L0Tu>jM96pQz>k$}`#g zZ_H!;zyFJ&8ULTJoB!9N_^$^36WfLp|5ilv|C{Ubzdpsk9`NtuDPaCDzlY@?ar_Te z{@3Pz1B(CWHvb2XV&<($yEDyylk>S1zcI!C3*f&y zB>s(`u>Bv&3+^@~{9EeszX`=(0Q~!S3dnyC$G>@0H2Ago-<0CN2KX=DE}Z_~jEMiO zbot+i;@{B2zij^J`8RTf|II1>Yk~isgTm?m&5NDuDmUKwosi;xYeoLu=YKY%_%{On zE51_8{}orW`5$roxAWzOg#QA?`@in|&lVK_bvFMY#lLY~H2iNP%|HJB2burcisHW> z@HZEQlmAde`EOfY{99A}HvsEa(j@!tmc%SVJ1|2IZ6{u!x@e@BY{ zcECRn7XFC%-&q&`P89zgfIoR?IQ&}?;fK!^N&S)azwY>dB*otj_&Yf#?o z@&6L=HysuZ|5il!$4KLMp8s&?f3~FfH-`Bi-#iV@u9@cl3+`j*e+)C4{3k#E!{INa z_&4$3m!1FQ@mt*dm#>q`+WZ&Bza_r^vn$2FDd4aCT5bNX@I;RPqgnn7zTwIZ3IB!C z_kTG2V=4a40Kc!D0sY^)pT&6q{p9bW=XBq3?h{Ip_Eh`V}{a+U;`oD{RcZz=t!0&5kK>SS)vi@&WvhhDu{A=Sc zruet?;FtA(9>2x$Kiu%QkHq-;?6s#)Dth|9SjqnB(sojs1Td#lJ1!x8`$x z8j%0GM_B%iW7z!Hw2&(|B>%reG5@>x_oDc>1N^>r2E^ZTJBuH2_=n2>wegRq_=`OF zW&NMWZw_<(?)6^@#lJn^@2=$hG$8*yoh<*xWY+(S7jfl=TgL=I|fO;vXvim&ecD{~t~9-vjd>#Zx$*0^;}Kn-vZIvC{J&9R7VM{(Av`Pe}O9 zi16Oi@%iO zzYp-YP74RW!M*?97iJ;#e|zZS-=E^YAMlqS9u9spBK&*m;y-}me*o}Tl!t@gsE(%p z`;jjG11bIo0lzUl9QR13@ORA!2ftY#4gV8#@tYL?uK|De%y94_twRK7{&i6;4hgK4t^97{(W@uPoemK3;26O!f!={e_v_* z-2MLv6#od%{EzJXA3y(NMKu2>KmWts|Ja-2-x2U5ex43rxMW)Y(fJ#8{>$X%znZJL zxC-g|=Q73lKllF6G>U&G!0&5kK>U@DviL0yKQ4xDh70~OihraBzpVfB_|Y)O@8177 zoZ{aZ@Ru&;{4^l{#dop%8^^Kze;;3NNc^|x-v60S@h1Skublz$xBiyJk2w6)@$uep z!Cy}C@8ZEP>;F7{bC~0AGVuM+A5;9J0DtQeHUDq9KUDs&jsGVU|E?bVvi{HGH-x_s>aGb#QtfWM-a^V5L* z_x+3IAMyB4;>r!l|1X~)dRoipZSH{t{{FR#e-_0*7VsN<6|Bs;fcLV-O|1X>W`2OGG$3MIQ zLW+OY{@?ZgITZgmkN?Z!=l$Ot=Kf#43HJY^DgNJs|Ci4W$N$ZU{J&Ju|BVeX{-Y@V z@xZ^eR1JT{+id=`IR1;4api{O|5qvYf8E#O?>`+&@ms+EKuG*s4bkMk{dM_2j^f`7 z`1kRI^H!$oAM+iSf3qqY{HpxB-~T(F;(r|YZ=b{YX+ZpZdPfn({{g!EA4Bn%c=(si z|2+RjuJC^%#s38GZ_Evce=8#X4^-qIZH4py2^9YX;J=H{(*gaz^b0or(K&4VH!bJv z8dCnhT6+H9x&CqEKS}XF3H%q#gxvE&!heu1|MMySiNL>)r-1ke z`dI#ri26TO{>!((-#=ME@&5t%?+l55)EEu_hwAcQMe*K-x+>r9$&lSi2F8_-u z{yzc#MMtaQck?>lu_DUi zAJ4zJIvV_k>GEGq@lW#bFPr~){t*}dynVu&|5WAQjsKG<{x0CZ_?U3w->8j-|0#<6 zyW{^_ihn=gzlYD$0pq`)i+^J!i@&#yvujBCzg2Pk@5cX9ivQ2Re@{sKqb3&rQ2GB< zUH+F*{H4IZkEekAcm9{n|A^y%sPL=u@5cXfivKUbKML#l*NEc3Oqc(YDgOOE{LAKl zo_}+g^WVG$p8u$$_@4&;n~&x4R6zgd{ToHZ|1?GZ6We0^D=7X0fd9@_YWTa~XXD@E z_;0P}$_*+1|3Y#6-?RAMjs#9M?`o{ta&ai}#PP#y^Kk^N*kZe`1U?KedwL ze+KZI$A^R8ipc-V74aABi1}}%`2Py{TSLNcoD@y}KV1=j#m*T2DvJMafWQ2NaQHVP z!vAAM{3dz-(Q1mn8}JW=gdatO|0jz0dv?S8H&Oh52mI|PhQq%V5&jv9`1{EEuTv@h zX90g@RXF&KlcS0MnTq%ecfkCgM)5xf_&Y+vZ$^aw2u1uor(^u5Q~b{Z{v`jNKE?hY zMTCErBL40*82=d*{|kU0U9yw#zE!6C|NQvIiU@y&BL1#3G5$3a|33hK&u>GD|E1By z|B;ILUH@N8@xKW8dmjr2zZnt!*^2mG|38!B?*aU!zY7OHiU|K4Mf}!T*#8m5{}SNu z3kkm!5&pS~_}%gESrq@vcKmN0PX05NMHBz?bn%}}@xKE2`+pyf|C;H)3zmhLEB>%rw(f?ii7gGF_0l%-E0r8h_!s0j2ji&$8#(x3Df0zfqtpD@)EslR| zM!Lx||8D<(5yd|R@E0iF|0&#*<=^1eztpVe;wmKk*D3nHi~kaee=6YjwKJgqcX0SE z4nHLx?+q9H7gPLY9{jTY&*MkK7k|p~on-#=Qi^{X;4f<8{4^l{K7P6NA6gjsIs9|8&6LbZSWce=6Jm_ngL+ zn~r~odo|0cuM{&y4p*9%+wU*cWo zUlO+VKMVBEhHWqYXS@gc_P-(e8!G(P{127zCl-A8{lI@yzZ(9V`@bLfclk&S|EQ0? zANcb=QNy4A$@c^QS&I12{+{4}{8KglpZN6q!T%PYtKr}B^X~=z-uYiB;Wrn2@%_Mm zlOq0`qs5=V@4s{3f6>2D>Us+{>K_%um4*4azh&bu3I8EPz3y` zn%(jL<#hc26VLcx`}%K~j{nK`kKFs8Kc)Czh5MfaA>IE(5#9f-RJ{M``u~j-|3TnN zK0n3omFfDgXg${dja^v(_jzfS{eOV0|Gkppp8@{gdpdWW9uPl|&*J>Q=yZ1ei;s_V^MB}Lx%p33|1W$I`~R)f|NjO4U$K2i>z|gZ z;rH1o!+~QJ{lDot{Qj?-DgHyCu5!ixub0dJCg=aH+i`XcDgUjfIR0_-e;dVrgvbA7 zbn>i=&3zk}lM1^@4OBAonhMD+cy<8=MMo#HU{a^= zmz@9eJPsHC{}shQ8~lHOAEyMw&%-nL>tDqARY>@6(jEUiK=J?E&i^C0>oisTE24@2 zDqa7-m*SsdW5xb2oBw$KH;1|ZyW^jS9Q;#1-!5+s_`iYuRCoMiJ*^o3lJh^>{{JxL z|1I$U#Gkl0RrG%|BL7b+`hR~CU;jKv@lOS;m5TYluz=0~7U%y3{J1it{I@}g^!Kk) zHM{da_f!0HJ^n8n|JY63jmhVKSAus!!msWBzoz)#2LJC4$^TJA{y$&Q|0_Pi{{I^X z|BrUMCBF=)A$}^G|C%}fH!fAof2DHQf7<@vN%@}#{@>ahPX4nv|L+*0@z2e=a{P|K_f6{NJdHX8gZU(f{in!S_EOqxcU85)0o~ zyZ&jK#EyRu=l_NLyh2F*e}V4&&!ZIo(H{Sojep+%4aNCSUpW~LX#4*Y6#sv~|4aWI zj{lnx`Trta|9_I=FSq@l_fu^DO!GfY8?ydyd>u{xSM~pz@p%0AIK^KH{*PM1;U97S z-}MStZb+5d0F z{ohj#{;5xm%sU4BpZKZn_{aF0TKuEDF;dSzYWsf|<^MhK|Ng&laT+lH@%&m5`Tt@? z|997a{)yuMF@UfX^Z&q+Z2mX7{9p7(&aNT(|Ava=A2uXS_7pPpodBKyq>-&zT5N0$$4hTK>R0D@wn_Uq zoM%5DVju5ayDTNY5RUH)$4bxJIaLnX8VA_t=lRMR1;;DA<(%v2AvnGb9Pg=j>LuGY ze7v{8sgGmAi{u2E2FaJmV|0htQFHhrIGWmaNg3bRHm;Zf@9WMF*FBJcAkpC0^ z3@850HEjGh@#Thu|5n}c|KBM7_aXmP{9icuQAF!MYb5iZ&;S2S@z3!1zij`{`#&0{ z{y$Xt-@5NhrRN_L_kS7b^N+xPD)MT`_0Mw-|1&q(CGU8Me-fwK*FSf#@gF$<6^xO( z{*jIUq2j-Hn{i70|1R5(i?sjujsKpf@&5tjzwVK0^S?a5W<=w^TIu{(xRKpfcmDfX zihm{?Z&JMfTR4a9|BY|h>;Gc@zFJ8A-$s(xe?#W~XMLrV|ID+$%1-_x^PkU9{!j4a zKiU3|_kYBVe|ULV*T1s)&lmqMQT!i5{8v5`&iKcQX#8`MZv4MY@gD&s`Qj84mudWO zjAG*-aq&M?{12P>e_S#CpU6)97w?Ymf4oTfKM~@;o4-y8%0Ex=T6X+{UghE{r2K!I z?)A^B6n{U&f5Bh5b}HgW5%vEk>&E{J6#p#1O5$HS|8wzg{=nkjJo?~#mHE#$(2I8d z)9HCDufX?zdL91D_S-zK3gVx{sqXcU)y0ng`1Fvr|9@9*{fl<|zfS%CBZ&WGNbzq) z6#q*V&(0m(G8j zgPUCc$BA((d`G1ZX#4+L6#vKI|Al`Gr~fnR+5X=LEF}Jy>H7cM6#tRXNS~kLhG!c8 z){JKT-}qKB|M?6x_yJY_@7fcO|Nc$!&jZ zDW7Z?z;W+=!GfPTdKMhF%g={@-usU5Q|m8*d!DYF@c8dthyUA_B=QzO{F6A<9se2K ziu|uXMr!_BJO1CJ{{Jb&e^ED=r?9m%<$s^dT(R< zKg7kq$*-#lDgSRGIsUun$u#l*$29Q|$L;tpneN0T*_wY!6aR4Bj{l`D{= za9kMwaC}JPpY;FlQ2rNs;$JrZ^Zsvf{XZ{Hd;RA-aqt7$@&6&k|38TTroV?1|0tsP zuhWhHeu{rCnA#Vo*!-FDU;D0H{6{qYm5u*Po)^b|@*m>(KM#)E@!yQ&pKOyaisS!Y zIBv&(@A1xffo$7e6371&aNHaJ%`2RBL5Y`-&EE>@<@^5yaJ&M_C&xSR`x|KA}w{vWdYfBWvGbpJas zX|L?w|NeyX{~6@J?vV1I6;b{>MK}Nbm*SrXQ9|;cZ2!mSKXaJoKZyVJ?PSpV59j@l zt)-(=n+ ze=IKk2l#SB>i;%{u*{`DK7SbI7LhhTLE@i`e?F%CFZRU0Z2sp#nB4e>mxty5+VTH2 z#XkV?-@dDJ-O9H&)A*l1-;5~!8+7CU8;bvE0O5;M3@j6VYYZ3v-24Y`pRo9sjsFDh z|BacrAO6z8Uu)GEJ3;?nagbd9kJ9x27T5oiatkkH`~RY=o&G;LANT*~W$6FT3#b3@ zy#?R@_=@ts1meH7H=O>@;^IHKW*2tc5>ozem%RS*_5Uy&w8wAuAnFT<|I+8f!H*(} z|CPG&{{`j05^O-?UpD{q@o#*`j(?$O_AeykKaMi(_+OXC|CbQ|eIdoa6;b>*O2x&GCT{{rg&UqSqvFND+o8y7}{ zf0b_hZ%FYU3ncpD6cd|i{9n8qJN`F}b(wtN^N%dWzpot;9~gH1{|1!*lkDsN%hd8e zZ$|Tc*8kgH=i(|P{_oTs|8GL^e+}{9A5#3A5yk&%-S}UR;y(^ZB=Iks|M~d0xc;B_ zkFc))Rr`N*1MdGfa`0Ddz1$cL{eO`u*Z;S{0!-2TzsdFgq}=|C+5W%a=Z=2i0(||S zq5n7a`~TGQk8NXcJ2s{K9}gsTC_ev{Sf3sLnOy!)p1|dmkm7%H`SBl%e=Car1im51d2g^K>~;@_6yPXc~lJ27#Y{J&&(7QdMn&G=6n|27o=d=GwE|L5@= z!yJG4Se*a2qxcs9ev9|hfcy_6S^m*AEdO=DeeCp{v9d)#emh<&Vcw!_hkLwxR#B7Tnya|7yKhA{v{s#vi|SGpFdpj zJL^B(_n+)U@z((UlIOVVbj(;L|L<7B@^5nZoB47>;(se?|L5@UO!3zOR$n^<;;;A- zi{Ik#<6`J0%lKPv9_w7U-mqC}d+s03$p3m1=>K1I@}KtopSleGPc6ajjo4LqJ;r>@EW2KX=P35S346h;2ksSTt_ z_;>sN1m*u^D4|91{$KKOHvWxuSo{TJxp75E@xQfV{wur(^FJE%KX*<3cffyLNc>xh z{G*|d|CHt3``?>;_=ov#-#j(;s!aVK?|fE7_rJ8~zY8h;Z(#nru9)*vMf@nD`R^v_ z`ERHHcjJFoihn6!^~GsG{N^||{!K3adH)D&{#!Nvjry@pKRd?3KlWUBVcDke{MSn% z<^Os%|M~D|=|BRne|6)3V-NqH_?PYfc{nIn;(s@a|67Rvfq$rt|9SjYMDc&BZv2m; z_?H0)692ON`{F;M`G3{;?|XQx6aTwA_{UzgCO;qIzdNM(w^ZYQ#~~m8r~3cmYw`U5 zSP%aY{}pe9pk9cj?~$-jm}04&uLfk8t{b<0AI{Kc64M>irXj=i}ev`hOpr zS&sky8^=21|9u_&x9_?(e*=jBl2=0N|5s+ne?EiY1ILdU>iPea<=y^&qKAKo{|C0ZFLlTNQz-uRpiQM=J^vR`{3FHqch`TJ z6#q)#x}6`V2jsuvR&M;y=l>EeuZG0`c8cTwil?yumpS;Ge|l#A_7ML){o%yFu}ZD~ zMQ+s=6~Wnqvw)gAvEir;@j`Ev6g^6~Gie{rAx*=*xf{F|0>&ZIRDA|KcD~1i2PqU z|NR5|{}B%U=5J_?rN$FHQsE@4lUj|A_ckj(^hs zAMN08z7pl{2Jv6|aX8mM#zPtWAKTTp85eQ<&+_o^iGSJgACJT0@;@&R>-tAE{@X4X z>%{*t6#qsL{~c38n*WF>{?FBo|JfA(sX!8me_8(d_(u`(uMq#Kkw@DDnEy%-e(?Y1 z8R6uA#O1%{vxnyW-}fqxe@idL_)nntH?}RaLpb=Yi2VONMgMo#KOIZ)p9b&?C#vCZ zxr$x?VC>D#f7I~hro7OX6{QbsFF*ce{lCh=KlSIE=bdKzKlW4Y`Ttuo^ndB_zbDuK zsrr9g7xw=o<$n`sQ)^h)f0ruam-K-1CH;S>zJF#N`FY;WeVZG`f1H1lVQc@p3IFSb zt^F_YuJbPmTl-&P_UCzL!?qXyGu{Jz``-}#CGh$eH~$|``9Iy`|FZp`uesMo!@sKk z_x~CD|3Zp?Q}F-Jso{)&%!vHISkgKGAB$=DN4;|WpDO?E_^*cYzd5w2V1(NEhsTE^ivJ50`FG>Ln&MyU z;a@iY^ZX+&{(1X^b^WW#zdQapiQ>0c1|&n`--?L;ixl}UC(r-XQv7EE|0Vz7@-!wc z)BJzo9_;wvyq=B!UcTHk@$d7K3eK(DD=6_dE{AUCI zeKXbYw~lA?Ke~a@!+@5X;U#lJPQsq1Pr{Jei#5%GVSBL6j);qiZi zgTL&N&GXK&`NurT=Kr2U+5C?bum6$c{Ff^KZv3yL{BHyNm(K|2`rl|_{h#-bu*SbF ziu}9re+tF_QxE^L`Jd$(Oo^r*Pum_*pdk zU#-Z$8~|4V^^lU3LM6x}`6>Hp56_%8zgH$LF{set(TcB7kF z|L@?-4JrRWsM!Cx{{K^oe+m|MC8BaqAy>{|IaR ztL^{iIryio-X!m0@PFc`y8XYUI{trEuK(Be|MMyTBfLh^qrBLDw|qW`<^zc`oT zUjt5R@#{3P<7UeLMO(7Zzgk@WFWQ^yS3}BwJ1DOIbo2i?6#pe2|Cfz_KE6%W^`Cq} z8GdW~|AiF)&cI1xB*#-g{(a57obCU7@{styM%Vu@qWITBBYl1v5Pvy$|J#aa{fnyq zC+{8WjDIem_%8+jPktEA_{ZY>zp$SxHzfWaQXK!d^M996{0V4N#|`25zZsGLU#si? z%@qHc9{-okf4u*jx#ItqIrz(#Y?*f%_&@Pe-SLmXjsJt@KlHxb_(#?M-TBWJ%Kt9l z|H&J}@qZMN|6ix*|L*hOms0!)NUGz^8f2~{r^ge|12QU=cfVvKgq5C zFck0q@qU!)w}Stt=D+$M9P5mKE~of^2L7M8S&jda{n+(S#%-+sTSGMdd027$d7sqFZtqKuvYH5BoqH{`}Ys{Ze;|NjN$e^>CyrjV|G&4~Q}Mn(U3=l_3B z@t*_!pV&t&|MhLnj(;rf{l`swxgo{>j`HIlHveBm@n7Nbf7$rw{U34pf2i`Gvj1N& z*6IJQqxi=FC&fFf@z3Kk-;E~!x9R%-^%Vb40ff&_F|bVI|1Oiwf2QjFZ{Cm@eyjR_ zX(#6YT8jTl@c+7xxOtj@_*x@Km6yLiQSnkQsif`hUe$c>HshgMZo`TjsTb{}Vrz9shJLV*MW}&i|ti%S}^8ecu{onom$DI`a1>kEfe^-nD&PnX}$Kclgq9Gdpj8q)| zxcUDMivJfL|Cfz_pZ|0D-xtQiCI8<`@$U(3YC0jL`Twif{%@%8->&QbzoPgrghu-O z6gNE6_^0(@Hvd_i{|^;@RsVOte|QhYe+~FQ`b2H~)3-4j|L9JZ{~o^Fko^DG6XaIX z!ut1A&2Ij`kK+FkNP0uc|7Jw~e}}IB|B~Xr$m9RA`H%O1bJ+U7^ZY~kSbY6|KgEAB z;P2u4setisbh7bpa_fIeCUO00NdCXGbpOZUf0*LG1hD$r84!Q-R1SYc*MHjhAENj# z_28HFe;&WZ@sG_&H(BPt?cCj*>)%Hx{>z|s&AgxD7H8`J5|6U{8wat^e^TIhFC_fC zDEfcvZaDsbP4Txt(|Q&0x8Bb7e}>}qkIzmS4vbR7Zx& zA7lAP5yk&#Mf`mP|DzQD<$$$C5q||Y|6@hO|E`Mon@-r>iT~eH{8s?}K1KWq&i~Db z?thO_#P2@;@)*T`CEzzp)%?Gl8~<7y{#L%+kn-Pdy7+%b@m~e_eeHx}_Fty>Pj15I zKa0En>y+a8f4Jc9r1-Cf<`Mj|{XdW29On4l_0PYj_(LgVG;zp;A;-X!q*-`)Q23CjO9P)f<>&i5br z0yD*b$G9CFdtyb4g(`8VeO4-WqGcReeA9Pr=ziIb;f?|<<2LW=ww zdqu;)i~mp9|L2~SUjq2cKMe=JrHa2~sPQ}VfA0GC2dV#$gFY$obU5?hD5CklcIo*) z$Nx(=!Poy!JNU=!bbJ1Bz<lT z|M76Fi1@!#n*V~-`sdaSG5>Ek_%~d3TmI3&e}A(x|1X>W%=6jnfAat}{*8$Eci(^V z7s~%$z<*yz{2N!Z_dj_5kh^Q)({>NsCCxt<|9^Jy|7h9m`6mGXE#HI`|BqzA?;_xK z4vr}P$@;JVqx_cu|K_N0;@|u*1AeG0jK8}T`7gK{$Ny6f{--}ZJO3cye;}m(-?&UI z{?Xpi@bC8jf2I6S08ToN4~hSX;{TV5{3r7<|Iax1-}>+E`BlKb`E5AyZ**qx|1{2z zqKf~nvCj2MH|2jK@ZWhtIQ*lC_`gSyfAk3E|L>Up8F%C_1pbpVoa;Z?{-3AQROH_{ zWN71msJ{P~`29Od-~U6P7wz}|oa-NV{PQgJ|GmNgtrJ7?|EDsmfH~%5U{D%&e<$qAReL}*2+XT%2ibSMhX0oT!}wpN{Feg%J@doK z|HfZ3_&?MY#@_?F{J-Yl|K&Hgo9#Q%ee{FfKt@lUUV|LyB;&7TAOC%$y>>yG~n#raPZ5&x}wWBjjE z{tp2DTaw}AfAeY9|6TtkJ0ZpYL(=>^*S|e~!~Xv!#eblUe_=TOZ$*UvVMYAKf5-U$ zP4OQD_{~M(;5Yv-8vY-V#_!z!aMwTlk>bA=eABm10sCvF`+td(+3SBRqV=z;>mLe7 zuk-LPyZ(vi z-{hWuB5BXvro-=^5Nt=4fA{&X4iA10|FZab{;i1ctMc!z|9hL_zaC6p{IXj9tGk+B+>FI3$@V^fI z-wojZ#7|}Wzs_0~zsdQ3Q2eM_uK$zu{{&wD>GI!4`M(hwN%)t||2+Rl5x>t)84jrO z@8-Y%c<_7pm&NbnKO+BE<==h(=lc|Y8`!$y0JZ+Fq=a4ni#Yu4e7PaT|DMwQpY!~y z%l`)+{J?+PWX0>>E!qCh{3V_zA^-iyfT@a(N0zY^L}(?qTEKxQESum3+A& z#s80_^S_h-T>d}x;0OLI71#fjZ^PoZIQ#|ty0Vb)|5oz)2k!r-)_=SC|8t7}R^Zyl zQ$YS(?q%^C_p;&YxDm< z%KvR1{$=wY&p+b)pAwJvvdq65|DSpAd-#{d&+~6aCg=KpUU{4YTMzXSLuJjv$&%I#VF7I*zif#bb& z_%D#l|JwY2Mfq=srV;*S^B>Q@G0gdQ^Z(Z#{2u;g@%#9X2)`=-?)yK#qxkOx{*!#3 z#_pOa|Dy;0pS<$`tE1@t@Z=g5J9g|>V+^rkG>U!g*s){B7O`W;nzducPOPY(iXA&@ zV%8GHjxA!xl7z&D`+?fy@W|FAjp=j9B6KX?!L@1T7;A%EL(YX4__Dt`k#uhJ6#vxdii zr2pBF|6X8?c}mD%a-zx~5dUH|xUj@;>RPYE|Im|e|8F>6<@XHvea-%# z+W!#re_zDEZvUhHeM5c>NV2c={qy;cy#M3u$bUcl$$Q~sHMIL5;V(h{2Y@xUoeBA?P9ph#MCBK&!Np+VpA-2XjPUE`pYjL9KZ1*|W*R>q z|K#~kb0PmjuxSC!so2~?`Oi*N^B)lZWgC;avczAZoqxhV5AwGGYiv6c^0QOa{QEDt z$$x78xsm_j2)}OrDZlsVVCCoiPv(DKuF9C`ftmU{1g8jbiJ1HzovHn3IF`a z|0uA=wlg7r`SL2i=ji&+)co@y|6>t;-TYI2Hpuzq`5y})|Kq^l`8Da&3H`Sa{{i9e znnKoVDgUDk^Dp@qME)m$HMX4z`O8*N^B*|6{xLOwDe^xV;n&SS<@W|TzkK~`A>?ld z{^~PGP80g?CjLEo{o9#jy_WL7mSO%S|02l$RF0KyXF~qEE7kdr_o|!mKQ;ft$p3VN zUpN1hKcN1_^C%ZH%|AK*l|ladBF8^;`RVZw=4k)N^!SH7{yPWq-w*tqhVOqV!hWtP5Gt&CDH%G5q{nJr~Co&AC|pb z&Sd|Re;MR|1o$fruYav2$3MJjYX9${>$SxHT-y9E$NBGs{67l(;dbigzk?kAW2XKu z(aXOnzx2N>`hP6KubY3$?-Tzr_u&^a*}vq^BLCyS-)wmOb9;l@|5%Tj|Efcav;X&e z+WfD;`Nu*2p8)=FJ9YEld8*1E82a}$^KZ&8{V$LHpN#P9=AZI=#D5rjxwMr3)cnJc zza9AdXimij7kd4tVwgJr2`K+z#mWB*Y4bmv^Irz}e+u}S*iPO2x0B-^KINC<#TWhg zzf`aPoAS&2uZaGij_~W|pYpTmYX777w(fte&(H7w(HY+VVhW!Bv=KPzHSGVCFL>Pz zf4lbmFF1eC+9UY=h|1Cb#=zfVSpSsYd&3R?Q-=H<@2fuZH}a1An_E{=gCcvxfZg{*S98{}#YscetJWd!26lPc-D0 z@Bgv}@^1d zH{_S&-zem-0{-%&?C^W=0Jgd-Ox+!uP{vkb4~FfL+J$k$*f~eg%(L!{fQ@CUQUTy~o#AJNJ5Q zQFyFrB41Cq^x^S^;qita`Qza-fXCN`wS? z^WU}6|F+=2;%H0xf7ea^Cu#Z*`Q`Y(4)SjY{N0xL14sNX8S=~Ve_iC?9{8J%vE=_f zH~wGN4a?kTb_V~fg=OxOy}Uki`~D~V$W!}} z5q$su6Mp<>>KXTBj)43B*3D+;{_mdQ{onnf-~XNPug~+}v-G{0qkzA9cRTO@;~Vm` zP4$j{>JA3b|MK_0kmr9ciuL~ttgQS*v->{!1IZ|I6Ls z`+si0`KNtyZ{}F=Up|MO{0D~q{i6Hl=fBJ2-z!D@!}0Gn)8k)95&vaFd4Ca-YY!#4 zvgH3o?bko}{73HpRU-cmuua~vcE-QJ(fHS)IsV1!e?#OS53XW$D*P2X{@Y9ZGe^h& zQ`i4SoPYWm_hpWU`fr@mPW`i|3(SA|X@34@#qR&S{^j|P8*~1%;q|}qQ2$|_>c0M$ zy;^wl*8FZcg9!Tj$C_1|l${=N4L__x&mUP)X3iy{AnNd4=+{z>cK zf6WcQLH+0FKl1&LHs$;)t#*IrM5zDD58}udvkrMyH+s zZ^`+meR6;16sZ3mOZ6YDP+E;!h{{_dA`9G=u zQu?}@CI6GO@BhN*|MK|X*2rHC+thlTS^nwsr z_Z^-8k-Gl3;r!Fjcp!5c)PL_>cE*3-aQtUmx~YFT|KFDLp9J&&iBSJxo$Aj2+pbaP z|30aIS|9zM|Mrg_ziIu;zXkFKk^0x2|IzwqgS`G5 zR~W&MPwl|@dzOAMa~9Np^*na!KQOKTt@QFAtE&PJgvWp6{C}&6|49Ao`lt2JX1E#u zOzU6H|93+EU7-GJPq0(}-Un{@-_Wjqa{rUln`eW&Q8W`Dc9cVCEdC|I!*eum7-T3i$7*PW>v!^}l1pKh%Ff=jjRkmz+TS z->dHb)YJ2-Ect)QaQ-ik|LuzWyTUe=o@l5314s4$X4?AS4f&r3*ReWH=)d7wb^ga3 zo&RZC|2-4M`#wl(gY%EM`4sj%)PGo~y7T|C z>s0^V0|okDfA!y_$Dg|X_r(0~2HO-^s(-J`kiVaCp}&XUN?ZTc$p1p5{&nYnwElfE z{>QezKmV~G9QXl)`p+N#uMA)R-;48){`8^D1yKJr^V*sJ`-b(;w$sc1z|T(nyRrHI zE)oBc`q%YO>pyTb|2M7wt`Xw;r+turcgSS@NtVWcNA=&Cw*G67|3!#P=~y%VPBQ=V z$@pJK*K4W%*VUi@=j*>?#0b9szaQrxab{cQBB=k``RvqxU|9ct(d(a_|Fd_*Kh%HL z@cjRt6V>^@_l-LKb<*`(^8d2o`9GzL3I7Km{~oYSt;cZxv~w2P|D`|geW>!&@ArHB zGxmc6Kk#i2q3a>-vw?KN?TTjGD$u>R%w|A!#|%K#D3dAa~AH2zoYwFK{{;S)iw|E%}P^J@} z{yPlk|IIH6|3@PKUa(F6DI})}^B=}OTn3Kn|FUfO7n3dF$JOh9jzazpSVgQ(#cB)H zfBDJk{vUI6{jYxgi|e0;3;#!R{uL%Xnz;|^zss=xgZI?@2N$caedexsyqMhA@v^^j{m;q{6BU5AB*|lJJ*wzGdus0`t?3m`yc(jt^NPY zv#~V~_yGL4TK{#({|fwOSpT~7KU)7j8UJG&WvTz`*FQP_bwq?el7C%(ntzXsf5qZY zo&OV%e;;sC(O_x(bCmxpAkaD=@Z8I0uNn4#>Hj?Be;ZuKJSFtsOXk16qwC*N`#(Rz z5B_7G67pBwtorx9cQgM>?f)F)e<$K!xBpT9Y*z7qZiGMLUzeZyXM^0oJpOe7^1loI zE6yc-I${26_aU$UlIvd@>3S{ozYWv&{|h7h;GY>@|66yE%I_2ZCG@&NOZ=}J_J8UB zV&s1h@ME45`e&!B`#;Rl`Om5SUlQR5|1nPq`P*($`#<}^P5)2rzY+Q0kNDT^f7HKE z>R&vKxUiJ})c!Au@JIaX@>Bl-sec3)Us>We^)Kgtmm>dU*tBlir^V(Ln*aBb`u9ow zH=Reu6-)dZrS1QhMfkygJMGg6`5VWo{m&=$Uq`Piv&8>~e*e$^<@TNt{QRds=gKc< zTsk@P+WheTXD9L3zk{jb`yqb`%Xn}z@_*n%JT&0K->$&%Z|~oK-GA84`42MxP3Zpv z*rZra#by@DfBPB4zoYYiQ|JH62tVXMmeYj%Wi9IX=k>Z7{|xec8bcb^g!D`G4N| z#ToxLPCNcx6X6H{Wro*3_WGp%k@~Nu*Hu~a|EB)gNJuZ!?U{Oj^l z{{g9g1Q%af;@9`j@Bb*z|2`G@_k(R}I+gTkvAKo%KjjM?o&R%Xmj2~|{|`T&?|<_3 z|8dCw3H)j^9jC89sgc8az^1NE=e_q=8&+QR@$bY%v^^cVgtMecB zlj^^9S@OJE;_pm5|G5kK4}@*1x|?_s;VLx#(+mcV@_#J^TIU0PT+RR8$lnbsise+S zybymAIsVHW@u$vzYlI*2AIoV%{<;oz{^OJUi`C#_u;l+9bAUwNOa z^-sTV>-xv*vavM}_yGL4n*aYG{}=F^Vg7Z;f0}=v^#9mKS@NGc|93|CBl*|mr}_70 zmHgk2{0D=R>Q+nr-%nwiFVFwE7x}-06?I-@R{!4F>iF-I{@-{BS+Ax1 zZ<==gb6I-+z&e|BmWEb^afY@I(G%IZepl^@N&#|KS4Xf6V0k zmz0g*$9Wz>{zGA#O76AP{~hIj90XeD1Abi1{{zVXHLNJizwY=?^Ur3L{684skK|vM zpXQ(a?56*j_J5iG$B};wqDx4=7>La{-2KU zL;e}fX+r+CXH@=x=3lHwE(S~fpF#dQ*rxjX?d0G4(oO%rDJ!4RL|?@6{{-?+gEfTt z*B$?9{(aK_V;g75f9m`{8R3uQUzeZe-=9_T|19z!o^$dk8K;D}Lj8~W4IJhF<}Cfo z1OGpq|H#+B#v^|Z{Aw$mr-;=R;%_9c|M;~3H2{YX57TMAmDG|J}6npXZSO2-v2E2gr6NOXbRA(Ne! z^3T3@!+&d52uiq!<$ogb&&aJqHjf3mik}n{J)I+ zN5M9AJ!q-_JIa4cHulU8_&_-Sk*|MELjG^yH){<0f9GU!{SO)c+UR;M`QJi&{=?7z zmB&9`MgF5gNJ zUq}99z<*h{o&6u*k^kGXF~tKu5cA)G{NKTEhW>T?KlLAw`j2hYV5$E%k^flOChuWO z^*_~3{oj#|J+lKo5c<#FEbf2&2J(LozgcpT8GqZyiz(-g2af80tF-;U6Zz}Gf3GF~ zo+JPNG4$UN`hOewe*pjOSDN*|>}Trh|DL1%x3#u^e&$`x5+itC-$DN4z<U*O1pm7)LYD+T|1$bUTeuYS~ye>Tlc|IcLg z&Lj={f8WG%p8xle|3~oOZs@=3b5j3(Zuqw`^v{+Y!TBd6{|Vr~>r1o#2Tz^y;r;H0 zpJkOlTkt=j|FT;}{y#wepWwGkFE-16Z@22-cjSLtL;uxF3IAQleVNj^zsMTkq0oOtm*D>x`G0}mt23 z>fe$7$%g*BLjRv4|9`=MVCcW?lO>hD;XCrbqqcv3{I6r75qx_;L;h31f87&y{IfsZ z)c;)C{`vW@EyGvl{GTKLui(Gz5;OkVY3lr+k^I-w^}=&)<6|d7|Gkrh|8C@OfNd&! z(u|+7_>TO~ouz+y;Qzyq=g)tZ{=Y!}-{4ncp2X@3jsLZs>iEyDb94T?ssFk~h5s*+ z|5WhbVaY#RYN*l=V^%EXe;yF3^8r7u`hN@g`(Q<(f8FE1)W1*aKemmQ_)Y!$>k0o~ zBmZfzO%3gK>figHoBls92-W$3AJ6;m-A&AYzC!-rVMX4jX8bjutK+{%`d=?yuO&!Du2q1pE?K}`JWGj>U_YDtNy1U{~xfTm?yFFLjAw)b@lZ>=7`_a zf3UIe--G;Tfd4K_{=L84)c^b-RObVJJnvt=|K&@_{|%h~(M`|O6Du#|zwCL{zemo0 zs(gvmm8JTBPy75o!v78Oe+&Gv?M%qu`GU$H9OA}*YW`P{|GNmk?)Xpned0fs(V6VO zd$Jh+zD54;fxqlmv*W*AlZb!9-&3Ugzi*g-$^Sj_{{Z~4?M#^e;4O9j@BQi~|Ec-E zL;l_fzi$31Kbuwfe?a~pf!}+X^y!5D%X`%Qe{WHB|F4;@*HZmYPMiN9k^d*)k8NjC z{N|+FUbF2;BQ#P?DZeksg8fF*-iet((?Zo`F{oemJYN2SNbjKe~$P+ z)aEbE&;R|`MgD(9{@;MV;&-$8Pxf8azwapjAEo904f*?kztNE2|3UR1IO6{}Eq@>K z{|@|>f0+4inM}sN#og5ZC))gc|F3IpasJEi$o~iMSHEIb|81qJf8SC4f2zsf^3?(? z_Zf)KX|T+F4w=F~4}@jzvqgM%!!q}|+Eo5Iqz8TuK5NCN56j$Vc5Kg(+hNJ3^UqCT znfts=e0IY!_nDo+KWkx``}E=W&VgmO_+;O}@8>>?^bubFP`Sua{cry1qnQWi zgX13y@%*=3yMl83egT%ruz}wHiROPof&HKU_;xS$`#V!@%FP zuo-{Z2WtI$ru=&po1Yy2oWl7*E&CHb!{eX2^Iv-WGa$#mW4bNv|L7n832-A36Tt_Zb;iE#-e_?bm-u{{IpA z-|z9vGm!u0Ma=piebxih{O{!^|JnJ){0B}SE`^QH^}n;gN%zylQ$qig-}}43_-Dy~ zX_o%wf&ULbuI7IT^8W?D8q29zU7`Fpy`zqQzN7j#%|F{h^uG+}A2#9f%tXk4@BViB zKYO--|Nb=X<0k)oTMGW!(EnJ-WaTq<@*gkhUw|DRZ3{Es~$;(>$Q zH&0B>%eeADVwQtK@%ik^f7d%uLVCf0nS* z{{z$fAMGapvj3N%{|g}hZI<%SGH&vJreXf&{qGh-{@Ee_HHQ7aW*PPT4@T<0jjq?y z{AV}A`A^F}qW>?+`M+MeJ@YN(zidf6`DcOQ{J-8!{$>AP3jJRQPHF>7{ohgk&q|yB zrICLQ$bT%SFeK(a3eEpIe^lo`0m(mKOXS~~od2c+ME;lI{8P4X&-6n6>n-KqH_iWX zZt^ehf3+<7Zv-c$&)La8o6SxCza$&URDv(V{{7MA{P@@M=>H?8Apa#_ znALwnR-ONNWc;h8>$TMXcQ>5>)a@qnKaBHl{YHD{H^_h2(suICo->>O_$Ro@zr6qD zis=7ha8m!gng3Yp9qOk4UuxL@W&VdF|6Gv&SWX34q4`hc&+7cgb5#EZ`OjBg^OEJf z{zoAHCGedNOaA>?#s3P(KX=5x?)Xpr2c-YS>SN~hzx-dWJ6!a?k;s23e5Yn{-v8+K z7Ro>Uc{aP7`rmg{>@N@aKvtapR9P$d|Cm!A|N0ZI|7bG2{-yM5QvZ&wfB8)F`j3#m z>+6+x{jZAt{|Ef7rq{m^e%}%Q=cfGO^*^g2|6joG{b`o}@+qqSz!879A-~N3>d5~$ z@HZRsHxPbS=BEC?Fyxo{UjzC70sdY?{$9fGIpY7)lt0XW1@g1mp>@7$HvjXclKeZm z{_QJ6ewqI@k$(vA*BJ8G5q>t#P5!?&P_{-5tC|5FV4gBfD{ zTMPMT1OC4Mnf3pQg;oB*5&u+8{$gGK8EpEC(eG1e>ndu{Z{a=gZ#4tf9dOH^BjW&SIXe@@`9{>!ZY^$>pF5&sNBewqLEkiP`@14I9{)7AV3j`+VZ8Ad_HRPB1-vIgN2L7@)%=%xjh&ulJbL;LtY;ok`P=LP=Qc5?iJ{4Kwb z`ge5vGd2Ip$Uk3%U-$SY<@W|Te{1;q*T%>{Kk(PloF??&FE{+w>|pPGL&~{Y%TrYW`V?>c68%`QOVh|B`YHUB>G-$2)EiGOdy z{7e3AkiQK0W7{co725wP`$Nrtu>4T|`f5zPUH_^1tB`+*2)}OrDL3S{Ye;>pAOaASVe<|RPZD+##*ZisG-=D{ge|>&_{9hjb z+YtHZf#W~*hR1(eW~lt0qvK!S8y^3W{!14f2Ce^+{QZw=J`%5g?1=pH zg8vRf|K2yM|9~9-%f3nailzGh!O*{)|LuVM%Ygrisbo77)_=nqYX4*Ns`cMU*K3J? zU+w;Gpw|8M??f8G8^{riske`^0bq5tI~{&o4Of1lKUvGT9)pCA7(zfrvZ z&o0Qn0Qhg9eL89Wzg7FcKTMtfchdD*s{dZY{xA1`c18Xy`0u8DIw61g+G_p#r2Z?X zk#WTm|9;y2pZhNzCj9Tg`M><%Bbie0A9~X5|G{^v|6qK9>p%MApQ3mDM{56jqW|T= zf6P-t{}t;H|MR=)|EB(B{qKhS3r76w_CM;ME#-zkwg26be}#yDU4H7H4O;*F{x`K- ziuqp+@-GDb%ikh>Dq;TX>ecr@^&R>DQM>>1{a?BNw-@pc1OH95PbcIrtyJruU9aZ9 zhpxB3{wMxk(#8JT{h#w!e-PT`|I%jsv78imz?5Ge|2P2oSAzU|J%;^%ed51Vfa~z z9}_#%>YwlbR!tN8zlWm#GVouy1>7Mewy}lJ|7>no=f9pK|Nk}gFOPp5g8U=Fe=qIR z;<+eP|Fwsz`S(fvS4}5%Wyyc7cK=^wo*a^V|L4Pye+ls4XjuPM$Ef^l88`L+Yg+$x z$iFi9k9kVy-y`!se<3&grvB?b7xjNQ@-GSgn`So~{~PL6|DGfNzv=tWS6=B6V*bAh z@?QquX|r_y1JBXV#UCiqTZi9c|}Z<_zwBSrlm zi~LstfB6`*{zv_Kj?RBI$bbI)hxWC_`~TG=|5d=>A?|-jc?#vfy+ZB(0pX9WH=jcK zSM>jXU3#uO1$oY@4^;+UTRGVL%|Fy2@e@k zOZ;QB`T6S~H6j1W$UhFY$y?42KO^V=#nx+y|1d-T-U*`qPeJ}0V4JG4X8biwegE5l zT>lqauOM z{!?tdmiUh_ek_$3N-u4>o9ze~|unB=Ro>$3MI|%;x|8c=h|2+-)Z-#BES%GY)nAjAW|5gqs{g327wq8s8M~%|klg^6y zf9L9A{67NuSB3ny(BrfT`J3tM9}BC;|N7{9E%6_yef*c?{|w|`8uA~@X+r+WXVv@% zB>!SHxUj^ppZ}8lUzYvzEd*HEdL0`zw*fWkL`55miR9)?Efpf9!cG@W4fe`R_ek?Ek@= zUWfc^;)WdA=9`In32U$_2g z{yozF$!5SrBld{V1E%>8>O}tGP2WQQx4||w)SK=9(2WmB{$uO4#DB5j{72>=-t;Tv zuYml=aw@ueB9)_@OWMgNoehd2EV z`PYo(U$_6!{QHjP|N8kC=fAaz{KK1`g#61x{u{P7^WQ<||I4|l|3A~_AKvsM#**|MyA$eUks!dM)LDeZ%}$9xeRCn;wPyqagonbe@v1{{{P~_3xAZU-B)PS6Sje zxMIL^k9`x)?#v(mYraSD!%06O{|dSOKi|LdmBKb-Uv@~;K?kL5IB{@agJ$A9*s8~>^E4=4SE{KFvs zore9t;yE?{o}>Q%SK9o;Nk1X~osh{+!~8ds{Cnj3zu0;$<$r^;`G=D}L;kfR`PZHQ z(EJB44DS3l-6#70HORjrB}dy_WJ{X_)`|Cj~#8^cM1uhWyvkc}l|m?;o%F_elS5r|Y%Ee@I1aiZkE? z;rvJL|H4U6A^&j5zi*iT?3pTm;HdxqlQ#cw(o@KPH#n&%H_Ja;Ma{oQu78QG*OLDY z)8-#edJ6g1f&9mEnlS(MH_7@czp;P4izB?*GC`Pa*$GkpC{j{8yf(=AUKV z^na#({EzSduw%shA5MA-`CB2A-ic=WKMi-Q`~k^-Y`vE9zh2t>!%43p|GJU<>&|~@ z{sXfA8;hfdve{~>Af4<|i@{P%#9Zo~dxw<_uX zuu>V)n<9{ou{V$;FwZwmDMXa(0d?1|v z$o#{Lo*{oZ@WpZ}R#xcsuiC}b`u9ox zW7}kj-!%Vn{}&E=hx{XR`QOHD{@eC~di*DFl>gaM=AXeq&yfESaMEKb|DL1sUsC5E zPI?OY*N^01cm6~3?+x<&%lqHKL64AsWypV{Vg5@i)a&2aZR+?}tok3Spa1;pAKuMk z{tr97A^)S0|K>9+^?zsik3F*kK5*0;>kSz_ma)<`IcK=cuDRZjMaB+cou3^0(7Eva zaOve9hc!ZJu-xO_pYiV>4Udn8$J$C($UlGK(pxL{^Fv^;O8HKsoQ_XF{G*Yo`M!)3R4y!&$gc({aBB>KpT@vn5O@V^rGzx7}3nLp=) z@n2m36&wFqMr-`{o-1(w&;GXdB)#+B`ddwZkB9t?z2$jt?0(Ka^`@sXe*u4wC4S$K z-#^(6f5T1U_&2=h5!U|(5b}~$%;vu>Wd84yhhYJ4> zaQ>d{pUw=KAKw2}T>q3d|AC=@c1p4R^W#6g;qfon=?(p_0^?uhwr2CcvPtUv&s*Nj z_&2-Z_$TxKAo6br`H$sP#Hi5xzhQB8{?A6Z;Wy2HTb;=NL!5v1PoK`r2Kg@)=l`b7 zKYQM+|N9M&^WTR4SB3mHKWEne+LuxN`;PKIhkpL^omb9(VW%fo|KIHUOlEfQ-*GJG zPwU?^^v_OpVHms|M~g9y#5Ie`h@%&L;v&l zH|ziH^!z6>{#P78)@y0}Kdj>4$NByq&4%;e@c#FYasH{FJd>F-mw$2oYufz#hWYo4 zo_~J*WA~Th`me{)|LTzc9>e_iEvxpwfcC!^Nnf?(za(w`pFsXiApfzPiXasl|C`DP zzoXYbQ|JFl&OdGG@tL_G|5E4b@>&u zZ^ZmpMDnlgpX8qn^8Cx|Kb}JVO(Fk{be@v1{`<)JuK~$_Wo>chKXr!lpQd_|{|TJG z=acc71t9wNj|LpT*|EFB#51&W5v^4)S$UpzfO=ABq;QU`NJt0$? z>;K~XkF@#s4f8LbpCWyc75hIj|IeZSQIP*wPQ`W<%6~n{KU>?4|J3;(kNlfQ@~=Do z(fqT)oB#a&KRcqF_qi81|MW{IWEO_}SB~U;DsBD))BJzoX8t4d|1A1nE0TX*|1|#r z>Ho2Ew$%Sj^DnRedmj0>fc*E+c}l|iuO;Wd`Xv8-UlnKn|8V{JPyU&g_y2nl`PT;j zy>y&T$WQ%xj{4u+hU35V-+}yFg8!JOg#4xC{2w;bP5;;RPd&N*f9(7@Z$YPFne_lcVqapt-+mm^!*t$aFKZWoe<$s>E`JaURTSfA(+y80)1JeKK^JDA&7rOZe z|1iqKasC^G|8{=-=gX^K%q#)l3E%%U#?MOs_52TScYgj0%aTkrSkI)?@E5( z!AJKng6Wl z|ML3RH#z^8!zN{x98Jk(r2lt)!~1{RRcimQ9mo5Br|AFetbzM~OX~j5 zU;pU|?|=CY`mcoicXp8d6cOA)^PlSV)&B31{MYPA>dI37=QqrMZ`l9eMgDCd|5XQ( z?M%qub*`F!Hpxx>AEljtKK@laQqJcQlaYU0;O{f!Z#rM)_lFN9^AyqnE%`r2o1f(W zW#nHU@*n0jHvcPd{Z9+YzfbZ{=*3=0>{0CpO!MCr`u_m=w*&v(my`2U#TFH+|EddB z|AC|af2_8Do`3IJG5&ps{M!S6^}%NKU)iYgvz6V{f4w1p({+OXBjn!!_{--1_x+hd z{#!0m`8`Md?>IyL%IgLH$H>1U@V6TJ@7qcp|9nUOkJsks{ZGFC`zOf16Y#S`%<|tk zL-ilLm{IzFSr3_4SnB^Lrse+>`KxpJr`wsZ|J84;`e&=SssGgcZy^895q{nAkMakO z@^8v7-~anFL;QQhe;Zw|rTm{{n19LNjr_X;e{4Gw=D)IvC~!u&T8es;Z^{r?6-{*Ffk|1{*^8~E!C z`75?l{RfWnf2uY=J^q2`KW_lXKicSVx`h7AHc2`k$`<+{wSW z&yEUl{);rmzi1m@t{k@vzg=>b`gqUDyiTgbedNNQYuu5~AN)tj&+o(^?|52_JK`7G zPUGt-8?Qdzc@}>>Adh#A<&S5{dfHFtkN0gO>RPP7>`eZ6xP4jC|E2%$(7zY)uiO8r z|A5qg`1j>TI_%DQZTFV z`F861mtMm!7Ijnq;h#&o%!>R=|G%LB&A@-mlUQ*f|JjYy@h>3$W7}sb|N8z({(naP z%_ID}{wcpdc=_|syuAN=L<~%YSO!Dtls`a1Ug*>m8_!rXdf4uYln}0YJfYl$x$7%Xh7UHKrAO64L zd+tBBUQ7Jp-$}a6QvbiB|1H6P%#&DgA^slXKOp{N+h>X2z(2qKD;)oSL;kHI{JQ;* z^816AKmW}CTmIox2v+g4-Te27{uf)XCI7Kp6?h;k^4~CdIG^YLiT<|+{|&THiS-rA zf9=NV_|Mi;`(GzruOkAJcCTH=pAuLT~+iZd_&t^dKPAgtwh zyZx_5@W<9W)A;%EuZjo7>tAfHd>_mm|JoMv@9%0>|K*#g{VyQ-uh@;O*Ao9C7W*HZ z3IaF4BikwRRH**NkHr=(!hdYNmiS|Tu)qV5?)>~mzW&{V{cj%#L16g$r%zu0WUHy; zUu?51@t>ys`X|qS^IYP1+iX1lv(0yBW;@7#nA6zne+BOU+(Gj1J!y9SlfS{h*MHFG zQ9u9W_5azi{`Up{WrvyNKfAqJ|NcvE{GV>R+D! zFem!oFXw+Ra-OaTT%rEgO#FL}>i-OF|2+R}esTPF4&>hf{P(?K#^2<{CBp2 zoBCfYt^awD{{ZkG^OTUkb_dme;Hdsh{WrZolJEb|i~Ku*|87J7{-!Fw|EnASi>LKJ z1?PXY5&yd5ANB7KTL1j`Z&M)r&yW7A!GERU@&8WZ-*Z&|WrqIc`JeM4|AFAYI%{_R zE89`cKU-bRe`k^U|5=9pUta%Tiu^l+|0YBK^_!{uKJj0y*MF8s>wiJyKM4HCJSFV^ z4aC3yn(AMy1{apb|J42$LjGOAf6P-t{?g4=|K5gf_*45|0QnD&_}A_K)W1jSAH|EW z28;g^Mhj#vyI&Fr}n=n@{fu5*X@7Qe?aQLSp6@x|HY7hkBEO=e(FCU^P3t(0?cK?>X{+c3S_-B7Y6|k9kVyzn%CGh=1ul{9-2i zm-oL~4*3rU{}o4&c}hb5`kmGM`;Ppdqv=0<`e)X1=HLI2*T08isWB+{G<8z z2YLSG{m+(1{v#m&9Y34B{!_Y(ntxW|X8b!(Gyhp}|HIB3NAly}@A2cmUmiRuvz)>G z57{37zQ5>grt&w;;P*dlx>mjaVVAi7p?@fU+%Itd!|csz?|;klFW>(#i~je9{5PLs z*8hT9;(ue6zp8<(*HZsq+Hm}r_kUXv`HzJBcN_NqMv{O3U6nu9Z!PhkubKbYb~t`u zu=Ia<|GN?B|0wX^bR@~Cczz1L{y$WG{~O;?|GPlbe^&HA`ToblIscb;Ov3;#~e;w0#|6|vy{jd54-ajkGi1QJ~4t)NPZ>j&u`~QtZ|3`!W9z*}$ZfgGv9QnUc z)4$_#kNvs9QvdS)hpV9fW59pcf6eAUHP5T(KLnHA^#4Xp|6%=CU0=@UKP!v+pY5g0 zaD(~}`l)|!bCtiYhu437vs(WhqW-%@{rd&#zuQv%w}$WkwHo?A7W_B zo%4S=?Bz_kLH%d<{P+EzfYg8cG+zJRPa!{r8#m|3>P6e>eUA zGEM(s{Wpyk=l_r5{F`;Xk=YLFziUC>|6<3#`g#8!zn}W|wov)ort;}Q2(`eq^*DMU!MOp8vUOD{;Q5Q>;KhjsrBzW@_)Ief5+t>`*VY({^jfc>!SY? z!GG%?X7%4e{0ENwU!mzA>OVj7__vGt-3Zn@B;ad*((L-j zrnS}jXDhlH|CY|AtuqyMh1G2kiJ~Tbb2AJJ*eW+5a~}|EGZelAFx@w-W#CfCBuM z=Koiv^?w`s-_v6M_X_#nw4Ww@o*V!2{m(W*{|(^3*3f@;9a8_qe>+{TCI45a^)LE$ zuK(`^{%h0re~&+(zM+5LwSRac(o%>bsAs3bKQT`triEVr35frI_>ZN1=K0TG|0wgn z6!M=I;g9YA6}bO1<@X0IKY9IoCFI`+UjL50PMy$yDcS$`$?M<6@~`{)cWgTxKM>o0 zaQ^<+#Q!k#zi-69ZvLr%Z;<-WGB!tE`3~ZE>q2wn`(O2m$1o@b*5UE_U;O?LFwj7M zp#EwP{rBU){!Z%rCtPps<>K#(-1*n@-wzHFk2elH{?}e$=lBl`U;o(>{qG0<`{;Qp zVmk}<|F#3k>%YW*>#1a3X{rA&qj~;|z?o?anjhx8{>A-2L;u^L|NX&#%u_=DUBth) ziJJe|6F!stLv`oJ|E5Rz{(tv{y#BVYKY_uaP}Xr-fAydF*Z2RGTvw3%llqrGH|D%6L_y1YZ|6A$>|IVEMjxEm390dMDPx1Nhz~f&p@$Ws6 z;r+G04eZbVXg&Va{&(U0i-Z5;z<+gM$A4hz|7tz{{+{0c9uNJ?`riTT|KNy!-SMCL zXI_E)_vgRA4e#gi)c$wl{Bwc-6Tv@w&W?Y!O9B3Vc-S>X_n&{}<^6AVMgNC@|IT&! z>z{PYr`urv6R+%lTgo=l>4s|1|Jl^1L1YzG?m6?b!eB=>M>Y zf8Ft)`VUC`$KpPd>tFicm-BxP{?7#er7zg=ADH@YEw+Dt{HrTG|92nsUkCo{$@_(c z-U{{qK2rZassF5aKeKRs{3wL{pYazf8210tVI%qe$=;lQN0|RX6j=9-cKow%4EukR zWB&)B|HHw5%#$!v$ba*pYXA4i^=~o3mg+yX|60z!8Tj8H{P)~s$-n9T-<6L2?}z@6 zi1^p-|I|MlJIY z-$47c__KxTKelz``j^=EE!F=p?f%clKY9Jbp~!y}@Ry7C*QDE9h`*y!J^#rk{61Z; zCH@uD@{d9Oqk%uRoeBL{A4d8=x&DDZpSH&T)cgk{|1lAM-Tp`U*&yea=l>pt{Kw|% ze^1{3sINl#uUTKszxR*2|L50`^;*jRaKrpd{=<>KKIflqXTtnfZ9w>sQu*ogX)FJx z{PO(YBar`i;BOS~|4O&FkbnPhQvZa%o37WA|CJ2=OMV#i!}A|c0RGr^CiQ=W%Fm8= z<3Bb3pZNYKCr0>n`(G8|4~T!7CtLY9Mj{HMeDy>&N}oF?>Nxvo0@W3{UPfUeh4{;z@4l65|^ z;`|TE4=;L$`9A~rW7{cKUTFT;NceriAKS*k!oLObpBdrT%|GS$206dH|Jg~%e-`kU z-C~yia&r75ApF@|$$BmMzt%ASk{@355A#13_+#6dF#m01NdG@jt^Z=>KQ;f!$nQt^ zb@Na8*&yea*MBu2|JlG_{}ee+kgWX+r<4^!VR!b^o`#r8xcn zdc*unet6M8%>VhoAKT7^{PpDcpYJIDsrk=9ez>$u^6TcG@_U1vUylE0A^(Lr{%6ek zf9Zzm{68T4ev$IuY?yz^?<0RB@W-|@Vg4Hlzjv^k{-2tEEb?Cz;n&SS!14fXBGeFBmWuTKjtZ6{!8ms{{eaZL#zfDGueN`8lwN5hy0g;|E39M(>YpCG8{m@sDee{~GY$@*mQt68bNzQvI_LZstEX8~T^$KVOaf=YjvSMl=4F zab)}_^`E_ntk+WiUtPQZ^ZI8`3;)+4|Fz)1&(MGSSk=GpsQzzB>;HP>KOg+ZJSEJ( zcZ2FbApVP0|N8#<@xQKB#r(e+`L6^2)pwGdCgiVLjlBOE@!v||C^D&5&XwICCq=#jcWh*93B5L^<+-~VJY&Y!#g{XTI2`w~m{zYh%Wf6vZek|_3%&kP z+pN|=KW%Iqrp&_@=;!@UyZd?n zQ=jm+PT}u=8r;N>yTIEHr1X*ME-x z^ho`u<@XHveMkIV;r-8ruN=QWp#Oy9|MA?vZ^+MXapPa|KZO3z9nilXe_+ags~i4? zuSES%LH-MXzkVt|{t?T6SwjA>_O>;vf4`;Z{Q3QVdHm-V&Yv4ZZj9{z>hAy3{ojBb z{|TQKxwN$Zqrd;lkAKMhzdMot64?KX?Wc(iF0}t&e~G&P7dSfpVX*&~_wTPJUjMlR z`ESaF;4ZSCnvlPTod4n-rsltfuGfXx? z=)aAe{}K@YVl}v!$^Pa2PaZ}7%fNpRJx-I5zw%~s{O@=*|K4S!t}OAdsek-Ot^Y@m z|CWe<-TYJk{;cBvN#wsA{Kq^c^xt$j>Hp;T9|m81HPig_{?`zm|Mdj&-wOWQXrE5V z->}=_%KkE|Q}bUe{@V@vzpVeqk^hQ_f8G33{~oFTV)5(OKld-s|9TqvTfl$G-K0+? z^k2D*dR)SDTK~@=|5XwHy8WN}_h%LV0rKAg{$rjJ=D(wn^uNR1jQ^(o z<@G-kk^gG&-+UZ7PbDFL#WgB_aJBmW7p+$mC;w|{_kU9V?a2S1h=1MuQ~!aZ{-4_a z3&?*B_>Xx?=)a~#?f>2hZt`#HU*7-cdE~zn{MXSwoshq2Z?*q>r2adnk@Lzd&42DP z?EkXBlYhS|4lED^;+Uz+pz!3`hOAm?~eG_%|G?;&no_3LH_H(f6P-t|IN3l{hyua zrvIDzm-oNwK>k+n9~k!kuKm>h&yG;}%kC*o{_i&I|FZsHM*ilAf8G33{{g9gY<%LY znOy(U|Le$q5BQIHN|^sLa{SXL{)@$L>R+D!{2KC)1OGj=PbcKByj`t-kJP{SVsY|6 z+OYpi|F0tdy%GPq`KSK9S;hZb$bSR)k9kVyzl-<}i2q{c-_(ES>f-g^HzD=4ex&+`hN%g-w*y{p2XS;o&Qiyj(>Vbs^fobqb!Yorv7FAJCXl^2)}Osqx@`; z^Y3H-rXX8t?Jsr~~;{vR~tm-+u3`P*~( z|HRCH^9?FLJHt)?f5?zu=D!>Hp920?L;l(uResMAf15Txzy4KT{~)ec$zA_)k&WwL z9_G)dw`~Fcn}#C`S>Cqdzm7lTry~FLB3~E&GAs6f*)XyHKNa`?ABX+_@;lA;|9h@d z=l{VfZu;N)hWr1r|9ye^e;V>%d9GRi>-${IzfbaC^C{^omgc_?r_KMDoIjWUOKn{L zB=YZ@=KuDh=Rg0<*H01GKg~e?D+av&X{gryAA&;sXZKU9cNCkS&;R7{|2HuIH%5;C z>dyb^@n3)N9{gm%fr_{{^9)HH%-pG z0r~GcX}SFTGnlI0A7FtJrZ@f-%D*2=1b<+o;hOW`e%8~^!%*G%>%ZjnFW;d5Tfu+T zBr;DE>nYU#dS6uMe*y8|Lf304|LYp|zxE#C_eaiu=>wB9o#4M~6z7lmXH3gK+g|Pe z{pg52>_4JA{>4@?-~%!L-=qH)@E`Le)>g=W&*SR&=bc=Df3W!fne$&VVRGgj@ZY$W z9si!Gf7kW@E&9JL;$OG_Q~zvM@&8}WfAJfWGw*@_ZcF}sL;vhiH}x;Cf9pm6w}bya z+NTrNe@Bmc{;x-_f2)3pj4PJvztXV(mxbf|Z=(Lco1FOo{5P#_r~U&||BpHL{|oxR z1N_H4CG_9>q}u-jNA+*&zx7*nes|ewA7nlP|JCc-@y|9>um2fvP>z1{amW6DLjV7X z_}A_K)W1K-{mc2^cbtF5rIRx~;J;QJ|1h5aT{UNZ{_gEiVE*GprQ_GWBmeUHmtWEU zo#4Nf_Gz(ch30?duc-5Xc1i($OZ|U6!~QS*|Bn7=fdBCR&uRVphW^H|KagZWB;O`1cm(j;)x{--?jh$ zq5r$VfA-R4{`L4nq57|UL-p@F^1ne^|9_$XAHaWj{4=e8uh974kAL>03_?PT|a5{J?)F8a{$?gIEHbZ{@S#|!)8r+P38>QtRg8cUa ze@TZ~|F55@@_UZ>H%`l+LH_%Izt)hSJ*V>fj`%mx=I7TxRD}0G-JjS0+kO9x_2Hhx zWiRsAe_F2P_azR8rv+FhlPi+g{d>b7pvzqgLJ=)d)SGX9a{AEmF5y0SF?_0swu%K2Xa|L21L>?Aw>JyZYp7TZ7X|K-EQ{{QTp z|J?Z=%{&19Lr=Q-Z+~8`e{ZP*`R~vFu6q2b{m;Sq9|!;NR^Y7Dl7HXOzwgMutp7fo z|2!D+uY3H1`VSoS|J43Vxc|GsKfDzx>-dKEDc$^s?K@lsrvC5K%YXRyk}k81_kaHe z(f{Y<{JHtxL*Tz|YqRs;TDsK!@13gFe?ZsUU;QTq5kI$S+WtQ`=N||D;jN%q_se$r zKif^^Pm1N=Uu^%p|NAS7{yz`r|9X>0Gi~5M^rV~r;6=6nGvYtS-;aM^v;U{|KQHIM z_vCXKycIfY{N7Ied#3&$aO6L%|GBXKACCCf?f=xjZ|FaklL8N<_CG)8Z@u7L25$w) zdOGaXzi;aQ!D9P|0S`V}7ZUw{KJ@=cuK&|{x_JHz9sjETSndDpk^=p&pZYJLJNE6( z()NF7hq>b)_danhgSWzE-Ya(ev)v2u$4K}C{zJv~&-Z^Drme*H{}x35kLK#%(0|KI zYXA3$|DFaiudw8Q^HDi_$v?8<`UkoHzmTZ^m(FF);J?|Df6vr^n;ZZ2yNL0BVa`A4 z#j`Vyf&b8x?)dM$tomn96nOo&KmTj$@tgW*$MgJ`{mPH?3?F`KrfXi9|8?@?|GNCK z1Rgb%*H`QtGxvco|FZrU!1{kY;$L_Cr~Z9X|1s+R{KtN9;0JX5FDq8pbm6ePpNjMO zvi1VL>=VoKM*jamENd>}|L+yc)?WVq#*6tfdkJ5*i)BYM|9^*AfAyvO|2<;qU&jC6 zb~#^mU%{89SMsHI6<>D!$d|R___9wdn{MF$FTas51F@{RiT}S>EE{j;{|}$Vta$&c z+AT%@Uljd60shNgCCBN+FBTgAJ3dv%|G<&|EwsmfzW-CzD&{{+ApeuVUvJ1?_L<7h zE}d=Q`nQz-Ew%ai`QO2C{`zm<<2DL?-^ZT|~Q$G@la`hS?~q)V9H z<>$Z6_Xz(>qW^aA-(l##o%r`0`QOUWe{H#V{eLOWKVy?0@-w5-Yxq1Zt$(&hf&BL) z%zwtQ|E1CYQ@Q%DBJzhZqomU6`227>i<>x{`37$UjO{{T={V-cl`Gm_$PLqa>D%gQ2sLu z)W0Qu)9atxMvDHo9QQx{fFBsV6voP~wbTE6!~FY2&p+S)m;OIS|KlV6b?5)oe?YE( zkG1=m=Rco+dH;{)vHm9je;d6{KVkm;H`M)KkL17PGtyTq@js$}{lCh;BJw{A{ITs! z$e(>v|LiQa|JOE>^;*jR zqlWpH{3DS6IpB|NXTto~zNO~hC;Y|Ae`@}fkpKAzzi$31zcLQP8Tez{nUKGo@H5{{{!{a> ziu@fBe%<_2{($%|R{fju%kh78RCggAVUgh^3 z`QI+B|53>QX2id4{||_NZ;<Z)5ZB8>mmO{@ZV+Vznl8MM1B3M;tkSQEX{v+Nb7%n zHsJibTij^69P zsr^@?|FfgYB{`KFIe?(l{`VsOb^9On?++pi{L->q&xlx)c>+(_3w|;8~;uH%lCiX z4E?_k{>#54IZasq?WF$MxhlU;*K2A1`?P-lSL=Th&}+=Q~Tcv z`6q+_n5TsPYd%o>A3IGQ|BJ=1@1I})*Bie7)t1Qr68LYTeL5k3<4-ETcZHh&V)0iS z_J3LbTOj`j5&ydRr~W-s|Hb0h_s`G&uh>SM|F{kEzYP9+4E=Wz|Gp#tI~)3!$N#I4 zzYF|#ePnk3w``Z1f1miT_==1xmipf_`u#uum*w?8+aZ4k`1jr-+nKQbX}$wT{&z|1 ze|zNr5d6nHCFJk^PJR8Co#&?i8TikS|NcW_|7Qo}e+B$E8~QI9uD<@~U+!l7+jW#) zA!Wt>pRE6Fk^iHJf8G91{RgD}X?^f69D7vz0aO1qO!WVqkpETi-)rc<_h+^Lu_iVD zJ@kFm^tAQ+yzFLJ|8oCtN96w){5R4*E&g($>mM6GRQWwp|J`)GmiWi(_y2tTOa5Ju z{}bSkZD&IM>W@_Zfbhoz4i^4uWJztxR|K7){e|ElF z|K1d`UQ7Nb80KH{?~eSR1AlBg6Xw62@cV?nSou%QzZ>#*NBDK~Px-w;&M(LRJ&^wk z;BTfmP3XV%6E*(<;jfxnocup)n19J%gZy6te{4Gw@>hMT@_QGk^=i`M-+r z>*k;Gvq8=;$N#;M|7+lHp*cM)69R+cs^TXEbQn1eau7W=9WM6Ww&^|;_5x}kB3Wk(fO`X@2ahidkA=S%{MiWpFWU4?JG+ zDBq57*$t29{%*MbDsf*@b_xHx)u$Yt|9jywD;^KGGvtF+C?8pR{OdsU|4r_XQBUHx z3myOP{#NUso$luNpRWIqUmpM38Tnt!z5YRuQzhhY`bFjU$?-3-8eCYK|Ck>ClJ#GU z{NG0W>-InD-=p=9MQ#iAzncH5^&b%b&F7KzTH@b5?eXu! zkpFw|AM=!y{~wi~T|~xzu^zdw#Gl%K9rC{k{$rjJ^0yNI{*`XVztsK@MgAWm{&o9b z4e=k4`j_6rF9wVMG06W`#J?^-_0O(!lYdkHa{upeh-VQeQx@nzW*|Q{$uF>803E&{I?kTul!B*?>q9pXIlS9BL7bj|GNE;`uA^e)Bp7S z^D{4G{nsP^JK(?1(0@3rh0DN^{~AO8a{hlT^8XC}YiXZOSpPkw{sZE_ovzo?`2V7I z|L6YY`LD+#|GPQ=dzp=Yq4#j@@ZV1lfi#UmTYIj{?|+V`;PqYo7VrS$p0Jok9kVS-;z=LKfB3I|1Ik{g3lE&n51EaX#lC`o^7^Pk=w%PTl(- zu*C@flZNkqsQLa^`uzOF1lVz`9DTG|J=XiZ$$pjfj_pL;+Zbw zzod-tU$6E*DJ=YAu<&1m{N2FcINZ#?PxyVpU%3)luO_Zh(Node5m@yWh{-_Ly(=_4!VKRt7Z z{l81l|CivuhvrmlN1^&}UP7(^faJe_GJolED|7!>A%73>w;A&H5q>sK?SJj76vzJwhW;i0)yO{`_+#6d(0}u? zs(+8>AID-5{>J49Kk;8j*K3LYL__}#;qlKik^j%g z@lV~?Kj`sKZ_pn9>@>Vgr&ZOa5QhKK@Vm zuSfpBfIqgK3Hh_LtNHf{zgP_}1`Gdn$p3eQUpN1h-y7uo>}iqzX5{||_#0_X6Z&s| zSiS#OK=`}qdM)|yFwDQ?zXADk7dghZGa-NN93=m@sP&J*7heq){&C1ZB*L$of6DI- za(+4f-H7}d;IG_}^y!5D%jZ=62ju+kCc0ir{$DZ7zvRCe`DX+E*mfr5?g%5#@$YR!>dI37Up36X{JQz4{Qe;4m*f9!$X^2d%`~S8{b%P^{j(Oe z|Mk-KTJryzVg4om9mqcy@W-|@A%8RB_X$4+Uwk!K_-{x4xg-3#`KSEeAm?uyxiUZg z^&jM)2l(s%A^Wij{a5d<{$4=%t2Qo9|9{;u|MK|HwaEVs9RGVGF09{-d6??nFjBK~#zU(Ek)>i8G4Xo)|y|9g=CJMbU#l+b_83aWqK(eZCn z|J51s`uBav|2^rt|Lp$a_}5Q-JK@k5TLALk zLdU6u{4Mhm{@dN;{|&?OPx`+f{r>>|W1bT7SFWh?d&Iw34K6Ize`^2tB7bSbzi$7d z{sTw-FSY*%k-r!G`)iPKDxv@0d)4zF0@DAw=z1;rKgF>AD_35b&wn34{sqB*^(JQg zb@QqD56Jwdm9Ezk|C?#+zYY0+1phHl3H^Kbss6ot-SofI{vSsEg}{HzQ$qgoHHd#l z{omAo%WPu&e+2n|0{<-^l5sjAe>e4ipX$H6g4C6z{5NRU|NOv{`=nmY{$-nOSNAvH`D*1m5`G1D|$8suU z6gvO2b}hC3eMkLIH~(;TPyYJvo`b~sFOMSsBDsWmq)rp^mn^LEvpdxKuc7O;RR3?8 zj(;nPdVdo6e*yoMYnt<gZ6-K-@-y7uqtA>jC&ojvXEBJ37 zWmf-Qo9ds{s{X6iBI~u3|I-ZXzhaE&|4$?T;^4oH_UVNAFS%dk4~YMgO^d_dY1sdz z{|U(d8~BfTO32^5uG;?s(*LpXiLVBW|7VfE4E)DDCFE}-^B?a&>iAzQepCOIC8GW( zB7YzF@1u2^kiWK4_0R5C`CHd6PX15Vu77^ywYFUFufX}I{qrN66J~~98^8aH_VvF+ zaIlBUPrlvnfBgw7CfX0{cLfE$5zc>P{~M3~mx$zFcl@LIXR}KFpF{rNA^)+Qis!S? z{!bUlzen;P(_*RrndYCZBJ%&d$o~RAvAH4t&6e`d_B6{sd)7_<8x9xae}Mj%g#6di zaXO*@ve9b)^GW{O>3S{se_Mb2&;R9?Z3X{}$o~iAzh*S)(+T-w`6lCk?K)(=miW)m z@BjJz|LRpm{wIn2FZUCh7rxW(Lx%*IwEf>R&Huz==bvByAo)8u|MWF}V)Fxk)x&ni zKi`nwFFt=hd2;-Jh4cTg(@*&$LoJs014Dimxbfe+y2$^loPXZ7pV&g+zxok7{#lJ# z|My+*b{Q3GX87cDr z2Irsg*3WDy;I9?$%aykO2ZsFY`J(&J^Vh5__}}FG-~8}1TMqckp0MMe?PXT~>_s>H zt>OIlEzUo!^cOY^_`7bfH2xd%`;*-8x2z`ocXIxY>@REt@Ymb&zrs+n{n(e?@Mm`r z{BMi;_kLlk0)K}ke&5u8ha3L-^#uPrg1`C~RssCkC+*aKV9Nh$(fNTA&hroFKkst> zh3kJ|qu@IYmiXD;hW+n#H~g(0_uqXgzYoZkce5cI0e|DmminI|zh7kjocriUDV%VS z+utknQ6heBAvi=hl+7W391a=C57>Rqf6#Ln;I@+g`oY(t{`9=?lP@g7R?YpwB12{y zlKa2S53rlhzdZi&63>5bE0zM7*l`N+#|s_*Dp^N8{=x1nkbg`2|N6&22>%PnzjTCO z_xLB}56JPKn8TUGAKQ-qXAgw=uRl^8|M~#^F9ZHdHzUWX66U|2y#D1m%Ky8X$N&DH z>5k!s{)3~0|BulBvf#hY(0^&E+W&k<{@*k7U;orFKJM+K-nSz5goy`&NBR5Wb-x48 zVC09Y&;IxO#YTQ4(UQzb|G+T+ZRGW@z)}9+ z*UW#&-yZURj{I5RFWcO#|2LBQXLq@o|4cUIFR2&)yODo+;IB92_itCvfAKa|&;N;) zn5Fs82ipAn^^frV&wG1#AI$Zi+)GJyPc5zVw{W`)&42wNi>tr4wCca(X|i5R{6n<) z`TV!$IN|>b^uGf5&u(Fs|B4ON@y~OV{|~kKRsZZuFzft)A3i*eD|4v47nvmbWo7DelZumb+>tFEY>VIwc4E^iw|55*Jko&JbLHM77 z{#OM54TkmK+^YKb9rgc@4gJgaKlvK@M}vQVyjlL6N&Wl8f5il{UQ6|#(dOsfg|R=|*b*_Z{{BPqg`Y|Cj!IkbfQUAM*r{j>-PVce^UPCW`Bw%1O@{u}P{0 zme^zeKX*Gj&&{(JZ+CWXa{hn$e9j5uWpBUteV%7#=XUqNe;YkdU(vr!u7BzJn%q}I zQ~f(B^!fjM{&PR){~7rwfPbr6E&p5Yll|MoztyiW^S=dA{r`gee}aFXCq@74b~E)a zvi~0BUo-8WdJ4!N-&H>TWjCAQSM}dm!`J_QMgG6Qf8AuY_~&nvXe{Et_PfI5|H)DF zzZ3b_%JLs}{zv^gB>%-5J2kL;SZ_6^8#5#rzlk z|3dzW;NRydAb;y_a{agFn3?}Z_Ww8X$H2eOQ$T(%@4eP0_226kt)}>o?EeqsUpvcx z*!u7Df1jE0U)6u@q!>{I`k!&a24#sww`v6zjk6zZmi_2L3DNk^KzFPv0+ghne_4HLCx9 z$iHsdKlK!lzkPSvzhkKWhxhLu|F)jT z!`6SFf0F;c{OG&ofuLzitl_|EJ6GUwJioUp4vvB7FVN_^&;m`yYh-1HgYu(SOq>GQVZ0{+}Jy z|6t^w4E}wd0{U+w{;m7XjDL~+FOK{J!GF`4Bu)eJ*IKfF+mQcrqWUjI{;DkhVe3Ej z&x+i?sDHbaiuwO)a1hY7&^`YlH2>dZ{bQ(^_}^2p{;?)r|AwIdQiy-+EVcOWA@T1R zivM#JwJ!>wjg)KM3N#TQUBfsWQK1X#RhmV*FQc#^Zk}mw)=eSZo@^ zf9rF4;@?q>e|u%a@xL_sUmxP%7pDQo{~j9uWd6%HgN>&7uX6k!$Mb&~Kinep%Z@bRB{=Tpb?{9o4PpLwgtq0+w*$jpY4{1A0xr&Z*jQAZ~6rV z|8SSTadJs)I`EghpoiZoUVfm2Jg?^UuiWK7Kfyo3<)8O# zNo*_NZ-2$TzB%&!zZCgxL;Q6caR1Bm{GYd2Y!>j>zo-`fsqN+ZXRF@-Y1Od)%hKT- z_$SWupYi+OuoYbXX~X-)YJk7vB{hEE4(zU2|6UHu?|bEc?C|lg$oXgYi){z|oiFR* zw^aE@8Rj49^3VFEUu*~9Z+t}$zpcn`oAU1+|E}cnS6|jYwj=OYb?D)D6#4%#cs2Y_ zFaB%1dqaV<+VtaE{zyTae#F0Y9|>sF4-5Y8G-y-& z!4|>arym9SiSzIO6zks==zl2qZ&mc4m`>u~kpGKA`v39Gv24;Q@aAr^s(bz)Z&{o>uRT@fw+!)Ls>mEh|r)# z@yNc*eI1MU``*uh9dTa&n;vrSd(Mt573aTP3{JZ0)bhXePx<^8r&O;0zU^xAzfVa2 z9>19XR$}}w3-ND1t9JfF;~Y8uEkp5tc}V_I>*kLCr!xKi_@6t;jsK<_-1o(6=dPDK zFYL)~oOkkg_1YHb&y^RcD);#`&PPwlofi)Dr{_iV`6=Gt-sy`ejFxo&UQ? z_55FN{!=qR9RI8c{;f;Y{99|w{MKDEzi(or>GwIQTDr zP0fEd@$VS&e?wINnTDS{!!q+R?&a`y5#uJQ2w_>^mVR|5lQWtD46DZx!pmnE&sH z{1xE8?7w6`1J=J*lK+;W^}pMr`rirpXMlg7r=a}%%l>UL{`1XX)5reB{C{WUUmg5A zivH`*k@?v@X2!oeqWa$f`M1pSAGZFtQvW3XQ9S>xkNu1J|1QYC2KcYPLM{KhsQ>-s z`EQ~4?^N_JzW=Qj`L_c9rN61w|Lz0i_;-l^<^t9KZpHd9=Ks4P|2Xg;zf#SA;#`^E zGL-+VQT^|Z{4>G7&l3;aeDnXd*@XWgGxbl^znK5;f&Amaf5(Sv{yV9EL;3%|sQ!0F z{;jk8hpqqAKPz(oV*bAu@=r+nSIqyK^W^xq4dwq`ivGp-KkSM8v%tUeyITG4sFV2} zvi{p$p!)xvV*MBM|GklaP4Hi#djE6c-!bI>?x_CvLH=#Pzt2;^`d?EnuYWj(@?X`z znE&sK{A+=KThYIDz8wGTUNht0JyHE9kiRC&f7tp@{o6(EU(EmaNB&Ci-|&dq_@5&F zZA0V#y^8+D_kZk%{M&;6nxE9x|2q#N@&B+K|JB!$_f^yJ-}j33U(Ek!Bmczo_^;@{ zqexK)|Em7Q{QqF&UkChmD*A6G{%u44+Z6qa`+pyV z{5ydEB(2i{JA!|or-1%j4wd7tG}UL!te<-+$IQo}d3&kNi7>|Hi-7)_)og zm-!t-{(n@g|6=}s6!K37|4oYilf=I>rJs9$DPQ5|9h%0!hZX%-dj5|_{#x)~GhZ$K z<4M^+d&Erq|D@<&%>R!;{wna_rRcx>e!~Bv8U9B?`**+pt-F@r|8umT+xwei1abNT#to6LWGxSI0+XT|sz z$3Mp*{}hP-jxE*r>qz|DhT{KG#rW^qmB)XB%Rg`6px9v${}u1(iGSYpb5#}wnga!(%rC%F9Q&K?vy0^+~%T|M#7p2@@COZ>Cf&BT9Q4d*}E<=_9= zL9wHOKlyqJRV&LG|@xWj6p&oummH$mM{1wM=|F+9tH+yjG zB;aQs>EUP3D#riYX85c6@%ulY>hd3W)8N=Cz@JFz;kQ-CzfLp!_2+W`XS@6}-X0R0 z5ByaNH1VtYUtpMjj>|uN;F7T$fWLd89)3rae__G-Gb3;H+GE}0^V2#1aZAQ-2L5E1 z9)6bZ^S@rkKid$0TN97}GhF^HZdx*S8}QeBp@-j6EUNLs`+Q1nc)}5|0lZq>HAXe2FL%59;c_@EcnTH{&yoe{&(o{zq=XyucqVQu*d%e zyZ`CaYbo9TGXBh3eRBUx;r~eVzk8Pdu%G`?|Mvei|2tNy`QNFsPyCDPKhHt`dw~C1 z#r&_BFR%YOWc|C9ZdX(O_k>*kdvQ)>=KEjDCc5|Y_gedm%FOq_q*GuHd_O=1zkhi$ z-4A`j? zXKwY}s6{&wO{>Axk7b1TmUH|&2t^dcjA)o&d{?h9U^ZCcGA?shk;{Q#x z_+RC%zKMU~{}S{MUs=X{o&wgt)OBS1Gj#r2(fHqgZMFJ$z}kIM|AhaG(Lda>UHA`M z|9t*Q{_`-xM$`CLH2yzV^uM5Q{EOqC%g{gEvV|pRoer4)_Vsf9vw8CIe;eJdCjY+` zOZ|U(9ku*_W}QCCf8qZM^beP8F`uV^{#$G1>mRMh%*=m_#{VVjs`yG4^YnoE-&j&Eo$qTC|8;b` zn(F`WA?yFs&rHg!TeNNKu77y#P0vCnV&esA3+{;<0}u0y$r^Ystm|624v z8~pn`@mI>X{?T;<8UGzK^*^-#Pjmaf<1^QP{6RPVz4o>Rx&0@)a{IS4{eJ(qLw_#+ zi7#{ew|RfT{a=Ir;g)T}f7tp@{W~Q8eF57?`R~QQxc5<-pLZbt;lQ67 ztoHd=VxT<#vk8CvroxQ>e}#^J!rzMg^}z4j&w%mYk|6p2xtaKn%zr2HACbi$HvTEU zL;Ul%5gSeQPnBQX|L}jveGuf2>sN)x`g|V*CsKyOIAW;P>rk zK>n&*3I75!@gJH0F62Kti$84qQ+~%#{;TqfrkKz>#y^E-s!w{LyM&z4N@OXub8^@e6 ze6rb7CCkD8>3F%9^&eJNl0FIUZ}`b(N$s$zwC*kb-&1n^Yx;VH%=0?VcdxsjI>>!y zeY5-b_51Sc@lX2a^Pf}mU@cm_NctBmy>u1$$LIfE^nYBI|FHQ_{o6(BpUi*mNB#!j zulYe523|;^4guMR0VC&!gtCZG1 z;{&StWc^Fr|LYO-zajW%_qm^o(s<36|1E8D{yT>JKOWM5oUeb0`(HhV{2Kv(w_^Oq zACURkGiK`F6CwGx89v25|Nmt-&&zn57%?St{(m|DJlkvSbUy?`=aDWP2nWqJGuboocq`1fQ;|Anf5$xEjw)xQ+{U0XB z68^3);=e1!?|<_qp8qhVKV1JY%RT=|E>`)ke@(70uYa?j&BXtbA^m&tFXq2bWBgBr z_^)|Vt^OxS{97Gn_@4>M|Hb%CGUI>GFn689Yppdm$$9Y^nd7d*MH(R_kH$SYep~rp+Bd8=+EhY%U=9Le@_2f_2M7; z3+Z3X|DQ+yn}Pq@r_}PFJtU8R)~janzdfY?LXCfHz$m5hF9CmNa{Mb4zx~c8O8gG| zok{*UpZ|&DpBFLyH;4F7Db~Ll690~&_{|#OL03-Dk1wA%Pr{;)j$Ifned5Yqp&&$r8* zhu^ZRyUyvg@dewl)#3V&#*5r_F0b7O`qS5cv~TY|-)leP{jG!e^&-5r7jDPKX3bmM ze?K_0ZkB}p$yxo@itaj>1N{}y@6CU0e&3B0^pDGWzBm7kcWuYkfc>G*ho=VmiSzm| zj(=W9|I@*LLeYO6@o&9uCjVay>Az6pe`@}IYWaWNetnYv;`rxH^j{7B+Z6q$h=2Bm z8UHU8iGSyl*-HN7pU&k?X&0$p6bl;y*RNPRYM@U0t8} z7xVvj(Epa;zfRG=P5iSr&E)?pA^o2*?6l1Kmv`N#*Y2}iy5B#}e+vES^(=3l%Ul1l zho2_h=PGsGA(?T0KJ=%r^Yi8jUdzf)O5(4T&O(+%$T6nSl+!5^OFjsIf){~r3^3j8~Y{yT_&+mQc`kp2a~H~;+r z`DX%u`Lk;EFaD@p|JYk*;{R1eelh?15c#(T{(43JX2Ne9;(tw%U(A0#LjGC6A8%Ll zU-p>n-+J4O|JN1y#rU5>{%wH2L6N_a@H>Y1-%#Wi9zf+Ol@%TSS{vCk7@_DuVFME#of7guvcNF>S-sS!m zApefQ->Ar+ApDLY{&yAmyDs71|FRJIcLM&DB7Z00x85`3|2;*1QUAM;e`nyY-bStd z*E}!Bzhj91eO3PVc>I5X{I$UEw5ip`CQF^54rxsA=iJ@ z((P(G|FuN%`WM0fHS(Vb{J#C<6QO+bpZYsV{2RLdBQpQP$bV86f7t6^D8F6g{Nnn@ zZ;=0F;BTdI8qj~u2lD-|S(lvur3*-2X^Q{FLdO579mcU5IA5QxXFiqb_n)`dxZ}9Y zdSmrT?*4o2GdsEcrIqe@>9x+z<1*`_o&0l5ukC{V^txy%Kkv+Iy!Ixe#=N}nI+{q3#pd5B)i^@#@dR=)nV8~vXG{(YVT`mcLe&VQTu7dznn z(ntP%{NEzKoy8wE|0%y!wEXV%Z{qtOzDNF3fxnIBX+Zy_@5%lh!e6$qF!|pvWd6tb z=l_ELN8~>Z_`~`>A+t{ z<20cE9^&67{0`l&Cjb2v<6rRqg8XLyzi&SS^4GsF=Rf<>O#DaY{~7t=D;orV*!ZXX z4)HJY-utDG{fqmb_aHyqvW(Si?tcHBx0_y@Z~kBQf$ZNR{_DF6Q~w7j#=qeI4fz{^ z-?yLq4ampeNcbJX@4b(r)#N`i|F6h@W)^?g_^14Kk@Gui^Yx$Kk^d~Mn@(0|2; za{RMJa{a5hkgO|e@;^{9{u6P|{}uA@2J1gvitAtYi!#4sX#FP@di}?p|0dq&>z{ui z|L(wVy-4a*K>rf15-~Ylf#Q%vZzjyu% zTOxD4eR@4$PvEcV?;g*4n!Gk&{dZoHv+`NjD!G34J1_*)eD6EDmBjv@Zf z6#2#ZFD1yI0RGkiYW_P3zm+oM|8qrtasJC<$iFx6mkw0puX%;|H^dKL9~J5+POty! zhy42hf14tIH{rKFHsgPxBEP8r{gHoP;IAuH^B;eO)PF<#U5fnnJN)zS0m#1}@Rtu# z<8SMbmR;Jnx^Al)%6d-{|EA)lf@r){fqKjMb2ODt$!_v@qaGx$G=cp|L7+E9m3y0 zx2ws2sp9&V;4ee|^MK#Cp8?~)?jt$>of-YeeTqp26bt`QuZ* z$nozG{zkf8P5u{GjDNvD0{Jfke&2oul-=$3l;y7`OA^NIg3AR{8N5by!>wD zHSy#BM)&w*J{HJK1^8Lzp{9FF9y#8$y|5aa+x}qunmk6K#?kigr?(xZrF8|ikhsT}+ z|JL_<{97-m`M1CO=kI@s8YVvfBhmkV!N1Q_K>rn=%JrXpn}@&e{DWl%-*eCXui^4< zK6};J@WtWy_g6jsZ8(`+{+=HGM&@gl;OAxJd!FL|kJJ2L0sUW*^@F09(vu=6**Zg&1=Ko7Zt^cE4{@d?gCAK8^k87I$IdCzp()d5fu>aN3e-ixrJO%V` z6aO~x?<;qj>c6Ug<{kg7hZq~i%ClUe=hX#pF95(`9Bu@ zUz_DWZ2hPHtz!4@&Hu-9|Ff5meF*-$bshh|DAzw<{P)sf8}i?N7q9>0(Eoh!-%aau z!2ECfUcUa_A^xksDNOwzs#yPfZsFtqnlAt83zv_50{*Li&@=u!s{Vg5lmEj1TIl~e z@bB{!(7&@l9{;WH^2EQU`XAYUrOSWr&MU?ifPeOrCjU<>*8g7(`=5aRug~%yw*FK9 ztZ4n0W+Jcq5nlhkDb0-2>FZzKhW}H!i`w~bJWWJn4>J@0;spc#66a?gG~dqa-`cMK z8MPy0iy;16yWKh+dH(ZK9{yhT*Z$2+{FmRu{ZGXBzX9UEYNnh2bocVDf3*#gzyHoA z@t-Wv_*bSl{t5q+T>j~eBV*m*zf9BmCwp1VKl{V5|Mk%Sjo{zsi3dVH|FwU~;~)Dz z55K1IPt||@e4hW4UH&a9R*L-y{_B6xl>e&!nVI8Xk^k$U|C_S>haLZ@e~08httYz9 z|5Ejzyp{W}aQUabJu0>`tbf!lrf2@c@_ql0?+tM~Y(wi`b@%f6Uxof#z<&>|(*g6p z`ENP@Et3B&-xlWhXQ|Nj-#z{p{2L*|5y~+P7Uz{-qZS@Q*nE{JVB0KmTP2 z`ac-1f2kUxHvjJ=*S}cLghWNi%P&Iz*P1(O=i2nyg{@PV}{%?l- zhXa32nHql^;b)(lng9Q&$j?S`{>_oU9{6j2R?GjEw`Bj8A^x8f`5WHi@&5;||IFwQ z*S~D%j(?%Y|BdD2e`|^v|H~-y*M7+Pr=kBNz<=8>YX0lrmi^oP`u+3gUz*0hpB4Gp zN1T5;@*kOw|E1LOzp7K_cMS3WqR3yq7(f538u^a`{>0L1{H=ta^*7_cN0DEQ|1*&P zXy9-7O)dV}JFg}j!n zx`@Hs#k~87d*6Q;hyG#E@BO{kTF{?fawB{d@e4b9nsELjDHeZ&&0mUqOz4%Mkyciu|ox@%isI$bUTW$A_u;ZzKG+A^yJ< z`71W&<9`kE{|ERx6!}{w%ky8y5dYsH`BPTz`p2f`u76{pKV65sy63g=O>@^j3;Kt_ z^S!#~wF&6YRsU@0&sG2Kfd2IBrp|KfpV!)(=dOQA-k-nzx$D1e_woGS2>suh{$u|6 zFZ?F`5uR1IB;LVluz=qn!VRivP&`J0gE;7Ju0Ir~Ir)`42jO{aAWjX{&VSIbNG; zT0gcdeE)gJ`|fdp*Rl(sAD%Df`5(Ife+}r*Y-iA_nRT8v-X=ehk}3!4b^6X)}P z@%>*rqyPVb{{+obzSVs7zq+3s|ISkK{J)KES5y68Rx$qt|E|b?7x4S`Ga!Fif0^H2 zTITo3DHi@(hWz&cf7$nBoC@f_=UI9E%OU)Abi11T4^xbP z!M_Lc-wXV{{S3&T93aQPGu6!JzmfTONB;Y=_`}9OD?(vV9|LuwV_XB_9 z-tO@htylT#e`=uY-y-}@f#QF;(D6_B6Ug5N{J#AR82>G$GQUIk>HDec_$M;|UdaDI z7Ju0Ir~G!&^1Ji@?l%7U*WSqgAn=#-^FOJteDU8rNcPW`mGi%2J~^(^RR4#Ej(@_x zFY-SG{J#AR82@F1WqzCR)Av(X{HyYd&%d@s{u5yRuVOj1_0QTBWq!7rnd3jUj_;lQ z$BsCk|BLwF2l*e)@*g(;seh};{a23V>%aRW|B2wgQ_+71^*>O~f1eah`5#mCU+vYu z{gD3=@ZYeHTKspC{C9}|ihap;HSw1#*1wL`x&PV7e-ij_98UI=i_2I4>qpA@ZyEAm z64iel@;?gxeVzjH*RCXg{$UL>6aT9I>&J8d2O|H;;NMwH?fl;^;@>vpf3c|k4?zCM zviygw|I|M#a{rwha{mV-|0&?Vsa!4p6D!I2?-=smPtm{iAfNvpg!~Tp@1%7)VE(r+ zF7w-K%k!Vc{mA>Oss4{ptpD~#-2b7-Z-f7i{%ZN(N&K@?Gxe{3RR4z||Ks4_=P96n zYYExEV<`Vs{l{b6|KZ4gD){eG%>SB|Wq!+${{d0`AAsr$IA7OZw4Dp^>1Kk|L*#i`23?D`JV*;Rr{;)mkyERpDicXzb3j} zP5jF%*8djo{O6;Pe-8MsUS5sgip%`Aq5Ln6>i=lue+vBjJOzyZ7UJJF^!cx<|C$t^ z{~Uw-r-OfMklOg)M*KU5{11xi|48JATeb-QVe3EjZ;|}R!pDE>NNU%HB%|7?(4{|d!FIJAFq{>!n*50`8*>j1U-SG}anZxjFBbi11Tub^1}d%XNV z9{J~j|C$xl_-*3fGUR{psQ&+h{Lg}apQnKJzl->1!_CCMs{f8se*WhP$UhJKvlZ3+ z_YnWKA^%H6_1}Q}?OFcA)_>~XA^BgZ`lsq&%>Pe9{zmZMs_4IdRk{8-hWrmv^e^WB zCnEoI;6FKAE&dya%KR3||C&0oT}}0WMaB9ruKzv-`OgIZr6b9H2CaX@KO1bO{w*2R zzm5FQgMXi=fc!OOvVVv8FI4`k`WM%~pNjlvf&Vr||5c-8erpXg$NxhW{fq10=OF*t zz+bnLTKuY1msaE#mr>*wi^lue-ZFE%~j)X9xMB2OPHyD<%;~G{-1;V7X!aFPmRBNjjzmg)qsQ(ut|9^qM{9Hx;)5!UchT?x^MSijVcQW$7khT63cKw&G|JX&o z{v)n`I}Q0?1b%j)n*XMyt6@muBP~pE5^UzzZ&`90)F3q z2INm}D#yP~_zUGfGXGV`|8^FC*!ZXXR+00I`Oh`T-wFKoVQTT;eujMf=MetN!^w6v z#s4bd<3IDt)=^{KeBHq1e|qfb*edY-H;uZ!|M|5%_1~8eZihXTpO@Rq|Bu=o=hr_A z|JS1bcfh~T6Mw;c$3L~3ll)&nu7AG$?qmPuZT$Xk^IiTec3v$u8vJ+t;okov>i6HV z*VX*9GQ<9p=>Od;|6%JN^=}oq|Jp~m|LeK`n^udB1^?Ecdi*=8{+BAa|4in!Jj(fR zbor;x8xtD`{3%WK&w4{K{+BkxpL96?O)mey<}tAez+a^){~bksdl@tQRZnyN7MH*J zrZKTf;BOzGC;qKB75y)3hQIv<&VMuKzkf_@9pG=)mH(>z!wSw1-|`4?-jAREeT&OK z`N`+iLu5IWztR|7|Y+w8>** zQ-D9IiQiV_w+-=&_`luduRm^VYy;r$EY;+{Q_=r$!~XAZ`De}>8`}u@dvy6%$0)2O@P1VZ%zK+QS)yXowb&ZzgCxj|KSy}sleZ&iQiV_XCut|kDuti z-n6zgV$*@YYOp5%?<)E?%+K!P@n1SFHUs!unR`FysK>vyB0pQc(EiE&FRyd?)Ayf# z4~~CRbe)PXT;yB-u;-EWFLM0bR9~3&uT{gZe`V%>;{3OZkpBue|D*9zwe#N`i>&_` zI{zac`uq>#{~qLjAN>0~1@vFFh0JfQXlDIO)xS9Z?_T7;68u-3PvSHnfBhU1|Azdp z64n0=$p1l>|FG*{)ITe7|Kj||`;q@D@L$=a=D+b*^7+@2hT>n*zxe#?KIH!p{98w; z@h5MW!Y z`R9ZGmW$Q=caYEj9Yg-dM)m(F@_(A;KWzP{{w$BCa{pTd=f7#|Hb_OY2?2i z{I^|7_LJ+%xBeAxl=<0EdHgGs|J9@Ve+KzK2md}#0r?YK$?PW#PZIyOA^+nP{fqM- z+mU}E_%AzFjlb(Tx&GP2zeBgHss4{qtp8&E{{r&g1pYfNSL3faOXhbB`5zzE|BJ}q z1^#`W0@nY!t>ya1RyI@rRsDwnKIIsP5uzfk$F z>R-(NUq}91!GH5rBu)eJHU|EnzjVe3EjZx^|LG5>!P`ELXN)mN+e z?;`#kL;fd*_D`<=eFOQw2LBDTP6v(u3+4LntS_(sRvb^>S55W5Lb3jf`TyI^E*zZEybuj*fX{`D5}f1AZ0w*FCmR^l%%yppY^Z)LI_^-cOZT^#-Df_n##s9jB@h{fD-$no3;6HJJ8h__Sa{fESf8~D) zQ~y?1tbbzu`#$owg8$NM$$kdRf2&F6XG@#O|4C8(e}Meofq$Q;fc)*-lK5ZU48N*> zG5`G#`Tqz0%jT>3ucY&TL;UMS_5U97f1l+)Z2hPHEkpdO{>A(^h5UDc|MKh9{M*F8 zwT7AapRDL#tbc!m{6B#I6s^-i^FJZyKO_82Cy@75)BJZ0#riMizn>ug-Qd4n(SHwF z|8WREe;cvU#9tNF|EI|RBl!1u3h2L%-2aS?GZX)+{>A$DXUKmK_>W&t;xr(C*EVwe zTZZ_jMD_nM^8b|OKWzP{{%u3?AKpK?{^N7x{~7qL6V?1D-<9WoHu2w0x2q}t$0^o7 zG5`G(kALoi__uFRHe+@ADKe|9ke4^WQeauj*gSf4@Nf z`@w(ZjcWcYE|%lpnkTP+;lRg#(-i+3M)kiC`Fpbbhpm6qKPz(oV*a}b`P;yM)lF*t zyNQ1`!A$;d6xu(_L|)BQe*N>^F8}Gx<6<-6`q$E!p6g%PdwJsDmk@4;ZRq+}vHtTV z`u`Q;KY5ax|JD!X{C7zF*PKkYt117-D~^9+{{J=dKLGJ>wUGVfp7Ndl*t8v~|Ayj! zW5xJq7LWgLT>fc2<6^TQ{@XOgzpWVmYy~sde~bA47XAMQ@$ZY%fc_Kv$^IQf{#D~& z9RGA9|AP?!?eD6^e|@K%|7=Y&^?#G_@t?W=y|J3d|939`+}iQ68i@b05>560eZ~4; z@c4JfzpCk+|3}W>Ha@l;@H?9LZAE^zVxjZj{rtD~HJ88X_EDM7f3~ig5Zej(o5yRq z|HlW4{tfZ>yutnd?E0ToHzBqw@V76fC;n|!{*}!57x#bq#pSOnUo*Bl@Hh0+!_Pic z^UvaD_{IIddR+dkYS)bI3H%+J_-#dg+YrC-|EtS?P~)1h1n^h%*W~{rMgOZ5+P}O0 zQPIlp|5u0WKS%V3^`BaI{11ElTfKoi|FNd!;ny_(Uv2GP4y1bNj`RB;H^*H5#im_n04 ze`_r>>tB)i`yu~dS^Qz+pYl7zKN{n|^_hQi{{H~v{~P#AZ4##e{r7w<$G=1TmtREA ztJTE6X6X1Q{H4gBF2cV349MU73E{6a6aSI<2O@tgi$84qQ+}(+`NjA*2>DBZzoXn8 zmubG{tAACW%Koj1vj3W|NM31*|Fsn3U+^!E{EGplUpT3{&D!i{Z zbVp?V!N}h)i$84qQ+|i|_ks1Xe=+}A0{Qy`e+!LMzT^4gKXo-Z{-^%GE=>GaD#pLy zUlRET06(Mq8IZr~Kso;HbAneXH>Yw@vZ>%8Pc&^m{G4{EW=H6&xC7*1r^m~8rwT;j}37%cS@2}>y&VONlpuh5NcR#!~1^wCUW!2yCdz`O-it~Smq5ns~e}|&~+V|!9ZyWNzX-NMEwSx!nU&=jt zZR)vnT!07a|M|2ZCe}s0_cadvx%^nrpN{Y<}P_D`Jq7w7*DNB@t4|BCn3>Yww0?4KDr{@pCB|4!F`8~5+E zsdswu|86h-p+Bd8=+EgN`g8ivY(Iy8zJ1T9@XxpJdG}iOUO4~a{MQla|1t32sp@}U zGXFQ^fAg^ZyIlWeFSv2;wW%+9@&9En{-Hmof9TKYANq6p&ul-3f4+U6f4+UsyVtTs z;rxs9KUYBi4*0M9KrR2uTdG}hjxcj=^^S%Ad z9{bb3$NBg#=Km|B|0lqI)rV^NUqe3svd_%(`M;*)zv*H9m%IMUUvxRWHZ`Ib|I7E{ zANq6phyI-Yp+Bep%=UBm=iB#u3jcijo_DWhD}?he=Krgp|0ltJ#}Kvk|4Q=tmqph< zX&`FyUmezeh3mhb`}f+^>b>}1qZj|spVL3|=kyQ#IsIq0pTj@jzRy43zUSR**|>22 z#r%I1`hN=iH!0?S-2w9a&oShGMp*wlfbNYw=oc=T0&*7hM-{+ri-}COZY^!ko#r%IP`hN!eTOX;7|7GO!U&oOD zt-|`Rb^TZU;?DoPHnmGH{&(%gKlJDH5B)j)Lw`>HneFHB&$sXM&$sV+_gc1FIR9e) zzdHJV7W_9W`tO)6*MG~<`v1(3{?D#+{WtLZ_uBYDx&2$|ewe#>9=v&V0{V0Lx1m3m z|0MM1@}J6V-|wFt>~7zCU2pyuhyL{TJ?~y?@qX|5-hR?)SDeoO$D#jr@ZYWIzm?{{ zA^%&4^nXyJ>%W8h_uAB%x&5=Va{G@%e=h$P^yl)Qfc{+mlbP-N{X2a7o=?wzif`ZZ z?zQafkoo@+KhJmq`hO1mSEtnKzeCP{u?&6wIV+_9v)Ww$6)(G-UdtZL?LVIG&yoKY z^yl)Qfc{+mZRpSC-^py>??1)2PyMrpa_4`X_j}LJm;Yk^zZUv`9{eX2{U<+@*Z&+t z{Hb{)p+Bd8=+EgN`g8ivY(Iy8zJ1T9m;daAUi|ZZ@A>)s zi~0XV^#20*?@{#MO3weW)-!YdLrqBk-uNfZ|C=*7bNxaL94`UqKeTy+i{QWJV>N#J_~FuZOO7G_ZKL{M2Kk3%`44;k3-!+o@vHh5^Z!Z6 z{}TAOmsDH-Ya-`AIfmAMw^Q^l*1sns|I5J7K2eMR$_4WHXHPa$|F&1;7w3PTj`eRS z#DCqliu{Mj_0KWHzm8)46YJkq=>HY)U#sZ9)OT@*lSTRTBSJ z(fW6<|Eig_hC5!ZkNh3rzg5wHijMz={O_pfKVHfCry&1Q;J>_EE&uBm%Jt78{PlFZ znm+$oH+23J{~IFztKdKJsTzOXX(a!rn92X0qWa$m`IiR&K2IlU2{D-ao)W1XW-;JWI|Mpq_6aND5e_%+Ty|Er(K>;E+59}fQG-;p>C$Y1`Y z9RC*K@1Wb&6#wgmum73*zX<=;$p1F@_jwA)-$eM?hI0P<)M(<5?0*LGmxF(wr-1x5 zhs*WfGQ=O*|CY$#3I02oTKuP||Fh)tUpr`B(d7T@sQEt~`A1~=4_p7Ke~09Mq2fQX z|Cz}D4*2(Z3K;+PBDwxKhT=cGe|P?qn9t`wTOt4Q;NSjUE&gi>zfJfne<0h{6#tVI z>%a9GAOB|||GVJ7Vj&u4u~tZx!>u?OI;{w?+Pu;J=a9>7e|Z$nnnze~NBb6MvOr z{TKdsK>iQFzt2-Ze%q4y9m3BygN-Ks$o_Xk{*}PL&r?AD6p4Sfi5&k3&VSRyAKt$^ z{>2CL_}>ZnKLr0Nnx_HzTh1W)Px!08C`|r$N6r83k$>eZ|6%Jt^=})B|H%Gpk^dv` z@ADMUzdeoQKk;9v_*eB`dL57dosmBd{+oUzaT<`HeJOwbX%qe~x?N5AKP7bick@3v zpO62$B7X|}chNiz$lp0#_HS8o{jlrR{{S%PXYOzxpMup34fvD zKeGSbk^f`x@ADLpzj2<-?-=5b?0*;JUp32r*!oZXGei8U{u{b^{o51yKLP*EG*1Ki z@7a>%|5Q2uo#hI%{{OvV{?{cr{~pLc3jA9?kvbKSzq?xIXN13*ZdX(NTVJvM3;zk^ z{}lZDJO$)$oGJ5Lj{NyI-wZaI_#^w@8~I0rf1js-{1uI){t^EO&VSRyAKCvt$p0Dm z?^ewJ?yY72Y*RV^s~3^H(!~Em)coHI`B%&GAGZEe|MtJd|9;5-Ir#T^3K;(_XUXwz z6aR&Ze^vj^HN5`si~M82f6Yo{oC?U_{^WAf`92om?=DdN-$1ecC%56Be;G?13S7O0M(tpE`FP3w3IMwp`Prj#2_4Q;r>?=k~^T^!K%I>wY|B?6iI4Dj(sWZj- zTao{yf8;+s6u;FkPyYADe^sIR-Sux#{}0CaAD5N?VaI=(|BS@HPmHGcSIvJh|2-V} z#{+*49jEw?=ez!)r@wsu7n>&gulc1gt8y|JW9?e;@R~gTx2gZ0!sP$PA@kq!FZdgfzY_Qv z-OqsW-*z5}|1HhLe`NmSkbhzpf7tk^{0{X`6F^h`N9I2s`PT;iT1EfKD`o!{@!v|f ztBHS;sPTUS@~;E@zWods|M4c7-y!@|zpmrI$o&67{&lnX!^S`5w~L%#od13z@=pT( z#IK}I2lU^*vwZx=wvy{#*>7aKn&RJ5jDNv@GV-qn{J#AR$lrN^9RD`qFI4!Mg^R=afAie+kK`rtI_OYVQUYJo6@2|;XF30U@!wm=YW%#k-u{2YesBIK{GW>c zr+|N-C;oc*=D&3p$@y>1%){Tu{yRo;|EIb9V{cxpk?|j&!TB4x|L6LZT%8{Of70XMQT4yNVgF~M|F6Nn z&r`tsuOP=imZ9|zRsZZ1{`uBf-2dwRORfd~O`7~$yDH}Y8fN^Le!}DbZ1n#P_^+pV z8qj|kJ^mw~|HnrbCjWaB^S@?0&VP=}zuFi5OKt%F$zL?(zpDRnhW($5{=WtPK2HJt zmkySX|Jd|A@vo`=tNQPp#{Hk?@^7)mfRdZRe@l-Z|JH7K`1$)v8+&}A{kzA%)iwP5 z$MeyDH~4QkR_*-HL`wer!y^7GRw_*X|Eik*v$_8!m;dR@2bA0n{%e2LG5yvo`;_%KL5A< z;pm*7KlbwU(A{x<|F4R7IsZlI|9kM?N%NGyLcaB%HA`1g4V=)dJ+`S_3RnJ4}=<-e+bk^h&v{0ko( zSn>e)FaJZ2e@D^3J<+iL%h3Oi;6Fw4G@$?bFXZ}f6aP)|!sP$&iuqr01h0S1F8{oW z(vnBPf5V@8{9B~{@wYL5vyNf^m!tomz`xH^K>rPkWdCe0Gx@LTKYkSV|6lIEuC(My z@NfU6$G@ZMf07yh%)9^T73lwG@Nca`@-(3Ty8p@b-zNU6S0&rkRR8}_%>S-~x&JG< z|CZ8{cJSY+$-hPFU;e~*pJ7in?EfnC{|or{c?#&i_HKFopC!!XzpDSz-7{wx31l>e&!rxe=1d;Y8a4d=fG{r7B(F5_Z>AXkg8wGu z-vs!5`x%hG{aQKx9m0>|`ESL-esI=TL{ zS#tfW__Hwazqw-k3;tV>e^cQ1?Poy#%IoC#w+Vlt;y*I~&B(u57Ju0Ir~Fot^Nad- zEAnp+{5Fl#fd1>ZlkflN5PoMonOAD6f72A>U+~|K{L_Hnx1Ry|%Wjb4-`Ymb|3bxo zWd7Tbe~T>su<=j%S&{RL`gaHNPY3>v8RR%Mp#RFFmZNzmslPQ~Xa?jDNv@H}Y=<{J#AR$j@$)kAED(Unu{o{9^s@I^_Qy)_;8KGy(Y= z?;-iWkD2^eUH=jO??V2WS^mT3KlN`Ht$+9YujJ8V-1AKCMgBj)e_}NVB-_=*Umd#s5&!oi|DWLB z=P4k6&AoE|Tl>oVd^6Z+;*adV4f$t*f1js-{PA04|2FZD;QTjD{E_`1GB{HQ;L=9+ zSC;><^^f|upU89nCr$j3{ojZFx5@G!mY@2!{w@9=K>okMe;uvU0pq`$K~ir%dCIwfK|B6^*`eH|3T!h0sq$4WIqG)H{K%GKZp45rrXsN|1+Z2|3{FY4TR6X zsHcGZP4^N0{mj(=$o?Ni{%yg(&r?ADid$uVYdbUik^Mh}{IM+mVe23DZ~a^RKaBj_ zW%&=wPyMrhi~q-vzXbgE*kqkHVEi{cB+q}W{pI*?s33J!Q~ir6)_<}7}Np!mOEsAoA|HUhHO_8|CUkf|C7kS82I;j3drAcKdFBQ$o~0eu+hXH+5c0>zXSO9 zc?!s1cbm-5wl~8c+5h9n-!IF5*!oBPJ0$;6JpZj&{6B&GJ7)P0%TN6~B>xM=AKCxY z$lo9QSFBFzRKWOm+T{3mNd8x@LAI;Oe~DuK7xVvTkbfue-*E3rIj_IUcl}f4?J~bb z^1rsGF#KCZt^dy<{{Zms^Aym3;sKf8nQf;2MfU$Z^6w1(eVzjHcM$&$@n5L?kL>?h z_1D{{JHK?*jfywR)949mu~c`1g4V$e*}Vj(?l@FBE@d|1Tl`;4J@P>mT*+ko+$ce`NnJBmZt${=@Q9 z|JJ|7|EtKqIQVZGr&j;0hvfKoNd8;n$#yl>zkZ7KUwr=i8uITB{>!!_`x!9*D_RLZ z@gIMktgC6_-#Tjje-rta0RKKu0r}gg|AWlb|H%H|LjFC#zt2-Z{v`2l?P!KSvj5kS ze@K@9u=S7nxBe~u-$4F7v;2qUr~X-y`>$A!-~aAype<$@)L>AK!s&R}=p%#riM&zlZ!o!N1Q_K>q4S zi2p-m|9mspXyT9T|9#|7r1PJ83d+Ao_Rn@Q!ynoIJIG&_R)94pCJFf;NRyd zAb-QxvVVv8FI4_V_Wu#`FO%gzZ2hDD9Yg1TM)sdV{{6E2hvldK?SG5^PmzCF@LyU< z>Qun^PdzW^KRZm$|2Dc^P2>MS#riMS|35?i{lR}#o7(tS{*9dfjC}t~<4)v#)x=*D zwf-+e{$b$X=P987mKTWs!)5=4s(+FFcOm});NRydAb;W|ncpV<3&kJV|L4fRT$cZ^ z^^f|uN&Xj#KeGP?$Ui&Fe^`F%-zswdr33l(Utb{qaPVI?k<_Vx@t-2~&nEd_N4Kk~ z{*@}$e=-0668Y=W^?zqI{;sdc=fC9pf4b;)HSuq&SpS9puaUnT{QEow^xsMAU%i?7 zAKCvm$bTUC_jwA)-~F;&|5?88e<>FKi;#armjAHzkNRi-7XM!%|3O*)!}3%AHp%}& zjen8z|6Al=9{iWDtycfyF;f4Ikn_KtZdX(M4^piE;{JDcEh(;ld=&imbh-Rt{r5~+ zK{{{LxmxBgl>fs+*MIl=H*x&ajs6b?{^nXW|D7eWf1A|5CVE_@$^Ukt`Q7WE#rXFF z@~;5#?~Bub^*{9rssBfs@vj>H!v9ame+c;Zc?!ti(INBO`M&?CSp0v7{3~Yp51aqg zzfJ02q4Gbh|5W87wk+&S{MEznoO24cY$Ei-zbh}=Dbw$@W1&A?V!M`h>w?$D*IvZn za$%OfZalr6)OCks{?3B_VbJIOz1Jq7KmEF_?Xb-Ayw-;PLFwn;?e=@^9nhbC-O97v z*Y#R^U3dF6#~qs4j@Kr6e+m3edVd=K;;#e$&i?VP{}u87J^DX1EB?d!r}5AJE%E;| z@{ff0?^s8z{&)N+uYcL3{#C3?wyP=s2P=;M;{2~)kpD37pWKD)Cl8){*MHRgD35=P zeE(C+u4KEK__vQb{{4>pD}jHXr-1xruaWwHl$r4_tp9I6{+3OG`cU?=`#GQ2vd_MS z`WN%nt$4a0-h;$0ZoTx{&7i*q`n~#B`?kA12l{i>zZCQ@lYTEr{af|(^mby*t6No< zx^ZGde|kHhWzze{=@Q9|2Cf|8kT#{#zCNw_Q!@binxc@f~fZ z{x!yZul$c4KL3BC|0BRZ+f9wXlhl9f1ew2;Zda549YT+PWtms*dW?VnMF}4Nj{^T? z*QoK+H{CYm|I9dj<$wNna#Wn99}a(XL7RT8vYPui725Q};SV+jUH~4m_+x5CoTVR0 z{&1kpJU*z6eFDE*tGka=p-n$N=8yOqah850_#+8z`VsrEHueOx@p10Mf;Rmq)Q>Oz z7eoI?Lj3#UlA`9YgVdR-C@_ zKmXg_@S|AzIJfKQBQnR2UVAh2r{{$o^WE?N@!Hfz@O;>$H_x+0D7uRRU=v*SE@lN;wL=ugL|7q?zsta4H+HUxUh&vw_5 zyw-;P>^QI4#Eo+Y`Uk`Fy}X#p^J1}+-RFD#ja%}(fd1_K@;LqxI_rOW@h?9A9f1Ci zhWPJ1ZKSl0@BL}M`rrBoIsQ3O_Mh0D%qukc-%)Y?BjSHB@{fV|cQnPnV<`TQi+hHG zwaHJ1vh>5@kA={tAF2OIHvNe2^=WKAwCoG_ zF%{bM<68bmL7RTWzjPl7XwwfH{_ZqrQ~bde!QZDJ1^V&D{}Sl`7>Ivgobvt17yqSi z%JUza#J>-xkK@1kHD3RRApcm1|MDcs(}4Vx&pKAl|9ZMzP5cdU`pWuYmY(r*X=|DPR86sIy7@$FC)Mr78Z8kJDHF z=YM|7ClS{p6d=$6xvv`TS#~od0!nyPEiSQXK#5ujch{8RTCb{5Mcf z0r}~>ZapdA|G9&1R}=q6tI}8g=YJQf{>AtDTygyWyie+%i2r5Le*?t7FHQscZ+=T2 z|Jg}${QInE@~;~IR>d0bJbxJSuL1F2F<&kJDW5~?pG~)`iGSme@gHaI`7b>u^88P_ z>%V8V4=Q~Hv?thxSek?;S`^_*ON_6CLh{^Nq> z|KE!F4}aGe^BWpOyb%=RY+69Ygb<@cGX&nP*Sp_dh5{{&A51oitB*kmeiz zeX)F;nfiBk-1o}=*a1%;oPI*nsXYHjxcp~T3@&*a^1q4c$$v*N|Jla>()|Buf!g>F zf7ciJFFyYtj`9B=$p7*^)yBW}m^}VlWc*L1$ma^0#=o6I&wt(gZ=T7oe_0Xv$3y-% zUZ=)Slg=`f|Mx&bhxvi0XY$`ZgXjN9p8t)5OWue4Z;t87e=Cuv{`Ioc_9p+*{9kLK zTK>b|nazLKf5SZPe--Y(YjDZO;J>;=kAFwi|J1_z_u{|n4nF>ma{0#&TB2k@dj6}4 z-`ZO-{x>zl-}DaWAMNs2Z@EOtBH(BJH2GKM-`os;=N&x$S9AH>Z(gFL8~7{u=Rc8; zf5`XW^-}J9-S!q{_?>$={}`A5i@`%megghhUH(=1tIhDYJjnUSy8H`khm`yZ{H6W% z#6Kh7f8`V1ONYIs8UBuUIe&%A|7`P+l0Shzp^4vC&7b{~9j;>NhW0(jWNC2Iz@@Ta|y78UCt8oPQkWA2GCK5b)P& z;%E83|D+fHti}v~`*)mwyvx7knL|s40Dt*FP5u@6?QPBQH+OOV37r4ep(RTJf4wGt zM!x@~H{HJe?alC~MsWT$IsbuWCBuNfT@$~p$ZzjZXnyzlSF!%Fvdf=7kLd(h|M0C- za6$Rj|0+7=^$&-vfA~E2@%l&UdE9>-`6s~oM@rNBhiz#66CmE^`0fk8uAJk$+9_Uv<5n^)H)z{_B&XDgN(M^xyFuKmM&m{*%Ced@nWr zM1MK|?RcK!e@*$w3u8jYtS$zF}J>;(h z|8=$Ga|-_EhV{=H%<#7XP?#Ujf9rL;{!d2!Q^3ESP^*7ErLup^kpEp3{fqfe74lC6 z|4o|4Kg*E+2NeA$=5zm3klzOXor?Zzn0)^moA|drA$g@~{M#+6|Mii7ZSdcv$-iyL z|ASHeZ-D%#f`6YUUR?6kzw(&upRHo1{;B#G^WP1Te;x2|-Jn+gXbpBonc;sps{gf- z|FkUsVUK^Pe~08heSh3h*w-7nBeMUEk$+wAUwxw<|Lklt{vT2F-*zpp{~ICy9Pppo zTaCZ8gyjDzGJn%PWV@Q`|L%(QU*x}q{FA_c&+dBW|CS;DPet`V75PsG|2|JVBlFe& z7UJI~{(XsEEdDn|{`J!SHRZo!$p6z({cnQ&XJq*gTmPwltH}L3JM-he&5?gH_;0z1 z)Tw~+?~Ctq{PZNzj+Km5~;^HL({o)<}3;)xRe;)YvdE#5mSO2T}$^I?d48N-X zhM9c*w;K7Ufd5)e{v9}(KG!;;kfbU8Uyh3{2KvS4e;V>PX88|W|EYgg8--!=ox+{oll=_JPqNQ8fNEzXtg?g7|OK75|3n-)oBTFRp*w2Kmnc|0z07aU=Q0 zzq$c(d|PDwyQzcZm8S7;uh8-DW}f)`YkTD182p#rLiRHtKMh>l(DCoGjsg&rlNl_|Je!o&jVHD9{>Pu?^WR;N ze=7K|*X93QnV*+YY&7w|9o7G?$lnD1eV+Ip=Ntd4OJ)By@sHsAH%ddc z6#TdA^1qrH|D93&*CPJ~S^mS;f9l^Va{nU#_dx#5z<>NUwfaZn+cK2@?81nzVqJOdevk&rL0{&~?P~%Symg~Pw{FlB-wyUZB z@1t1%J6GWT_ecKe;NRBe-_ZQ;gQ)%wK>ka?zt0no=zR6xT3q(ePB&BkRsDDW!Trxh z{%Y`FRj2s*pU8av%Xwz_KaA>sKjgnG%YWGVPyIV2|LNPK>+=s)|5c3N|MEcOp8@_W z?;v%G?|8oWr+k(n{~sy(7wbQD$lnb9n+K@Hf9Vo({@Y~zzw9mYzG|xf`zqFd;s0Rd z-xB<{9i!*`SI3b5R8;?mAphmy-{&b{{C80QhU$NK|L*r+Rb0XA|Dnjg75J|xlkfZL z<#pKnXXl%#|FB#Y>c>0(N#y@Q$p7Cg|6%Jt^=}oqfBV1O|KZ3#6a3qn{M%#9_=m&Q zP(Pl3vHo)y@?Qb|9a^XP*7L=G{SdkSJH&syvoQ64ztHucod0kn@?Q!3zWofy-$nSX zGtBsp%wLcES7q^s&40?zikx2@{~m?>R|9_sjnjbsD`(5+|Ja1zey1?;zrSMq3;tt} z{~F-;?Poy#>N=U9%{3GMk@=5C{$v(^*!ZXX4)M?5Mr<_Ae^vR#_e%5Fv{v-3Bg#0&W@rR9n%I^^W{B6WWQ~gurZ}sB; z6y(1J_-j8RaT?Hn%UW{$Tf~29ifmUC|AC?7-@X5R&2N1DV=b5e$)2T4hQs|Y8%p)u z|CG(n6aN?q@^3p8`u>+LfBoW||1_6>)auKWi~#-)RsNM^|F$B(9iBf_B*poa7iB-W z{PCOI_0DOxZe3Cf{4LWo`L9#-zjLAeyX!w9|4+sIzZLS|m!|>qzq(TP?~weLgB<=9 z%9`)5MTbKEXI?q+EPtO*clozCcvi_?;6E{4kAGXyzrBlL|2F!+Ez5t{@sIkqi`GAn z|91X9&vp5yfA{w(dxQU)-PHVByUFp-4phs3yKHpM^#>8~5r6Tmf1iQ=ZwLQvbe!g| zmv8-}Y9ir3Q|7PxxG>}YL7~Tg;=j@5UkUv03;x;eYW~?d%SqmBMgMFm!~V}i|960Y zpQnKSJBfdr`1ggaruwhyzw~>a|7W@UUv>X|$^qcNeRp^LFYNcfbQAyVAUXbh{JnJ8 zrv1-D|958j4_p7Kf2(NyyYt_kqxk)QmK&VO+Z%T{zT{o-U-hbD{u7_}A&UN&Hk1G2 z^N+L9e=GPe|Af?O&XuqJC)bwizeD`D)9q@?|ARxY`Q$YW9>&X7?EA#O8vHzxXx&J1Y|Ji>3DM^9SWD|JGG``1{y@;&Sf)QkVa%i%%%|5&XAl^6#knA8y$HMd%-H z*&_Uht^d?ND{}ueS8@N%F8`UIolx=%`0rfOJ^wrG@t>E!UTYnmC;q)BlGYw!#=p4# z|7GYOZrQ*pKPPpX?_a+8f7c|r{##>Y{uJG=ru;utvHmBo=KlZd^3U1t#F8HHU-q`9 z@n6wD2?y=}^w$4`|0~e{{ovo{DWLz>^<@8!q5N0%FOL7ObosA8{lt>rz<-@4|5m*m z|3O9C%Nx%B%h7*ZmjAHzpZd3p*1x;{EAD@P74km-{8b;TUH{WCS&n~pwd}unA*rjH z>fd3Z>mT7yBL9QH@7vFS`Cnc|_>Y(QeevIS{FzrSFXiX|9D)2>r>}ooO3(E#mZ9rk z;BwtiKT!WO{AGhV|9s@11^kVg_-#Y{aJgcrACJFoRet`%b;!RB@TWBKJBIl0ROA=_ zuSfnG;ICR*PyDkcGx^`D$S?fgfc)D6f0rhH%Mkzn6#1){;`x6g@^1(H)-rnh+lKh> zQsnO(&iQXb{_TOkTNA%yi2rUy{_>HWzXkbs0RH5%di=8s%;f()iu@w}Z$|zdfxkx+ zzh#L3UPXQp|FzZLm+2L2XJ{Ei|2_bc*?_`ePLYk|LZ zIX(W_g=YM>De{Z>za9B^0sdA^{FWj92Nd~*|2vR>SKvP?CE2bf|MiOg1^>Os?*Koe`x(%G z#fCCJOPcW?ng7Qjne!iG!1;IkNi(%@rR9n%5N7rzo>r? zApg_AU-uP>(}4aPKbG%*Vv)~(9J*ai{*P3Qf5HC{@;?LozWofypZtXIUu&lRN9KPJ z`Jc_=4;%lKpA|X3sDBS5e>?Ekf2|h(>}1)$P59&AknL)U|DzP+U+_PQ{LcZuZ$AUZ zfA?N;{kKW}du3m=#lrsx@;{%&A2$9ezeD^BZts`Auh);}Ic{yl-eyqe@G2Mf#3E;3X9A64WR{+~epy@0>I zS&x6q5dULQ`JY7oMB4udJ?nptq4hr}D*sc+zjxZdCVtzH|Hl>i#pgdyBmX|Y->!+@ zF~t8wRQ_j>e_!B_FRv&5*~Mn+-;+`KpGE%tfWJc%zh#L3si^$z$iF}E+bihtZ&jG_ z|Fj~%82_I`{sVx&Qxm^!$p15n{9^on9{Fbjf8~mL{5yvDpH<`+_5TIruLJ%@P5kT< zGx6W9$S>mmMdUva_-kHPJO7!^|7}D0|C}Pfi2s+6{~+LRn4xF>ZyEah^La&n5&thE z|G~hY(iH!;q4pvg+f9zccd>qB~UWq1} zIl2siET)-$6oViT)?ke2N3{qL*2V+@2F|95>NQnKCQ#_QkEP2T^p zu1xNK9skqT)l9noam4iB|4QEfsPy#z5E}o|%o_h+X#PJnqvQWVU# z@Z|V=+W70ohne;Mx1T!x-TU8jJ^eqF#=mh#ZJthJ|9kcCg5><~RX&sE|I;%%{y|Uw zpNftD^xpr}$KUytkAL_6|3Xjy52NvKTYl#3|IRNo{?APR_$T+jmwNhNr2bcDQva>h zewq1Sng0GKkAFM&^#2)}|4pwY_c2+weck`9zMuU5$GPg4>Hm>G@%Y!h|GnJP|Iupy z`~A$B|K2Y&|DT=F@qe+W|CQMIPw)PxkH7URAOF^M@ci2=J^dd;0JNQC6*x@1&jhl zfnTu#xxMRCf3NT>Zn9~bQNSo*6fg=H1&jhl0i%FXz$h?{3Y0FVXS7qerK{5M;`8aa zpTQ3^{HKI8(CnzdjR)0kMD4Djbn;lb-?<&n51a7CDQ|yr$gK(&>k_^iu{(Ac6X9b0 z$WKkTpI~wJ6DU9AyEK;hVy&B0+#Y_{7Klr@;!At#_T>1k#?RTz_rR}3`(5w@jo*NN zh2Yoyb@!{YRkvu%5Pm-eN9#mvK=_h`x2(y2#9Bv_|JZTfUxmw8BV74uUWeZ=F4k*d ze#aP&EA~pl3&fY>eEZ{E&pL+VTCL0%YZJaI@!S2;QGdj4O}L6%S(odJb&ut^#Wipo zhV=+napib!pN03~6R!F@Hzjp`bWv&T=r|t`J}}0YQ>DT7R@Og@(;ny6*ICaTi93m)$b1E{oV%NdLAEF#coZwIxe;B%g2AQBR^4ija6-8Ti8+gpEsI0Za}y?U!b2JMaNa|HopE3BfN)i-^;l5nc`c$_%?9qR}1(K z;ql{SFpiJsF5#*@!fzPM{;wc>p{SKq82^0kT5|tF!5xcO(fN=~xcE`{VSnL%xrEQ3 z;^!*(QRflr)AT#|`GWm0+Vg*x@CC?^v{UYP_=GFn^iL4sI!gB=GH~n5bbV~XRloF) zOL%I(2v_<@zg+3pSLuF+6TWa-`w5Th+}z0egc*LUu5|x)2CnyKPRj>tkB-)V@wh{y z^GLBF@WRo&{>9d=Gdi(;8piYA2X+aM=0_XO!(n~G=b~|ybzVFU>zQyFS9SjEa|M-U$0 zFQmT#;c5L1f#nv4R)Q>;t4=%e_R-B|xC2v_=u|L*hu4cNcp#y1CLFu&UZm-dTpdOVY71-y61MeDzMC+iq~#?}We>t5`` zgsbtE<8$F(c68kH-W!*gui;grqW$Cw!q*|btOK!~gbyOTZ8FyvYjuvZ)OEXq_K39! zUxIL%zhbu_T=|jn3b8)nYJQZl4~Y#UKRxsNB;233KHz@IylMQH_cfbv^OJ7NO!UO z5ndoavad}%hxHD@mv%~fRF}-hC}0#Y3K#{90+|Zb&L183dzJrKmyY)$YQWqX{xn*z z>^EAx8u;nb@Lm-)VDp8huif8Ir++P+$r=TI4GQ>gFA|;q%YCGWN8&yl@b>NadfmB( z&*$GKT%E7h-OA_3Vr$-AB=!EyaKhE~tvdfypKw{e&h!aa=hgZrBz*4Z>^WJo)_W>$ zjpZV)*qY8oto|u{m+-XvVP1qMeXHD+gvYOATMxr~e?CZW=U~Fq?pIwwc)Y*4t+>Bo zh9CRG^!~bpr?vki!c{xve7=0b@1lJxBs@(|>%SRzZwU-C2P)vNXeZYHfw*5C0GI2- z`n`A`=pnDit-UIy>;c4sNSuMSt;|Nb%|8Ei=@9)I5dHvg~r~7dUPuuT&!qeLSAmM52 z-(Dl#zmtLYR=^;0q5{Ev$4Bemn#A}0#D>7-zMt6I`;U*-zub2c>k_Wkv+NggKglOt z&11Q5CN>~^Ug8J$a9pvU!hh*3zE36AeUSageLt}t;VQ1&kCg8Vec*E6Pi#QAy1yvx zl>2{SXIX=3-DE$;` z6CT&u+~20bG@qZWK=5?N`UfuSUTp0%8S8=Y_`H<$;}f2`{s~WA|L|Wuo7cZs_qmMq zPk8G32QKSgY(RMG`j7mltpDdT`b&7~`X@Yf{S%(L{^6(B`hOu~{SzM7*{uJcJoQaQ zrN9OBds6y7z1Q!51=oK6yA9!ksG9sUyME`+cr|aq{=M-N%2z)7ldfuG%BN`xR?ll8z51ygsEpKH=)R zL-vv8!F=5jz>oayS1g4zAESWfy}oU<{ynTiu|9B_Pe-4_zi)3RT&=?#ezz|+{P(u0 zzyG)2ApbNg<-A|)7KE$cpU8Q83+C$sgsbanIbMsk|HFP{y^3`r+_I$IVqL=1)|*GT zT5r-0u>s+A6jxvWb)o7nsjwxUH-NR@WIwWA#X7)6H(CF#hRZ%;rl3*4DDd+s;5<-c z<$gZ*)9rcUM2Fwhq&A(IW(6EDi}&+3Z1Rlb<^m>qU6a{d50I z{=LAJgvYPLoeB7RBBQH(|6KdtaRtKF^8)hwmVy7~I0qB1?mILc%Js$89A1sS|1TWP z@x;1>t9FW?)*twL#*+w7YfnhHx-THt?ehIa%@N!lxlbT=JHl0a+{3s%VuK^AmU>^1 z_>t>>>!@nx@h9?>NGjCjZh-dH&}u!lSsGA}*|ZQZ@0sR(+XuzLM}XzJFFVdVZGC`x=Ahvzb2$wywna zCfJFvU9k2v`qkq$pk1x7E^G&E8Ft_tI=;GICZDc={cz3nt^X<0$=AX<(^=n@_C3OJ zL&?Lhhwt}%*Z?+^@BJR+dN!;B>%w}lK5PixdVX6BqSzGfc<95mH@@6YRgPSs)d znX#s&GgAQv&g6Gs#_~Qer|B>==alg^`zYX`sdL)-uIX>`I%oEov8JUnQvnCg=G60E z({J7fX6BqSzGfc<95hwFw>Fl)ubc?oMUo^#Nj{~=tSmr#G_ zr~COI!qxL0@|=X&nk_S){~(E8Itk*58YIhxD)qRp8FA7TS)J(OL$s; zeZu2^Ur3(+2?ISnSF8)X?MTMOdJ3l=iS7={uOVEGx4);&&kMqye5}H2EE#99 z)^Y!-QF^Jr52e=mI`a2t36GEK2Eg42r}u(A$j@Vm^?-+GF)sER!sGLx^FzISC8iBwB9CMy;n=x*|<5cTlWO^lYfZgiuDOs@ADOXwX+Vg)t;c-7j(l19TfFD`+Vy&_Nsi~#b=>2sFkNau+J^Dqs z8W(B5tbc;c=eMZ99vScd6I`2@TN19;x%}O4u>s*~-pG6Z#9G6W@5Af<``?5sKl1)S zv0fAN<-LDmuOwWpXPL+H9zknQjw|o|6KfN$-Xkb~_gn1NgsZsn{y?$rpE$1m{x6U4 z_&y@<5%dXH{gr*8`|p1fuHGXk>qpjq&0a%mS0Ge$5!+0-+8=wpM{sX$kAD0Q2v2KI zNVsZ`tb4K6K8(wI|HRtBrJeHkzsZI9%s~n`=&SiYjE{eFst$9|ls8>93K#{90!9H+ zpyrVwwdy|K#GUNuI#R4l_-bS6eJtAf{}wM1pUzk1?|z7V2)Mg8zb99$^YW0|`1^3= z{QqRam7m;W%ol5Q45?j%+9l`xVu!xR{JK21Q|xx{Gv0at|2;CXVds$Oy~A?eFLuEX zhSdI%{4YdF-FL{n&d2?mKV(1Qm+VKZ`{j^Ybw5nb^Ebr(h^q+yV+?N^%zm7&IIf&m z%lZF)gsbZg(M4=XxH@mwb+)=#H~sv7OTy!E+ZN%tA>r!2iJbR~o$G6kEBcD{2v>2X zopS!~&bw9AU%}=2|4PDDTzOx!x(TN4JJ|DW6~&eJ_=t4~m%lHrbZ*D}4wrBhS9oGQ z!sGKKe1q?+JV)u{Rvk(hhs2~u+IF<*YE%BPq^Yw!n_r0FOc3&f2pl% z=OZ0NAGv?@F5zlE>v4mnIj*{HRUdi(Pbc9juDm~6tks|6%5|>zw}H$3MzIdzaoyza zL0q{?Qa2y-#9o!#BkdQyL-_pE9`P&oK*Ci!<@#J~Ffi#y#_Mgu5CQ^EWR2v^tF`X|ir?{3KRS>7il_Bz7Vys9HdYJS?-2mFn= zopK+z+Y+w!rCy(*Th*>keq_9w@%M~|5U%D!!w5TCCt|IwSvTE}O}O+|m35%M4&h5u zzA|q2=vm)7?ZDRGnQilE-cKj)!}*RTwoSXT4L4># zt+?-B+z$A@Tu*OX{U9#)_hu{Q6L;Z!v&*(xVB3gxxM*M37{-gO?7!|bww*=P8_m`_ zf^GfLY&(u&TR5Bfl@`vsN3!)$-h342+fh&2S4MwZ@P4^2w97#|1GKvh`O=@*PaX92 z?_`}OKE!{=(8m5y!ueML{kIS2_Bo^2hC8yKhJ!iZf$<42E*9F=j^kZD^e_LJ>$Nm< zy{YMb^#Unr$=uHDVnU zu)a#;Ic^K)frW8wg3V!`RS<6==0j@@$89={{a1!@z5(;Fb+Z9{p1&@5>#_AVVq4mn zZ6|EqPVA@Q32sky6E1JxnenbaaK7&KWh1}VW}FW;XIpgG+Jo6vV68p5zPAPA6F*-e zs^5Wp^IlvYz;+H{p0gF(;@(`|IF$1~ti2D~g?!^YtiOK<$%x#B+?x_X=X)0^Wk_R0fY~t8q#jDr@WZn{w-cgZ@*9YlH^DKgoLZO z>iY%tnM>YF|MG~$?^uIzxL-iH@+0kZ_vCgugs0t~yy8FHo=LdxAl3>wZWJ{3zx4@M z{cUUH>jJUCTj~6_2v>YvXXkBhr}V21{c?fFLPr05>wnx%8CS7xwP(B(abftmjc_%- z?YMpwYk!vB&MgQ}Yo|}R(o_Eggs16w)sGxE!2KJs?=7-l)E@a>N^F?hFB)In|H6yz zXQ}U@`k|n7suf-T+V+0Y@2_?KeuT^SKB}zwcg(j|NcTU0aMfSYQLIOJT7T_)dfX9& z%l9uTZny}?4GCBCR{zwl%W?Jj;1Zr1*GZ4NAK~%-7SZ33@H9Wx;Qdm^>&l&YT%`YE ztwK8AAzaq*_T(58PMuA_W0_wQ=-BcRZFv#2on2J26$S7bGFbWt2i~_Tz z0$KO}gCZaIEBCOi8=X84XwdR{=bQT|*ZF$BJcIRhf76>UewXa;^wyu<`2)wy+5Mm0 z$8Sd4@6X}$e@68)^^F3vg92H{|4C;3&kn<9+GrFo3K#{90!D$Kq(Ij3e_$#7`p?P0 ze^PK$$tYkHFbWt2i~>f1S)zcmX-o9`KY4D|zL$SbHj41H-~YMW6Q6z`qkbWyes33^ z$b64*_4~hW{HjsW^QsRL9{o;Bo=<}vvIFCjF5}>DHs?K4{PIa5FXcGe!uux#P9vPJ#Q@YTk!m_ zSfB8;{sx4{`zz1?hrkn!r;L9_vi+jZTbFSA<@cLnM_kHy^LQS2u_56~WqCeZtbJLs zzuoWuBs{JCF5&U^i#{IVYF;fsNzIe%@H@hHZi3F*JoIno_9$QKvkRU}e~WN6pQYVm z-CJ7d-3au1(=mHQ^Ioh^_&kKG-)pLmJpcb7;p%yBHE-3Yt&!)+;9FbhcYtcPB|ldZ zo)*_G^E{OKDg7NmxSEHuF53IE|B&!S3D@}p{*mtACtSV%LfUyUbPEYr^HB6T82VVZ z@wiCbx_{z#tAqea=qolLd|=!G{v8sY_IpkL-j?Y1d@`TJ z?)N13SAM@K_UhLem;Fer`){5PdT5{U0<~U#k6V8+?;CFeSHFK%^KFvHI=FA7x6}TJ z+o}71=)3fGuC&lG(R`5hi46(wQM1RJz3?%qzt?mKSL;Y0FPHGN@$v|l@lySg`Q}Id zd*aEz9wc0iqpW|ic0cwnF)qgZaS2cRU8zTS+IsilN7mOr;3ptFb)FEOHczJfE?rM| zxpclyc-rqo1Hx6G^z{`27hQ}s3K#{90!9I&fKk9GFsl^s5O_}ed$*>)d_8D%FgoOB z)#hX38U>63vs3{O(dX3n-kW~&@z3ZmXX`LaHz5<;C}0$rB?@?mTD+h4KVyv!>Uz-3 zgE?y+%#zK=1T_j61!k!N>USSgd;d=bzxOZUeE==6&1duT0bL6(#qa$_FPhsJFTgfz zjl9?)$>$1+XL7y?R>bI-fO^eIzLYoh?-PxJ4u&-Geir@I}9 z+xZjgJE%ACC)S_t_L>St0i%FXz$h?VDexn;mR{*;S>MdV$MM>E*)9OP7;NMG5$+we za%6Kyv-M$v7S0!rVH?60kLA2|9NQACeLV2lN-fh^qkvJsC}0#Y3j9VC7(O!f{r@)b z!qNOZlUPUL)OG#+|1NO-c{q>o_;VZb9($kg=-ChL?*)W}&reTJ={Vpkh6GJ2j# zp5OBEzI1m#_9M@)$ov1VAbcV6(|Y)!(eqehYeupkd0wXl?-h3lSM3p8-v93rzJO|v z_IHp2!lUO@^!7(M>7%vZ+MjjPXN^sGnm!KUY0r^(ge!fdo$~(w#|T%?dntX?r!blC zUt0&TA9?Oi>|nx`KKdshJpTM*r@ZeSessRw%=(DFV(rnakN*CDC&G0vmgNGM=d;9m zgs17_6Rz~}#_;%x4GCBJ=%3Zb^ys6WTgqR>`nZR)ADw>%;R~nuv5!dVQ-wYb;i^6I z+@DyFa5aDQPe8buKl1+n!{oWT2-n$^Ka%H<=y@XeHsNXdIE1VAh>l`C!qfD5jPUsU zaiEWNH2YEOOMT?|zrlp3>2n3)%8$&?5>?Dmy%2sPC-MKar0XB2n134ui~>K80%~2S z{r$h@XVdR{S1w4$f1cJEuSNl*fKk9GU=%P4{2U5|w^XC+|Binj7F{QMm+lwYd2X#n z@Bi`fchbd%gsbZocTeVvwaNQC*F_XLTxZs&GN+}0mB&H%zw+e5f&kG!`b#QTe` zAY8Razn=eyaMhl6v`4IWXEpkJgyQF~c%M%|c>KCLw;ZmE2v>3S`wQ0n)#yDf`u&t` z2v_fc$)C?Ui1h>RZ^yYjeqtXaJgvX>1Iczue_g`W_)7cb{XeG@uKFu~|4{5z4|01- z_&fAs?T5Hu9VhWT5$h7J{MY}T@9&5`iE!0UiQCx5{R`noaC!faH6=s0XR6WrYQ(Qt zhj0~F?jOnfe-0o#tzRcs()(pSo17=IZXCjuf4S}#>k>XM^-Ik|^^y1gcoCoUe1P>4 zdnMs%<7GX^al7u~c`SAX!qxl~edK*CqX<|1l64}s=7p-YRtn!GTzL_{Vtv9@zx3<> z2MJFbFZ)Gqr{b&oEb=}v2ROlrj|*J2Uw!2LKb$lFHwqX9eoh6{_y2V&z@!EFd;h2F z*uDU}GJo%Htq!|3?0T>p!v36%G`@`jMggOMQNSo*6qur<%Am81Xvlwr~@BT}uFXi={ak=E%!JCBN{nu%KXSnW%Bwy-@?ZWd1lGkkq+O6Z$ zn)mvM- zo_DqS&4}05M_lpKK8-x#>$W_D^}A-UemH~m2hQN}CpUxjn`W@S(?|W*KFZs0+%Nyc z`SsCuLuVRp6!_T`2)zn!23sG$ zi|s-_E6~6h{QXmw-){VHZck+l+6CKzzfa&G-!&TThxK3!ur_QJ^(Ml0$1(pf3K#{9 z0!9I&z;952tmA*~M?P+5b-5Gg0a@kwbEaNDtDc2=6XiL83}VYq^$&k;AN3piD9>ot zYy;Q#(Z5n3`p-5UH4QZi7zK<1MuAiXvX1{veH{N&of*(5U=%P47zK<1MuFKvfvn?y zD~|t@%z40UF^;B@MggOMQNSo*6qp_b)bT&<`Tu&n|E7ZDe>1SZQm+r^)XN8ka%cl&sMo>9*zU=%P47zK<1MuFK^fvn?y zQ>|R*&%S*#EjJ1n1&jhl0i%FXAYFm1|`oG`kb|ERquuqK8S3? zzkVO_#XcC}HCE|!#>H-No8s4419xTrVgumqH`n8N)E;YaNCz#Dew z_K02R5$3n-#QhTMKg#1(+KJ2ec5pl6GEQPW!sFvohjH03V_ce_h5v_n z+)J?6KF7E|?pHj|xQw4z>jfT184s}o2v<7G_=)uhSK}z-@^|QYHTa$AuUO|r9!GC2 z)<>*Mc-lC6gsX8>Nsapi_zlrfI`zsY|5M|m8@Zuu7D?%s@x zeH*xs_K0=gPOg`WL^s0KJnRBr?0|O|x7XtKi+z~zw0*{Vm-Uo&)G>y~^AW<8|JGA^ zpAj3p$McGYAn|#N@U(g5ywCHhGH&;1e-PVDxZ=ycAlB>T{wADL#wR>&UIm1!In}V! zp^<;FA>lG!%2%0^IzBXHjMo95aDOKa;r@=eF{xHf5Z;>jPZ%U z#a;=#xrzOY9q{?E+8S$7t8xbPfxU)s<=@(q{fiy<1>-U=#l8hx##^lWCG+e4$>S*Y z8sL=?jEi-@8df_G=_K=^c-$e8uBQ>M^w;;FQ@YR|95*{*?XQ#im$2_`oT2}zHBG7W z)2VHW*1NPv=I2R-D}6*?vGdHucyUkGS?v43o1mxInt7Nn`?%PV!0Z0R`imVnFY_yZ zV*g^@`I@5RCP|d|oJ4rqx(EqZ`|XloKXou4XXmbCzU;GNeZtjoQ~w0u%kffdNVr-T zy*~4&`>_d^w)CoF0Hc6Wz$jo8Fbe$I6j-#`T7s@80W)T4IT2Ya_x{9fb#b@$VV@rPz=3cLMypN%%s<7rbFC`x(46`w_fr z5k3$02#=2UT7R7tnyHPXk9NN65w3L8KYoPw^jGu=GVqY_G<~cAJ^H8^7olGc;Yyzt zTtA2%Pq^q4wF!Uk#a@~Hi2m2W&v3$(KKkbY!j&JZCpEvOc;W zkML+-9nRMwd00QfQ}hAujbXmnknmJ}*6Yzn&4=rxJ%lTL^v`(0;r_0J}O3?=(8dF>4(6FNqYuo=tH>DNAx@qd_Tfd^Z_n9iVX=*)n|(y zeN>a~koFKR>r3G$10PR#T%U=j^7^v3Vm~q;?gxK3;c4?HAYA#85y(NG5Pqb;r%QWw z&d`VO)b$nNbe*its{pv_Q~VPWo~q9-+^;xS{o5ftb^Z_@*T;Vb`s|+WXE@;tcdO77 zB_KSmPrc}q;l~-Cp%3Ay`b2n7Jo#6Ufro^r>N6s}Uk>4^`Vb!1r$gq?{^@>(6P~8e z1B5F-YQCwD4SlS?r2BD3XXrzCsy-3UzT^K7GVqY_RDH%|w1@CieF%^1)3_G@9^XDP z-Oq5sQ}rP{uFpWx=csf)&bSPH2v5}~!sE*Dzk>`sBs^80lQP;vc&a{x$Mvbo{5dt< z&v3$1^&vd2kM}zqzfMc{V`tz_2Hsm4gBS&j0!9I&fKg!9D`2Au)hqb8r_RHFq>r_b z`WA!EZz-vBtKywFF4DiFahFK?(+5j z5S52sPkCLue1lD+_DlVnr~!%kLpF`-cb?x#zxT?X>>q#cin?#rQxgAP|GlH~pxC2-|5&+m;@**e5A|2p z>N`K|6V=bh^igdP|IU5;M&)sRlm^}9_q&mQslObRCF-v;JgOg@)6>4?f2WzoM^xLPB`9w`;LPn|D_9h{I3x6Z#{NsqW&MX`r)_5s9f|PNab<;!@W+3{I|r` zk7}dzKb(AGRNfwouQZl&zc?=PFZGwEvUq*_8ZMXkA5(cezSVSkRA2TVwRYqCqt$#m zA(mDBxMzP^jq(!Ts;7;SKCLnRSC5w;cxL2Z>Z`F$)PL+uRh>4d9(~uOtoZjnzCKZZ z0F}k-d&}RTYFi!W_S9dS^4;~v-jJxTv`f@Ko9kPxJ@xbP`neku^;gmB7j7hk_TSk4 zv>xTV<9jzpNmvnqu&m7$G3(( znW(>%RzLjk>8M=VujWp?{ow+Y$bUIDKR1r~4{vxeI(|v{pQtPYQn#2 zTf+aFUq$6IKh)fbk54%6d*#Ne{HL!$h(4WjyfY<_PQufN6~QMo(5N1vhb^1b(r+AsB&qF{;oXY3i( zFT~bwW4!*EdnM}k*Xp~2?}*B!{c8N;?RSUY#s2@@vwv(y92r0NlYd6#@%>}_c=;Ch zM*a(^ua3Wo`d8i?)sL?qb;K0^;iDai`nFa--1?QMetC3{e(L^Bcm2-S6ZO^j#N&ru zuSfO0Sp8jM^_@$?M13{4;`N;~-sJix_r%{VUVotvqVh^?e0PtRpYdT-9zXxuBUT>X z_unYK)K|yuczt)*AEI&(@sFYMczo*sE*Jgj_fd)VTN4&n)7P@k=xM*&14KXT^kt*+ zFt$JK6)&&*9sRzkr@lx3PShXxyQqGBY<}(&uYY~A{z-cMySaXIZ2hP+j_&qtvRoqm z$$I^5my6tg%Y{;~T0 zkj)bHFV*V%FKiywFUF2f2gK{&F*qtO#m?`V=N4$P; z&CsY^;{Tq?ZZK##v_ zW8^=$ey;BQxfu7~*_dd*I{qixU$;$E-`lsgyZ)GX{a3b0)K~jQyuQ89PTYR1pGT-X zK7Z_g?-cp3#?Bv(jQO_@*@fF5D?ch$Zq=yY57O}sob0KDPdjifAoj{;@5I{{Kkj@%~#6ak=b&e_asIT_tczt)-E2DCWzY%$h$9Mm5AN!xsv;UqJ^Y2dhqkvJsC}0#Y3K#{90!9I& zfKk9GU=%P47zK<1MggOMQNSo*6fg=H1&jhl0i%FXz$jo8FbWt2i~>dhqkvJsC}0#Y z3K#{90!9I&fKk9GU=%P47zK<1MggOMQNSo*6fg=H1&jhl0i%FXz$jo8FbWt2i~>dh zqkvJsC}0#Y3K#{90!9I&fKk9GU=%P47zK<1MggOMQNSo*6fg=H1&jhl0i%FXz$jo8 zFbWt2i~>dhqkvJsC}0#Y3K#{90!9I&fKk9GU=%P47zK<1MggV3B1>7h6eT8p-ai#j zp&IBXC{Ta+l99dxe`Kq>D1D!f>%3{rx1B$8{Y`6J!<#)7D46*&dk&mw_0OU}e)7!S zKi%;&*Wb+QbjPo>UDMmY=GkQba%$7hzoxgpzczm5%=G!)Fq@3a^y)dO-*0mqr&otx z8^1J@_w8R>|7O?r&j%YnpvzW@-6r_EY%5%>SQre0*~}{yF8H?R+;h z&zkktHhSuDD`uX~c5^AM!G6Yl+%&Gii~_m>`A4U|Pw4#V&3FAm-{-XK#r-J$TJCF1 zq>2m0#b;*AI0+^L-Zov6|WH`@!}ZJm2p8?zb^Ne(Jn3^^5}3qCo3R zy00@4-;YmA%s8hylfO5Q`<@m5?$oXi2KI4WEzTtU`|4{m_S3o}%)U4^tvc_SHht{J zXYhFX#0=J-S|@(NvaXt6$NkSHbG-irN8N<_xfN)!ejV%T=kDjU`mdZfZTs@H`kPt2 zi8J~9rDG=hn_2xdetsJYgtOUwfWB1sr|~?jYX^g59ka&&x zyq4+w{gpeDz6Wup^ZU5cuWY{7|H|5vHNFOC1^iije4Sb2P?^o{dj!9+^UrA=$CCEk zp8FH;mrrXv!<#)72({~!+-$Z_<+XV|X&UdR&#KYtI4k{pZC15sdgC_Er1P)ojjQvW zX}k{C>&>iutM{1d_{goOz^Gef3Q?? zULza(gm{PGS7zPHehH7fbJ z9h3O>g&L2Ny>lUn?@c(R(ADrW2&ZJ9qv4kjPAT-0xV82!H7a@Qk&S)adv~i*$$ntB z1nxh%Ta8NYvq{|jh%idlCrRA@j`)Ww#KF8y>)C7-|@H_mr}6XaY?-2S>*q$8f$S%v5))o+2o(nb7v><G)?7Klkn$kCM}NcM`vna7y9CBvsIe#o>yeFpoa!evDg|GBlEh12)Hsyf^S?;q z#qVnzO70QgC-C6KEoxPA-q@lx=H7Ci-nCXG@8w++xOdmET9vE^D8)X0`>@^f^REJa zHQ6{{;TKc7hElxbCd%JP>1GYTf%4Y_kNZ*hL`t_%iu<`0c$sXRukh63;Z zM);W;e|ySrM`;HQ-x2suWaDx7p#1KXhEa-_>_+)rfyem@--S{Wr8s|2;C~_;=PP_? zN_$a?myDqNa7z1WxJ&tcfyezQ{Lhp|Qi}W8ANXI$#`y~0htdI*;w1&jD}B=NZ3%DI z_^VQW6-om&d^O;!la0q+m-2Z^>rslAtV8*=fyem@UyIWEl;ZpifDa-Y=PP_oN*hv& zmuyD)O)33R!~a0}O@PP!D12i|n^TJWaexmd8|N#$fzlR~;w5WPUg?vDuT1!s8o!qE zHI(Mk@VSA{LpC0FA<8dEX<V@=BjH+#-B=jsNd&ejNKc zr8g+W{rm@bNH!k#eagQ_sgqK?icf<9vm`Md>3-@siId z|0$)IKzUdk(d((td_S^rzQX@RX(Xk1$qtlP`lR7o6TZL3Uy1T7Qd(KVR{_2%*?8QwDZdt_ zbtuJ4)};Izz~g*{uTCjXDb8OP_ZkMk8i52Xbu#rX>XUzlv1ukg7k^`jIoS(5TgP+CgE7pMGUz~g=tz9^-o zDaHNN1Mg2Z&R2Mj(lV6dC38_;>5zthPx!JLKXg8{JWAFUlwu!eOUhGnha~ZUc#5y^ z`27KIE5`kyN&X3+(6uS0v6N!&ErlOP=@d%wl4B`<4DdK#;VqO-r4;8MMtPMErxfQO zO8G-F@KJ;xMJZmx{quIUM+1-h@fxSp21BRRTH8#ijrZ5Ra7wK^VM=XCHjW1yK3r=J zdbrlv=-~t&9!2<(57)X!YxrG+-%0pClejnkBefQ#P}$hWUVw3L!AEN2?e_*fN^u{p z4U~<4He}r0=+Oi}eEq3fmy-3yQ;Bx^tJA$DO4b^c1a7Tasr3l+$j03}gektl<2tx& zRcb@Re6n%eUz_+Ut&{WdhqkvJsC}0#Y3K#{90!9I& zfKk9GU=%P47zK<1MggOMQNSo*6fg=H1&jhl0i%FXz$jo8FbWt2i~_$l1xjm9+xx@w zms*Lx`;ohX^TpSacty+W{jJ`SYs{lEeqW{+7#~)7h3*NBh=cTfTtt5c-AMyl}or z`ghMx=A|8C{Y$vqrq?*cb(eD8Rxp2pPm}y2`fqQI_M)O!VqOvbC?KBrEn(hBUbp3w zxPJBgWIW-8E$Mi55VynM5W1b16phn&wbBv z{m0o>F^=M=cv-Stf{P8^WO+%Ohr+XuXI^1hj$i3W)+@h?Jm#0wtE|QR>Iqz)m;K=(xzw|cOO|)z_($*rm;000mJdtk2ODtwqNaZ^knwK62XKAwm2^MCt5&$Yh;>~0 zFXw&qvp6BWz9-{``CaNt=LHus?&|H!@GI@g_tW|#1)6m*Uo?2Sv(Dwo_6O*{ILd4L zkl?y47TJ&2!0q?Z@BB?k|5C4rbyeZbqa7i$YDL_zUH`9?CFq2-fAL$E zdA9=di~ZR;9mzPt*KKY+=I38yzK`(|UUf3#!7|DA_|RW?Wo;kIp*>QbWvf{4;aMD~ z1YHYgmwPee9{g9e_7%0bc{%UEx(_uSLYzP3vA^W{I4_WP+yCQsNZ!Zs%fa#5$MILn zbz8!?7O=1Qnr1@Kw_NU{|APNiTgG}Uq5oCv;~{X} zudD6HPCK{9zLTxa&uPa$DbH#9g*T1!N$PjojQz9p5x1wPjYAH{X{m2x{!}mz1rNq^ z{qPF5m6zGNn4f`+!_quXHje9gZ9a;>g0`Ll?620P>{obM)?19@_*f4P+Ed6l4%s;W zuyFpK<<~u$;}uXI$bHGRC3$Ap0w#-1d_GrGAL>P|1reB7Rw$*JaGBP}{$xUjCExI3CuIpRrFB z7D@KY9+1pCzfa~RUIoXe{E_K#OY|DF9FfZt+2*TBUWoID5{^Gb%wI=aKi-nb_<5YS zNjs+1+Sqr5?_+*RKJO;mXJOt-x!5YM(tKj^>%UD<9r-bv%0?xmxeVp&+aD1z1`?C0}XxAr#=ldt; zyWkeqad-X{%rBWABa%9G^R$1sn%*{aw6)`-`|{NNh3h8US<;S!T39Q{IG?THc%R3< zC-s6-di((UoR9spbOG}mnNQ-N4;$k6TEKNp3G2so)8lr#dx6W#INx-%^A+J$FrTXQ z+DEkyTH3x^!Tc#_)Gr;w^{U$bTE+RF#3`X4-FbbUpuoL{{S~zP12)Fl{}k;6Kc`*q ziT^BX%f5p4IIteZwSs*-hxJ>e*JmnS3Ru5Im-8iU9y&Na1vvke_>OkG4-e=1dHAm) zeq|c>xj;KUNt_Dyxd7Kwwssy+k^5;%+%O0s_y98cZHxZKl@`yu9I5%V>`_)2qqjFX4<2wu35{Z%ku!!FKO5hqv~ z?Z`M^5Cy`jpR2mW!K$cAiy{;|K@= zj>Cl?xqcD*t<=|TY3bxR=;cM|YH9md8P_Ly948C1Uuq5t-*Y?c=hFKl^a}JWVO%TP zdKI3BVSkc1 zF4k>XyN)Sn^U}jStBhtpRUEg)&$Qa=Ke)bsYu2;qJGsO9IQ9Iv}IJyl`FVL>TT^u(H zxK7OJ#}VAO$>I1Ver?R_@~O}f-+P2uFBbN%oOYeyjc2~^v9gt;V;DXcd&eN|8@~y>Xowg8ExH%&`Ij$>)EfX zeP1BuA=Y!Coo5uFV;<{7_^uC~1<-8ns${v1{UML@fFkxGty)hO>nx9Pkb<&yo)Ki6 z$CX@;U&20+L;oC%i;eYAI6m3V0?tb$p3}IYI(CP_K zw?#QG!tp78G3(%Byee)|7Z2w-;-`T5BYF1(<~ykGVjnHycxk=L<(@Vlr2e$pV8!Hq zBlSYWakPC~%EcD3e-&_iu71w#%E|eN5Mcw%H&;9F@UX8{pXK`g7`9T~?xP*T%d#b{ zpTX_yzl7sR3Fo~z>Q}+M7G6m^f68Os=CB{RxPBMDSYKQJxzCbusu{;8sqbj(GlzaxwBuw| zI}S;G3+EYSv@ehQZ{6kEKZ=OwFOxpcHM&*A@u?RMU2N>jdU;OTf#aStjrYeroNwv= zvhszDaj|jy_qF465&LGKt*0#iI-Wm-$G4afw~Xs=y`DXd`=(y6JelK#+IkOgzEH(+ z(D{UU141LwX$~JpoO)H z@MojG8^DhcvEO?*KM`2BHqK)N5AI|?<>Qk60?ezbc3v*^rq_D<{c3IB>C2xZ_j_=@ z<$ufVEkWP>63Ow%Lx%#^oA*8Q^K!m~fHsaldC>vaaaC>p6>+{J?JP}Zf9~^1-O8H& zIn0X?wvusO=WF#Oj)&ulMf6I*WK{#8-0 zqFrB<<-83QN*V1Ef1Y-pDtHdZG0BT9pg&c)zQH`o!;g=4*`t%=kh?FL52fAO@ulo0 zc@kHwb32!paQ{VcSLPp%Uj^-YQh1?uo>)1H{Z;hy7mQC4>$`;c;N3Iz_Eoj>Z;9)E zmtL<3{k#jg+{U_)dSVMWzPl5d=OSOlI;~--TaR@PKfnp)VH`!kIh-6;syZ9d12fz3!^Qzi-xYsjYlzwXCE&d7^ zSL>K$yb$xTa(EJ#dI9z~AMFetWnQjda=$BR$8D*vTMxRGaUNNEp8b`+W*Y=(2XLuh z#5$9_h2vH}V;|3d$$rW!B-`0tKjR-Z?z`u(|2jpqCxb6=cqH?3+Ih8<>$ZS>st6q` zUvT{@bOTY7=(OSyydurl^HOFJG^^!)}E%i4Li_!Dd6`_%x)S;57I zSdWqy>q2KwYey*eV-8NXzkvPE_LF$t<9r_XWBgZ<$9xT5N%AGW*ox*)@Br)G&sf(5 z?f7A1zB~Wpcs}M+ad94(YQ}wr9QIL(TgCn+c}qLb$#t;*k{nlHbGM`4av$ed&U@p~ z9@uWb+COqQo@%gF(C!OMx%V0Sm3)>hXy^YyhMu8zzaz_^;6-ge72LUd>g}p(`(_o# zA*t`-{KdufY8m@i0p|nGVmzKXIX+;2E@50;tp5`B7YF-m8S_Ho6wjM_JB8PmEo7|E zvOYf#<#^SM>!B*X|E^|S7kDn$FJ#;=&taaIu%GGe&T02)ia3tsuwJ|QH*%b^oL_-g zKz!kq9${XwkM%A5Ube#ZyKz^`cNgFvm~Xaze9_LwTxmCS4z%&{ui~ChGQNj( zXUq95_O~L=*DLsbSeof!A1U3-eoETDD!fqkq1TvK!11MweI|$V!4l3(q@K5M^7vB4 z`IeMB*mrUmkNh&sw>3Y)&*3=aYvWhC2s+659O71R{L4eX@Dk?vF53Y8DZ!ts>Fc1M zmbU(b%TfPn#FYlZI@+zF}L0p28Db z($3#(oM%Y6Bj+_4z zTbN(b`YZLbY~Uv2ROI{_6&$%gpW(oR4yAk8Pgz?Bc^t3ZgOhQ3x%-;SL;Mb{ApODq zQT~j}1FVxg)~AR2Gro3y<6wW%<9JvXMcL1^_Uil){VU&{-hL1BH!t%6`+nsg%&%g9 zEa7-vzi^7nD-rc)-B5?c$467^$nJc{C%6j3xszH^S%ME{^(@; znifR++Lwy_eGT5k!;`#r`1^S2`iR$+!K;ARuZ?+MW$-${JM?|#eVM@v!8>c!{!!d7 zGI*WBJAiqgXYf=vbL8o)>zMah2CpjqR$V5F`zd(3elGOe{%YoZlELeOzfqqvubRQL zR^;}bG54}j+?T;?JN9=`ySdd=^vHrye$*YyMZA~5tGhKhU+UoR6)IQ67r}EiUJkrB zzu`U!-(a;U z?vCK;aqE`maoZXGb^uS0+k$np2YB0O_zOh8_g0VMZkNI91n;_Q*Nk}Uf!C`a9nf!y zwIbfS8UCv9w*i$aVjeubA6?*W4Bpb<^@`iT`Ykk`<1PiBuAfEIN$pqt;crRs^tg54 zEf3yzKk)IWSKLhycZ0Q~{(cLd9=9I;exPzi{02Nd?m&$1T!{N-R@_Yy_iBzCX2i7- z_ie=ePgY#;I>CDcyk7nN3gf%MI#GWg22byA9{$?lZwh#Ne;dGi3cMS^>lOD*^mhu! zy#YKuZp)TDzBj|)_2B7oJ*;^g1aFy<9QO$DdbRI7nSbj>?K>Piy?q7vI|^~ffTy>w3B2RL+Y`KAaW6pJ z7dUPcczWDc=)4#F4FgY)+X($!@csy1uefc9J953Kzng)l$1S2C4*YEjo*uV^_H6~; zis1E%dlBNk!*K_Ir^jtU+?C;P1@QE^F8aGVcs6*ILz45rgTM8bSU>9TeBkwJ-z8|@ z6z0tfp5DG9;?9q_^MI$fuMKhgf%nn(8T;R5h&z6RsD1whPmk-v-^Wz0h#!Kd$DIh? zXW%^xUa$W89Cyvr2Ssr!;OTKa^!IuAdj>o`ZW(bqz`F~)UU9EOfA82ZihCz`dfZmT zodkb(fTzcugt-3#?_%(J#l0T=9kNjr_agB0xE1)j6#gy*PmkLH-j(2a;Pr}oBjS$d zxMRW7Pgp;yyWr<1PlC9=D9~SQ7pg1y7G_ zBknTbb$yqyzdX%4-}Lh4QGdSzPmkLGf8S8KB7O;;9@hcyNASJ?uQHCW2jxCPBY5Y% z%5h%@ua_Ft{YUEV<4SHaWU7l8LRc&~t`pC7nr-#zbh+yJ~@?RyUE zXbqZ(^tm5Ay?xE__aNfl2cF)(B6yF2_b=gfB#&Ed6ic0FfAChL3Txe)!RtVOKNz!3 z#G9POL);H)w~cuBWbi`aJxCXP^tn5O*VvESx7x`&M7&Ah4Xm@HcFQ~n(Y|et+AZS! z6TH#_NnRCkZ#JGvfMGru5t9H1>BJc+P^!xYjDn zyYY19mBDMggy(ZD`A{Dh_wkh~CJ;UdO!a!OO3eoPV7dH|0mgy%xOsD_9p9kGfZRJd_{B zy9PXc9yrpzyEyLE;B{&3YXtA+e=_e1@br1mfVj$!itA^@ElAu)*x%*gOEqEQ>+(I0dp>x%T(W%@-40dj=*IV%Hy*tF$I1EJjD9FTD(<=9HP)~{ zSx448>`(boymP?Q+t(uceaUf4;00RyJkjqf=A8vzmln4=f#WJaD(;yXaa$$syt^x! zbq09$SIPd?i7xXo@9z@#>*W2;68tGY%HQ8I;`$PIDfTxGyh+Qje)Fr!^r>F8Y&0G> zEzLYH!(R^V+h!H!jRh~TlI@!)`mM^m6T#ERw+x>0quOyic>4Id7+>W_@s0yeAK!Xu z--aCbSn%o><^Ia?!v^oBjhJ@~c>4O7g!U;vD(+F@Pus6bJMsEZeiZLW@bvZtG9E)Y z?h)X%Ywc?X@0P8ZHyS*Bzbax~DnBZ2F(Yn8;_kuz4g;^WWKx%b(B+0<%sT`;eZQ(; zJd__5cT`5)P~!fD{T&Qm+fvE6t&YX>?*Qf<1fD)$I^j?GQE{8W)8|Ww_9;J#cK~?$ zcvPi*M{(T0h`*(i?dt-sd^Gb$3Qs$p=i9g+%8!b>Uq)PORpxDT8v7doUY8cP4!nPy z&b;B^>AK`GZpx2}yDxaUF3!6gSNT!AKZB?1l9Tpb%W?MsuXXO^InFTye+`fk6T6X zlphs$bMW-@x@Mg3DnE+%NAPrATHtS+_c-om;B_p{{grX^z`N~z=4}F=e%$g9SNTzK zH_nLLDsh(@rf60Jc&$q$c1GNZ5_b>ww-$KrB1v7Eu-H?=w&NQE^wuh+CHNc!d4g z5?8zaodn+Pk1}sL@bvlDj`^qjsJOq&h#N@Up-qZrEd!pepAY?R+?sj)GyJuSzoVG9 zG?pZ`AVa{bZFTLL`qmgIGO7y5Bi|2?DjEe>Ai8g?|_WZ!66l>Pnp&-+BY#lUMC zl$f4O_oiE{j-4!Dv-k0F%{`{@E zeP2_#B7Om$e!s4Se*6I5>)`dePuRh6KMD_s;=Tr+9(UkCj{64uy$YTlH-OG>gZBV< zz2d$q{cVoo2H@#&8xZ#)_`4rGJ+1>@J9zhjr_X~5^n2o!L!-F=0#Ba@6QQ5-qlour z@La@w`Ze}989Y617kD>*SB&D`li|;zpMj`-Qu$HDyTO~ZVRD|~B1Hjq5Xy zZc9d=+@#ebf7hHaI?5lG!K+*g-kHqXHiK6<1-wg{w{iy0nF!v^%(F6h!Kuu9_+QL> z?HgVndOyn7!{1ZPyDNid-w58nnRiYGFMm3C|Hr&hS-i`@`<{7QXYec!yoJX^IuFR; zm2LuWIp%%;b$WlTTfke3dEbCnx+b~*6{~zazxMdUqqtvX@G7T+cM0=8&*1su?_TEp z7rcC%9nB-TpVM+H-_NPr^vEb~XNJE?@b?LoE8>4L{54z+f7`Ra*E9T8;O|}ddp^To z(>3t7H~Xt(`0IqfSK#l_41a<2cNF`ZlHt#4Wu2dbzsVW?>dI)}@$7F>mcLKf-vjV> zYlgpq_&bCB-IU?49{%oxzpFC*c`_cCus=V;UmpIhhrbCK{@SE{H?hC*8U7mK?^5{t zdzQcJpx?dhuQkJ8aV^&G9QYfX;jj1)_9b;|sEo&6Ov{I$T} zG4OXt2CoF(wZA_qT5kts@ai%DuHA`w!@<+n?Gp0_pGN%-bG3y&u+X7`NA%w@rq>4*1)J%2i+|!(XHL`-uH* zmf^1oe?#GKQ}Fcjmx(w|U$^G*QGeG3&$^HIQ~DWF^a=jM$L(#8JSobroe{VBQ=ZQo zBkqbB{`~vd|F);HKRd%;3FEN_{4JT`Z(;y{=d-`XGW>aH-*WIbUxvS?2jK4-_BVHi zzc%<=1pdCp^98zo)pw!ao$T*R@bu$l8UAYE@4p%T+y~LVhuL3ehQD_B`;5xf!2LVJ zU-Luo_aggyHN#*1x;(z`!rwC){@SO&-@EMZ$qava_;V(pg zAA`T!GyHjvpndb49L?u)hQBWOn+$)~WcbTJ3V%zozbiBR!=uL-^GUf*p17+Oo#$;k==5mZP6kiE?hdeTta;3t5zhm!>297!b493S z*?(nS*4*Uc2sshF;urkfPAzz)x%qjbo92BoLQVkBUOD-EPum*YzV?2d5$|~L{NE>e zA^New`X5BRvP19+=G^S_996nOeR z)V$PEk-t?|{50Ynp273L`^);wD`xQ8gm*jh4$0t^!MpY$<{gy5EB%MZ?b_#=cOZCe zt0i^rKz~1co@1P?;Oj#9WwlR@VCn2NuKVn9XhY{1oO7d@YexdPP<^Ps2@YXYq^zmnHRzYC-M32 zc@vU6J#Hv*FPb{fMt`r~WZpzv-Cq$p54mCLyu1zl?wN0@{&G7o@9GbjH#kF=Ds=hF zrgf1&;py$mqaPzTW8NP#{MGfxe4d=->HZqvZ^*sO+XVhPi##54V?4sT+Gw8M@B#BS zmbeu=!lOnLw*k5+KdS16!qe{O*l6D>OU)lu6`tNc2mV%CntAJI_-lZ_c@ItUbbkXe z9&;bYynKeg(zU#f9(kI1Yh~~Xi2F$Y1)_eep22Gd@4Xi0t(w7Wll6N8^Hu_{@dO?Z zIp6T$uX*x+GX_AKb&eV!H&cgj=DTQI|4yXg02lBfGC zqkU7pXI@=~zcS`u>nil(5c&vD_vd21Oj(P0^JVDLgnm4BT9VhxA9zEyqX+KkBmQ(= zfPTDl3G?PgT>bnYgf2s$VBTCA?Q^mJUH>Kh!AtrGPmfzffA#18^?A^a_Q~`A@}24=OG9EE~@%PMqCeZZ@8X$pM$5b%NCn;QGQh1 z&%kRtKH0vB7`MmwpcgsEczXM)=*KC?GVjw2e`WD^T9T*x^K5S4kQ>aT*h?>w=>RC%rF$CP^pOqExKzbUJ)G*w=k=yEZ= zz=u8`Ll=EMJInAse(g8R`)>xX3A}lip%+!rM|iq^^+R|(=3bV0of-a$@HcdmBv1Ee z!{3lUFz?+Ae?I&@avbyC%HV}^p8fYEPmengaaTHndH>1qHwkh7a&eNU`zv8xj=Y3< zuV?tHh%S@q#bERip6)L%y4=gWS2Fx{O8XX~7uwNBc)GtfY2U(A=lS5ha~bnq%7|+% z%kyg9z1EE4J`bLLobHn2;IOqK-gDsT`+Xz&``GEsdnUtQJ>s@bVBV7%?aRH1^Uh`0 zj^aL+!OKfO_D=G2{R%r`-tWV_M>701ioY|M_b_<+^STA}cgz9nMD3dbo_>F=32{Gs ziFpr!H*vlJiR*j~y z>Cg(^B76Taf+m5d-=AzbwA?P?U{FHM*BK;V_iNx zn0a@A7xvS}7wy~Nb>`hJ{_aX1r`s_PzBqVD)V|xm>sT@AFTi+w`R!H_?;jcdLh!y= zqY&}hz-v90W#CrK8?*xR&I3=^IS<|vYcua$@X8k@?-MqlA4hD# zymP<{R@8X#r~Ih?mcZ+3OY$7}>%SxWI~zQ`zm4$s;Zw{zD}z_JJNI|>ADDM$1}_KR zhd1vV>32p3&sqUG-+Xz*`+Ej2?|}C`^Zo{2!>IUczWD=#N7n`HUzI% zT#Vc1;0*$=^|j=mXdK}-ZJ3n{cu-c{g$J0 zHE#XE)B7aJ$QOQeDt^9|8d+Ozs&fZGyV4`<6%h{>{9%GTPS&UEZZ~rQe(2>FsNV&L4u;4qmTu8-TcL zy&tvjQSfwK3W)nS{5=Am9=D9~cm}+i!Rrlm)=>h zufg`GHd_8pM4Z%HMZNz)zC7Zj-XzYWs}MHn$s18y(G zNk44#W1rdWU99Nn0$%TGI<5W^|J3ujNkQuTOM)JzV7WM zy04ptqh14X(!LPJWo5)Ihq%&Z+`a)-?$%Je!Psh zUgP#(wC{Aly@WVvUlRFVMZGT~PTH43+#86q5hwFLjkw8c&TQFtH{yEPw_c!?&(lW( zZZhJeeOWx7-h+B4Ax_$tLA?(m?k>d1ymxROO}-oSUWT|{_FawfdlGP$B2L<8k8Hkg5yEcP-Ss8K5Ax_ToCi*dX zr{7xs4nbTm`<8<1tLftaHy7fheI?A70O}o#xL)?{0`|?1xNl}^j?eF4p56_5ry)-2 z4WPf@&Tj9{)2|UH^#)My4~T0ZP99&%=*Q&Ivs!VPia0sXEgX;c_Xpf-i0c)<4{&_5 zfO{2j(vK4IRcE(%`|%3mq#tF(y^Xm05Z6oZC#bgqdhbP?)LTJ+A3(l)5GVBpF@BFA zu7o&wT(gny?$Lj=;x`F#^8H6)2Y7yP>+fByM{|Ue&v%2HLB8Dl2jK3|@RgA7`7v{} z_-;mA_#Sx9HKaSJv;P&(hIKcu#{hQ~;(}$s(K_zPG`OBIx8pczUmW8yd@Y@PSM!cbq>bQ0^Bhg z`$9Ls{fK!d$4UEA6u(J;J6dC3itPIZa4C&_VY06YxP3MDS>Iy(W^tUfFGKeI0l2Xm z`?6%;o^!VHZzql3@(j>xCjhs-hOdtKeD0lq+f2ika)2*)7vMJ4@P!Y@{F@56bu@hD zO)zeD18{32PF|PTm{*fF7}WB24aCX!?8W2YdHb{t0k=BhlE3rk{8c<|bn|r2)720s zuXAdMn{*}cnHs$n(t8!)Mr!od(2s7OZoR`1*Xwvi=Y8o%9mltur`wO;5hwkKk{{;*-}i`< zel&MNKXQO`5GSvP3gpK_fSZoEUVfYc<1x=8fcpk<(hmd2qnoGOj|SqTA0^7GslfLU z;-nwRJ7``4?nA`M>z4-R^W??nYK?CVang^j6`4ZX*&#PmAZy&_T zd@=u|@deyo8ov4w$afy#cGU1?XVGyDaNBA4!erkIfQxGQVkaY?4Y<*Wljr?<&v^@Q z8zWA}*}&uEv|j$4CB1)=IM^}hKQ5r{RZjXbM^wd+5gtl=uP7IPTLD`>uU4{ zV{l*5&C|`d7UJai#wdR00pAG3$?>g@$Mb#;a4R8Bp7%qjchW`Z3Rv zfSV6-(vJw{K{rpgA9Ev4`jH_&#sJ@+KfrZ_^dmY4`Vj-%ABdCZ{Vx2zZ1M!a{fap0 zN7t!%zB~zVO~gq*0?60R)9uGkh?9QUbl$%W_@*IF`r(it7T~@{oILNFmBd2 zlYT_$`sIDVeStXXM;Q6KdAj}h6milIi^gNYDIC(9zR(HeFW^qq@EOGS5a7}pzEm3d%78mc!xtgGp$oM9O=|e6#1{bE z{)m(3!5HS%t0MuoAL8VBD}={`SFZ%z-WvPrbUb($a64-3%ToMmfZG9a@;qaZ-l4-< z{%)($8>hI80o*8!UYqhX2DnWSC(jEe>V0hj;5O9g%}_o+1h~~SdK=_#8E~s2P9Dd@ zq<1RdOpV?w`8zV$ipx?Oz3~Z{S0><=M4UYC#xW0G+Y@k$YxL&H-zxz(k4CRG9`zOg zH#g#X9VgM>DK7wSh(@o4dbggnP|IJ!$>&^AJpXR_JKzRs_zD!i4Hj-qTS z@O=Ep-AA=>ZzE1V9}mr5xZC~SzBaqP`}qGB;^g!3)L_7Ugt(^=mtPtDTe!RP?0=aT zS8VaU_@7N%dM9ge;q4K3GvKb);F3Ea?tZ}KG`ReZhfa>)Hb1 zNBL5~vb7)J4nv&GgVe5YKAJxF4lTYE;^ca71J|=2``eB!+@Xl;wcdL!7~g3d?$p8^ ztkE0X4fL+|dZLBf196dU!4HZ{9pe)D9&lSCE;$x(3t{|>@hi3B)XmdfwHe~%^-C1> z?tr+B5tkG1Kk_&)cSPLkhzsq^?Mst=bL`dfV=2T*`|1~fece3W_Jt59?MtA2!x6U- z;-r1q3*r63N{H)1TxLtSzoNLLF9f|CEeQ5abMSd0#&7nr1NfJO<7qcfcg0l1N&6f; zPX02xy&Lx_;-q~Qj9(LRb;5~tEk(@dRqg@%K0%zEM;7A#J><|9}tq!>6wj39I3gX;SI{UvY@=ba9 z=oa4x$X612^N1UT-#HL2@G3m#>ES~^P98h1#rM93uZnS*ygdO#!SOBJ8;ElXeB5ft_ehcBl9&f%UmbDdqQ|xPUPr$Cm7K4ExCirqt0FEUacJK| z@#9;3QxI1bemIDGunM@>5Z4fV4(csuPiXPIin!QS+`cB_9;*ZH6~skFT)Kuro<3Zi z(BgX;aZSmG_B|fXv~VvWP9Dbt$T#hJz`cMtc|7P!z;XPm5hu3zp4H$&h&vLMcmdl;P%tt z!mGn~PtR|CYRiwkHMk_=zS;|Lam2~|Gv0%IX^aKj4jR4$`FkGVw$h=&S?32 zgW#j%ZuCdYzrldJPQw?N1^#}u0pKPIKFXIOj&CCZxQjJ>DH@OQfICCO7og{?#{up% z4PO}Jck2s)%OFnfx8&e;`+YXY$>$6fULS1vGT@Ha=#A01{Rp^m8okE3a6j|rOpcR! z%c%F@UjTQcMz4Y6@%;ERTjP5O;wrd)ZT4kV>t7u8esUb(4$|-?$&W#2wfOec@MVc_ zFyO{&__8>@L&gAZPsGXl^8(`TirmoByPJkDgZ7QM7I3>FPF~klF@AS60TO%Nx~zv*Y;ddPg0``ug zPcj8?8*22%F<(Zkc2mpWbu|9g(cg7e2b_sGvjpcyI&K7;aNKxzO^%cH8MIHwI)GbA zV_ya1a_iB6TS0@X{|k@1CBQ9?I2pgtuXtR$2XKpM_)3_6Bj&rg6_>d+d^Yl#LBI{s z@TCs{`$pUaxLM!v^D4#9oCWrolK|I5oIJ0laNN!vc1z2?pES4{#&7F1;C|5HGKYeF zw@v}v3=Phq@i1;}>HPw6GR~1dzz=JAj+1%N6@Wawc}2i|s?nRJJUs<)?`ZTkP_KC^ z$4R{b)I0oiz`d!_8#o%zZ!-XAYxKtOcX}EQ;GWa)*_2oN+}4WUBN{$?N0?XUzJPm3 z!)KsCbR{-2e8ouyQ@FVvb$4R~j z@qGcfaT>l{1CQeu-r2H`aFVZS;Bow7z#WNv@^}!(aXUABSBviejoy3!{aB0Rq}~|$ zu@2z&(D2!-!n&ovXB;Q_;>b7n3&3rs;fu`!_QlSe)bfLHk}rXLTb>QLsD{tN--$9; zo800foaBq(`DpkWfLl+)*EJv5XHMrh$(Ka?hJWXdOCj#r?AI;#iGW*F*f$I=JG<%=;eC(!;XN%r z!b!duj>i`t11=!==)NL~??cUT_qOC*a~+S*xBkg-(!SY` z>)`ro(0whvKWX?%7{4Jwj+1-^eC~brB7plr!&jj5;PxEXix0=+<~ZPHX!vZ(t5-Nq z@)gm(o2!7EuHh?@ebYHk@|DRx2XJ3&`08ZeCil1EOgPDB6JHc?UupQ7#5e4L7T9~Lz8vvA2Dq&>eCFlI_c-7-*YKGbzeAQUxBMNg!PP0B z4*=XI8eEk4CIW6l4X%lNU)2G(z6O_~yjuF$F(h!kGA}nOQSc9{%-vV;O5leg1^JOJY>1YT6}*^hwBn~y-~(- zJ9iw%N&5PXNZ&QX-eqFLd#cLe4iptKCdey?)*I9-a%Yf0OmD~Z|MTK|2X!!XIgxO3#k1UeDuM4%IaP6Rp;=tQ6sfldTE5$Hsq6M;?yIuYnZpc8>k1UeDuM4%IaP6Rp; z=tQ6sfldTE5$Hsq6M;?yIuYnZpc8>k1UeDuM4%IaP6Rp;=tQ6sfldTE5$Hsq6M;?y zIuYnZpc8>k1UeDuM4%IaP6Rp;=tQ6sfldTE5$Hsq6M;?yIuYnZpc8>k1UeDuM4%Ia zP6Rp;=tQ6sfldTE5$Hsq6M;?yIuYnZpc8>k1UeDuM4%IaP6Rp;=tQ6sfldVee~du# z0r>q6@~w6W{O&E4Nv76--*-tq2ftHNIRkK^GeKsSV}_7ks8+7G$=qw5!3uy6fzd{mzvX|#UdiOR;F z>Nrrlm#l6AzYpz&%gzgWvZDZ>UzOY8)qkMc3y<-*MivHpqEWRUsi!zzXGh{Q_c&Vb z@b=PTJg=(_UZatxA_}4>qB)si8nPC{Ez+!emNWX z+5Vc+}w`b6wqsa3icPysh*_$7;i7^4fZzf;Pr$jS>1kM#yS5f z=qbDcvg9+5>!0)dtj@*DfgHr8a6a(nzu@iUM_`zH{0P^sG}7+zBR-?d^M>jNT87pJ zKciQw^NRF2r@*+z?@*6#a|-l#_E5)@ct|E*2YhBGk4NMyu*Z2HctTroyW;;=>nC24 z^`jtu$wU91aV$Op_En~Fe+!Scr>}ZLdwBAXq`5D~aefiU{dwHd`+=VDe!QM|qCctQ zTD;ZWzU1TJe{&8suKX3Zi}aDq{J`)3tgFDj=9k>g#^Jn7{dF>Y8R)gYRof-|#dq?D zqkh#feB7y?WM~k#x6$Q3pDSmBy_t_eCgoCmt9Sr$LSs2^Dulmj91}7j-%f(O^WkDcxR6Dva_%4 z@t4*9{ZnM zH+E6$HMRkN%p?8TPkQ{y!kucpe)|(Hf!FofwfJ#@+DXR#1b;&J^W%Z}Z})z-xK2#{ z(4O6?7r8#Nhh+K`(4X1_?4x>;UFX{LCq5$ZQzH#K%Fl%W~-rf4s7vESLW49+$x9?)f13WZ4n-W5u!D&-Bs|XX6ZBFL|OnsK-O% z!uvy98tZ^xwP!hR{&^@H?}2piI@x+2`XyiHc*!5%m&c>NB+oyIr*h>dK3?^hd)%p? zUl~mTUna%%`0YPjGFH=7$GrPEttHe{ejQrt?xc{jSVO-;9`HOP}@xXdDBbsJc-}P+nY;*{ecGOE#C~d#7!KZ#{0qAa@?-qEgVO7IV*Ess_&~z zb#XoM&-nAH(vRFJi_2$k|=TB*As87wWwyQQ(-7kLy$HxsQ=Nf=_c89Vv zP2E2{iuX@`!Q-3$3d+%OF#dLtAK#19IX<|6dOV6l+^^RuetBDMC$;OO`4rb1*`C|k zNI@Ps#{hp+tY@jN%=0^X7~rj=czksFgS)Hkj()^>Ym<4I_!>+4i%+b<{i6N_kN0ha z^DC2sK~Ho?wY@r?;!f@1B~SVybsQy5S9XH#aST2K{3(>g6Z#RxJM#MheEn+ocEU+nEWq(G`yLx8rsO?{wEw zljoHW-SJ+2HRe>uxq|CA1M~6oO;$WN@#6PtkDmtm6Q^@KGQaY;)ED*Vr?~*n!>H5V zc#yr;s^E8KCGJ19d&%^#+}<)iFDre??bGqpaQ(5az1{lqX6||`U-IiF;;$X%FMgSO zfj{DNopfx1IXY)wCG z&l!Av%Kl#E(m2pxJlUPc#&wWhe16+=&vAW)xxtRW+iHKE2FH`0;z&MUs6H?q@R@DZ z{Rk&z7VigRH^6vS@H>RY4{Dy&mVDk6H1~s~r~Dq|OBm-r)u*#+erhKfKLYG(EXMJP zw|LxQ_&lQdJH$1yH*Y6CFB#v8>(SvIydO&$Fdp`y>bx#*5B3vJW(B|p45%+0$@>LX zQIBus7{D2;LwhXCd5Pb4`1zRX2Ub%e4brtE0j!++GsNEjN^P+jAKfluWeWX)>{4|U1c}n_9O^l-r zddfSi^VgZ=&ko{EFV6j-`rvJ9p6XaNp8Dxz`8sZId>M6oyIL9aD4FqHE-=W_xWo)!gLf$HBf!Js)(uUiHSJ-2cok;73xtHw^p&dTZ}<{i(;*b_el#uX!=>Wmo2Y zc-b}3?TtO#)1SOm?N=hl{SU3j<5xYmy>TBXKbvE@T{_;%5 zcIt0FsOC+dr{lXEr z;P-j~To0DP@7?m#;CvB24E(imy|m6Q>s!DV>AQ{wKi`z*<#8jP;34YqrFN3Z72R?1 z&D8uAaU5xU(B6C{{Ujrss`XI2lvRB0+kB|K`D=gDo*t=JSI%$9^DX_fd%hA+tg4QG zdQE?JMh=9yH(zZp4n;$)m+b1VY+S?Rq2tT!5BAr_sQt}+1ND)Kz-No&cVmp&?*_(2 z>NWBDqKWfKwpZ_0+aYmOPHNVt1;ly;!s}!zrJg^*)716p!+3pSq&nWte2|A}+=oW$ z4}H&%C$c>+)_2QxDp&D25tY4U0qr7OL+lHXN~--Kd~6)|pXvjTsPm!Z@mzrVle8`b zp29tR9v5zGFF%N{ztVYw+tFV>>K~g4ytcT0r}k_V+M8c<{nd#3`JDPonO_mcHNCaJ z<4;Abb4?t>$2~P3%DG#C*QoRH$>BQu&;go!dQ5Fc2%oc%{ps(x|4ngUOgJgigMq({ z*WlV` zdzKR7L!a|;ApY>K?tTz1ir=kJnPhrX&KqA=?N4oO7|#@5ms|K=ig=`~tPk_VS)KDI z8p!jgT94!je2sbJvCoF=*Vl4Id?%SWUyRq0JRchs?niW9-rlwy!`thh_t=kv^d~lI zkC*!CWORnVyrce!iy%&+C)E9FZ}9VRJYd@ug;}d8plZ8vHdE2AM@k?cqhB zJ|n(ksGSFP*0G)NUNR`&a|goi@wQgxdE>>O9}52Feueqqg-_u7SHe~BxjB`+WGRC4 zPV=5j*S~=4S9R^tx!|}E8ld;Sf#V@h^1r#q#mK^Vq{V&^f%U+i;-1jIhWGEy$?o|@ z{u%rD!-epB)gpe+8efYaSBOu_!WKOL>nmWt<=yob@qJjGcfg!48R;&~C@)cyV?pm`ri z`jWU#uZqtvsQ#apwSszH_SKH^Njz@mPdskKTbUDZfi>D2C+e@0(FN7|ba<*SuG6=E z)Za@Mzv6y|MZU#%=lbJQIX+h7?W8ZVGT`jx)aSwM^6Gl(|98p4Tkd+T*SJ3pt}i2d zG8^+es)TsidXM*~e(lQoO>i8I+>FOlB#7R^%aXU?(N6fR=DDPKG>=c?0`RXsH`f~; z$8p5lu1tq{K6&*Ip5NYaA#SPh>HGM&>GTH0`lJkgCukp|?jLD$oqbfSuWD+(%PKDe z@eUlz$ARq5hY$i_mYiG-19hj0oda##m_gzrFmKEDd7EqtfzA1#`f|db0E*d z(DI-^j_WlFxPB()VHfH5E0YJq_~(CB=RxixZWr+ukLC4=J=AfIm;A-Syou*`Hm>F) z{gGQZp6Ye7ngM&OJ8@ns!R-sJz}rpDe)6OzyfNUNK~}^_$3}yk3Zq1OmBg_m-9R*uJ3MF@^`g8lHXb$cpQ8lXltIwP`~UE7}pQMk2v5znG&QztV$zd~|k3e&WxybU0aGs`GfIaX(2L zzi%ge9^W4)Ug7rS)`$M_@w}e;#qc|@u7&yW*ueXl`U~oQ)ZedcpnVb_9K!vh_WHZ( zcvHKVtcmNB{Ml+fUOckhz2SC@8miF~H^xL9Xg^!RQyxee$u&v&<% z_?>G3pAYi5Pvb z<3~Is?cwh2g!{iHYxsV;zjj6Dg?Q!e=5fp8_!ZXjH;%^fd|YDqK1JH+Tmrb-2^=qR z<_0{UsJ$eTP^W&1KxgRthaQ8>*k!5>Fu1B_O%lCudNso0S z#W~!^Gam4#-}Jb?D&C{klimyXvzqn9TK_~tNPLHE-J*_r@E2}JVh}G2+OG0M;0f%h zjze^Db$)gI+PC`^(x1fp=j?*$$6jiG2%pE_d!TZ2dv`qHNTwf#dEj)Z;}O~i_^P}3 zSS6g7fF@QuC#8T~=W@pZCP8lS$lvy0(!z z4|M$os=n#*{dc>1N-OaA#Bg7n2JT-V`O5F8^E@WLr>A~_Q+XZ*{>AkX&Pzsy`8#jw zc#^xQ?bhMjtq+Uu!rJXG@%apoTfE8hysUXX6O6ctmBqf5p_Mp3{W*+FWEakxKN{+DVn6T*?)MhEO+B6#{+>;G8+Ci& z0bXz6etPA7d3^-;BdgcBT{14RT)_R+WPN5Ch<9c@_+NaOkCTD>@ukH5X9?G(R5bgy zN9=@Z%XV2V4RIfb;26-G!FW|`{_K!?yvntM)OLh%A4#wNUhP5rJ)-8b z5FZ=go9X&lxSvP$FFqc@d3ibejym2pt~1J9&&OM*uPOFt$6@RVM<)%R_n*meU}p}$lhyInai5Wpn1@k(U!K{W$3w?M z^|d`XK2+o7-~;M$i)o&Zl*IeUQke5OMK~@6PvH5H)ckG~+1Xzi+DM%TetFCHtK;Ce zfBq642iecktP4-?tj^2GqF_(`^7j0y9m(yeX`Z)A`$D_%e(^W`#iJWm(9F zfXDaQgts)`D>Yu{b`m}>?%TTF@@GHwCt2H@pYL-!L%BMd>#b|nkEb{1*9F8Yr6JZ6 z%62Lj!+ai5y-tQS`J}@qzX$)4_&tcx$L}DEAE@(Kr&m{R-3#N^SV-hOez%gvbpTbL zzyFl42_BtdQQw@%$6GZ2PjQ-io|P7X_@?lEeRa?F#`Av^@xMaXs{IPz5BhRTf~-{l z7k?b=44>uGFRrdDsQEoW0qZGR6LB2HzW9+1-TklNet*G^Q!bYf9@#z$#QD%_Kru<7v0B8^7pqK#r3H{&F{wq=HlZR6Z`8} z8}j%Rrt)&v*1W&8H?+vW`kTV%Bc#W~eZTB;AYZEDcWDUMcp2J5VqJAn^IVnswJW3e zJLi7;W!4|q_=NGfVBvK4d8V_khR?mJy*LzjlDIxRjQ2O0-`vNY`X_(m^T`bG{E4pM zk0&*X>v?tUe(NiDf}MqN?)FMP^E9>n5=Z5R zcpgsmk!4{#(s;jWY0hhbpLyPvMVa_W+D(q9dXlBv!QWI&?ROEsyEE`TN)=^oa~PlO zvhMu#%iQOG{}AGw9jVU$l=!{*hS+bO zcrDF$kJL^wgU=!9>d(CF)xUZ#_>q~!?XHRMnJePHGtuQwPwsFSkHFoaC)f1XkL(WO z?@mzJOXj=4k8~Fthr;6bNOk?IwtHSSPvzri{ienn7*Cy^uKhTV7N==wuBy)O`YY~n zb(V$p0Isi-^fB5$<^Z){gs*%7_BS-&i4rb~_k+gCYQEBZ;74;awLiq8lh$+G-%5}l z*Uc$BpLINb>+J=&K3%_n_`W7x<;R`OHr!4fPZRgu$<5>LM*{B$B~Nlo9#{J(us>M= zzQzOUagjW_a?{}aT`!2Tt|Qi$KXv!ZqkFIB$hPh2Pp%LCm$%{bF}IQWJxB9Nj*|v7 zCPI697RdNP!k%NfzcwD9h$mw5{0fWj3RC!=iSUh$!OpCB50?2C_?7m!A0!@+n zTo+qwg8k*I`j*B??xAKAAO1c z-!8|*I;?@Rr@SLS&Pd+)J20-YzNh>L?_U!8P4?i#AIWRf`DmKje7m^W#(wlzC5l&N*v}sK2{3aOX9w_vAa6{(%!&b?)-$0 zZx7>^8VT_(Xx1lM8GqwTynU7RJGmb7dR`{p1U?6)azXPxpz$d`-Vt6Wqj*1<6Z_j{ zHP4N$72)_-enV|1>8a<`cBGH>H=e{pvNpn9AK?;P4eaqb{5JO^bR6d|;_vj4ev;Oe z(65pPyCXOcLN9VZYNH??&Br(|@%WX7$9K{?p8Wj&=8dj@yY;aH`S{mv^yhcv2;Q&y zgZuSDstNPk#NRO~i2ac(Yq{$+aDOS|GCp4EH+Vjf{~2759r{XbS8;y#^E~nBWb_Yi zZ*4U`ZixkX*}~(TSMUS zVEj@%FD=2xGimej@N0J&-{<$4B-r?#1VyZ2!B;LGeDiT|JpEATEKAxZi$x zieem_$NGyG@n>J=dSi3Ck5g?<^>K{&yktRqhZJo>epJLhU0I*kyOnqNxCaj8d7b-= z`zP&73cPHma!qqzk{+s#S78x;Ja437T!I6%o|NpW4(0w+y_BZMIuMDca#8cW5Va4K zOuYheOx?)yw}kt2kRC(+e#;y@&V(!D^YW_1BcS;>=(Cnkk00^Grn?{C>(4>|m{=EI z{|ov#$6(cEv+U;hUB8*RQHr2bMCt_FLv$3fhRA@08=zNeS{sT>pQ zg%hLH_7lFCd6{q|&0W>wO6^`Ufa~Z8*W6jHFZ#Co_)>qJOwR}7)0_!$Y?}P| zQ`G!!TzYRfE`@PFQUYv`&pgu&K5kLk$*$J)?QcR^ON|vJLmKKCi|rfiSLdACh#|}0sT3T_uj;3{i3#u z+6(gc!}kIH#I1OI+YRgu>3$DQ>{CU&B=eempwpJWyda+NWA1(sF01)H0BR>$xR3MM zI{&DHkRf~yXIFuuBUh} zFB2}fs{3_p=})zv)Zedc;&(dMfB1OG{*?tlpM~!~9I-AxhTpSAD*onQGV88S>X+r( zzahVyn&VpHJ~-ag${?+mxxVsF>i9)hf%?jM>UOdtyDmSTrE~6h>Q{MJJ>Dhp{Yhpw z;EychK96I2Kzr~B&~F}~<|q9m^J95DsNTkX!l>*e!+74Uy#?bQo=@=R)p1Fj?d})p zjaU8Qa(Ep|{d&pO)pqp4X)2t{{pB@v4}axv9BQxeJZjwK&tK9bW%iD~^>^ZY+{$h4 ztB?@;ky-dWx%!Mc4)K$@-_DL|9Ql_x*x&eBecUIbOV}UA@5oC#yW2(fmG|fIi}-vm zn%J20=N92{A%2|*{0cL7qjPYfrD_vsd>wuYz;A>nT6&?oSoJ zPpd7!^%=iIzxw%n-c*)y*C+j;a!#|Zxq;v35KhX-9blJrAlOle@VtT@=GXPh zeg^nDejnZ#p|(TU->W|Sx!N8liTUC4xijghAIS5`IggK9bUn2`>hD)pu2u7-mjiwI z-8}NuLs3|>ZXr5^$3KDB$5Ff=j4dwa^XA-+^zGd4*zugt!z^uc5Z4boBh`F`hq+!! z6gi&TDck#7jxI0af`q|@+TP&4YP?@Nj9>fL->;r_alx59&gsv%o#orqf8> z-rRQX@hPv){mJ5eujG~Gpjc-w+hsZO1s+$P;r2;f5cf%?`W#-5P&t}+_rE0Wi=C4= zK6?=4cQvH8BPZ71k>1GRJWf>KUs>P3z4;y%--RW&SNoC0=ScyN@0rQ|jM$f`u(^BQ zP(Qyi7gpOT`ljQMTp1}Eh_Y=UT&*M;d>Gtv{rdh`q8s$DdW%*sx z_v-Uo>`SmGzp{HC*2MelEbezeVMuHCqoQ__#=lX|qoCK&>}Ob^{TDR%gDH=FsDrD) zxF$9CQ)G{ng)WF|w8!Cln( zl%es$-y8Art6_8fUU+IxO;hJzP4hb@iCKK!*3RJemtN<7XKv?Z((CNN`%yi~$k*-p z)9{I}czlOL`bpZy^Ya+hldONIjvuv4+5C(1<>qM5&#q(K<3{>&@B70MUMCY*gMX#H zfiLwsAOGB@-2dp8P>$ky5FM|qH%{X`vi+YbM^@wGLwXBGsPmZGb+URR@TKtgX6z@q zpSe}l`a*4fAF0zX>mzUa%eT@u+^*zhF#g5wx&76NcpN+n+8ZcIZ$YyTh}w(iw3nxe zW4T?#Lo)Q8dwUY!&qwinx^uKY{nZONE;WLe%R~LemF$!!vkxQcw<yI!uwHu^ij~C+*xf0;YeB=sClUUe@lkH zRmV9~85nz`d-Hrt-tRA7x_C4fb+;?NvU>b=eAN};Jxinn#~%lO-#)tru5-clP_lm- z_bD%nbe;Q$Y-=n#Ysv(~2up??eOX5DO^evA+_1DSd zcYrSr=Kb;q@$*L(_oL7F{7zq|&k)~NI4AHp$$kcom#pu4k;l7NyQU&3_T@0%2K{9* zUYhP*<~#28Qa|%g^?iHbIrTVFKPj_fe`DGHca`Jw`18}R{z%e&9;X*Z z$1%L0F1LAJF>oKH0zQYV59RTcb|vO+Z+v8bzvUEu|C2hx-*_}G>DzoOegxxIUy#ou zI}d(VHSYy=egv;q=RpInGj;tMxUWL?1m54A3jUYcyw0g;>>&N+Z@3<+Cu!34ELHSV zX2o~L)s=X>b@b+N7>C;Y?VX3Jzx6F2$d1eyJ`W1=e()Y>FVD$w5&UkEc%&?9zN?Zr zT{#fq`gAy1A6*mjsQfaIOYC2~O#SkBUqWRsS$Iu7p6Oj7&zj=9IWNAytKFI(?5W^B zsLec|2j(W+kLcVG?_i4K$iDPe98dNCS7q@`VeiT?uX5sd+NAwCTt8kD>-kIP@O+GT z{BDZm^(q(fcYI>2^Y}*(hP*XS75*S$;XSCYAI975!#EG=Z@$lQRNqVD@5)epazpNa z8Ozy8YCY+V0bdRK)JKYhv^Doh`I#`!GYhHp3!0u{?GJzF*{(bN;gXU5`PZDgfBkzL z6Muv>-=9}L;o~T}^(uz0;Kxk^*L@Xn-+tMl`WoOXx42(FRjUx+n&$qo@ifGxayr*< zmEC!zJ(aQQ_@`b$bQiYhqdAsT}_p`ce7+sw`{=KM0pt%$?7;n~xjyYgbn13fdX4IqqUQcc zjUKpK2frT);`?}FE{X3%sJ_3_I**T|D1L9W{zhhR|(O+DgB|u-==l=Y~J;ZS#!OJ1>yW#fU zyj>Ts#KQdeRK|V!LaPkS@vnBankOW$(}aPI1dn3??aFH2zlrYp;=B--q~?1YYZtY> z));lYUXi*bfO?zac&JAAzqZ=uc`W^ndj2Ga!@MZp&gX|Qo#WGS_q>aEtShOUFfehZ z$c299_QfA@w~zX@Er)Qs8#B0G$rsoRuagdiJh$=pHY%Fme=mvoF8K=L`mDT{KR>hL zz9ak~^fN+WUv>$!Q!4!bq?}B{I0ZE8^vXHN_w)e&J}ZT<_zu5br~1E37IxtCm-JLV z<@NQ?{N)ezj~xvCLk^z@)K1ct`y&0R)|353T~9nDoihLz#P>^7pPuY)M(o|| z5B5tSL!bDwgY=TDW_djAKh^pO?^ot81iNbQasJeBsMqlXX7cvTRXjchUiUaF!11VY zG4R(<;yB_j;Pp~$MSh;9c9JRlomDFLk_U6Us68b1*|x4%+d+7H8(~M0<5Tz@YG5sa zBLX2)_`X(D_Y|F*gxx;(@#rD&_@gSmkBA?|^DtKv`Zatu?YEE57i_%WCwOEj_q;6h z^LJxRpYyo#GS6qSuU%Qk^B46?ug0%$sh(s3-#buQCyfJnJ`pasxqJL-x2XHoZ-;() z@qVSc4a6Zi2OigcQ1ctx`paXoQzt9;x#v;F1bb?q^8CxJ4Ejrh-R-b3{?@+ zLRs(b|N8~7wLHb=u{C$(gT)=BT#mA-K^*zReV1MCOo{wc*2TS@% z#&DnL_=|wA?+kh~;&~n6y=3hNb^K(%NSWtlXd1*Tw}QX^l5fDuTk&`kZ%A`L7+wyP>tudiz*lCt&j($9Szla)$Empu z94`~U^6R3?iBK>5o7;lFv8SOud=9s({4w`0i~E&I9$9YQ&Us`zl?$5piqxLMef26R zsoox<9;Y1c6Kwe0*FU_tKRZcpBLw*1oILK-PO`BLv{$C9?JOM!Jh34#PYc@u-uZ@) zTkuO>CVrBQ=hXbvo)h;oRPR@s)489c3cN$k*JL{_-Gz&#TQj;kZ-2gWDB;QmvoV^;Ozgt|wuEy>+pl zMC1c^Kl0cfe}K=^<^+HFQNs5nef5L-WuNEzseYhkW?>$;{_@v;bB{0a*CqijH_IQM z`VEw{Jl1J7Zh-MluIGN8oAcU_YZZ0A$A?4QQ=7T-OMk81fiLzIKVC?jEH^dy@UuMr z&CB|hcln9DUvojVU-|w0%_C`lVr|YZ+q;_T_A0(NFvagtQvbvNuWv~j>hUIhB;#kh zkDvXp+8^p)JsI>QHNSIfK7->rnvX+%2lafn=5p6ZdJD_K_(gvc*}t#l)FglY6Th(q#5MJn`#6>#0^Y(Vd>n|UzcP9>pTGU(OKHBJ?Zu1xgw=Kt zd4NEBRC{)X@cbS7vAur1?DAP*;(cZfe}A|BfqGs9kLLN9T}th5SUew%J^|w%d&AwI zz+iQI^J8w0xwJaZ@^^82YNOSB@k^k8d;!i&;R@WtdAd#kp8Qpuuegf95dq5N&w#IC zoC2Gu_2qZ+H{bGibNxbHPqDHAAE%xM{G*QR!DT&_>v( zxZht>|Ju9i@pTph|BHAZ7R2{awL#q9{FXePR>)u6NPk~t4dWDF(Oq9~Q8@l(@qJ?j z%R0SDvCh1{k^Av8Df1VJ8z-pas?(eDu&Y-;d|%Y7-e-k52J$M3<1D-7H-T|BH^=kH zC@en#GPWs51NYI1;B%qWZNO`dhW4%~N}-_X@Vrhv;U2Hjy6)pZ^r<`C^MP<)GI}Am zkMO4E_eX01cfAF9-9m(Yl+`VHTno7FBC`{(?<0Lrx7Zf$e)Ry`{3E|U@P@^Hkh#eo z`c{K+$-k-|9|!kcE=M6>3a@j%zbjjECB<~-J`5W)b z7{KL6xcgDU@3y60E6(-Gb}EN(|IlKa_k&%U`@z_$d^{67s`Jha^5avw=r1m0cOHMw z&%Bh!C-E>ZM^5JU*oXUz3+W-5(A-B;d-_Mvn_CF{ZDiE`)ZYMm(#Ju2=mu_&J&4DJ z_{|g4eAF&wW=Y^NG`~+I@l?+33HB86elKvV+Me>sd|a)WU|(_#s1Lr#+lfDMD)%>q zzdu3kB=d)>^-{Z(Ma^?9iKBA;P@X4L?~b!+$h zEdQpyzYJvhmUrc05Qh~0ZWGy66Z`2iAN-PMUZ>Sa=uXc^RL##Vw&6DnK05 zD2dMy>%^&^WJaumq56T6hWH(zrqAC!isJl^i|-&4xX#5n1pLiE)3>;K`B%dCfnGRj zkB{JaO!e)`UN6B{E<2Vr*1Nmd&`)}F5-E#Tgz}LJQ{lMqH z=2qMv9dCY7=qK9?n)`o=>uWi=g8Okq$D8-Lo=VsM@2Zbp3;9?;8CnR&CI2`cCmJvw z)*z@SI~v$d<-c3ja6jnSZeUN~O+KHEonc%m_xc+jQ#^04tO5OkXS6pzb2HWF4ZraS zz0Lio&f)L5P-3b-KgkZuXb&G=kmGZExyL1W1#d4t#^+~g4)D|5o!66nBx84}=YI|F z8{)YBJpG_M5Ak`)_zbl^>K8o{><+EN^Pk$=l@;+FiDB@#g+{9V3U9;ng!D%6y+uvL z)maozmUcGiW~C&WM9(nzRYK+{U)Bm z<={`~ba$MM?Xi==9{X~@XEA@Q*TLUp&Yg$!I=Fuam31Rs;s7B6t;4T=4PEsx)mBRfbYo(29G`cL(J zmEj>g-nDPJzmm7KF~l$YC&WD`p3_QvPx-%GPfxwiKhpTTu(1Z{&EWT<&8xuPz~kzy6sI)cKb3_%2N9ui$qT}{7JjcIs{34w%>!{N zY~Vf*ycC$4_tyDg>hpGOP4&DgF3QI(c|GK3rVLVNN9iKY7g&k=6FNnmuek-(_DMa) zGhBcDC9Y56+b-k#-{eH@e_HI{K)jVrz`rV*8vk>eght7s*ilyw|K{PUw~iL-T3%f znstJybJh8k5c}hH1^Dr^EY?XR-c_Gp$*zHt&MFY6ux4GmPEQ@jyM*tX3qHT&)A3P# z;(nfQx%GJ5gSa09;iZh>ciuI8zhpfDe3dQvxEOQc{Cb+}lYD;5@dG)(u3vU8z*!}A zeinUxKULkB>non?&yR*?U4YJBuX^Kp@FRbld%ng`J;?h}ef3c8f9*~+ zj_@QCFSz4!t8=>owmY79Nha`pZ24Ywzr6UpL>uqVW8(Ua`25QH`s(qodR+eze{)AZ z&!T6l?I(QwV2D%W5#FyJhVzk`;Bjnd_D3K-DbsoNc}?Pa%6LCW<(g*yDf2wwb$;M> z_w)<#<8tOG@FVMSKS=#a+M4TTYVVPQ)OPf=d;F1Hh{xFj-qT#3uFjVpK%0Lg`gvd5 zrn(+@{d9gD2+e_c6N9)ogVgaUZ>)}c=pr?~M`4?PWbk|SDjp|g_xe0I4&pnCC_Yci zjpY8x{<^Y*_Z9V5)$=%ZW_!H3%K`5^(_X)V=KD{b-Mab`?pLd8r~2B9{J4>vU+q8P zb+VX&e(^_n|HyB=Ec;vQa{aR1Z#i}=+S zyzr^1{Toj&ermUV;Pb5TBlw?NlgFR%QihjPpHB?U?;AxPf6f_}ft@@ZgVdG&bIHQ#4v=Hd3})P%3%GO9=QsVop$WY)9M}Q|L_G5_c>@VN)52@`Wzmo6qam|F?@zhUBBlY);qxk^X6Cdh+ z{5O2gKWX=&$Jqtk z=X2@{fB8rH{7UN&e|Z$feJhf<-c0g`ukgns`%&3`gZpnC0p-R)Jnn=~z09vW!b7?K z%w>?rP4V6%^eX2oitk#9za+k+D~;swcMj$}(O0&vN3vWDNyW%0X;u;#ie z_$}9GJEr*2h6SD&x5wg){i^ETZ`y z!0h7jB)uf#7jqt}uZjI}%lMo!_8cF7!b_Q2jmM!b_60UyR_jgT`fAB1%f`wO*EHS_ z%62LjSLE>z(f+Cg(8%=FV85{j_d~*Kxc<|)25^CcxnG4#__)dbx^lgN<0iguDXa#3 z!F8eC9?JbAzR-SZz14skPyI-SJ@%h#EDHRwSKZ@7d|opA9Jed_0x!${!B?O?KfQ1I zW54^$DkmU^Dq`29^ViS76uZF)G*6XGLTob29CxaQAlz0}^W%y_K3 z^2?XT@4oW$s>iV`=1KlQ_c%+v&Ov~$reXYZVjr*KOwen+rPeR`s9buxJv{Z(N%Oxj zJ~fp2)qp>DHPlxyFJj;Dag1EU%aXr|_{^OC@;~#rdwio}pOO^*ju7b$UFUDU5WZcR z8wL4Z!u>_4f8HYwg!7V3ai8IZr}pF)V3++l=F{dp4(Z3#@pmqT@pC3~Jn>3dNvL@w z&Z}H;;Jzn6m|vI3ez7&$%k$v;5QmV)U&*g4I}bxVA~*2kn>mg9UpwDDZlN7HUZ?MW zyFNJ|_mk{NPvG-AF7~}8oRI!f zjj!CtC5GQ~G;iQ>p#GlHQuAkUe+1j-x}LIlp6jJIitkkk=M49kM}#L?TUc#BwP%y= z?L9c$?|{njls|hiVqGrvuj~SP50y zOv@v{UTaYvkMj8T=0!k*kG4CzjR3fjXiLEy=If%J}?Bz`TodtL>wXY4QCb)sw93#N%2T?w+4nT(3p_|0$We z6UN6Lpzi{u-64;45fUH%i=U@uyDZ!Id`#AxBY7Ukc3nBVDP9j;0`n=eD9CW$eSX!k zy>^H?Z>q~eoHL6<9!ElIzM{BZi)`$k_f5oSn_zb+%6YSgxyKFT(8_4C_aecN9gy!f1w`aBU?N6nwd@2`sD`D<-oz^9IGZ#=#1Yqvf0yT9Xk_6)V( zq_22t|Hd!)I>aG}-$xiVt}k#Mlp|ul*&H5+GI)JP_Lv2A9+&O|p5$KY@oG%-7mxY@ z+`bwf-$}ntMqXFjrNdKwb~|;yvSxqaxW~S0xgXmbuiBN|U$QGTFN|AsTXj4MC#56s zwZ*tS)nV=Ng*H{khxFE`aQmCzyPtQdAIXHHo~LCz|3&dRZdAO-i{W?j#AAx@L*f&; zUDm!l4&{`)U&PyAnV!buZQ{NOb-WKK9jmq@c)GgY%bw(`+|SU0JPxro_fd;(#Q9R! zbG~|&+Zn*;T(-~m70r8j{~rIAQ|Cqe3w3=@Km4Q8)bI*mGRSd3TyIf2lItn8c^wyd zhxae%c^*`s=5Z8eb>+qLd1|ko#mA$D-rHo`lC-ulwq52?=( z$CncB*H{?B<01RCTTY4f+s&onej$kKhZ57cf7R3Q{s#9w2~Glkvbb+-Aj{)Q_GI=^ z`ikB-M5|aX%!9*Oi-(K-_8{@$+{M zzspHX;dW+{d_L)Tb@c&}r#c+f7k+|xJBM*Qs9nkwt}lum&hhmd)aR}2_3AiEURka# z+_yNS@8Nby-n7TQYZ5VZThuTSIKUBw$+DRIk{3)E^o{!ck?r|gj_?$d$ zRIihPUHtLZzT~*@_q-hV5yuUmvsCf9cVktsr-|#^QfK>%fAbxFT+-R!wNZQi5>Mh% zfBoWDp81G8~#&h1Rpc{$z3 z_uNJh;#0-<@rXpY9JY`+Jp> zJGtkFw*Tuq9_c==R|t#e7NoCo2lyMr?@|*rf5(67AI9HHa@OT`QhN~h)uOVOG{yJs zc~i~n#UtBeAM?B^G}}8)6Q8+v-}+I1FPXvT9RYlPlEB~BrhbvTd4AeowKra+YoULB zPtH?Vo|j1<$zrxWzvH+LIyEPZUvw?^>$_0CJ$|w)brA1Y-;9ql;VSP#oC-mAI|wgj z_9>XZsa4he%Xpn%Y5*>Y`{k5Af^t0rb|wFWc$DyYU-E19aUr%b9*-VU`y=gZB0hQ_ zKTkCFh4@r(AFt4Ppx;Jmj|lz zWOO7SXR1%^td5WIhx@!JiG6BH6M#SXs9F!{BWa4~km)Pbc9@!V0;vG_o4Jtp%WCkX zS1T8Bx4Vq{s79x%$1#t2QpEk{Nl(z?`5D0P*Q4`sy9uw84Y5yDdKl-`^$WiMaf*D$ z^Ce>Qd~;&le`f~A6MueT)H@99uRq3l2q$GsT>ph}f2#C)*k3#sr2aYaJb>zT(prGW zHMAV?H#~mdvF`A3Eq)659|?fJal9XlJp^%ze9!SZdvx`|CH##a^^Zl><3a5tQ9-p+>ce&o=dP5R$CW&a9?P`<$hL=54C6MJ&VuhNYpQU zC$}qs=f?o9Q%P#p<5U0CMBbn3|0x+h3Fc{Yei$!fdw<6jvM>D;*dG)7hLmTx=L_|( z-|s#yg!3yC`+@z1cAsZ?D2QAPc@;afz4$anw|BfDGfLvUSQ&rkklLlRrt$e!(cC`< z7gpO}T3CI3NO}q@^E{0Y;`#_@TYzg$SC4yUV2Ak%k5B4rt|x!5+FsJO(k>G~K&m_e)=@w_ejQ#p5&dz=Utj&fXTclCG>K8gFK zm*?XCQ@dZ8*_p>H@B%MOp8U;VXL(VGPwE0abBt)DCyw3ljUeUz+)+|P4lf4T0SuY~g}!)F3t?pybK%Du_+q9N`d z{p#y4uKXs?$MD+jc6;e-{04k=+}F?xPwh3${wLNZJpUb!eK3fxqPhN|_WYxe?^$tO zLhU4Thw}N}xCQ!^?}qxs0lc01{arG380as0?AOu6?@A*hxP8H$`1oeu<>Rlj+s5~R zx^}V=Rt5IcRckYSwVam*8{{iYVZ7= z*qY<(c-|s@DeJ=_?u8NR_}9dK6|%oqIkJ#?+^AnwbDu`-b_RC&;Q(fJpYI{@;h9=sE2ycshJE%UrHovaQ zj|aZgTD+d{hIr3F^~srhUSzg_{Bw=~yYeD$0=N!1_@LTe;?>FU7Mi$-`)^%;zx6?% z*S&uEN@5>L&wf9<$0r$9kCP`a0%8V?n^EQQ%si={=Sg{gnsc|$uN^vEaeJOugsX^k z>{Q=h85-g*o~eEP;esct<0$QH)Bu;p_XrLAt}G_rqs6ZQy^dymSWtY&YS;MqWHK<$ zg*_my&gR08#nkrJ|K#}*nuX;s=O@2H+o+}9#263@PY37 zNN-X6o=fC$?ib;tEc#rhEc?lFdI)O=56odI!3Xx0gmJ;seZue1Ld7{4-)^YIJ%j930cuqU%G&j+%XWM*~se5Q6O za~A`z@eA-~eup?#alN0!>&lrn-k5$F%7A^lHe0Xz?ElB!o4`kQ zRQJMnj7`KEc>%;?++!P%4aPm=O=j&LsWlST(pGE6GD~i^q}FsZEvctln$b8A+5{72 z1DP#?B&5w2k-Q}00YO=5C%{vd7XbhEt9g^>H ze{-kQ|NFnEPMunA?RBY)N5*Y8{rB$pO+R^W@3Xwbr!{~1F74L;mVUq19dCutx#ib? zR`MHvDt~WU{hqNNnXXu$a+k*2Q}X>SYNxDUtHZteJ=x#J@3UK9ck9W|_v@~YKD6@I zXkJ$5-^p~bXzhR9{D`ze*FM+Ha5%GX(fV($X?dG(aoeByQEuC>y3<`0KlU~4PxH78 zXB6MY(<3q;+0S?Tz4$emPCCw)_8dE_!?XBgT@EdOUGk&k_kC=Cc8HQ=JN3O# z>(l(ogG+Z^G=5#a-yNP+Yo8}ukEO3kyBGdW{$_p~t)of&v->&oY`62LWIV)ondh-k z(e^GMl;4Z4U)1>4zwT_OcG@4x)?@2k4^2F_|GEs1?GOK6|KQI4wOym1*RAy6Y+qX#nnt!0vSJ&fYd^P?}^TvKx=hwcHe6Q<4mKRZa#U5~%KZ_CbX<1HsO}>}D zP3pPV?_x9?>)}iw6bBxwoFpu5NcggR}qV@e` zp6zbD*=--@Ez>wv?LTC`;pbgf5I(rGoUs?{@@w;5`?L4rg*(e-J@)Hv-{#ii+@DK3 zE**38cJpuTMjd}`J?{56Z`A(OX`blX6>i>c{&YM|>bo2N!9HKM=7raG*~gjviBtW8 zf3v&#I(NJ#UbnyS)JCM7=KOx`DBoxOY`6WF-07cr?U|jw!(Ff2`8msBw_wd{VEo~7 zS6{95+uUV7RLxp96s1oiVmxqbmvO`>d1F?8P3*C{JlUSyUwVm>&v^Q#ozu_Cx83D( z`Zsn?A1t5U#rM1A@blf=jq7x{7wmnvenY0S_~g!dt<%1nTfZdpL3v)vVSUDKl03!> z-B)-?iQ3ES%QyS9p^SPv@q#V@FBG zQ&&ZFDDV}I#ollCLD?PmX8JD~L$yGF52?U&VM%@167gSKak_ABD|*=>KW+n>!&iEq+4F2A>%o0!?g4LhY@e4A)#lJ4o{lYKG=eB?Ge|76qJF~xZ(<0Yu|E^p6U!AMUa>jn2f7d@v z`rqM>w+>pb!F=1@yjg}Xo0Rq$`=)$uzrWYtOLWfi_6MZB6A}Ho^?uTW>iyo6+~H&Y z%kR|BJK}EM)^E#j@q4?uvB$aJTYb5V|3z9~(Xi&jtX=Mo$4%>dw3{CMympE9ckD54 zxy-ZO_7_Th`T0u3cy?iz_9DN(o7?wncYI{?8sGYY+rGBkrZxV;&o`+5nSZbT%l_=b z@3mRw`udZkUVSgu`Jg>wT`J4j&D~yh>$eoKzH{+9xBV9Xx5U@qtbcc1FY(>c)Gk;da8^Me$H-()gD|psnh!^&4XZG`# z56tT<$mg|)^(@SfS@W&p|MuYO0ex?fcJJ8Oo1DJ)yUXc~Z%BEpukB{vv$K6|{=@xy z<-_jq?APCw`?Q?em)+$b%j^5Yo$b{2TRXqsWsRe+{?vohKTZ0wUhCFA%C&FkblF_i z`65g0L+01F^z(C{mFbtCucj$K(LQ#yJ{j(=Z_D5O-uf5hcboCOx}9Ipa%=C{n_bQk zfAI;@?u+|8S8eqcce-BuBI&codRA?h^OV^RZLiefJ2$4?=3RRWFTcN6cZ13|o4@&Y zGXByXI^No?dCB}<-{mr1WAAjQo30PL?Z|T2?fYf-`&*yW@3+%_C(LKJaG{K6#@XGV zdRQm#N5BsrX1DFqo#U^M>#3wi`II~S9dB~u8??{zs&(#L=aaR)&V5I_>HjI?ss2f~ zysfj6_fVN<KpqXniv1UgVT3&Ud!9E&W~li zn*YPC@3OT&%u;NB{;%Jz!^Qrv8>9YA{@wQTJEv#nvD@`MX&=UIx9exz{ue&Hzi@2b ztL0?>Udk)bIj-%V#BDwJclH(g3+HA;|4m|5>VNL7?)YPW*R1{P8DEI#r&@ZV)H6OR z<*$5B*R$52FL9R3ZsD_1PsXF%xV5g4d5fQRmn-qx-8jGZ!@3Kf(&4OI?XtG6y`?|) ze~tJnf3&l`n7>K;S{J^d?YAB=E}UJGdUSl#ZSU13x4&z&j-~C{I{kLg_zdgOLGu*X zXk29ZYAvV3>VIMWgLTtyamQns&MmBc$sMkmHBVx%{x3e?onJd1<<=ugZkE>DCTM>6 z(sepM`X12vr|o8G_dZ(xn)n;d+x`iuN5?MtY4v?t-Uf}AEqzM+lm42t&stgYRtT?s zTRu-bNB*|Mw@Uk2ZqawDY>hK5FKK^Qk4yb+IZawewmB^AI(GHW@7Z#8``x7Y+DNXdYklh za-QRUJxp|Idu~|cIGaCYzfF`L&BszYwe}B<;{ULC^9G$>S7@E=#uH>diIRUVq3yC} z?f=b~pL}p~&ShkN*r0V1ZTIb*&)WW2=C97H zWVukwx!;dHozmOCxyz@*DXC9Xc%$(8N3|W!Q9nZbC$&H6#?JOxq37+d(*75wNRM60 z-!kp*)c0%d@OEywan`^7Ew>%`dHPlE_xrvk@y65i@AbDyoaHoMB<;HVW&OMSYKb$S z-M)*Ye#>+6H}lpW*jWzq*j=M_2K;+Bci~rLxK@5g>(Mc(-S%h6=ex<{=Y2FUfq#26 zuVHOO%iFkqZ*m(np0V(II-S*=aJJv4-z$*2^)fAg`SDVp!WZOw9S^c!u3@b+we^hpz4!?C_pg4~ zjjs+#yR+Pm|K+wTKYy_9xm9hia}oQ^BqGj{DSybV=Wcow9{=Fpi;`QvOqTQOzboUP z-&=X2+uts0KX2x<+pyMeF>br<6^l`^*32w$pC!+0WDeqV2KvT(@1;tbG&OrrqVq(jNEwTE1PDtF}J;d-+Q`fA;lA zeuMhUHhx~}oBdarpIHvOg)4S`&OF;)e1;5fpD%xp{l(7dZ}~E*r!BwJTGzDExwAZe zf1B!8D}VUl!o_laRPN@b50BpU4QcO=J??v6Taod4ZkKbm&RP83?AS;9J?_Ti=ZkyX zr-Avqxoy_@bLCN)uR5*r{@kE0U$*`q?RFlQeD<&WIh|e;pOkjz=j^uavmV{K%Q*7l zkk+d?x3_e(_F<`if%nsUjh2(3_21s6I~?s*nJ*Vkxc%MuHJy%@tbN$n4xNwF^|!u= zeKKk{Xgyb`|0BN3IBegCwEisrhjkb3li^?dZ5__+Q*`)OULx~J`%^W(@NH?|#dm66 zfu7rX#qN>z-1>z6oqdrGPvbY;_HCp6IMR1&`5pg9>SOz}+wU#fU&ZES{hjT)(4+mW z-?Kme8!z5jF6*)WTFG0#ME+)8l)F48?aREy54rW-u4#Pr$?o^~eRel#UIYJL>e!op zW9Q3sQajJxo?*FB?z*+VY>dWRR=?oZW9$1mJ;iU+{%;VU<=4wnFUHwz`~KeM2QmLY z%T45Ter=<9|GW8{$hhOb>jiE+{%5j0XkPo^;*0faqy237H@jVbCH?Ps>)z7g+RHVs zFe3To<2oIzK2PH5y!<^jC4YB5My8+GE9G<6_n~rQAJ_gZkjrv6tlx}p{fE}4^Al1} ze*RFqahm`1P|Mx3JZoMdzt@PE-@?zE2OeJg#9lAcEBm`ww@&NMI)4;3yZOt{+lIBhRzJ3LdSO1h z3vb(ByzqOSJ^DMa{$2Tf;O8+~@6oa7e$G7GUEhVjYVV`?32EO=>%2Z&e))1~pNk;!9`Mp}Zj-Sov z>}-!EYd&p(&gWe^B*Rz#vOB&T*J^!g*Ghi*g)$zuEq#|>qTkyje>PsE`SDL`w=XH< zcY)Sx$B4J|S?M2#d#fbhV?4_3dWDp;S<~U{J0SIsdf&zyt5P06Z$B&XE}EawPW;3_ zNdL-zNp^jt49~i?9(bMR>$F+tFSYgW{2gEYfz)SfTmIg>O8Z;BZs+vF;bXVf=HeN?~CE_gLCdgJwD{$O%w)bHs(>idex z{2KAu4f*{;{-L;^8cVA;n9p+AWxPys*xe0h|JcRwqaCh=8||=E)$KtW-y)pl_uZ}S zz%Ju#7j}bi^(8ZYPikm*WKf0cD(@oiC%{j<(J#IbzXX2ZZR3vw3~v+nL1_1Nhix-^ z0S@M5Tf(dAT?{Yki{ULlRmU6pdkiqVP5JmY@*f8`^4sqU`2eZQIg)_IxIA@izI0cLIjDjb9BI-X@NJoB6c%c&(@J zXZl~78t(P`hei(_?xNh~d1#00;T^n9If&l~7~VDxS>MCk#Mxg=Z)pEI`HOOT0K?nG zM@+@nDBJT%-Vk7ToBXT1CwXbW@HTPZAD=Il=87|ZZgR4cuU2QLfZ;)UX1rRMpPDM= z6>8$MQ&ZLa9MKK_>71XdoFKZ+7yX0D0slyUkKYT~F*%CHLmf;zcRhmb%>EYUPvrg6 zxssOT`^Bn1S1Fz@=1Qfr{={tgY;GL1YJB#*Kn^lt+N3U5{mf`jx8I)`hSKfE>u=-; z^Fc^%rkb0WE6&dN6SoaQSJi!&$uN%WrR zog^v$LE)s|QhGK|KUwG#Cw}b0Ulrv; z0@zq?1o<7!s`H+fQnS0p2?dvsqrS`VjRsi*exH}UQ}R0__=EkUP}o4e zys#qVw>{l0ANeDhjF(MH{xW^{>-R`JZu^Vj%|P-&6Pk9=`VSvH6z@et1ojDWRUWqB ziVfv@wkq^rfP{$lX)H;+4j-mgyA7rWhevJ)vw6+toRE{S^;h}~4)^pbb-cvA?-cw6 zD*vUP>EQuQhY#jy!Ee9VrB8bJHV#)@@;fMAYWGTfiNY)W&7>fw9!Gn6_e=f;#h1nJ zAL<@f8PA2IO0iqd2>n-__Jpq&$iX1T?v(sKvS(ve;>&LR`-l3pA(~Cek2%vPe>EZA z6AMDmm@{57w~maG{JP|ik$q|h&I&nox1OUtM}~)0zB?rOS(1~;Nj&XLS5US?7RGd# zxLfj9$luz%67O`|VRWQ_=x7E6S@EcFCI8ktM7UNd9=$sy-bd*(_5q2n5x?;TiLXZ3 zXJo7wYODiZ_QIbQ{-!BjykinSM|QLHzdhskr@J8l+503vOZN2M^(rC1;noM_WO_zX z&Zi{55b19wHHiEJuNLw#Yhig(zhB}Tk^Ua*A4WL`e@4hjxZ@E%^dqUGAYa;HG)c`V zudyoSj5*Ue@Pm9L`Azb-+5Q@#&!*E3AcxAaMndw-&h$Jwpb8VTPhIlc$Zj%R$GZEH zBVZjUH$El#X{UXTjrI?w6kp0Yp1Cd4t!$LIw~NjWu=leqW|!rw(ZUi!O-hmQO3Uj}N*p7)!t zdBXvqsAjvWZ$pg~)91bSX`I_li?*KWWcMw}qbXJO0{+h=->BqV27jZR*ypvJUpS@l z#}MBBdh7eea*mCtlycx6&1Zj?NdMpaw8l|4l)w0MPf&V#TT3Fm*lt5k(Un2dp zACUMK#aHcqi5Doo8uz|Q$SD(^J@96MFO&RQQsPHh0CKDIF^}r3_7x!zj8>F9+RK_3Zhw7NlVF3=G5GY`vMF%g#l|A$} z;co&W6zys8GpW=qKGe#*?2_bn0$15Tw=CqONlr8Q4uP*xxEgm#JZ_guSP$$S7*1lV z)6@s?fnF{)yxN9UA0~ej2YyZX3&Vg)&)AJW6u>CX)5Pn*Rb=yA&* zzy^cE-=KnS$$^SBvRm}m71k)c)jq)QQ-Un{nbDC^mGxZs0JNAb96!ubPPeWDDkb5+ z`s9a1x;jVstNz447Wf9Gx2sYByo=>(`ycCc_^5YCJpOu(H@Chd+6o;p8m`z)cr?w*1qm=7~ah7gU3@N{?Q?*IKtK3lI2Vs zFf3=hH~ot6x7}54blvLVw7kP|l=MY4}bZlI86Zr4z{ys)1fDEBRR0 zL%Rw7NOGuWc+ejmIRy1>S#CG%?-h9kbJ0yQvbX-}*_xaxa#_8Ilv zZyb%Oa)I4^@3TC-j~vx^16;fl-#;hhY?HsSzx=$w`x3gGNqk=7o1{Cwur**8jjnfNbx@mG}ndH*|hjqxlPuNg1S zO;LO52(%1!Eo=yS2L=a+hg3gF^Hy1}>m+}hrzD;x{k_*pd;!9zz6-j($1OPgOsOmO zCdsdp{?7X0As9vc*>4K_)X85b|HkV*@6D25crnG-yCptGa$+Bp_)0?ahyPsHW1GLH z>#^)+yT2v$iIaVz@@W(v#>?cHTxH6in93>pgm``-KT#@ct3mk#1A#MhetE7kS)7{k z=lp_x67q}H;>^?}RH?Nb6~9NZb7nyszBxH|o2O^9L|rtnzn17$=>Efyvnk67O9G)IdA@|XWf>w)!uylfoDg7IRU^P!7ylnj$ zkCMM%oaM8>G39HkzmOg2dT{Z@_JQHw9p$h-<@Z-#Na1RQ9QzJYU6YTT5!%U;6w}>Hnkh_c2lCf$<9WwO?FIX?E#xh1z>` zzFVi?+vGM0XI}fwnxA;D<};6VsuBL9vfGdS<(SxSdU$yGVLfdoHxty-P}lwWE9L0A zybkgH-MWBf5-W||0wd* z)MsICZWb!(llaKyWBn8_#<@Pg_1XEsiG_vhCX1(23)nP+ zb_CBetWM-g?;{I+le zS;ilHxlx@f??FyzPvFmlFWBW+jfx%Lub!Qm@bTm2<2{w1n<)6$s&$u3ru@ppbeY2? z@i4pspPYB|XTk@9U&_16tGUVy%qq@n&jo)bR7l{JFk%E=opZ$3RJj5lDNYa}zdS!T z;m^-NpUBBPmRP&lXX;F)IG1Pp?9NB|g&Zp+{H=!mhInMj*#=uQ6 zMtVMN(t}{MKToeON`F&-uMIguAx>}HuIKNj$u~U+@nSVsnwg&_A5DC`l$$x}z$a$r zDx6VG{)tMi%mt{4muAo8TkTw|mf^!N=a645=O#EJO*!*rm`vZopPS89CyGS}Zu)E6 zhx<27`DYA6Sa`XR(;f(XvUs9M0T8%h2!X4Zx8*>c$WS!o>v{zR%Sb1%&cdHPov%#6 zTlmzSFMd>bs6Uh$<_F**($kK|HZqWnx7I%=)OWDeo*HjW&l9LV7fXiyp%4p;LmTJh zyzh7k?KWj*Q&YacV{dzk=m%bWuI|^(enjG39fW^E;!DI2{Z;j}AiVXrJypnu;|ElG z!N>Ik{%~(EOnHYTIW#K{<|o{EspR((Kd2`|Ib-D0#+NS>`~t80F!)CH@*XkuOfL=n z*O=O|AA7B)*IUN#qIH*aUfwG0Tj=|_Iauy9K0lZD%k!0dxPFK0?ZxVX;eiiJg>c=G z4`t6uKl~6H_L-ICPbhz8b_Nm!F17I?zB0GNl-Pj*|F+?g9-L*UQ(P#gSUqDFtP%Ob z_Xm2848V+wp8k+A5SZO`aI2N_qy+BJbn$uE4jXZWZ;(W zAy}H~kNP;dSDV56?eE;G>j$?EnCZ50rw(8J18!Wc|AN7$o{X(0r(0gvHie^lM)?4vRvJ`NaI<9(|y;q+E= zzEJzV?wupm}AN1HL~!JDG1SAAEnNRGc~4@}T*Hmj?MlWt2WH zHzuJXTxsF^KGf&n3vL%cgcm2RC-vt)O@yoQVwOKwoObA$_-n~8Q@NCV#ic^d0^wi> zXgbf%Ov378(-x}kglmjp9VxC$)w4!m-SvT2sPE3$4Z6Hyx7PP!A%BtN*PfLWxR=oS ze?6w_UG<@dT{XmfAzP`?X%-Z?l8# z=6(a#O@lpQIkss8&_m_F|9fg~mur3(?9Twzz`^90xyc6Ty5IZ@dX`Q?!`+TY-=C_wp7^7E zFx$7s&%i>lR1bZuz)G<{$cu1w+@kH1d(xD`dH%^Vh4;=iiPu9r==~7VM$>&LYh2-R3BJuWXv_5yfRN|c^r}mP9&_7Oius;LqgLN>_=f2xDKL{7` zv#*qLR!N`w9TH!IxWal!;};~}L3%bnFYz^!ll_6j8zcwX1;gF9_{o9(qeFwKAzgWZ zXTCo?1PkjOczLb>J+za41-coaV9Y`1oImF!9&=LIAraVNqLk0g%$NPCiMg;11@c)= zsaSHZc`L z0iT}faerdI;!o$Gi4kRo|1P*AzEp%caAk-1f{fj%sbdc@-<^K;uTPYoQMlV*oSr!g zO>t3K0!u{M0cso03Kq2QUP zeK)JcJM5|;>Jt~&ycz_<@99*r)bgc`FCf``NAqhx?+bsIxcq;+{%&%9T%__U`zf}f^xp6$^5khTN&qxya!cN)6P=%W!7aLng&vJ;I4 zmyO31iusrOD~dVT?y8(SePSGESvc@B4t(PDTy^qrwc5h3mP#&u8SqJm9K=sK@k)f8 zN`#zBl$@MfpGwZH5A22{$KSPmaF?VK^yl05LA=n4<5+3cA!mB_v_zCnQ5V;rRHz&JSY7C+M8IdfX>oczg*4FPtGzvH4in(>HN$b6rBMF!UeeA>?;J} z72nUpplL{CVKz?c0KZymD z7`ujyB6-3^)V9V|{RR5qf8;us2u^_DP$qOzNT4YjFcExYquf_KBbu zZU^^5`Wqd7e#pDXgHM(hf0wQ=GKKMVsL)~ihcA}j9GCL_V>)?cUODhee9iwi1gTC)Jea!AIhjT&v9_c@N zGzBZQgRTbUH}pS@^uWFY1O20;pbl(t(w`iHCyc{eAqaYLc&YgEnt^;RC*1?10xX31 z*zdRX`?_D0U6d1rb39^uc8$Wd7ds#y3TA5mrbkD5`g?m-TOu%XP;PViT*nO$;fj*q zXnUr26Uaqq7uuT|e7dClL8z+Z}J#(Dk^m$^~$qi`61#2)G1WJV3S;%-VR zX>ok9{%vF*#ve)HYJ03q&y06P;E4!1W5kE=TDc6L>*5@I+{$w>lCOJ=Y<~-a&$R+S zH$SI8@HT(R(&y2n|LW_c{#e#yd?o%ue+O6&WGjU)So*V^4U!Yqm(=(y50iS0_sj9h z#TUE%Ex%Oz8x>zaDm?p+r;2uE0Stv{F7}}p2)sskl%Cwsr2es>y&1)i!Z}{h#rUex zcj4OkYUSD@OhBHW%wMazl%5NR{jOnkt=Q%naBjEa^xnfI zp@*J%E$6z!W6;T<_KF^a{hKkvMCtisT(7(Tu^s+%>;O|xXJ=s2e+j#=pkpczQ;)F~ z@L$dT*qv;S$N9s@U<%TIJw5kpx1ik6s{0ntyXQrp zRplptU$THni1-1;nyV2{w6fsV&@LR8{1j&{cVp(Kb$^V{PlDU zFwS~D(egJ47j;0`{3k^6bqv`2ODz6k;%b%db?M5daq6t< zM>OP2l{oK`woau5&tGebFWtc0)w>pxY2iVvSs zVaOM18aPZ}h4n;JN_#WjHQpLtjq{S^ARjHvRydu@`MSi{%QOvtb$`C@g*W{z!nh)8 zq!kLotM;qGSz5}V7S8G$@)e)exA93*N8mVvn9N|~PC1z5IH8;RAdX{kc!fBOXuvoE zwCkZO+8h@sR!eZ4Na!z>4|>5I=4}`qG399f37G4GJ;#ClL;m$Pe||=Fd#ir(P@mH5 z%n2CqAdek#ta7QGgLP+TImv}`G|mQU!Rdj4&z2`<=Vw~-OPO%J#?s(d@?o|%?5UPx z1_g(uKbE1E{zhgL_JndjG=m`@mO4z~Tt01}P@j3|oX^3OPdzjf;xK5%iCM{)@dzIn zD;|N*gIPi!WAMu@$BN(C@mIni2xN>qP*uwg_+hi`05enb(@^&0VczOVBfJX7rJybx zXGS93mXAptd^OW2e2LYH(n!9KAHvXX$cL3ifqX8<6b>sg^#j4zD+^onJT35vv#`je zGOOBxIJN~NL$HV~l+$|*_Lc1)9#ZPt;eyhPaaFIN+y&O89BJ7ZOFxQV2Ona9>L*eT zd_7xmOu1knCk{S1aYzvkeQ4c;r4I$HMGgc&$4d)e1>cFz5riU z@^tfE;YB&E;YID$lq$Es4m(qfweS&F@+~_c?uswU0WES62g|wf>mzWSH=_K-RE7eA zk}piR&{JGES@y?gCMV_tI}5&%ek88!8RjpRQ-YSX%U>hBm@0SG2TE9$Blw0s5)b27 z;-UQ|9_Ay7hw%cDB-8|bR4Ac-R)Mpu{9tJth1cYp>0jWWCddJUV;cdc3|0Jb_<&7P zeOSep;2Y^*;Fv<$&LAvM)UXd?As*UC;-P&c9@+s@Yaj z;-Nkg593SXp`I$2n2M4<5(kCcc#yv=KISisFPv40@ing^Oxr=lm)TB4nB|+eN)On+ z;!Ncb_>Du2LI+U}t9GC%%R9Y1|pcij!lh9*ue)^D$-3%!1DJ z!1lLE*$Cs!u6FHh<}e9IwIWcy*4l z92%bu_V(7}Xu-H`rf+yeon)uq3;k8?pwes(_Go~dWc$0_5?;kumFEJyV98NI8J5;EWjZ}m^k~3-D2o(o#KUYNPY@$Sm(ep?!89qb2+Z- zhM7*+%+J7l;mOP4HFaGMJ1JD*C`TKQbxsH68~WP?g#(rk?C-VkH{$I-qvc193&3|) z&G(wqtH-e;PWc z$0O5Vy()h8BiAckqpSwwuOHR+Vi)G+boaq5Y(F`a>G%75lz|t-dnKPglIihJ!mQ803QwxMhL09vSiJaXd6r&g?Gy$KR;=B!!NHD!$q6 zo&Kc4+31IeSA!~ReT=H}z7CX{uR_Z;u> z;NorSgMVXv1HU_{Pc0~~!ZmrgO9HQ_!*g%pldf)44&pdQgSU<2m=WF*zsS1+FuWyx zu{whq%K;mI9$-2)6S z;`Pj*2+|M!Y=Qx?yyEj=VO<4m8^*Z{&d)aIML>T`F*laQ#}a>r*=&4Z)vm6y-=68oA>klZkwTHu{}9GU_Ama#yMUXk4jhj#clbQXm105 z*=|vI-QqWXz~R&nSU%&dKjR${e8$;YHa{w#vivAJupG8CsUL)QWmB)mwDUFNde(Uu zFO0+ILR~DMaV`gJJQl&navd+5Z`+^sw{cD<7i%$r9LD1jcp?JFz7V`vAC{BWa0}iS zfn(bRFI&!>hFkF0S~#aej$d2O&su!eb14E}jKJ#=_;Lik8iB7w;Ef1;Edt+&z&{p& zpR;hbTNGZS4950kemp`>BZ8lx3<>Rs*2N)s7@{42Nm)lezR=W>bdK;rh{ zaEZK+SAGOk4lkDjWS-D&-__-OOL_7gd0s;xhj0$Pjq~>?>bvt$;p{KRV}fjJvaZcI`=2`Y<=Diu4^Oy zp&N}Cc->sWS~nM^ry&P7+6&f|(0Y>=g-qP^*u-1_qZ# zsQoNel(QV>Z&81djkiNb2g+d_UAz{^U#M4rY}le*ZFdEml;qCBs6)tS`P&ilJ;?A{ zPn0tcQ_XREuM*5ts^m%_$@aGv5#Dx^!+iEPCgfLgGq6~7940Zs5U?7t*ZN~W9?V&U z)wOxGIy&^1<#a~LC;MnQfsK_7Tz2Rb{0eMnHJ^vcOECRfFXSeBT6i_E1M3qP;lhbs zMKwpiqPA^l<#$=}$Z`@9;p!9eK|%l2Ja{k#d(b%JH!b+Ugx;sQ{B*el9i;ez9WPnI zKarowS0DmPx#{uAoQvOp4tX;jvi|E4csU|m3lVsqh!?f7D~w9R94wetfg!f_uSLjN z6yeG*OytXRFg&1a=1LFgz~7@|V=%YB--m-{Gr{zkz+bGUV!qz6!pnF)LZ2}!-Y+IO zowObe_k*ItgVio!J}Ltwt@v7_)p5H1>@#j5YI!4y1J zmn}bjmz2+P)~)=`_=*)?#y5y>hU>Qe9$3?>L&p9xe>I3NUZ-iYLpw0P&9Xn^wIIA| zyaVD=eOmA%G33WXIasend#+jfbG)?EdOg;Y?cYhb`tIPcr&JTld80mn&nY4$PK(Px z2Z0;1*k2A;!_qUzcNWg;7MoUjVE(3MHxAdB87{6@2>pZlLzfw5))QT{XETV$fDhl< zP!RK3pG6~InEUJYeM|QX8ubm36B@|CX_Ql@E4D)nIu5wJ+C@Idamt5kNT|QzFW@1c z!^QEn6r@8{521QdD2Mr6ZfqIx=+bjycJ^curZkpjVd8(dl?B&xlzh|BDBmT=tY4Xi zV|} z49y?#+5Wg4FULF9-&jt)MUIH}7CBjx6NcBcLRg-#{Jt?=ehPkso}iYuN_JrTb9(R| z$My;8v1arJdLkdMF48k<{P)V^S9*9i>Gp2B(!={2PYnaNjPs%$@hX2*>%lJLON6t_ zIP=(LoX3yZ4c5)Ud?9l_PZXbV_K)4BceB`!dJGnrVZ2B28E5_2WxVjlC#(0_<#@sI zK}@&xpVsX{<~Q!ve0Diphpxw?W;3HO2Vw;6h~u-U7pFSof2s>{{AS{9^Re#; zZyU!l9&d?1$HP8 zrTmLMToZ@4jduWsw~gbPM7$+_k%wy`@iuY%+iY(x()c*q|1x-n_fGsJgMSdXc$<8b z^9;c7HgWvh^mo~i^DKCVx5-C2&jt){8-EU9cuV|ZFAf;qHhu^&yiFYIMK4Va_XhJp zd?3JuhY$+Go8-=VkQwh42h-laF{e zV0cTs-Ae(6w~5>Gm!W{cvI0-RJqj+~CLi%W!0@*5mjH&hjo$(o-Znk}7~T?pk~at# z-ZnlA7~Uq1f1CDcQ2K%WV@Fb>Fo}(qBUtr+d=JaFI20^gHkxu4o}_V@_fX~T2y?!K z!ppOzv(vMca-lc@;?$LR#(_W|1wa5%KBTMBo^awIr7FZ>0`*K4=1@Z`5jp}&xdmEJ zgbTaV!vV!@3)aVgKadIrD zqCiiyLlzQ-)-(9-o7FUBbF|MTa3g;ssLup^Q9ohx$1*wTvpPQi=KaeM9+e zP>`DO!gAs-lkG%~$5o>~Z^mOg$x-tI{nYU!Y=)g0?Hks+dFr%e^4B8dY+WPuVSfwo z@iX;ge4Fx-_P1qvW?)YaFJ@S6f0#e%3HD-4s94Zd|`jSm_F~ze;cCEPJy2z99YR`MP407I;_huik2(5Es*F1N|`^ zn9j$9e3aw159_l`^)cHH*+7n-_iIg$1w8{?BrKM50qL`8*@5l0W#Oz(!Lldg+ZG?c z%NX8xS*AnA6Thr+(leFL^h3v#S-vU#tzB}$^uThmG+&qGv_uStm+fD+^k*C^PC7p- ze_JBPma`DppXWczl&jJ|mZ(<5n7A1+0Uj}*neE&j=&Aj+XO!D|E?VJbyKT|DYxdWU z0G5OGE{w;7Sw29x?1*7Gb_B2-bWzTdWjExTImYI9P6`!k>I7PI6q z-a+%*136ZS!g4rY#B4sqS4%vCK2h<){;rsI0DhGHIleZi+-5y@vs>IuCm`QW&`J(0 zu7*w(VK@#imy>H&`eFUMO!-QVOz4JuF+rc@bNSOS?V$A$24z0me?3B3?1lcC201S<+NMhO?-~&x$_z>H&lKci?S!%En(UX_W`pC2&E6>M#2hlSwOI! zY@c(MeK;QL5#N!f#fRjr!d15F6^y4%d!n9}Jy{GN>=OY1x2cn379oj5d}dA>xj{|`nqT#WNRMFajA ztMOtvj3*Qt;ye#rRm2QF?|Z}ZuUHQAd7pn9_iEY$#(Dk>d0YEO`Xg{Y`)I0H;QV}Z z++WvqTKIpb`PZnP3a_QV^cvM8;li(1UUI)DyVt0m3Kw6uFqy~hHL3^0^SED<-D}he z1!$)&>3&FduTec1P_HGNT{~Z|QN5jUE)Tb?@`v#iDz8+zcjNW$a#G>$@{qqTV`h2F ze4|`teYpI@g(N|{4EffFocXM0)|S6Zd6eQC4xvC2c6zhZp{Sx!62 z;dHzHQ`oZ;UeJC?byE+3YdzghkUkxOKALX@H)!whxLeHPXO11gCKWczp~Bz?e4wfD z#_nSKgM6&l$!Z0*zcenRJ&?oSyEysF_Q7HV?HPNwme2T;2+z`ZG|P_)7u%uB3>WAb z6)sLEX_N1)FG0At{$oTyxDFyWFy99ih)kg#0>{ zOB`NKhhq_P)<{m+ACBYdt>dI9594|{_e`kc8)xbWy-v2~ydOA0yj12$T z;VP3IYr28-``Ihi@6n^eYhlDTXIkx_|5eSo_C#4?64lr^QEae zAJp3!CwhRhoLYn&uDjU&+H$ylj`exCUc>yt7xnsrn#Lbsy!}fWf57sW`B3z!i}|c) zRJb^vna}b`j934}#X)+*a&wU!(jL`~42Vj}brdU5R%R-n{Y2g5OMOeZqQ6v4WfYaCk$!G?6csf^x&a zC*e367hbBsRs>uDGWZAw{OEJ&qRx+_eYDihCwlKO)HRepk9#CJ_7PS4a|YvXAs=S+ z!nUau$aoV4bAQ6g33KPjkdOOS^65mTzxq&~R=b(II-2~cGVk;$^;i2hI`&a4R&lc* z4nU|6;IkF@P-&k{ocBt!<>S7Kd7Lf`4?;f9ZO83SZ8@-?C+sDsPwO%HdjCVs7C7x^ zsCP^ZcR^*&|+9}2f|*iJ&1 zxrV=x-*Z!~`5Masg{v~!DPM*c_;a&oa+OJZA(UU9J##1?l=C58$xr9tpg7w3sYSlp z(G2%JWBmg@>0{uh=4UAyB_DA1SjYjKzenMIO?+l2@7EN_$Il>(G36u9VhkKlTpJJg zoc`Ob^Tk4a6u%UfW9%>CL3!S~FCwNlE-U8MX~b$uiZVrceh&6%g`M9lJoL9%g@dBc z@WxvLFXK^o+M)ulLLr%V;K8nfX1s&^1+_jyy%5TQG~(oo&$VGsv0b-;S8;F0;QP+? zv@)$r)mobRK!U=27vvYV^9<(;OV1$vs~8CNSLxXi??L*s_$nTQjg><=*rFL%-y-xF z>zgVYADPBp+#7rbno<%Cn0 z{LJvNk#49q>g%ggK5npsb^XM%Zc{%NBY-ql;>G5 zQ+?R`uEgtvH|H-Ec1V+)*t4E4@G-_$B%UR__P)ymKStpS?FRKo==fv1-T7V3=l+~d z;>X^1P{>&&J#9Ih;9{S6Cd}JEU!@mpcQo$Q`%A@+KTFLairszu_Yh|{yKt3|UnBkF zcj@=MCta%SyZYPux9M*cjVb0s_4(jK1B^$@3D(%bf!?^oy>1Ix@&o(e z{=KyB(Z`M3xaDNxGjM!p3AQ7`XTA?#ni(kG6d4a2EzM~>S2_c08)3+XsY+EiuTz~Y z3Qck2G0K7Ug>$&gJ};WkA@ltcrQ-MmmY>Cw`O;YqukYi|huC)po$hK)!ZBQ!1#+Ov zKrPXtJs0tOLU@VhwwmMES<&%d7X)YAk%`+SjKQzwbayrB8OReVfKR?s=NR*}dvB#Q!yo_mO+m zm)*GCueJFYUCzAu27Ru5{2Cn(?7lfg__uU^iIaQXTiy7{_iB8b^k+BoakuByB~Z;1pfv%--vfOA1xfefc{(PV1lI!JsId_ z4r93ZRxM}ydwN|KyH~x}jr)E#ZUxuhBczz$9eutqrUks-{29{UvOlC-JhKs|Z@@;h za0Wd5f>E7ONT2+Dr_E@!7{L3nZ!h4(FU7CDEhEaw^--N38lRAOUrRX;@^ROAl7GcB zMwOiN;kPQEsl5HU4-a^Fzx(&~edHqp9^OJv*aVlvct_tmsP2jP4SIN=_nZ0-`Op}I z9v9|E$&Zo~#m9O$)>xp^8xKhES)twe^MW5WzvA70{IbA4sQWtEr~9uZo+dkY|AWNa zpa8}CKxhYSbr-1D*z>-A@5@!b*nGCmN9;m*8?2vAC;La(ZhHUBBe##HGPfnuxO1ky zYNvdW9yUl%>2I}c)Z43Pa%I@TZw3~r&&<(w?5L;2sfo(v&m+M*Oeb-ghbiRa?*F8Z zg$L>9@K8+y*S!gvE%@R=DCcz5d=TQrYOYi+zP57+O|@yMGC^jUJZ?h!k{P= z2;p!j*e749Kwm_03O0E-0X_J1^bCFPpqoi`?EB-B`k;3x4>4i2eDC_7pv!Ik4zYXH zhc(XSBfIaP*X0}Y*nRT_8D}{kl^>(>`_QX&z8Jefm(T3tJdNSxsH)ZI{hW1#eZBn^ z%HOpcHJ@E!|0y_w1y5>)7?`~GpHzOifa0<1Le8f+jt1LH;>j;iN7K?Fz47wvzU1+g z-*4pe^gkCUUYM^EWB1tD zp+mUo1I)+zWJ>T?DZaQILl?`RZECj~*e;z*p)ZZoc+dmBNx^SR7aihN! zJBMHg*%^HZj^fk!2yAUpz}-{;!z(x^g>heh!CLV{5q#9rC8sL_M=cFL?s(51M-$iM zIQ%&c_0+glrj?JTQCFb9=4)l(iG^!rOdNZWf>TBeet@fE5JEX2t_%^#4{@cF16MjZ zaHUg#V>g&fp8)4`c6j`Y`FLuJp?}Di^3B60On!jd;e~!}-5W3EhkPqs0bly7`g64) zjLaas2CmaTh0DOvV;3JicH!u8faA#AiWLsVO)Fbz^(ih z@Rhd?zVgOR?R43A*_E+H|9U8buhXyXvp~f+_ke-yzLtLh- z5SQsn<9s}q9WEB{z^!z}a9lOe`nlPebE|enDrRI?pH=!2mua z0UX>F$NQihz-M4k$A#nkAs0Ra8>GQ@?8Z??S`KKgz*2AklEn2nJJ_Kn@qkV^pUb1= zU{2z5aBu+GJO@YO@C(UsNnC|d9k#=`I^fO_#JD=(E*cL!V7@+=Cx8QggY$YoTYL)P zorl>0#TnRV4$kGF(Rwp}5wF6?4|KPx{K)*mJZ$v_`>35#;R@xb^JprQbJYoa;KIwT zcsU3C!4Ccuw94}{r(5Jql_nKz%SV3oOso8<8JP32(2B!}f;z~So>L1reW8^#MNn3sdpY(4zUs&r8-zrOv!Y9E47hY`jSMiHrPm8b5U22t&I39oG;up$p ze#wE4SK+i7hn)eRbm5iB^0YIZ&z4R(`Lm^h8?R_S?_2BrZ@Hhq7$|iSDn=LYYkLfS z<6akhHEF-wK+cAg!{geW*0{FlAAtUu;;ibP3EOL`y+6l?J!l>AhG&&Z&96gzZ6$l1D(`X!F^k7m>!phJE?tRWo5gOtDz zIClf4NWfM~MJO2NVD2V)pmAuyIdSMhws6jOyuPW83kyf$^1_{pD0S7|J(598-GUhBh@KA$Gn=r7obxJ`-SZIh2>W2;(hN{?v5#5 z`cJg`f15q`8(yn?NRJGU4x>R6pI;RAuaW(sUl-@`-iE8J`8+H=zC4qM(P^j|P8O%8 zg5ePl2R~x!zxf%gDszvc8c%_-(n-vHRllHP5y~0f#?mUv!txCccZ2hi0zMv{rAB7) zh47h=xOFBLzNGMxW3bG};)h&OfWk3ZQ11C>)TE&~L(f2lphI~M$LryCg~@^bqeC#@ zMi{~N(yA-?xgiPw1?@F?~)!#_0@ zKim`6KME_Lp=UcY>K_@n1tU%y2!Q11kz>8~gNeV;^3Mkv_8+d2zrXc3eU4cBTlKg$ zyZK8sUb{f+&+g(i8eiztk?Ed_#HNG~l z$5+@z6Sx9g_;t-+J*efg>%;I0&hmhozuF0zl8@&fPeOhJt5G6n{F+mrSN-Z7Pwb+< z$A&rR!kfv3vL`w|-G{_`zJxnOE9my>vc`0pxf9Hu9! zcv+)(|BEe+2jf3PK|iEmK)LHqQ;7K)?Ldp-0_h*(Ns_lyysrYUm!hEpYCHLBT(ZSxE)^_)rZUVd|L9iNWORLNl|}Wf{H3U^4@!& z=JUA8Hu3ZKOB^@vL;f=k==15Azd_+eefWI3;nD8oP4Us~6em z7&hdCtLiYvl`FCjmPcz)vDj149#v=e@huUcGZ}W)qXEmE4pE9;nl+Y z6n0nG?RV&Z##VY5-Zfe;X0Id5ewog%p$8l;=EJ91U5qpT0eZlA+gE5k+5?i$>&`Gw z;Kh7iPsjZ;jI$ig4*499fGbUz&p57`Gv%|tF%ral_7}e=crhNtqlN?Aqx0Pet}&l+ zT9y~A*Gqqm?5SS}_1ThQA!|F@?hVQ&?m* z1ziJbEmRKntR$S}Grz;aS$-7WAU@10JMHJji!rOdCz?z#Xo3)5HAkTR5R=U*M>|Wu zR4qWiazG9R;dCA7vDHnp$=UgFTC!({YuySLhxacmoWpD5oi7jKMdU}uBlF{vwFkC7 zS5iV@{M;4#T*wEk@`Q0xvnAe_;Cq1=%i(ani4sT&vWI>$PeQ zT+LW?;Hq`+z}2EU2d>uMgg8tmcdiRlxWjIMPaksFP2mpyRBqh4{!Za4OlY}KAB6`! z78V{X6tr;1dLooF87xqg{BQxGg}eMM&CXUF;e}FqmS;~2{VQMz7a#G^K0NPkI73bB zj7mVEK57|I$PdQ#6wcc-z`4_7qMpCT?FGp%@e84R9`Cc$C*#^{2VdFLfm`X5<>=lg z2j5Dc0bi$2woiBZm}wwG&e`&8xNhCT9d?7!Z|8b>g}eAFf_1Jo1VbpZ6w;AP4&7kq}e+7H1YA4ZnVd>7=4Qbhb}JkZDDvj>L15$p9z z3U|m68QYfAnomg%J+S$lu?<`qLR-zWTS;sfVe=i~5(WzT?Q#BRH_Sg(eQQ#_nK4ZH z3MUUt91{fVdFD`7%@^%Ba=B{CvTO4l_AHqjWC*^oVz>ow)o1pE^E(LH_fVY8W28gG zUFE#OUHpjjFVr{W<9-eB2_pj;`pf(hrcZ^l$IaNd_%1BbeA;GH;+xd}*{n|pevJC5 zf_PV*%H6}6Uae3I-Z!8ggnCYtD%Ekl=>$B9-Io{g<4*ah?!Nv3-TwxKKJDiw_SX&N z>wP@92#WoS9ADmqgC4ML&-Gj0$A;^%&DDa?C)O|dd~UnlPUQBrwnD4?i|GN(bHlS8 zt=%O;KG)~DddzwHL?iPb_HHIM&x+59gJ&&x`n4eY%b>eC-Cfd7U=9`dlY<+!jn0P-n~e=r`?$ z38_o&Odp;DC5|BlzS0Ng^Mw;_K^?$xe>eO{3GvKFa`1xoH#qk}yr9qd!UG;c9W`Iu z!IY!-wZL;f$BQsC?ku0Pq5Ij?xuUr_x(?SuW6kAxe?vpRzHO|aiGR2x); zkulIfFh2p$K0N`;NnzDZ-k+&XP8R`ZIq0ICvbA45CRfDI(R_R6Gv2gtOs>f98x7+T z^~C&xc!JKqU^&d+c&y~(d<*1ny-woHKWFgGbxAya&+=K%w51Q*ZP^O%C9J=74kP=! zP5y@IL>vny(@%KZTwrI`ryj&tkbZE_ao$c6(_0l58~AfD!4pbE9`5#PYwg}mU>AtSn6~eE$Q{tV} zPU*f|;#)Kh(sPf-d7NvT@bf<)@i@u(_=d(gz7m9AaG%6iNuQ5zNqmj)sRK=wUwB_H zJopK}BfS?&ypQDLc#xW>YefL$BU*0-`!eBKvmgVn5Qq7ivp5q{Um-p@>(9>5IdSNN zD-@^HGr@ER`Tm+~_w<_b!bz;S8-JZT{X@Hi@wx4yHb9R zJ7~Dv=6)Vnj;XG2*MLHC5~ges?9qBL=*WcS3%H#L9@_&UARHzv!xZOMyf_=6u*)C_ z!~B33@3YJ<>It)WcUX5OcU~d>8T$pqVf~sDpUTfpxz@G8lxtj~C_H$$$G=d|skzEo zOmnae7)Og5m&AS3X6E5^>HG<_avtaCD?UsiheMnvPQo+pQV#Gl@`3NqPQmUhE#*n` zgL0i+mePOh-+my*#X2az#LoYBftQ(oiNq6BE@gWp-of=lH9t@fLt zzmxnuc>V(l=kha7_`9#vIG0OZgl9)J&gJAH=~4!zVqL1=RP_KZso4De$w;v{CK{+1#=#7G3=Y01qiKj`tXvo>c&}rSSPF3#Vaih`Fu_&;a?qkp(>X; zkHu7dgNm-uM6NGD}V57`&@2z-UVFR|2tt3iI(TlD@*?0)## zlnPh&QM!ML-N0YkeSl{U(s-rW#8Q^ltt;5uGJi%q3*U2HBkwH z|Hl8%pwegQ_jG)*`#}4U!rQLadb0Z`F^zAW(DB0V_@8Q=-)Gm~aLc*0>6SzLa?qwp z*f8{!s<5xo%slMr2^Gf4@lx2&{E3QxIS|4_6rz#>|3e>NH=a6EZ8gGnyzQX<- zJ^utIh>YX2z;3GFX>howw^zMl^I^Wqd==hkY{>qBK3L?B^>&-D79yT$#i4dot)3Zg z;a5u~wNS*CQ?2Bnc7^>C3nIK}x4#gqs%ny3a$r+ECk|@PD<_^B~C&tb^#h6jneYeIiaYj}I*mkE54%Bx%M zeYwgnjVpA1VK=b<=-7~-N%nF9(SrLux8t|%^rw6!r#-3lXLmWL`_I>@|D4_Cs_gGw zqwkuRl>NQusQe84Rp~7`nxrk}B;K9sAJFNru_f0BZP?#U?l;zSh(}o1iaYa6!Um;& zDR-9Ix`|Is3A=4N^?^>iOd8GadH2fx-VRDX*~VLhoI2&l?5(oDw~yKv-hC3^a_XNN z9UDE8!J2}!1FW9X#ZoKI;pOzB?9kf{(`|MA=YF~0au=t6$xjU(*G-<-opSzdTWh}! z%yNhI2>qk#+avXay=8_+biS7I5m%Zv%OzpAGPl1Ze}vbIN%=70xIYcY5W-T9TW5rv zO-lcg-=Bf=Ott0iE(`v)lRtO_r|ZKS3NLZzoZ#1-cEj(5N+n)nRq_**9;80$;oB&_ z8rjoA{vyfu4xSM>9^9S3oy1RETT$pB3`QD1NgC?+|#L z%T-Gbl-p|Hq+`VKWt`8!VmH_~AlNVEdS&QXPL{(96fUe|V1M!@aASL6jrx@&dI zgTp;2KlV6EZ|YoN>;N_n;Ue8IycjOzcM3lE-H&HRg+~Kl1t-5_-yPm&xYYPa%jk$c z&;3cj#oOfL`RO=y4sR1@{n15z(t$o|TK+)t2%LdooQ#Bah9stLQx5IV*%AQcUkQA? zO+MmR0fx7Uw&xgpMKJ%O{?~wux5-ERxq#tqUQxFQ}GLmq5dp~<9+Gz5@-G@+27``(s>!^Zvy1ujU2uZ zPr?tpOSi)Q?eb}PI9~hRUyC3-}gfjUv}1i28NGPJt2Eg)+@Te z&MIEScX==cr7oov|q;FB&K+DA@4wwqjh zTn~aC+wCcA&_?0tfz4O#ba-InAV;;|ow$P!4aky9KHvox4xeERR*S#9agXgUv=g0t z)ewaM+kAyP^i()_?ckr7bIUm~=isY;iODl9a&R=q)n73UhCbtv1N|6hiViyft~RQ$ z^+dkQZrC3Zfm3-R(Q{;I7x+$pVf~RC&qer~i|WsDg%|cMnXaD1eiE5a ztEVbzTNfLz@B@nv2huqEVPHefa`kYzXv+b-T0IO~msoNjcAat{8#!_8Z*lcIO%_i( zam?-!d?&7wIZCqh1iVE1eTnpdc;3xF5rNMrL9OyMqCsxAI3f6EZ@QMhycCY;iuKKw0m zQ~~Gc_l5pHO@ws0yZTlSAq#i4@_@ilqsFmwf5atL?E@8n_FaH^GGo^+R= zh&$y#I+;{$jhi4GkAxfR)g6!JdbKRCpd6lbl*5?bsuB7?dEOE(EVo_XFD!>$IF`dM z9IIU}9FmU{2l-B1m)ju8wx=q$-FO}~ZRJC8>&7GaIIhuRAJ7NOc{h%NTK$EoO%b@8 zkLA2e4iv*q{ozzTCywR0OAeOjZX5-*>W}4l3y$SE_}XG;EYF=dl;=(yhHG3nl;=)4 zs+`9cEIpw(S7K}&%Xyc48dquw7nR#BxN6tnz>MWD;%6do=lBlrPr3MzVa6kHr+nZ$ z<$!@uOsk&ofpp2I;U@3-IX&Lgd4(RYVK->ECNr>2#c2QVPzIyj8b^Q~Rbc89wr72q z)m1LRv0u}$9hxylWsh6=MaaP*CviabiLYMG`A|5bl^8yz#?AS>B6gdz$3%O% z?i?RE-g}$cJp;yJr{#LInzKJ2#tU?C!|-A^#BHhMEpWaO_63>iL#w%|V4hpE@l!&d zb>}#d-dqXHCgtP06+RD$+Uc;LIQkqs`GW&`9IcSl@x^WsUuqoZw(bm%lX82Xr9gba zK2@#$DwRC%%-vdkXAh+ZauavnDZ*8=`V(&Ml6p#glEK1^R$O;jG}Ce%aGBzzd8foT zoc2rx0~?lnz_tAPMRGiG3yj~|AA;kFhcS9X`vl{Rhqa(nQclB}-cXJb6Us>^yKhMz z#f_dua3`DQhLqDu{W;A8a=fzcOrJQuspU7blE3cMr+XN>&QfELQM30-zDNB_(ryr4 zeI!37*Tpo+{>`++S4huBP2z1%`FKK@9#=|yK=RKy_3s&gkx49Oy!xRxiF6nPtTi4} zN0L2*nWOM5cA*@%T_rthr=*;&%barbMnAB9WHu?~v~$1QDT!~B{>{3?yPW-XFlgVO zQ~{IrhjHW{NJFUq0XdGmMf$h!;cSvyfbZobzv;9mj#G~y+iNaKej-9o+*%F!vAf?Q z?B8aW+bX|+{L##@H1ZG1@#{6W{=+b@2?l|0^J;fWe#6aAr)b~KX8o-~p9Shiwd?~& zmg$)b&Gw?;Z#&Bq7%m=6!Ca$Jh17nEx2Em7ds{Sos>@M_egx5!j=77 ziN~p2tsRi#?_=a|HupB6{|fONamn8x`Hif^<1b=cL^br}DWW<=`PDnD4xU za@;>_+egnUP~-kcx8y4vOPbgRq?~ikc-LppU^x)GPx1@ouXmxGCy=G|;3Xx#!TsC( zebjme1M`-ifRi2SQcl8cPn?IK3(!N;BEH(#ZaIm!lRnwIEu7=GA@L^Jr@1BZKBqqF z+#IdXK{@|n!5LqQuL3OX&=0dlk7G1?&6<>xcKQpG2h^!)7+;d#LE);MlKX(g2)F#j z@4MFjQ<6XC_80j&!Vbv!8#PWRIf=)d=|Rl{aoHhr+mV4J7PyIfrJPREzka{O7oB!i z`x{fd$nm2rg^R}lc|D8HbSesd{NIl)@M8=7*aAPcz>h8PV+;KM#R6}5y!ga7?$rG- zEy06{RI2_>4{Y9f_6uztg1<`p1KPax^b-Yd{i%9iPn*Z$SAJU07w6wCJj-8}$9!+~ zeBqxRj)3<+cjnpt)*h?pWAXdhEA_s6HgD-x8Q$g-BEoBhgLy39`_TUM^DKE>zq9pg zTKYwWqc-y3!omA%+WtoA7lilsAD-~WGBO;TUiPiu+Wz#*{;u?w_w%&CS3a=dw z<^|z6aDgaCBI}8d*dyvE%hhiq>J`Qx&k?6RA`e4c~ND`cgeqj+{WqIhe2l-JxNFa4`hzs4`P+xy{IkDXww>!wm+5b>?ei#J-LlKtFS+d!8<*jYlDF6RsP+ls}D zDi5|TUX(mrzpm%HC$DbZmr4G9A13KJ z_f(xzb?@6>YwI88r{b2z@f9O+7`OMT^ggHqpN1O%oVH!SxcTGK<4#2Kb({jeDBG=C zx7-fq>HE%byD)S!@F~}iPzQf68S=FtKMmIeT=DAU`>T)-<7(UU(y3C1hU)@cY+P-> zX%P4{Tzx?1r};7pe6jiQ_no1CmD6Ng4c7~}*tl9>4S-&49Uq3c8ejf&sUtQ&&F79! zNj`1AsRnU1z9GQH=BM?kJ45ED;d)R<Q0l>xT)qKWzuJvihnbH>xHv#!+ zam&CLt3&f8cZM8`O*xOWzQ=V)TXzx1$46f8 zuVzO_$FjIS7-2stp(*+OM&^h0Xi^;aYl(}k2llD=<+mC6V4Y+gSYPJHxQOdIC-D#G z2ak6T%KXq5C($GR+EdKEq%?;esm(3fEv?|v_F zv3jlf+qhoNU+sJ+=i5);E5U!GFFl`;e7rqET<3Y|IOcT^XVcpUe3lN&mm%QObQJ4} z4yzC9gv0rPzTo=D$F<&<|C7F8zf4dZ_Xmly`elU2Q6TlWoBrMEgVORBt*tm;Z28hW zKk*NJ@p{Lz>ELlzeRCJY)vZK0HNQt?eprtNjdzbooK=rl9gMT;F&e42aG_C;=VnJo zKgG5BW$?2}eym&Dj~KReTpqs8#Qbhj>c#rjE~0#%m$=ya4qcS&UkyH!@ZfqdMEq8L zbBm1q>=(lMdA%EFyKb6aV#NKgjEnvayodaIQQ~6#v-)L%_|^IAvgu`?thhbzO?0Vo z*OGD3mlln8FO#@fUveAE`wFnHa_>v>v-)cA$n^RmUkQ$x_awy--E{2ajDdy^MdC27#)mld`Y*)Q)+^-Gj`s_fgWh)f^`lB84&&yP`)S5u z{#Kt%kBfXA%6&_1$WL4E^H)f{8V=+3T$A2cIXG{j^=TL2wBySm$WOyze%kriu`QDK z^W%OAZqMD7(icrfY}`8VX+Af=7cFkzL-IPTHjm1EQip~cjEozr7jb+Xk3KgcKkc}? z1vt%@almzUrS~c3H+FP7u5^|3Ps^_ha9Vy7f7>kTyg&o^G#!PjWqum20yr(dUchO3 z(Lb%P5U0iMhqxLpmaiSjm%m2(r)@tv5f^zqRGa68whqgFZY``T=Ss>SNdJ@(>hPn*OKcCU*F=sulyn$7w0dJv(6{F4<>Q( zybq5bd?H)i!l2Z_`<=|^o(}UdZuHM_xLRc2SD%aHD?A&AbFU8f71pB-zD(S@qqu** zPRE)_{;0QbgX}A9 zyIO_!Z*c!1Uj_KI{Y2C;IW}iy-H@*z__X}G7D*jyTr#BE+9ugQrt7j8xAr;7r|D&X z`Dgp3pW(WaMp2h z^Ez1%-fyye=Jg(Nb&AV+wBwJSAsJWmWd!)N{;Sb-94l`5BQma5-xlPj^=Ymj_>|*{ zCdAdwCw3em_wTj*qWd29@3rH2#}(!N3tkV!brSisdN4m8CnMhk>QMTx^LXi>7Pkz~Eym7E zZGCA0pSE2X2b|U~xlhFDC;^VQAMC5!S=J4Ydpz#{vh6CKdrBd1F~+~dQb(N#y1JiDQWBJ2=J-(jnvzQ=Y=$%``~#T4OfnQex?e~ zlW01cz?aLXZ!de`c@3@qu&;P~gneIv=NvTLz&>%;)f#Z0jMguM5Ldg-J_&q$eURsa zdnDVsi@s?6HwpQ1T=cJUE6fjNJ?)Rg^#V?dI}A9j5AvUe{FLo}8~C*C`2aj0pv{k1 zpSh0K`rLamtj~(iL!ej9?>6a+Hs4BoKRzX@?I+fOPh0;60H^Vd08Z1<{;JfW^)uE( zo9AV?zg@%STS;8=`~lqepsfd(AM5R;IIa}l55sv`ru(kBzqI)=4tmwPy)th78*0jW zFdygP9?!O3wJ(%>vGvt_uG9H(&WC+Q|0;NX_o?*zRVLpY=Swf}u`d{RI1<)**Z^rZoOeB6yV=Ck^5kob5%qW9VKxRZoKpE-_OS8iv_ z^E5ONuS;5@+=R^IOlIG>D(; z%j0ls2wwX$wF-v&6J zT_i4czFGBfbe<4(`26n6)-N4jPWnLA`?~4ru+~Y=*V5af{7^6UeeNrUj@L^aShp@3 z?{<|qt8UHjq{qelSTF83O~JwWU2VT)l=8Lw1Rtvop5Tu%$GW_9wRi~y;0&Uy?x(H@?+gvJ^0_z7yjJ+Dcd?({(77*O~R?Z9FR>f z=ZiY9uX1!A#Hw3KIbXtYTt()Gb!*Ugcc8>sbz}b6^8%=Y$GZjD;#O}@?-$SaRJJ~- z6Q5e&gJgc_AJ%O^;X|DJzSP0n1+U{T*>v!@*m@w2$GZ*I6ZgSdebA?zzw&&4pBWvV z@7bB*!+O-eozz3^gXd-^?t~Th`PqrvL;E>6FVUCY@5(;4)@O^aF)aCdUr4`yw|=(7 zX>rFR_t)|VCg&}ie&FAI@% z8v-3AY+c^&jid6f@xD}P^O<^QA4tH4(Ns@+#rg1%z^kgo=MwZ4jt zI|y;LzMACY5hCXG9`oy8Bl%uSYaZok-Q_&B^C0~1{8PhKq5m{riiE>;5_Pm_UUFP* z9!)@8&A*Nx$n_w0zG?UCabEtX^4H13tY zX#Oz||70ClH~x42so@48u66yx;+q6MEiUu$PYqZ3A^2jPM`Awhx==sx@$laD+4ZTJ-ogJ+5BrlTuq1PH~bs^vDB;amB2sN>*H*e z@p$GZGOp(HAjH*hqmj7DNZiOzAwQ+BD&QY)7rZZZ|Exerx}w>*t_DS^x4_ z4@GZhB#!grpPG)`uj2B<>z7)ej>YB&^&O?}o1Lv8)<^34n5P)F?-QU~|5kGp?1zQHAN^C!ghbkJUTAS z=i{CbiR+2Pof3&VBNEpe#-Y!($7LUMZLrJAd5E|XSjVdyB{=WPS=r)Zzi4s$j!5Q_ zx{fc)7PtMR)H{0b&Z&Cyzlp>30j~bTbiScT9QvZoU&LuT5U1sbxZaU;9f<3=Kf(Dv zsAsDO^05xjw@;YQ(_QzclKJV@0Ua)#`J9bUtX3p=z)r-qMTXD7X z+2|khd0*Z$Gx>SG_lEgA?tPKCMi^)LQrI$mokU+o2}6-3bz*n#va`C6JM)|~PB@!+ zCMk|PMDpQrGWy5k+x77GgE7vkTkrqH`7%s6)t5tOM@RKTNnc@H^rdq=UB}qI^nT5Y z*Ae?4md|~}hjH0g*Cq90A9&m`5{Gf!BQy`I2962e6~>`2Jk08Y(Pz^A=4T|ga$#}fTm51-#@v*ZiZS9^c)Fy)7OeSSyD{II^L z7q{np9N)?36^@X6Rv)w}KhB5ybV^(TOt)W zmt(_vS)Y4%w)Kj~S^15&jk=vE^TWCo_&nM15@*$|aAW%Z5a;dA$;Q|7??i{C7w3m| z-fWn3;r#XaeKdUh>v1P%)4}7c^{V(#qSxb<>#%))j`L-VaH`%@r4H@_8#wEH#5noP;WfP_IJZ8t< ziH_Q)$@d#DKl)eBh#Nas>SbQHBwKwszviWq5A(~@`2%aa&pL{fAJ0GJ<9zXWl|OeM z%H}hVv$oTmAI8P}O8<=O7xs_&a3r=-9mCXbR@_n0QP<)|@-=8bn|&Ek`0~#s`mFqFkvQhD`l>II zZ*m*CebeeT^a0ri+I#bcBIB|SYyS3}Amj3T40*i!RJQebXo2L@>NZL1F4wn%&X3{z zC`=~xwQ!v8z*m#)@5JwuJdh9LmX){zJyJ(g!PVa$heJNCzPN7mU6Q_T;Ci6paDB=D zH+?<8d9Lx{Jg+HyIDa)<8`c9YF7k~jadAE9zbxH9To2l?U*x`&t?!##()Dj@#Qf9g zad|sk-moC{FR@QYUP|gT0NZKqb9ZmH{03;h*oxaj`==I;^Q&Hw=;XXmNAHoz{6HOu zV_z&B@4r~M2AvPI*1ra=LruERL))(#JdAW)Aoa3t_h`2FOiVtJeqI@UVSY=;q;)>= z37H?BhpW6S(dQnMIO{xI?u~{o?QDFpdfSvQ?uYSs_q2?QdOO!7y?>TCOE2?V^eceYbrNwyw0%Myh?`g^y&i}gAsq5~U#^ro zta|V`+`eJl=DJCK7#DFZ!m0gymCO%)&aFrDvQOe>N=Fy*TRIwqQ*~TDJNZpU=2uuh zy#%Dm$+D; z`Fx3X{-wBKqJz&X$l=WamqVSeR} zXx+F$;xIogF8k->@h`WA`55LtCvlkHIOq2niNpLn-{&K7Uz9kE+m$C@?vgk)?w2ER z-;g+rJIZle5~s%fb|mfx5{GdsuOz+Sl{k!>xex9O^ZB~{RN^qdHs|*viNpLn-vg1j zYWO`ip6?;ahxzqwO#b~=;?(>eo8JB@uWQ=*KetJe2hU5sF6niQN9Ok@i9@}0isK%W zIMkcDU;Z5C^E#f9ILxo(RaB3^N*w0r`L=(BI3KCvo{!{vN#Za+ANP|R2IIC^$G;_? zn%~F6d|ExYulRbI&+lW|__{Wg{m17MJzsyA&*RpNtjC8V`EH2BttaDR-Fjb5eYLj4 zVLddTSs&lm!hgGsvhj5;q&$dVa?3d@`v~LKHjBgI{b6IJ;P`zls3SH%_Lu8hCqI#|YYXY0cHbQH@lUnBa9^qBAMetz&LhaLvPBUaXyy`r~3S~%nyBT(s=iz#Hl{F!#LDiJV$O< z`TeopzrTg~Jnq>r4&(ATtDlGYejm6`2KmM>Hl7#ym&^}+p4@@@`8kPGeO^Dj?y|n- zozwe10&D*E@0jGP_SMT}eyF!inQ9(d2bWL)&6xhu`LqQt4bd^C(h9kKPzz24Bk|L?x{&sqNZ3p2GoBRLQ7awo`0cU*Xy~9n5d_OI94?`F#rfxBGhddS)WM&-6SMipKn+&4&^8h1a5!?=ZgNXJ_x4*9SioG;%;#(yJj;L{1e)mQzL2lgrRx_6sbU$oc#Kr2h@?&4r{1~vx&*XcwSNUMYucylVP)CE_)998;T&xbR zn|7c6DDiVY^L_eQx6&PPbt}9z!KuD{Q0hRv7?<5r`Q9Do8>W2RnG$FDH+HA&XYDwp z_=PxMI^Sma@-dko`qD?^-A5$O(qZ~X0A6oa{JHA)z4Lf?o{Wq670Zb}caFqa`Hkvp5e5B(da@$N$sm(@S*{Wf5?~I-s$HZ zJzq=eK)pkhkNc{`#p=a+__zzE$EU7C^TT{T?k6P<^?Drrl3(S6Rec_qPyKw8%kO0ip%%C_K@!y4t=KK&V5$;g8f&hkPn}h zIP5FWN55!&s^!Q1r)^jJDGy%9wf!~BgZl;Jb}o?h)$S{;0Z#3M$og`AT(`mRBza(d zd>)DQYV*y#UFxvr8^_mtsRCcD-eJ05-qO(<`Tof+dhZ?bO+bFDtG9fR^iS)99>8Vw zg?;Cr+Wt7|<@Z$PHkR-EVjj0`9BBJzmy(KAUvj5ph00`bAq05LZ~`gH_jY z%x@Lg%3rm9E*v83t6i_f>$+-vDKO99(Sy_HFW1d_AIdO44@bP*&tBhs+3J>u=h~QW zy8fXrV_)AX_5Q0qh^x&bWb&TGeoQGE9 z{v_LVze(b=;`R=t$Hn~e^!x(L=KEv$Z+CvS>w|-TPxr<1{Vtnc9%uDIZE+G;_4#YF z6L-vt`;lhQY2&){a5n!cYZ&Jp z=VZ%|b*cWnHq6K4-5bL=tXuDGhA(?(hn5by*%FiFx)R5cW@-%pjiz!;bFaYtpV8~WTk zvUBQjckP|&>n`RuL^#fe`S@@5lkogNzWTdleLL~UvE z9Im@LI&bOj4CBye=4W5{J`@e7J}=apG4AK%*3&`KW!0B;;C$oH-B+@$FO`$B&2!b4 zW!Zcg&KTG7C4X}Idf?oW~r`xN==k$u4Vsy=U%EiUt6zhHih z*SzMzisQX{|jX3MXK_;CHhxSSvR$JfvKb2lO5V*lk% zN%D4ol{l-fm>=uQpSw%Kd>;2;cpcaD#@5Zkjgo%!+2_}mI?z8YKlBB0y{8)evV)9k z)uW&IR2|PtzE~aTU!I<~k(~Um(@buzZ{Wm~yv0pSD*axi7y(sg;zUn!H)|VF~Zc4vwMs<7Ez;WP@ zhjFN5?89--i&rTRRc|R<+|rqee)O4TxSPX#9{1lc4)yXl>_7h8-I9%Ol60uP+!p5Z zabLE!cwYwg3+mweY1I3SUK>77*xyV2=VaU|{l^IohIL?ml`YbbkC@Kgk&UnR?(}}a zxct4tIM03DwZeLlkH;Y&;)-V_`C%U*u1Ywy?>CeAVIOcl?n`0+JZ{%;9}G}F?iDgF z_5tc(esvx_oNfQ5e0H3F92b4&&)tv0zMzg4#l?Ccj`^)VU>y2_d|k`p^p+GH$8lT8 zx?#VJ(s;MI#KqPZeMTLHbJFLf&u?8B7xU|-@opW7i_OpSd6@Vu9c@Ji>SbNn2mHBv zjnsj9J#P2#ysVv@`0BQne3ma`!|CfT>KG$_?0cWzKsdk70_~TqpDjP;x9V0uFK&Je z5Kh&xt;`SWF+t;9LE_M7&fDcB4*Ae$9*6x>u2X$Cl6)8!`ARp&oxdubPyCd?l=qr$ zmn|-yM_2F1qlwp`Ka?@zn9bVJ(6v|sSbLX4}B@WNBY9oL%ZlX<29BiaOwM;Tk&(x z<^PpVNahFsL_Vw=^LZV=4g2D8o#E|_6<51%+5){AuCRmbQ|rBqr^7Pj0a^}dld zfpFu$K$J~qxxjJj`2txJ`egu zeU1v|@8sWiO7)NV`1zyKrHP-GFPhJTG@g0K4oi<)xJ=fqxHuh$_2B0#to*dN6^P3^ zIA8bU)vK?jBY(Nn%Y9|((Dv8L^!^ggoA0MF`ILFYJp41ZueAJ_hx@9J^vCAMjKl`|^56AVm z-6C>u~jNT2r($MyMjM&jNUiJKRR zJ1`P=P$cfqFb?ZhZ6?0r^OxS2#bG{=dwaOAFz(O-8JFKT;`xq@jQfsATz43U`Q@HU z_9yZD0pbdi$#b&opZ4B7e$Qw1ifzU9F686)Fpr%Z#+6!e=firBOnm11{`r10@AGiB z`?Qdc-@oDczL$*;pG)BU&==;n>d~b4NvrQk_(3>7j^pl)#EnGaeiX)Odig#c%NNFR zJuJQ{?{E5fI6v>pFTyx2u2na@U)0CrUmgg@WtjVQB<{D7xCg^H)QdW%`273T<7+&V ztT$fo!`b+F9M*$BcaLV{L%rOmp6?go?KJv_`)k_sILy!c2Yn~Wx;$L zUQIsE+Z`YNUPjc>c|+oprK68$h}NZ%khgc)UAC=7&1a zKOSe*cZA|v`At~)y(^qw`NP!rM@yXLb7fhwZmad}k$mV&i{qXkaTu5Va>s>nn$Ony zQu;_-KX(yM)q9G}5A_bxcz2S-q2B7bv_0$%<52GajkEft&~Nnf8QJ1;eJr2*DXx{@ zu$A9AGC%Y=|557avm_3EM*m`U)QI2G!F(2Oi1@ItrkkJpSX@6B35RhxZ}%SQANpLU z@$N#2i}l&^WyH#_PsYXkI&PvqxI*Hr{P_Ei_`Cq0-a0Wv-tW5r}py)q<`r182fOY z#92Pa>R_Cuqk3~v4^_vfWqzmw{o}Zn&m$Dq%5TET@5ABz$^+DIH%Of2bG2d2qdO%Z z`qJXKw@VzxWxrg17&l#?OP@;gTRwLYPVIw_%luF;=7;Y))XqQG2WfwhjL_!!5Pa`p z^WW+3fowi3&qMKbUCfWq4`HABdVDkdzABIVP8f%A`FuOZMcn8=<@tMSJ8d0rl{(Y= z!0UK@w)0JxAHO$rkm9&F=5F`MoI{pZm12u2nMfQ6lKG&+mXRpT{kdIGjiP z-sRr!xRuvqw4W2C&mAK9aDBnP;yh3X;(Bf~`sJx?eLs4HQI8|SIyi4P5sn+{AL<>s zAz6oTo%C@h!*P+X@tJhJh{OGy*!ws5{UtuXBpH1{~9LDkA zZmn>AF>dFev3mC;?51@PzUqleB;mEC#J`zZl`Yz^ZB@+iNu{8 zuAArkd?eppk+?60aZ`MT^ZeR&zkIvwD-Bnn_x`dzzTb@hcDqIT@{O<#&-d*xZi-$S zsP@%;VLl)CN0GRnMB;uHi90>gztJ#XW?z1pkq`Q+>rcsjo4s$PK6-zoj^C_aT=jVR zPT9|08>HV)-3PepM(Ma-dfylK2jlo}HnAI0KRo_hXT-_C=|Kx6_Ez;(8rVtX{vc4vael`Ni(vGoR0| zJv;eT?~(rTemm+I0UYmVBhK{s&)Ia0&rR~f{auVZdXJoMd>=RBwEQOar1j);+4`?* zza&4t&yDXh!nnCFOP~3<7{qD$`97$H^YgehbK-tZYaVHFF~0`rsO_+G>hmO%fE(X5 zeSaf1F6*+k`-QJ0KI3tGcXxG3Wzqb(`*$C5_>%cu-3t$2Jb%&R?zsmnnZKy}pal!} zrvRw8LVVbN|KnS9)6)!yfWh?$;eeTP$zPO%tch5U?(W3eDmUJ&zd}#N)YPEaulKl@}uwQqj zySnJmC5L(*{^bLb5Bq>&tygRx>=(vW*N(%r4cz|(C(Qlx(&stHZRFzOcB~V|Vchny za$fTK%yHdU;`|#j;xb=l-E8^sIP81=eB9t;Tz$Q8T*l?skHZZ{;>sJu@r^~|dN+*Y z%WV{g>&(aDMhzVHm7AZw4zbVu8;9c}-{{xF^J8R_FdxTtUyJMK+NI=7F*xgEne ztjFMi;eIad6z1c4)aJzD+&AL0MqD5C>>bJ18HekS#JMNJ&pEJv?uBgEqb8O2 z$F8_uw&EQl*8j5LR&Whmb=F-g-d{3IKUMyhh3l~oWyj}TnWyuH?N;uu4mP(;J^sMs zibj1-I*thWd5tl8{x6H(SpQapiuPsQIA2&7`_l2@#Fy6f>AsZdJ*Rj)lSOYP9mj@` z_c?F3aab?oMqGHl;d;g6@OTh$T|Y?Q9u3lcG45kw9muD}jrDotPC6fPPdIKYALiHb zh4ky)EBIFY&+1d;%l|O(FB!f3|K}v<1^nNYZ0}LR`OAE~9#p!L^RvvK`$*FFjVpHu z&U5R&8|LHnVC3zIF4S8iy;ffh5f0}Y$8opG`r`4vyN`UmMdGyMc(;D|ywBua)K}jO z^Pyg>2fy!ubxf`io|lYsCuWRG1F>$NZ)rBZfiEWd)p~qE@?kxiBUFz&Bu=YG`R+AV z_9N$uIP|&nrSy4;xWZ49^PQ@W7vu7CcZYEpmvvx05Lft-Tn~6Z5pm3C&7%tNY2T;L zeEhSrX8L`C{lLfT3+6W*iE9H+dmm%|$I=%Khx0A}+Bu?++z-RsOVrT^aW%a|k+?Cy zsqgFiiPWp&;5z&8&WT>s!FA>JdG!8-A8{SuN}oqO-hF>|`hI})TK(MdQ|XH}KREA_ z($77>$Lllt(gd8=f2~NI)~6UZ_cN(i%dZ4DtzWt#ahP9hUrkUQdw)RN%cp0jUq(rX z)i32yW4-^+?Bv(`^Q3N8e*J_~w?`8)KisaiX}tTJ#97-*o)=broui2kHNVGYT+FYJ z#=AdCTx@>U_HvB)EgkL`hK^@teyF2Lq zFi1FczU8Ga=-(ubcN<6?`iJ@T{wm3j_3(WZh{Npy<9M9=XSRCqILp7@2eQ@8;>-U! zt{y{#<2+rvn0lPtNjR*V^3Gu)b6HXrQH+`7K=WH|f6cc(*~e_d-;O&+=u0 za2!W_&nNbuic@@He)lrzGtLi>dwC=-7sg@T#(yj4n{(;MTRso^Mca=pjY+i!RkM`-_*3$S50KZdzy zNWMz8`PTV6>C5W&RUhzGc1iDpA;78i_`S?e>z8Uf+0QYzzi|Ak@v-k* z-#p~&UKLr7E5p~Ba2|2o|NTs#=N%78Uo@Y40GEF{d9NVGEdx%i2l%JWj~4J*=aJaw z0jf9V_dh?9-$q~BRGz2VEV3S3gmDoA|k6~Z`xL^2h_n+`Q z^0v8#YMV)Z}0ORsFwXa?yby$33e>Cd$vT%N!k9&2t zxa~)hb(hEUx-rb3Z+d$Kxzta6ggzp2xd?h1ZQ~$E5)5pO44CypS#KSl;OS*TrqOI6VI} z{UadiKwoN)rO#iE<93~;{2n*rzCK&r;wufGcgx1d`YoSF6dmYuEMLbH>AoOeYhy$2 z8)il?=k4A&GkmCn`LR#=bGOI;-?*4x<4@`J@cHdEJNXsbM%=x##U0%wy$3WO z*vfC8Z285;?R?VkhyfE@@rCD%+JT&CA^=*xPecuA&ygUzbW^0qR%awo(|k! z!@lYwe$;`u2H|kOoprb)vgKF#3+eI%>E~7WpDi8zz^9#OEfCJq%W?Uqc0Wxo@u4s1 zU*}(?UOvCe{LbhDP*;8n@| zvifu!bWEw+yRyZ_x@q^duuh!k{JGmIV_X`Dd{~dJzbAFG)`MImu0c5T+3VO&>cI8h z)NWJKDjmEp8#92O% zZYSp@e{Uq~b6?5!d`j^-=^ww(1AW%&I|WCHSUy)NuH|!`aH`L5lm4O4BdqVO5@-2b z{>SS1;_I<-wz%kX$JOcA%a|X1=Fid|WrR|DMRU4s}v~Rz3O%r`Dq)ea3o>u@47IoK+7^FZxn?o%F9>ogn_ zIgVQp#$j9@hxI_*$iI?4uza2%oa*yIGC%aWOy?Ec+a(Tt=Dgi$VI1lh+As0h(!u=o z?{6*YfP9Rz{LB42&c71jRR0c@deJ}5$Gs!`J&FyA;|`I0s?WV)9QsnG^R}@*qkmq< zyR*gRama`HwO^F$TI}~xX~%D!|Ct`2bzEWj$KUg4>1AImKKEa#qjF5L4xxWVz^$%- zb>P$Dj;$~6k5c23VDx2lFIs1hnqFU_f9$I}H_Yd8?+oM6XM8Vvhw>hE=EwYyulZ6^ zUv+)?Yk1w@IBp|(9|f*MIY)Ks&Zd|7Egh?i5o-hu5uKqRsJ_^J!KkDVr z`DcTFS^hJ(^7rH^c8w4F-Ve`*pF{IF{$-ViRI{5R_V_{zyH)7y4UwC}!@5PlqXgDpuaw{&s;XlRUCfZ?KY<}I{$DOnEv}H@r z=wANY87Fj~aqL-Voq1k&@3OPHk2~|6GfqfWN#~~U!F|mW%6;qX8~S4Lm0y>f*W>Z- zz1jMz`5$AxeKS1YFu!tFIv?UVUsEpu5y#`*2f}(i?pxV(@HmW%I_jTEzpoT=qwA)x zyNH`4oVA`7)=S@haNh3QVZ9!Aao9i1uW(ZOI^_BGmG@7o>)$=${4j366?a(j;qiyh z@A_)<-Nr(~bv{J{Jgz^CekKHxq@ zKF$N{!JoVD%lvR2A>ZWj+17jOeu4hH^pE@A=lAJs^EcO%YAbP3Z~m1s zKaCIjC2Kt}ZYRaH`n2nm^!dj6-DPtAVtt2L-^CJV^=V&Zew+vPAL`AWp41I-Jl;Jc z`xNu@xG!eY!Q(J4<~Oo&(g#=%9`CM`ana|FO{kBqmN?Xbahp7j0%`A^X#tL(dqO^+ zum2@{{~G$@hkaP;K)tzFk>2Yi&eF^L*84X+?%d?Q&BC*Z4*uNzP4)}shrV=CzNi;* zo}Yfv>cKdRZqOJhUu*z31_bo8|p_7&rfF>VwN=epVk0 zoD+`g1|=WH?c=z&Nt_k8b*`}v{Ucjnu}@YXFwW}x;$}u4d?tKeet^ciyR-Si`B}$D z6T}~@mwB!A%Hr$kFnsx@)QkPnqVeu)5@+>G>7t}xSO@RF;QXDS_k&tGD!u8)Tgb=p z_<83t<*(r|ZqGUNob0GPUxL1H9Cxqu1#y#`(>(v4#996^ztva$TM$1D7=L~GaS!f? zY4^WyT=a!McR!UnP;cyeT(jU-#J1k!>hrr*=7&D>dsq2AB|NU(pS*Xq(3h;+*e}Do z8T*rK$mas5>xiLpfPf-WvSNuWx`Ijs{uX0I?ZJF{j_Px67Grmu!mwX<+Qf?pJ zP`GZWw|REldeC!kx-V1swl>zu4q0EUhd1h;unvz~Tk>JQV1C8*5*@fdRC*2d%gZGn z=7)ToN0Z)Hpgku%Nc{YKo`z#S%#S~Jt*|dzez^X5zHduD%Re56e6evgoV8!l-X^J! zx}I(z>t^Z57mPmLM)FyGP@wlhs&(5i8(;0#xOwS*n66{GK68E1XXLAIn;w_PyH{q@ z%j2xL6IR?!WL)fn@^(qyZexkF>Z|29kf;5eOTy==(Z43;f&GHG{tME#mx#-4pI#5d z^<9|ou^v9}$bY+^g}0X;HyVliWhAaUj6)r`AC}*3r%cxek*~5t;ve>(*Zcd`%a5P` z@O;N+cqFd*wq&V1vM-?x}IzDIG2UJ5X@ ztGo|X!&&PP=gU8}{k7iLC-vp$=!fZV9_KzC?q`qtY#grketEtK`;`f)3MJHPkD?xkm(bY^$&*(aWJ!kH^_)9PWJj~Koz zeH~)GZjWroZ^cqlH(WQmyAPZft z%oX3;x8moX%m3>;DtT`n|Mc)rOz(K6@4RhS9=FwBkk?l+?#Qu8T>goAYnRLV_WUS0 zp2@u-sT1-Q-nP}sxcn3OSQqwHclWW&mYucqxO0}B*nPr^``V8`cG-z1bf33$S4`d--7G8-n}>Up{AL{O%Rs*FCTM$hphEE_}iKdEI-J_S|!y?gI{AIB#+H z{H`S{xmM(oj$3k6b-u)5T-^WjeQ@CNFA1O5)z!V<`~w#(>|Qwckok+NbLY+PK4SUT zpf5OdA?ruJ${XeOh@bQCX1@8$8~uN5^A26OWbT56^A~A+?h0AA_O;1zyyyEL*TMVm zcX0Qii@KL*z5DLW=W#Ob6s*Usn3a`9hb~-j^xP%ObuOQ()$06(iT{QW%llD>EVr(E{{<_)jD5io^C>~}kMo|=SAuW(x4L)D?WQlNpS%3~ z=@%^Tjzg-;Cnxfa?V+qg%(wh|?Yrmgv(Jj}qfff!$a%}ZkG^}wd|zRr*RcY(cwYCy z<=+}VZ~o%Nhb~&&edxl2)jlZhnZ(8IAnS9V39knp_j!rK^K~BghVVM+aeGAKu8?uH z?V#H$%!l>(QSrF7sJ&8+)hsftH_jon(~wR{J{1 zcf|S9Sb)dT~|0G0BJhGV&(sm;2=XG}tehbv!BKt~TFaBp>Q%zL|79 zC2_HFxo-SE=~%t7IIg>UR_2E~G(POpu6;@G-z8tHUbSDIn_<3xNKn??uUnI`VHN9sicN>FUt>K&{&W^0*Q68{+)jIxF}0xgTTmv(|C+;q>xDpS|Av^!Tj$7WRwNTOpjPcjMW~Z#Xi)wvu1#$8>+_t7a#^+Ppab zxQhtz8KlB;66^Z}folxL)r= z;r$$sdpL~4xbE=u_uzWI|C4;Nb+ddKJ}_PHl>8_Wi!WbE=kq!q4eO}Uc=w3J%~W3v zS^52OcH$Nn7`{9%<6?d5G~PWXak0MO{Kfi?5WiL52}{Q<+17)hcO`vq#qD{!;oqNT z$Cq)6Yvq?aC_O*)dHA?Ey-bFd!6?PG^iEp&t(`5u+;i#AWubq)8Q-&G z>A>qV6Z4AVIMJ<_O$XPsC>p>rlcN<7tY#&(pjam7ERX0sEw=g@RthW<^*ADd4vuC-klr?^(Xt|m`k?lS z^yf%%ziHsl$$nF8+$^}5daw@8gZ&#J9mAv}OWYOrELs0s!MEanR==E-z}&=BiBD^; z;TkJHYV5Fbf3v!0@;%k81Mj~r-;~s2=&CJO;&FW`JfA)OXnu}_5DWTCazBUfZEB8zl!oR;*Q^v@C_Td;;WN>Y1}G( z!MOc=Kc~T0pzqBo+#>l+1hq!*s$A7zK#`83gU+-tq z^XpUMHr`9~GNXU}9ddt-b@2K;_#b(mphfHR#P!Mg?Df{e-?v!#d6M72ZE}9#d>h@E z^0`CqZy>IN-}_;#S6TW#X1?X`rTsl)-H6>@_SI>A5G_LMDpRh)Zz{uNBwxgw(>j}H}reM{md|TOL(4p+-|a; zt@AWFx;}&31*}_tjrvj3u~W9VoG!NIhsd~?pF58F_aKRj%@2J+|Ek2V=6Bfa#O>K5Ss%2x`N>m6ZVeBAvd4*Rch0{J{o;;{cb z-)FPEUo^jWxDQ-+I4=6kd06X4<;3)L1NnLhhdy&0cf8CG{Trt7?pTRK|Ni%W^rdGk zUDkcVdB>i0((*5oIJx`mr5Bvoz3kZIPCIdBNX(D(u=Fy{S`Qeq z^`bA+)^T!N-HL?6{F?jF{5Vc)H)ZfIX)Jw09OKwo-KN$T!SlQ`_tDSF?M9(M|kgjnyt zsuN%AdWAUl%k3-sz|=tl`Mn>bOA|j(N9U=@=eQmqj`OhUR(@-oe`6FE^1BSa55|cf_40W4P`3TV+!^VMNlapLi=7LMz2ZwcctE|0_f_;a@`+*ckqH(T7?QOR)t#>M=Gm!(((vMRx?$9~3&Jm&Z{&772tX-esykd3merG4;f%%Qm=eWLb9Jfr? z4c9e~n=f&=4q;p#XYIE$&eA(_?#%W<$9d^|oR7Om>P26AXuP{X;$nTV^l~1!Jwl&b zmX7y^^W!*fK_spoiMvGN&_5sd5Q#(o2J1Ax8etszGD_@*BG#eg0y8%_Gv!qa%*s(o;I*k_+#GmM*Vev=t&%FmB^LMqhnodOCRjAV>V1x4R}AU*{){$o_*ZivfgJa22oE#948H;l_V zaQ}}#ccas*hm~LHl5}5u-0S7_nVFiu%x~p4YUOv+^zuWWu^#!k>E{_ZZ}-*d#kKS@ zKjQdv_sMWvkNZX#hkAJ&#zkCpzjR*^SGz2|uV(r_H_qFAE37y6J~!qo?IZ8=#lGkJ z4jc73;yPmEBXmD-UveKg`cit)I8XhZuny$oe6eo)dHzy)e=_PozS5OR-9|1ctklKh z5!Z1=dVM*r`|ix@Xk^qeN;>M7COUXL>gX%QZTGu~54T6GcOqkc{e6jl#mkcXcs%CE z{8(SaO&a;tE(`Yo$8q;%t6S}=L`UiJLO@E9 z6^RZU@4g=Ph2y#(hjAEp;=s7$1?ES+Q}{^7=nctxyUUj+bw`{doYv3or(qpEl_YQX z%`k3CToPjG=(#4T$HbLMJ%$t=qpt`brxdOT_dVuUx;BYB(3iyJ@rdicXJ+fxBE4EY zni+LWl8(Wv5*;|+JuowMR6;L)qeXY-G%jKV;)${jq(3da)j@ zX40p~$8p?vw*1D459f#H`(>EV;~ov;P{-)PncXgoelYO`bzof17yXOH@p$*GZ08v& zA4<>9^NnTmuU1X`n<>5d>y7*_4bQjC{ymvZZ=aRl!`b+%ho$@H>rvcL9IxW>pvOIx zEiR9X?LTWh7`VZx+g;)OI3IU%_`Imc-5ut`KIq-S$nU}(qkL{g;tChV@wxLO^$tYh z`e%54d@dXpedhXD{WAICq#m*TXW=RzG3xtC>C2SsA2i;5T;g!Pq29(}#&-Gx+4$H$ zOK)etq4$e2F6u=cv2huP_2tjqm&5(yaW{tZ^SGA5cWJVIy01t+t8RUZ)9a@Bf_f1* z^3n8u_By^B)`5Hz#E08e&v%p5i}mgKSdx$XsKi;mOkN(hKhz?A%nx;NzLtNvo6`M5 zz7pXuF2`}VNWJJwgT}j?B@TV@d_Rylk7q~6IPt6b{XART+)&b|T)*1m$$M9@zJni) zTi1qeNuQUMkC89G$d(`HW%kvrarLbdPWA7}Z267dl-|$PkCWb~vhl_0ZQm{HHhS;Q zE00gHZn%F?erQe+{G7jf94&%`0@(JnN4~|>fB+SP+SIgFa zwQq*wy5qupKJF25xZ=K%I+n!oxkZt<6XI}%x5eex_trRE&kkW+-}=tZcZG44Q)#>ML^y7&FNmw$ zkNd)_Zk_d%)s@)da;fX7j&gY!lIG@Nzcbu3@+ zz3J;8#w~3g*H;z#J}S+Z+8UAT%fDsa&_CAaz9xO1?r~`DF6yIy$+#9@{pWG_dl!ae zpSn58_Sft9j?{sAu^t2TUR*z(_z>4p-m8W<=E1(=&)t8+-_z=G|H;o8K9{fB&RF>YNYF7mBMxL)F`elgLH{&mp%pwT~G?Ep?IU%Vm7bNpQiZ{f4@y{p*wJl>ri_Id0ZG`|c!)Y11q`uz2AM`T>g5BYc;`ci*q zlHc%W!g`zckdAw0TKykadE$-_T-$@HI0w1K-Du zacd*#J|nJ4K4G77KCTtHKlDP_XV3TbaKCt5E<7*)hl}LeLe8` z?Gp9{`TD<}^ey(E=X)_5ACI$ijMDdGU|h^EPx~L(FC*tC{Z=sgl=E>rhIM${u&ghx z2OjsUaD6@Qzu~yWZ_>K)Eg9EZH^#3{-@iitI1g*xV4PLA3Cb7i#^c@V!+Je#tFT^= zdqbG7bwSbxWup(!m+DVeZ=Lk{?G?@s;|`9-t&{!R81wRuY;ieXs}Bahoy5iYhB_t* zhkby!%6H=UMwEJR-frW_^?AL>zWQw>?tY2G^#Jv9zLw9m;q>};(&z4nGOo2A#K!F- zeylH#cWZ`y*7V}K;rU*bjj#IMbYGfBC724OvX+?QvIJ3w*K7fr8K-}3j;b@=?A z%2wYV;=}xyuV8#Hl%_+gTg$lqrtw+6jU=FTGtqddiitr z7g=BIQ`B4eL7XrBgwymkU^|F$+ce&75cY+2G%g6A-^d-EX*6oN$~szh8>~t{Ll9lgDow?o*7*{QR@DX7Zj0{yTSZ*gwW~UJ}M(+|iN5 z7al*fPNgr5!I`*gJIDq3!j?EEqhx@{Dd0aIT*MC_yUxx2b ze5rRQ^N8c1-p(IM|J-hg4#edNSF9y`tPgQbIxevKw2%0jk8HEjH?9-%;rUan??A@- zvhQt*%j2iS{ju}~k(X9Z$+Wof7vaVLl)CvFRQ6 zSo4Va5yzjqABFQny%Xd!_Mhk5Uh?5~+T%tf4!0l8pHP2n8^(FQd&4-?!Q=RScs;x> z^FMqq8(-h%;q9B-E*sy_BMBdWe-x*s>A?CTuKuWz-%c_=tQ+!8{xqo%_Ce)mRJR=^ zAJ!N7Sf8b1nD{X+k9TusCvNA@)AjneJIlD}UmuNkMTxU~X*`x*H}r2X636*kJ~IxF z12ArJ)bQnXQZM>~d{yGZ{08WA_gcwk`Nukt594KLT)Zg+`89auNc&+5~jcKSTx@otZ7aVIHX%NORi zaQzP${&mXy(7!f~cY8@3`p5aWO~U8-r|a|Jlj%MqU+q_kUdtEG*TRhvpSoRmtMmo^ zEB-pk$L%X|=pX8c&96@UYJTO}i92D%-CxE1AerkBTA`7w^qH|2Lsd_o=d|4a9e$Gfd(C%?|) zlIu*Cj`FyX-^;`Kc^%t^ap((=v+`pc|J1%Wcihsk{p{wKRfluQ^&a$P@R9U-AZ~Ij zsW1C7S*_;Ytzwzxdb+8-KxBGHR+F~6Qi(zjb2$GvuT&UaS+WYps=;ePS?mBTpHTR1(v zPZ7ubmVf!Sp<};n`DtM)BQsn z^To!UDcp#XALrv1WUB{{v*xcmb7uRr_2+CpV}6{sdo-Kg;x%#Wct>xX-qEKL9h?u} z*Mj{r2{?XE9dUU7MrD`e{v5DB84^rcO4Id859|Lr~$-oAO<8^bt^%j2+55jXUgL@)ZnqdjdySGT3 zwH^!}ki;FkIQ>3VH#Zv}*OBkHEj^QdJUv=S|9)5=@8(S}uH|$8-@`taKedLq{}Fv| z(|9+3dim8hP3{w9oj89xpGoqwbkqo^&hrJ+%Masnp6;M9pT`{%#-ZNk4oM%VaSzSL z$9eRfNB4`ql-_>>&n7G&?^-6;|m>x(td*}wn&Oz+d7BNP8r z9cN50KWl$z`1vHRrK3$aoWI!5`F|QZdZ(v@{p0;{{@a}u=JU8^VI1nsyjp_Mf#hrX1y>6Vhd#8+x>n`do{5yRfRp@hfjO2@5pRK;)d=bZ=yLZh_ z+|C!%_4>Fq8Q1c!{X+V6mp+Q)x+Nd_=i_b??o*H3Cd`NR?f7q^m&fCC9Rr^YKQF}N z-1>3(bqK z7{4Wqn-Z4>TK<(@GJH8z>P24~G~O+hIP`^ev~LdUU|cm4H*j9~d!f*meA!r^-z{~Z z-d;z?5obyq>czOM%c{pP@vGa_vu7u6=Njqj73b~FlX1}(kJ~-G9`sQhcaG$<{42gJ z?)a?=I6eo{&N-ABT4k#Fqmaw&_B$t&EqIhwGY-v^jbRduaNV6 z`0DiQJy;L*J?fN~6}OY(s{Vak`hx!Tao#scoaLWZU;e!P#qjnL>oI2O_(Zn+2L71T z!}5>wMI3+b_Rluo2G&mEs`a>8>cDz*y`OI|8C`1TF3DD7MUOVjCu=e!F5>5uR(F#rzBt2dT8^!u-MqI zyES9nNdJ1*HT*ju-1po^?lzep`rM{C?$Z)y`lsmdaX&LNeAowl>lwb>F5{x!F&gg% zCC=1q&9`UP64#kbKE*%OTVLPMdzaLKdXcZ=K{=0j9U7rH?oP=!Q##5Ur0c-^T7=_1 z;&lyi8Q}TWg#4*2h9fEOuf7m#^mnD{u$Ga=C-6zB2to+&= z#r0|9PC1V{k6ArmYWcXh{eO(RuZs0reZ@GwZpwda^|1H`=)Nz@XO1&dxcV#8=Ml$o zrEJe_j}Tw%d_x^R?(X5Z9(PT)?{naBRy|rz#P!R_?Q!c%?oV-igBkC?xB9PZleqbz z`NE&O8^S(&TxVq6zCAnJOU?uP3g>0<&vEq_D5al|MLv$p_W|TyOuvrJIP3aR=ceiN z664kg7dzjqxI>X~$CS9N&s{OS`dZgRtFMmprA|2X#pieB^zs|JD7l|zP`OWLg5p~9 zlJl_Eq4H+w^OwiFzOW9D`&}4^ebss@ZhlO@FMa*195vUwVm8?fdJp=_uC{UpT&cK9K-ce)%noetv(p{Cr-< zyzHa6)AgC-xDQM(Kg*ZmmWD6QY;lX(LmdC4wEq7UYeqi$NG#|E^9UYZtfK?Kr*qTHBcteb2Y0m-Dc2x$P2P z7~gS!`gypXZPWeZaqe?rU$DM2eci7_I?VM2&O7pT2(ROgY&sg?U+wW?@H!LDqba^n zB39iB+o#t9`6ekp91BfmqsULNnh5Z2*w8%=Ls znsrn93U!Q;4$epImmTH2tnH9KFFXDr>oLCRF00jlb&6}%V}Nit-&mI`XY;uUI<)iN zEy7v(jeaA2KNjoJv6J*!i`xWT{;_19d%gQfz1DT1uIFXlwD+dqI@!85y$?7Kt4~XG z{e$t7^!=^q%OK>(&j%o`5y{t}>p0ji$TtdnQ+%E$eYUQbRnC+9VSN0-`dvphzLxcV z)-AK~)pnNs$M?DU{9cod5Br7hhx2^fX5;Jsr|eVi1J5@n8y}Ce`gDp8rBB^1iGR2r za2&UDw*0EZhkfe#4#>ubI{1Dw?0e?tw z#eXIJg7rWhb&PkVuYdXX$a${i$1>{Q-#Yzz?Q1jEmk7;%W`DJ~Zwl|f zpf7_Tj=R3lN4}uX?1MWvtk>gC592UD9+x{#KCjE4yEA5(@5~wIqeR#D2|Jft`Frv` z<^JQlv(=5qS@Xl~mOejty!(obYwd3oUQFgC_Cb~6xO*g@wO!>rPzQhR4x3&*@c7sB z4TbabxXDOdD~!|n8TD$o*!95T>!-R|IM#3B#!Kmag*r;Rr{g$|`=;~{`)`!SyRSG@*y0rO*A%&)v>Twk>ahxI_daRtZuxG||0`^w{%h3nC^7xmR| zB_H;c=X;0bQ{#RslJ6YJhjGyt&I9`oas83^*D)W~gFkoQ3G2YPJdW>cY5qG|uMs!# z-}Lce__pH1iExTpj97{`44H{v=z9(Nvz$75Xn-2EWzpU0gyy*^-{%Zks{ zeWZUC!#|woKEL|(^27DT^Zg_23)X|jvEGpv()(b7^kO}buly$I3%_rPoosPO6dhVzE5Dw%8NM7IzVDy)x%IN?;Bi)dvAA40 zT?hJ7ip0gnE$^M|zceqE@BhQNgGyYEU-)zP>Wq46prvDAUXmZj;pd+CZ`T#>mnk}k57!~YO+ef!_eboQ zQ7_cDc4PQDgyly`E#=>VO#uH!#y`{IOuNxf4{W9Et z$TvuQ*ax1kmd(H3gW~#N7;su2a31J0>cIKSeSo;mgX8k+r~ItGuK}OBy^O4Hp7_*y zJP@ug`^7&S{LAv6sq59r;rjaFzY51ipLrbCjX&?dJ==R{s)vO8zH~=6z5(LXd>%3Q zSV!&i;kb-*C&c+YTo1o*j`^zRhjCf!F>dg2T>o>G+YM6t>et!&Wqe_{zV4OT_Hzc- zOurAs=l`lOpU0gZt{eJ1d3D_OvQka-V*jnRJn#x@2X2(x51$YI(h;enC!3DJcf?)) z;B;`Fqc1~;$#qv?O*pR4uQ%KW9#;tS zp)Y-F$NAT`bX*zE594CLbZxLpYQL~9tQ+!`K9Ihh;qmUmZ267Q{;5@8cVv2fF+a}3 z(otR~t{zp2Yvos0^5cBm@51l>n68eFuJm=o$8E@Z;C&fgOA{a5rfZA)f34%j%8luL zpy{yu<9x06R^-n~^2O~Xk9Vhqb$Hx)VI1n{`)IcP64dMC?v?HRSG~&lE6?|$+~39e zR*p{k!@VGJSYOZgzKp)SF8%v<(7%DT68}_R{u|B@`8Z!|o_Ai5-Y>}4`Hu8?gt$J! zsr~mdxn00|jL~@KBo6C=abxusk4e|TJlDFG*X7clT-Nk_;{Sv2UF&+ay@iH@deklQA@`{sRR9M z9!Gt3u*6yZ#p)d=e(WpMG3e6kfjIO}d#*P&zsB)K|D7c7V?_TjzvhOC4(tQY$1RaQ zBcI2;GrYf6IDzW6Nb+IbMoFJLLFzyp>fk(32jYe)53DbbcSnTtLp~m7#U0!zyFz!esE>>^z@w_H)XvVn?{7<9UqSCamR)A#>Pe5B>9Pbia5?g)p3%{59`L` z-FqYTo*2fpmr@^`Amd_vV|8da>$tn`l=S(5e62;)XJkbCrA<@MPYw|u`iy++r-iGY znw}qzciYa4f1d9&$%lO~LHW2-B+jZ^^E9eA1)6eQ=;Uy}Oz{u4Tg->J$t_lIo+BUo zgnh-IyY2oTd*1=xMwPXF0|ZPLU9?3&0Edu7?lM(LFmaX;v?-v_tQ05Ck|NSDU3Ak; zTgVrr|M}uP&Pd~P-}9dL zoO|caozcjfF4#_02N}>$)z72z6!o&JJ3r*Z7K(PX4lKKKz2z;kx$``y7kIO{=vP%& z+4;_OrJFZu7hB+rXT|$~w|G;)PnBPKT$Nof3jse>9Zv^%ad_;ES z{msHX()qa`-4KULmq^^Xo@H@RJmkTSb}* zwC>xs;_|u91%CCE|o-QfiLHSWUwnW5}-N#LJL7gdHGr`NdPx?`B@#^|T zJyr4gmx}RXKc{i%;!%DX$@jaoO8lZ9_C#^IG+p4_KM-Gfd`lG8e^okDU1Z~*?`ZLO ziN}59%~IZUNgprfS9*Uo8SnG%tGd|Tuf^|lcl|88Wtw$#enTgSI%D3bU5wbF&eX1j*vaaJ)|G6$>Lz&7Iyg~`L&h&c>}33snszh}94DzR zt?N1Gm)dm^zp^-}UzvXXlSEx)`E4b3x_;v`N*(8QCELRB6ADwNvu+%Tr}gGdB`1sV z>c%0<8|9~KC({}GsdOBF%3J?UK)iGuM?dUL_i=;PUmEaK^V9e#qRy&#kq^!{@ICvx zw|KL}uXH@H9Pk(Dm&S``G#}J1{)}GzwMp#I54+YqUdyh_-H!6Zb~qoe2OiWeFp?jq zX}wT8b{fwwtpoJKlJ5Mn+d=<-(cLc3FE~);19_%{oB7G!DuycBX<~g*SeYXPx_bp5LJJIy&-ZRqlQ* zyLY_hqeJ4C@o)^G4%{lqu?OA8&r6=ji1P`Kj{T3wSiYG>){y4*jtA+;ygST`FB7;{A!L z>nZKa`FKF%wfG(2P3P>n&UI?xz3(kvdR!=xtcxN(jf3jf(c;XH+94jTQ{2zSc+-WQ zr&oWOa_73I{33v-sz2nb(xpp+hwa%1?s>E9#(LBR8mjmqK8-iN6U?6H4L1$cG*3G2T|a{35>8?<9|YHFZv3;H`g1`5o?!Uw4(WE~o>W>J1OuQGT=zQWrYM zi|yHw1LHSzk;3oM1LL2KWs$%?+`Wu|Kz%*c!^e7 zK1RCY;2(#uAii|nVtz-tTCoJ?O>M{Xp|;~XtL?acYCEor+K%g@w&Qhwx~48_JFbh` zj_abfJ87zmtj> zu=J$V_Us)a4_vgA0xi1LsKd^N#Zf4uz)-QGQ z5zxd7Yuf3KLo&Zqm%#PT=Udbc>Cy8P+|M=?pL3#GkHvO)eL4j^WPa)TB(+Ok%jX@G zAGPZOJ9<8dd|1NU`daf1&g;t5FJ0fo`lEJDqxthZkdO5Hn9%^Xvd`_Xm3+QN45g^LeWll98&RPH!ApD=55?SJym|2RerA! z!KSk zwTs@YsHT?KC8yxFy)9jzA{Z!7Sib#M8-!5bd7qj=PB z3i#6FAhu_>h<<6jzFQ&Qn?yTRyogW7d&;l#2)#Ou0S{HY=vQUe0eDhf?iAyty3jau z{mSeT?NFx=Xx8anB0t@HsC4Q1r=nlpBl@MfgxjHB?iTG-{CXjNnh&aT=q?zSKuFbd zB~kCZZKu1=)Ncfy6Gr)2xEi%(&AI(P;+Ox+*J5@f~CC?9|@%GHq8z<9}I4GX3 zet~=R>YyI%q;>GEs0-B(`6PD{zkh++wSgb@jfkhxIdiA;dQL;b*fC=o>PH<`*Dz`7 zgfR_c4m~6?YGPf(s0jx)Ogem2q@j#6)74Lj7jnl#9T*e8x5iv&Kl3#HT>@3c>z1kf zx#zgm<(Fr7uU>xJJH&Cfb7g7ndT&F+w8e`T&Y8Ysabv^r(-zKeSTcXfqQ;pG3mX?L znY*~50pn>HJAT~gG0`ZOder2}6UU97GP$nduyK>djUG3C+~ld;(y|*}H+I~Fh6$q% zshboTHKxu;%!J9K#!aZ3h={OV>3+T{#T$R%==oIJtT6sIs8y>b(^~=tO6?r?QfBYgJ_C){S(QzZusfgpLf$`fb@k{w({HlD^ zKjIump?GcmjF;_aywIcl8*fWL<8}8lUg=|c@kSqZ9uIWuz?#-fnPklQYHJ(DA39+y z|8Gov-I#;19w}Z@lVAK|KF?9jU(k=L?!%Ak=_13!{jAAbKW{D4FV(N)iQ?j*c+q~w zYwu^gUJ0I+j}N`&1KX+UCH|zd&e)!PG%$X%D!-Y5@f&+e5%0(Del1-BTjlkh#g?nmo1{jBqOJho@6yz$GB=OU_}H>c`v(U+a|qj4Z#6<)gp z58JcV-r~h}D!<{ooyRq7&zQIG-NbgP>-N1bDDpeV-7orK*SlXIEHodXSDo`~`CZGM zU!i_GRDRbU7{8^jImb)mh~A^9mvsh)UzdcRm5;&wxc!!nVm}K7KvZbw!#sp9azug5P8c2a)-5$lxlYlZgg zd(loc&%roU`eju7ei#_P(GQ&a5%Oj~iGHar?a-e6DB7uX>G^^m7o_?4*&816Rq0&+ zFGaln75&n9+n_z`741~<>hjB~`28|4eq;Yu=<=KBm+I01?b)xQU4QAqK6K_s$5UOM zBNDvqhy1*RZBp2{tE#^)iC^T+d;{Y*{E@SMmfy`qzcjzC(4K83+R^-4crD)QpyeaQ z`QR4rehaOGXhxySR-#|3OFOh@TZ(p6mqPjVs`%|SFn;47D|GRTeyJ{b@sf3A*?k$= zU!9K&d3aE0s{R)GL=ngK?s2q0d$yfu*I)U?{-TP5tx&|Vv&c`G4{%(6w)lO9GM!cP zu;%p?{5}xpf4cgq{Q6gNzbgI0U?-h#?BT9oE3{|3iFW-JNAMHp@vqQ)1V7c&B?@*@ zU51PC(zF(o3+Y7KR3`Ax3`*Z+5RU9nq90!dTb)n-1?q}Z>7O#q5_xsNM z*Yf+hH^1R8c)ZxYWB4A9-|I&23&Q(fWV+Be5T6Zlzu!WJXSIjVK~lSxF7dt**?n^~ zj&{lS^7!F%Z8Q$*H~6KudQssqIA6th@%|U;H=*m7%!m9hIDd{W0@pQE`~qJ&$BTSf zM*JKf9mg%Z4czM>4u05&A|4&@+r~ow|Ii(e>KA>}xgSwGGmRJ9sdS0Hq*!(s z@fOdAROg*H5$^Y)`L+D^x*y+KUV-Dlmzr^WR#<;i)xE{ndcpgp^%hv>`&0` z`=iW`>KytG`U^D0<3}G7e-*avu=}NW^mys}Z>f+cgpuLl-*KD37sl4^*S0(NGGW`{ zX!jq@{ALF>zu3>?J)-XHSj~EdI0LG9e{_#GFK>WH>(u5Z_cCGI;i&Vj?r}6UOkXl* z?&3M~8)h^e8*iA`IB!wo;)eMPrq7>g{BP{D;oDy-{i3n0J2>)F*y-vbvqN~*=MrS& zc*&#U^GoQsww>|hg+Xf%V)2i8zgkUx&_CrD{lR&>N4)y4-0={X{pwy>NyMXdig=Od^zd4~(6jR$+rM^+<$8F5FZJyF&+FNBDC}rGxBM*5 z$HRN^^D@-AzDv(98={xD^v8O5O`qu5u@#zj>*(=oQ{YkkP^Z2vnP1)N?w8{Ayy?7t zVBv4zj)!)=pK9u|u^wLQXYP13j#4<^myJWrr{_1C_2!q3&n(NwXUdP-MZOTnakjm9 zesz-TU?h{*0a?R zU+{4)0e)CW#G}V)8V91N@GEn>%ghiJYK}bbtLMy7x>a~h}y*gPnC}l6US#< z=SLo_+FKo9JC!cJcSXN=K278B0Y6o|F|ecYA|JNDm|t2i9jL>8qFteNVENtGn||?e z&d+nBxK^e``9M3$kLr?@_{H{YmZ%HWIkW-vkC~z! z)eqNCljkkWt)He~Yx#i}lpp?G6-Ni~kk(6+J3n2&$cN1p@u)754MCT`igr{NUBA>W z3HZ`@=MRiu|3=PrYU#32^h!;$E06S@Z zn?-(9=QOluOGP_fomKn-n<(la=ITss-JID=)Wh6cKxMa z4DhA-EqC{eIvu9Z7l= zSw2d)5_OUJjSxF&K1dy4f1~+L5(v0VLzpHh5Ol_?)kOs;02B&=3B@6 zRRWrLySv*_olCY6^DDbQJ4ozs9i8GOBz9K3r+Pcj)6H+1_?5-cOYGVu*Bb+VQ5TsV z<%jiR#arqvA1UION$xYJe#2KguXAMyo-A*^ZN+$HcGRzI+-Toj#FNF*cC>h$PF1^) z<8;1Z>3py^ov|J5zqFpwj{42B+m6Re=Ox&ljW3L!%5SsE?}UNz+oSS(=)m~(uMq1> z_Pyp!+bi-Bapz~{?Jw?jd368{Re1~Upy1ayFn-%rerLP;wRC|O{8+``*pFL<>QcX> zLYF!2{0jA(Qu#f0VEl&uq=!#Cx1KzlnXFuY*~2y2u^RvV#}) z`st5)_6HR4E^+5)=VRxp8edvfevkL&H*$bN=M%i)VJxaRqB|?}J85A2rd57V85qCy zyC~v4ZD9PSRDMtQ=C@;vqF&DQhNoLEExRi8J8NM4vLOn;XAg|uW|iM_2F7oX%I~=Y zh4a1nO_TF2+4*W<53V1^C$ozlb%~zQ&-FKk zx=cy;p@UPj`$!&@BjLq)%`I8tAVcCm{j>&j&QQldE? z$gVH=7Hi&5Nc_si=V(xjL*_Rzh1Wej4$?Yp2Ru4&qIMm3>fvF3QLUo~%6J?qe)V9d z;uriz)J1lEL6=`jlV50>^Y}vb%WB4f{8YNc%6Yt07i`a-TSvIQPw!K(?5fsxwWD#+ z@t|pi^LT*xsyIq36mitJ^Fu%EP;)wT6R<2?WoSZuQ}J1g*VC@9=4
^;h7T(zUwuX^`O z>TDc0VW~&i80qhAx4C!foP73;g1ODgLGqs9-{=9sSjgX!n z3iV9?T~9B1sDJr%cJ=QkqaJlEoFnRafscfot?TvYn#V1i2_dI#-lneRRaWW6-9CQD zJWcg*(lPgae?6OL`On)x&yl_S+okq(l+MROJttV)BYA($^dAPh?qWHio;7eOJ^MZ? z7PrFnA;mTHa?k5g>jKjA6QQ2vNA&cvhxzN-5SCBrI+o>w>Zx=Kt7p4P?M%OXX7%&u zdZHe!D&#~xLU_a0BhFb^%bzo??!$g2jC=hIyFNh>X}_cZ$G&Y zongzDd%ypa>uDRmw|+?VXkOvCqjRA??x-B;uV-u2f82rcY2%EXK%B9VoarC@-*6@s z=OQ6FCkDl7S$9!X>%rC+&d>ApVCAFy^&IqiuqTA|ov*LsKI#wb#DLc)KPlwwuyxej z2OsR{y;T0;bBlT;ZI_-Aa+V5uoVm|A62kA9^7RJ%dW3YJ7jljqqjPc}>A_~zcQ@d3 z3q2<`)vq5W&MRl>reN=XmN(PWYcp=n;RyRn(sjT86zVy4tga{bIcG+=E=YRc@Ks^E z#J`Wgea<;9{5}GIznm%VuL(I5$Lo5wj?;b48F@lh-);A0knYRExEFt@b8#Q(!A=O{ z&fnW+()0C@dUAci2U`<BFZ@X7 z`!iu}yJ*OUM~JQP;D<$^rObtHQWTukRgU-19}9 zll$OgoFBfY-eN2X`&UK!^nAvrmBpHKaf5pvqru^`rw7(D(9;U^&FW_=UqCT_)?6U z^A&ca`$T*@{GfV%7E({HFY=e#pn4_)>IsgpdZK)Slb0XUc+=^3B@rst&A=;=9B$2#iC#dIE|+g4m-zaT#NSa*SZYHB@8VbXgY zV0>rV9+Y!U;CnA7?2bBgyjsZr^;|6A!kGBSi6&Sgb!|RTZXt}KdGLH7{&eT0Xgfx zCeHlX{&5#`E~mH4{Q6!~>n@_gcAl@hh$&v^!>xGTg=L)p^!!FZJ;4)J&#>h)CFG2j zDbDG4$&UWUKkf}xu5e!5O3NpX`({8+90zXr+>S2d-F{*}DQ9F+N@vr6oVnkUj^j#S zhPR)wrD@#ysj&Zqv@=fruvB;<7dz__@N1eJ}w zDGRehfxFz%Uih_`Ctl*V1knGVPa*}`)2dL*6y+)v0ksdSw9Bk2hr+}w^E z=E1O^H161cDBh)i>9&we8 zrngkj_8Rn@-Ooen*<{?{gSC}U%qMd_P4me+Qu(ybd-L{~`{0vWsh))t)%Vjw>KVU8 zF9)2@Rz9Vi*-eP^S3=Gxd#_Q$!r9th_MDWoo!_}vkL>gFg^zXpxX<;h8~RK9`fh8N z#;+wk&km_)>@uC3a}G++jym660_qu6>jCQ)PLrNEA8Gl_uTOdwgnD*v)35KNm;37( zvApjBoVM}_J$DVLC-exbCoiAU^`Gww*W1jr{*$c-1wZVVa9yRX9!;ut>9@kT^L8nB zrGMO|^@v|DO#S&$VcdEDo%_%c*3_Tpakp`%)VSclpqzgu9cya*0WNM$oY)Wb$QJje zihDU^+_Sa+o47;I?*-LU2@+OM9(S9b&W6-}{!pkVAIDWy{1HcPrQX}jN zz0=oHyy0^`_+yKc4)D1}`IN3x{g1Hy)>te!#3XKEwT^F*PZ{JTu08~o!g z{Z5lD?kN@b^Mss;d-^1rPaYZf=ak0X##v62o)-u?3zzHVvu)ul3(KdCv#IVMog(DK z{Uemmu^avMl-@tGaU#E`h3^x{?Wo@;kM5xRNDnr8jQ4yU>JjFbr0W&ea_hU~J2)SxcB<`_+LoJ%Hs5U z-#?quM?U$F$RGKHEY1tIsMgOT?$UPY$3i_DiZfOxUiiqL+r(CM9pT&I2jv_Qa`N@b z+(-VfBLiBeiu6tua&rB+kMv+odZK(v^(@>$arsF=&e7W`?sXM^aB*wm#C}0J#{zO9 zpRk+iCC?*7?;stKo~d2H?=}lgK2K}nJVwYl&N$nv>GR7rF8;eT z?l|sPVcc_nB|QtvQ~L=Y>2RBzKA3i?snR(ujGu$sfk0_c>?$1R1Bae9jq?lXG*%kn_h~}TuHUadXbX ziL$s$ubcCR3bj-7IMZP(e>m$=bRMkDUEwf$XRUY_hA~0n{(z*@sE3N zxZ@rqU6;N{ciiF3SH$~Rcz*Et_aC{B{kX-t^kP|Gzm0L6^gH!0_7b+QQ;j{Q$DR9} zFMra2#+!FjTuv8`H*>2{yEOU_;;l1o&KcXk37)W=7#D+6T94in zt_$MteT+V?mjm#_7NqNfEbnJPdKU`ybS~7#TaAuCXF|RA1Np#0&$-B>*xrtm$=i>g9tVDkz?zZoD)b66|#YF-2%j zncnyLls{+s{K2%JC?{tN%V$+_O+HP0@R1I;liLV6E$vd}ZA#~EVcdDUlu^8#4}SUI z{?Err>k-oXbwE9FTv$EPeo8sh+mfEY3CKC|EXBR@jDPu*#@+V*kjeF^{cH;39(iBC z9;Fp8^yRkm>0sgxJ<9?01W#B!5qCG+Ud~7l)-*rgZI&eKm&(uSapwNmpX2I_#45)Q zeWAE?Gxd*?_jvb{ZP(4>0u=Xqg>fHe&z+^(IydxyZSEyo|7q)gCN?0>N2Hva>0BKP zr}+7IOZ$oQzCu_&bL-IeKt`7&TY6sSMtZRAg0P*p^h1!|?}eNr|0J&R-qc@$k94@r zZ71WjwM)$D_m{2rww2GCI^S~w>Y03zbRB!aKkiaJrJUym zK7YZ-9b+$2`ME|I_mP+NxVMz9;O4geV`1Da^*wzoab7Ld6ZJjz z8pXT#l7HN#_1#vFO8ZegdQzxohrQ1#@v=W>$MT(J#NAdt6NeG!GeXYf4mwxU!WqAR zFmcCt^K~I7?uOxR8^-hbL~CXBhN#^H0Kh1U<*qd`;N-5a=!~ zpQX1+&o_m7R-V_}rTnY@agUrbnDU8s=^CM)XqTWz*mfysJD+@o+RvMWdbU|RUsvrY zxVarURi>xydQ?@MHw!sO|E-UYMql@j``Caui}TaG^esZpu~+o+8MVAWxh3SZweyJ6 zdcyLFb<<7td`H;#JR{%U{Acf-iP%EcG>+TC{W;~tt?xO>y{X5U`+9D65AD+EqbXj^q)PUgw)sP9tyW+(-|$^GD(M-O^t|de;f#USnL`M|!Ze<7DFw+qf9% zT_2Kj{1g5DG17z088~_SY2!?&^+h)X4(BW>%)_<^w`b%rj)( zA-<}Gvtqd45tj48fSkxDEGOcQ^`DqeN4lnV=@FMxGQTvbbVPdG$9Abj+->&}klw>W zJ^6WaAL;e&fZhv-^fnQ4^7mwieZM#24n3vU%}0ft6YBlro&Qihf{*j%HY;4uV2eBM zAN@_p$>SXM{?SZ&TCPX9-*KCe6XTA|Z>jxEDP6ga@CS9@5a~T8^+=M^*HBs#$2KN-dEXTTqE!L_dnBz`Tq{i@fY=Rhl%qE#o0A}oW&2>c{3m70oKMT ztw&k)9^JffT+H9Ul=w*J1|O{SJv`Fu`}@M@r1<+o3PjC*n(y`AAc(u1v(yvOe-pS^6|ou%tkpK%Y6tW%9C9l^nUZ08p1 zR4b<&?!OE5{4`+P!4Wp@(9_h;SARw4(^^|UujhIJ7_wfEMjeWKbcif`aC2+Z8=U;Q zY2s`PIl%{>&&w&j9yL@s|4)z8-hQIq=%^ty?~s^CoCt*XLp{~ z@tCJIeQ!7G?p}0gPSdX+68VbWE^#0HQVTt8<6@-u0@JfPi_U}nYK)Wn*bla2S?3Q< zTR$YG-eXo2_Lq1+B>PqG^8u&rJ!Yuy{5|BR`hKvg@7?(`zqmVGXYK<~+0+O6{So$a z?>+L}^2y_3ny-7&<&@0V@$$fZ&SCSVaYs5YvGR%S+-7E_I8Q1IpYI31x#nQT#Ypev zfSfokEGOC}sh+JLQ-9`_fSlwN zNQc|nhq8XMw4HxV$eFxSzhBIK&RI0PFFmZDlR{3eANM(@Nzb61V+T>Y@j*b&;tdq{ zj*36$gKy%*@2Ky#byn3es_$uE z4?9hddyCCGfDd*=U6nWR!F&boa!6s||dSd+ET2@atKTPW}$CO2S2lxK4f0wP!IJuAXU{j~)^ZD2gi+YruTc+o_ zLOn|j{k%sP)P3X+TmG}Zp5T;THw|BR$w?b+DW(2{~&qoioCG@WGB=I#|w?LvnI%@WGaZoYL#&Dnice zBBbZ!5!4TZ4=!%Ym&^2&a;_%itS+j@-Qhk19j|)dFUD?Ym!zDlhvb}z8vx4Y)c2;@ z=Dr)0Gb!Zc{iDocOy52M{gJWsm$3e`eTLqjH_a!n?T+Il^U0Hnt9T}*3!mYM-JtKE zKfE{I97@^V7sTIh4Zot^KVMPrxexsQdCNLLocL10@q2m+J*jymxG zr4tXyIl;KW2b;f7#wo4uOA9$uOX+%+m(+dm!KNM@Eax&IIXO4@VA})YEIvf%yKG3# z4$~KWur@u>E}=f+I8(cHw6I;m`{wZ;diY2`s14fAFDKMrevYgj**N1rqVt^=l5=bsUEi>rwstA`AaO1)pR!eR^O5CalL+>{k{zU4hHv;9<20x6Sn(YNN+)*p79l^9cm~GAL($LxWd1_qaH~) z7YfJ;p0J!j<+yBftC@2fS)%eSY;_p}r5WfHr8{e;zRIzzG|7 zT#th4xkOMs6)4wp^1obcRv{<xwdHT^kL-}8SD51&uYu0+=}(>njtdwR}qoll-nT#;YWI0-)VLq3TWDZj}T z{I8=ZpVIrV^9bY4zbjH+%U{o$@H->Y?>Njafvw%B{zO!a*s zAt(QCLx+9OgL5>6?>(q~qK~&toU5^Z$mEsY@hq)F+eg+V3!n4B&pjrq?^4dy8E3}A z368LwxV|Iqwsr~meQmbxU-o&1w$c&DaUa`ZTMgNI@5xVPaZfTmkq@_H>ruRuBV^(8 z{optLA&a||bB%zU;0Vjf<1U>KSyRZ_QaUC!AU)xOo7+fBrl<5d=n-MN)Kq-nDXvev z@VQN0;6Ls_J(B9VRzN+$6IM?icd4H1ht!kn3x3#{t=jS&N>Y3kI=ZY&{=*Mkqz)>te(96l z;+@^pKkm}i}MREChKs_7tsQFJ;4!{R1EuYeMelww-`DuFlQBLdS6@0LrB?sG2P7C$q{kX9G zWL`e`d-hE8idzWv9NAjeucP|)(2v{tzhw2@7Wc>!6qhXn>X}MX{7YNu+?-Q7?vUy^ zJ*1voU(Q)tT2?-#?dK*!J=-eo$!$qT_?!=ZL$xRHxy86cdY>yT)HAYxUf;*I@sE4$ zU0L~*>bYq^J)uijJ$Zf4eN8ql-b$!vbs=5PmWn^PxlJrLnDSYAn&Pr~NIh$;9B@uk z`Q&;=*?US&?dLW^JrmpO<&pcGb9{N3o>Is$$iclPxy1r**(C0pH(}nmrv6= zmhD|m$-1@Te!8B8jP7$zn~!$Mc0G!2M&j>dNK zkNcp$HvwHP4akY(#_kKp$@QFU>FJo-&wYjMd~07ly(II&51X3Dd%liy+P>4&RL^%@ zBCPKt8|cqjMt9McmCsyE3uc}K9^qh zUboU7qV{Q0SpZ>u9Z%QP&hPJXO4|88|L$}ieIFSIv}iwV?L3m*URXXOyXiV}AL+r? zR`kDaN;zXIQ#v~Y%oO^UR1@#?#;Q73qs7KPc|3TQV$>T#xn&$O#^B!{;{hsdqiXenIuzJ0xdVJ$c-1{bXle>L*++>?fCA(${;BXEb`^6h|}$Oqi;xs6Qok2~hU__yqz5~y#x?M{4a&KbkhAa|owLcfIY(*0oI8i)4if5_|E{hl_rV97Sl+)~ z3R;h{LeAKz&dGi7!Dd&H#a-Gi9W3OmGfwV<54JKOJ&Wpm_YiU-f7sCjb$ziNc2Moo zq~hE&Bxm${{+uacyJU-d`$Ot)?-i1B+`^gpK-QnPagMD<<@{Sh&d6N)dt`G5`RiF0 zepg-EE^RM-elv2g&c%I{%f4Mu_MB8~T{bU$4}CwZsw~nwM5t$tadIE&!NyjQwV!n% z=b=K*>>;|I+y@_QH6i1S9-zP&V4OkwAx8?!=ftgg`@wyFe(m?Y+a-*Pd(&_3LDKI%GFrt3LU)7ukp!A@-BuO~Qd{duIfx$t^aK3uPt z+(&w_?ic3t)-$6xN0mjQrnsBx(bX=eq#p6>2KTFTd2==tU)zh* zqg^s_UL)j0{Vp9zafc6mQgeHA2CeTV&TEC7(64p0YTwy?^Ok{gPUP@2#gP?&!};?{AI@?;G;6uwr9|!f5QvIX;c$@W?CIjk;dBp~s zzc6tg4Jnfy-E?MVkCm0v^ z!N)D;Y59FC=o$S$7Wa3B^NN)P^mZt@nC^4F{13h7KY97I#l7_-s*fiLT zHRd08)Ab1FgSf+oHMR41v+EJ|pUJB0Pxd6m$F4_(CB55E)AhZ_8K7TxkB}4NjB%{< zXPnigyg5z%x}cnmfSje%NKbG>_f~u`oTlsMy)I{vaq;Mnh?9>uBg=Smn#LVL%jbPU zJ<;Fnp#HG9k1XrW8MJ(w^t?Zyp6#D{>pA*0Z_YvK`9MHD$A0Er-<{>WIeqm+;hthm zdOk>ciu-j{)eq(Eb8>laPE)_mR6b3d4+Z2bo=$pl&Ya;r*@NPII3Q=@3~$a-BAA{S zckp#Vrt48tSU#~%Gr0#{*WsgR)z$mQ;oGb!?k3K^2|3X&wSMkhk0#W6**Ra(dSv4K zdqB>3$(u92ig(-x#ra4;&W3?=JPc=me#oOjPF&ANR67qJaqg_@t>>WnA&&**jQx`0 z&N*YN|93h65sPkHLQb?x`7^!idvr~2JqK0a zp9sh~{wr_J)LOwfG2Z0Y3qH?~P~R&V?_C(|^9;4O^!FY(6U?6yyY8R4V=MdX z3q27Zq+_x_6zW-3oJi;M>M5;974;tGy09Mc_uHiY<6n;w+xyp}pzA+>)YEguI#uY! z?c{G&d!&BgetQZ3IP>&^a-JaMto%;rDrqHE2DO zmQQ?#@uVK7y`AUfGwgR5+pExhI&kvw5x*Yg)%PM#7II>pZ|WS1fB6r3Ie^Ttrggvg zJt*fX0XdORSWa9wc{`teit3@Me4Z&RpB<%R@fx~r!Us3QaW((?A5_m%g?d(( zrRQZv{z&mIo$DX>+~%_T9n$jolYpGiFDxhG?yfuZ{0_LOzcl7@O4b3km5%KvDemyW zonrH}^)vMKv)B)om(Pk}{uKM4*3;8TbuXWO>uJX-6zAl5WZ_3{qH>6Q@=N=dOXO>6 z=kYtYKV_UP#liOjAGUv9PV|#`x~91QOc;00&wcPq?ZRqDTRlR07YgqmrLNZNH}{bq z?8sjF`Vf5AEWamhho1a9@+Ljca5*LQDDfwqll$P4TC|^h9+h7=OX~TxhOqxxd7j?O z(YTO!n~aN{$PW995+dOftszf(Og zH_0~s=3VdOhtvLud;SJ}+-Qn>Nf`II(h<6FAKRriXx#4&7iJ$;Kc9T z2EA@x-fKVY!S;o9esi z{$|^adywaPnuhy^xK2Gs<_He5hr}4AJl>q-x|! z$@QtfW#XJ5&i;Gy!NqO+TAd$0<{6L=jvGCd;_kCv(Q}^G#QBbpbL={ull$Q7+v>Dl zWb1i)PQS3H{(c7Bhvnm=>aWyu{cG#{KilhA54n@j{`0iS>vc}<_xaQxvCsVPf1)0B zR?*kDo9g@hy>#v4qZZ@jKIcsA>b-s*`+<{}bIv(-5S5<~dwSYACnCC@ojG(L`NP&e z^yWl;2PYr5a!#c8mXMRbUy=Jr57zX4MR4-_2rab^#x$>ZRwexJS|yhl+a7Ov%x|^YptO=TM5zdxHlye>25Bb_-ef_#OFl?xOti z)5+p@ZcTAFasFP&2|nca-{Kq}CLJUD>er)lgq(GyBRD5+*ZYm_hSG0qvZGu1>v{1) zYdh<>iPd&pvUh!jePCgC`w8y7(KX_|?Xbl~)^-+f2LRov-IGsnoYJ+2T-CLe-gdV? z^B3}Ao9^~*`h}a8>ZJqQUTke=L3exNR@xudS)8_iMWtW7TBZM&Bb^1@eDcQ~+RG2N zuC`~6-nF+Kw(V}uxM_eh{T7{{bK8-j8}g5sfU?jcI2R;K-7okO}mcelISP#(~JzUFT4#&L9< z$}8-5j$PAj$7Zy*#Txw{KW-QS|l zGEVnCiQjs~k$ZJc?sxMD@-Jxl+|Err?yO*qdz*1`KL}%YU&P(^{1MWv3g?&bz1_O{ z&TiQ6*dpIP=STW@&{RHW6TUyWv#>r-ncqtHkw0weeA#@RP0x&a4&|<1uioAd;p_Zc z_v_^qe6ZzzdvoG<=xO_oSnYXArz+&+-`g!d;LiyjlLe=3{ug5E#+z-{NJuD5BZ`$zE?b-i%^ zXhhwg;r-jm+q~y#OzUlMUmNM+q)hjG}~f z=nkHC!M`5@J$YPAdVUg8Pp&Wcq!xPexR|b+pSqlq@n-Z9D!2JKwWFhd_b$hMPT~D` ze!eEo&jNCS1KjXuvKCH$|0uTswQJ4OX}-I9hCc5dbH6v?&W7~Y&!?aC)@fYnnR}Fe zhmZT($fu$1qt`d`ZclTE(tV|%oQn{r^?nDqpc{N}PAWa5oG73CdSQzD{5?*4f2p(p z8^M?eUsz3Po zMvkO<-eLPM(TltNeF9a+$$jMCw`~9ZcJ&81`TCH8y02Lq(&wiR=pAQYAChV5dUBt0 zq||#H_;&ccxDUabVNK<8I>o&|Ki}RY7)OWPQIL@SJoau@Exy5xV^)&Iq=le9x#d&3-g{iS{!^{ZxWVIt}pkIkJJX$^J@Y11PAnm&uydXzwS5ay7Zfc z>!`<`qd2!z+~IRR_*ujAGWb2Hp38;QGi>=pKRKwLw*=G^dW6*z>- zSdWU&>-C%a$cNj+KlS7AyUQ63ay|Nskdx=fedI5-LF0a#Fz!vIOW_652fm4`YNUoDy&xV>`&c8%)hi~F)4mj?A4af zd5{qD8GVI*hmU?8@+p)kztpMpeheJ%{BpK#58g>-F%K4u^B&^dADsPk*&pD-X87Q2 z{gU{Moa(?CoJfgm{w#kzpQO0==a=-OXL!*L=~#P>Ec`z2uau7Okc}vRMhf&-Md^w1 zDSdCuy~6T2t~i@>QGXsj=YT(Xt=_N0`QUeqH~Dtc_5D7VbL#ygq{A)BZA9q_pYJF2 zG2WDN-Y?_?A2>cQC!bHYmCvUr?kQV6LU{xyeCSaLSUx!?(v7Kh3G;l|{&bJiJ`a|C zo$3#cgAZP8ms-p(l^^$>&*JI)UOiA}o2PZ&&^bFTS^7Lb_(ALYLlk%GI>4&pOsq!p z^ze}{w<+uONI#-^HnnFHYW}mXEcSYa;@-b6gYDdA-XuLsvyqPQQ9hB+h|16T4du(z zadxNcQP6SRaY8*)-`C?jaft47p2V@<-)X`)E-2@+!u2-obxF_iEW}rNOE0gSv;C?! zC-&p@y^|vSTk1YsGqwqFh2>1E=i^M*&8>T!^VNT@^wiIC zhF6{-9aHa+g%8f$5yV+jyb}w1>sdG4-?VXVL!2qw_n^TAa`<66=R-ouMh>O(GOhpI zw#PZIRnLynvGgy}6FzwR`Mg2-HNWqzXZ-tAK7(>@N1RqY!37!MgR=rXgq*l;^7~vS zJu}4VjJW{a`VJ0mN8TkJTOZK6Z}@ya`02xFfB4+;b}8`#(%&@iy+e<4{(ieuxX!!2 zw-x93P4qi_l+W=36;-tD}Nb7!HR;DVm;!*Ze?m3PtaZ<_i`yYx8i z_q9vAsr5kLCJP_jEu|;?&aQg?*bd9fXTIpIKlb0X$7z2*ZQ^~s{=$cz$S1One}2ff z`^;02f4dQ9zn>h78p`K8v^}>U>BPs~krQQnVB>m@oJ7Z);-00r_xs6>4|Ls-ZefzP z$JOufp(paGDBh;Z7sta^4D|@dn>cqTPHVdaF60LvoY4u=L&}MH2Bd>@P5q@kTu#Y6 z1J{}R$VY0yiT)vuGjZ-IjH&d% z10QimKKMOCv>b)_0yPU($yw>MCaNgjU$-kY|_i=h}Ork{NoRqRSp4WHVxMLre z(_H{ztw$(F6Kb3UA9^O$ct|?#!1ajt>rCqab3M*!)_z^|6TQ9SK6HY$U61%s3*&f20hzMfV1Tx9$WeZD>Ssje^bht2&= zUw4M>uu{(WJ5(Rv9_}7#Uw47^-pD8NnLlTIZ}0V=I3Ap~=TM4Eke+i3^^9Gm>shmK z#(pEy6Yu8*KQEt+cS+BG3H2P=UVk1o>v;E9kYDQ_8K+H8=S)gxk&t>iL;jpnJ^6Y< zu4nQ;r007=Jqxevaj#l9o2Ly%&xF!*(U5v(h6kgk?fH(0g{U5VAk=f@VqMQk3uh`P ztM9gT>FG6za~YwYt&(1kDqr!}Gkc#b?l#WGRg}(3LQeiZf%I4XIc@I~K>KOqtg81C zEGOjb9Ifj)Vc{ITcQAUQom(#8yf=;uJMTTy{Jfdk1U*N z#W@_3v-3GQc|RHVbxh;UXX*ZtwV#apMTk3m+&>!qHTCBQeg9}=gyO!MP|pf`-^ED8 zKkl~oUG%!W?nz6Z?|9DDQ}P^2n{ja;I&+KrzRivF`$5unDYHK5xrR{B6l<5pX7|@K z)9`PXFh1h^#ey}#Z`+8dH`~aR>B7eZ+B1b-%EFrmp8dm7ccy@5MQFJ-Ls3U?)!XAD8s?d|6MI_dhGoQUCKE z;dm3@6#_?6-S>dct?9c$xE=*vC-72FPy0BIuLI&f=QOPg!umSi&f|E~`jA(I^{6nn z9v}E<=aG-pBJR1D^mKXLkzPvpJZyC{y}ZTe(bGqIu-OZ#T*2oSoVIaX;wgHr;TyuZ zXExV4C#LH@=g2+j{oDk~Cpc~WPo%rKP|y4{T|e$4J=ok*bRB`uE#_&P?EZvlp7z`B zJeXuYnUA+j_Zv8m$q#yc-=xCvM3P*`pryzoVsoFttnH z>2ccI`P}@(nOcnOIO9hCeLL)5kHBf02Sa)XFwWLex^CDHoF*UJVbhz*<{3Ia*T=CY zJ+~CLOOXY1e(r-0w!W-PPg^@*dYand&4lfIduwXfi`$W{F>dg|Hq>+eD6{84XLN?(!1y}h8Gj;VZZ zEi9kag>-)I<9uK<%lUKSx|uym?0{% zK9v}8l@=#EY2l1-DJ!2+&O;byb7^m#z=`wVKDNV_XYr4FP(2T2oCzT(*RxpB>yb@Q zluw71dsF#5Mp!<1du3`Dpr_43PrlB?RNuD~*7x$FdU@bJ=Sr+3i@UV_JdDMi=La9x z_vn_?-tm4&?L0m1j<6phC4ndE)JS`h1;J+RjVs`w>D;)bF&qUh#U=W}LQq zgz_onJW|M6yo%cS$@Azw5`2`4!k=_KTi@|7pS(X`y?~B4eaGPkJ16X$Pa#4PPCt>mq^#teje>|O0Ms` zpPw}J`;ni`f)nis_BU}BLUM9$D|tcR6k!kKY1OkSLgY{FZMWR%rC{3^Nwf! zYx;KhXy=j7=q29QA>;>(xFa2GH^u!#Vca=C_mPj(q8}pdC!f^Q(>@PYXF7AA^Od*r zAICvY-d{55d3ION_r+uwJ4uF?xu0vslxJ^OHkZ1tB{3n;u??m_mhKi{#wWx zSy3;a+~>Tdxd+QRCgiL!PVRHg=8pdLJ*b|)5prf%()Hv%=SJMh|+51mT?dR`=oaNQ^@>y9`_c>>z?!PVw^%C<~wS!B5O3(^JY> z3djkLu$;Vn+SYp`zuyZvdEB{=^kB!P%k;Ee-y`aIgsp`4<3_)s-#;mBrTgH6?YueI zbr;(SIU~Cf*Vru7@9ZS~>rr(Dp`Mm?YsCdC>*U{7CKJxEd%l9V0 z$=7dj&g3mres&jfb}rQQOsuPO_xaQxtx=htw)$S$fZE}8g`DZF^>KF7!kNF@zkJT# zdpjUMJNH{m>U*nY_TAOvT+X<&QvbQ#_=vYoh4u99)fM#iwE4Vj{tIN7XW;3Y<{5tI za!T%ZaDMJ1f2pOXj~$1fuZi;{mvhM3t3SUqa=We*@@+7kNA}mt0rrzx)FZw=gx4da zcdoEsSKmO7dwzZ0M|!a7t^NBUh zUz``LseGRAa!T4Il%t8?sQS~<>rt6;BHxB;uiLEM4$AqbfSltSd2=Q&)AbxQ=LG>d za~peemag}{|6|gV-{-Qu&+5Wn`JC}StLC+OJfRET6E*g4)t^`Ix5E9ShSD?a`>bs5 zU%H5KmhbT9#QT<7>U~l0!I`_9;x2tp6xt(BriC=P^H*YpU}|d7lr`P44V} zJqpTM6>@fN)35v72On%?(tCV__7j}^J&C64`(LD-o9p^zzN!1*gH0VgSUoQla^~LC z_2fSIV9SQ@nQ}d)m@6s!MzKJ|xfyctx_+k|>{7#H_Br>$KIT0ZOD@+nv+!0*2gs(ecO^H&S? z9GOn#b1Y33KGzX`VMkfJWV_$dS(Vb+TeyxovV}e_Y%6YXaXWga|9l9_r&P~t0_q8# zuzI5X1gC8t4Ea@if7ts=$u0GEiTg+ow*IZb#C>EnN@pKo+}oGy*Y_6V1|Mv67w`TO zeutjY`v{Z07xUTmtVMOs!jig={QLGCZ#{Y3qa%7crt8u7g?c8o*5l6oKA-xdzM||o zXj^?py2lEyM@`1beWV9lo!whc{EoP{cF@}qlb**5IVbng(<^MF>x=whCt9-dDV?wT zgRos{Y^!s{nGZhL)RrzUt9_rV8S zKGdJnowtc}zjwy}ndX<4aCemSlVgmN`#e7K$l<#Y_YY}z4p5Jz{p34B>dE!x zoVCSe_cx{O(i1|?!ngG}Cvv*aIkQK5$DOzH((&e#LeAWd#Fe~>+NbCa{+!Wcyg6|` zy?I5C@@c9^SGd=sh%;@ddz|0<=c6wY*JxI8Dj)gQX7`>~tgG+ZxvA_v zth8Nf1l3ak_4Va|%9rXXjr+YJIm5;s?NV=9ipM#c?iVlZ?mP83!)zr9COmV?QAapX(^~P1hsScZHU76V5oR^u{iJ{m+rT^zz7kDIfOx z|Jpkbz&463?ypTkoB%7pEnlEepu6Gt;Gh;BkN-PC+DJM&jO&pX<;vUA^;?<{bh-e@)R+y9%Hot>Rs zK~K7V-lpe&n0hu$Q}aNvnToeaxKTdWqP=tb`InjXv*~bCPwG>?=*hhH&TU7pRLGf~ zW6tAH&bCS3oU|R$=dIb|{;G^S<2pk75lYX{9qM>Q+bQMr^AUG?T(h0WMVaII^pR%V zsZY6LNAbqp{I@7N#cNympa&NZ0py<@AZc%z(x&pbopv%KRG zSI_of1-;;7omEiIQorQ0PN3tTs{Z_q*)PS2ZKBSqrSrIMUoqa+k2mWl^^J`g z4vt5e4b1Vp?WC?{#<(wao z6CB`%Pi@`vy#AA`=Q|a0R;nlZrJ#BinVfi@P5l7Xj}&zLsgCdyr}6aUjzhjSyceiZ^+h$xZoe^%L81IlF$ZI6q}_(m2O%H0uG% zhxLm)mlJya%;bcg;HXqj)K4yFDysDSg2_pr_nG*6`MAgP<&T>s&Y#VE=y<;QW;Na( z%)D;cv5I-V724bMp)+h$=MNt?sGf%LxYK-|74^Xf8#~^6-9@EwcbMm!h&wncjeAhe z=x(aLe_NrR^||u>Cs$AIdE8~p`_4MgH0vkzp)+h<#5?ZzyworGTrbAn$y3nVi%|eq8IW4-p%4e_wl?*p{pT~vFo z3fM0d&sDtj+S)++>Uads>VTZ!s+1G`C*n@8$Jye(l;Gs7SHyZ>aQ1fHFE{QeZva!z zx+WFxc5UG!A8Om5VUFvV{pY}doZzXH6LIJ28K158cjGRF@4}MrbJyAb% zN15YTTm3vqWX$R3Yc(G@sE>564XWp$fO>+XQayvl9p%+9IaAYAoFf-13m^GV+otOk zO^46b6Wb3C$cgV&${AG8@Ep~Sh6Lnnyh!QUrga53wSA>0IF|{?37$$hgX$UiRgJS& zXL8c>_we-c{Sx>5J++0|FVXXN=<;v(jsN|ydBR0~NI1!(< znVhMa<~#%SksoY}&pg8l?h0OPy~x_`=bG-GZ>|{iJ3p$q)QofI=H_{6VzfFxs@*`@ zuJy~GFL94Y?H{T3xK2Pl^OICR(n`1&DWcxl^u%^t&e|1KI~va9q}R0)mznyad|1Eh zhFnhMw>guu$L}3oUY;{vR63v>YBBySTx<68w(;ksVjT--{Fx7Lss|i9VU0fHs1ZZ?K#gb zr+aMxgv#31GrS`>gFH{5?n1>$@4IyBy*X{q6IezrI~APSU(Nls>3KJ^enzi0^P|40 ziodst-h?~vJ&RdCJ2YqOok~ymR-(hr`bl-G(et$Q`?htz--x)&CuGTfLaw7OUTf-x ze44LO=}jjq&Kfc=l%C@q_jA$M3K&gQ$Fr~=N-_K-k)yM^H3&d?H; z@WHnA5ogN^s=e=5A!oy_roP~V?Q1>9F*$R$nOq^_gAcZIgT9UXu@!PsZt%f2kLGc5 zk4JxIa<<-X>Y4n9>4OipWL?}>e*1Co>X7( z!PYVL^gA9Qzk`^Z&K+i)6Is(oez3)rd3th>?}-XIDL43Fv#XTn#CSfjo_U^N8_yps zI63P>vRcpfLv+66_aec^wHPmP<9-NJPdYw|&nO>v?l^?5x3RVNU6`CL6U=c)mk(!K zsC?X^CwCn3S0*Rz*E4sP*E8+Y-cdhk+->zU#;l*6`uTdOf4zOq9yn=xw{h-KAt#;> z2=1U3ap#Vc$1>wi&)Zt=Dj)akFlPPq`MvV4Q`ETb9(Q8b|G1glNZvo_jmZf;JIAYd*SD6hpEf>e+F<*?-2~RM$INH&r&hiTCvn>`ze6bKT?7qTgMOJ!$eF z-`e|CdeaF=3Frz$S)@0sHG-a5uC&vtzOn>@Zd!+h7zryfxGMIKbv_B*oJFFy-T z{O&Baw{bQGIjZlKJw)Ki96V95)%5#P^FXhaolz!ab z0Z0Fd{6K5#=O+tJ&hd!y+jK{HeiodF6SlW;rYhv5+$e`@X*+8EQauOQ7Wb=}}PI2q!qJG|%uk*NBZxjDCefqu7#(mp=o?0O%<))m;KIWXl zmC{XRx2PxHnZ8cUlin4%gEDv)HEkvs|^h zkEiA+bDi6D%yCGkKEKO9rpBl6!G&_1Jym%PW0l3{)I!h14rW|zdQN5P8GTyi*P(68 zQ)d2@!_NmN&Rem)jWZpPv-ugt2X5pa)Pj?%=NXcdaUKUg@cg&+JhMX1-s*||lY8EA zmf+-^9~Ebt^|7A#&>6PPr(X)nd3J@IlpB1o;Z4i;pF!uB&T%;xop;!dhv<({@6k?i z-jSTC`XTQ8(!h64a<-c4IJtcza;0*~zUQV_Ic@u^bl9VdCyC#^s*+2@owLOE>dsly z{hssgNzU+Y>BU=)pCvyZCDOMN+v5AMX_3B?NSEEQ-0tiXHmDYFojLCIRZjD5tGW5Y zCf}N0HC$|ma@$gB`!q>E?qrpIn@Ep~{IGq~Y?WW~?fF%*T%<=QjdwXSB7Lw(l@O9= z!bvKh_eJ_PA|0I39pw6K$4Smt`N*)z?bka+ZIAkyn!}r?9pN62{Kp~bHnSa3Utk!o zcwPB%9XP{V^EhvFbNA=0{g=r}eFIWBi6eOPHhCuJKbV{a!byF~SwEepC-;7Y-DL%I z{Pj#dYwAgT%Go@%e82SkeH**&J+zr>*RbgaHg<+jT~z;T?>#}a3z;qoL3?SwU!~6z z>9Sq7ueQ3|9$;^KXk(*)NVlr~A(`9QZSUF0xTUQi(?<))nZeagoj+TSoobgh4o|#{cbb|=f)kJ zcLn4`IhAq-)f462&E#}mQaWa}g^zrwZ9KUA@rbJ@@|_is6W^Fn#dC7WeaRN6-`PhUlkYl-=KQ#6Hre8RjMc2k=rjJvu@T_KObiHOIS}@ zgY{eFITCqGzhrxkg#0~P_hh^qqkL=Qe1yqaywO~TL;b`o@BWiulw8C;{)t)7ZT)AQ z8TXDEs(shbRJQ3&Gyf8ReiJ{?yZ^*?h&%UrzmGEerMkCFF6yIvYVo|^+?D2aE3|j| zJB%HdsqMnk&Fvr4?H%WFv>f>Dgp>N%4%Tl!f^z;-b2f;QNO)a%?pFmiO8qXI1c)y%)iXvskd?3)-TEHD`{s%H_vkIz42XB zKkC=rLpZ~VGdx%IgV}G*`4QAlZruMAFz(Q+(zv6&%l_KyWz$n$KH}(^*Yy&4Q@=>{ z)Enk?yo+9OM`qoutsTjqN2qa@uaf&$F76HQtGE|;Q1?s0M-i=a$vC7|#XY9up3)ZE z+v=x{Qyz{4=NW#Sp$`;iVQ0k&ALYjMIu!U$o#M=EzN8mtY2!t2Y@D)scITw`eIf^p z7jWJMAD_pLBYM^=&Sw35s62U2l&yZ+=I7=1GDkVTTQ2U&50##EJ1RZlgERD3!l^&V zYQFZKoSyxsjZ;1zOmL>bnaY~yso=nKwoAH!x7_-PFL$%H=fX)o z@m#pHJP(k1w%4iSPPebRZ*kqMX`I>*_}H%N38H6%;*9I(gEf%fcXl~FuFKds#dG8g z&hQ1^oVY)%`FDyFJ~;DF63&?7v^~GhRzGd$M^Z;|+$_yAS*K~cSpHoZD<7z3V z-T~WroJ~&~r@SuKozr$dF6J%bTPi)_L(jxhM9;X=(>4zlR8Kiy(|sHgy3jlB^t_Pz zxn~Hc-hnP%FKZW?=Q~05T%K^|ES&WGfco*-gfpS^OlZF7vmWCm1f!d^9pB~Hi*tOZ z&*`Lo)6;}Av%Ki+?AHkRn3k-mEwqwVqvMTqll$ zp8dS-xH(J|RK-|#LGQ1nep8s}nN)Fa(ww=T_0w_a#aO{&<6KdE#u+csaR>FGE45|D zA)cJJkw@HZ z{k%L+>E3@Le`;yJPJOyPd|N*+`vUpGI8k|yW1C-koH=iU`5NTc+j$%Jc;um{tzVMQ zi4D>(fs^)2NT=4;FX4QXj=N}kk4#qc6>qtE`p<`SJYgPBBj2h1lybqZ(bp;9!{U5X zw%;JHu-;h4L5@FL$#XK07p_MYeo*tu@bP)qhot|+2NnxGx$|JJG4;&;+tic#6sO>$ zCzmsOvWk0qK+f84RJ_w)myf%R6Z;dC^Ywt7D5p|R)K73?{Ed8RJ3{)~OwNMVvC~oU zhmU-y4W)SVirjUoo4aEx|Ms5x){HatDQA-TTupAj^d?hJ^h-^hinr2!3H##~D>Q2S zUgej&NA(xBb$5xt{=(sGWm*<`{OctoZ3w8*PiPJU^|g(`FWerv1a|Geh1Ohg(&k6 z+B-d7*xLIv=I@#2e=s?zPmvndEI&W*K2Dx~N%*#LNSn|z?QHC;CyfvF)AyP6(*was zvT@q#=fB)`G}?EZjCu6bHcD6cC_H?BFiymsj$>_cKZe9e zXN8_oXG7oTv0z-27^jX$@WIs@P)}RjZJf^q=4lZ}Y7@Wc`uVG}@NqnH3aXqMU0&e@Z|?kf z_1u7rZdZphr z_3Zjh)ys~zR62ZcHodCKX?{uB#4E~TznqVho<)nEew_bd>Ip8C3!lxYzX(nokFcH; z`Pz<0FS(rlPLObS^IY$CpYfz$psCJ>j<$;%(xdOnLg!AoMx_D!RNGo((4hnxNpzYvpB%i zlltI*jeW?|({G*u`NiFVpnv~abC7v_>ZmKPXLfy_p4_;%yTJaObxWIiQXl&bo7DG@ zz^4|+BW`=2?`Gi7*-kjAPdQSD^5Ra%+qU|7EOVVzRDT3a#5dhHXp{*lUqNVnC-nlIH})*^DOl|9hwdw^^>mGvg!Gr`$hlynHp^BNqv+L zTXQ&1&l+;w!p8XplQS~JyBJA5FZ~X4yo7OF<1&i3jc|hx);6xg=ZL%C z_!FGPfSf3&Qcil@q}QEoaqn~s_OGAeWzD!#AN;T}X58s|7#ruiOg;0Ovtc>K3m;rP z>?yo<#N~W1ASZY#8CXsB5azz^Fnvi!Uv+L520aUGZU z1L~PvUh(C8IGsL39d>x5qIcW!)))T25s*ew9@uYIl1Gy zZ`^YIk4IVEA3;y*BOSKu*S?8+gRVax2aJ2yimHCbwFMWoeN{if*%6QvJe6|NxYO%p zw)XxBlQT11=@?r{S@__lwq^=1?p)3V0Xe}_DQ8eU8<$t-gP#WEjIN^e?9{q~n_8}( zt;~LDDzjgr=f&Y~6ffn2A6w0P98#&Cp9Rzt9F^)xIl1!;pEEf-biA9xN=NwMrnbOr zM_kS?0&;?qnHYpIklt+EH?KRnO0;upPDjP@a?9j{M>d zJv#&HiMUs)CyjfEtdp=EkG^7ZqF--0PtDiXty*5sMqRJ4U({k;SD0<)W8=Jzd0nRK zCo{ixAI{_`@BS0K;N;GG|Kfhpe_WUO+2l;GX8I@}w&n)j@!c=(c^#K;1IE3uy5g(V z7F^VFjY^1-6pMXaKW*)?RCJQlE0>zx8hKw0?509}Q;K&)nK3C-o_3c&GAu z%KJv;i{77Zn^(M3#J$?t(Rcl4aV2#>xyoJSzmCa`bgq^6yLr9vd<;C#1KW%cZ_?rq z_w^v1T6*1#`t|pc=W@^th%e@8-SzXdz1#F0DZbx*o;G=rw@$b(sdGD}D|}LX$<34d zUrQh8H^bdkfi%_buc|*P=}De9gKyH`Kc_kby-y1B-ZWpEo~sFv?s{fVH2X<#I+`E9 zuMWTTdB8Web-%WC>1&AmBhI3A>Ghj<#~t%k7%##HUg2G`J`o>SEXGUR^-DvU{ZhQv zc&$VS3oQda|0$Po*&h)p6Zw2`|;R5 zxAmX4aouQAc&V@n5Taow(-&?BBQiZSGtccvZWbcl#|-ROs77!<67uR^Reln%#{$aOvbX(KvQKl4biaR~Z(?(zL#=JCC8D>LrYr@I!N zQ+~bo^Ye$>AoWJv(U!u>Ypnh9GPQ=~sytw8& zHJ<;jT7vqI=To2R=j*xqC7x%njad(La>*3VFF&4#o;{B5mggR9;pV(;sb4A;MBaqz zO)lyu13updoY@0-{rr|LkAMBl5l-rp-STz8NzVsu^;7;voa6Y{&*bk+J*n>tMm7Lv z{b58;OWf<-@B7ESW?Pe!`UJz*MLXi&&-JQ%p!IJ@t%Q^M6f8Hp{P~f5{-j(_OJBC} z{PtqQ8fSIi`Q*fQrk>QN<@x#U@5gy;WP5(y@5QzuXN2$b>zwUP&K|x;ndOpfoVIcD zjv}*&Gt&2XlqHFrSKV*!rbknf0@7qB&lu`NEuEMmew@x}Cy@rS;Q~Go{<(Zvi=rJ1bqA zcQW+_2ds?~pWFIRTio{&Uko|^aj(~WD2Mt;=UQ&uq36PYdV-@;JrQ?Xd$%2r_7(+4 zoV9(AM@_q!ai%`_xfXijx*5J_Yex=qJuTL))$Xo%>vlD{QBKL;RDS#kPQUZbwtuL6 zR$y{=?PqdD4>bJ}pMF!T^QY-f&wq+({=so#UsCn2bw z0|M%a;w#k?ad-9f7>C&O+|Sjs)>qFq9dB?_AL(2RJ#jrB-?R0f1DSf_evZ25)cT9Y zv1UC$Ik3^2dHtu~{l&;{7?U%+r{ZcoMp^jChuY%pz zLw%%kt*yP==D`jS8K)gJw<({SZ7Zi?FEh^6w|&o+&aI!#y8hHK?JW^`pK=k!6z*cfa*E z$YcmJ?lt=;&Q@*VBOhubx0Y}3K{=NR$O)cGIlCW^kXLtWi~GT1qqMV{?{$Pk+>AT* zyO+gz&($-pwWJ?`v{XHov&r`gxn4hq!vK<*R3wa8aLf`uRciTrQxVrSb`P zDP6y@>52LYPQUXby5JS<&Yb7ampD#XI$L=kwY| z2dL}Chr1as`n~edQD%HmZp#5?I`vUby)MuBXZh>#+_+<&Arvs~?Rp-h(s>5#x4f@F zzUc3_+Q!L8h;79>meM+E_sbstbddQE>U(^}O~U;ou-Fd2D@5Z$L;Mwc5T` zTWtRq_f3`Wb%cWE#P_I=blB+GN_Y6w;&ppx+fbK@`xve$w*bw-HY2M{}fprq%CS#vWI{E0iJi z4fT`eW2>Jhx*-1bv++n%PwHcTV7c{^yN=~=ZpQxOqNqRGI*68a5^xMg!RlNjn zZ#fZnR%{%5@(mi@tg*!0BbsGmLde~voN z=CsB3De;C=KdH{tM}AxzRL_+H>RIBbP*2oPaB`pLzcQ1vOUFCYpyCd{#7*AB?%-YT z;Bu}KkP|qSat75iulF|`khA44O3&DF-u(jhgR3WZJijh;Jl{#Us1H8a)Sl(X^W6Fg zJx2u86C9Q5N#pJ}PHy-@oo8*xvsnxluq)@KnkfR8N$* zF_W{nwVGcjo}lz>KE8ZAO1;4Am*{;`w)5ikneC`v^I`v}k962hW;^nWJM!B!pq}_% zrFvEx_cfTDb$?TFZr8Ty#PV^E-OY2Yer*AnU6>?UpXVAFE=BoW& zDcopw-<9{da;2af@6Y;H-GpL@$_m!Rz=6dhYmgaLL3R+iiQ`^1|@A&T5j^dxF z>znH_^+Z1(nW*BOnovIO#ZUU?xCzen19C#QN;!kZ9p%+BIWZ0iPf|LzXVprq^$2fHe2%z>J}~#!Hm=)-$r+k#a#A1Vm+X-| zPVVzm>zSN6!b$xSpMI0m#}S$iAA0(=qxjdVAFgAzBlPn%rzl;MDN|pR56d0Tb2&E) z$O(>0IcYnJeafq!+cD$bs&xb>^^p#nOY-WcpPtBXbEcl9aq$!t@5HI)E+u|pS%FykIgoAr_URL{bn`sR3)`9;<9 zZ3F7re1_ufAl#Ib+m8JDd2ntQkP|$Wa?-f_aiYBKnVdMj*PX5OtUuGN2gnaLwvg8^ z`QF#_y=sqpFgYVlI^K7yaahrZvvV(Ad*_}X?Z|9LO=p?prQ%}Sl z9F@jBX#Ff!tNq;}AZPj9E;9 zl#lxmx!y+fiQM}UP7xV*UmwzVzIVNA)BQX+`s#iJny+nL(5ZwI9MqQh&r;VpOFrF@ z>6g~qd~D7$*f^(%e7oyuD<*t_sWbI$-?OEIlh#ig=V?sNyyonhtDa{B-^SsW4o-S} zw{f1%H0bw=iix}p$pBpQ{Tp8O9v-i7i8m{%H+%uPU_ou zZ0X>n_p{hI(@akKJ3iF6@z~OFUQE}K+UC8_a5Gx8-n;87@8^EiOjmKwe62o*Z{u(* zzsrX0!AbSBah^pukq@=4niJ{NM|#OJIdLBjzGve++udN1p4gt+#KmSiqCVZ8t>;H( zKX2nahso(Q>$u;b>xK4v@F9V#=Vs>q+c+;_a%Kq^^?_HiOiu3e70+XG#xF7VoBAa_ zykT?z6LTp3mgWTx#k`{SqJEFgfXZY#ZkVOwQP4inHlf z)sEl;tA}NBa@Va*V{&$CPVi74=_TvKDer&qdfASfcZ>55&iE7K#Pm*jJxhn#@3jwD z$8+U=+iz-}c~M)i;dn%UpU4*X>FyW(`}ybX-QR zo0j9tKlc@!^mmkOdS2}2>#t|?m8PE5r<~m5Cini$W+rF-RVF9(gL2a6NYpH?>UaKf zRiBg7l|{a-?)iIFR6Y;B+;gJByPNC5;AgHF<+h)~AXQG|KxON-k8)t66V>*JJN?}j zTih>oGw_dlQ;Vr5^}$iH%yvY755>lL8I!Z_YLk=tB|f}ia-zS(*KC}Z6VA|sCJ(;f zt~qPhRr3t+@j120pLz51^nBCCc?IFDy+v`*a?{r+{`5NPbNF;S_)Sbszj<2ZH^Y77 zUqA6Xz@fDjFMQ-ft?hS#u^rkG_x_Hn2xsIqB~c**I@va)xd)IjK)M(@aioKYufmGe$+V%NH<}&lVV~>Hd1po7n*q7#b4?fO2(mSeh;<~)HbIj*-l=fr1dEUXD zPrk#=!2kH}+-AnThhG9wZ(4lxME}X<9Lqd^&k|1R6HKRNLHW4jIVarbSzRz#mN3kb z^NZ!qH{<^>^^6|neZ2v^jW3t~9C~u+KlgOci~ZxCxm|I_URC4MF2W5y*y4WW^$g0n zS3pj1fEzxwh5dP)-1DP5-2(jejAhNZQ=f8naN7~{ddEyAXD8vLKIII3*SC7!#pG4I~pQE4m)3fO( zmCybG^=!Xe@iyIMa-)1$o1XX_oLoJhalh!_&(~?bmceR#2Os59o9^mcJ^vU`Pw-T# zC#|2{{_|df_K}{Y;#|MF`W!yEscj#}Ywujn`v@m34}NW{Ss$s7?O<#5I&JvW zqJGkKLALYv1DSCz5Kih-j_@zM`pMPvezySsc9gou)RX#@GtShL%b8@JcSPJ2q*QCA8d-Lr(gYS(Df$~uzu$6SGqRdXX*<+*v!v;TR$IkGxo2a zVa*2)>LVRC)5m%q98gbiRH|pC{rp32!Tx$SJYdF|`rwCc^U)LQ73p<7+q#Pj#rZpD z-37g#NPX~eE&6$Gzm#(`_SZ8}^O&h8^}z=l8O9rba`k-N&DcNgv45JJ z)CV7Ij;Sa2{QU{SSramOP;RH@%rvU=clh|6+9H$FFYYZmE=L87d*KbWA1#l2?+r^a+!T`rw0Y{3GwU$sI2}$>i+NoY|;4Ucv_#wKdFn8}4=OYz3Z^-r3d)Tf+&K92A0`yipf^&egyKnsr|I5^~vCZ@;r=K5`^O6cVDYqXN z{T!V1yu+sF<$|-y8C%jb^qjX&4bPhCd7>}n@biOmUO_l>Ois$}$3;KKag*+^?f8DB z;N;AIQhuB6l*i_SlkTsL^QsCtDYuQsmL9bKY!RHC@n_9EvwkL@H+{;Jjr48*d3A-H zl$&yP^)cr)OwLxKC-o_3el4D!e&_GVceeY+|GXpdf*EJ(BR|+I^L&$g+`N{lr}J-< zvxg5rZ9}7YdeU*7?L2Odo3Fo~S?#YX6F9e+WR~vXUj`we$=O&ZA?A6_wByGP0s?8vqN*%=G445e98yEgV~O_^T{tVIh$WG^`t)dU=s1gewczBo_m|xa z7ID)2;5WTy>PdZU2U}pqo!j1DaWnSktZO$psSiHb=oH?3GWS0HSDBpcgp>N5M?s)zfrk;&&E6(&FWg~By+~9*v&*imuuAXnX z8T;$mM!2XCKG+nqesc937f?@dKwtRO)=lBXojVTs!7adF&+vRR&eW%z^$U5N+~*qI z$6TMBC!Ex$oS_qV=kHuSi$u?+>%7My4eywGQlD~$598_SS3lcVRQvnqfb}z1RJle_NX0%kj^ zdC%mcKKNkMXP19I80Nj(UowB6%r@^mPv{wq40HURXVpqLQ%{=tgO6)5o=<+ri~IX- z#{T_h;(b$3>QlbD!+Gt!=I8R9iB(nonZm4}SdZM&p?P&ZrF`%kM)K+>w;lbJ$%%FZ zj!N4RZSUOQL;27x*gx*^56!q!AN;VLU-9DZr)O>@6_?`!>Y4dS@pchz@WFEXB`)U) z0Xe}@DQBf||JW_qKkl)Q&A3w^{IF?ed#BH_w;hkVn4F!2lltI;ZDNk=xc$;;%($ap z0*6y!zeMBC)$>QDp3zUtxKqExuivyY^-TU$zMqe*qT2iTfO^({s(3pHH|0#M%u|KWo~|@rDH9#=Z7S#aYm{?sJnH`N4+5<=atd zocy>MciTAmX~D@^$I`C3;?Jpk;e#uvMckeB&Hc62&(GZg{NtYf!px8Ql(UN&ckcDg zlLE#aJg5ioscrR%JM`q%&q)<>R$4!4zr>CEm#z^0aZh!cai>1jv#E(Uujr>|e1vL` zCkNEC?JLC_(U$VT_iOLmxPxWO*TmX#G>_?z;aG3Ij*xZ}@nU10xqlqX!&$9}`ce&d~Qa>sSe%=x8; zZ%zHE4?ftYbD851=JUbkGUFcl&g7&%_+UE{{B+$a z>iO>QOQn48{XE6cLiIey$g@?(_4radV(R&wTabVKOn$HQ?AlR{!{C=V$(t5t{p7Zz z@0px6KPb+I?Gz_`f>&}on4Et7QgU@wf6~nQiGHa#Lh-h0?h+Vz!|j*2{rpdE{{C@y zel*)rqRaFNrqg^e@A%H;{JBC-%1t@zkL2~A-1>PYGwxZfXZ$CnBYesSze(3C_|&4k zb2-ln$cgeQ<)q^fdVi4ZyyJT2IHXJK2u|uF9X82a_sgxHzq%Rwx1-F@X1k$2_+Zmx zDmxyf_3!1hkl)R@O2j?ltl%sw3MhBq8LsE2Mylfxd~mf`jz_J!yyTHR^r zxZl8xd&h64o}Is#K6qg>FCZ-_g+-^v#E8!L=Etq0(R^^3c0TxZks>VWMirt2kb zM{O28{n`<|57ee-hN)*=wfVb3^^WO7N7!~||4H}P#wl)&6EFXER3u!~2On(WhVsXE zH}2TDo3+LLnt<&ns{1F}j*?xKwIl9v^QH>pPU}H8Nz~i5%lAuY@7(7aRWakIqxxh@e|+N=jCA2z>Xc|F0&U7x%ZGwyAK zi~8V$ZLKiwHF~@fA>)<{MBGE-KiN-|i#x`N&DZF81~T80v&6k#m)H5L_c+<_Ii=X| zTbXeW*O+mpKJtUjF#CD#^KG7Eau!}O=ach<8+@=Glgsx@w)Sp2zE4xfclP;FON)v- z9p}W`z1zFrxQ_N4w)TD-Q_s*4Gw#%fjVp@yadX55{jgp2wF zu&s~V(R60q(QcBx$3%}tVcUwCO8ux64ai{eFyj+X8bNl%kX572T`2qDQUsI-h zd#Ar679XkNVQcRfi?}<^u)N>=Qur9v&hy&B$M1->>bOTnsPe+AdDjDHocTLqv_0C| z(H+d=X3H?M9mQ5KeX3{Ox{Tuy{gUu)dNwoL5&Dl-^!Ma<)f>O|*3Z^|qJGkPZqsu{ zg?dtbsWb^6J;BLc=Rbtmj-o4?ai%`yY`&rVd~(on$R*6Uqrc4R{vAH}YQFJ~yRH9( zo^+nd7WZYCdNvPNde*$6=9A%rliJ))jCSOfZGO|%jxG(TXNQhI)iV=NPaKbE{j_n; z6z!(7BKGhT2~tP z`fn?1N8EXvyO{lFVT7q?yIv7I6xTnJ=C-spZY~~#E;i14E99iy;De1`#_Q*~ z_jk;4I|%>lu*t1VJ)7S(pLY#D*ka22z8<PLO(2-~t0kCToQXxx$C8B9)RZIiQyj|{b~9mwP4&d;yNJv;Sxhs#; zuN_71QuTa2W;^PbY__BLIz(Rr+VC%4JL2j&oT+CQ;i5jlbRx@_pSQs{g!|mrm6@EG zbxr-KPdV#n@Q&|(&tpNpt1vlZ>zSO?M}DyJ-FWqr8~1aWoSlS|`rw0&pUJDA+~>ZI zU~;ysZ|X^X@WF<6=jqA4FLET4Gg@nMQXhP<%}maYjmjT4k>9FJ&JMy!edGsQWO8!b z`x;En<_%0esSiHbY>XFoZhK#o$yqmNG$H~=m6qB=VBa@T*;Dc>qa&q-to5|TuIH?al*mfo-w;ip+Pda@!Pf3sKJKgN4Y|k7_r>o5bIv=mpQ-CH;GjOzVWYFnaY+6n_5H>})$_E2j+fSB z>RH&t)RX$)gYCG_HGmw%@_IaDdEt#i-wUn>NDP!`J1stgFf^tnEF&jQxO~-1a`2sb}M6rk>PC z`LK0+^Wx5}pBpkc!<(C&)CV7Ifyv3OpBphb^MsT7;Dc@a15ZzG+&5-&Hf&+)Nqz9a z*6+jP^gDk?ew#2kLtC1h)JJ}>?OaZuc`)R+DU<IH`~PU<-#a^<;9^F*)hHH}$~> z8#$cE8Qz+AezX~rvu0~E?$ie#Y`(}lZiec4oLewCTL~xi!3W#H)RQ}2+LCZ~-eS(j zqTIwbrk>QtcChjHczSZ%`&NV#<@B)iCZ|Jv@`dCP-J!;jSs%{U z!_41p$^NR>3+w%HFI$m)ldkQ$_I2vIHv4|qrYfatk9hs)J?@C>`#b3Uur^NHb?xh! z>sYW3uoLSP$#ve^pS(G3>i}(>Ha%|$sAv3l-g@ROoPDL|jRE!S(wxv2RV?vyFg>HAAl+&LB$I1Po?uQIdH1CVFwRcPzHhUg+`nn#wCR~u z^|Le%X@A7L-iq=t?#OJbbcJ8~+``#c$IUwgC+Gfm^q-dxYGgjrTr>*~#bwa-A z{am)Vzvs>`g+!$;f8TEH&Sw3jzFTOwe>%@K=S#bN3Ju!9id-u9-}zngEO?0H)mh<^D|XDVvj@WcTk+PpU+x2ZT)=E z`uV=DpG`uTa`%H&Evu>!6{b$=KbcA!&*oDehGZscUBmr%4r;^Y`yleAF$Dh>b^6?y)fMD zuWjw<17_S2Z@aY%LfbwP+bt>?D-d9SLUzU$I+dzgAs zANvFAr+3hHbYH-BRJ=-^$I*7wP!p^j1&w>Zrb#`oXMH~#Jpb9Nw~oW+j(C3^`F?T-}WoeuRy;7{R;Fe(62zh0{sf~ zE6}e%zXJUV^efO83XB_{sFr`#UoD)v%Y;Prpo!{lfbe%dDN((&upbCJNZT512WvY- z+hw#}R@>#Y9jfg=CMBxn-@PZRKj)N0wfh%vCqn0ypNH_x?x%sC*U@`??>D{O1oOO} zZkH?^<0Lzep~=EuxKJiWd&^tBG>>;_wOwSoomWm}Bnu6Kw?U$jm*UOzmUkGFcelar zekGgjyzUc$)i`b>3lk7wMcM3_6Q^lk1f?+c2<%-h3zQEgXuhMjk5@wMoc z&s0aRvGeA8%lk5uca*9R`7*rnQdV(`+0~hCW?S{`>@DxQ%=%lawo6X3>nqn}6erHE z&QG@UM$YeL{TZ0D7b z(PvI@q92^lgBHhQj}Q8j`W5I`pkIN01^ypYKpr#YtN97Jo__J!&raUlk$;(#`pXL| z{}$-K$Ro>Dk2`g9C#r2y+l;n(Z6i}QcjRAG|GDtp{_!nm$WT>|wn=R>+UB+GbvZMp zs&ceVYMaqEuWfJ3iEev_TTW8jw6=L|i`w?KoXE+loT#=*Z8O^Dwe4*=>G2P^`;*Z& zudOpdrAJ_UTMsr`R>eo#q_!Dt^V;@$e;V&q`=f1MTW7pVkHGeJf369s{n0k5ZARO? zwtoAA{vfUUgT-Z0PNOboaoKKNgZnmjv|8`msBQKObNw&2Z#_z-$Cg*?beb*OVSC?x z=M7!ov`uQ8(KfHGUwnMa*;evG0UQTwB9QrnESd2M@L&KzBi zwn=R>+UB+GbvdW%81a_&;cv#7R7Z8O^Dwe4*==`jzwx@EM@YwPTw(j&0FJf5ac)a7WK z*Vg%)E(f-kT0aZBpBews~!P zUCta`ueD8To6$C}ZEwp-ub{`H+UB)&hUxJrtWQ0_IHBM6EAao40{KnGJMyon|1v`- zIMthucar)qBdq)@>c2?cct`#v^( z!pgsl{woSA{~}wczo@YCFRA}-5?1~>TdF^q|0wZ3t^YE@%D;E@Uvw++eesvne`#Um z-~X-GjFz*Vt)@Co*JBZPz6I8~=4@xUNUyu>z*%Q?vk{ptVCA)YnO^++3GU}nksj}s z9{XYqH@~DvUrD6Xe9|I)MUkHR>O}YZuyaNFRwDQI3l$G+{#w2L83(BCwRNtOJXKD7 zvf_Y^h;+##uMtSjYdwH@xb1) zj!YN(oz(lS?au4giv6f6@z$NQrmJgFq|5!zoUHa6cB%D5K7yF$lNRZ6zv=6Fcl#c$L_2^G-7~i-3iO6rU_9r6$C8-hEu%naef6O{F5?vvZ=iQ6U9UgPG%20a)B5#> zUO}wXTWX5qru=Sqy-VqOy$0%a=Y{=x2hkbZO1-6~?#~P9#O`{R()D^()a&H*e!Zb# z5G(bTn!1li@X))IuGib5UKcLz*E@*L*jDN-HFY0D;-PmbU9T5Ly^dbeM|yMDAp>{` zw^DDZsa%7MSNHy;l&;r1qh7aO+DCeG*HHs*3Aa*jsp+6@`_WzRQo3HRje6aDMIY(S zT?gKcZ%KYD^_H5t&*jrQBK2N+(wJ&FUzI;x%~!w?Z3I(pC!`cA`R(@ zYu0kV=bS#KTF#%K+^tcrPOp1feIGWe)8$xD=6}AP4->BY!uY!s2fe<()Q?=%NA;U~ z-vGdta4YM#)YN?}yxy1Y{YfcZ-=Bbfq_L%s^yc38u!QRje5tq8)P3H#hu)=h++U&V zb@A#x(i`~#=>Kyo^_H5-dp7XuUcXD}`u-5q>-e>Oq&N4z6TmIuR_ZM^#X2^*JKgmz zrR)1!P_OgX^^xA(`(~DKoq;d)mYT|YX7K8+cPU-ppVMdc8ijH1`@!~0xRrWKP37}f z@sfJe>kXOT`gs0Zs(?yObzjS?Gq{q9Zm#)u?bh#fruFs2f&+GFd zUFu!aq;!JK|7^KF|BL1NyhxWkIDaW!pBL$p2mGb$^CW$7U7ydt_m#Wu0q0ri>yLKp zZBeHe-cs>|b>0`-3*O|xDjjxhk=|YJ>@0PDmJ#W4|FGXE=Sh*isYrKnYCQz(zz@E1 zud63cQQwCxiuA!krS_*(xv(34D7UY2vOB8nVKX0@H0`2C-)1Xz#t5F)*M zJ*(H>d*0o?s^@x$gk?R1PN(~x73s3vt~=Cv2-xDm-s>T%5Aj|Pkre5YlfKfH^o&k- zJ7w`Dx*p>BZ#Hw+pJ1K>HvQdZqTVm62etR=btN)g8G?os*B@t`Q8PhT^#mh<@;mh*X;E(oAg>3m+KcR#;`-bs-z_3m*# zFVa2F=S8|aUyPm|QF>~dzteI)KhttPFVZCs^edgui}ddCFP+bm^u={PKO<++`w@%Y zGTlpWk?yItNcYrRqK!{r=?$BI&Z7787QIEfr`{snQ*V;K*z|6<=>3L8Z<+3; zw@CNYTcmsHEz&*p7U@#&=ChREu=zJFdcS4STcmsHEz&*pCh3b!?+%OJ3oLrebT7R{ zx~JYE-BWLo?y0v(mwM;)d@OAKQ;Xi8S@ag^o_dRPPrXU{;?ldv{K?<@_Zax z8Ik{zG#;E$bB_1@fJ4slz8_Ggd)04|?peP@x@Y|s>7Mmlq|5qUn5Oy@*!(hjdwM_M zvXaN+en64#S-(ZPXZrRm2wU_XY0+Dzd+9CGJ@pppo_dRPPrXID)Vt$yHBSqh zU)7@bY8Jgkx~JYE-BWLpzS#7xwdg(CqPI-<(p#i^>Mhbe^%m)#dW&?ackxVBzhUzm zTJ+w?qPIx*)LW!`>P^xYm)_6Td+Qz9)?4qWO!v?`Dbl_4PK$Iey)z=+OYaVmF7=L| ztMrC-w)fUMD$>3BlcY%Z(mO5Ez4XqI^u?w3jD)w|&LQ40Wxz73os%{P{}nl0DR0Z|5*?y(1#sOYf*i_tHB_(ifNB>Hmo9zung5;(BpLr{g*? zY+j}dy>Xow_I;7wU2j}3PQGMbx5f41Geo-A_2StgeJhbat`oy%UiQ9T{HaKH+ry6P zdU0Ia-g%u4onhY->D_gW zUZwUkdhypry=ikA-Rt~+66sP`%ws_BnIc{4+BjZ)A2xZ(*Wx~mDyM6Xx(*MU5$Uqu zz;$`pr$o9JPvla?gL0wwjw0QQ=OU3VdGd{l2R3@S%7@PXR3x^{|L$)Lz3b+y{VeKq z=nU)365EUKVZI9bjS}fz`<)i)vVLH{vHeXVUG6t@gZ)UP%l$5#uJ#+Y*!qp)>&uW{Cnm+^JW*bx%X~181zR=iohrFbtvFrJt7&_*NbjDH zv!=?YDAHv>BpU{pO1N$*k0s=?Hf;0>FbJgFCB^^y?eP6 z^!Aav=es%#5_w5IZF5IUn(!K7l%)9yYyifBzk-nAS#Ql)4(SMG0?~BBJp0MYLbU6=;`!iva zk4sLmUWnYM*(B0s{-I6P^HyLpPpJHx^mB<}^E#c*!^*ZN_m%td+m?R5xP30S-*yqb z!IE;EUtFBfVR8MA(2|mGzYgkn3LO?#eOprUg$_$f{asv~(4qMWRX_e$ZNCm?|Inb% zv;J2t>O)MQZ~w1ar~lQjK)(Y03iK<`uRy;7{R;Fe(62zh0*gg~+z`i^C?5D&BQ7qq z>IWikEYjplJPy)XOZ>@sZ}}X2y#~OY>!owD;^QUeRV^NJnU6Tm&4O6&-)`bh?ql09 z$2mb*`C487$@j;I53dn_M~L_93!Ro1R(`Ke{K@M(^0l2ZrFrmy`o{rI+3BTOU!CyV zgJ(XI7?XJS)^GG?&a(0%gLv&aY4@Yo7&LF4*KgYE?9hAD4^pX)v!)h!a?70b8QGPG zueH`$sfKGV5-a}IE3&e((;oZ%nkyWz=cC6ybmN;7$6t60KHo@A%8OTiqy1JHFy^5{ z_8s`vT~orh9ivhmXHy;Hr$2di!>=wXeEG*GZ-4sEr8l_-pKmDz5w9~Z89Aom^4R;w zt^WC#Wp*EVfJ$|otz?A|uYIS_nip!EdD~}=gAQD{;F*V2s^e@euFc5Tx_`d*rt7!5 zVY5HPj$L)F?`G&!$N8OnFt>Ppcc+1>ao79Ter-p5zP)@-^Fy?gJ0F}qxF z@1EEF=aF;IUT?}7o8j}_b^K<`m^|XPV2wTtGQn&^K5MEzz$_P6GiHDhC+{dmqd@63Mcq0;B?sdo=8H#D(e*r0s|jQMEd z7wR?#_k&6LVZ~E_IN{562Y$9-{4bCEb;yI4J&5n8^^QDx+Og|h`N&mc2j24i??-Jp zTwX46UrqYq(*M3{_1w_4-ui9tm3A7lvUAhE`1}I>W{>;dJ@Kox4*zi0oA;g-9rAGL z5y=*1)pbh{rutV^k=`^y~6GPyzL*Y=`El98K2*w>))g+ z_g#46+2_6f+#go{qEbFnw~ph9ej>JUOukz>Sa=2 zZvVuew>;^OU+g~{pWmnByJGU*Paa*l;j;_2KV@XqEyHEE;=bDT!yWab~Plbr{`>Rs`(Nws@lJ$c+E_pJHr4F~SKp!B(TR-}Ag(SFm(vz|FVJ>v9N zX5G8PQ?IL3@yx&x>fNu2mnR(ZmoYmG{ratQ-uUj+Gw}Jtx_`QVi#?7X_{qHUci8Xm zKW#nmsFFU9==jg-{2Q)7p~DI zW^~o-aoI_V*P##A+@DzWlGwB(8&(=Oe!V+Ys^dJNzklfb=G$J|d){hWk7|xjUO2GS z|2(ZXeCpxUjBl?$Z0Lq-T(`-pQ&Xk>?`h3{;EWr-jh(t+sci-xyUslyE{pElY18pt zdeuqy>UfSvP?f3Zh>Tk5_j`N(3^yK;b zx4f3ya{ZaR?)vViSH8Fe{4eM?Gw0m1*Wf>&Gxf8rM_;t_nAN_<=P!*`@8+DAzIO1J z)9-j{V#AcDhD?14pTDZ>_oJ(I-g3@f`yRPX-Iw|IMn3gw>GNIGyQMBZ<=JV2POG2y z@J_S$8ITr7DD`?xE(Q>SZUs@OT|Qe|MsKH~N9quUzi*q3yf3yx4HT zaZRZ9PKS=~X4}?Wz4tZy{q^5BZF|qqvz|Q$-(RqjdiTmlv-Vs2!lPRrUa-u4Rr&SL z!{=Y<_^kTtjq`rG=9T!y({}B8aM Date: Mon, 26 Nov 2018 14:11:28 -0800 Subject: [PATCH 07/31] Refactored the code to OOP, still needs debugging --- libraries/AP_IRLock/pixy_parser/a.out | Bin 8776 -> 30320 bytes libraries/AP_IRLock/pixy_parser/main.cpp | 29 ++++-- libraries/AP_IRLock/pixy_parser/makefile | 7 -- libraries/AP_IRLock/pixy_parser/pixy_parser | Bin 18256 -> 0 bytes .../AP_IRLock/pixy_parser/pixy_parser.cpp | 93 +++++++++--------- libraries/AP_IRLock/pixy_parser/pixy_parser.h | 40 +++++--- .../AP_IRLock/pixy_parser/pixy_parser.h.gch | Bin 3053776 -> 0 bytes 7 files changed, 96 insertions(+), 73 deletions(-) delete mode 100755 libraries/AP_IRLock/pixy_parser/makefile delete mode 100755 libraries/AP_IRLock/pixy_parser/pixy_parser mode change 100755 => 100644 libraries/AP_IRLock/pixy_parser/pixy_parser.cpp delete mode 100644 libraries/AP_IRLock/pixy_parser/pixy_parser.h.gch diff --git a/libraries/AP_IRLock/pixy_parser/a.out b/libraries/AP_IRLock/pixy_parser/a.out index af923f1458d7558a87b0dffb78fb95565b977a3d..6a4dd3bc153d1c7de0bd49da667bb95a2b995281 100755 GIT binary patch literal 30320 zcmeHwd3;pW+5f#W$;?0?2?;wY69qvr2?>F)1+ooHlt5%r+&X5NEShBEECF096{4mX z8(R0;ifi3orEjfL(F%wGv`cJVsI`6bwxB_5n^y6qZv4LAv)s%~lIo|Q_mAKE`EVik zIp^8VbDr~@bI)^U?w#vB%a+(o)6j?ASY)u)>6Dm4McCe?3IK)1Tw@r{XBej&4%8C_ zPSOh{0978xm1+%L3U3Fb++3SP#KTh*pN85(!bC+I4D6gNu^JkNTOcS$TU#4Ps>k#-?hQPD;gW1C{b>lDoSP#Tt{J$ImPd~fy7k?}O!X1xf z9pe@X*Hq7#!LgcS_hhAtK(l{!WmThJ z(gvsa>ejFKwfKXfKyzhdLwJL)btW6CtFHEi*iMe&ThqL*p}EGl(jSU6`AMvn2DC)N zAy@$es;~4_*I((Yt!!vCfUT~t3>q!LhURcB=+)~heYFkLezo6d@;5aFT49lodX(`^ zl?~0t(vlM2tgM+v$=bC=#bv&ntXam=Wo5-BzTB)ltCX8H8;-EypIw}7A|ey5_@tXm z{JR2B`?uoE4M|*i{){kKnFiDfClcwbOSw;4AnI#Ht=8b&hW|DkY^i4DVO z!{;R8(Cd(1KRQ)my;^THzCsmTGu=W?<8}RDw#0KS(DRLqJyCcqLws)(emD{8=!?Rm zBQ8{IHyc5M2Yo!(vS3M zxBXAvO^5m_Rxj&F96ri0yd5LIhe-2w6ubwn6JxR<^Kr`LQh_=jl{Mau#4X z!{G_&qK#E_apYwudTO&$CT|w{FMFB2>aRoPC^B};9xl|J^(ExJyT7!1+xxt`dl!4n zF7NAKhQ~wUfoW3V2r3*(-^PO7U^61w-c1GTSXx7SMtHXr+=E*0NOZZ^i&IzP-Kd*1 zXCn>!=w+xxf5?8>ky>!Dw95Of5ATAnYrI<$rcMW&x82j5v#YDE?#mM=VD#;T-j247 z1Q^*XjG~`WThR`lMe*lwAH??cCSy!6)~Q`>E!5uCb``+mU2Q>G3&~m-Af>A<0$_Hv zwMwuK!02jQ4^ZFLwn5ge23XnEc8#oE3oxat?K)ZeCcw?W^{ROJly5E3Gn6%x;*WG-=5m#*#dY=c9*9E@K(ru2XdW&TLHg2uFLa1 z$liv(+d;phq04h8;9Zcv8}OcKU7qg)-aE6)^8>&iLhe4uZG+tXka^(mU7iPfx;zgJ z>+(FD+U0pGJ#{;36`ES5KP3iLd8Sv1|F3(}ZyRU6M!lsqsv9GNjMaGPGizs>* z2;#at#2CXxqs{J=XN{C+ceQt6;%vr>E&{FhtVVs?8I>FX}~!*kp``i9`$CwM8UHE;URjXqJR zH|5!lvOL20983;5x@9j9%xbaM3j^2(?T@b8Ql9IU^$7SA@VBd|{kVvnTC1sh|B0qH zdHT$wcSzpC3c+!q#c?$_Iu9sc>E5+RdcYplLm`xJ33;eChT&_tK=cJY-E@3dt5bO5 z=ylSliV6wK(dsa7`v~@{C*`?9xS&rJRqu&a9Y@g+eeM&+?ZNg!y7$rJ!ZbT6=Z7L#MoAU1Hpg=8LeOIx497MYUbQ26K!aSVluA)l z4LaE1q(K|}!lg&@wPR=y-Wa)#t{O>^UZ8e}9by-vI>wrmwhvTWaIthjO558+brcMv z?2}4eO3IB)VS%1V^zA^`?(-Z12J4iAlug(5rL0?mB@KS^^jQn0xL$F-_IW$JoN5@% z%`T26*2UdDu3_D^*i)rE=jp9AJ%_jy*^d51+4zFsqA(-i#aNjSAoD@(0?#2a&ac7& zy(d1_c-?Ah+e*h)ezlWS}f)n{k1Y5#|? z8BZM#x7bAu*2hHJzjd4Z#ccL6O& znYG=bW<@qHPekvDVR|{1=^u(|ZwwRH%cywySTSJ-64l(kSf)?Fgx!q1NFa(n!37fF zV{8oo{(&6@L-TRd+t0Q)1%J8w@YlVe88U04xB)S$Ow=%-jZzUagFc-}CNzKBsu zNNHOcJto*Eq})^}G4%1zV?6UxtY`Ebp9ChGtRfX zvdFR6*Sngla7RJF;y?U1`t~6D0^c4S(zgc(`gT87583AZ(6PyLQ2N$PX}cB5qKBxX zLbcyNjn&qebM0GusKwh6#F~z3$G1fl*Ua``_ud4}Qd7UEj3_4}3M&AJ)-)_TK9u?rr-^*q!rxeg9xt`=`s=KPhehThWQp?|L`A zYP-5 zGgf&#?$zG1Rhc-TWDxb#W*Dp1RkpMYP$;ne8h5|KmHx__0c;vs8w@n5mX|aHLt%GS zW1#vOgZ%j6hM*paQE_EOD2t zD6d%NS?$R%miuAe)QGz&5cIpNHiZ2l8e1J`YH9R`{q9OP*oPa%%T|<}7bRtUwOlbx zA8u%Sm-(CP!u9S(nC}kPS2nwI@?v_UThtxOb%!=ISBKn{t++kR+tKbybT5Rv!R|!` zLRj{^qGA08=yop+`YUk*Tj~x3-Ttd0m5uC5&K&o;2DGdcp5v~rY^;tnR*KQD4pwL3 zFiKXIxR;?8it{psFq-$ zwV_5LL|m?}m&4$0XvRJ9Fbrx432t`31)Xg~XB$FRd|tpPz#VvZNxdJTQc~I22=*HH z^qKShO)bFZ%x{pP;?6}$yV*T!zK9#Xr#)b4aU@JB&zU$hCkixTCTjum^A#AP;`N#lyUMrD3j5H7AX5x;jl~D)IbiZ#-<7K?ZdU&Tkk~ zKqr6wkrO9c$eWzHBzgR~DM{;G8;!*i7o0t7%IQQ?z7&7k!H0dCbx@Xvd3D7yVTtqm zr>41$NzxvvpKW{>_Eg#N3C5l1Xi;+Njkc1J4(}$reT^NKOB)^n-!J|mZ<$#JdLigc9{TkkwCGbn{}l9NG4wu*UJ80Q z#_o|A`u!HY2J{Osray_HKV{K3gZ=^Nh46#bzI}mk0R8w7=*$j2O^Bu+OQ3>Mp!R~^ zhYPG9WurJb^*grWBCeJNOo>`PUy*Swo zKJXVOyTs>7BM?L5vAeM+BOYE6hrdbH^>^;XXMVup%Ov7>X1s(G zR9%0caFVL)djb-89f~e)QUT*q9T2%c z>dG8rjAXaYN{!K}zMrRa+)l-z?}OkYBXNvV@N(6##^0+JeE4uw9J>9}R9*Ao z7LDj1%oQkn)j-t8D}DH`kEm-qaXUcN#b=bzg|s||uGIgp0sX!5c!g)Gj?YnWiGmj> zSgT;Gg7NZSRoCAi)qMCO?R@w2HC4Dr9&zVq;XAdNx%m-M&G}}|+^m^-XGyei4n*WA zN*~{&T+O>lgB_CpVFa>d{9J|1TpikRLiYpD8!n8o4vbR59Z<|$G=nu{GhOB2vDuub zAz*9?&ZjWYHkb1;0@J}eDE1A|W}BJ`g*IDaF)H>0q)y8NCLtjaUpR(Dq8%;RM^ecx zVG!&)SnOai(dBU6O=;6{0rWXpcDT0T?0gs}7rtJNY56#G4$Fp;gfE6Ce8JD2lkC^m zz)?x|jkgJK<8V-u?CsM8xTQ#djtd01^-2N0vr&Mpj|*_yD+1i{djanLM1Xrnp$AF! z@0SShgK7b`Z5H6cI|O+60RbL)Mt~o^A;6;_3Gi4Nx{zdlV!8lNE*GHhHDTbfPtb=X z`zH+od3>_~|9o43Pwy7svmF9_{&xUl#AP@ooEQb+k)r3OnVevnKNVW`OPvR$vOh~@ zhoqLnQp@{NbuX2r)HJjj_BS7ZMhd3x)hCV$%83VyL9)5+KZ6%+sR?|(!j_QGz>#z% zOhDg&91SqaDBmFg&Y3kGnEB!4Lf zUGaNZb{TeB>R1wx{N-a18#GYzFK1EluVC55c={3r`&ckKD(*uOG0EGBqi=@!j;Zz| zKsj80!+8uXV(_I}Cs2j~F?QTa^v6+QBZr$DJb`#7!1xKTlDNi3Kn8}BWSE%4R{c3p z&frRY7*u0o36b^WWT+{mm&hyGM+Tlmj+;Z7bin35=k)k`Cw}NhryN)^^7H;tp%Z5@#iJn5si=cH}IlKBpAJciMv%Bqmz@QD7E zQknw<;+!m0lAQTsm37YLL`ZVZ6RWIqK7&2Uxlk;3&P8ICbry*>1OmdcrRo3Yd ztE_XWSY@4FvAjCZ70avhJh8kwmx<-oSuU1W=W?;UIxEET>O7yz>*QBqkUI;dgRWz1 za1BhW1H$!*Ff@%{kaK;;p>w6p#;CYH7sHt5CjJYS$EWqM{3Xlov`Xl4onU!-#zION zCMz>DUPFIfrl`!#IGYrks1#+ z;u>$>4Q-n;4zic0n2(`ybHFIdSEm2DZnWhGlw9?f`% zm6@WlJ>$Pw$u$}AJ2JjYN6iwp?aJ6gLuZ>$qn*9R>7!`EJ?`hhG2XR}olGkw_x&sy zX_wHB2iRR#+5&d>5e`o(Cefw9Ib3f-*%`d>)9fk5C=koh6xf$EHr<$d5&Cx~S9aH8 zllU`7(8NMnew0QPiSo2X;2Cxk+niR2CWqZDirkXsvI=gzK^U8s!>s#(gmA zK5(bifqTT1^H4O>T3DXSvMp^Q_(z<{aza`!m`6-w*NL^< zXlukd9Eb|zY#)F#fotQ4nID65#wDN{Gp2&yobeorwi#Pdw$F$FpJ1d>>4?nl2t_-o zXdxACPfKD01@{5JBQ2j+EF!);Eg$1GVsRlfA57cARtkylNqd5NidgQoe@y)JD)2bH zNL$XK2S!Y4hjz0O^-la{J`K%s@&Bn+qSpQk0`|Ls zS%0Gs=Kcds?gV8P{uWsrdr&g6{z!A?1!41k)Ystea*Kn0F|yBP6Z0PgAIC5hOEu1* z!#EHk%7+z&=9&!)Hy>g0K(xS+Gg6$hJiC(tI#2bIOn+0j+stZ#qZzE zd#}S*KbN1ho1-ai-}?5oxmmE$97~<{t$o+#UJHHZcrx0z_IxvU9jlYr5Bt{MYjcls zP%=6cbygzG;;}*k<1!HP8VvJPDRA&wWAHnhPoj7KOG!#1ofw;`Yyd`ODl9r&PS+2~Br}yn zmYuGLaZY?3CzYu@4U_sam0chpQ)xg~kg0HAoMgW-1wBEga*hDEED@mN5&>>)5#T#* z0&IO+fZJXb;Eo;v?*2@Gd&Xkuk*RnE_yM1ZOR{fk7vRC~3-Iud1bF0U0{rNA0zAsx zJIVgoI1DZ_l}rJiTqQtXw=nS7XXpbmm1coF-Y&pD-xc7~9}4iVNqu)EXQXm4*?gKsr(fvr|V;!MW*7y(56}^Q23Z#Or|oG z96W(I17JX=!f=udDpO&?!Qe_|kVa=J3^j$6nF{;Jz>`RwsqmR@#$mr*sT^r}`V&f4 zrb1UURK+e)ZWVQ=!fPqRSE*K+3VqFJPG!sD6qBhi!i9in%gR*P`W%wPiM^6^r)wdw zDpN^hIXY9}1c{f>nF?o3D*GAVGo7h$KFJOZmZ@-l#bhdU`EQ97#<7Iaq6<`}!tQb! z_S2>Es7!^^GoBossc_y3x|ONWExcQk%7#)!i72$pZFY2~!l@{^=p-vs;e6xtjGA*Q zQ(-W3#>xg&ra~m=Z@iT%Q~5o}oYw=$GE>P0ne)A$tTUAYP*QP)j-nt_5o@M%hFCM5 zSz?)U&SJnJQ(+iIXDVfs7TX78Dzi{QrXp5Z=UlPMI_HU1);V9Svd)EKxpOWOtE{t7 ztg_A$vC2A2#VYIch*j3PRIIX2uUKB4=ZfXkd7fBaoy)}X>MR$_t8=+nUY!+Ud3B!8 zK{6E%oz7ImFse+2Wu2+8tTPpstxSa#D^p>`%2ZgfG8I;=OobIIQ(?u* zRK5!ftxV-ERK7;0vJnctMyB#ZXtOevr%1J`aZXgGG8WhjO-ZFy(V5CCpv=WziN)~?l%g}0-=Kam z{`?jP{Suw2a17VSQjIg{Fb;%>a%3uu5)Oc_3l+ed~_vXWfd5xs&?rTc5c;?-Evj z&SA7|y*%$M)^<_Iwsmcuo3&Ti7u(ilv*(Q#`i(*f3_sHhq$3B|dE3?sWA=ZkPt(p- z95*SB_e3VJwbaO8pgu3t9F+g3q{=l61L}P^2Q-Ih>oLi3fo$t3S^Gx*w-j@9TaU}O>hn7lF}AHIr0k_s zpTnRuFZ~O;v_$#lC#qTVUSdZl$M|OLT=eBqH9&daqUk<4y7fj5r;U03JV0pFcsF5Tqmy4&r<@h=wtbYm1pR6*|7Dv@e%@&`xYc zoc8=16&r64@}RzKHBgvrT;t3c#^n$T;ctPSVhf7l<1hslQstMpy4?d9RNByWahUfK z`yl=bsKU0j-k5(GRc07JLH#5ASt=J*0?n2eRiVJubWyd&)S$qryvVOHwW?q&rgnbp zIu^OVPV-x>_K7WETWGuB1pzNFctyaq1-}xoqTp=-mlgB~SXgjGKnNyR~lkCZp zl1G_o&Qwfm+Y}=yX%SFZSjHOm+!&*%2eH$k^zTggE%!E8t9@k^Q1E%v>44{7o-rdS|X-rpo?eOVwyTT0o6rG z98f)kGp0ik?*yJ>^#K0PO{cdr)wlVdmtLuhEx?aIsMeKbOvAH z_&bWl2;}zLYa7qIjfm1TC;gEJiW*o_W=jetwQvGgj(;(%$*t)&Nb;epc65XI8{VAv%)D>md+|eI;yHdntq=X8|?Wy*yln))FhafWyUvq zr<_OgHN~AIC*%Tc2d-*aW=?u@a=)ocrXbPC5q2%=Z^bYc55kSf_9*US+KkmWo91W9 zBXKrSHdxP&go4?4?yoUY zzHGeuZ=m{o-ExdVd|v?%-DXv{w7^CqyrIP(%BrWa)%Ye2bn){RG=b+?Ya8l7!DbYM z8h|>G%lHW;=V-gR1`V zPJx)7@}NDi)}H1{vp2gI0(K&|FwI_W?u|?S&x}>Hcm6L8nckt<-KOin;r}@N_Tj^e zZz$h{p|Lw|-~c&X=>)C?>kcp8X`7ku8XZM@nf_k}riF)ukk z!}wwr31IN~n`?|FJnh{qFzfJ;zF**~`E;{S#A1_t0-kR&ZI0kQq3aD_ZDVB}UMgB0 z3Hqu7jgh8iV;$cnidKA0mBB0Vo>D_R+U^Sne4zl$;HuEf=6x40pJyqWh3_+Yps(Ds zYE{uvkFRXGeoo$~@mDu;rJCLxX>4o>2hTEs{_0jAwF;}yonSZsnjvh&lhjqzos$za zeR6We+fCU|ysE&{YJ~9409BLnjWr538ori5h&~EL!f;49u&!EoBvjcd9inX%k53!5 zje*LrQO!3TSk_-qw5+VuC!X9NU`k1zr>Ua8slKVn!24e7+~O2z4mH#@`|-p%w8(B? zMEJ-(e9iSTXAV8ek;1!MBQU)(gg3i3@>^h);Q;!MH@0Hv0tQC3r3l{rW>oJDD&n{Y z@g%#kuAwGeFLdF#{Tiu>%qyy{FsefS%3yUpdyhA~Vw~1Piqaeam?AoxlRFo$g%$5Y z@QEkc`4(DO7w_{Nsb9Jran=;5@f)*YGMG6^+W%I3h=<^XWioX7jl{4US49FGj}Qk0 z5eHw$7!|HyHP@Ge_tU~~UzBI*&?q9tlyBZ$;S-}NM5_V;xR24ClOui4Igni+X!2)Q zUKy&d+)#DJ%-r0Z>{5T|%5b11o6f2b*R19Kb+I++Y4QF55ukkCE}#3ygs5#sx2>yh zY?5&#q1J&h5JH@l|yydHWF^)@T|qXLk@ zDU47{NG+B?L@7d5Eh&8Sw!37;jGR3AJ#KeqQ#jJ>FR1flA#A8dm6NVOzSrBGS?A8I z74K-y#49So{_1cbmQ-Xv)Z!})4)?B`or#Em9OWEpXHiAu&JE9*oE1HRVL1woLMnJLDTvtF4|?t!_+x> zuo3eh67n<6E ztR&U-!8#$RUtQv_5iycugzFnHyW`p^$+Z@DhA7pp3j`s8iS<@rNB-_8o)b9fp41BwEI9IK_w1(Kwdv_};>J?Cs+ZyD`kT zc~JatLqAUvEn_#54EJ7JD$$b&jH2a$Kv-6+|ejew&QEu z`njEGqMc9s%p8n=f-!zjynYHPS_{WOjchk0>= z@%Iz)0=%DWGm?#6apTJy<-{Z8VvY=j*UxonVm=C{(eDSg$72cp%t8F$1U&WY=fud% zV*~z7yyZnd*CmiR-G#rw?7x2q{80Vm*k2gK)Zgr0%%^LxQR zdO*B=sPOUq;((Zg#M>BjKz)iMB=zYmflnTABfb>)RK#a|9G<86<3Cv`#(Lx)B%ZGU z|0rnE^ORph;lY;_o-T_q=SP%&eWyS_4fO=|;Qmtl^HzM{P#VTP{HD?Np3UDa2*hlkM5FM3A%e}Xy=52bz5BrdCD2z>SRyC4h{p%pUaFef^zZ}9`qbA_1!)Cp* z(N}|AW5`z-!OmR0P_8B`f6lx)gER5>J{o+L!C>VETm1nhYbx|>r5cR7ig@yX3NBDyy19oLO)~?Lwuc-`I4&cc7s$78? zqev~eC53g-zmXE#xJaxp5}|+(@7k+Dsugd}fSVDe7iI-W!?L4b9LeAu?P+X~q4#hCp*n#Rpo@-&jcjRcdJr8(Eyu zMiz=$b+~bpg}Vnh3vXrx17a3t`RmonQeOilx(4m|F(d!_YJW@EC+=iOWpdGxI&>Lr zRyH+M!%9x;EJUi2g$1t(ix_bJsz@C;E1T=EI;v_zb8SGEE32x4{#ISXuWR{r8Gegi zs{gGrci7kpV2>#eo!@E5FY!emQaM(3aqEwA%M4X0>E z1>@yQfyZkX1G;^kS8Ay3*J+>LFKM;QQNSnXmi;@FA`R!N4&!?z!cSUWU51SdfXAiK zlGk~vhWb4SU=c^W|Goh%-!Y)==a+AJXs9zIZNKKz@JjIVodvqC^Ii?bXK3J|{j^it zkD@sEOe~w!@;X1(@StSlhiT%_^1A<*12n{Ujbe`Y{y(PV_4w(0M8lDB0@`k^ROWg8<3H5z3u^v2bq4c3`d_!N z??Y%z?+ukU}X z&!o2gc$KyOx|aV41UaNAc#}!S}pQKSv=dq$by#FFjdLN zu^Gim{_;42meXi{|2Q5;+5<}dn7#lgfp}g%TON-i>z(CNV38iUA>`)`A^+woDR5WZ zgo$sx&+HDIw2=^%Aw3*z9h|YLd;#&MJ6{ z#>P-r1S49Ct+raNR;;aB+oozY7(0U6indl;wT%ikSgi5INqw;W{yX>I%uY5vwx{Rx z=FEQge|-1;bLZYWbN^hW)h^A?%M)BY;%q@u$tYV>p$vtmstTY&l#9{$JxxpzBO#BF zI@?}h1FUu#P)#!yD!m6tyz+co;l?S-kC7uJEKs(bFkWdHgMYxk$kDFJZwg&-Y`~*L$KCX3r6OB z6+DXbix!`9T&4OOZd}?_{EYk@<~GLa7L?6xjLd0_H77UE*<8M0&VsT)A|9A0@0;2u z-(@S-%AROgd8jDnNw`Qy_FXStaNn*OQyxe4Kubu}!a zc+a>hn1?Mlz%nt1bsu!oa_Ao(#{bS?^i9L)r$X%MKmkDF2zRK3GHp{~Cq$xe( zjR~!Z;tF#}h$eig5pKBDs1L;&5o36B$OxIy%`q^fP#yov`OwqM^WblUoPjj!NMp~&Jm4*m={c0(niPv+rH>GADqZrF z*l3!mMywGSn~N|fCLoYPk0|FQI%`ezQKBHjP2j)()X)6kfMsfo+b)+|qGUG{-DWoF@rThrVG?YiWrTh@d6xxvoq`Vh$eJ5mDO5d$X zy|6(~y{We!>R-90c1OV&gsblue-kMBjwNryD_y(|oR5m8R!h~r5Z3BD3hn^viw5-6 zVe@2!ej$knef;`#Z+)O>>NT?c^*t2zpo}JCDQV$QR=~o}6k%{QrN6eUsik{L2O1mwsZLOtUz1Pyd0c;0eQ)Fo! zd6u>f*EfZwUE5%3Dd2UhENwgR`stRo1Guxq(ry5Df_Ec$yE-lHCU9=X^)2XkAGWk_ z1NWS7X}18sGsDup3%qr%rQHVn9(dme?{?rFz#p7sX?KEq7p@<|es|2$?g9P?{Ck0W zzhY_k0e_5s?+5+_yq|*i0C*3A^U(X2_Oo6~dw8^^{oH41zgTK%zl2{Gc)x=F5!4^; zx3tH=`!#rvBi<*#>&CSYwkHv95AZ4U_Zy&vc%KIDN4y7s&w%$Vc+Y|NTX24d>v`x8 zg7*UOMeu$P`~!F|0sjcz%fMH_`xAJ7M*UTAUPGL(kFm7B^jg|q5oa&#Z@~6uv8BB= z!O{+acNp^9(Ekm*KHw4HJ4KfEckqwmdKdP8;JLg9?8kF?ANT>D%ZI>^N-XVTVRdY! z=Wcae3D|3OTqS40(;Y29S}^){S=Cb(W^GRarqh+5rPE!oz_fNCqR*csXNg(R*8#(U z9yx{DkNQ$uKT9PC+P8j|mz;O?)`4^y6Lc2Z=p2bQE`h7Qqxd4UhgGl@D$MmIB&DA2 zn*(E~-O%Gidx92r-(3iZW^T0*!3%=t*Q8z!t_@-EDP+$`-)ayO#APrYYO^(>}uwnAJD=w=VF3)l_Z4{QLwh?{u@Sd8%LeX;>K z88@^USPtw1w$Tlu(DxISyen3Tyv@G6Q^$=e?93bGBRzdHuS1)&$w8Ie{z6QLo&5KI zl1{HAU$1Yeck;PKV=pgk6X%?=_>B3}r;(cY7*5d-Ke`7l#Jw2T2k5VgZZ+ujZOgA3 zKhkq{K0=ahe;w-L7BgO zqj~*1MpSxdUSFVlOSX;Fz2)trmU}B&z2!k~Nzgm9((8vG{42eM^8G#nW496Q*iVES z`~MgIKH%>Ge*de-oOyS$Oy4S0#@Qgc)XQESPsAGa5`NHq{A@_@Mfzo^LHm&>ZE&hpP(TbFD$lm3N)`GJx-^A;wh zSbAk?d7z|hmaYB*4SO(q`CRXG_h3)t^KiD_BTOD}hk?G_c^*2{m_r4b`IoI9DR`b{ z>qiNGe%X3V0iNIvg9lj-o?i|%`W+*99%k#uX4Yf2ew;YS3&vsai1EUojdK3DvANPnM*sOQ4{(z}o1DRss3 zEcDdxR<-fUcPn(CDm}kXc;BV=a`jsTLmuYCXZ%8eAD3MIr^&#E&Z`pH&d~X=Ncx{J zWd5A1^!$F}KG(~3hR&Y^^ttjL*Fo>Yyz;r`)pYD5{v7k|M)*$vgVzi1-?u|Qje~ID z80aTroX=7(4*87(`(xBj{z-!OO{VNdzY}w;(*v>{_8P>Q(tmKh&sL_lhVj2d`VZY_ z(kdSJIE;mVuDlQ>*l66`>rq2HKFqgrHQzYWxzc~~ka1ot<6*Bs+$i;4(W~aC{C0!6 z1$zIWTc&os@?WXuKSWt>mHLcZrt;`8?L0G#{?IV(h;XZ!Fq8H5fv_0NgBfO%5vEL7 z0tu%`+}P9@uM0IA5i{PJFha@AA{=jOX^fiDNMPZDMU+*`;bb6b6*EGut)VSOwApOk zBI;X1O;IC~Y--v9ibFEsX=b@nYAX8Gh<=dV2n~`kdW^SHAj%M2CN3s<%znJOayroN5Yio=(!OB_< zts+Y(bAS~UGIyu4bVf81GDFBZo`-vg#F~v{B1)}NE|AlIih*n&<@hk_iMY{#d!uZn zBWdV%%g!$jTFbyf%9HOF!zr_ruDA?}%g#8$zb=vBdhTqen=SK|;Y3o7*S}A=+PO{g zrKy9?T)ED{$nD!7n#%o8(zV%via=sZlNqW5nyofAa4pu1+;EEsG{?zE@hWqF5ZARwvXEL9oxY-q`(ALfTZdGCQ)8L@cXE0Tn&*!uAp`$Y)^Ly0+ zk&(}paFInd$D-JP8lBmg&)@ls+z-dkevFrbPiH`uGv@(CSgCrV_{oRkS88zuDm13d z=W_!ipG&!a=5t)vD1N1Ckk1#48=RSK1HNFth4x?0_q>*B9{`Ep803E^xT{i zdG0w~D^&m8YT)QSGZz=f&-(|>Z;su`r%!w;qg_Vs*S69bAvb@tN)#SvM}= +#include +#include #include #include #include -#include - +#include +/* + pixy_buf_size = 17; + pixy_buf[17]= {}; + pixy_len = 0; + blob_buffer_write_idx = 0; + bytes_to_sof = 0; + bytes_to_block = 0; +*/ int main() { - pixy_parser pixy; + uint8_t tempArr = {}; +// pixy_parser pixyObj; + pixy_parser pixyObj(17, &tempArr, 0, 0, 0, 0); - uint8_t input_bytes[] = {0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x17, 0x01, 0x01, 0x00, 0x69, 0x00, 0x56, 0x00, 0x27, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x17, 0x01, 0xF1, 0xE0, 0x09, 0x10, 0x46, 0x00, 0x27, 0xE0, 0x00, 0xF0, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x00, 0x01, 0xF1, 0x0A, 0xE0, 0x10, 0x55, 0x00, 0x15, 0x11, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00}; //array of 15 bytes of SOF -// uint8_t input_bytes[] = {85, 170, 85, 170, 15, 1, 1, 0, 104, 0, 82, 0, 36, 0, 48, 0, 85, 170, 144, 1, 1, 0, 229, 0, 86, 0, 37, 0, 47, 0, 85, 170, 85, 170, 23, 1, 1, 0, 105, 0, 86, 0, 39, 0, 48, 0, 85, 170, 23, 1, 241, 224, 9, 16, 70, 0, 39, 224, 0, 240, 124 }; //array of 15 bytes of SOF + uint8_t input_bytes[] = {0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x17, 0x01, 0x01, 0x00, 0x69, 0x00, 0x56, 0x00, 0x27, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x17, 0x01, 0xF1, 0xE0, 0x09, 0x10, 0x46, 0x00, 0x27, 0xE0, 0x00, 0xF0, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x00, 0x01, 0xF1, 0x0A, 0xE0, 0x10, 0x55, 0x00, 0x15, 0x11, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00}; //array of 15 bytes of SOF +// uint8_t input_bytes[] = {85, 170, 85, 170, 15, 1, 1, 0, 104, 0, 82, 0, 36, 0, 48, 0, 85, 170, 144, 1, 1, 0, 229, 0, 86, 0, 37, 0, 47, 0, 85, 170, 85, 170, 23, 1, 1, 0, 105, 0, 86, 0, 39, 0, 48, 0, 85, 170, 23, 1, 241, 224, 9, 16, 70, 0, 39, 224, 0, 240, 124 }; //array of 15 bytes of SOF size_t size_input_bytes = sizeof(input_bytes)/sizeof(input_bytes[0]); for (size_t i=0; i<=size_input_bytes; i++) { printf("%u, ", (unsigned)input_bytes[i]); - } + } uint8_t input_bytes2[] = {}; for (size_t i=0; i<=size_input_bytes; i++) { // printf("Calling recv_byte_pixy : %d : %u\n", i, (unsigned)input_bytes[i]); printf("\nNEW BYTE IN:\n"); - pixy.recv_byte_pixy(input_bytes[i]); + pixyObj.recv_byte_pixy(input_bytes[i]); } return 0; -} \ No newline at end of file +} diff --git a/libraries/AP_IRLock/pixy_parser/makefile b/libraries/AP_IRLock/pixy_parser/makefile deleted file mode 100755 index 96a27f72d8..0000000000 --- a/libraries/AP_IRLock/pixy_parser/makefile +++ /dev/null @@ -1,7 +0,0 @@ - pixy_parser: pixy_parser.h pixy_parser.cpp main.cpp - - g++ -o pixy_parser main.cpp pixy_parser.cpp - - clean: - - rm pixy_parser \ No newline at end of file diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser b/libraries/AP_IRLock/pixy_parser/pixy_parser deleted file mode 100755 index 9756c81af436eefabfa34381356209af471b972a..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 18256 zcmeHPdwf*Yoj-RblT0#@33*@wC>I39YMwj}UVn zlh54W`906?{LbT^bMC#l#i(6o(KM!#m0iII>r54t3d!idLS_Ie*g}?$>r6I-kyr|+ z34VnD;EFUXO)F@ZbSog~Ewl(iGMpym6jUA(v`OB0VBJ(fRgf{A6G)GI-E}TU0d<~H zaEtU~7dgh0&aXr!y+@_qqf$@7A?cWcs(w^A`mK?6li^bEC@Dy?lle%`Zt)hj_yf@`g$&*t2D*=xxk4={CiG(wr*tYU$1%N+KW5(?(p5iX z|KT(PlG)=(2SL-vp*uhuPoDfAkABfv=vSVFz72F8zvQ$8gz@a(54xT#47>!tnd8tI z+M$8MzJRqwBVp!tha;YbP40%~P3}gIzlEp`&7Kfz3;6?)M(`W9c-)QtfTzWOlaICf zT3dtdK9I={>4qZiR*yfxuB@%8s&YurO|3vC3>m@BZ#h*^n4KfyL z{Hk%+nI;%}0en#9>q9376DX*iCa zVNw};O47*&)mx>5addM^0<$lUuEsv;{5*~xKR@=z(N&#E-qrQ4-L=hjqCjV^t$h*8 zNWZJ=r}iUkWd2M8#c2IxrM z0_c3?oW7Kk)&p7V>akr7=vp-F>OK)EKvgmbMO7wl7#V0Ra!$XE+uv}6YB7q#WC02G z%+Ka#F8Un$uEU>OUEM>j!-Gp)TFmwG=aGCEd^ukjoInQ8X0NmSb%?QOv8${6yOdi? z{!DOfE8hofa3ZQa=)xstdm6Y#?sSr4A0B~8)Q7}3oNR;y+paD zYA&shu7?M#Fn0%;1J(_TJ>?%vVC*1S8C>%D$Ov2*B7_&Wt)dP-425qH*xDiIfu;Sa z&I7~oc#8AD&*O26^FY7AqmWO*udlLuxI2cTwwp!0@)?TiGKRF%-x9JFbzI^WQ{wxO z*zvrom+tER+92xo_&L08T(;Siy&bY(-XoZ2ulRNdsESiKseWC<>FsH}{-@i8D|K}O zE+2GlOLuiopxO*N4^*JyLozGtOjKE2WErpN5clmP^ji_sQ=g)ys<56qjpw`T>ISbu zv=7oiGAl`q_rhdeK?rvDA0D25cyPM*T-V#$MbCBj-)Vc2Gi~1$GQ6N4m<4?u1;M~w zf_e5JbVDFM2uCaGsKE!H88_gU33KE5!^^+kEMF7lXPjN(>^_~zOY})}yupxcm>deb zt0(tom zryzT(@iOB$Z>4tfWD`8$qv+(z@Zuo9@f@WbujsSF=Kx7o3ZLKMJ`bk|pNA)MpXUpo zX@WI<#@xt#E*R_cyYS;(`1}q{#lq(^*;F&~`CXnfeSY70U@d;eJG_Br!4uK+zZyo< zA28lWb>4~OAl~1_dSP%ksJuF-Z3oFkvzJ$N58r9L=yh#NnLUSG$J||t(rn)r<(_?L z-46jV+%cWmyuiAjbM7}@Z>uBu%qacitkN&6@(?+`s(AJ11m;KZ}Un zM+ZAG*t?B4w;6A8J9|w#pZtZ}`E-)(k$*5bZxN@b{7sY4PlTh!0IEaXXCP~H5xUPl zXrjjqsHW)S1w3tP-A`Iw#(;MEg`XgpY;ZjYU0-|C>fE{(-5RQ>rJn`{WoLX$Zwk@;sZvrT4tBJ(3K|B|K5zRz=}*^jwza=Jy+ ze~kMHz(=@$0{j`bO#pGb6gQEhSh0!L+50iY4#NncKZTYW`~@m~x>=E4BT_E~rlhI~M~zn~yxWXdsE45a;gW07bKycs>9H;5PNrB82_ESyP5lz+cNwo}rw=2%DbB5W zd@ym_bl#CE=8?~ws>UDjoLOTEZd}#%Qz+?rA0jm z^e356?;6BFvJFvoTi!_mJ+>DJ@JRO|H~7X!aBiFJMNU0BI0usy##MYT-kfb>Sl-$O ze~BvW0BP9knkyy)5F;=n=Zdety8{(TnkiyN=h~R@^?fnpR=_U6+nh0Ds}?hE$L|gn zGwy7T8Qp+)t%@1j0Pmg^GkO5Gm&A;F0CzxdC-m;!5i`C4op0jzFQ9+xM9lbCz+KnG zjQarZpB*#44Y<2FX8arAccAwG^!5Ng2>8%BG2>zA{yTnq!GFXbGrkM>DD)o#+;?Hj z_#WWnDEA4#C!zNr(0dAcPebSXAH<9w48)8drpJu`%!(QNm&J?&kUI#yAA$Z1^1VYb z;}GlFo`b(f0Dp?|eg+tWzefRo4u78q{4eOe0KFHX_Y!n|f!{Ad z?}y&YfWLy?uK{0y-fsY3h2Cp`$DsE*^nQ!{8_;k6)(0>=d_rQN2?eZtUA+*Z}fPY52dLa&0B{ zdb1~|^Q~MV!PS-BpVf4KTzk<8zBfJmnRW15=(@JP7tu@KQ2Vdi?!VP`f4sE&Pn9FN zZ@RjUXs$)Si=Lvr>-8HdZ>Zc*d1Iyf$d1wd-iJphFxczz-7W30Xf9Ot1Nk$KNODW^)11MO?n_0(Mz_> zpRX4c>C1iLu&2qV*96*e;^UnmN=Ny=hG4*(pio&kuEOe-%k=7%%j;^5HO36K!Uy+e zNA=cV$fwtLM0{a#wjtQs*5Zr!bdL`43|3XUvii$$TI`GUs>t;Wru?n-1)3twdJEjw zBh8+GUOF$KHmXEbp)x((5oieOo^~91(Q%aSLG{8oN&o))S~=>mPTA0Cmg2edsFHo|YDfd-XXbi+!zapqDQ8i>{)VA*aHu z&t1&>kDGeKJelXc?V=1uG1U=NF<1z5*GC%{>x{;gtWQNn#XmGOGHBq8pDLHFF;?lu z^13zaVOyrZBTrTmbuv~M*XmX4*BE-uip7`<^%vzS2 zf0fg*+1|;POu6h!b7##YGU+eH?@q{JVP_`Ny#c?wP)|CGW|f&)w_B0L`s8U?9`@55M(MbmFbV`}KIfE=MVXod zrbzytb9J7h@kB}S&wM@-Bz%|b)Up`XM+YoO>RAXsW&zG`Mu0ygCK65sdCHeCPeKKx z8MaG4pHO3Gixg1vo~%AQN76f`BZ}TfV;@QR-N!M8=hGso^3RjFlEZY&>xX!963${d zzC+r>idONtCZ-{dM4PGDvzd*ue5?&)=qlC$NUxcgYU{_XG zFV^R*t;gCos$W_(x2UAB?9wPlOK&b+SX46aB0*-Cz@%t35mVZ4Q~I6ingTVi%@7m8 zvuoQC_LL69t{$236fK&46WA6@+6I(iNlBYSz@BzK0WGx^JnIcGZJAw2SBvdFqP$Hi z7tRAECB=rvozSrT02s(%+#R9pXC%`@S(`o8ejhQk)Ch=al(*hUm;5@q9tY7{P*2%1 zTvCoz;R=gS639yVD_pV1a7nfA0VVBqT+$ap=a}t`7vzkOK(Kw>iYv>Y?q~bt8@Spt z{+sfjQa&pq4H2<@M)~}V-%$Q@%Ig``Fkl;@{2WIHY}%McNQvWCTx}Xh7CJOU&t~CB zh2v|alEM*}BS5xn9I12U5t7Q0b&h(nX4iH@dZU9@8nz7WAt23;KM*oOBZu1@Pm{GQ zjzk=Dshn)>pTXJUm`KQEjiTJ?I6~IW(Q1I)>R5%VEnj;Ss$Gunk%4I%%@21vE+w7W z+U*e7;V33|3bma;b~zRhQpAxxj&eeZIr6AuDIp~sdCKu+LdvvW=p1zXh)mDrzV$g) z5of;kW6*xeCKQrC_ovf}E8n(E6Q}3WMC;f!7 zck=A@a67e|XP<#$+7xnRA~it~&}=s8LR2Ab>iIw>{fGq4BY{a55Oq3HbDn^Ow3N$0 z)iQ1YA(tO%=hB3z<$ePtS#pozYR$bFloU2`FC_1Q9IsXu%d13Q%O=fqYlW_Z%UIsS zM9iTur(4%4B8_h?m-N%E8x^q)wzWJV*{p~I8i&}6j+0@kBL>b~wko>`$ z(FOK`PZqiFQGqW5K8-H7(ERfriaqx`%}xz6<0^8(O~oFPs|UW&hYfA_G~7(i zMM8iKD2X9-b@P0y#l*#YNb@TT6oJV(Ic#FoLVQD zmq})xjl9_|bk~76^^a159wAW@Wj!b)t`TKDBCs2$o*AdCheTP;Q&VIMC6@KD(51T= zn^{kuuRVn94XAmxjEAbKwwtKuBZzB-&2@R(sN(BH3pQhps(^uW8=xoii{C(&`U>wk<;sFZvpfPv zbWwZ(nJc;jfqWj)l#U4iQ^hbYl#8YE)Jd{Dnk*?%Cn*#4+lUSBJs@cpEW%YS5coco zsJo|bmjx68r9`?H%6J3SCTX)Xa~#&pshN|s?6fSb9xbz&!*K;j7!Z@0HFL4!GDi&t zY>K4A8JiO#m~{vcEA0YCz^FTg!xp0EL>B?Uy7Bnc>95VB{WHaRIM`3eU)rAp781I=l$l{czk z$;WX-jwW0TWKxmm6lqHecwJEhMWQ1ATU7mZS#}z6rhsEdInW@^RKdXn z#N9_%KG!tr2=MTlM$faEF(K9I(h~e8RL_!eol%7Pi1;V?G&A0ClE3G}GI2#*nGP-wV$xRW1nGPZ{KMr3tH-}sZq;?lQ!>p5Y(LOAWVOU zdM#zSy<2*(lR}YH`wU36J^&#h!3C1pO`JWG+kG|l`Rnb?kDss{v*vNaMD48(9Ug?GIzK+7>d9YUY?{bvJk>yJQ?nDc-5XJC`AP zr*b8+-1VNYk0n^7GD_oA+ZkTWY|{CKc0$DF-U+{3S%WWt^KbVSmFZx3D-?&t!O@EN z0$vbXJWXNlE?zE`#dAhOG~{jwwnSS4;@wiy=eX|6+`$$vMJ?>(E|iII2_IH{c@ZBu z6i(JaPg_`VbFkG{?Aa7<_H@*LrKGH^w0Nm6yeSfFD~=mvjGjBto5Onb#TS>(6Z=uU zur(45_{y7n0bj`90Mrv|Xf7A;CF_MvdSN4fGqw;%=n-E-Bp50TM?#1Z;|JR~66a>a z?nuzh54Ksnue|E8xXBk1Lz>}HfLlEp@OfFY&)?J>5kZdz!v3a!4@dD7c*Ja3O|9W> zYl(^o3cI|QgsJH_`@NB7#(RREpvoVwkU!xdItc89J?%cx_SBT5yWCj4y7EfHU9&pymXkEiLfkBGbq4cvbCi|T~ z;1;!lGQH)yIT%8(fHR^R)D?J+yy4Fv+}v$0LQYWkmmv@nB?&gr!v{VX+^ymP6?3-* z5grlZFf-#I-d#?ZV9}M!_}k2~$F$*&d;XLuQwRXR@9M z4aOHAg{2E<7}D6KI5B8$K_y6M!8}Lh=zUOiUH2zMkqI2k5{>)m<^~P)zqSu_!GAHnFzWK?L788u6VPXKlpR2-VMi< zg_;%I2IKE}k2WPQ1;L${XsOxM&cpWQqn&-NS^ei?c_mheAN#=JWiS%sNMvJ7RWMw(# zIdMG8il;~Fd^nMwhwowZcoNTB*<|xPH=b#w(_4K!`FxPaqmSbx3|g5wwT`z=^r?vi ziCOtmqOmM1J9jJ*6f2`+y2OMf91c%D7)hjJfe(U(WwNJ|+L1QTMCb2B#wpE^bakGu zSeGKBvC%kCd6bsnr;QVTzKMqYPPqZ%!nkyB`LXS|3-s~)e}v2DvkDo1xnXBNkaTtU zBll>mPtrF^dFAIDlCF+`l>B>=u1F8^`czyyp z`JZej4fnZ3Pej3VMoIo8A0d^2K2!P@4}QtZ9ee*;A?+leo z)!jf}f?)~g_6FTeSkil1++M7*!){L$n+*Aakhkd41&bDpFGOFZ`Q4sS$kXA*<|Nd? z8bh8|pW7R4ZN=`y9f!Fg8A%Y0+aAC(_jR=k#ohvoO%tJYA&|1tvuxn5t1T@{Tyujm z&!mW50SuJJ8z76N3&$>KTjBAtRh7#Px3OZWo0gUdK4T5Nbp49TgVsuFg9!BLI5>;#h)n+I^w0KNv_r+~9?LEgn*kxwe)FE8^iPLbj+W2sA=F zp&}Zm5DM~cQRHiuBeU5HBMK9$Vu%V2l}8DlR(}J0qFz;m$g?6$53LyTp!w>fO_1~i znlP70)E{UJs=TMZKICgx7`{FBsXU?-Ke7EU^R%46RFAcYNNOLW;512BfMny-`9NrC zru5Z*M?pPa7L>dz$?PU%D5grkPX^e8Qc#tjT>smoewCC{`$Yw}#OYIA zlJ&QPMlq4g33Fem_Lo@sBqZscN$W-~USI7$72Ie_icFTo75pafc>Ol%h=R&rWk%r& z(!-~CeYGx9u%0$ZaY>b{NDm_uudm)`QcynEQsQIA&tp+Q09S zTV5px5uOyT;9HRdCH!_k3>ociAzfVOK~*HDsu{c z9!HB8U91Z%*{;%4vh;RMGL3j&(S<}yQiYRc3(lhd>Kvg@`@Hy+gfe>VB$-C?{j%aW zsDUMoB+JsPLPSfh=OywHClm0_s> diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp b/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp old mode 100755 new mode 100644 index 4a5e6b0614..b417661a46 --- a/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp +++ b/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp @@ -29,44 +29,39 @@ #include -enum message_validity_t { - MESSAGE_EMPTY, - MESSAGE_INVALID, - MESSAGE_INCOMPLETE, - MESSAGE_VALID_SOF, - MESSAGE_VALID_BLOCK -}; - - -pixy_parser::pixy_parser() { - PIXY_BUF_SIZE = 17; - pixy_buf[PIXY_BUF_SIZE]= {}; - pixy_len = 0; - blob_buffer_write_idx = 0; - bytes_to_sof = 0; - bytes_to_block = 0; +// Constructor - pixy_parser +pixy_parser::pixy_parser(size_t a, uint8_t b[17], size_t c, uint8_t d, size_t e, size_t f) { + pixy_buf_size = a; + pixy_buf[17]= {}; + pixy_len = c; + blob_buffer_write_idx = d; + bytes_to_sof = e; + bytes_to_block = f; } +// Destructor - pixy_parser pixy_parser::~pixy_parser() { } +// Method - empty_pixyBuf void pixy_parser::empty_pixyBuf() { for (size_t i=0; i= readbuf.count) { - return NULL; - } + return NULL; + } return &readbuf.blobs[i]; } -static enum message_validity_t check_pixy_message(size_t pixy_len) { +// Method - check_pixy_message +enum pixy_parser::message_validity_t pixy_parser::check_pixy_message(size_t pixy_len) { // printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); if (pixy_len == 0) { @@ -119,8 +117,8 @@ static enum message_validity_t check_pixy_message(size_t pixy_len) { if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { bytes_to_sof = 16 - pixy_len; if (bytes_to_sof == 0) { - printf("SOF COMPLETE!\n"); - } + printf("SOF COMPLETE!\n"); + } else { printf("Need %u more bytes to complete a SOF\n", (unsigned)bytes_to_sof); } @@ -128,28 +126,28 @@ static enum message_validity_t check_pixy_message(size_t pixy_len) { if (pixy_buf[2] != 0x55 && pixy_buf[3] != 0xAA) { bytes_to_block = 14 - pixy_len; if (bytes_to_block == 0) { - printf("BLOCK COMPLETE!\n"); - } + printf("BLOCK COMPLETE!\n"); + } else { printf("Need %u more bytes to complete a Block\n", (unsigned)bytes_to_sof); } } - if (pixy_len < 14) { // Looks for at least 14 bytes i.e. "sync+blob_data" = 2+12 bytes) + if (pixy_len < 14) { // Looks for at least 14 bytes i.e. "sync+blob_data" = 2+12 bytes) printf("Message Length less than 14.. Message Incomplete!\n"); - return MESSAGE_INCOMPLETE; + return MESSAGE_INCOMPLETE; } - if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { + if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { printf("2 syncs available and size >= 14..\n"); - if (pixy_len >= 16) { + if (pixy_len >= 16) { printf("PixyLen Greater than or equal to 16 with 2 syncs, calculating crc....\n"); /* check crc */ - uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 + uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 for (size_t i = 6; i <= 15; i+=2) { - uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; + uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; crc_calculated += word; } @@ -158,23 +156,23 @@ static enum message_validity_t check_pixy_message(size_t pixy_len) { if (crc_provided != crc_calculated) { printf("CRC Failed Message Invalid!\n"); return MESSAGE_INVALID; - } + } return MESSAGE_VALID_SOF; } else { - return MESSAGE_INCOMPLETE; + return MESSAGE_INCOMPLETE; } } else { printf("Only 1 SYNC available and size < 16, calculating CRC....\n"); - uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 + uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 for (size_t i = 4; i <= 13; i+=2) { - uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; + uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; crc_calculated += word; } uint16_t crc_provided; //Getting true crc by concatinating 4 & 5 message fields(original crc) into a single 16 bit - crc_provided = pixy_buf[2] | (uint16_t)pixy_buf[3]<<8; + crc_provided = pixy_buf[2] | (uint16_t)pixy_buf[3]<<8; printf("Crc calculated: %u Crc provided: %u\n", (unsigned)crc_calculated, (unsigned)crc_provided); if (crc_provided != crc_calculated) { @@ -185,6 +183,7 @@ static enum message_validity_t check_pixy_message(size_t pixy_len) { } } +// Method - recv_byte_pixy void pixy_parser::recv_byte_pixy(uint8_t byte) { // printf("INSIDE recv_byte_pixy:-\n"); // Read 2 bytes @@ -195,18 +194,18 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { printf("The byte inputted is: %u and pixylen is %u\n", byte, (unsigned)pixy_len); pixy_buf[pixy_len++] = byte; // Append byte to buffer - enum message_validity_t validity = check_pixy_message(pixy_len); // Call parser + enum message_validity_t validity = check_pixy_message(pixy_len); // Call parser printf("Validity Check Call: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); printf("Pixy Len: %u\n", (unsigned)pixy_len); - printf("Pixy_buf: "); + printf("Pixy_buf: "); for (size_t i=0; i<17; i++) { printf("%u, ", pixy_buf[i]); - } + } printf("\n"); if (validity == MESSAGE_VALID_SOF) { // pixy_frame_received(pixy_len, pixy_buf); - + if (!(writebuf.count >= 10)) { if (writebuf.count != 0) { swap_buffer(); //swap buffer @@ -238,7 +237,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { if (validity == MESSAGE_VALID_BLOCK) { ///-----------------------------how can I store the block inside a frame?----------------- if (!(writebuf.count >= 10)) { blob1.center_x = pixy_buf[6] | (uint16_t)pixy_buf[7]<<8; //Extract blob information - blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; + blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; blob1.width = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; blob1.height = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); @@ -261,6 +260,6 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { if (writebuf.count < 10 && writebuf.count != 0) { swap_buffer(); //swap buffer - } - } -} \ No newline at end of file + } + } +} diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.h b/libraries/AP_IRLock/pixy_parser/pixy_parser.h index 79ddb1e42a..2b34c34549 100644 --- a/libraries/AP_IRLock/pixy_parser/pixy_parser.h +++ b/libraries/AP_IRLock/pixy_parser/pixy_parser.h @@ -4,21 +4,31 @@ */ #pragma once + #include -#include +#include #include +#include +#include +#include +#include -#define PIXY_BUF_SIZE 17 - - +/* + pixy_buf_size = 17; + pixy_buf[17]= {}; + pixy_len = 0; + blob_buffer_write_idx = 0; + bytes_to_sof = 0; + bytes_to_block = 0; +} +*/ class pixy_parser { public: - pixy_parser(); + pixy_parser(size_t, uint8_t[], size_t, uint8_t, size_t, size_t); ~pixy_parser(); void empty_pixyBuf(void); void print_buffer(void); void swap_buffer(void); - void recv_byte_pixy(uint8_t byte); private: @@ -29,22 +39,30 @@ class pixy_parser { uint16_t height; } pixy_blob; - static struct blob_buffer { //Frame (full of blobs) + struct blob_buffer { //Frame (full of blobs) pixy_blob blobs[10]; size_t count; } blob_buffer[2]; + + enum message_validity_t { + MESSAGE_EMPTY, + MESSAGE_INVALID, + MESSAGE_INCOMPLETE, + MESSAGE_VALID_SOF, + MESSAGE_VALID_BLOCK + }; + bool write_buffer(const pixy_blob& blob1); - const pixy_blob* read_buffer(size_t i); + enum message_validity_t check_pixy_message(size_t pixy_len); - uint8_t pixy_buf[PIXY_BUF_SIZE]; + size_t pixy_buf_size; + uint8_t pixy_buf[17]; size_t pixy_len; uint8_t blob_buffer_write_idx; size_t bytes_to_sof; size_t bytes_to_block; - - }; diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.h.gch b/libraries/AP_IRLock/pixy_parser/pixy_parser.h.gch deleted file mode 100644 index d6ce4239147433410b7ffd6742b89f682f564ca9..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 3053776 zcmeFad0?c=RUg{6*&$|!7%&z~z!!5bYDuHTc+*I&8To1?SuNd}G0R6w-I98y)vf78 zi){=99y|zyK-dC-up|V+P9P8n#KwL&fQ@O-GFZi8bYyWEND}L%1-|*d^{<*bh)a2j! zJB{S|kq$renc{ecgEb#cLzlnLs9h~DKEAl%C}nsOH1e~Y-#fdfdxVq`?wO>K@C^6s zqB?5nOBeoWP<01F1S`(+WzTq*#52us?4?njQ9J4MJHzf#B}earz|Y2CQ8b&oMRR{| zXZu!B%*=ltM&wso=J6C^<-i%rlN9X57Ydjuy4=3Z!Xl8D9 zc6oN?L*exS;(f5Wy`yR@>n zyfnXfV}1#QxrG~x%bmyPmp7PqP5;)~TCv$!D{kCaDb{xG>~1yg&CGpR@Rp*ToD4fB zt#PO5kJ@Kll&?NNyYP_+W6QT(?BCyQpnQ}5sC&}yv}cY^TSLBxMMeE?zOu2iQEY7O ztnM$*B3yluNxX-6qLx@WYtKJ=Z02a@qdsb8i;ePL;*Tuu`bQ%G+ovelyth}M zY81`;+iTLmt9y-Nb$h*N-d)`->NEAH9d_;=2)i&--@yB|)j4|B8{0d3cU(Vh4`{&f1g3#$E#>jQvFGI2r*nbFA7AlDN_n?jhrAn|D@GfKBp*`Vu>{b_E0| z8c)INPGkS}&N_Uh7wE8JKRN97Tf^(3*By6;tseOT#|;}-!yo}Po_zs($@3%!%vh9r z^h>ajvIGpo#FYPBw1(YQ8{Kl;IXmxRunHeqnq7E4f@p??4{d-A;jO+)xgHfB2V3mL z8or4lyZ5_c-R+NAL1nX&DF(Lm{Kw~KmmXv7DPP#w+}_-0KgS^4+1|R(8p>oET_MRd zD~XxVx433tewF)z_bx>5knwtZwds2p+Ng{iN*r^Ek44(r@~5p)(d{4gChgAi!S)}U zDT;_x6hdTbt~|;ckdsj4`DHd`JQmB0&M)8KYu*iiMIoF@SzDQT@*e!+~_>Mu(G(gfym^H zI&rg#nG@H&dxQQ-Id!44zdJ&{EB*=$;{N1nrq05I*2aKLIPc>6#ti&FTq0QRu-`1| z%ZrQkVxGf*or2;^QB3+>q|0hl5rkRd3?yx(Vgd)}0Vf!S0#myuL!q&^d8e_x5B{@u z@7^qhiaMEI7&Rg_#4-ySxc(T~UOW>b0J3wyMo8+{3~V%Y{V^6^1BH$YfyVdT`XXPg z152l0UxuaQlBb|rRGdNAcPzC&&j!(mZoZRTJ^%5di08k@XX=l!Be79rKw(%!!om#5 zTJ;g%+}%M|IUSd5lfzH@V_+>IFE{3=a$l4*;l4~pE90Qa7p&fFY!$nEjg3t<#mnFu zT7m;7>L^dlE-%bsj4jPAEZ?{>i*C9wJG-=SV{RF8>&U6fB;0`zCo;*_ABk zk`6Kd#Qfr1eHN^1zFx;$A?7a5;lCxkcxfILdSh;JmctyJi$g)X6z113o>rb%k$;U9 zjMa}q5RNLHKgXxTPOCj?9e2EZ*X?&jx?7%IOxO>bGhsjTPe6pJuYjM{mzU=jmKGMl zg65VNW^b&_&o6=})mN4w$AID1*`}O9IUt;{sVsAITV_knku4kiWS$mp&w``Nnv%Yh16AK&oFP8Jc z&COf48qNJ;b!+q1HfN>aA0#Iy!-P6QQ&XmAMd|=-cY0i8cKavA(V#yX4<|?C!BC`F z^bfvEGoyTol^Ktjm%_i~W;*k@Wk&sprIn>cG|2qI@*?D&8%wjxb+Fr|g}HgiK@gE4 z2X$V63~k92r#*%O{IGQiW-vsSRG6;Mehglt^~EWWvUK1rvsZq6a=zxjEoN9NfGpN# znNv;ZxvqLJ7gv+v3*BIi*3YP75tB8$j>|=}z{-NmmKqVc-QC{{oMCZcCS?7o#I+^*JMNvqdA?sl|SEY)W@-v4oiD|uo>3eMz z6YNZ#2`i75cVD!6lTI=09CwDD{*f-N7VERjonv`a5J6-smndvB^-~$f&u#N_FAUky zuB@GP{t1+M8Crrx3gUCi%Qse*>+GEMW%OIjFNCMGqnZqE@L}*WJcY-fOVp8Z-6z`s~siXGP67I?Vd!#zqiDeRcZ2u~l-D z)>#`}s$RCV%pKc1#s2NR#_D>L?0^$X<=tN41^Ik_F=1+)rj|I|w0{flk)Kkk^cm6T z))sq$hIR}~)GVSiBAZe6k!w%%xLGtOtJL?!^PubUx;(9LnZd9QiUwL;1nbJnMbpHW z%W747X;}*29TpeTu12Awi(dY!&Jc6lXe^8e5(ukS%T{(8*V*QlSu$-imhQB3RUG#Q zEebF7#o2lKYE;e)t2Z}`ry6_B&7JL;`fOdee2_-imn@qq6UUp=f=76YrS->qHL6(}Xs_VZ4%B2RKVKNl}fp1wdfKX+Bm$zI~Sxw&3!K+m@-0s#9) z+)QRoNo7$fW4M9kQ_{8JoXEnuLU62(i3syv#4=!gi|Omw+H2g}#Oi3TT!eAVXj~_# zde%XPQC79DqjFLz>o3e$v8+*H;F_hUt$d#s{d$?Ryw;p;t%C%7baQ)ab6cdYlELCfV^!vk)Z=c; z7AcBSGA)J5(dhttE^+lSTVVp@Ldi~G)U&-4{#4V(LThIfNnkwg&S2@jRIjrmI+2OH zGjXos*HJzyhi)Xcr_u~lPvYk|6t8CZthH|;DLY40r5g#*BDz~i3 zm~^aQgrZ+G4{mZ>j(b=#hs{1A+B>&2VrWf|l};{Z^eb_f-(r8z-Y#s+YjoiV+?t?9E&)D&AM8LQomvc4yF~@!)>mdGYgIEED5!CjXUfjtixW#8DZ}uSWwgOKi$yV;&CEU}|Ez3r z`~!s6W<%x!JF7?x4a}44>#XdOJ2>@6xs;(EU-=GqTg#VLnRdBs*xg&bb!QceP)z6) zaT@pbw^#3AHCoP2GVaT_l=5z~ajV#9Do4~V7Bj85Im>R~OBts4dbI9jg13<1YA7dK z0ln2tsZRF9O1(a}vb?akfK>og&$CO=fMcr~n@#i3gs;>W>+?|e-T*@>D=gYf^+lPV zV|$kMDf$c3)xm7pwUn`;bhc9APc~yppPOug1m&$TSXWq`^8Kvqg5rT2nYyxESt^%~ zo&zjLqvRzaW2hy{4_f2d4aVggOVEbTEiQ7G13Qem!RUA6Lh-1iirdW(K|Z&*6Gzh{ zw-?7*PDiE8el|OJY)fUi}W)lYvfer1Y$Cx)|5{-Ln zjop1LoY6zdTJvfW->QpIjS9<-)VhnQ9usYCg_WdERqZQ^+NZy1%PoeFN1m(Gn6P;6 zszrTKE1O$uCFcaTjhN?HrhYRK2=)+~cn*Cq73OXS>NGzJ6|Cd~c6O0`o@m#^YX;*WzwJIu+ zMk!>S!-N8wa_Xk_rA##LmT{M)TP-HE5BX7ohAq1T`>4K^CHGr#?4aNr)j2ls;EX1i z!Y9?nNh|D&=A9Nj*mU3DJD^R zPhr-V+c>Dh5P(He?&zc|F+L-=LiQIaY#848_UfOBC6lELDe7F8=hxTCOVn3&f5sHf zbya0qA`5wiwd>Hft7_?8wwt$iutS>c;Xt*^La-(^sInX6NoyH)ilUmNw66J*R(I|C z^tVO8QOc$lRWDy#&d*X>-`{o4(@w@tBxUqd1G_Ybv(`cIPKFEXI4(}vY1l(qSdERc zh?Eciz_6i=D;cw^IK0KTHeao+?HF?umAl5wwZ7V^$DtZuy@&mPS!x`$BeOG>>zznf z__X#hw;oFvyiA(Xhu(p`ZBCkgDlDk-o2hdM>d0ijT6Rk*)}+qtWxKoa2OBC@M#;5I zS43Z>pEjebNWa2?%)l1Vij?ig-PQdy>?Aw|3kYmrmFrWymL;qR<>c6bYmh5gPUCs( z7MEFNU!uU76K#?@6}I*c*C{4VR+m>sK!4i1 zq+BO++R{XB-iL{wvhb<;FcwP36>`Y7_Ssupph%#VE@Hu?KklBvOl3H1U5}ucSzfBo zal$L7Vl&CaJd^2^dPY=Eq)|wPMQpIZ^v_yKvSzfip=NyJzN0cfn@Pn*8Hr`jriWIU zh)rb`l(NSzOu)h6GYdErCYE~QQkTjeF1pHqahOHCyA%dAPfvftk^NE|fNdn3^PQ`6 zir6&OEPI%2HKHf64#V&+GX$Q(j-bQD@swaquuMrp`v_msxjO2cQzm35pmvVjs%)F8 zlwO(Rgaf<-${!WY&BTPv`*xb2V-~a;TrZAW1chS>G>aIz!r8;rg|+>Sge`LBs<1^y zPNttVEHw_e7A93|R9F*=zr(RS&!rz*r&N)RVaO&BF7hOaUqp; z**ko%^?cYr528Ka-Azg#b5wpL6LPXveg`(=z*SfjSA%XpJ)YTL247{5stJoN%HIJK zEIC!6lO<{c%LU~UQ8%Wt9o@Jbu#QnWd&L{2z~$F|rYBSyve|e=vDVz5xlytq&wSBO zLm}0GnzN&J1Hbf$laGh>EJCtvW$6ya_;=}@yr9Z@b`y>7spuC@`!6gxs%JCS#ImU@ z1_!GMaoXYUTHi1C(3h*yCi;%SGY@=PR&YI_}~iNo+;W9eK8a z_Iy+%2U|K_&M#7OU^bJb(w1GZG8wHwX^-ldEGJh4FfUojs5a4`rVpNMo>Z`pwyQYb zY5mJ0ArX2)>vMxFEb+h;issJ2-Wpg1*^I_!)6krtIBK0^wJlaFY?w;#gb@afKxV2w z-ZW(X|NUzui+>;28p8^wd-M<-x;w6Y-1uw;M}x3qaaMbxn8jb6f8r3=9N|2F7Wi|6 zKa2cX;?FXFR`A1MbBr~|SaSjyYmTwz7>kI2ZYIF^jJ{HP;R|ao>h@uw({0ZT&T-NL zdnYfct=3l0&wE`}w2x}#>auq8U;|yRR?024wc6SXUQj~^+A8)NH~|Hxw*)F~HTIh| zoLQY8>+SVQ)o9OHNbd(SFb5dT}*xRXXY;FPI zhdNI7l$tC@aWH2a=5wwO;|$)$&TeB{{RhJu_IYZu4^qsblD(^5L%Y{*Z`NqNxk#IW z;^qdnt8EqBdp+y6>EbXH z*ZAzb-#V*pbq|L)*HXK4vsgP2bzSXFZK(1bwLfX{7~ncJqTpn(bNc{^++_#w&*uK>{z0>LcXJ~Ou({!bY@&zV+FspaaJct(c6Y_Oy}e(% zyS;OJb^8{dcUL!ogEt+BSGx-%hCAXo*xuh;T|-pX&Cc3taT~7f<|gY)9Xjeg*k51W zyA^rvugfkuy!YAX9FM5UURuEcAZNgkD4R=9sI&HZs&c>JJ2Q+Oz>B}m$V%mqq`GQXx?w$SzX)PX$FeC2E)rxQh!ih@XhriO!BDoo4|Vq*rwP|fo@)`J0gdC2;qPUA>3Ni zdukQMZ0;-Yi|iCdk)u{aOQ374u{g}@TDSL*s&D5SowqLg-hJIaf^&eAVVx^F`fVu8 z2JlA8s|OhPz9X#ooh>-`uz#655~z z8YX7Mb1uACor}&fKNlR{53ElEVLe`x!;73v#jLnM4ROOeG>3txdwOei$8P80YF2&9 zY8Gy~yIbHChdXV;_vof`y)NXnm2fmR=S9&bN0%Nv#RKW*d?Z_?2P|bcFF1WtbfO532-h-Ph|OS1C5K+c&SF`Gg(h4kU@~dFx!jnZzAQ$t z9Q!*GaaK`LI^?;iXjGN(FW2X^b<1GY9#E|99&p^EOi^WFd9fZh4f7N6YM=Ug4FP^AT2&k~sr zX5VE&DRM&`h=z5s0a@mLv3?&Vg^~s$!zSi%&nINraLd^`$5foVUR~R1Ze(atkCOA* z!sBqZOJ;f-z6m3M46Tv|I@J9;C@0o(FlFE0d@3rGzGZ)Pd#;iciIucK%mu85LtWfF zfD-Vj%_d|4NR{_(R`+R>fn7q%N5*fhvAJbmLz;b!H+m~MEh-(=o2gxpZdZ~7t(s)h zl2~mJMC?n}w>H*9GV!BGUfsC4x_+mb^a5lECkVFJU{Q~mISsvbdvmKo++5$gV*~1y z0X7fNc8I)dQr+HxVd#^UBzBs+5yRB%ZtpZB9vEnlek*D2qxbBfAFbl3PsX=-uxqId zjit=p3jHoP?>Z!H>#++Vw?f<7*^fB6W^o_KTx~$opgOdjsj+`=|7O#6zsB9212PXB z0k!G)4Sfm~kQ~r(lpz)%prmbg54!m64H0vV$FA*Zn5=ED+5m^Q!APrwTif2pF(LEv zjmGvkXVV2wO%D4Xq9lgYg?G~ZBF-4O_k^* z+W1(1Z|<`0O$xFuPh08s{oNhgBZOvOBt-k7P0UVDnU`QW!0m=S70ZWo3c%n;1YKO% zMg(iDa8se#ya}-R8SLu$4@y40YQ&_Ut9os9EXtSVHn~Tga0;w|Hla`5EA-!U6 zzw%ztD&e45;mOttzl6*!H&xg^#r0E0j!+RjlgeIWZx7;Y^}Wu+PSGlVCd&qyER~*n z!9G-&DZ512{hf+L0_wpU_X0!^T9;kNYQ%dRxXY)KTNOPaf!@UB9f%K68CJDWmvFkq z=EUwUbObiB`#8tDvzFl@Q1=v@ySVcp69a0)RZ$EjV}>!HpAgkbHd=GNI^{7^vyo4X z1No_qOf@qO{PHik&rVvE75E~lh+Kj4vj(FasCF$aDD=!Y?qn(^Bd~*185^Y8rUR`) zf>kaKjoQraZ`t8{AU7-7a0lB^X{}eHA7pFbsg1i$h|RW#KGn>VvsBgS*lgUzvbfUo z?*^4wQmc3Opy0I}E4zLZqOCAYchxywh}Dp&@5(9+O4`gaOsKYEgjh*6x0EV!YpL9# ziL^>r5n}Z{I~Bvsv^ztav#T~U$9~!v&wwyRiJ$F@}EjBVU zt`MuKW+y^kE0(DQp;nT}iK<0bR#j>xft)-ErhpDushg}siLh0XQi+)aGD0P;w8#}V zD(qI5-!(VISHxAiAY68<{_=}mMKz?tQ9MQjH6bvk7mK>s-&G` z7ob%~A&I%zRa!=#DViC9h6=1IUsP&EB!FVD!kS5|W|YKAra-LFpr~7QcLRWz$=2#7 zH(pB#MJ_rjv8>L(j-U;Xh}&yh2kVVu8;ZOFf`Z%63yHWxvlYFc7y&rTBeyFU;=s=M z7I(^I2d8{hso*qf-qIu0Pp0&YZgP7^j}t`iaFk**>OnqO0g)$K>ICvD4pyUTgIQ1m zdoh>qGV8kZwt-VGn&3P{t zyiCMXRWPm6_gDAw5e{OFgHI*2Ql&{L5N>TXqN?ze?3Tms-j3|VhXi+)URPP&kt1wOr zf%09r0u-HLd-Ij6+=77u75mcL&0=)}J1l>9u$v9+@kLc(I+j3o^wpb*n7@B-yJ)U% z#1S2ZeXe{hH{f)edmo8xHzHLcz1FxHC!(eqf#SKck|rcucDEa`#?OTV6Ol`9GvU<( zM<}8Vs}M_eS+iblQ=polXzsF6f}ZH@`}$qVY^c(3YAs*TGQiXvrh6Q|tRnbl-^q@R zb?sEYNK5AvLzHA&%G1q$p^&Mf#e5B(g-#mjuS-wdCWB4Fn8S!)WtUVpKe?U6oyfFl zyrq~}-dL~dt`}dh4lY|wXk+a*go`u8zbk zu?;4*7BLmlQTdfrwl++l(C%p-AjClkX*43$J(Jvy7j#0XOiZLY!;WI_t~8P<9}RSN z?o|5)n+rxa(W;DT;dV%Dblu-<#G;0JXsMx=+}UgL&RD}An&6Qs+%CUfd0`EMEf z9`422TW2MLrrU_pf$va@DN2KNw|jv-U0PLfyMj$XYbuB;bU`+9W;w9U;m+8dJF9GJ z2lk+SEFo&;=GK!=-3t8+{}+>va$+rx&j%xDzsF32Zgt^$j{b!@FIsX#QLWgVNB)Cd z(&o;_P1MZh&Xzv5^?_-IvkgkP3CRLNpLarothCK-++U#1?VUAr9d5}oFr}K^E$s9w z)Qb+(4Q=kgfB?x^;l!b|A259lvfaSo)9w@zcgmdma69|D zl^G`{Y8tE)l6+tc;%Yh6mxOeR$g+dsEw`zR#}oVuwj7jL1r#?SPjWAj$afH5y&$ms zKH06thI9@HTQI*0RBV2_O1ZOoi*p8&5*L1(*zW^`#4DGOc_4Zo@Jx6?@hDGrOzJAN zYhf%wXDJ?go40POtGTvGv#<^K4p{Bpy@^}XBou+%)D$6oLG#JY-Mh|7p-=+sZ=waz zlQ;ng;b0r(*=W#Kk-38IY=c2wesE`ZpIfk+0Lc5k+|Z>q_SXFSr2&GMTt_RLolFb- z7Fu2=8#>xy>*(PG*OTL{w7l5eaX>4Fb$GjSjB_lc+!{SzrtaV&*RSESc1@j`;l>7#>0+g2>0&|Y2YTI z=rrDV8LmESos2XHV}=Zr{EV?3L!)!p;kj|Ck{0fO)u<$1R;c6Qb(*H;u6)O3x2?rJ zrmHw>T_1LM#W+SauKd7F=aTwKXM7YKX%XOc8T>AfQqRDAk?jYQvvcxcID4%T?v24m z2{d))(EEtf+t5qkv)1roN2{>kp+E`=5aGu@+*~y3k|)l1o88+z44lNz?;w zw7I%b$yzAh$>Q=kirt|ubw<%x<964@qN{*ew025_!L%Y_CZX8nU;NP;&WMgN%v{D#@Zb(5#8nUGPKAg4n0RjSLn;GNGpl#qq)Ncl(+IET)C0L zl?b+a{mB_)wR-2L%tG@}hHdk(*XpyoG>`h@VUG^EwTOI#^T6M#?!y zI32J_Jz^(qPR?PePsf#uzXi)>n6zy*&Db~ zHL!gc+F*tV^2m0hhSelyZJ4UUoDj0;_FyR257dM+a!uprj2d)++$e>Cm$T1R9FV`5 z2LZhk;za4@83Hjm$Bcv70utSR&D#r?e$6$A2WS-7c+-A%n^%end?gUcv>x`)K%l(g z64ww;J%c$T#f*W?Da;3WmeVlGDc0fi^>*RjB~e%ns2!~j%p2U8gWje=Nf|_^j%YrG zJN|ryaD!?M60K~J=}y`f?9L<^?vbe-G!rF??Y9kqGcR=zB!|5)0@}z+a`87;YF>A! zdIcvjtF?a_T~_QE0qw4GGr@k83%KMd8jh=d--eMBbpo?!u}ILT5ZtmA_rQrRqE;OA zF*w`BUS~8pL)Uh&`C#h-XeYSAll?rV9`re#Dm|EfI|p9jU8;LS<9dQrLs*VD2O@Y^ z**!`MZA6iTAw-eTG7XAgD;GmdvXNDw{(oe2y}a$DZg@ir6_nG_tDkWe7k$m zxPsaCE1To_*5RlfT&NdE1K)G5li&gyaWt@3=W?ka#U8wI+NXdX?~bYpy=zX0*t>;< zgwv2fYPidaz;FV>+Cj+SY6()&pR|X$8rC3NPr~>L#aB;;6H0L@za-we}n{w4q;N|1eTEL0#D-(juVS@_2mv5k}CFbq8y{WhBNqELU-V~B>9b-MvklzlCBLxSt$b{>*&T&hggYnP-h zsj1t>fxPVDV0N`k==q2&se|j|^8jwyhALZy^*$C#y4O;0)21O`AyI{fCdtd>pu#QV zL#ejcc!f`zYm(SqhT~$zp1pI~l!Z+7pj+No^g!fN$!p5kI{vLcCpgeT&1eC5y*|%Z z`Wsl8Bxz-thyo**ut;fd6-HfBGQ{Ommc?s3TL*WxJz9r}1hxiotdN~e6nh%1;=xfb z2^b&pjtpHGNtQk(Az?9@2+D87!{*WBkfIVojs%t&aWD;CzE-^L+jx^lv{&cLDq**= ztk>}ZHtv0HHDGK^^L*G}%K)N>a;V$5I+IA5(IyU5;uA8_$l2W5#bJL2LEnu>I3UIs zcqNpU{N#XmYOr$Laj5x87E`JhNxAEV=5>-OsQ1e#a%{x!KI#V|u>Qx{OZT-10UW#% zP?4}qL)xZxH40P>Q@9|FRaO)(df9;bjaJ_fq~jByz|_Bsr5ndI1Mpfzw^NG#DfJW6 zWD41lJJG1r(eM&rcU6i4{Wwp;xha!9-yaTzi3_MOTx@s7 zo-5)UTHIoQNY%HP^F$1#yH{XR!N59?PpM`8_zp9`-;?@SgT548H0EM?30X-G+F~E2t}oA zJh#D8p-Gn=zT(ME>Re3-@?2<^sE!UkPRZ{QB~#pkPSkp{(~GXKaOZ5x5KWkDb8huz z5DX~+=XFWc?+UQWUZLYrx;KU_DBdYuI>y@k!5dKeK}-m7upt}wh&|w_OAykVsjH9c z6is(|96Xxf2A;~WD)X^#K#}W<#bG4L82ZiCy}eDGo_PD-xtI{vP)qq#>6eQm9b{T0 zw}rqGrFqvjo))d#=5dQSmjG&!qX9>d<-t)JRTQC0GOoH{oq#MmAOkD#0*IFsLhtg5 zabY9n4vwbHTR7ZyL`jg~&1K$oNr8tHg3wAf$O<_MmQvOLB*kVChYf zGm}Tz)u@Q0%~)#?6wOF)U!?-ESsmYY+eZcoz=nAcRs~UVR}!f*7@}}wwuwTRVEPuUaqL%g%pU5E+}_X zz)8&l)-SvqgNV6Z;{_lDyvxFYqQLgBh-y+Ry5KIiB#NRqJCx0fVw_NMPyVO_t#?eM z8a!z9ic`FbH(V8})GM*m>j?qc>!NkoEyk@Ac|Y!nIf0(3kSF#($hXCP*6EMEn;TF{ z#SWB)z&?q-N8u&zr^CB(5o$+*Mpz@9wU1k8xY5E@bRAv7&G- zPC^pJK$XZLS)p=hR)`BZBFCK%*^@ev-6-y{MLy7%+H84JlC6>$XDd+SYz1PRtw4;j z#XU`F0Id(%nHzR^;oK>2kS=p+ed3%|{h|z3JfnP8{G#ku{Nh}512M{GAzfIDP|doh z#91zBQC0&n%3`2JSqro%OMw<;1^ctDF1Fp|_P(+zrLox?Go(0=AsjD>3LUAWM!77B zQ8r6rlut+GmbUMjfs}bU`b_5KpjKZFV)f-9R$kt3Ro_lp_4P`v6kf=c3<$N71EE&3 zz+LmS_}DzBWaUPyRtag9mxEY&HE5L=gI0O%XmV)Z0aEqFLae-*)XJ+#th}4V%FC~+ zg$Akmav@e;PHN@lBvxKdV)XLvNH)jCu%IkFF2RXq}bn@<5DU9ca;u11)+jzpsO- z@|YiLEXzK^t#B5`*%1Gv^D8CFfD)p&Ds5ntsZt^lhHtmGa3=2<|?UCMoVIp(UPbc#m7|-C$w7uA98Ld zz<4B|%ZVhf5DZ2~iC7doYzLO<)A z9f2Wa$Y%o>4rb`*Q^K>WYarUjF@p(U&8%ze6%c`#hIa5}I?oSDx zP2HO-R?@$ilKYFP<-Hi?qsZmKW%IQT@lnU9* z9D_6oFMb#aXXgW_Neb~!PGBYmfkmx{@d|1_^8*c4)Xcytyw`{5C$mMF(Elj=0=GAR_Dgky?M!JdLIepB1$ zYy2o31cY%Zh~qqgBPOFka2mmk2MLiBTq%`QQv!QZl1e z0=te4VY0~}l~hv#+AvAPbOP{0G_nn0USs=#L`q(Bn6RxQz@#j|NpRCdfJt!MK*W^* zHo*jUx)vt!;hp+l#r^mQAN5FsU!8a3DuREv62K;yV9FhC2JR0afW)a;zoI`#r&pjT zcHU1W@o7nyo>S9yLGp>qoIEY@(sOF!E=WFciWAe)4t`UU)(|G;?pcfb3}Gx1C+$T- z(mq`Fb&qu)B97S`BnbiHPX8!nAtXr)B~5#fz8oP^|KW(b!I0Y?Fftemi$|nYBBgz} z_o^h3S5=aDRhq!7(&&T!gE&55QY_#kIzC7Pu7K5D66yS!N~a7dO-q9vtD#>gHzp6p zK2GKbPAQI>REQ@hQ%49amu8nW>H?<)&~zUqnT=%%%al?fs=|`sou;48O6Q5>bOe}G z32+kod^kv&gE)-S=F5Kt^M5nAuKeDF8kiSJb> zS;%*Y5F4te(ag6V5EgITnJgL?x!xsI;`WLQAqMlq3heL9*t?T7HlWO(7&P&SJK5eAY@{0JVLb z{Zw8-;42gQDh-}2evZ%5wGVL`d=N{_*hFZjsSnyo@WC+FeI1{RRv+SBoMF|+R4LKn z+c1ufd1N;UnjYaz0w(?JeT&4& zyayJWotR1LXa-g66g~4UsWAf$)MRN;QnO*v-7KSlRbqG4o<`4SWYj*%CO>NDGXwgR z@YxKh3M13LPT`Sh;frzm(Of2m(yOg?f$lliu2zQ76RoJ$sM53Pbo1{$2R$2pH08ac zDd~V-od_;4T;?(pgrirdLtNX#7`Yt5C?L~o5gzn>_{D{3G3b+xGnx_u^la%!&z53p z!_gyKQ{XuHDyK(2#WeG^HqDVA-W7hwMGxI7m>-M^Qo{R zEH$gClUT_&h}G^vVl`y8@~|q+ya~i={BA$}O;Y37vc6qjX&+{SJXM^#o$IB$G^!I|DHnGLz<{ zS50#;tdEUS9u8eC>&lF6(F5`V2DX^zci82}GqmZ7B(r#y70pgUv6-g6! zXtj;f$>kGl!gd=5&b1=x$re^fVl*uyRVFEkTu#aNB%eIUQzK+rtKCLDPKl5Wo)4Vt z-nydp^OcANZ?zIZ%w__1snx(2Cz%EYF`L50Nv0Se<^szywwkt*r$(rDAc>GIz4%l! zq~s}YI2mWN1oG4f*({xmr)BA6oXrx*xi_4lYhPC1pyYgnt4!bKBr_%bD>)dFOw#8F zKFJmsGf*ydQnQ)q_H(I|nhh?qNVNgLr7`Q|qfC0IlWK*6F@v0a2YmA3rv>k2gZHKd zpJezJvIBB1J5{L+yQ8^)qgMN{nh~L9gP%^0tKDV*#NyV z&!3M-ofiDjG@t5pfON8zN_zIKQ`62CGuy&Q`!bvMWj^0SIc$^;uMvpZ;)9+^o75@6 zGx;92^7#fmoA$JP=URCx%m-pVZyu%}xA`XsKq(sm%L16=5UCV%2T?j!Jd=~F-icmXjk4Jf8YyzP{aYb=Q zuA9#7KJk`f?^|764hOx{%1{TfI)mVr>s-iTCZshN(p-|7sSza?{Yt$K=~Jz((cxjP zm_n|WZ&Q&k}5LROdlWV4l!6KeCTx_lv5RryM;Xy%1nRpcuVg`e6?ElLeJ=E9KF&47o8*AH8CzO>WkF@96aX|Lk}6o zkza*xlzvrZdGK4Pa*@(6F-S_^xA1n-T+XLSE1cpYqq*k`)pJU2)N?ssHPj*%qvLKx zEzM+U5q&WwRq@N@RqQ@IkFMGeB;HjPhv}!SU7g5+#IgB=1V~u7 z9VKZ{28wM{7{-!^0#m28Ya-Rl>0^x8Q&bB3@2SN$0^JtP7J#~$lwO}+vVsI}+ z+dmo6^iUzCU4^8i{zyox&l)j|NT}wM)Lg;rA=mB*7iPq5NLWwp0~WV_pCwRc@syVqs4 ze_d94(`B`W^}`xTPA{v4ysVb;(w;f)jxPO2DxyMGNDpSCmpw?#p&ul+&=2Zyz{F1Z zL1Lu*Anqd%l4gF8v~e%xMjTQp;8 ztCS>?SVBhi(Gx;q8L6b?-5DE84OLA$wX*Els;bmXwQ8z$qveQmohfUkusy@>dqPM` zCX}QUJQwyi6fE9Vi47V=jF~V&jkSiH$#S zEU*xo3?(PO;BUOsclS>oB!_Y8m|QNAJ+xZRo1diZ8Z zB_K}2B`21!<&ZlvACr@_bC|87G&$v^8XZ!SNsxqO3Iri8Bw-~9Qet^g0>v^W3HCKc z#$=Gni&GgBLE`!ajAcx~cwsrU1!Vkv^{8 zIJ{0p)<8?j;sYkBaoLMYlH&FTsdb#nfqhR)6LbM>g5v>>eZ>L^qbt$IS89^LfZvwG zU12AKaeQ`baQFbnk3`mwGK(*XVYnriJK##j?l>NjN-$?)lo-F*Q4-SN{0MA49%1K> zWRr8`T3TFeg+9bLUP-$ETj6)^wC9f#ZRSklC{=aym4*3jwDTTU}lUluF{!5qlMi{a4BXRO3v+%4;j+MC)yTsZ1 zQ%KLw65=t%2iLH42AN%+og~&F4f9pnOAM45&M-q^4cvErjn=g!{jt4 z-ZxAa7NAs023nl%l=hCui7-C89$jRX1fHBO3Ov;;3q08_4AOfF%ryn(mIA`KXA{Rg z8#sYhi7;0EKvWY-Ng|zce>QUhd^~6wMd)~7)l1`nRT4qCtOly6lAr{Rnf7>y@1n-J zBu)xWLY(W#lqr?;>_8Qdyw4QwHJQe}#3P>+zG#UH`HWV4q94Yj_B$%0qw*foWPo8~ zl$V{k>CN9gsbg(2g>jLd&(KuHg#~ZA1W`i4t)(cJ5w%FieRahQN;)z?FoOaVJ0AQc zd+|&Cmw^MuCvwyT$&u=E;Q{P$G7Qf zjF?j1uj{|CevI{IxB*!r#MfLNVVNqQ^v0{r7rm9DpPeq<(WSdb`b~E3Zpq{j@Bo+X z$rl=M@76%h^h92`JbQqTTywD=QMIXjf&&hXlQEAQM`5t7n5DbsEhA6*qtouOw1^|R zkGqG|Dj6GajQV$B5k1B?F(L|?iX0?_mBS%E%po0YfD`;8bn^2G;VNSR{wiYvSsbdP zz}G4Ia)+_Q5z;eJq{F3+J?OW)8Zu>@w}j6N53}c7yU3= z!ew9j;e_y^B7Ye$J<&t^BV3t^H$h{8RsCQ{8RBTno0*T~>Siv7oQpTm2gIvw&kl>D z$q*l;r@}`AmGfGHlc?oP=flWw@L`amY?4#zIJ$x|5f>(5NsX-mC{VQiL6vK&FS^6A zZtUSx!FBQ!K3C+EK5*d^Ef+$(J}GeP6S;s?19+?IhmI;9S2D4%k=x{DZANbg_TpU8 zNYJmTgK#)uzi#8!99Ek;&)IJ6POpO-jZX^SGeGE`;l>h{4{m;q9nb!NSEfWahm#3# ze92?n5_JczD;0PlJqalJl1;lSNp`Wq8_T`gT*=_bUi*mM0}d!_$K3^Wk34bg9arj* zw(lU1Bkg|`m)uQ+L@+_&;%RYA&dPhfD}<6U$yk&wtgh~H(dT`nSdKClZo?k30_h%| z!w{bi`Rd29+}aJdt6S$PBGTsFc5AgcU&lZO9#xD}K+J`-rrRb+aODm*5IpUJf39PnA#89i?7>U+jjHzjtG)U|ZpxnX*`Mgh33^QV) z+&Mp-@G}C)Q|coNVUqA&gbRM+DoMc;t0|N|l@vtMiQhKqcOOkUg;VPf`6-AIJ1V<6 z`w?I7rYB+JQC4w9__1nuyo&7aIQGP{y;JXpY%n2Cp<%qivWteyluSfNfhgxFF#=*&H)8Zd>`VNvQKv)EROXFr!1~L9Up{x7y{{COX@Yk zm)RhdLaJdbAb;t#Liyf=Y`DNrF0)cPc0y&>1=LP|!nqhOFh&su;p}n7c5FyJ&*dU5 zc;TMyYe-J#r(KFiAdKWfD#0TRPe65Qu_F54(%bhi6g19`O0T zqk&sI$Wl|t;hQl|py9BT?L99dl>|9S6+zYnpcXWIa*@RN6A1t`JaBja1IZ=ESP*MK ztrd`=sPSRA?xim#S@#guMl3~AN7OVVuqtDMLI&rYN-5PwpGz2A_9Y)U;Z9)&4+`XX%Bz|4WKbwvd9L#%}`l{r4-0|xrYco0g{`jBV%y4F>a z<`9}{Xp>slPDnyZQjWs@gHEN$e`M_&bACnjZKu-@sCS2_x+ z*>k#~Ay)LR`_rlUhsr`7m*o4cB^B3qR%y`7Pkz|1Zicmyj04cJwQ zCFyFT3bE`m5YPO#7|C1!9gBAYH6K{Ix|J}IdyjkpMBeQ_n5(hLpkv9C3{QMsrA2jL z-_nS$>Yz{1H~nx8X8wnmFQjVxDnI?A3xpt_o=dP?qJrzlU9a*~jlMW_2BLE!bsT^D zCjH_KTCn_Z4MF(24M0cu1RUYxYH;g%3XbTDH-e&=*#3g@i8?>1USJZZHztn8pdX!j zC4j(V$o$yYV8zh)*m}1+u{Rc%_=KDfd@>dpRU-C|PBG_s9~hKG;lLvX52a=J3bYz5 z9YxP7G11P-^nK*fXw0ctJ>4s?_1|^#`Up&)Tm)h(LzO6Ehog(3venTw*8SX3g47$n z{#PZ+_y2NaD&#YCviS^|{60fo4rFAanvs|oWh5n+8A<46MiO$Fk%SyFayS_Dw1431 zddv|&yXJG5^(-?s#XDp$?;kRn_YN7(dxwmR9hKx5jp{R;5X+1ja>!sx4;f3zAwwxS zmk|-drP-sfs8fmrIdU!|2%gIb$hnMwoXH5xEi+X@YA!2E&*VisGMN#2CO1OQWJe@s zQ-16oWom`gOh!P?WCPSpCP2+(0ehs?HsDTcCKE!=Ucwko~N0COxH=-yiv(3H(xvMw=Q5#2*g-WU)?g`Jmv&0d zC91CR;Be5UT5JrVQk2_nm)H50TD53D*{wSmtK4M9UM@bM%@tcr1fOhO$-*Nnq01!< zNusV*hb)LDkf~*FT^&&YxDUZPmFKq9*93Ynu{oHOYfF5)=TyHAIf=JL`4L*`WF~IS zFV8r2Bo4i|CQJ8X(Z$Z~Snc&EN|D#Y3C*|hbh>bc!(!2Ry5%E1%NJ17Ch5@t+-HvN z9!^Z4_n>Z=UHuF*S6!uSo`ARv{#(u$2!Tx+eqq`fDn-Z{D1qX>L+G}1r24&kEZQ6N zAV~?|!SPQDwih_YfR9?ymF`MjU}O2P3w8RnCN@A%SM!_;=Tv&4)(93!PCsbA0eUfp zwoG&jS|b-@d`$~_0KA>;$xSg|OIXkQk5!Y*4Hy@~Z9TgkG|7Z0C!oh;2-oGDR?m5# zQrx*bb)SWoJy15oWu&sYbeoK##!#(=nm2Hr>Rj06fJQ|ywDjEl@ECdklJSr&%S+!y zFXcF<>k^j}mVxoFz|gUW&ke-DNd4epb!QBIC2oy2|3PL=Dj3>zcY^ywpMJ11AxEzs`r%-tS5eV+H*6^XI zx2VYml%nt#A^1QL)e%FDiWPm0ic+dw#f@V*H7Ff;^ zssqVuH^DCrW%*DVeuSRyaelX`yt}gFtt{#wYbo$>34s5dbyQ+<5#|A zssn?+r|`z_u|5z@x~?7^!{$c|(fJ`<{|q0*6)Gkq%;5uE5JCw_oOru@510GVdRASJ zr$Yd#Q3$~}ZuPHcgk^*0B6-~|VEEF_3H6~-~!3)yv6^P=vh6C3N=m%%{ zi{O+J`6KoSbchH>2L({tY>8DaHgKo~)-R`4DBNGeR%J?$DYCbjMlMMvw)2RiyDz%( zOSb+UCCNm09&vQ)L^_#F9jQQTqg_Lw?Q`zv$t-q+cE2 z>)ufwcJv0t@)QXgF7z##?A!y%y19=}MSKS=K59p@C9BtUKzcxJhzTvW{`+b>tLk+p zJgV>5i;~K+#fDaVU}iPb9>A0z>8fGv45S2{qVWiFc5rinU_wWgGQg4rmYmdp^XGy5 zAnWoOSNy_6Q+~l1y%W6;H8jA=pbx27x7@v5i!+AHg{%o|N*@JkzAWErbZ{xQM; z|4V;uyZOD1b#r@Rx#pfK@pv!<8CC@PQB(btX&YUweT_lHSLsu`B)-czuJH#~pkOQV z7(W+ zjL(VjL;VMTN>&Tmg!QYBh^+gLIJArH$C!+~yRT~EiMQbgzt~$m(%&d7h!pnei6_es zm*VKex?8I0BZ^IXIdp5cg42hb4R%geER7O7yl+EYD4S4_Az{$?J$lH5iCIWp0nU_yo$}dW(pR+t3b~&iMy|<{DJYY7}q7JLb4$8^jfqO7L zc0zUreF_CF<1NG^`*3Fnj%zpAvG|K*CsF1#prS8 zF7@GYPszN9=>)61BXU`FUBRx;xt#+8QF=Om$|@wHc<7#qhnjQ4hY}ASV!_9!GtGk& z0s($U@-sPvtrA^eF!}(y0lciKJ@^S$6s?{v{a`9xqq#I^iQrIEJWoDrJ?wBI30Q35 zR2_#Bx$e^oCdeRWM6p1Z+JFQX`heOsyGL7}8e5H=#gG|f zs>vz%;ZK$Xc*=?ZPZ=0^Qu&Gp#|$6CW10}*)9=oj)<2>8b~d&CsT8rSE$wQ%?!H6! zlrSpc!h*Js^WRF5C91QdMS9+z)?aeyo)VTEO>|GfR@H@8R0o<-94-j+s3(ZsQ&OP5 zO4L;@1z=u>q$Ei}R9S+Vf`}vjDJkfkckrPcDipo)t~>I^w%w7QaCA=z_51U*v`W`H_of+=EnJRMV@S)o{w@l(j9VZSV^Y2JX#22n(Kby9?aF`atrw)ML1> zYiAHR5e3$>1KK>E9r9VD0s@y%@PVr*R2{(wwFP`~+0Q3sN7yTmTDZuX0uKK8+J|lK z7~+X_M(n^~_B6c8`BJ7kd*}nov!pPXkTjI0Mtw8{C$fH#pZIeuPSl92PWME0;$k
IqLUv)bHh}-^)?Im!p0!NBu5EyTRm)GC4z~+@LE-VPq?o4(kbC`IDCVnxSaW~~-8U9RoRKQXuyOWtrc%li< z=Hv94oDLKIIDAQ|Y*r{i$D`zspqXEz%_Ko?_-XS*X$AGbnCz2DkMWsRHOpwf8f|u9 z2cj9j(RFJAM(T{SL#$>!^(W{Q()B~+_?R3YljCDX!gSr%)t1$Zdo}+-ve_^|tmX&| zDWIXm8!o9`!m^2&$kDJ&|L8u0jt=e9F!$?n{K4dUUQP`I8>$=wIaYI*6KW@d@Dcc1 zh5*apzD(WWp)w*f7tC-)z#&FTD=UdIGePqnW=5kjA`=#s5!%TRt{}b4a8ycyB+Cp( zWh6pd1A`>XOh;Xf#7EOYW=5p0M%)7>vJV88HO*`Dj0T-=^aq2{p!83eWM3n5f0<++ z>l?zIPAkb~nCQ^3oU~-0@(5iaQ6^U#L;i#Moo3ui_jA*ar1e;JJcrMoIWM$-(hQJ= z<&Z;E9;x4kWPd}7u#&cOa0NCr?sBIIp($P z@dao*kyE*>EJ(#O`z%>sN9`8xds`;kLwVn)=}%HWyRy_gckvcY1k z)k;&TC_bH6n#qyVZz2AW(NzC>NF85NpTPA0gSEA$KgR2BIb0=e+u@8}A!Qd(+G zfO$?&?%|rs2tV;dbDvn>VFq8Mr|0$bKarl(8=7^t@*JOCOlN`=^!&-}pfxn*l#!K$ zX1z2}W*-JUA<_L9)LxtOOxL2BsHnnxX%O?JbbB--$#Rq*+aBq9Dhbi{S-LI*bmm2o%n3w9 zG)rhE+Enk3UuC&Z({p!c;t)P)TyN$LH64Ab-^+S9+Vq&hlJcWjA%+k1jXUb2QJ*DNc>YhlY-yn{!g;xjD6iwPy6@j?Hlv z6%-dOD46EV56&}(#=jI^bseeNNA&}do~E0Ss@M5`eIDa}Zm#~6nnQhVJ{Z+Mre7R= zox!l(Wu24mztH@vopR8is(b(_{>(?H%f>5S6@wcA}S#*TQ&1arai(Oq}y+@TuQTf zRWvnNO1tQ5iJHDX&)4!PH7pHVYWZ(<4^NVLdzJNk`(_uIAS!El^Y58Dgb%$A^!%z` z(^0B>U4>i-H0?<{-0Pe&c`XN>H+i5!&o9k=Uh7xqgkk1A0L5uSZC^Eg&9A1Ta`7Ef z9&PS4ebY|TOotB>d4_at@OmS@M5y1#(@2I!#>5w8&vZEH^qYyN^03St`!I1t?XBr} z3Td4ZCU|7sQmDUOM*o!8FY&m^N27^4x*7N|jxwZ#HNRS}?@L|xG!S*&qsFUt^ZDqF z2h?vwQb_ ze|q0jcU>>0=R0?t?1xsp=0oLy!mD1>SAR?E11T>k(d$%3hitcfX3eJ)sn0#M^;Cb_ zero=dvR^MJaX-;^T=lsyh+fCCOS`{btG{2G?tK2(^pDVT{!XaJBj!apIg>>3*EPkX;i0brUW=h z`%_@Kxhp!3=0o?MX}oxBmKc}o_*}UV`Pd!{G-Z_~UuUvoO3S0|2X$S{&+YD;Su|xT zX?(t!1(V5>`qzGwj+=NL21lUxeOc8-{RmqA!0S7xe>9!@N5t98DGR65iWA3KFw5(k zHMyAkO=f6Jq$vY4f6miyG=DA&7tQ-mOg`v=Aa#*U|B6Vf@y!jJ$lWS(m-!sd3;$@G zQ^}^}=ZjI}BLC6TEVGcIye4ek*CFefX+EbmXk3iDb{;86d6{^meu43?QPHHJSvWyl z#(&U!11~2@*n!gJX*zN**C2*v`hXIy<UgQOu|v|S(0!ZxpuF0T()#44Z|a=c)ZM0euVSu#j;`-U@C0bS zgf~>sxK?T|z2$|b=0Y_8BK$Lr6q1Ywe%vplWMo{<@nL@7^b0wC8P*f! zL69N2qq``iNA%oZH2EfSeER+uT62Jz)?_Pu_wPls=M+w!J;Na`np{Nds(gzk^9nGp z&w%JH;`%_G!GG{PTRok=f%=sLxzjv}NxbD6S&u)EKXw03z4R5C6(Z`+{Yc(=r2Q(9 z`rAqMr*!uVDZIIrXn5@p8h5HX>aP7LjYra@`D#j?Ynb-8RIk+jDfLTv8GWMtR=rZw zRoP8?sA&v`Wdjbqc8QyH^Zq6N!@PHi{s{0Of_~IKOT)(k{m9*Hi6Cn%b};pd zS`_VXYQJCeXY>?6*4LmO*3Rf(D-oyE?i*zI8&^8UeHH3fO?;-xRKS^EX&L>J$5kt;t+0_vWnWQ zH!?Por!2HSLzaKi^BR6y;w0WDXFRRozXkhx3)p#9!K^6-^T;k?@$~i~k2`$m?Sbl% zdFvXlW1K=Ebe_N+rS=QPK{3`v9WSUq?Z0V1NpGb}4X^9V68j_(ug1gsH2H7y@)x4Y z3B4;HZg-WnKC7G{=8v>o9%M}YD^;He=g#M^L`F6&tOcwEtOcwEtOcwEtOcwEtOZud z0+X(N>;v|gzWR>ldDje{|MQK-TUQ-tenG+BzNrgoL?OSEmOL_r|LTkkH~wkd&QI{? zFPOYw;e2xMcz+wyWp24s^vB%(x*3-=-z{=OOBxSnoa_%peq@^wX2K*dUDDt1neEJY zGJTrJ58wXRt=WI^43RHxShNMpPNB$OroU$%xp(G^y#4hfk7aeo6p?Sud}0Tdy+tBV z-p{uy%e{Mxyr{4JXqNM5iG1k&SAEQK59C7%-*|%Myg8!pF4^Y-mh&4#K5Wc`&#~MC z`Q$yGx}N3kCeeRA^OCPw_RJM|tIsc9m*vGu0eR|h(SZ+K-q#RpXIjw zMIIIW_-`!tHHvJO*Wp<-yURWdOmdP;Z!yP?64uiEWN9hQxblt{`LSG@Tc_IFznK9`mH9o^nm+H~;Q8T% zY<6;_%C!ELULqxLs1^&TY%T(FO7d^kF{jA%AU9P`&L8jaNY>L1j+FR#hevY!EGLI2 znF933FAI-TWS+lFl#lfMd^=gD9UlF%Ol+pg$^K<$N0Q#`@JN!)PLCwn?6XLbsU=C3 zlk>+rK2p*%J3W&9^G=UcIVHT=@zJlBh3@A6^8Oe889CH1_xqO}9!avypC;^8X|@dX z>t)ABvdkAvl5AGSC(ACqEB=GcJZ-;!Ga-!q9{u^1eIWe>pnV^_u|lh3Qu;KJoRS~2 zpgdJib1O;dnH?Xga`O40@U#IUMNd0GQsk8SC==O9dYAopzC8K-v78*AtjmpE7RaSy zI6WoO{%v~JN$0ZcDHpjvep$D>GTnbE(sxeEoXFwZ(H~CIo1K;^GM&(VS#~@o%e-K> zU#9*OZ7rSp&gs{3{1r#L^GD0dD86Ig+51ndFFxL_mz|0I@yX7^emP{~$G*bE4F>lU zHJ5Y7=_AK*{Qd%W{IYRt{uc{AWPR5jqJQS0hi+s!9qsMZXHPzi<>IBHKY8Tl>$2>P zxZ|Vtn;xw8=Z~|OY!7O`Xv;#9UY^?~?$4yBTpzvl)IyHGDJtKfLU??U%Vd zOHPmbTf9Hd?BC;8XPIA8dt%zCJ-@6mD@3A4xXZ&=L-P5i>Yb8*(x=o1uI|a{lT3N; z&mV#Llxyh-l#Wk=tT?rqm%ecE^Gx9r@bT^aP|2QIrQPEvZ@9wevF z*MIW);hngtdTs%~d}{+UK5E7IuRs61Q!Y6??~qFgZwlD&pX*oh^=}@aC*_aKNA@Va z?(#o!`QjM=^@o=oxcxG>7b)qP9o;RHUfrIpC9c{&;eJWruZt zd8qwJsXuZKvmAL3n?ICg;yYo~b$fDpdCT4Tmj$c+@sW8bzKgGVHG};-2fF>sj!xO9 z!%wc|*B_qyhvm-ntR{1%^!g<{zGLU3eLQqGcm%OG+-Vk!t2d#VYpM7V@{D6kv4Eo{!x4Y@T#$S=oxT=0j=vCgz zC9At~N0)vlm&|(s_^19yiI|Xgamf>0@+8Rfw|Vt*{xf=!lqbtE&7sqImVEB^=7Qz| z*5~=9JXy|U7M)(`vm7&B<#eaZ=WJE(g}ivv(NrsGKI#!Uze8A{U-%xn#}Km|6TOpu zmVEc|qLcQoG9Ipy{P20=Fhh-_<4k^U9b?~C%*Uu+602(4!omv%1*Zt$*>W>i@7hc88>Q>|aiyy9nLC?@Uc!?Um)2>gsr}k@K@? z-_dE4&V63s)cvwFUy(D!5!yXsb81+ z)(WuL*(33#-+N^q%W2QAIQ}zxXWzv7jQOitALg)kC*!KkO#X|`ywJ?oHoYeC-+xf> z0i%CX;tPcu>sgMywc_-(JZfK+nf!Zi^TI2b?O#iLn_peC56f*INPN$JxPhtPPOr#W z&RkYg1NVO>e;S|re7fa<(tq^quQ%f8@;;aN52(Myv{#=0hee4U7SEJUG%ckX9 z06|-uCV#AP4{Mf+iI(p|I04g<0ba*T|@l)d{gF6qs>JN z#!4S!tS010{&s|=(oaLC)O&vx#pIOc#j^1%TS>K%B4IVnjT>qZ+CB1~+ zEB=Rvk3WjNw+~ryeiHr{q}G>#>O+=O%+Wa&FH8S#yHg)6V!1a>;@>QHh-vS7)?RUX z-z}fS7k)+JbL-u5ma{J>=X8{>xW1@=&A4!tYhEQ6;CBxs%%eKo*^rU8OzEat<C>s({vCT|ITF6jbw0Ixntv@%mgDE>9sl85q_n4hFs^K0zxk{9 z9O*xvu=|{K*r9N1&2PZyTX)(tCHz44(eww(&+_qSo34AdKlOZReoijEr;HP9-bT{T zdH?zrmV34pS>qopefGyc^{?@(Y%)RmvV(@b!TvnkuRMNtdV|UC^1J>2SiP3#vVYI{ zjPu`}_xmroY~vFZn4s<}%a2D4zPm@;BxEuguWYTOi@z96iwt zczS27Jiec+eEUqhD8TlP?=9(%d|^l?%WWH{*5_5Vm)6HMI1>7)tl`)EL&V%LGxm`5 zGSAuVQubG|r^p{3J#940O?$1}9(sN>{_kray1bu4^3~Y=gzp8%hTf#duA^= zGLz-BMN+<3i*~qxarsv@ zJ&pggGxuoY_*$-)@*Y<6=0_~&M^+xchClV}f8EXgJO3u(@BDb~43>MkMb65hfie9m z9v6A^`g zJ|BHoi|+5d=}+Y8GZ*BJ^-U|9VJy~t+vx!gpZ%=#=X}0}^qq*}Io^WVWA~7J7;D! z@TXh(y}c#}9*L-V-Vw+1Uws}q|GxR=1w^#1Ox|Zp`!=UdnMu3pW_c$sAb+0d^vP4E znok^=2uP-1zfA8B&Z7_PB6dojUU)%!GD}B}q{K~l^TH(xU_^?KzpunUk;mqYn=mdf zcl@{sB2Vo4vYY?PyF$lzGPZMHUs^v0x*k-&&3p6z$niBkD&@^`yevA+uKuk1`c&Dx z1u8K+Oz+2BufR-TXM8L9)A6R~R*Apy&QX_f{7vhu{QA=Pht$m5mHo%pU9tZeXH0m< z=(p4Sqkr#D9lvROY7dpoJ}0y3OJ1wh#6? z@5Vb!`yw3bzM9`#=AqeDL4I(m{06+@m}5UalGE$<^J-}F^8J^8v97}C)EeX zu)ghr)ayad?>Q%~-^KduYecW}!_g+0AKoOe)4HsWekJ-duGz=j|N1Ug|7JSG$)s5; zJ~3f>Ju>YCrq_*_&s-+ts(RX(N&EFw&--|JA0NM6g!fhkIT8BNerlEyo1Xb|s5MnS zd5J#hS@!A25mYV>_T-(b@}rOC(i^IMwEH?(&1GVH)04G?{kSs`rjJ+Y`KYg^4cg+> zL{LgEzNS6$Y7Pp|Zx{+CPGHp%{;pD3A16DI6X{cW_2u-1Q$4||*8o*ZYD@&kE`=A_ zt=9-uAAtw%3WWo8X3m1+;POOjLd*1>XFj<#&GSv4O<$j2Jza3Lx|6mga&@HjkSy^# z0mUVuFH4mzIr8_0h`|F#gx!}L;=hCnz;bj)i)lN?NZC83%U6C1xjfEttj;3StW z^OY>G3z{^jeDq{LXS_LeCPXP!{9r9UCPOY9RdRTV-(=1BH*!+>Ici$nTjPt!zT$*T z5%Cw@MqPO9#vHKsc)5QZ7`vNVX&MidOMAP{KEvN;IeV(K*D7}wta!dMf6Tu(VgJso z73&{Za--ZIFP8XYHyu*I-eZ@DtoIXb&$*k&`o>!%e;rHKS;}(HUqoJhcjbL7r$4Rt zzts6}_k8%zFZb^e=X|-#qq6&cspVCDzr6DDj9K)b>o^_fIVpeXE9)J>Vk_i<%B$(i zcjRVGUQj6g=jI#FyPm^0y}WXJYWTt8xB3;Izkd6rKJWhS`TuG4_ib|ZHGF;xm&*Co z=SO)Ti(Iz)2Y+RKN4i{(d_S!(p|8YL$Om@HX6*L{>)SUJeP_odW<2cQD8)a$CQrVo z=cDILbia+zEx=ST+AmKpE|E>sNgJuDbu!^W9e3vNq?haP;@fUw?iizW($@*79q4wSOP*hq>G8qzzwr zdIQC`Np9sM9KLwO4-0?)HUBZ^qjjW&r}{%H^0c?Y?P02YR30cl)IQPdhOR#P{^2!# zwGVyYs)l-Z^3fG4=Vwdb+mXxLIqQd&_lbuh&vN+i#DT)ExIXot-ye2;_n&_WujQL? z(b47seajTdk8|2*r*ru*)_dw$VoH*5t^!D(Ouo}-C9ICA9@4xB#xDg1i z@^+BlIeVtV$Ix@-P<HtMpMBwq^@S}X-(h{m z%}8(lf@#wVrpv>0a;NeI>v#zV&6Vp)r}f?2g<&IQ4Q&Dh z{z$*9ydkl|`Sb%XZsG9JZA5>3`=w{I?93H;{;OZTV&rm>|8!~LG?oi1MgDNuOfz#+P3W=nQDKelqlS%?48B!piXjIU6MU9nMz)?}6f<|nypd$)KuV};; z3o`a7qQM#q`mM6pX`E!d_xFAOe9t}41C#f>d#zp0KKtyl_S*5MJWcpxYkMi*!(*mD zI|+IJCmbHyt8?-az#>=qC;H{CbV|SWIr9f?y08$#$Nb26Z06?eh+EV6`5f){()yVH zWuBjWZqq$9{%Y-F{QcO!XnYnmf#08CM;3kGyeBcny)=oUZ~aM-*L=pDzDC4ozo}b zCH@oN_^gK&wm!*Pf54Yc(MJ{|4#m*B~g_B)=p>nYeE;@jp>W|(wXOTYK#uq z@`ATt#qi-M&VTvP-)}`6cK~DGtel#O;9O6f;t__O8FMfYT!L{f4==$*40T**!~AvE zv|lTi()-qQILAlxZ9HFiB7SJz9dySdDC+*1+b6LXZ1{wqchgU!>HF__M%wcNoI)%r zqgGPWlD{n``L2!34~u!WoAf=;Shr{M@_HA{rzYg$0W|75^qPIhzO4BT4*$a9Tb@A5 z)6RJDM{m?4?ojJJlxWW2h=@xctV1*;)Ar3b>t3ybLiYy@Wv8I%aX{=g!@*brcB z){o&01-iY1o}SYDYM-1=i}6qMdckK(!gR_m;G|?vc5))T6jaBU&(6(F5TdL`Q-&gaLSQ{hc5Aa9&s>VQC(Ed3VrBsH`$X5 zPdo=>gy%u!Z>)FZq-N*p%OAi)b`1!a9=rqx%+F75=s1mQ6kv-2!HNcXF$QG~s(y$% z;5mIW(voNjxckYc@4$4&mU8G@2#?X}5HO`zzoFtcVH#eWFvw%i4%JDiV+_^Ff-UP!TptY{v7tb(k17CTLxGB4rB=lc@yQM1 zA-I7#J}ZX!)D1m83pNxmZy5ai_T)(Vv^O3k&j(Ii_N65!`c64z5|tm=1NpKOlG4aL z2+9MoSO;Nx5ra7q)Kd?1kB_;aci$aqo(2v6PVoySL4t#!bLjunY>C?m$XH9yEFC7CnkdrwG)1RFpatoG5qLbW#w+&qbl%fclo3 zotBu(TT~!_*~!V7x!DPsG)n^Eb5paEVZJ6OA%!xu@wPk9$MnXIRq0L1%FazonJEgX zJn_(o?1b!@R9>8aZXKz-sXU-LAcIgTAE=@90QM@+oS8YkL?{GRA@Tf${1Q`rr*kPF zSGn1kEO#PAvGZ!`C4das<6v4v+mYeT`4|w;ppD*8?t}%xOv- z^iNHm25k$pD(R>I`b(KfIzo*0pV+@*3A_C#^Uy)p(?J{T6-pK7*LmGsqCnD0RPE33+3(;j$pV0{WJjb!fxt^q1k z6!`oqDr)D8{WPX$QT}4=GSj&hydGOsVPI?z4GUUWAIqn>z)$)-ND|ri&=?5rLLq|n z5g|@3@^kP=H)v7k70+J`IMeFT4%5Rvznh##WY_T)yCuL z@h|7?k9;VK`Bv?Inkq>h$ok8d$I*O?M}40z{-ka)hHtxs`Jaz=-HNz#1>@E)r(w0x z8eV67!Yk94BkoZ9Gbg ze5l<{_B{XDd>TGHd_XeaxIS??<==ZKKi}_WXHfm>9?IAr9%lk_XmrgDy3F^9zJkd| zJc;S_$FltMf8T!v;uhT=z#2cye^k^!e+=smUgyoaoW_4qYgv9?*Xxht{opvp3$8!; z9mFoRUhYq=`VMhe_g4ZRCS&;(o)`8Nr|Wm7o!D7R@*}x^-n+2xTErd7URp-hvH7(% zl`zNhLV6Uff4SCkeXTYx_JQ1))SQkhtC)gXuzu837E~6|vqC)f*nxihbuZ)e+t<&i zKXGmXd~tK=i?DIf)0G&$bziQ(dxg){2hyii;lan#9M z@i%@LzkeyXGYAK(coQz@Z{P`4U{cGN&jpj#6nXe~^U^&9u*cW<;Kf6ch*JI;z@9sQ z4mu2~tejT{I-x#Rk_i}nefMrpSFM`91?A(CIel!;OGn7yZS9-vUk}0Gz}d_nKCu|P z1zPD~e!q7&1%E>vogwn*rqnocY@zMouxroXLo>e?MY1?SRkcQhV7@A^K7ha&UrA8CXhq{KX48iWTH&i=nPx^x4CY+BdurgSr}6 zznwqm)5Z59A9$4crGpm!fml=aSoZMm?HckK(ylObuAbK5oWwvoU<pt(C>agzU?N~2mRw>X#Jpjh<7pn(qAt` zhi_&~4&7E}Z<~nW;u={#_JuR3euj$}L;5FRY_eVvfK!X%l_;#DuMFg)GGK~6!8-CMuWk4n8{TQd-`eml8~)CQyKH#34gX-nKicrmHvEeXciZsq zHvEST|7pW}Y*<0vKb(3^^!G*DE2;m|J_z1V34F2UPkQrR=WzdD_$b8-?r*~f*zf=w z9%#dZZ1_MMKFEd#E1a}+;?MYJe5B`gF&gJI+`|5YbiCGzW19shP>N!1Vt+MT7VkbE zZ*+Xl@00jDbSqx`8@hVTPa^3H+tO>~hk5NK$v@+0=>KwgB$0e{4bQ)f(HLt1E3VV| zWC|Z>l>9JGRsIxZzpJM9yN=POQTVt@?*9n(%whaz{W6;0>G-!iKMo&Oy!bB+=;cS# z6I!G4XE;Wq;jdPzmlxw!9iL6{m-bkG(}{O&=JF7Kr0y_352+u<^XKp$6@HAyGt+fD zq`Vl{hpjl~Ex{QSpSwWHgK?nLinTJqnH0WN&p+c-b$5uvqe!OSnUSo{Ssy{3%|?)cw}N`txNRrTjnX{@U6lz2}mCt%LDv^2l<1?1$ELgtJg7Fuxo5pmF!{0zAk5|4NasfS%kn$%h;UnqmiJ$uHnLncbPF4Rz zpTsY?C;5GUpLGbzN9Az(B83-T^#3wwB;_YK9b^g@*HsAhSXMJWTt z###S1RGC9H?Vl`{{O?Z;n~a_|8v{_G9?=FS-4b z^606)*?Hr6!63GxL?2H}dN%f5g`XYGwTJaD`sxGfs(CNAraw}AqR$?`VByCN|6>fs zSGSP$|GoWE_!7c+bP3~}XOH>@vHzmp<43)CiGHac-{1EqHGpj@KZ9>Low{nxm-Mbr z(kJ>v|D1^jyovF|HT*OA7bh%Vj^XRB=J2bBb+-}zip%%U<5GtsZd>us^htUmmA|C- zkVhtML;ZoT|5<&J`sTf{_w+=Hzo+uMvHk5`n4XwxS-;e;Xq$g2kx#zhIr?C?FR;#M z^%Vb<+osU_(sILpmVUdwNLbSM{ndYS*Zd}quX^~LTQPriLB`kLbt%2ioyy;qJU@{a z{7>Wir{Vvv`t0eG`qZ)h_UABv-4FC$zIJ(gdPHAO`LWB}!^``fQn8KtFYR|ar{~zg zs~^MkdTjpD{;B?+(r3?4Bz+Qo^c5wvKPBcKPVc4nJkp5i3n~2H#wYqkK2mz5{H9L3 z^#F|D+sx@1*mpl3dfx9`o;~RoeT}QH+JpK$s(x(!y>cyL*Ile{Qu}fm0JJIGlRkTX zFdSYzg%|$ke&0}sy{p`seo3Fm+x7p`^6E)m;V8V_{|*tth>G~LmXCE!i)Ur zS6o2tfADPn{%-zo%pwdQc#Y-3{)Z0w@PU~I-nYyDe~q*6|Bj~iy58+Q|B|1c(j(>5 z6CX+5&Kvsd_7joDgU;bGU3l5+Ph-}z>+rtk?f)+S;*YW8BbJ|c_iME7tF7nyJn^9V zVW>Yjy}EBJ-j6 zIJ^m$>|d&2sN-UVwdjNC{m|TCD>FpXp5AZh8l>t^VSU5a41XJOV#zKfCNyGm z7*9LPOX+CX#QB@>spn9Ve~Izm3vcHB_sfiLZ#tRAYk@Y#p{FL$dT!@mjKBC{{SuOY zp64IFDQvtDvG*0mSKl{00df4Bj6eJG2kJk!D}R zNBSBDGcLdAO8QUTQ6sRWZW$`BG%OT4#$igyBJ~cD(3H7S5<)6 z{cpxcoi%9$;*K{MPc43!s$%<_jI)lPM(tlz3_tH-D+W`0)Y!)O$)&tMwq+_~SJx(* zI&Mm3yz!fpGf{ukA^f}^{r+LfU+Y}vPi~z@_0Ofo$Ke0643@6xn}l+||FoUPU!})! z_&{MPv`FA0v$C+bx*GTM!)dW#tB7Io`YUsQ7k|6e{ffhsV~qBoXhE8l0~>T;J=4B_F52UI9p&q~ zIDFo!?mH2O)PCj%e)yZ(W9>KQCk(hbhl)pVqU`E)K=!J7o+<)*r1fp zXFP&;(_%1>ttg~gX{;xN)B@P8k1lRP`Iz@v{_o2+(ED8a0pkrPWl;T%{*ZCtuQBl$ zzI7y*Pt^~9UX9rQ5%WhOfa^8edfVGJ{DHz77T&ZT!#8}z^6yQZO!2p?{dTA$7jgkD1pz zi+t%Ye*XquxP$uRK^NoOuIt-{y#FD_qF?%tooB71{&L_1=4TA}{5}j{ca}B0w7(*M z5(a`x)<2rn`pT%n`9){A;DtNGH46Dr;NGyZYBBxI;d#EiQJ+uE!P{C_A?HudM{wOG z^Zm430roDkUNf7*#|@GBW~%O5qw=>uMk^$~RF`Mmt^EIw(Ta$#*XM7!DQNnP>%$nW zgm_oJq=#|4Ixk|3MxQ6m{h*|;l)`JJGXKl3YwSCskFo1*#=b;$$iYJJJxeT`KhIYk z$X~=?G=&#eaIzH-Hqc67j7HTN&M)Njp}jLWd|_vI5JtzkJq3F5EGq!_ouon8|CSUL zv%N2b7oH>(4=yXjpB4GTnp0E5FCf~Nkw+0-Kk@SmOX0jZil05^`c!(+Ke6l`#9K;# zRq;Y_gGd;RwZH?74;-ZwL;I}w>gpQmKI+(rUm14m`fH&_kuSvq;SJkvj<42NU0R7p zrP2lV=im|1>@Tyd+Lu3P4xABAJ}}8XG+wOxFg?Iy+Q9CN^#O)09r!I#*y6yD!jlt4 z;jJDHNk7A`)cdiBQe7JneZ8~Sq4pkCJq;cZy_VM+ROa6_k_2CPev zV7Mnhr{J-`DKJm;{LO9b!%bpPiuKwke_Bb zj}Q-`1mjOVeYpQJ3u9DqR8)e0o?^pasLz*?m6WX0x<4Z+U+5Us!0V?wEQ9@KssLFb zycb{_s~@)v>B*vlR-^<7o8njgs^mCD&FWoN)0BH*G%;886a7~i3h-$g)|i<8sp-=b zaR)c22l8t^o>7yhDft2WJ@Bt<*k4yeOIli0Spi)>YWS5uEWMbZ{1cLrvPC__H$8c# zjxhe*vnnwV8-0Ct@du7+Jhi69!psx_>l94{)k5};v9;c@V{goLB5dIj&+smh?_%GJ= z!Fa+{UZU@Kl>lfz!DTZz%Lb>kC?fngl_0x*`2JZ0Bs>j5KpwuQ`9($GVob#^{1_X) zNa4cG*&6=Sw(vg*&%Gwphv_%;?VX;2`SWOV7sn{_lP7Zof{#)d*5l^SD>Urmg+EiJ zXK(*;9A2J?9$wd1Qf<~K{1jXK$EXL0^#{zC^%O{WacE)i9HTwI5`Ns2<0!=#eor~^D~u}@x0HQ&AdH6^v_&UqCZYupUNKAZ^!37PA?y5VZeX5XprYqv0AD0bJ6^W! zO|YLNhaC+vt=ZfiA`cGYOY;?t*y6t(aGm)ElvgD<=!4c5Iu;-VJPfu9_5Rl|tuLvH z+pXps({koiqRGsvbT7 z4uGY(*2F(pNb&vs7gEz69k0SGe~SgsF5nRG(^*?+exp_A%c{x$A|?th?C-NbMjof` zI6UJPydSOnnIoTHU0BAWP)(b@Uow3vyf5(l815f4^QXe-ef-3t{*I6&~)rb?|RAKh&x3N1?7^F>br5 zg<>22-ILFtXyXh?kK$!N6P8o{e7!?tsNXpD6y*?~@w~Xo==#+ll}AS|eMk#WZ+-=M3zZ6{ zhgTtxhu1;pp*CQ3G+}xhbWBNwty=~2`4zBw<23w*(yTkAx2&382VGwLiHeG{YCa)A z(gzr;yB@yg-IxzSjppg#`c_s=ubR?V-o2)sIf z%NxiCd>p`3}YZ@!8sGh}}0k>+c#Cw;B1yTa5IXYlL0@ zyK`>{VEE=nBfPnW)NMMS<^mg>`=Ttek>1j4Qv1M zfLl>tdk_9%|NV8vqsRxIRP8^=o1eH{|C&=D`WwT$RvGCt*HC+SOpm#S_IdnY^zG<= zp5wcza(gD~i@DR#NA0nyaV2->pN)J-@q6o6?Y9d5?y9r)#qiO0IhXIaKy*6tt%^T( z-nglV{dYTux5sD41CKmE7v4Tlx z?5xio{7d#2|K`f!|1lGxO5vF=@kAY;M5trH>o>lxrTm zt^M(*kJcAjpJ4vF;dL~!jA~Wk=_p}Hgc4e^V$wG#SGPmzyKvHfqx7gv*m`>OEzdr< zV1qSzP(}%uuYe80hC^l3(Zv{z=JS%fBmFkH|AW~SB9TW?a+${WjJ@I<#K0^e+rLEt z$*V2lcu#m;Kb!}(pcdw1R0o%4U3@TLDk`I47h_|{##qlj__L7|u*Q-pU6O3BOzUSD}4_=DAcLc8wNq#ZUczqt6d=mbaZsYju z_6hfYaLI$n2j6F2)>B&4dW~Hl&Nt7&;f8vCbY7t}D5dU(S>CdaS5Vd}h&C4baOh4j(K41V8J z>wUEc^t%ny-87!-i}0V>)*rvJ;qPtuR~x2}KIoP4>=ZR$A^3PTUY}#@uk-vrIz;0h z{1}b*KX~tx^ScW$xmr+PkJ9%K!&G${)Gr-ZR?OA3A5uH$d#gRI+9!jD{l(axNcb{X z_N~)i$lG`X>W{gF>)Z6SALx4%tYJL*g>#l6U)qmxM$TKC5I23s>toL!dv*q5_kqkW zyZ5G%h+T&bbKHKa$e(DTkN+8m>;pM)=}7 z@LR84vUxqV@3G3BUfK7{a9n%T^;H?_YdW6G|6kuHQ-95?aeceyu~Dxe-`q#qD_FoS z3@jFVuCgi1?nK`Im$WCvvUFTw%5dE4(I_`lrEtSpO^69r_~bYw+0fgD&^5 zKB&1UJjTp7!G=!)EcQh6i|Rm+fy=3%_4A_-k3jvgr*eFs{dvxLh?~+mzRD>FB_VE~ z&U{hfotGl6OJ^MW>mM}U=)Qo%f3*7D8OX=0{qBEvzjGbprhMj?z4O{Th{G>%`Cgx} zlj5)2!uZ9C$y<=`x{UQtf1#Y}XX&fVzxV4(`tWxg!Fc;wXHfsU`*+4$w{NBXKwMv5 zPyYGFg-@cs80F9C_0!&?=a)K|`QjJ$(D7g4bpM<2F)x2X{h_X{j6dEr@dFIs`3B?Bne`_i z?oj?VL!*ZAM1}Had3Rs`aOCTbK}R3dACb0{$&r+oywl+&-*U819ALT4*&2qFMf|W zPT4p8{NS6^Kdjrvd{*)2&m&*o#?Nn`{ZIQDaou2kAHJ?XzY%eZvVY2*ci9lco+Fqa z@c8yC5WCJ~eC0=v(0q$Of${ETk5m2YOk*6%_S}o%+p`$g>|5B0IIPaE*Wwjqh&=2{W z418-C=Fj^&V`V>us_3fRaXfq_z+OxF_f~vfZi)|y`GUkSJ@3YEnD6KPr~~;Jb>7Fre;@e};x6T1{F7bDe;{rf$>C=&om!4K<|xLa zzIZDKanwM5KVQ0kL=9r?K*o*@)|Y;`Hb3 z8nO{_=|a}`%iQy>N8Gp%<5{z3?L-{z$9U9>Rbym; z;}NoI5Pw_Z(E8XDH=c(2Qfpa1$s6vSK_2|~Vs}wF5GMb+R5$^;V|?sl0ZK?gp)|X z-wpaJGl@w2y1Xx`Dt}I8MaulelqB@;2_C=n_DRZ1xv$6c@aR-2knyR^2vGT%Zc_Xv z7iToS&CUbw!)koY<9Xd-FT@W6=yTI@(!j+Tn>3or<8Hk%Ha#xSD8R*g*9x=M=q>qi12TYELuU)(a z^#|PY>h8T@egOUd!5COgqL}_94d9;*{7rx8b~5Nsq4t&e)ad zd-U&ySeBn5{y9+j7eb{dp>_@42RQzhT#a#jKJXt}X!wi+dG;4a-r_L*kR0&FPl4e- z@^5B}P_RTu{?pKRDkqP^n^%yLH!lz?EaDVCU^19MzSf4#4)2gRJG4V=c7TWTRp5?E zswepW&CE&DZ=yeA@_(#*5CmB$UfsM7c(_wo8ITDBcz+gF8Sbxv*G0KJ6_ghUUdQ-T z)mkD3umuPC0+{bMy>B9)%SkrYr&uH8F9*E+!U8l!hvfwr9PFtZgmd8qOEmGBS&87p zIG5fh3=gh{lRfDPiEx9$Pfg3@(ENNe5~igoae5wv$;OBIyi6$Z6!2FJX#jaVVGVsG z(|29r8QE!Yj2z|{csw2>2iz)S9E7v8Ef^h4qAuadIk|EWh~d+6=p~{%h`|AvMV|Z- zqLq}=pOT(1EeBk{V-?2mIn&cTGbnW&e|mC?UZ10$WIw=u^-J+(<|b!nCeXNr6=+zQR384|B?WmHy@Izt{u`r2-n@Xx zyrF@y?w%Fur}$s2r17VL$xkz-*L=hr@I^lGq=<3hh3SJ76k(6tf?=A@f^nH%g;!^A z(+!ko%nA(53J^nT$%;VqAy(=sep;V3=`Vok%3AQbixHqa@uu`p`-;loVq;rVc|dq{ zCkSq-^XEVTtHQ^krVGu5@C&cw%K18#eb!8@#$lC(-erjy*qe3^1QhN096Bp+87|K;$43+B-O_ytsIt@|RhH2g*YtvCg8!BJp721~wlY z9@57#P_Y6J0$>YQMxzE!uj0|O1MpOvbdx-o&odua2z=#2?r2 zlvXHE0@DZK7nbPmK^5j1CrUr?)sR50EgT+;8>$#38RZen8&C1q8s{}4ErCD)~9zd;jC2;{18!KE6uTU)b=1F5JZfE!kJs&ez+6 zeL$!5XD|r|ZCl{M-}WE5Kfn3$QkqX|JAlVKnBGMu2dZ{?OJ@i4JapOWOHg0yfh-T- zo#|+Qiudrc%L|tIN(wI@QwX2@cKu3}Yl$}LgCo1JZN}@rm#?!JebIs=SOEPq@Fg z{z9;~tlEp0{I&NxWGd?G9LoCC`2(;Z!~KgYvQ~zJl+Pxj{O?PUq>=K&Rx-${M^ui@Wu%AX8!J_y6#MVNQ!N(ds~I919I{qGmn z(I6M@^Y{v0W()+E#4qWG?=O5z3OSw(|ilKbNbW*1HA*|UBk`p?@Ld4!w-x+n=@or*`oDfJ%KM+> z^fau!uL-gDsehKf88DR2$VmfB556RQ_VSnb9*8=$2t&F)V*N|+yMpY01KSy&RbQ|j z`RMRJi(lds{Wp(3fd1_M;=hyss{gkaVEnPlpV7v-<6lPH`L$JFPwnZ6FF$=5hL782 z4R0@xp5#BAltJ>*s(&l_`=|11{7L88pbfuWzV7UsLYThh-<;DoE9LD1mRU z9;d!y+a{jxx9bz!Q+}==Je$@lqkndeuP1q_-@@;UiGoY;ehi^MlBn|PweV723AKBu z{nB3TJ^d11^hY(>Rz_=-Nk@AJ(oUTng6HkbK)p3bp+j+OT|HQ#{yBXRpACJHXvFPR2M zyyPkjZ6^RT*WA~hq0=YlKqjnk z_5`{_#iEb>Sr`U+d!0w;vmCDg@hJ@Z_-gVoemwrHO4I{}{Sl`5u#%cU4#w3yo6BGP z7c}es3uw3i8;8aJ02o=p)soNeCzKD&ZR7F0YCQ;Mk7)lsg~Ir0|2__@D(B#NF)$wS z!TI4eRdDPxgkk$HvHn5~d@<}u(B%QwR+!F@$g}RJhI7YiU=N#qz7CvsYu><%dwtCt za+JM*Y`5KOzbcF`tH2_t3ipfRDcCUIhBHC>iU;o3Gw&!Y$J~^;^d$~RKkV1n&Dr$* zJu!Z6Pj~+I`PG!QM#fd&w$l1<{7S|zpT496`Ls zP*@H|pR_oJ?&pV?Qan%0&{y@cs%2-UYc)x0K>~Q?;I*R$@^VY*x z9@{4p8n{ zc(g|>)aZXx0J2gvVTrE+EL5W*-s5x6p{Bj*Q`${i#=oPAIvM;Je@bEc>Z5;LY8lPnSU8Q%tiG0ITj2D&|bF+9~>?P~( zV_y8##5~A&>YDRuJmPIp^0ovlv`)`xAG9`8+Z=A?@Unjh_|f@%^(B{Kc+W>%UM3z+j$91k3*i7&SaN~WA+cZ$ z9_&-?7-k_&e2t9<|L<1$s_Fu*s1PQYYLqi5&{t%ICVgn%YSv#|hh8v@_+ZV*k{XY54`Y8JP+`a~sv6XU@-2V!`|m56y9sf$ z@~?&Ap~cnp5r!62Zj3*E2K9$EWp6xi=Q+otyr-`bUzI7om_0Dj3|EvoFBJ5tCX5q& z%Jjd^M7~S;`viLcX)!2EyAS;7a^$;TROtoYtl;9Mc_$zrA0_dt21^yl1Dnsd0{Mpi z%&)s<;SR*^WX3Pv=<1KSUD+E${1ycT|5`2r!9Wnmal+Z_)^y6n7cfr<_Oa#1i!ySq6qjj9a z<Sev)E|u3cs^jx&AtK1M<2j=UCuhH-=(8C{2$9-qV+D1vhQ47z5Hwp?;XV9 zk8S^s><^oUFmCymo6;LTl<^%8kNFbA`$x0B&)gHKzP25~{C#^msekKIc(6z#G#iMFS&a9 zkBCb*Gk$#5Ge;tB-NLxwoOsHAcqgZK);?E|e6yNwcz-fP1Xth(=70Qn7RA@}I?EqB zd&z3#Bu(?VtncC>*#sc9m@C_?Wk9g4-92|+*|LCMjWO3gF}WK=|`NZ`kOC*f7mR< z?xQ(;PD=W0#NjcFf19)CbHp9WzVo!y6`K)9k7s`H^rNVL#EfJ7{f<8_MZQz*cUib) zE`{$>{sVLFsr~}_xC=S_PorP?8F7cg)osHP5XUZMzPaMpI}x`lyz$1zC_kY~nZK!f zSy$OjHgX|9h()c`AWtaGk>JDMNb3c zAx}=F`G?ehF>bkV^1T?o>1xL3?QEv?zxZnzAN|5M*X$fe#VNPvGxEK|e2im0|tjH4cAOsGZv9u-Y$hNZSSXA>TBS!(ZO- zBI-}ow{!TXcOJF~`B?Ff8nnbmd$)8PhuEXOch^q3mgdi+_i*@kC$9Jo`RKzK zKl;$e^nSJ~od0ym66F0uncoz13e`97FvbpFDLs_=x)(BbAzwd<@qpKcPMe zVcfm$uB{k8+Rb?S-**%ub{)vygSY!!cR%9hB<2f;Zu%B+>NLiuoiUI4AAy57{IdOS zxfc2O>C9)(9QFj_hIGci-N5HFbYw8z{q_!8k7z!OOaI5vA)sqLq}n_sOj9^9(>ktsxR$|zhvr8YR|jDAr6lJf`cE2 zULmyKr7ZvIqdyEqTw2C>OJy|07p?s19`n;`?%%2X*Ei1IkL3OHIJ_^f0`~qE`Lc_v zYs-tlFX~Aer9Ci5rSImecB1}}itmDB4oyMaGGEF2%4_GF{PRNpvUYxvdH)Ic@3mmy zP5V`zJmwPm-f9&leWv{@wH5O!Di>Ag8&q($(j~?;kPdji>*}Dq7f!%bLI0*=u^txj z(AD?si@!~Gu>KRXf2I62u4YWmK*Sgr!jUma1-XhuF|DX9AG~i?*OXB$gL;kD8m0{~ z;3^I+2*K+xOoTyr=>MR9pz1Q!;i3IF;Bu{|jE4v?-v$L@+)(z=K8lRw(Xx_F*6=2r z-wbx_CVN=0P0B-iOm&OTQ`LQZVtJsYo3eI8d03!K^x^&)u;TY=(U+#aiE%Z(#r5f| z*(bUXht&Bdr;T`W0pd=zpXS1s(&&9{e22piJ$(n&hw!_Mzq)4&^?w@PW8Ajy@AN(I z=wSTguy5U{ukJ&}x20!1gt$$uXT3Li+r5b6mA=XS7IY!*Q2TW}uNKn$KI-R~J%|n>~C2I5_3?KC?wF(A>7`4SUQoOUwsVY+wMN$a^yX# zy;=FyIXQ@1a=83fdk*ptU(fie-^SdAxcO+7-|+b@F2unxjIY1CjLI+d7{*Iqe~J1Z z!R7q^?fxP}?Pt@m%rAN@gTBx1SjN|d&+b5doeHnHrhYl%#<9%by5^@x5yz|jO1US` zPDb2tJoBxG<(DFkQ~Q@r8$E;C({^z177h0&R=rL6am6wI*ROBNX6Zm;u^74kO5xeV|FIn;x^$%Or_s4bD5}Hr-rgM7UetF;{7~Ye~_`1;t4M5zj z@Un_yZbe-8D(m0z;)~Q@31)Hl>3KhnMZWo7j&IUcyx%d^!~EK;5ibxQz!aYHlXFJkYBM;thX<3Huh zom3xUA7uW5wO>z0zFpz>2By~|u3N|a^)>Zw#DRwxhYH5h{6W`QtZ()!lfOW|w1xSn zzj*0P#I3OH4(r$Bqj%qhIOiVE)yD@x+Ie|8?*5m1|L7=gpk|rMHiw_Oey^U%&L>Mrx1zE`GjG z#1+tdWfZvW$MSgSl~Sr-Eef|?9VkJ4q0_m%Zt`|ooYYdqW4dq zhT-GY{=KW#q*8lP`V)umyJF7}o>!alA74=3G7#4lk4r4sG>cdY_-hTvRZERyZ;*k12-tyfaS0Zj2#eB}r zenG_XYCNp%*xrJ;eJt}A9`qNDM?21BJkC9bzW1?H7+38coQmNaM>Br+_;l*eyWEU# z`Rp{Tc3L2T@l!K@rSDbDR2BZEtEheJRP%eZe-YM)>7@iYv=;^Advw==YBZR>Hd*7t z{4$x}>&q(;eo-kH;1*M0_zzs;fib!?5Bc)6m|kca+bWqCPFVXF)%Z#L@GAMh`NyX|1R zjhfZe%(nh0Qc_d3SU2`ZY_k1FUiWw7$;-wMwT@w1T~02Rx3L2qySOmFSx|<)2&KO( z{%~?rv$JLxw)0p?@n2v*IDagKO(ts1y`~h_uT3t;b;mmp7B6xhU1{>i1N+;m%D`0* z(-1$5FD6WyL?02j2lmAI;J9agvFc#LXr`tNTtchhn!esmtv2YdtpXGB8r`9?o?rCm z18)w@kD~W8)A~AWPb@0aZ@_s1W~im-`m&~;os^a>>67x{6G)8m%$b>SZgMv4k0JX` z=?()9n7rF-+5#K)*=~Tb0+^HIN()~&-48zYqeo0piFoRfng2&W{ZrSs#} zU?Bh;YD0zL{pY6O@`E5Fyfly;pCI5>_&Pm)){kk& zOTr7Eosfz4MN9&p0h@jDvW+`by}{avgyBENMtqEo^*sqM`X#&-LwI$Acw=~q`q92h zf1eblJ_DvfVg3CRUdm6fq*$<|Sg@p6@Tn(rf&jzoth>YG{MH&bn73g_zeo^YBuL83 zhGEN}WPrj$`N|E(u-#b&U<|2MHza(W1w-l;ww`u@^#%Ono9xZN-U@ApO!jEBd)kC) zceM#yf@@amBk(6{@%9e+wcQ~5Hp84sBWyZwf-q!XzAtkAg4}@lA+%u1G%$H5H{L(; zhmf3}oX9OE*~iUF&W2sRxmnO8=vY-?_`Vdup3LfbI!;N-p+<^6wc zud-bp@yY4%Wj2LROqb8kUg7tahxP!c$W(@{2-BOHl7wxN(hqidKJ*D~#Am%@Jv{-& zSxKDE=w$wlgn7TDSpQ-CXhEoN_XG?nG?iCUa$>qKH#x(TF8PNCkdcs>4co?(VCD$s z*GzZ<%){bBYneLzg8l8nQ4zXJ9X<_5?+$3VTM8{ECBK5p^XJl;KsttMjXh8u=fn2V z;)R;pUMt0m80=Ye2>nm%9jo_z@NZ7xb$0`Lc)26t1#|fs293(TQa5l!4CXetofVEG zs)O<&1EnfB1V>@q;LGRw^>k z4-O!u^+SDgCO{uW_gG+H4ukfWRmEgVqU0ewJTS4!L>|9j=$jF*fI84b-dDk7)e5}J zokHu8QOZ7og#P#6|4QJ0CGfuz_+JV9uLS;A0{<(4{~weYU9QlCo<<5LKQOU0=bCmBEeyf%D>GNj^ z=O)8UOmbpcW{Sz5yCgC?N$KBXl^5PE{J6P}@w@)5@_&sp9~AkG&U~xzBj!2kcmJmJ zXE^g(vP%DYXFg8&?aq9v@Pp<%#_tz?vNP`*qv9`j=9@)+l{4QV{J3(*_+2SV|3+s% zUie+ke5vpwDjfB<2*1>s4-3ED%3JFf_{f5RRIU%VP)W_<->%=)^BYv@7=O3uFL&l+ zr>XpJb>;)Y&ki{1Zxw!{mA9rpJ<*o|6TJ!3$d{Qp2ldBD{a)#)zg_h2vg+4$q^k6f zSl}q%HdN_fYUOR|1J8)LaN?uxjz(7>8mIJcx5`U^ZqYxe$}#@f7#06yEAJHlxf#i1 zQzE+Yw{)b6zuYP>VcepBl{4QZ>EG(iN1dqj?{VhaMgKL`j`{P5{D>MyK2Dwg>>hEe zBVRA_8P4);^8PP%=Cxs}e78IEp@UTZ2Gv^Px0b&rD<{nhRWu_Z9VWr0Z1J~I^p9I; zk(V&B$0+@?t-P)uoa(8gM>Dcu1tKexT>|Pnd5JtHFAdHn#VLBxE5B~hKVp$%{I0`Q z{xh6;kMK*K`BLH6JM&(blwX}={M{nI%9(E$`K``;^bsokdz^W<@Z%Oc#_tt=wlnY1 z-_P3}<%1%>(JF6!J~_GB$=TUi**<;#Ql3vxp3g3;yzs5Uk67XuzcyUuf2lJcBm8=2 zK2G@U&b(jvK^Hp4pL&#fzU!U&W|7}+^&OZctM zylaHi4`;qp%6HsSi~haShl^iE+8p?qIi@b$-aPp$=fy^OxbPcutSY~ak>WRPb~nk# zOa69Q4@+W+^@PjUKw1sBPV{egmTwe((6x@~YmbnB zZx+}bLSeWkU(3a>S;uD~(ZAHHUw^+m35nC8UkJ{Jr-3uwtZdsCutVgxTjllgk5%O} z$a#DiCF94*R(`Mea}&T-?OxSGbBTPpO&~66g{6 zRaSXPf80yGKfijB-__{&e42zWzuu8=5q`Zh-zNMnXFh6u@97JR{Kgv`LzWvQ zd74|~cUk2nfLHk0H#w%iIYRoHr>gv2<1F8KwBk29^9>UJpqm}zkC*w4RnB}zg!FkX zKZ4)?JvaC1OPRL5|Lqe0xLX|K?~0&5R^~5eJIiaMRQfbAUFonTAAghjU zk>75W$Fj$(LCSwyg!E-3z(6iHZ!q0Z*n-61o|G`5n^~X|vV(O4RgDQ%-3l);|ZFJV(DDm%c z=0n1dTV+YVCH|bm)Z`@J%(UcmF~5}TX&n;(Y^%Hk=n(zaIP+b??{ellq^c~{qR5PtUpfXhc-IPdqn>(XFmRDRX;MU<0IcRWxj&nr;NPZ zWG@|PWUQk zK3@3CoOv&p=i>YAzrmSzi~QZre88>bH#zfu(Z9`^k3UMuf9lMqO8h@K^K}w`-`5?> zw^ZUE;>-txALY!)$n)Ryj^p!9Rebo@4oALG_@N&<^3B2@>&%CQKdlE|<`KsWZvMCrZjkGvzK^Yn?|7N_H-$Ss?z6v%4=LVN zGK%V7IBG|qekLC5;}%yG`U)z+NEbc(fvubmc4zo-lQFn^(XU3YdOxd&TfQ$6pgmRb z6Gu4m&2K6G=p!w>iXXRh_-cy5)gMI;_MBpXtRir|t>o`H$|4_|&h@&hk@M#-9IfpO zGEzQuM>8LnrsNBcA$j2?{cY=ceBw_$R-+A-YJQ?g$+s8qekK2B$7=hT^lL*|zxL+7 z{C>ke;Ql7QU6p^_yYl>YSe{>p;#;5N{i@;a9hT=8II9o$3&0ISH0TYNhDl!fFP%zW z8*m`=b>Tkd_$7bwQoowQmiNP}+68wJm!JFDu%&*Ks&=8iOz|IC`7RZISom+Pe7EA= zbCvv`R$e=Y%P%PL5B$UuzofrTrNjN~r;hE9N9E7G;xkMB)c$~^v>X_fgH1DaZN*q! zl*4bS$PfJ7A}>Meg#6p`{jF6#Ugf_<#>W?ZLE~e4 z{cMu>&-~IcePJn|^lu!?CrXWsS$RoDG#pb( z?aP5bI?m6yg@4YO4+x+6lcRi>ieH=Yw&q3~I)CI5ex)<7 z%~kr>I`b`XY$@hn`%3GJ-w#c-|MPx{*6`mAXYAA0-%TNimH%}9_TKpo=k@DVe!~&_ z_R4R&uy@`wEUH)e8_w(BJO51Y{DvbA=v98(83P=7DW?{XJl{hcpPwIA%&2ttKa8gb zZR-PVF^YfLnGeE8o8^Z(%C`tV!F^=(f3;*OWM_z+Y8Kr;d z;f{Rw!HR#+nGZ?*UU`IL`8J%R%0GU%Bi}0gE6#ko@UuoZ%10lf(l_8p$MnZZ{-!(g z9V-3xEoWNv`-gM?$8{6;e}Y9*`W^(8O8P%izv8kvf5D`)Eb_vq3O_o*k*^cJILX3y zC35^)4bM*nlT-R0W{Teh+w1AMb#wnKSe()qx`cZA;)EZq)PHP3HJ`a&xH&=)C| z_=WFOTKCx7i z&c9t;KSTGwSN&-{qJz5bN{zn_zEj8>EG~7gzx`_&grM5z<-_6{!g=h zUs_cC_gt;&|5MibA5wgMgW_MY@}fWfJ#HV|mw6oX?~?pASjUedALvl>L$V#^JB7c& znQv45H}?@t`a0Yn>ENtpWWdSA(p%C*Q#u*MCl z|NHSzec)3K7e9Y_emDH#+`kj~D5+Vqq&{FYewH9&@c5r1{zCjul=fh)Dpa^eZ;RU z_)Sr~wwvcSv=?UeHMbAZBh>frXT`rctM36IC+#mOf&bh}Pw27p9KT=QVVsW8=<^-< zpiA*Z&U~uqUt{IjAAwr<;Dtpvd=pG84HGX)V$}Kkd_v27miArJ@2yh&Pku+fJy-FE zlsNJ((SMUO-zoBsS$TN=a27ip=qzhDYK~vhCBHFwD*iEZ9OI7@{uC>}mwtz}A&etc zZ5*#Vj9nu6q9OSmT#4F5!Q+@^<~WjFgvYQw~bvrT*?)=J@(d@Z&G>&DRUuDCHLR8S^QiyFaH8hm+gmSP(T>kYOM8jxXUqsLf4lym=zpE#7yX{ESwA=nB>nY0=nvn@`df~0)~_|F^uKM@ z9~{g6_rN(Pr~hK-^t(^nOzH2+an|n_{bTxD%BT5Q*8jJpU+MR!sQ15=pO5=B+xiF< zChUg1i{D2#V8{OB-M#begO&YX5Ard}KBg!A%@O#RhkK9T)zUj(AAxs2(!0Dj0^hQ_ zcllT~zg7R+ELFbN@t^xcmal*RJV!pDc=vPXTln@)e!kK7^7qGGF`L#GrGMOYEc0+O zJJlEW4!`E2XT?;goPij_%Ez{{SQk1IK}5(VUceX{shGrTY1O| zUBMsu`D+~wmgg%xxHqQsX?%Pa+_u)ARmGOa|+&G;n2#BQ$_XVnpYl|w;pHO~PRX&_x zxj0Y^j=4%Ib%xa${u`Zxpg$=*f}$FB891o``z>^q)ME(fUsqDk+F2aZr}LF~^ix4` zl@St>7LuQfvaT7>z}x(NDH zBgi*K;A0#W94JF^`8Hh2=d_wy!&n=ey8*`JlH!QS8ec4 z>5sdu_w+~C^)9bn+dJPO`{$uZoyI5b2>JsN__j4h{7&T)j36JB{x_u0NxnUTe0YHo zzf<{Yi+kteBJk~zo^OQmk6CBL@034(g!mgH@LIso@05RcRquQ#g8qgG_1_;Mf6Wp2 zt_bmW^(22L_ZwWZxc}*f`orTdw6cV8x#H`4;3*LN*HYU1`xm~wcfPv^-shX<^}?QI zPjWWwjDcQvI_^!2^D1}d61~w9p=@%@a@zw$=lgFWzgUQhtszn2wO7U3D9;M}|r z=5ed_gsDGTdytoKZ4t^(TjgASDt=muzv%Es;Oipr%@O#R zkDT)-@pttg&-o{x^F?KaU}6o2x5MdEdzF8}L+rNnCAH8|b^N%5!e>~1Q|Co9l&p*P;Ur%Yi#Cd+x|0L`0?m@qMl^Q>v zXw@J5CYHw4u((0`>wC~Yb-)(-e1y(*PJdAJpTzp5e0%y`q6qg1Dt{8Np7SSm0KzAp z`ZC4uUd{Qim+z?4m~WV&r;nOTng7;udEBpM>+=J|hkxbsJ|ueW3OXX9N~zH_9FFWcWz{!MU`Cn%(zlMApf3(h1 ziAny0cdGX3)c%woS%36AWRo}Qhecjw&*Z@oSy=`ny&7nw|Ne z@b^3OA>kij9@{UxWc^k9cq_GUv9r1TN&p^j*m?IooDO-ud)2=yto5gUw5|LG={&_R z<*zN^=dM-h&)>?g=X7fiJLgY(NbxPsd`P8Rd&HR!3;(GzudPw#{{{0`*~;g#vF%iT zjmvo5ccHy}DL1gby@AU&R_$hx@{Lm8zo3f8UjD*|6yKBnx*qfokni`soDaKx;a!Ti z*N=iY&R?6-Z+eCT{WR(~yTMc~~L>>Iiw z$a^Em$49WgDD8oV`I+>zsW2r&hNxi5=|k@@nZ7tFSoPc1gS-beV_-Y#Sz?`E>qD#P zhLZLO-rm#ajlc&Z z@LGiRnJ)3~*hBdRAL>1QF7eOTgM51g`OXM@Y6SZve+0fU0w0RNH$})_*fxJG^;haw zO9c7&2=-H+2z=)!y+5Ds2=a}~dzTNMXPrN{=P#`MQ@A0+IKOV^L+AG{9~j&F{HLc*lalOAk z-4W6s`&jSkZ;OzAcLe!B1im!_9~0p8h0b`luhaLvGlIPKc<=d(i@>Kw;KLD~kNbk& zpKo0R{jpc}p8ik-d3OYPZv?(8g8op1`saG0_w;u~kS~oOAB<4G?(*Ktzb%6P?g)JJ zlfCCJHUi%oq5NBp@BRG_M9|+5fe-hfAI|qo&&A_bQxkH0aC|{B41N+a?W@z8*4=}= zw9l;(;*X8sA6TpC{rPFW-ual;-k(ou1l}KkuZzGpN8m#d_>KsCu!r*df7rVc__&Fy zFPqEU<~9Vvl8|7a2~L1uZiU3bX%k{{fH}Q6oY;`V*l}WxgaHbe+vTduX>J3Bn%ga< z70?#9e6%h{F;J+10xlFVN5S0R(`rVe8O?e%GqTnT^6!^OtEV?J|M!3I&1f`|QvAXD zb~5qT@!P@e)0IKqn@PT6aDI{*_$z*F@b*<^kT++Lm!?@C?fP#9{oXqUZ(m;q{i5HA z^;7)8`;Id4SCU4bw7;@lTt1Oo8SLMbsr)SmFTXv5eoqE@TZZzjZJqj)dyC)SnfU$S z?JLb7ugD+t1fB;miNkTE-On_&B#-)7H8$8eMOIp+vn4VZ-Lw2|MJ#hmr)*6AHE$f((lS(pJb5o=aj>D z8w8Dm_B933x2I11&{8I938HU*7A;Ky#qcbwJBIo(0p8 z`~Dtyeq-f|Wia7Bf9dM^r#4ijUSzqrzPdWqD*9hvn&;Ep>EYCa$EnXs!9z5YX8_EU zvf%wL3!N9dIAy;|s_5P$)qe7mY>B+^S+RVy0S|x){>ahM2E3R-@JEi0Hg*t54fp71 zV}wvnj*d2V6w1lb(Z)_fIXODo7%7yKqod&oSI0 zjym@a(;g9#-E$%<@%^r7t@srn!NfVeN zdeY4=$pI=|Nt>sM9P%x|b#z5?!G zuUPF}T#RdR3-;rY$<`bL`h z`6~ANPw<>(?ULp5>BpZ|)K%BR2%rhcm50AIYIB@jKx zzxMi$D*L@jQ_JARK~pBrg#kQ#sb)^<6i(k?04}HvU%w_tZ;p>R_&xdn(67$PeJ6P2 zU;v-ku;68;_H|FonNGi%{G<>f+V*MZ{S%zNzX06Y7BYYG$rfqs*OKJI-#YF%h;zw48z3h50cNZ^GCG&>KgLtltuGb z&WHUa%Tv$)6a3IMG%kaWFD!))f<(7Be&PEo)$m~k{5U=~ySwRm3j6PqTQT-0ClquM z|K6IB)AlW{U$KC+kbc~S%4-{z)K|l!L-p0CKvzi0rSiHJ4Yf`7D*{poh@5N_r2Z?m zNmIY)yE4@c?(<2s{Kh)48?0}uUU|~8I>>5^NztioDJg&9wrR>=H6LEJu%xPPK746n zX*JJZ1<^kzoj$y2VL8rm3u{hhDu*96ME`-JH1$_its0~NMD#xyOh0}7twewC?bFv! zx)4G8OSi-R(ZK63JQa*qzhZGMEN@)g2;T~US6NiM<0r}weoY(apHvRSRr$}s-~U)# z4V^>k+aJsA4}j2*e_(m)s4a0$q;kST^Ru}9b9UhHr~keQ(Y3c`Io7`-xPBFRi5KWs z68#4x^e565)DitBS$%RwAHnw~E64T`f4`-aXv6$kCC0bah`{#o&|nzPVg1oU{Z%kH z=06`pD~G)zqCX|DzSq1)3DKVuT;F3}qnzl&bMnr3jr6Z6{}8p``}rHAjqr0taD9*Y zjU=gmZ}$5+m_K3twwGhM@B286ap6Z3DgP5;`96JO+;rtvd5s6(%D;vEK9Ez2Vf482ojLyS{44Rk>LwUvE?>gWzZ%oA|GpVezl!Z43ZBRM zp9Ix+l7l-x%(o94IK3Pj5F5ZEfgSpz3da-L^Njvj5SpDL61e;WHS z!4K~*bia?ZD}H~1qfhujL_UX=)BF!B)oV_!t0JF~Te@Pk-HW7^H`c+GF?=`YFlT(4 zTg&ly~Q;flIbz52$laQ%e; z2gauOC+{ypxcmy@pHH&o6Mhma$@t#UC;mg^HAH{TZcKa);OhfpPv`w@$>(-U-FYL| z2Nk$|y=Oc37m`~Q!<+2r`=2Y$#qGZZ%crn%mmhfb*W#tsP4G6Xs`;zt*Dl3#B%|!{ z+WaNe;~JMYHdHT4tb%t30C)H&Tr}ao63mYYzn%PEkdl;tFfzqo(Y4OD;E|nEzdMn$ z#p*`$7nq-KUuEzUc~6@6r!eT>Q`-{JSgD^h}cW2_8 z)Q<>14ZAb#YsJTn37DUC_Dnq)unxX{E5~`y*ayo;@0oi49g+7E{g1GG3Ma?@m0XDP z$CG=e@(1C+7xSOE9>?c%d#1j>M*Neszr)Qx<9zuCX7?5}!q7hTbPK%C?6hh+f0=-f z4cPIQc-omCN!~J!dH*0OA1%V|n=+m$pU90QmOmht7giJfy@dKL^;kZKmD~B3w0}`G za1W2?z@s`|5E`Y=Vhc-e~OP8t0hIP=)a+i?88IU(g)gx^ZszV;`a=L3@s6NUU( zD=_{~CW`Hg+nGFPZ)`EPf2ny4m%r6Msq#tw^5UOgzp{35?ZR3Zi@Nv;4;6K|{#*7D z)^FU5?fc}ucx3@wzi}&;KPQ$~xbZuQiC+uj>c;Q4Nj^CV_n*%EN*9(F-izb^IaW^E z--hj+oI?6_r+ov2-+i6uF_Y`;&*bNJ;y;h$_HV_?N%=)^!_1DeWWxdYkW)U)|2Yqo z!SqCR{mRr8Ap88;(X(bxwck+>3kNFZ&Yn7b+BCSoc*Nnjl&UHsPkombzRcjf2Yqim zzN|`}jK7%YyqkJfh5hEp$um+Vl>EcV%Y|n-_A#D1BxPTczq%iB+HDf~i;kT5XT^^l z{i0j2{yT@H>`(Mt?sN1jvHgwD9XZi2#&#*eTVsPmQ|%)8uLhTI{MoUuvD=|3`;+p^ zar=#@v3x&PUV+O^G~)UDcMfI7Hz%4Wd3 zzWuLnHxOy(e)bc;_8;rtUBth3n3|IEa`=3R;~#s7<&fSS`2k{iE0O(7W5x1z zB0oti?;!Hi#PUuezfdeMGI9Iw63Y{_u>3b-xkbwVi&$Pl^j{XsyNLd~VtEJV&wPBE zkiRw*pK-Pm|K|N-{XSx!C&c;%FFJX|e0C;dA0FQl zeEs3zgX<6S_$Pet0aiZGESpm?c}ki6jxP5V@F@$FkoLVHZeNnfKNibNeueSnAHm?K z?Mq#K!Sw7xxWHJx0Y{*l7=58&%Bb4#(jgVaBfmHX{iCp2Ie(LapUC-&lrxZ6F6o!o#*nu-1>R-e@0M&uLI$VvMS6U#e^e70ELP2>y2^5WO9{p-c@7W{ov z^K7x)Am5+5SuC$1-@m$_m2>v1Yg}Hp@Z_bd+292uwUGSq#B5=HEGP9p%a%{<+ddLs zpKg4F(Ep6*o$-tL#%%oLIXiwZiGA|f?{kszEmHmnary0}eV3=vC-Ns)IcJ}Rt5&Y8 zYnWJ9OX_v~|FE*dVcjv!z>{Yj4qdWm{wd|3_VkOrLZi;T0fh@H*qL0vv+Wnu->_(6 zgTH<@|Ie6um@~fR^_Ky|E9w_D5P~^*9oz(MY*2}%KvH>okD65%9k#1Tgc1dE;<$Z?O)fhbm{6^Qn*N7zjVE z<@Z!G@)DTrwXf@p_t$f__p#q^BNcScb@H3_U^RX|(ur@FwN3wWd7=#4!s~E;gnjS) z8#$%##=+%@8wQuR)H>HcCKTw*Upw=Ar2MuF@4qM|{XZy(+E+-v@A2#7gyV-|BLA~k z-i-4fI+gwY2Wel?Y>e+)vAmPy&&^H{)}JK$BgOI-A|Ef7cjES&%d6P(VIgPAKU(qk zM}D=y*gs_>XMUoH$Oo{zVv%9r*&x@SB}Crld|%KsY79Gf5jnx%cD{o@vFkFX{${M- zo5a_@+q2&vX~lADHJ0zs$~%jk_9vRK{1{G-_1orSc`YmNBJC&NKe>RF_mKMW^EJjV zSUJ3wF=anQ>i;z>FNB4xDf_OAzmKx#DXA6d#6BfhUiT|!ey#WJm4+R8L|%&Jg}-y= zzj_~KzrT`v8Lu<7Ncl}h1?aDvnx%v1^0B^!@%3JG1~b3ViRB6W{g2*jS$P+h8wp(g z)9m+Moc9YjA6B&Ia;8k4Q3el?loQ^`Hu15;fA3dkGW=KI<3@o~e&U6*VC9_sj&8^Q z3O{u0S9g|UpTt$%_hBA#nOej6*V!}=BXWBEg@yc^3)9>Ve$Sh>;fl;8F+mcPZy zO)M|G3CsV-$`O{MUt{@t=cf22^Gh9A-v1jc--ea^1C`dvt5bs$p?x@y8nxo@6BUy06P+rScg(>&ULckyi2j{ox&4??q1}{Ui{-^c z|IcE136Z}fmX{Lw7h<_d@moA~=uT||DgSl&OuX}_^r zEHC~H%byaxgiS>Io`kN46C6VtSme&#a9%6YjkslzIcaiq}SS;@(`p1gp z9Yp^mvAj9M``Ic+;p>A-5OaOt@;epx6UQCo43AU26p_OE2Xg)XG<*F^&Zr>Q#|Ksj z%P%1H|3oZrItaJ#II+BEeJtO&QdoY?!B~E>SUy1J-)88q7~#F63bV>M|M_`p3T`7 zZA18Zo6#p{we9KjKgscZ!v4pY>3k0)Ir6>K`aiz^FuriEPm|-*$Y*2yLs)s$^jUyl z#mTks_0kpY>LBto3LN5zkvb{k8b`Jd$Yeq&eACF7qO z+^-s?Sbk!E>WO+HFX_bk19ge(*6f|7Ji*wtWil zHu)_~D8L_SUklc6#oOd&pD^+^e7v2=N3!x1KTE6UFK?`~A2~}6Q&+-5xl|$WUl-OZ zB=s+6^}DgWpnz7WdWe~jfvisgl*{Kv&|b2}%#dhh#E7+==Eoc!AR zxLDpp} z=E(;$<+oz|9SO${=IIBg<~N9clKR{6dFF^infVWT{~Y$<`5m%8uo15hOeZJH2YESJ zf9L3X*LSe%-{4oOX;h!cm#tV;O&7?emE!{ZTA)h`hZ_9)c>NfsPgj+(`ow6 zFj1HKbNWYr`Sue~bbVhsIcXx5r`EqX>x*g@tS0q}<#hd#Sib0#LG@vM$l&s{`VFVl z!}^}8<@IUw>-iJ7_Q62Ap#hfXxC_wya_59J<=g9vm;!ixyne@BKa@u9KH$#Fp?%P} ziRt8Z;GN4FPF~=ykn!uUtXniOt^HE#qZWDBN4f6@an?UU{r2*uLG9x`K~#UkAoUab zEW!rn^~w6HG;(|WPU;E%hQ+l_b`hL@9W2mkpwVop;XIQ^Df3WuR%NP0b@%l!0d1D&+Quq3v!-w^k zR^#-WMt?~LefoGkSN^j34JShvwdj;aTmdJy^LOeI>s5G-Y+5;9fSFcadP=Qbg+Pwi zcc#Q?<@+>bSpSKa@TM!jRJ=Zvt}o4?KVeeZ_S*xvRfCkDl4o9@>U7~;`{4~f@Nn|d z`AgtUV5tSHgUC|_aPrhU!n_3xCbtWqa_8H1RjX@P!i!$)mmH-$gvwKH!L6S4>Zjy2 z)${9^CAOSCyr6GkeQh0m!5@|5^|{;`R1RjfUn~Sq@K)EtQ|3PZh4(k59?pkXbu`lN zr}OJ~*9ARTzl*gESnFrMO^g27*XH*6UV4Tj>)!-lU+uJjxxONr1)E~|t73U6S^s;& zBB6c_kv}GucM$nZcKtA^zil$E|KP>K@;ixqnONRU(a=KFfYNWE$FiM%eu`kMZwgRf7oyLs^Tw~r(Kb&AkG+cMPOmqA{_egBaEzFJ4R z?=!(GHtbnTl*WDqSYB}}i;w@lVhQ*CM^b+w)^E+AU!F#v@RQ6SZ_e<2!|n|7^4nQ_ zr2VA+x(weRG}3$@F!g)!u2~~T0-(t{|MxWG=GJHR; zYX{u^gPVl@)tlk_g8dolFUatHz^)APX0pELl2e84Gc$ZYusF^8^@)9q4Brn-W{`Jg zC_ho_+}|^yLVFBA{DaN^bB>t-AcW!1EKbIU48#dw<-kJ~q{L0Erh5w8CPv3!8E|DKgX{a&(u^O;7W zJh?qC{~NKqoyZ?sCDiXB^7qB^R+67yUCrpT_JO61sZV53_vhua%Vy7>1z$Me%x5(1 zNccIODW9B|+y&cr*%^$SD<9%_&fLj!kD4}zHX&6+3(-Ge4Wm!WH^}|*OT_ZZk+^-= zpDEODCh}**a{HkfyPq~+5wG9vCHHrJ!rs3@Qyo2neBboAgPHq_r2WO@{?CX*nD%uh z9Q}$b@%ZQDLsIvz$o(JZ`{c`4z-#%c>*(uas#cy_=gvXcb+nQDLmPAVhurrkRKk}l zj;NYj1}~t7S1gluk!>5fzxCdsO#6tuleGWQDMEQSksmmfk-PlUCx?CSZm{dw~+F`nklv)`}{M0`kIsu?{_5nkFx8_ zU3{ret4y6W?=X12%z1@SO4*h3_I01IcIqfFaeTZtONg(Z_}^Dzc_E3fjVl;^w|=`@ zo-w0r27KFOPT6dGiFoSfcpAzP$1(Uw`H1L0c08l+)G}9uD)#_=w7PkRKQbMspqFs+RpP=6%|#fC$MHto?GrY z!!tndBKCXiM5g_u30(x=GgXY7soyg`AbMn5OxEXrBi8q<|HmT?qUmgVN&P1zh4t@W z>OMcf=#%z&w8nJwU;JZgGFC2~I<6!ag3GJl( zWny`P%r9Nf$_YN_`Gv`I?QfjIx7W%lr^A9e&tCzVU;BpDC#RH>`L9dF^K+G?{qKwA zt)%>&#PfGuM81ZV_d)~g{E{TkS8vEZzf9VP2>w@DeIl^h&9Bg|?`8y3dKR4@Wc#qmtSli@LP3_i9 z!R_0$mWdy7UMrCwES7f>`7*J*;A3a}*L%@g;rcl%&GjLvzc=0d4L+eI-S>;I96gN3 zpYYr1;Mn=YlFq^99p?-#@5&%Y_2TPif)D+E@bW9}8eHCK4K6nx7t7)KS^E9PROS+X z9??jScl3LodRgcnO+@~pSWa-p+t>oJ1!4=t7KkknTOhVTY=PJUu?1oa#1@Dx@O`vE zo`JMrWnW*b`FO5Hy$olrCY$<5y>igZ)3kuJ{`(uI<~vEFvu{7r618pIel@!ht=N9V z5^CGnerk3jTCx3zCDgXD{nYG6v|{@aOQ>yQ`>ENDXvOv;mQdTq_EWPP(TeRyETOiI z?WblpqLuse7l=Sn+Uom{ZvDFYO0Zp}nE%-Rt}`g?#Qu}({-Z#;M@651PhkqX`t>7) zTB%Chf9TpT*Y&9{sO-i5tINNN)u~Qw|JeT28|3$5|IzcGy&4NVu!s-w>zElXujKmL$PwXRO~@$0tVg`%{hZ-1p~ zT_t_{BeyJ-9ew=Su3rT;)zQaK%Tn3X=U=5(s-uq|(ZUq=^y^os)T0vH-(w7gU48zL zLakIKuAkaMWiPfLQZbvWll%5_p(yR><5#NIRm%PPk&8uTM<0K#*Pre7tFT6O^v56B z#;;p{uIp1SRrd7bSEW{}6W32|p|Tg-PsM6fC$=B8h00!RKNYJ{o!EZV7AkwO{Zy<* zbz=KbTd3^C_EWJM)rsv#ZK1Lk+fT)6R429{wS~%FY(EvNQ5}8zAzGNip8ougLZu!R zef*xn6n6FTBZXS2O7`*7wy5l7-+oA?*{+U$``x0HcJ%8Nr z*3!41Zv9%#*L-`n{r+v;_Geo^wx5m#vLC-Xtsf5ltJ{8EeWX=D_Tyix`61*#-THOy zpX>GOwqI92+xFLOf422=-G13_{|~)>UH^^kr(;3={#&Q^FvefH_3P>*tpfDN&${*N z>TAIdVf>Zt_UqQKs~_86#{${Ue>$xn4*65pe|7bB?We1++x~3p>*Ckd*TtXh`m^2s zY~#=M`gPkM>+4uRfBdUcyWM~4{psuLm7u3R9Pnq`{&D>}7Kr^%$9i%6#r~u1KkMq0 z5ZhnJdU5>5{uBF;js;@>(Xn2ffAWkCl?>R1#u$a5sqcSCseYoA`}GqfYFmB$YV{H= z{rV9pN@<(@`m^1BC9}Co*|(qD6s4WqzyG8J+f~Xwe&n`AWk=utRBEL<*{>hb#whIR zw?EtUD}eT>L1?&C)c9@!uI_+@Kk&)2UXu?0&0%KiE!0duG4 zK7Pa@lKZKTU#>p>Z2kHXU!>IU+^=5>uJ7dB$B%rNWDe-#m#NKvu73TE9gOe{6T9HpQm3x5*Hls zXzte^5NMjyavwiRgDlu#ef&n2*S};Nf41w7?H|n3#b@Qd|BG=2JsRKt32G_vc_H|Z zxZr?C~qBLje*Po`~fQRGyQ9w(H zPs@J)q1%34eX(7F9@Y21TyK9+ONr0Z_djvDL664u2ep*=yzJW#i5nL1X!hG5u%T&A z({DdYQ*yAw`uQ(dJ?YNU$Dgj`V8^qM9|db@nzOQRzcdXCcsRCyKtrWDO`m_1rsQCU zbHDyzIMbaK`)@kS1UsJl{)2)6O>>q${xk&#Jgi?o3Rsi)wA`;>j4SBTIDZ7Sl=!^d z_a7t%7VxM({(u#wIZeNQl&0ihhjYLFU^vsA72{85nPA7WZ$A{Qp=r+2Z-1JC10L3| z9|f#Qd|K|;FUA%0Xzt@jL7@uI)5k9?Ht@lC{1(_$!V_cr3C$AtpuYd3z;%gE%zpji z7JMpdtl*efTX15ULwRZ5fcL*N=ktg4{a=jWGrpoUzrU~bf1U;}e>fd~{CVkqi>;sT zZ2xh6edI4x;)p)~5|s%~)yFR=RN_!vzl5;_r^faZ7)9bxY(FGnE&r+d_RDtteoQh) z^zqBo=0Ep)(0}MY|E#O;H>$*un12al2~LgeCoqb{q3qjFqOpQgzX$nCfGYSQef%hR zWr8!a?>|5E_Uq!;)fYI0#G%-KvTc9e`g2`h!dV5U>gQiUp%RDm>qio``A^l4U)}n3 z_5GM+j_Bi;sm*_G?$?j}pd^my`@ckGf>U$9ek4E@{7~-uUvR9VGxhmLqGAId)3^T* zz5c+a7M`eYe_^qK561NeHkI(i*nUE@1U{&5KNPqw(TV!?i%JcCOuv2DnO_$4Y6oSOamk)Tz<59#xl?fQdb6`h%V{GwI`KbHIL4~|uIX71xhB3OZs>EjPv zmGH#u*Dq{V;Dg!E-+`MdJW;>>NLX&rgK_=2ZojzwL493xo__wzw*5t@f*;ezAG|Kn znc2@jNYt#r$CSUHetB5mPgnbXd&SwL{_NoIZ_IA}9cPgG15+(LQI-GhHQB8nok{A? z4*zxMgj4^ahLLX*)Ba7dQE2bH_Dt$`=hfS!ekX6vbB^0G_(Nz{=l5C8Ha&mI)cKkI z)6btMQx${C)3-k%);nNB#vYODbFGrD-_&fsuD)*jZ`EwSuD)*j+cn!CSf6Vs_p{?% zl0VY*e+f=Q{8QThPT5p1esuNgHS5>a=gcT=zxy=(C$N5!YpM9Bbo<}dY`;%mZv>qF z`887vm^+$YpF1(l&s^6}1Iws8$QeH*raIen=Skzgd;>0jNb;|%|32@(>5v6GF4=lt zp?OAu?^uunEtin|ucqH|sh)oKWqSG@4SM?BD~Wy(Yo$L&pTG2F2a&|}2eDH6b7K3Y zw@na9Y`-8@N`FrF?T6AgE`TK4?GMmI=9JRQ*zriV+aK4@&?EgLwx6`g7=_q=j5(x# z#P*Xm8KV%}k1>bzkJx_FCSw$0`!VK_{*itAA?Y@I74+{vc}tVu*RLPRSL)Hw=TEnO zU40K2h28AiUl+fwzJk#_DzW`M#!%SJzWo#$?NQNhzo#&TUH$x}P^m{nA3ySxCcmqX zU$=f;eR<4Yjoi1t7mfUW%s-Mhnny$5e>{aL?CRH#6l$d^vH$4WFWdT*OO?Is`(JE7 z72b$W_T!hdL~X0zezkguR`&g$v_x$iw;!n)4r}S#Ppf)(`+c_CpX>GKy8Yw!>sUZP zespR#;`r4wUz)Ff1TQrEmF6`h&=_9IcV0v`*Z{hIIp&U*U;+e&m|2=)^d8~B)h z{zQT65}lZR{GwI`KbHILN5R1g&eZoGL7@_d^y^0wwfRrg=U=yeU41_$nIp0NWBbea z3x96xKf3;tZGE0mx!?Ny%hku9tzSRli2+8|QDoO=OPf+YiZ9 z=Q}t1_4}G6bwEFUkyL&B$@=!=OO*Sa`}mO@VD9Yf+dpnUM~T!=egBoJ&UbR`KR%O4 z9niNQlB$nCS>Jzj>(|xi5y}0I?VoM?%kjmZt?$2liE_W=`sM7!pB>wew}{;DT+d&7 zH8#}mRl9uQ(#A#Ado`6#s+zRVxTUqr8=J;0S>CwUg4&f0d#$Xgub#hXTtm(L`szjF zR-Rf{-7vm}SSg6Ut+7|b%KFBIE2~!4E~{QOf2mu5zW*W86s2vh^QUh=C9}Co`u1~+ zQrgLW{YuStm9pP{F3W}uV1(Q+14jas%^9HziRC!TKfJ=N>bZq-+oA~;aE$*{aV$358hvt>-clM{YVQy z?)$$M{1D!MmFxD8?Wbdb?DxMqt+(Hwr}r1@$M(~)Kop+u|JZ&y7Kr^v$9nPjDfXY(e{?Jm`;U(G;`|f)PwYQB7Kr^v$9i%8 ziTx+`9~}$C{-a~PIRC`{6Z?;j1!Divv0j{i^!*2E5um^RNVk5i=7(_q;D_G+A3FZn z|8y*%pFebJxBCxW|JBux+plAR-0%N%(8vC(AHT8vbu19uU&nfJ{Kozh`;U$V^!*3v zR6h*X@5SxcAy9YxxM9G`zk@%~sk!gJy8frDFS2UzWBT?FUYF?1+^-*rU*@<>34Ad2e_i|Q>IbGuc%nXk!eRp-jN=~#ww36_+_zt@;}@|K z{Fr|H#r6wsZU342_D^>Omhe|5IHDiFfvs4#oD9FqYud*nR?| zNF0joCt)nXsj>Y8Mv*ua+fTw+f>UGr35+6fD7K%3u>_~a_7fOI;!y6}4@sc)pQ?ZT z=`T~}Nbc86MuU(#UQ>Djj*;#ws4GxlFy`^njxKRdR6Y=7P-WPWGgf3nS=jJ5pd>gVrl z*;-BFPrBr)S@OYlNHFA11CJ@@e=4w2kXef)Cu@n^^RgSUv>Z+-rdT!q}(xnDmANb+ay<42N++0*s$ zv*pSD(yt%MR>_>7{rtr=NBT$h?I+!2Mj`j@j~G0%KXRWxS;Xx5xsM;QfFytE+_Gi#YyjHpTD^M(xiD5V*iQ# z$KwvtyRrYo{v+))9);L{V*l~DgY<6fKe7KvJB>#n_Mg~)JnkU9oBRGF4Vh8M{`DWz z9O)nW{7F~IDCpadDNg!F_VFX>HhUGaZ$EEqMy8U$9pKX0z{&m~0TfeS;+Yp zETDh=ugjmVz7G1>fA!<{hi?CDsUZP|LfEq&tJ#(kNro-0NXr1(_n)}^It1$T7u#RY{<`+l)z@kL_hI~@Yd>9mUHj|S zpX>VBwqLgE*X2*Q{krE9O(ewPy!uPRkUTEaoH=noPuQ$YSZt66?6j(=hocbjGYtv_J? zAEx+M1OLV@;qY%vi6;NQsLTHY6#qXw{LAKlo_{pV`LFyl=D(BTZvy^1LgL?yi2oi% z{tIuy`Tr4$|3$n1e|i_C{MY;*oBxg5oN`ILH^0v22P35TZ&J+vJ=@{&|8FS%Q-Oc9 z$&O0+2~M&_5%K?$F8_~G{5`;%>9df6-2u|KC#lrvd*x zA@OfT#Q)2>{QsKbf62qYZ2tH0&&9vXJK4!H|LuRl`Tutm|LMSg=eUsi|EbaR|F0;Reg@8tM5Zg-QA@KRx(m^B<4j;{1QO;dih9 zpQQL-1^ngz=HfIU|L6lY{!Nbminq9OL*oB5`S?%q@8bU>#s3=M_q8)1{s9iZ#o-?+ z{z%0e|J&oSz2dzu;s}?+&M2!h7-^P9Bo~pRVZt zF8(fx|8>CcYiB_GeIK&%k2w6q4(@ii;D3tZf5U@c*8h3@<}k0^`0M_|l^YWOXDIr=i~nhg|KEV$*Uo_W`qZTv8ys&fCQyKY-X4{`X>d#rziHUG6n(f?iif2H`}0sOvp z2K4{dQ&{}QozeKeHvVTQ{yqlu2kRBBBZ6C7ou;TyB334SR3=aSE6#x5x-`CE7_^m@( zeCAzFxjw%q2SSQ}ZT!zs{2zGm%lbc$-x%iji|@w%{{qGTA>gm*XL%%aWt#shp3LeY z9{)$IT+VArEBsp|o&O#Gck#bS@%ICMgKsCUG82B($o7B6-O>2JHvWH5{2zJn%lbc$ z-{Se_sS7FoRq?lv#`phvDE^NDe}^Lf<*Qi!tqS)3Px9lT@&B_F{olp^GR6N1;PAFB9Q z#oxOK`~Pbc{{Z0c;{7xr|DC6@{2Q~`{FnIO(D?s3ivI87@1^*^0Q|mo2E<=^8jBxs z_=k#rZT$bD_`mevm-T-hzd3C2JI}wk>tCOs_}9SthvtyhKcI-#KfEfx{vkE;bk~2r zN%5}*{JkOJw<5y-nj(I8{o}tW{xbo8%Vy!Me=*9~{5Mqb|1U-S?)tyCD1HR^`$EER zMufjt5x=|s?QM$xEWmGW9uEH~BK)r_;&<17y+iSz4ftC_!f!={{|!a_ZvOA1_|F0S zB@;(6_pwOaW}5#X=egTy(Zv6oium39_aBP?r+~jdB>v5a@c&y8znlNwrTEVU{N;rq z#eYQj-%`Y1_c4C{;XR7~Jiy-;5`HTp{NE|!Z~ZHt|NSq;e?H(J2noM&cr@{EjB+zh zpdIr3w~POMioY4~S8NfE|CK0mXj-;BOBJKZ@x2_k3OaA5#1m0)Au5aQH_N z@xP8P{(g%8B0K)~4X6LNBEr9}G=As)PvS(J|Jyf8jd${Z`pxoT{^vVxo(5-?Oyi&8 z(~FpK6S`>~=6Bm6+EChw|A_K`u^s=D!r|X2k0$@Gr^tVC z4W9pdo#Our=6|~RdAfl7m!Hnge_7o85BiMrtC0Brsr3AxGymg`e?Fo3F9H55L&|?< zMEtL>%m1eo|JT63kEekA7oNfLZ_bIv|5f=%&*S+2AH{zu@ZS*<|0p8`R&Z>(YC zA94Jb4shj$l>g6_zW>kV|1T*17T`Y_692~ZX!75Ny8M4h@qY*W`*;e-e-p>QF*h3g zs{Fh8|0|0BXTX1FNc@`-@xPHS{{s}iu`cCbHvjYdTU`8OH=>&?$G=s8*FSwj@m~)7 z*K8e5{znnfz<=LIYU^K$*0TBE$%te`8NMNPXY6P3&+33@lOLE?}Zfq+WhBH{8s}1b=!m!|HhA_>Hjv> z<^Nmi|Lb`8m(Bk?|0q}ZUx)I474Y8`68~mI{BNene}5w$|L0Tu>jM96pQz>k$}`#g zZ_H!;zyFJ&8ULTJoB!9N_^$^36WfLp|5ilv|C{Ubzdpsk9`NtuDPaCDzlY@?ar_Te z{@3Pz1B(CWHvb2XV&<($yEDyylk>S1zcI!C3*f&y zB>s(`u>Bv&3+^@~{9EeszX`=(0Q~!S3dnyC$G>@0H2Ago-<0CN2KX=DE}Z_~jEMiO zbot+i;@{B2zij^J`8RTf|II1>Yk~isgTm?m&5NDuDmUKwosi;xYeoLu=YKY%_%{On zE51_8{}orW`5$roxAWzOg#QA?`@in|&lVK_bvFMY#lLY~H2iNP%|HJB2burcisHW> z@HZEQlmAde`EOfY{99A}HvsEa(j@!tmc%SVJ1|2IZ6{u!x@e@BY{ zcECRn7XFC%-&q&`P89zgfIoR?IQ&}?;fK!^N&S)azwY>dB*otj_&Yf#?o z@&6L=HysuZ|5il!$4KLMp8s&?f3~FfH-`Bi-#iV@u9@cl3+`j*e+)C4{3k#E!{INa z_&4$3m!1FQ@mt*dm#>q`+WZ&Bza_r^vn$2FDd4aCT5bNX@I;RPqgnn7zTwIZ3IB!C z_kTG2V=4a40Kc!D0sY^)pT&6q{p9bW=XBq3?h{Ip_Eh`V}{a+U;`oD{RcZz=t!0&5kK>SS)vi@&WvhhDu{A=Sc zruet?;FtA(9>2x$Kiu%QkHq-;?6s#)Dth|9SjqnB(sojs1Td#lJ1!x8`$x z8j%0GM_B%iW7z!Hw2&(|B>%reG5@>x_oDc>1N^>r2E^ZTJBuH2_=n2>wegRq_=`OF zW&NMWZw_<(?)6^@#lJn^@2=$hG$8*yoh<*xWY+(S7jfl=TgL=I|fO;vXvim&ecD{~t~9-vjd>#Zx$*0^;}Kn-vZIvC{J&9R7VM{(Av`Pe}O9 zi16Oi@%iO zzYp-YP74RW!M*?97iJ;#e|zZS-=E^YAMlqS9u9spBK&*m;y-}me*o}Tl!t@gsE(%p z`;jjG11bIo0lzUl9QR13@ORA!2ftY#4gV8#@tYL?uK|De%y94_twRK7{&i6;4hgK4t^97{(W@uPoemK3;26O!f!={e_v_* z-2MLv6#od%{EzJXA3y(NMKu2>KmWts|Ja-2-x2U5ex43rxMW)Y(fJ#8{>$X%znZJL zxC-g|=Q73lKllF6G>U&G!0&5kK>U@DviL0yKQ4xDh70~OihraBzpVfB_|Y)O@8177 zoZ{aZ@Ru&;{4^l{#dop%8^^Kze;;3NNc^|x-v60S@h1Skublz$xBiyJk2w6)@$uep z!Cy}C@8ZEP>;F7{bC~0AGVuM+A5;9J0DtQeHUDq9KUDs&jsGVU|E?bVvi{HGH-x_s>aGb#QtfWM-a^V5L* z_x+3IAMyB4;>r!l|1X~)dRoipZSH{t{{FR#e-_0*7VsN<6|Bs;fcLV-O|1X>W`2OGG$3MIQ zLW+OY{@?ZgITZgmkN?Z!=l$Ot=Kf#43HJY^DgNJs|Ci4W$N$ZU{J&Ju|BVeX{-Y@V z@xZ^eR1JT{+id=`IR1;4api{O|5qvYf8E#O?>`+&@ms+EKuG*s4bkMk{dM_2j^f`7 z`1kRI^H!$oAM+iSf3qqY{HpxB-~T(F;(r|YZ=b{YX+ZpZdPfn({{g!EA4Bn%c=(si z|2+RjuJC^%#s38GZ_Evce=8#X4^-qIZH4py2^9YX;J=H{(*gaz^b0or(K&4VH!bJv z8dCnhT6+H9x&CqEKS}XF3H%q#gxvE&!heu1|MMySiNL>)r-1ke z`dI#ri26TO{>!((-#=ME@&5t%?+l55)EEu_hwAcQMe*K-x+>r9$&lSi2F8_-u z{yzc#MMtaQck?>lu_DUi zAJ4zJIvV_k>GEGq@lW#bFPr~){t*}dynVu&|5WAQjsKG<{x0CZ_?U3w->8j-|0#<6 zyW{^_ihn=gzlYD$0pq`)i+^J!i@&#yvujBCzg2Pk@5cX9ivQ2Re@{sKqb3&rQ2GB< zUH+F*{H4IZkEekAcm9{n|A^y%sPL=u@5cXfivKUbKML#l*NEc3Oqc(YDgOOE{LAKl zo_}+g^WVG$p8u$$_@4&;n~&x4R6zgd{ToHZ|1?GZ6We0^D=7X0fd9@_YWTa~XXD@E z_;0P}$_*+1|3Y#6-?RAMjs#9M?`o{ta&ai}#PP#y^Kk^N*kZe`1U?KedwL ze+KZI$A^R8ipc-V74aABi1}}%`2Py{TSLNcoD@y}KV1=j#m*T2DvJMafWQ2NaQHVP z!vAAM{3dz-(Q1mn8}JW=gdatO|0jz0dv?S8H&Oh52mI|PhQq%V5&jv9`1{EEuTv@h zX90g@RXF&KlcS0MnTq%ecfkCgM)5xf_&Y+vZ$^aw2u1uor(^u5Q~b{Z{v`jNKE?hY zMTCErBL40*82=d*{|kU0U9yw#zE!6C|NQvIiU@y&BL1#3G5$3a|33hK&u>GD|E1By z|B;ILUH@N8@xKW8dmjr2zZnt!*^2mG|38!B?*aU!zY7OHiU|K4Mf}!T*#8m5{}SNu z3kkm!5&pS~_}%gESrq@vcKmN0PX05NMHBz?bn%}}@xKE2`+pyf|C;H)3zmhLEB>%rw(f?ii7gGF_0l%-E0r8h_!s0j2ji&$8#(x3Df0zfqtpD@)EslR| zM!Lx||8D<(5yd|R@E0iF|0&#*<=^1eztpVe;wmKk*D3nHi~kaee=6YjwKJgqcX0SE z4nHLx?+q9H7gPLY9{jTY&*MkK7k|p~on-#=Qi^{X;4f<8{4^l{K7P6NA6gjsIs9|8&6LbZSWce=6Jm_ngL+ zn~r~odo|0cuM{&y4p*9%+wU*cWo zUlO+VKMVBEhHWqYXS@gc_P-(e8!G(P{127zCl-A8{lI@yzZ(9V`@bLfclk&S|EQ0? zANcb=QNy4A$@c^QS&I12{+{4}{8KglpZN6q!T%PYtKr}B^X~=z-uYiB;Wrn2@%_Mm zlOq0`qs5=V@4s{3f6>2D>Us+{>K_%um4*4azh&bu3I8EPz3y` zn%(jL<#hc26VLcx`}%K~j{nK`kKFs8Kc)Czh5MfaA>IE(5#9f-RJ{M``u~j-|3TnN zK0n3omFfDgXg${dja^v(_jzfS{eOV0|Gkppp8@{gdpdWW9uPl|&*J>Q=yZ1ei;s_V^MB}Lx%p33|1W$I`~R)f|NjO4U$K2i>z|gZ z;rH1o!+~QJ{lDot{Qj?-DgHyCu5!ixub0dJCg=aH+i`XcDgUjfIR0_-e;dVrgvbA7 zbn>i=&3zk}lM1^@4OBAonhMD+cy<8=MMo#HU{a^= zmz@9eJPsHC{}shQ8~lHOAEyMw&%-nL>tDqARY>@6(jEUiK=J?E&i^C0>oisTE24@2 zDqa7-m*SsdW5xb2oBw$KH;1|ZyW^jS9Q;#1-!5+s_`iYuRCoMiJ*^o3lJh^>{{JxL z|1I$U#Gkl0RrG%|BL7b+`hR~CU;jKv@lOS;m5TYluz=0~7U%y3{J1it{I@}g^!Kk) zHM{da_f!0HJ^n8n|JY63jmhVKSAus!!msWBzoz)#2LJC4$^TJA{y$&Q|0_Pi{{I^X z|BrUMCBF=)A$}^G|C%}fH!fAof2DHQf7<@vN%@}#{@>ahPX4nv|L+*0@z2e=a{P|K_f6{NJdHX8gZU(f{in!S_EOqxcU85)0o~ zyZ&jK#EyRu=l_NLyh2F*e}V4&&!ZIo(H{Sojep+%4aNCSUpW~LX#4*Y6#sv~|4aWI zj{lnx`Trta|9_I=FSq@l_fu^DO!GfY8?ydyd>u{xSM~pz@p%0AIK^KH{*PM1;U97S z-}MStZb+5d0F z{ohj#{;5xm%sU4BpZKZn_{aF0TKuEDF;dSzYWsf|<^MhK|Ng&laT+lH@%&m5`Tt@? z|997a{)yuMF@UfX^Z&q+Z2mX7{9p7(&aNT(|Ava=A2uXS_7pPpodBKyq>-&zT5N0$$4hTK>R0D@wn_Uq zoM%5DVju5ayDTNY5RUH)$4bxJIaLnX8VA_t=lRMR1;;DA<(%v2AvnGb9Pg=j>LuGY ze7v{8sgGmAi{u2E2FaJmV|0htQFHhrIGWmaNg3bRHm;Zf@9WMF*FBJcAkpC0^ z3@850HEjGh@#Thu|5n}c|KBM7_aXmP{9icuQAF!MYb5iZ&;S2S@z3!1zij`{`#&0{ z{y$Xt-@5NhrRN_L_kS7b^N+xPD)MT`_0Mw-|1&q(CGU8Me-fwK*FSf#@gF$<6^xO( z{*jIUq2j-Hn{i70|1R5(i?sjujsKpf@&5tjzwVK0^S?a5W<=w^TIu{(xRKpfcmDfX zihm{?Z&JMfTR4a9|BY|h>;Gc@zFJ8A-$s(xe?#W~XMLrV|ID+$%1-_x^PkU9{!j4a zKiU3|_kYBVe|ULV*T1s)&lmqMQT!i5{8v5`&iKcQX#8`MZv4MY@gD&s`Qj84mudWO zjAG*-aq&M?{12P>e_S#CpU6)97w?Ymf4oTfKM~@;o4-y8%0Ex=T6X+{UghE{r2K!I z?)A^B6n{U&f5Bh5b}HgW5%vEk>&E{J6#p#1O5$HS|8wzg{=nkjJo?~#mHE#$(2I8d z)9HCDufX?zdL91D_S-zK3gVx{sqXcU)y0ng`1Fvr|9@9*{fl<|zfS%CBZ&WGNbzq) z6#q*V&(0m(G8j zgPUCc$BA((d`G1ZX#4+L6#vKI|Al`Gr~fnR+5X=LEF}Jy>H7cM6#tRXNS~kLhG!c8 z){JKT-}qKB|M?6x_yJY_@7fcO|Nc$!&jZ zDW7Z?z;W+=!GfPTdKMhF%g={@-usU5Q|m8*d!DYF@c8dthyUA_B=QzO{F6A<9se2K ziu|uXMr!_BJO1CJ{{Jb&e^ED=r?9m%<$s^dT(R< zKg7kq$*-#lDgSRGIsUun$u#l*$29Q|$L;tpneN0T*_wY!6aR4Bj{l`D{= za9kMwaC}JPpY;FlQ2rNs;$JrZ^Zsvf{XZ{Hd;RA-aqt7$@&6&k|38TTroV?1|0tsP zuhWhHeu{rCnA#Vo*!-FDU;D0H{6{qYm5u*Po)^b|@*m>(KM#)E@!yQ&pKOyaisS!Y zIBv&(@A1xffo$7e6371&aNHaJ%`2RBL5Y`-&EE>@<@^5yaJ&M_C&xSR`x|KA}w{vWdYfBWvGbpJas zX|L?w|NeyX{~6@J?vV1I6;b{>MK}Nbm*SrXQ9|;cZ2!mSKXaJoKZyVJ?PSpV59j@l zt)-(=n+ ze=IKk2l#SB>i;%{u*{`DK7SbI7LhhTLE@i`e?F%CFZRU0Z2sp#nB4e>mxty5+VTH2 z#XkV?-@dDJ-O9H&)A*l1-;5~!8+7CU8;bvE0O5;M3@j6VYYZ3v-24Y`pRo9sjsFDh z|BacrAO6z8Uu)GEJ3;?nagbd9kJ9x27T5oiatkkH`~RY=o&G;LANT*~W$6FT3#b3@ zy#?R@_=@ts1meH7H=O>@;^IHKW*2tc5>ozem%RS*_5Uy&w8wAuAnFT<|I+8f!H*(} z|CPG&{{`j05^O-?UpD{q@o#*`j(?$O_AeykKaMi(_+OXC|CbQ|eIdoa6;b>*O2x&GCT{{rg&UqSqvFND+o8y7}{ zf0b_hZ%FYU3ncpD6cd|i{9n8qJN`F}b(wtN^N%dWzpot;9~gH1{|1!*lkDsN%hd8e zZ$|Tc*8kgH=i(|P{_oTs|8GL^e+}{9A5#3A5yk&%-S}UR;y(^ZB=Iks|M~d0xc;B_ zkFc))Rr`N*1MdGfa`0Ddz1$cL{eO`u*Z;S{0!-2TzsdFgq}=|C+5W%a=Z=2i0(||S zq5n7a`~TGQk8NXcJ2s{K9}gsTC_ev{Sf3sLnOy!)p1|dmkm7%H`SBl%e=Car1im51d2g^K>~;@_6yPXc~lJ27#Y{J&&(7QdMn&G=6n|27o=d=GwE|L5@= z!yJG4Se*a2qxcs9ev9|hfcy_6S^m*AEdO=DeeCp{v9d)#emh<&Vcw!_hkLwxR#B7Tnya|7yKhA{v{s#vi|SGpFdpj zJL^B(_n+)U@z((UlIOVVbj(;L|L<7B@^5nZoB47>;(se?|L5@UO!3zOR$n^<;;;A- zi{Ik#<6`J0%lKPv9_w7U-mqC}d+s03$p3m1=>K1I@}KtopSleGPc6ajjo4LqJ;r>@EW2KX=P35S346h;2ksSTt_ z_;>sN1m*u^D4|91{$KKOHvWxuSo{TJxp75E@xQfV{wur(^FJE%KX*<3cffyLNc>xh z{G*|d|CHt3``?>;_=ov#-#j(;s!aVK?|fE7_rJ8~zY8h;Z(#nru9)*vMf@nD`R^v_ z`ERHHcjJFoihn6!^~GsG{N^||{!K3adH)D&{#!Nvjry@pKRd?3KlWUBVcDke{MSn% z<^Os%|M~D|=|BRne|6)3V-NqH_?PYfc{nIn;(s@a|67Rvfq$rt|9SjYMDc&BZv2m; z_?H0)692ON`{F;M`G3{;?|XQx6aTwA_{UzgCO;qIzdNM(w^ZYQ#~~m8r~3cmYw`U5 zSP%aY{}pe9pk9cj?~$-jm}04&uLfk8t{b<0AI{Kc64M>irXj=i}ev`hOpr zS&sky8^=21|9u_&x9_?(e*=jBl2=0N|5s+ne?EiY1ILdU>iPea<=y^&qKAKo{|C0ZFLlTNQz-uRpiQM=J^vR`{3FHqch`TJ z6#q)#x}6`V2jsuvR&M;y=l>EeuZG0`c8cTwil?yumpS;Ge|l#A_7ML){o%yFu}ZD~ zMQ+s=6~Wnqvw)gAvEir;@j`Ev6g^6~Gie{rAx*=*xf{F|0>&ZIRDA|KcD~1i2PqU z|NR5|{}B%U=5J_?rN$FHQsE@4lUj|A_ckj(^hs zAMN08z7pl{2Jv6|aX8mM#zPtWAKTTp85eQ<&+_o^iGSJgACJT0@;@&R>-tAE{@X4X z>%{*t6#qsL{~c38n*WF>{?FBo|JfA(sX!8me_8(d_(u`(uMq#Kkw@DDnEy%-e(?Y1 z8R6uA#O1%{vxnyW-}fqxe@idL_)nntH?}RaLpb=Yi2VONMgMo#KOIZ)p9b&?C#vCZ zxr$x?VC>D#f7I~hro7OX6{QbsFF*ce{lCh=KlSIE=bdKzKlW4Y`Ttuo^ndB_zbDuK zsrr9g7xw=o<$n`sQ)^h)f0ruam-K-1CH;S>zJF#N`FY;WeVZG`f1H1lVQc@p3IFSb zt^F_YuJbPmTl-&P_UCzL!?qXyGu{Jz``-}#CGh$eH~$|``9Iy`|FZp`uesMo!@sKk z_x~CD|3Zp?Q}F-Jso{)&%!vHISkgKGAB$=DN4;|WpDO?E_^*cYzd5w2V1(NEhsTE^ivJ50`FG>Ln&MyU z;a@iY^ZX+&{(1X^b^WW#zdQapiQ>0c1|&n`--?L;ixl}UC(r-XQv7EE|0Vz7@-!wc z)BJzo9_;wvyq=B!UcTHk@$d7K3eK(DD=6_dE{AUCI zeKXbYw~lA?Ke~a@!+@5X;U#lJPQsq1Pr{Jei#5%GVSBL6j);qiZi zgTL&N&GXK&`NurT=Kr2U+5C?bum6$c{Ff^KZv3yL{BHyNm(K|2`rl|_{h#-bu*SbF ziu}9re+tF_QxE^L`Jd$(Oo^r*Pum_*pdk zU#-Z$8~|4V^^lU3LM6x}`6>Hp56_%8zgH$LF{set(TcB7kF z|L@?-4JrRWsM!Cx{{K^oe+m|MC8BaqAy>{|IaR ztL^{iIryio-X!m0@PFc`y8XYUI{trEuK(Be|MMyTBfLh^qrBLDw|qW`<^zc`oT zUjt5R@#{3P<7UeLMO(7Zzgk@WFWQ^yS3}BwJ1DOIbo2i?6#pe2|Cfz_KE6%W^`Cq} z8GdW~|AiF)&cI1xB*#-g{(a57obCU7@{styM%Vu@qWITBBYl1v5Pvy$|J#aa{fnyq zC+{8WjDIem_%8+jPktEA_{ZY>zp$SxHzfWaQXK!d^M996{0V4N#|`25zZsGLU#si? z%@qHc9{-okf4u*jx#ItqIrz(#Y?*f%_&@Pe-SLmXjsJt@KlHxb_(#?M-TBWJ%Kt9l z|H&J}@qZMN|6ix*|L*hOms0!)NUGz^8f2~{r^ge|12QU=cfVvKgq5C zFck0q@qU!)w}Stt=D+$M9P5mKE~of^2L7M8S&jda{n+(S#%-+sTSGMdd027$d7sqFZtqKuvYH5BoqH{`}Ys{Ze;|NjN$e^>CyrjV|G&4~Q}Mn(U3=l_3B z@t*_!pV&t&|MhLnj(;rf{l`swxgo{>j`HIlHveBm@n7Nbf7$rw{U34pf2i`Gvj1N& z*6IJQqxi=FC&fFf@z3Kk-;E~!x9R%-^%Vb40ff&_F|bVI|1Oiwf2QjFZ{Cm@eyjR_ zX(#6YT8jTl@c+7xxOtj@_*x@Km6yLiQSnkQsif`hUe$c>HshgMZo`TjsTb{}Vrz9shJLV*MW}&i|ti%S}^8ecu{onom$DI`a1>kEfe^-nD&PnX}$Kclgq9Gdpj8q)| zxcUDMivJfL|Cfz_pZ|0D-xtQiCI8<`@$U(3YC0jL`Twif{%@%8->&QbzoPgrghu-O z6gNE6_^0(@Hvd_i{|^;@RsVOte|QhYe+~FQ`b2H~)3-4j|L9JZ{~o^Fko^DG6XaIX z!ut1A&2Ij`kK+FkNP0uc|7Jw~e}}IB|B~Xr$m9RA`H%O1bJ+U7^ZY~kSbY6|KgEAB z;P2u4setisbh7bpa_fIeCUO00NdCXGbpOZUf0*LG1hD$r84!Q-R1SYc*MHjhAENj# z_28HFe;&WZ@sG_&H(BPt?cCj*>)%Hx{>z|s&AgxD7H8`J5|6U{8wat^e^TIhFC_fC zDEfcvZaDsbP4Txt(|Q&0x8Bb7e}>}qkIzmS4vbR7Zx& zA7lAP5yk&#Mf`mP|DzQD<$$$C5q||Y|6@hO|E`Mon@-r>iT~eH{8s?}K1KWq&i~Db z?thO_#P2@;@)*T`CEzzp)%?Gl8~<7y{#L%+kn-Pdy7+%b@m~e_eeHx}_Fty>Pj15I zKa0En>y+a8f4Jc9r1-Cf<`Mj|{XdW29On4l_0PYj_(LgVG;zp;A;-X!q*-`)Q23CjO9P)f<>&i5br z0yD*b$G9CFdtyb4g(`8VeO4-WqGcReeA9Pr=ziIb;f?|<<2LW=ww zdqu;)i~mp9|L2~SUjq2cKMe=JrHa2~sPQ}VfA0GC2dV#$gFY$obU5?hD5CklcIo*) z$Nx(=!Poy!JNU=!bbJ1Bz<lT z|M76Fi1@!#n*V~-`sdaSG5>Ek_%~d3TmI3&e}A(x|1X>W%=6jnfAat}{*8$Eci(^V z7s~%$z<*yz{2N!Z_dj_5kh^Q)({>NsCCxt<|9^Jy|7h9m`6mGXE#HI`|BqzA?;_xK z4vr}P$@;JVqx_cu|K_N0;@|u*1AeG0jK8}T`7gK{$Ny6f{--}ZJO3cye;}m(-?&UI z{?Xpi@bC8jf2I6S08ToN4~hSX;{TV5{3r7<|Iax1-}>+E`BlKb`E5AyZ**qx|1{2z zqKf~nvCj2MH|2jK@ZWhtIQ*lC_`gSyfAk3E|L>Up8F%C_1pbpVoa;Z?{-3AQROH_{ zWN71msJ{P~`29Od-~U6P7wz}|oa-NV{PQgJ|GmNgtrJ7?|EDsmfH~%5U{D%&e<$qAReL}*2+XT%2ibSMhX0oT!}wpN{Feg%J@doK z|HfZ3_&?MY#@_?F{J-Yl|K&Hgo9#Q%ee{FfKt@lUUV|LyB;&7TAOC%$y>>yG~n#raPZ5&x}wWBjjE z{tp2DTaw}AfAeY9|6TtkJ0ZpYL(=>^*S|e~!~Xv!#eblUe_=TOZ$*UvVMYAKf5-U$ zP4OQD_{~M(;5Yv-8vY-V#_!z!aMwTlk>bA=eABm10sCvF`+td(+3SBRqV=z;>mLe7 zuk-LPyZ(vi z-{hWuB5BXvro-=^5Nt=4fA{&X4iA10|FZab{;i1ctMc!z|9hL_zaC6p{IXj9tGk+B+>FI3$@V^fI z-wojZ#7|}Wzs_0~zsdQ3Q2eM_uK$zu{{&wD>GI!4`M(hwN%)t||2+Rl5x>t)84jrO z@8-Y%c<_7pm&NbnKO+BE<==h(=lc|Y8`!$y0JZ+Fq=a4ni#Yu4e7PaT|DMwQpY!~y z%l`)+{J?+PWX0>>E!qCh{3V_zA^-iyfT@a(N0zY^L}(?qTEKxQESum3+A& z#s80_^S_h-T>d}x;0OLI71#fjZ^PoZIQ#|ty0Vb)|5oz)2k!r-)_=SC|8t7}R^Zyl zQ$YS(?q%^C_p;&YxDm< z%KvR1{$=wY&p+b)pAwJvvdq65|DSpAd-#{d&+~6aCg=KpUU{4YTMzXSLuJjv$&%I#VF7I*zif#bb& z_%D#l|JwY2Mfq=srV;*S^B>Q@G0gdQ^Z(Z#{2u;g@%#9X2)`=-?)yK#qxkOx{*!#3 z#_pOa|Dy;0pS<$`tE1@t@Z=g5J9g|>V+^rkG>U!g*s){B7O`W;nzducPOPY(iXA&@ zV%8GHjxA!xl7z&D`+?fy@W|FAjp=j9B6KX?!L@1T7;A%EL(YX4__Dt`k#uhJ6#vxdii zr2pBF|6X8?c}mD%a-zx~5dUH|xUj@;>RPYE|Im|e|8F>6<@XHvea-%# z+W!#re_zDEZvUhHeM5c>NV2c={qy;cy#M3u$bUcl$$Q~sHMIL5;V(h{2Y@xUoeBA?P9ph#MCBK&!Np+VpA-2XjPUE`pYjL9KZ1*|W*R>q z|K#~kb0PmjuxSC!so2~?`Oi*N^B)lZWgC;avczAZoqxhV5AwGGYiv6c^0QOa{QEDt z$$x78xsm_j2)}OrDZlsVVCCoiPv(DKuF9C`ftmU{1g8jbiJ1HzovHn3IF`a z|0uA=wlg7r`SL2i=ji&+)co@y|6>t;-TYI2Hpuzq`5y})|Kq^l`8Da&3H`Sa{{i9e znnKoVDgUDk^Dp@qME)m$HMX4z`O8*N^B*|6{xLOwDe^xV;n&SS<@W|TzkK~`A>?ld z{^~PGP80g?CjLEo{o9#jy_WL7mSO%S|02l$RF0KyXF~qEE7kdr_o|!mKQ;ft$p3VN zUpN1hKcN1_^C%ZH%|AK*l|ladBF8^;`RVZw=4k)N^!SH7{yPWq-w*tqhVOqV!hWtP5Gt&CDH%G5q{nJr~Co&AC|pb z&Sd|Re;MR|1o$fruYav2$3MJjYX9${>$SxHT-y9E$NBGs{67l(;dbigzk?kAW2XKu z(aXOnzx2N>`hP6KubY3$?-Tzr_u&^a*}vq^BLCyS-)wmOb9;l@|5%Tj|Efcav;X&e z+WfD;`Nu*2p8)=FJ9YEld8*1E82a}$^KZ&8{V$LHpN#P9=AZI=#D5rjxwMr3)cnJc zza9AdXimij7kd4tVwgJr2`K+z#mWB*Y4bmv^Irz}e+u}S*iPO2x0B-^KINC<#TWhg zzf`aPoAS&2uZaGij_~W|pYpTmYX777w(fte&(H7w(HY+VVhW!Bv=KPzHSGVCFL>Pz zf4lbmFF1eC+9UY=h|1Cb#=zfVSpSsYd&3R?Q-=H<@2fuZH}a1An_E{=gCcvxfZg{*S98{}#YscetJWd!26lPc-D0 z@Bgv}@^1d zH{_S&-zem-0{-%&?C^W=0Jgd-Ox+!uP{vkb4~FfL+J$k$*f~eg%(L!{fQ@CUQUTy~o#AJNJ5Q zQFyFrB41Cq^x^S^;qita`Qza-fXCN`wS? z^WU}6|F+=2;%H0xf7ea^Cu#Z*`Q`Y(4)SjY{N0xL14sNX8S=~Ve_iC?9{8J%vE=_f zH~wGN4a?kTb_V~fg=OxOy}Uki`~D~V$W!}} z5q$su6Mp<>>KXTBj)43B*3D+;{_mdQ{onnf-~XNPug~+}v-G{0qkzA9cRTO@;~Vm` zP4$j{>JA3b|MK_0kmr9ciuL~ttgQS*v->{!1IZ|I6Ls z`+si0`KNtyZ{}F=Up|MO{0D~q{i6Hl=fBJ2-z!D@!}0Gn)8k)95&vaFd4Ca-YY!#4 zvgH3o?bko}{73HpRU-cmuua~vcE-QJ(fHS)IsV1!e?#OS53XW$D*P2X{@Y9ZGe^h& zQ`i4SoPYWm_hpWU`fr@mPW`i|3(SA|X@34@#qR&S{^j|P8*~1%;q|}qQ2$|_>c0M$ zy;^wl*8FZcg9!Tj$C_1|l${=N4L__x&mUP)X3iy{AnNd4=+{z>cK zf6WcQLH+0FKl1&LHs$;)t#*IrM5zDD58}udvkrMyH+s zZ^`+meR6;16sZ3mOZ6YDP+E;!h{{_dA`9G=u zQu?}@CI6GO@BhN*|MK|X*2rHC+thlTS^nwsr z_Z^-8k-Gl3;r!Fjcp!5c)PL_>cE*3-aQtUmx~YFT|KFDLp9J&&iBSJxo$Aj2+pbaP z|30aIS|9zM|Mrg_ziIu;zXkFKk^0x2|IzwqgS`G5 zR~W&MPwl|@dzOAMa~9Np^*na!KQOKTt@QFAtE&PJgvWp6{C}&6|49Ao`lt2JX1E#u zOzU6H|93+EU7-GJPq0(}-Un{@-_Wjqa{rUln`eW&Q8W`Dc9cVCEdC|I!*eum7-T3i$7*PW>v!^}l1pKh%Ff=jjRkmz+TS z->dHb)YJ2-Ect)QaQ-ik|LuzWyTUe=o@l5314s4$X4?AS4f&r3*ReWH=)d7wb^ga3 zo&RZC|2-4M`#wl(gY%EM`4sj%)PGo~y7T|C z>s0^V0|okDfA!y_$Dg|X_r(0~2HO-^s(-J`kiVaCp}&XUN?ZTc$p1p5{&nYnwElfE z{>QezKmV~G9QXl)`p+N#uMA)R-;48){`8^D1yKJr^V*sJ`-b(;w$sc1z|T(nyRrHI zE)oBc`q%YO>pyTb|2M7wt`Xw;r+turcgSS@NtVWcNA=&Cw*G67|3!#P=~y%VPBQ=V z$@pJK*K4W%*VUi@=j*>?#0b9szaQrxab{cQBB=k``RvqxU|9ct(d(a_|Fd_*Kh%HL z@cjRt6V>^@_l-LKb<*`(^8d2o`9GzL3I7Km{~oYSt;cZxv~w2P|D`|geW>!&@ArHB zGxmc6Kk#i2q3a>-vw?KN?TTjGD$u>R%w|A!#|%K#D3dAa~AH2zoYwFK{{;S)iw|E%}P^J@} z{yPlk|IIH6|3@PKUa(F6DI})}^B=}OTn3Kn|FUfO7n3dF$JOh9jzazpSVgQ(#cB)H zfBDJk{vUI6{jYxgi|e0;3;#!R{uL%Xnz;|^zss=xgZI?@2N$caedexsyqMhA@v^^j{m;q{6BU5AB*|lJJ*wzGdus0`t?3m`yc(jt^NPY zv#~V~_yGL4TK{#({|fwOSpT~7KU)7j8UJG&WvTz`*FQP_bwq?el7C%(ntzXsf5qZY zo&OV%e;;sC(O_x(bCmxpAkaD=@Z8I0uNn4#>Hj?Be;ZuKJSFtsOXk16qwC*N`#(Rz z5B_7G67pBwtorx9cQgM>?f)F)e<$K!xBpT9Y*z7qZiGMLUzeZyXM^0oJpOe7^1loI zE6yc-I${26_aU$UlIvd@>3S{ozYWv&{|h7h;GY>@|66yE%I_2ZCG@&NOZ=}J_J8UB zV&s1h@ME45`e&!B`#;Rl`Om5SUlQR5|1nPq`P*($`#<}^P5)2rzY+Q0kNDT^f7HKE z>R&vKxUiJ})c!Au@JIaX@>Bl-sec3)Us>We^)Kgtmm>dU*tBlir^V(Ln*aBb`u9ow zH=Reu6-)dZrS1QhMfkygJMGg6`5VWo{m&=$Uq`Piv&8>~e*e$^<@TNt{QRds=gKc< zTsk@P+WheTXD9L3zk{jb`yqb`%Xn}z@_*n%JT&0K->$&%Z|~oK-GA84`42MxP3Zpv z*rZra#by@DfBPB4zoYYiQ|JH62tVXMmeYj%Wi9IX=k>Z7{|xec8bcb^g!D`G4N| z#ToxLPCNcx6X6H{Wro*3_WGp%k@~Nu*Hu~a|EB)gNJuZ!?U{Oj^l z{{g9g1Q%af;@9`j@Bb*z|2`G@_k(R}I+gTkvAKo%KjjM?o&R%Xmj2~|{|`T&?|<_3 z|8dCw3H)j^9jC89sgc8az^1NE=e_q=8&+QR@$bY%v^^cVgtMecB zlj^^9S@OJE;_pm5|G5kK4}@*1x|?_s;VLx#(+mcV@_#J^TIU0PT+RR8$lnbsise+S zybymAIsVHW@u$vzYlI*2AIoV%{<;oz{^OJUi`C#_u;l+9bAUwNOa z^-sTV>-xv*vavM}_yGL4n*aYG{}=F^Vg7Z;f0}=v^#9mKS@NGc|93|CBl*|mr}_70 zmHgk2{0D=R>Q+nr-%nwiFVFwE7x}-06?I-@R{!4F>iF-I{@-{BS+Ax1 zZ<==gb6I-+z&e|BmWEb^afY@I(G%IZepl^@N&#|KS4Xf6V0k zmz0g*$9Wz>{zGA#O76AP{~hIj90XeD1Abi1{{zVXHLNJizwY=?^Ur3L{684skK|vM zpXQ(a?56*j_J5iG$B};wqDx4=7>La{-2KU zL;e}fX+r+CXH@=x=3lHwE(S~fpF#dQ*rxjX?d0G4(oO%rDJ!4RL|?@6{{-?+gEfTt z*B$?9{(aK_V;g75f9m`{8R3uQUzeZe-=9_T|19z!o^$dk8K;D}Lj8~W4IJhF<}Cfo z1OGpq|H#+B#v^|Z{Aw$mr-;=R;%_9c|M;~3H2{YX57TMAmDG|J}6npXZSO2-v2E2gr6NOXbRA(Ne! z^3T3@!+&d52uiq!<$ogb&&aJqHjf3mik}n{J)I+ zN5M9AJ!q-_JIa4cHulU8_&_-Sk*|MELjG^yH){<0f9GU!{SO)c+UR;M`QJi&{=?7z zmB&9`MgF5gNJ zUq}99z<*h{o&6u*k^kGXF~tKu5cA)G{NKTEhW>T?KlLAw`j2hYV5$E%k^flOChuWO z^*_~3{oj#|J+lKo5c<#FEbf2&2J(LozgcpT8GqZyiz(-g2af80tF-;U6Zz}Gf3GF~ zo+JPNG4$UN`hOewe*pjOSDN*|>}Trh|DL1%x3#u^e&$`x5+itC-$DN4z<U*O1pm7)LYD+T|1$bUTeuYS~ye>Tlc|IcLg z&Lj={f8WG%p8xle|3~oOZs@=3b5j3(Zuqw`^v{+Y!TBd6{|Vr~>r1o#2Tz^y;r;H0 zpJkOlTkt=j|FT;}{y#wepWwGkFE-16Z@22-cjSLtL;uxF3IAQleVNj^zsMTkq0oOtm*D>x`G0}mt23 z>fe$7$%g*BLjRv4|9`=MVCcW?lO>hD;XCrbqqcv3{I6r75qx_;L;h31f87&y{IfsZ z)c;)C{`vW@EyGvl{GTKLui(Gz5;OkVY3lr+k^I-w^}=&)<6|d7|Gkrh|8C@OfNd&! z(u|+7_>TO~ouz+y;Qzyq=g)tZ{=Y!}-{4ncp2X@3jsLZs>iEyDb94T?ssFk~h5s*+ z|5WhbVaY#RYN*l=V^%EXe;yF3^8r7u`hN@g`(Q<(f8FE1)W1*aKemmQ_)Y!$>k0o~ zBmZfzO%3gK>figHoBls92-W$3AJ6;m-A&AYzC!-rVMX4jX8bjutK+{%`d=?yuO&!Du2q1pE?K}`JWGj>U_YDtNy1U{~xfTm?yFFLjAw)b@lZ>=7`_a zf3UIe--G;Tfd4K_{=L84)c^b-RObVJJnvt=|K&@_{|%h~(M`|O6Du#|zwCL{zemo0 zs(gvmm8JTBPy75o!v78Oe+&Gv?M%qu`GU$H9OA}*YW`P{|GNmk?)Xpned0fs(V6VO zd$Jh+zD54;fxqlmv*W*AlZb!9-&3Ugzi*g-$^Sj_{{Z~4?M#^e;4O9j@BQi~|Ec-E zL;l_fzi$31Kbuwfe?a~pf!}+X^y!5D%X`%Qe{WHB|F4;@*HZmYPMiN9k^d*)k8NjC z{N|+FUbF2;BQ#P?DZeksg8fF*-iet((?Zo`F{oemJYN2SNbjKe~$P+ z)aEbE&;R|`MgD(9{@;MV;&-$8Pxf8azwapjAEo904f*?kztNE2|3UR1IO6{}Eq@>K z{|@|>f0+4inM}sN#og5ZC))gc|F3IpasJEi$o~iMSHEIb|81qJf8SC4f2zsf^3?(? z_Zf)KX|T+F4w=F~4}@jzvqgM%!!q}|+Eo5Iqz8TuK5NCN56j$Vc5Kg(+hNJ3^UqCT znfts=e0IY!_nDo+KWkx``}E=W&VgmO_+;O}@8>>?^bubFP`Sua{cry1qnQWi zgX13y@%*=3yMl83egT%ruz}wHiROPof&HKU_;xS$`#V!@%FP zuo-{Z2WtI$ru=&po1Yy2oWl7*E&CHb!{eX2^Iv-WGa$#mW4bNv|L7n832-A36Tt_Zb;iE#-e_?bm-u{{IpA z-|z9vGm!u0Ma=piebxih{O{!^|JnJ){0B}SE`^QH^}n;gN%zylQ$qig-}}43_-Dy~ zX_o%wf&ULbuI7IT^8W?D8q29zU7`Fpy`zqQzN7j#%|F{h^uG+}A2#9f%tXk4@BViB zKYO--|Nb=X<0k)oTMGW!(EnJ-WaTq<@*gkhUw|DRZ3{Es~$;(>$Q zH&0B>%eeADVwQtK@%ik^f7d%uLVCf0nS* z{{z$fAMGapvj3N%{|g}hZI<%SGH&vJreXf&{qGh-{@Ee_HHQ7aW*PPT4@T<0jjq?y z{AV}A`A^F}qW>?+`M+MeJ@YN(zidf6`DcOQ{J-8!{$>AP3jJRQPHF>7{ohgk&q|yB zrICLQ$bT%SFeK(a3eEpIe^lo`0m(mKOXS~~od2c+ME;lI{8P4X&-6n6>n-KqH_iWX zZt^ehf3+<7Zv-c$&)La8o6SxCza$&URDv(V{{7MA{P@@M=>H?8Apa#_ znALwnR-ONNWc;h8>$TMXcQ>5>)a@qnKaBHl{YHD{H^_h2(suICo->>O_$Ro@zr6qD zis=7ha8m!gng3Yp9qOk4UuxL@W&VdF|6Gv&SWX34q4`hc&+7cgb5#EZ`OjBg^OEJf z{zoAHCGedNOaA>?#s3P(KX=5x?)Xpr2c-YS>SN~hzx-dWJ6!a?k;s23e5Yn{-v8+K z7Ro>Uc{aP7`rmg{>@N@aKvtapR9P$d|Cm!A|N0ZI|7bG2{-yM5QvZ&wfB8)F`j3#m z>+6+x{jZAt{|Ef7rq{m^e%}%Q=cfGO^*^g2|6joG{b`o}@+qqSz!879A-~N3>d5~$ z@HZRsHxPbS=BEC?Fyxo{UjzC70sdY?{$9fGIpY7)lt0XW1@g1mp>@7$HvjXclKeZm z{_QJ6ewqI@k$(vA*BJ8G5q>t#P5!?&P_{-5tC|5FV4gBfD{ zTMPMT1OC4Mnf3pQg;oB*5&u+8{$gGK8EpEC(eG1e>ndu{Z{a=gZ#4tf9dOH^BjW&SIXe@@`9{>!ZY^$>pF5&sNBewqLEkiP`@14I9{)7AV3j`+VZ8Ad_HRPB1-vIgN2L7@)%=%xjh&ulJbL;LtY;ok`P=LP=Qc5?iJ{4Kwb z`ge5vGd2Ip$Uk3%U-$SY<@W|Te{1;q*T%>{Kk(PloF??&FE{+w>|pPGL&~{Y%TrYW`V?>c68%`QOVh|B`YHUB>G-$2)EiGOdy z{7e3AkiQK0W7{co725wP`$Nrtu>4T|`f5zPUH_^1tB`+*2)}OrDL3S{Ye;>pAOaASVe<|RPZD+##*ZisG-=D{ge|>&_{9hjb z+YtHZf#W~*hR1(eW~lt0qvK!S8y^3W{!14f2Ce^+{QZw=J`%5g?1=pH zg8vRf|K2yM|9~9-%f3nailzGh!O*{)|LuVM%Ygrisbo77)_=nqYX4*Ns`cMU*K3J? zU+w;Gpw|8M??f8G8^{riske`^0bq5tI~{&o4Of1lKUvGT9)pCA7(zfrvZ z&o0Qn0Qhg9eL89Wzg7FcKTMtfchdD*s{dZY{xA1`c18Xy`0u8DIw61g+G_p#r2Z?X zk#WTm|9;y2pZhNzCj9Tg`M><%Bbie0A9~X5|G{^v|6qK9>p%MApQ3mDM{56jqW|T= zf6P-t{}t;H|MR=)|EB(B{qKhS3r76w_CM;ME#-zkwg26be}#yDU4H7H4O;*F{x`K- ziuqp+@-GDb%ikh>Dq;TX>ecr@^&R>DQM>>1{a?BNw-@pc1OH95PbcIrtyJruU9aZ9 zhpxB3{wMxk(#8JT{h#w!e-PT`|I%jsv78imz?5Ge|2P2oSAzU|J%;^%ed51Vfa~z z9}_#%>YwlbR!tN8zlWm#GVouy1>7Mewy}lJ|7>no=f9pK|Nk}gFOPp5g8U=Fe=qIR z;<+eP|Fwsz`S(fvS4}5%Wyyc7cK=^wo*a^V|L4Pye+ls4XjuPM$Ef^l88`L+Yg+$x z$iFi9k9kVy-y`!se<3&grvB?b7xjNQ@-GSgn`So~{~PL6|DGfNzv=tWS6=B6V*bAh z@?QquX|r_y1JBXV#UCiqTZi9c|}Z<_zwBSrlm zi~LstfB6`*{zv_Kj?RBI$bbI)hxWC_`~TG=|5d=>A?|-jc?#vfy+ZB(0pX9WH=jcK zSM>jXU3#uO1$oY@4^;+UTRGVL%|Fy2@e@k zOZ;QB`T6S~H6j1W$UhFY$y?42KO^V=#nx+y|1d-T-U*`qPeJ}0V4JG4X8biwegE5l zT>lqauOM z{!?tdmiUh_ek_$3N-u4>o9ze~|unB=Ro>$3MI|%;x|8c=h|2+-)Z-#BES%GY)nAjAW|5gqs{g327wq8s8M~%|klg^6y zf9L9A{67NuSB3ny(BrfT`J3tM9}BC;|N7{9E%6_yef*c?{|w|`8uA~@X+r+WXVv@% zB>!SHxUj^ppZ}8lUzYvzEd*HEdL0`zw*fWkL`55miR9)?Efpf9!cG@W4fe`R_ek?Ek@= zUWfc^;)WdA=9`In32U$_2g z{yozF$!5SrBld{V1E%>8>O}tGP2WQQx4||w)SK=9(2WmB{$uO4#DB5j{72>=-t;Tv zuYml=aw@ueB9)_@OWMgNoehd2EV z`PYo(U$_6!{QHjP|N8kC=fAaz{KK1`g#61x{u{P7^WQ<||I4|l|3A~_AKvsM#**|MyA$eUks!dM)LDeZ%}$9xeRCn;wPyqagonbe@v1{{{P~_3xAZU-B)PS6Sje zxMIL^k9`x)?#v(mYraSD!%06O{|dSOKi|LdmBKb-Uv@~;K?kL5IB{@agJ$A9*s8~>^E4=4SE{KFvs zore9t;yE?{o}>Q%SK9o;Nk1X~osh{+!~8ds{Cnj3zu0;$<$r^;`G=D}L;kfR`PZHQ z(EJB44DS3l-6#70HORjrB}dy_WJ{X_)`|Cj~#8^cM1uhWyvkc}l|m?;o%F_elS5r|Y%Ee@I1aiZkE? z;rvJL|H4U6A^&j5zi*iT?3pTm;HdxqlQ#cw(o@KPH#n&%H_Ja;Ma{oQu78QG*OLDY z)8-#edJ6g1f&9mEnlS(MH_7@czp;P4izB?*GC`Pa*$GkpC{j{8yf(=AUKV z^na#({EzSduw%shA5MA-`CB2A-ic=WKMi-Q`~k^-Y`vE9zh2t>!%43p|GJU<>&|~@ z{sXfA8;hfdve{~>Af4<|i@{P%#9Zo~dxw<_uX zuu>V)n<9{ou{V$;FwZwmDMXa(0d?1|v z$o#{Lo*{oZ@WpZ}R#xcsuiC}b`u9ox zW7}kj-!%Vn{}&E=hx{XR`QOHD{@eC~di*DFl>gaM=AXeq&yfESaMEKb|DL1sUsC5E zPI?OY*N^01cm6~3?+x<&%lqHKL64AsWypV{Vg5@i)a&2aZR+?}tok3Spa1;pAKuMk z{tr97A^)S0|K>9+^?zsik3F*kK5*0;>kSz_ma)<`IcK=cuDRZjMaB+cou3^0(7Eva zaOve9hc!ZJu-xO_pYiV>4Udn8$J$C($UlGK(pxL{^Fv^;O8HKsoQ_XF{G*Yo`M!)3R4y!&$gc({aBB>KpT@vn5O@V^rGzx7}3nLp=) z@n2m36&wFqMr-`{o-1(w&;GXdB)#+B`ddwZkB9t?z2$jt?0(Ka^`@sXe*u4wC4S$K z-#^(6f5T1U_&2=h5!U|(5b}~$%;vu>Wd84yhhYJ4> zaQ>d{pUw=KAKw2}T>q3d|AC=@c1p4R^W#6g;qfon=?(p_0^?uhwr2CcvPtUv&s*Nj z_&2-Z_$TxKAo6br`H$sP#Hi5xzhQB8{?A6Z;Wy2HTb;=NL!5v1PoK`r2Kg@)=l`b7 zKYQM+|N9M&^WTR4SB3mHKWEne+LuxN`;PKIhkpL^omb9(VW%fo|KIHUOlEfQ-*GJG zPwU?^^v_OpVHms|M~g9y#5Ie`h@%&L;v&l zH|ziH^!z6>{#P78)@y0}Kdj>4$NByq&4%;e@c#FYasH{FJd>F-mw$2oYufz#hWYo4 zo_~J*WA~Th`me{)|LTzc9>e_iEvxpwfcC!^Nnf?(za(w`pFsXiApfzPiXasl|C`DP zzoXYbQ|JFl&OdGG@tL_G|5E4b@>&u zZ^ZmpMDnlgpX8qn^8Cx|Kb}JVO(Fk{be@v1{`<)JuK~$_Wo>chKXr!lpQd_|{|TJG z=acc71t9wNj|LpT*|EFB#51&W5v^4)S$UpzfO=ABq;QU`NJt0$? z>;K~XkF@#s4f8LbpCWyc75hIj|IeZSQIP*wPQ`W<%6~n{KU>?4|J3;(kNlfQ@~=Do z(fqT)oB#a&KRcqF_qi81|MW{IWEO_}SB~U;DsBD))BJzoX8t4d|1A1nE0TX*|1|#r z>Ho2Ew$%Sj^DnRedmj0>fc*E+c}l|iuO;Wd`Xv8-UlnKn|8V{JPyU&g_y2nl`PT;j zy>y&T$WQ%xj{4u+hU35V-+}yFg8!JOg#4xC{2w;bP5;;RPd&N*f9(7@Z$YPFne_lcVqapt-+mm^!*t$aFKZWoe<$s>E`JaURTSfA(+y80)1JeKK^JDA&7rOZe z|1iqKasC^G|8{=-=gX^K%q#)l3E%%U#?MOs_52TScYgj0%aTkrSkI)?@E5( z!AJKng6Wl z|ML3RH#z^8!zN{x98Jk(r2lt)!~1{RRcimQ9mo5Br|AFetbzM~OX~j5 zU;pU|?|=CY`mcoicXp8d6cOA)^PlSV)&B31{MYPA>dI37=QqrMZ`l9eMgDCd|5XQ( z?M%qub*`F!Hpxx>AEljtKK@laQqJcQlaYU0;O{f!Z#rM)_lFN9^AyqnE%`r2o1f(W zW#nHU@*n0jHvcPd{Z9+YzfbZ{=*3=0>{0CpO!MCr`u_m=w*&v(my`2U#TFH+|EddB z|AC|af2_8Do`3IJG5&ps{M!S6^}%NKU)iYgvz6V{f4w1p({+OXBjn!!_{--1_x+hd z{#!0m`8`Md?>IyL%IgLH$H>1U@V6TJ@7qcp|9nUOkJsks{ZGFC`zOf16Y#S`%<|tk zL-ilLm{IzFSr3_4SnB^Lrse+>`KxpJr`wsZ|J84;`e&=SssGgcZy^895q{nAkMakO z@^8v7-~anFL;QQhe;Zw|rTm{{n19LNjr_X;e{4Gw=D)IvC~!u&T8es;Z^{r?6-{*Ffk|1{*^8~E!C z`75?l{RfWnf2uY=J^q2`KW_lXKicSVx`h7AHc2`k$`<+{wSW z&yEUl{);rmzi1m@t{k@vzg=>b`gqUDyiTgbedNNQYuu5~AN)tj&+o(^?|52_JK`7G zPUGt-8?Qdzc@}>>Adh#A<&S5{dfHFtkN0gO>RPP7>`eZ6xP4jC|E2%$(7zY)uiO8r z|A5qg`1j>TI_%DQZTFV z`F861mtMm!7Ijnq;h#&o%!>R=|G%LB&A@-mlUQ*f|JjYy@h>3$W7}sb|N8z({(naP z%_ID}{wcpdc=_|syuAN=L<~%YSO!Dtls`a1Ug*>m8_!rXdf4uYln}0YJfYl$x$7%Xh7UHKrAO64L zd+tBBUQ7Jp-$}a6QvbiB|1H6P%#&DgA^slXKOp{N+h>X2z(2qKD;)oSL;kHI{JQ;* z^816AKmW}CTmIox2v+g4-Te27{uf)XCI7Kp6?h;k^4~CdIG^YLiT<|+{|&THiS-rA zf9=NV_|Mi;`(GzruOkAJcCTH=pAuLT~+iZd_&t^dKPAgtwh zyZx_5@W<9W)A;%EuZjo7>tAfHd>_mm|JoMv@9%0>|K*#g{VyQ-uh@;O*Ao9C7W*HZ z3IaF4BikwRRH**NkHr=(!hdYNmiS|Tu)qV5?)>~mzW&{V{cj%#L16g$r%zu0WUHy; zUu?51@t>ys`X|qS^IYP1+iX1lv(0yBW;@7#nA6zne+BOU+(Gj1J!y9SlfS{h*MHFG zQ9u9W_5azi{`Up{WrvyNKfAqJ|NcvE{GV>R+D! zFem!oFXw+Ra-OaTT%rEgO#FL}>i-OF|2+R}esTPF4&>hf{P(?K#^2<{CBp2 zoBCfYt^awD{{ZkG^OTUkb_dme;Hdsh{WrZolJEb|i~Ku*|87J7{-!Fw|EnASi>LKJ z1?PXY5&yd5ANB7KTL1j`Z&M)r&yW7A!GERU@&8WZ-*Z&|WrqIc`JeM4|AFAYI%{_R zE89`cKU-bRe`k^U|5=9pUta%Tiu^l+|0YBK^_!{uKJj0y*MF8s>wiJyKM4HCJSFV^ z4aC3yn(AMy1{apb|J42$LjGOAf6P-t{?g4=|K5gf_*45|0QnD&_}A_K)W1jSAH|EW z28;g^Mhj#vyI&Fr}n=n@{fu5*X@7Qe?aQLSp6@x|HY7hkBEO=e(FCU^P3t(0?cK?>X{+c3S_-B7Y6|k9kVyzn%CGh=1ul{9-2i zm-oL~4*3rU{}o4&c}hb5`kmGM`;Ppdqv=0<`e)X1=HLI2*T08isWB+{G<8z z2YLSG{m+(1{v#m&9Y34B{!_Y(ntxW|X8b!(Gyhp}|HIB3NAly}@A2cmUmiRuvz)>G z57{37zQ5>grt&w;;P*dlx>mjaVVAi7p?@fU+%Itd!|csz?|;klFW>(#i~je9{5PLs z*8hT9;(ue6zp8<(*HZsq+Hm}r_kUXv`HzJBcN_NqMv{O3U6nu9Z!PhkubKbYb~t`u zu=Ia<|GN?B|0wX^bR@~Cczz1L{y$WG{~O;?|GPlbe^&HA`ToblIscb;Ov3;#~e;w0#|6|vy{jd54-ajkGi1QJ~4t)NPZ>j&u`~QtZ|3`!W9z*}$ZfgGv9QnUc z)4$_#kNvs9QvdS)hpV9fW59pcf6eAUHP5T(KLnHA^#4Xp|6%=CU0=@UKP!v+pY5g0 zaD(~}`l)|!bCtiYhu437vs(WhqW-%@{rd&#zuQv%w}$WkwHo?A7W_B zo%4S=?Bz_kLH%d<{P+EzfYg8cG+zJRPa!{r8#m|3>P6e>eUA zGEM(s{Wpyk=l_r5{F`;Xk=YLFziUC>|6<3#`g#8!zn}W|wov)ort;}Q2(`eq^*DMU!MOp8vUOD{;Q5Q>;KhjsrBzW@_)Ief5+t>`*VY({^jfc>!SY? z!GG%?X7%4e{0ENwU!mzA>OVj7__vGt-3Zn@B;ad*((L-j zrnS}jXDhlH|CY|AtuqyMh1G2kiJ~Tbb2AJJ*eW+5a~}|EGZelAFx@w-W#CfCBuM z=Koiv^?w`s-_v6M_X_#nw4Ww@o*V!2{m(W*{|(^3*3f@;9a8_qe>+{TCI45a^)LE$ zuK(`^{%h0re~&+(zM+5LwSRac(o%>bsAs3bKQT`triEVr35frI_>ZN1=K0TG|0wgn z6!M=I;g9YA6}bO1<@X0IKY9IoCFI`+UjL50PMy$yDcS$`$?M<6@~`{)cWgTxKM>o0 zaQ^<+#Q!k#zi-69ZvLr%Z;<-WGB!tE`3~ZE>q2wn`(O2m$1o@b*5UE_U;O?LFwj7M zp#EwP{rBU){!Z%rCtPps<>K#(-1*n@-wzHFk2elH{?}e$=lBl`U;o(>{qG0<`{;Qp zVmk}<|F#3k>%YW*>#1a3X{rA&qj~;|z?o?anjhx8{>A-2L;u^L|NX&#%u_=DUBth) ziJJe|6F!stLv`oJ|E5Rz{(tv{y#BVYKY_uaP}Xr-fAydF*Z2RGTvw3%llqrGH|D%6L_y1YZ|6A$>|IVEMjxEm390dMDPx1Nhz~f&p@$Ws6 z;r+G04eZbVXg&Va{&(U0i-Z5;z<+gM$A4hz|7tz{{+{0c9uNJ?`riTT|KNy!-SMCL zXI_E)_vgRA4e#gi)c$wl{Bwc-6Tv@w&W?Y!O9B3Vc-S>X_n&{}<^6AVMgNC@|IT&! z>z{PYr`urv6R+%lTgo=l>4s|1|Jl^1L1YzG?m6?b!eB=>M>Y zf8Ft)`VUC`$KpPd>tFicm-BxP{?7#er7zg=ADH@YEw+Dt{HrTG|92nsUkCo{$@_(c z-U{{qK2rZassF5aKeKRs{3wL{pYazf8210tVI%qe$=;lQN0|RX6j=9-cKow%4EukR zWB&)B|HHw5%#$!v$ba*pYXA4i^=~o3mg+yX|60z!8Tj8H{P)~s$-n9T-<6L2?}z@6 zi1^p-|I|MlJIY z-$47c__KxTKelz``j^=EE!F=p?f%clKY9Jbp~!y}@Ry7C*QDE9h`*y!J^#rk{61Z; zCH@uD@{d9Oqk%uRoeBL{A4d8=x&DDZpSH&T)cgk{|1lAM-Tp`U*&yea=l>pt{Kw|% ze^1{3sINl#uUTKszxR*2|L50`^;*jRaKrpd{=<>KKIflqXTtnfZ9w>sQu*ogX)FJx z{PO(YBar`i;BOS~|4O&FkbnPhQvZa%o37WA|CJ2=OMV#i!}A|c0RGr^CiQ=W%Fm8= z<3Bb3pZNYKCr0>n`(G8|4~T!7CtLY9Mj{HMeDy>&N}oF?>Nxvo0@W3{UPfUeh4{;z@4l65|^ z;`|TE4=;L$`9A~rW7{cKUTFT;NceriAKS*k!oLObpBdrT%|GS$206dH|Jg~%e-`kU z-C~yia&r75ApF@|$$BmMzt%ASk{@355A#13_+#6dF#m01NdG@jt^Z=>KQ;f!$nQt^ zb@Na8*&yea*MBu2|JlG_{}ee+kgWX+r<4^!VR!b^o`#r8xcn zdc*unet6M8%>VhoAKT7^{PpDcpYJIDsrk=9ez>$u^6TcG@_U1vUylE0A^(Lr{%6ek zf9Zzm{68T4ev$IuY?yz^?<0RB@W-|@Vg4Hlzjv^k{-2tEEb?Cz;n&SS!14fXBGeFBmWuTKjtZ6{!8ms{{eaZL#zfDGueN`8lwN5hy0g;|E39M(>YpCG8{m@sDee{~GY$@*mQt68bNzQvI_LZstEX8~T^$KVOaf=YjvSMl=4F zab)}_^`E_ntk+WiUtPQZ^ZI8`3;)+4|Fz)1&(MGSSk=GpsQzzB>;HP>KOg+ZJSEJ( zcZ2FbApVP0|N8#<@xQKB#r(e+`L6^2)pwGdCgiVLjlBOE@!v||C^D&5&XwICCq=#jcWh*93B5L^<+-~VJY&Y!#g{XTI2`w~m{zYh%Wf6vZek|_3%&kP z+pN|=KW%Iqrp&_@=;!@UyZd?n zQ=jm+PT}u=8r;N>yTIEHr1X*ME-x z^ho`u<@XHveMkIV;r-8ruN=QWp#Oy9|MA?vZ^+MXapPa|KZO3z9nilXe_+ags~i4? zuSES%LH-MXzkVt|{t?T6SwjA>_O>;vf4`;Z{Q3QVdHm-V&Yv4ZZj9{z>hAy3{ojBb z{|TQKxwN$Zqrd;lkAKMhzdMot64?KX?Wc(iF0}t&e~G&P7dSfpVX*&~_wTPJUjMlR z`ESaF;4ZSCnvlPTod4n-rsltfuGfXx? z=)aAe{}K@YVl}v!$^Pa2PaZ}7%fNpRJx-I5zw%~s{O@=*|K4S!t}OAdsek-Ot^Y@m z|CWe<-TYJk{;cBvN#wsA{Kq^c^xt$j>Hp;T9|m81HPig_{?`zm|Mdj&-wOWQXrE5V z->}=_%KkE|Q}bUe{@V@vzpVeqk^hQ_f8G33{~oFTV)5(OKld-s|9TqvTfl$G-K0+? z^k2D*dR)SDTK~@=|5XwHy8WN}_h%LV0rKAg{$rjJ=D(wn^uNR1jQ^(o z<@G-kk^gG&-+UZ7PbDFL#WgB_aJBmW7p+$mC;w|{_kU9V?a2S1h=1MuQ~!aZ{-4_a z3&?*B_>Xx?=)a~#?f>2hZt`#HU*7-cdE~zn{MXSwoshq2Z?*q>r2adnk@Lzd&42DP z?EkXBlYhS|4lED^;+Uz+pz!3`hOAm?~eG_%|G?;&no_3LH_H(f6P-t|IN3l{hyua zrvIDzm-oNwK>k+n9~k!kuKm>h&yG;}%kC*o{_i&I|FZsHM*ilAf8G33{{g9gY<%LY znOy(U|Le$q5BQIHN|^sLa{SXL{)@$L>R+D!{2KC)1OGj=PbcKByj`t-kJP{SVsY|6 z+OYpi|F0tdy%GPq`KSK9S;hZb$bSR)k9kVyzl-<}i2q{c-_(ES>f-g^HzD=4ex&+`hN%g-w*y{p2XS;o&Qiyj(>Vbs^fobqb!Yorv7FAJCXl^2)}Osqx@`; z^Y3H-rXX8t?Jsr~~;{vR~tm-+u3`P*~( z|HRCH^9?FLJHt)?f5?zu=D!>Hp920?L;l(uResMAf15Txzy4KT{~)ec$zA_)k&WwL z9_G)dw`~Fcn}#C`S>Cqdzm7lTry~FLB3~E&GAs6f*)XyHKNa`?ABX+_@;lA;|9h@d z=l{VfZu;N)hWr1r|9ye^e;V>%d9GRi>-${IzfbaC^C{^omgc_?r_KMDoIjWUOKn{L zB=YZ@=KuDh=Rg0<*H01GKg~e?D+av&X{gryAA&;sXZKU9cNCkS&;R7{|2HuIH%5;C z>dyb^@n3)N9{gm%fr_{{^9)HH%-pG z0r~GcX}SFTGnlI0A7FtJrZ@f-%D*2=1b<+o;hOW`e%8~^!%*G%>%ZjnFW;d5Tfu+T zBr;DE>nYU#dS6uMe*y8|Lf304|LYp|zxE#C_eaiu=>wB9o#4M~6z7lmXH3gK+g|Pe z{pg52>_4JA{>4@?-~%!L-=qH)@E`Le)>g=W&*SR&=bc=Df3W!fne$&VVRGgj@ZY$W z9si!Gf7kW@E&9JL;$OG_Q~zvM@&8}WfAJfWGw*@_ZcF}sL;vhiH}x;Cf9pm6w}bya z+NTrNe@Bmc{;x-_f2)3pj4PJvztXV(mxbf|Z=(Lco1FOo{5P#_r~U&||BpHL{|oxR z1N_H4CG_9>q}u-jNA+*&zx7*nes|ewA7nlP|JCc-@y|9>um2fvP>z1{amW6DLjV7X z_}A_K)W1K-{mc2^cbtF5rIRx~;J;QJ|1h5aT{UNZ{_gEiVE*GprQ_GWBmeUHmtWEU zo#4Nf_Gz(ch30?duc-5Xc1i($OZ|U6!~QS*|Bn7=fdBCR&uRVphW^H|KagZWB;O`1cm(j;)x{--?jh$ zq5r$VfA-R4{`L4nq57|UL-p@F^1ne^|9_$XAHaWj{4=e8uh974kAL>03_?PT|a5{J?)F8a{$?gIEHbZ{@S#|!)8r+P38>QtRg8cUa ze@TZ~|F55@@_UZ>H%`l+LH_%Izt)hSJ*V>fj`%mx=I7TxRD}0G-JjS0+kO9x_2Hhx zWiRsAe_F2P_azR8rv+FhlPi+g{d>b7pvzqgLJ=)d)SGX9a{AEmF5y0SF?_0swu%K2Xa|L21L>?Aw>JyZYp7TZ7X|K-EQ{{QTp z|J?Z=%{&19Lr=Q-Z+~8`e{ZP*`R~vFu6q2b{m;Sq9|!;NR^Y7Dl7HXOzwgMutp7fo z|2!D+uY3H1`VSoS|J43Vxc|GsKfDzx>-dKEDc$^s?K@lsrvC5K%YXRyk}k81_kaHe z(f{Y<{JHtxL*Tz|YqRs;TDsK!@13gFe?ZsUU;QTq5kI$S+WtQ`=N||D;jN%q_se$r zKif^^Pm1N=Uu^%p|NAS7{yz`r|9X>0Gi~5M^rV~r;6=6nGvYtS-;aM^v;U{|KQHIM z_vCXKycIfY{N7Ied#3&$aO6L%|GBXKACCCf?f=xjZ|FaklL8N<_CG)8Z@u7L25$w) zdOGaXzi;aQ!D9P|0S`V}7ZUw{KJ@=cuK&|{x_JHz9sjETSndDpk^=p&pZYJLJNE6( z()NF7hq>b)_danhgSWzE-Ya(ev)v2u$4K}C{zJv~&-Z^Drme*H{}x35kLK#%(0|KI zYXA3$|DFaiudw8Q^HDi_$v?8<`UkoHzmTZ^m(FF);J?|Df6vr^n;ZZ2yNL0BVa`A4 z#j`Vyf&b8x?)dM$tomn96nOo&KmTj$@tgW*$MgJ`{mPH?3?F`KrfXi9|8?@?|GNCK z1Rgb%*H`QtGxvco|FZrU!1{kY;$L_Cr~Z9X|1s+R{KtN9;0JX5FDq8pbm6ePpNjMO zvi1VL>=VoKM*jamENd>}|L+yc)?WVq#*6tfdkJ5*i)BYM|9^*AfAyvO|2<;qU&jC6 zb~#^mU%{89SMsHI6<>D!$d|R___9wdn{MF$FTas51F@{RiT}S>EE{j;{|}$Vta$&c z+AT%@Uljd60shNgCCBN+FBTgAJ3dv%|G<&|EwsmfzW-CzD&{{+ApeuVUvJ1?_L<7h zE}d=Q`nQz-Ew%ai`QO2C{`zm<<2DL?-^ZT|~Q$G@la`hS?~q)V9H z<>$Z6_Xz(>qW^aA-(l##o%r`0`QOUWe{H#V{eLOWKVy?0@-w5-Yxq1Zt$(&hf&BL) z%zwtQ|E1CYQ@Q%DBJzhZqomU6`227>i<>x{`37$UjO{{T={V-cl`Gm_$PLqa>D%gQ2sLu z)W0Qu)9atxMvDHo9QQx{fFBsV6voP~wbTE6!~FY2&p+S)m;OIS|KlV6b?5)oe?YE( zkG1=m=Rco+dH;{)vHm9je;d6{KVkm;H`M)KkL17PGtyTq@js$}{lCh;BJw{A{ITs! z$e(>v|LiQa|JOE>^;*jR zqlWpH{3DS6IpB|NXTto~zNO~hC;Y|Ae`@}fkpKAzzi$31zcLQP8Tez{nUKGo@H5{{{!{a> ziu@fBe%<_2{($%|R{fju%kh78RCggAVUgh^3 z`QI+B|53>QX2id4{||_NZ;<Z)5ZB8>mmO{@ZV+Vznl8MM1B3M;tkSQEX{v+Nb7%n zHsJibTij^69P zsr^@?|FfgYB{`KFIe?(l{`VsOb^9On?++pi{L->q&xlx)c>+(_3w|;8~;uH%lCiX z4E?_k{>#54IZasq?WF$MxhlU;*K2A1`?P-lSL=Th&}+=Q~Tcv z`6q+_n5TsPYd%o>A3IGQ|BJ=1@1I})*Bie7)t1Qr68LYTeL5k3<4-ETcZHh&V)0iS z_J3LbTOj`j5&ydRr~W-s|Hb0h_s`G&uh>SM|F{kEzYP9+4E=Wz|Gp#tI~)3!$N#I4 zzYF|#ePnk3w``Z1f1miT_==1xmipf_`u#uum*w?8+aZ4k`1jr-+nKQbX}$wT{&z|1 ze|zNr5d6nHCFJk^PJR8Co#&?i8TikS|NcW_|7Qo}e+B$E8~QI9uD<@~U+!l7+jW#) zA!Wt>pRE6Fk^iHJf8G91{RgD}X?^f69D7vz0aO1qO!WVqkpETi-)rc<_h+^Lu_iVD zJ@kFm^tAQ+yzFLJ|8oCtN96w){5R4*E&g($>mM6GRQWwp|J`)GmiWi(_y2tTOa5Ju z{}bSkZD&IM>W@_Zfbhoz4i^4uWJztxR|K7){e|ElF z|K1d`UQ7Nb80KH{?~eSR1AlBg6Xw62@cV?nSou%QzZ>#*NBDK~Px-w;&M(LRJ&^wk z;BTfmP3XV%6E*(<;jfxnocup)n19J%gZy6te{4Gw@>hMT@_QGk^=i`M-+r z>*k;Gvq8=;$N#;M|7+lHp*cM)69R+cs^TXEbQn1eau7W=9WM6Ww&^|;_5x}kB3Wk(fO`X@2ahidkA=S%{MiWpFWU4?JG+ zDBq57*$t29{%*MbDsf*@b_xHx)u$Yt|9jywD;^KGGvtF+C?8pR{OdsU|4r_XQBUHx z3myOP{#NUso$luNpRWIqUmpM38Tnt!z5YRuQzhhY`bFjU$?-3-8eCYK|Ck>ClJ#GU z{NG0W>-InD-=p=9MQ#iAzncH5^&b%b&F7KzTH@b5?eXu! zkpFw|AM=!y{~wi~T|~xzu^zdw#Gl%K9rC{k{$rjJ^0yNI{*`XVztsK@MgAWm{&o9b z4e=k4`j_6rF9wVMG06W`#J?^-_0O(!lYdkHa{upeh-VQeQx@nzW*|Q{$uF>803E&{I?kTul!B*?>q9pXIlS9BL7bj|GNE;`uA^e)Bp7S z^D{4G{nsP^JK(?1(0@3rh0DN^{~AO8a{hlT^8XC}YiXZOSpPkw{sZE_ovzo?`2V7I z|L6YY`LD+#|GPQ=dzp=Yq4#j@@ZV1lfi#UmTYIj{?|+V`;PqYo7VrS$p0Jok9kVS-;z=LKfB3I|1Ik{g3lE&n51EaX#lC`o^7^Pk=w%PTl(- zu*C@flZNkqsQLa^`uzOF1lVz`9DTG|J=XiZ$$pjfj_pL;+Zbw zzod-tU$6E*DJ=YAu<&1m{N2FcINZ#?PxyVpU%3)luO_Zh(Node5m@yWh{-_Ly(=_4!VKRt7Z z{l81l|CivuhvrmlN1^&}UP7(^faJe_GJolED|7!>A%73>w;A&H5q>sK?SJj76vzJwhW;i0)yO{`_+#6d(0}u? zs(+8>AID-5{>J49Kk;8j*K3LYL__}#;qlKik^j%g z@lV~?Kj`sKZ_pn9>@>Vgr&ZOa5QhKK@Vm zuSfpBfIqgK3Hh_LtNHf{zgP_}1`Gdn$p3eQUpN1h-y7uo>}iqzX5{||_#0_X6Z&s| zSiS#OK=`}qdM)|yFwDQ?zXADk7dghZGa-NN93=m@sP&J*7heq){&C1ZB*L$of6DI- za(+4f-H7}d;IG_}^y!5D%jZ=62ju+kCc0ir{$DZ7zvRCe`DX+E*mfr5?g%5#@$YR!>dI37Up36X{JQz4{Qe;4m*f9!$X^2d%`~S8{b%P^{j(Oe z|Mk-KTJryzVg4om9mqcy@W-|@A%8RB_X$4+Uwk!K_-{x4xg-3#`KSEeAm?uyxiUZg z^&jM)2l(s%A^Wij{a5d<{$4=%t2Qo9|9{;u|MK|HwaEVs9RGVGF09{-d6??nFjBK~#zU(Ek)>i8G4Xo)|y|9g=CJMbU#l+b_83aWqK(eZCn z|J51s`uBav|2^rt|Lp$a_}5Q-JK@k5TLALk zLdU6u{4Mhm{@dN;{|&?OPx`+f{r>>|W1bT7SFWh?d&Iw34K6Ize`^2tB7bSbzi$7d z{sTw-FSY*%k-r!G`)iPKDxv@0d)4zF0@DAw=z1;rKgF>AD_35b&wn34{sqB*^(JQg zb@QqD56Jwdm9Ezk|C?#+zYY0+1phHl3H^Kbss6ot-SofI{vSsEg}{HzQ$qgoHHd#l z{omAo%WPu&e+2n|0{<-^l5sjAe>e4ipX$H6g4C6z{5NRU|NOv{`=nmY{$-nOSNAvH`D*1m5`G1D|$8suU z6gvO2b}hC3eMkLIH~(;TPyYJvo`b~sFOMSsBDsWmq)rp^mn^LEvpdxKuc7O;RR3?8 zj(;nPdVdo6e*yoMYnt<gZ6-K-@-y7uqtA>jC&ojvXEBJ37 zWmf-Qo9ds{s{X6iBI~u3|I-ZXzhaE&|4$?T;^4oH_UVNAFS%dk4~YMgO^d_dY1sdz z{|U(d8~BfTO32^5uG;?s(*LpXiLVBW|7VfE4E)DDCFE}-^B?a&>iAzQepCOIC8GW( zB7YzF@1u2^kiWK4_0R5C`CHd6PX15Vu77^ywYFUFufX}I{qrN66J~~98^8aH_VvF+ zaIlBUPrlvnfBgw7CfX0{cLfE$5zc>P{~M3~mx$zFcl@LIXR}KFpF{rNA^)+Qis!S? z{!bUlzen;P(_*RrndYCZBJ%&d$o~RAvAH4t&6e`d_B6{sd)7_<8x9xae}Mj%g#6di zaXO*@ve9b)^GW{O>3S{se_Mb2&;R9?Z3X{}$o~iAzh*S)(+T-w`6lCk?K)(=miW)m z@BjJz|LRpm{wIn2FZUCh7rxW(Lx%*IwEf>R&Huz==bvByAo)8u|MWF}V)Fxk)x&ni zKi`nwFFt=hd2;-Jh4cTg(@*&$LoJs014Dimxbfe+y2$^loPXZ7pV&g+zxok7{#lJ# z|My+*b{Q3GX87cDr z2Irsg*3WDy;I9?$%aykO2ZsFY`J(&J^Vh5__}}FG-~8}1TMqckp0MMe?PXT~>_s>H zt>OIlEzUo!^cOY^_`7bfH2xd%`;*-8x2z`ocXIxY>@REt@Ymb&zrs+n{n(e?@Mm`r z{BMi;_kLlk0)K}ke&5u8ha3L-^#uPrg1`C~RssCkC+*aKV9Nh$(fNTA&hroFKkst> zh3kJ|qu@IYmiXD;hW+n#H~g(0_uqXgzYoZkce5cI0e|DmminI|zh7kjocriUDV%VS z+utknQ6heBAvi=hl+7W391a=C57>Rqf6#Ln;I@+g`oY(t{`9=?lP@g7R?YpwB12{y zlKa2S53rlhzdZi&63>5bE0zM7*l`N+#|s_*Dp^N8{=x1nkbg`2|N6&22>%PnzjTCO z_xLB}56JPKn8TUGAKQ-qXAgw=uRl^8|M~#^F9ZHdHzUWX66U|2y#D1m%Ky8X$N&DH z>5k!s{)3~0|BulBvf#hY(0^&E+W&k<{@*k7U;orFKJM+K-nSz5goy`&NBR5Wb-x48 zVC09Y&;IxO#YTQ4(UQzb|G+T+ZRGW@z)}9+ z*UW#&-yZURj{I5RFWcO#|2LBQXLq@o|4cUIFR2&)yODo+;IB92_itCvfAKa|&;N;) zn5Fs82ipAn^^frV&wG1#AI$Zi+)GJyPc5zVw{W`)&42wNi>tr4wCca(X|i5R{6n<) z`TV!$IN|>b^uGf5&u(Fs|B4ON@y~OV{|~kKRsZZuFzft)A3i*eD|4v47nvmbWo7DelZumb+>tFEY>VIwc4E^iw|55*Jko&JbLHM77 z{#OM54TkmK+^YKb9rgc@4gJgaKlvK@M}vQVyjlL6N&Wl8f5il{UQ6|#(dOsfg|R=|*b*_Z{{BPqg`Y|Cj!IkbfQUAM*r{j>-PVce^UPCW`Bw%1O@{u}P{0 zme^zeKX*Gj&&{(JZ+CWXa{hn$e9j5uWpBUteV%7#=XUqNe;YkdU(vr!u7BzJn%q}I zQ~f(B^!fjM{&PR){~7rwfPbr6E&p5Yll|MoztyiW^S=dA{r`gee}aFXCq@74b~E)a zvi~0BUo-8WdJ4!N-&H>TWjCAQSM}dm!`J_QMgG6Qf8AuY_~&nvXe{Et_PfI5|H)DF zzZ3b_%JLs}{zv^gB>%-5J2kL;SZ_6^8#5#rzlk z|3dzW;NRydAb;y_a{agFn3?}Z_Ww8X$H2eOQ$T(%@4eP0_226kt)}>o?EeqsUpvcx z*!u7Df1jE0U)6u@q!>{I`k!&a24#sww`v6zjk6zZmi_2L3DNk^KzFPv0+ghne_4HLCx9 z$iHsdKlK!lzkPSvzhkKWhxhLu|F)jT z!`6SFf0F;c{OG&ofuLzitl_|EJ6GUwJioUp4vvB7FVN_^&;m`yYh-1HgYu(SOq>GQVZ0{+}Jy z|6t^w4E}wd0{U+w{;m7XjDL~+FOK{J!GF`4Bu)eJ*IKfF+mQcrqWUjI{;DkhVe3Ej z&x+i?sDHbaiuwO)a1hY7&^`YlH2>dZ{bQ(^_}^2p{;?)r|AwIdQiy-+EVcOWA@T1R zivM#JwJ!>wjg)KM3N#TQUBfsWQK1X#RhmV*FQc#^Zk}mw)=eSZo@^ zf9rF4;@?q>e|u%a@xL_sUmxP%7pDQo{~j9uWd6%HgN>&7uX6k!$Mb&~Kinep%Z@bRB{=Tpb?{9o4PpLwgtq0+w*$jpY4{1A0xr&Z*jQAZ~6rV z|8SSTadJs)I`EghpoiZoUVfm2Jg?^UuiWK7Kfyo3<)8O# zNo*_NZ-2$TzB%&!zZCgxL;Q6caR1Bm{GYd2Y!>j>zo-`fsqN+ZXRF@-Y1Od)%hKT- z_$SWupYi+OuoYbXX~X-)YJk7vB{hEE4(zU2|6UHu?|bEc?C|lg$oXgYi){z|oiFR* zw^aE@8Rj49^3VFEUu*~9Z+t}$zpcn`oAU1+|E}cnS6|jYwj=OYb?D)D6#4%#cs2Y_ zFaB%1dqaV<+VtaE{zyTae#F0Y9|>sF4-5Y8G-y-& z!4|>arym9SiSzIO6zks==zl2qZ&mc4m`>u~kpGKA`v39Gv24;Q@aAr^s(bz)Z&{o>uRT@fw+!)Ls>mEh|r)# z@yNc*eI1MU``*uh9dTa&n;vrSd(Mt573aTP3{JZ0)bhXePx<^8r&O;0zU^xAzfVa2 z9>19XR$}}w3-ND1t9JfF;~Y8uEkp5tc}V_I>*kLCr!xKi_@6t;jsK<_-1o(6=dPDK zFYL)~oOkkg_1YHb&y^RcD);#`&PPwlofi)Dr{_iV`6=Gt-sy`ejFxo&UQ? z_55FN{!=qR9RI8c{;f;Y{99|w{MKDEzi(or>GwIQTDr zP0fEd@$VS&e?wINnTDS{!!q+R?&a`y5#uJQ2w_>^mVR|5lQWtD46DZx!pmnE&sH z{1xE8?7w6`1J=J*lK+;W^}pMr`rirpXMlg7r=a}%%l>UL{`1XX)5reB{C{WUUmg5A zivH`*k@?v@X2!oeqWa$f`M1pSAGZFtQvW3XQ9S>xkNu1J|1QYC2KcYPLM{KhsQ>-s z`EQ~4?^N_JzW=Qj`L_c9rN61w|Lz0i_;-l^<^t9KZpHd9=Ks4P|2Xg;zf#SA;#`^E zGL-+VQT^|Z{4>G7&l3;aeDnXd*@XWgGxbl^znK5;f&Amaf5(Sv{yV9EL;3%|sQ!0F z{;jk8hpqqAKPz(oV*bAu@=r+nSIqyK^W^xq4dwq`ivGp-KkSM8v%tUeyITG4sFV2} zvi{p$p!)xvV*MBM|GklaP4Hi#djE6c-!bI>?x_CvLH=#Pzt2;^`d?EnuYWj(@?X`z znE&sK{A+=KThYIDz8wGTUNht0JyHE9kiRC&f7tp@{o6(EU(EmaNB&Ci-|&dq_@5&F zZA0V#y^8+D_kZk%{M&;6nxE9x|2q#N@&B+K|JB!$_f^yJ-}j33U(Ek!Bmczo_^;@{ zqexK)|Em7Q{QqF&UkChmD*A6G{%u44+Z6qa`+pyV z{5ydEB(2i{JA!|or-1%j4wd7tG}UL!te<-+$IQo}d3&kNi7>|Hi-7)_)og zm-!t-{(n@g|6=}s6!K37|4oYilf=I>rJs9$DPQ5|9h%0!hZX%-dj5|_{#x)~GhZ$K z<4M^+d&Erq|D@<&%>R!;{wna_rRcx>e!~Bv8U9B?`**+pt-F@r|8umT+xwei1abNT#to6LWGxSI0+XT|sz z$3Mp*{}hP-jxE*r>qz|DhT{KG#rW^qmB)XB%Rg`6px9v${}u1(iGSYpb5#}wnga!(%rC%F9Q&K?vy0^+~%T|M#7p2@@COZ>Cf&BT9Q4d*}E<=_9= zL9wHOKlyqJRV&LG|@xWj6p&oummH$mM{1wM=|F+9tH+yjG zB;aQs>EUP3D#riYX85c6@%ulY>hd3W)8N=Cz@JFz;kQ-CzfLp!_2+W`XS@6}-X0R0 z5ByaNH1VtYUtpMjj>|uN;F7T$fWLd89)3rae__G-Gb3;H+GE}0^V2#1aZAQ-2L5E1 z9)6bZ^S@rkKid$0TN97}GhF^HZdx*S8}QeBp@-j6EUNLs`+Q1nc)}5|0lZq>HAXe2FL%59;c_@EcnTH{&yoe{&(o{zq=XyucqVQu*d%e zyZ`CaYbo9TGXBh3eRBUx;r~eVzk8Pdu%G`?|Mvei|2tNy`QNFsPyCDPKhHt`dw~C1 z#r&_BFR%YOWc|C9ZdX(O_k>*kdvQ)>=KEjDCc5|Y_gedm%FOq_q*GuHd_O=1zkhi$ z-4A`j? zXKwY}s6{&wO{>Axk7b1TmUH|&2t^dcjA)o&d{?h9U^ZCcGA?shk;{Q#x z_+RC%zKMU~{}S{MUs=X{o&wgt)OBS1Gj#r2(fHqgZMFJ$z}kIM|AhaG(Lda>UHA`M z|9t*Q{_`-xM$`CLH2yzV^uM5Q{EOqC%g{gEvV|pRoer4)_Vsf9vw8CIe;eJdCjY+` zOZ|U(9ku*_W}QCCf8qZM^beP8F`uV^{#$G1>mRMh%*=m_#{VVjs`yG4^YnoE-&j&Eo$qTC|8;b` zn(F`WA?yFs&rHg!TeNNKu77y#P0vCnV&esA3+{;<0}u0y$r^Ystm|624v z8~pn`@mI>X{?T;<8UGzK^*^-#Pjmaf<1^QP{6RPVz4o>Rx&0@)a{IS4{eJ(qLw_#+ zi7#{ew|RfT{a=Ir;g)T}f7tp@{W~Q8eF57?`R~QQxc5<-pLZbt;lQ67 ztoHd=VxT<#vk8CvroxQ>e}#^J!rzMg^}z4j&w%mYk|6p2xtaKn%zr2HACbi$HvTEU zL;Ul%5gSeQPnBQX|L}jveGuf2>sN)x`g|V*CsKyOIAW;P>rk zK>n&*3I75!@gJH0F62Kti$84qQ+~%#{;TqfrkKz>#y^E-s!w{LyM&z4N@OXub8^@e6 ze6rb7CCkD8>3F%9^&eJNl0FIUZ}`b(N$s$zwC*kb-&1n^Yx;VH%=0?VcdxsjI>>!y zeY5-b_51Sc@lX2a^Pf}mU@cm_NctBmy>u1$$LIfE^nYBI|FHQ_{o6(BpUi*mNB#!j zulYe523|;^4guMR0VC&!gtCZG1 z;{&StWc^Fr|LYO-zajW%_qm^o(s<36|1E8D{yT>JKOWM5oUeb0`(HhV{2Kv(w_^Oq zACURkGiK`F6CwGx89v25|Nmt-&&zn57%?St{(m|DJlkvSbUy?`=aDWP2nWqJGuboocq`1fQ;|Anf5$xEjw)xQ+{U0XB z68^3);=e1!?|<_qp8qhVKV1JY%RT=|E>`)ke@(70uYa?j&BXtbA^m&tFXq2bWBgBr z_^)|Vt^OxS{97Gn_@4>M|Hb%CGUI>GFn689Yppdm$$9Y^nd7d*MH(R_kH$SYep~rp+Bd8=+EhY%U=9Le@_2f_2M7; z3+Z3X|DQ+yn}Pq@r_}PFJtU8R)~janzdfY?LXCfHz$m5hF9CmNa{Mb4zx~c8O8gG| zok{*UpZ|&DpBFLyH;4F7Db~Ll690~&_{|#OL03-Dk1wA%Pr{;)j$Ifned5Yqp&&$r8* zhu^ZRyUyvg@dewl)#3V&#*5r_F0b7O`qS5cv~TY|-)leP{jG!e^&-5r7jDPKX3bmM ze?K_0ZkB}p$yxo@itaj>1N{}y@6CU0e&3B0^pDGWzBm7kcWuYkfc>G*ho=VmiSzm| zj(=W9|I@*LLeYO6@o&9uCjVay>Az6pe`@}IYWaWNetnYv;`rxH^j{7B+Z6q$h=2Bm z8UHU8iGSyl*-HN7pU&k?X&0$p6bl;y*RNPRYM@U0t8} z7xVvj(Epa;zfRG=P5iSr&E)?pA^o2*?6l1Kmv`N#*Y2}iy5B#}e+vES^(=3l%Ul1l zho2_h=PGsGA(?T0KJ=%r^Yi8jUdzf)O5(4T&O(+%$T6nSl+!5^OFjsIf){~r3^3j8~Y{yT_&+mQc`kp2a~H~;+r z`DX%u`Lk;EFaD@p|JYk*;{R1eelh?15c#(T{(43JX2Ne9;(tw%U(A0#LjGC6A8%Ll zU-p>n-+J4O|JN1y#rU5>{%wH2L6N_a@H>Y1-%#Wi9zf+Ol@%TSS{vCk7@_DuVFME#of7guvcNF>S-sS!m zApefQ->Ar+ApDLY{&yAmyDs71|FRJIcLM&DB7Z00x85`3|2;*1QUAM;e`nyY-bStd z*E}!Bzhj91eO3PVc>I5X{I$UEw5ip`CQF^54rxsA=iJ@ z((P(G|FuN%`WM0fHS(Vb{J#C<6QO+bpZYsV{2RLdBQpQP$bV86f7t6^D8F6g{Nnn@ zZ;=0F;BTdI8qj~u2lD-|S(lvur3*-2X^Q{FLdO579mcU5IA5QxXFiqb_n)`dxZ}9Y zdSmrT?*4o2GdsEcrIqe@>9x+z<1*`_o&0l5ukC{V^txy%Kkv+Iy!Ixe#=N}nI+{q3#pd5B)i^@#@dR=)nV8~vXG{(YVT`mcLe&VQTu7dznn z(ntP%{NEzKoy8wE|0%y!wEXV%Z{qtOzDNF3fxnIBX+Zy_@5%lh!e6$qF!|pvWd6tb z=l_ELN8~>Z_`~`>A+t{ z<20cE9^&67{0`l&Cjb2v<6rRqg8XLyzi&SS^4GsF=Rf<>O#DaY{~7t=D;orV*!ZXX z4)HJY-utDG{fqmb_aHyqvW(Si?tcHBx0_y@Z~kBQf$ZNR{_DF6Q~w7j#=qeI4fz{^ z-?yLq4ampeNcbJX@4b(r)#N`i|F6h@W)^?g_^14Kk@Gui^Yx$Kk^d~Mn@(0|2; za{RMJa{a5hkgO|e@;^{9{u6P|{}uA@2J1gvitAtYi!#4sX#FP@di}?p|0dq&>z{ui z|L(wVy-4a*K>rf15-~Ylf#Q%vZzjyu% zTOxD4eR@4$PvEcV?;g*4n!Gk&{dZoHv+`NjD!G34J1_*)eD6EDmBjv@Zf z6#2#ZFD1yI0RGkiYW_P3zm+oM|8qrtasJC<$iFx6mkw0puX%;|H^dKL9~J5+POty! zhy42hf14tIH{rKFHsgPxBEP8r{gHoP;IAuH^B;eO)PF<#U5fnnJN)zS0m#1}@Rtu# z<8SMbmR;Jnx^Al)%6d-{|EA)lf@r){fqKjMb2ODt$!_v@qaGx$G=cp|L7+E9m3y0 zx2ws2sp9&V;4ee|^MK#Cp8?~)?jt$>of-YeeTqp26bt`QuZ* z$nozG{zkf8P5u{GjDNvD0{Jfke&2oul-=$3l;y7`OA^NIg3AR{8N5by!>wD zHSy#BM)&w*J{HJK1^8Lzp{9FF9y#8$y|5aa+x}qunmk6K#?kigr?(xZrF8|ikhsT}+ z|JL_<{97-m`M1CO=kI@s8YVvfBhmkV!N1Q_K>rn=%JrXpn}@&e{DWl%-*eCXui^4< zK6};J@WtWy_g6jsZ8(`+{+=HGM&@gl;OAxJd!FL|kJJ2L0sUW*^@F09(vu=6**Zg&1=Ko7Zt^cE4{@d?gCAK8^k87I$IdCzp()d5fu>aN3e-ixrJO%V` z6aO~x?<;qj>c6Ug<{kg7hZq~i%ClUe=hX#pF95(`9Bu@ zUz_DWZ2hPHtz!4@&Hu-9|Ff5meF*-$bshh|DAzw<{P)sf8}i?N7q9>0(Eoh!-%aau z!2ECfUcUa_A^xksDNOwzs#yPfZsFtqnlAt83zv_50{*Li&@=u!s{Vg5lmEj1TIl~e z@bB{!(7&@l9{;WH^2EQU`XAYUrOSWr&MU?ifPeOrCjU<>*8g7(`=5aRug~%yw*FK9 ztZ4n0W+Jcq5nlhkDb0-2>FZzKhW}H!i`w~bJWWJn4>J@0;spc#66a?gG~dqa-`cMK z8MPy0iy;16yWKh+dH(ZK9{yhT*Z$2+{FmRu{ZGXBzX9UEYNnh2bocVDf3*#gzyHoA z@t-Wv_*bSl{t5q+T>j~eBV*m*zf9BmCwp1VKl{V5|Mk%Sjo{zsi3dVH|FwU~;~)Dz z55K1IPt||@e4hW4UH&a9R*L-y{_B6xl>e&!nVI8Xk^k$U|C_S>haLZ@e~08httYz9 z|5Ejzyp{W}aQUabJu0>`tbf!lrf2@c@_ql0?+tM~Y(wi`b@%f6Uxof#z<&>|(*g6p z`ENP@Et3B&-xlWhXQ|Nj-#z{p{2L*|5y~+P7Uz{-qZS@Q*nE{JVB0KmTP2 z`ac-1f2kUxHvjJ=*S}cLghWNi%P&Iz*P1(O=i2nyg{@PV}{%?l- zhXa32nHql^;b)(lng9Q&$j?S`{>_oU9{6j2R?GjEw`Bj8A^x8f`5WHi@&5;||IFwQ z*S~D%j(?%Y|BdD2e`|^v|H~-y*M7+Pr=kBNz<=8>YX0lrmi^oP`u+3gUz*0hpB4Gp zN1T5;@*kOw|E1LOzp7K_cMS3WqR3yq7(f538u^a`{>0L1{H=ta^*7_cN0DEQ|1*&P zXy9-7O)dV}JFg}j!n zx`@Hs#k~87d*6Q;hyG#E@BO{kTF{?fawB{d@e4b9nsELjDHeZ&&0mUqOz4%Mkyciu|ox@%isI$bUTW$A_u;ZzKG+A^yJ< z`71W&<9`kE{|ERx6!}{w%ky8y5dYsH`BPTz`p2f`u76{pKV65sy63g=O>@^j3;Kt_ z^S!#~wF&6YRsU@0&sG2Kfd2IBrp|KfpV!)(=dOQA-k-nzx$D1e_woGS2>suh{$u|6 zFZ?F`5uR1IB;LVluz=qn!VRivP&`J0gE;7Ju0Ir~Ir)`42jO{aAWjX{&VSIbNG; zT0gcdeE)gJ`|fdp*Rl(sAD%Df`5(Ife+}r*Y-iA_nRT8v-X=ehk}3!4b^6X)}P z@%>*rqyPVb{{+obzSVs7zq+3s|ISkK{J)KES5y68Rx$qt|E|b?7x4S`Ga!Fif0^H2 zTITo3DHi@(hWz&cf7$nBoC@f_=UI9E%OU)Abi11T4^xbP z!M_Lc-wXV{{S3&T93aQPGu6!JzmfTONB;Y=_`}9OD?(vV9|LuwV_XB_9 z-tO@htylT#e`=uY-y-}@f#QF;(D6_B6Ug5N{J#AR82>G$GQUIk>HDec_$M;|UdaDI z7Ju0Ir~G!&^1Ji@?l%7U*WSqgAn=#-^FOJteDU8rNcPW`mGi%2J~^(^RR4#Ej(@_x zFY-SG{J#AR82@F1WqzCR)Av(X{HyYd&%d@s{u5yRuVOj1_0QTBWq!7rnd3jUj_;lQ z$BsCk|BLwF2l*e)@*g(;seh};{a23V>%aRW|B2wgQ_+71^*>O~f1eah`5#mCU+vYu z{gD3=@ZYeHTKspC{C9}|ihap;HSw1#*1wL`x&PV7e-ij_98UI=i_2I4>qpA@ZyEAm z64iel@;?gxeVzjH*RCXg{$UL>6aT9I>&J8d2O|H;;NMwH?fl;^;@>vpf3c|k4?zCM zviygw|I|M#a{rwha{mV-|0&?Vsa!4p6D!I2?-=smPtm{iAfNvpg!~Tp@1%7)VE(r+ zF7w-K%k!Vc{mA>Oss4{ptpD~#-2b7-Z-f7i{%ZN(N&K@?Gxe{3RR4z||Ks4_=P96n zYYExEV<`Vs{l{b6|KZ4gD){eG%>SB|Wq!+${{d0`AAsr$IA7OZw4Dp^>1Kk|L*#i`23?D`JV*;Rr{;)mkyERpDicXzb3j} zP5jF%*8djo{O6;Pe-8MsUS5sgip%`Aq5Ln6>i=lue+vBjJOzyZ7UJJF^!cx<|C$t^ z{~Uw-r-OfMklOg)M*KU5{11xi|48JATeb-QVe3EjZ;|}R!pDE>NNU%HB%|7?(4{|d!FIJAFq{>!n*50`8*>j1U-SG}anZxjFBbi11Tub^1}d%XNV z9{J~j|C$xl_-*3fGUR{psQ&+h{Lg}apQnKJzl->1!_CCMs{f8se*WhP$UhJKvlZ3+ z_YnWKA^%H6_1}Q}?OFcA)_>~XA^BgZ`lsq&%>Pe9{zmZMs_4IdRk{8-hWrmv^e^WB zCnEoI;6FKAE&dya%KR3||C&0oT}}0WMaB9ruKzv-`OgIZr6b9H2CaX@KO1bO{w*2R zzm5FQgMXi=fc!OOvVVv8FI4`k`WM%~pNjlvf&Vr||5c-8erpXg$NxhW{fq10=OF*t zz+bnLTKuY1msaE#mr>*wi^lue-ZFE%~j)X9xMB2OPHyD<%;~G{-1;V7X!aFPmRBNjjzmg)qsQ(ut|9^qM{9Hx;)5!UchT?x^MSijVcQW$7khT63cKw&G|JX&o z{v)n`I}Q0?1b%j)n*XMyt6@muBP~pE5^UzzZ&`90)F3q z2INm}D#yP~_zUGfGXGV`|8^FC*!ZXXR+00I`Oh`T-wFKoVQTT;eujMf=MetN!^w6v z#s4bd<3IDt)=^{KeBHq1e|qfb*edY-H;uZ!|M|5%_1~8eZihXTpO@Rq|Bu=o=hr_A z|JS1bcfh~T6Mw;c$3L~3ll)&nu7AG$?qmPuZT$Xk^IiTec3v$u8vJ+t;okov>i6HV z*VX*9GQ<9p=>Od;|6%JN^=}oq|Jp~m|LeK`n^udB1^?Ecdi*=8{+BAa|4in!Jj(fR zbor;x8xtD`{3%WK&w4{K{+BkxpL96?O)mey<}tAez+a^){~bksdl@tQRZnyN7MH*J zrZKTf;BOzGC;qKB75y)3hQIv<&VMuKzkf_@9pG=)mH(>z!wSw1-|`4?-jAREeT&OK z`N`+iLu5IWztR|7|Y+w8>** zQ-D9IiQiV_w+-=&_`luduRm^VYy;r$EY;+{Q_=r$!~XAZ`De}>8`}u@dvy6%$0)2O@P1VZ%zK+QS)yXowb&ZzgCxj|KSy}sleZ&iQiV_XCut|kDuti z-n6zgV$*@YYOp5%?<)E?%+K!P@n1SFHUs!unR`FysK>vyB0pQc(EiE&FRyd?)Ayf# z4~~CRbe)PXT;yB-u;-EWFLM0bR9~3&uT{gZe`V%>;{3OZkpBue|D*9zwe#N`i>&_` zI{zac`uq>#{~qLjAN>0~1@vFFh0JfQXlDIO)xS9Z?_T7;68u-3PvSHnfBhU1|Azdp z64n0=$p1l>|FG*{)ITe7|Kj||`;q@D@L$=a=D+b*^7+@2hT>n*zxe#?KIH!p{98w; z@h5MW!Y z`R9ZGmW$Q=caYEj9Yg-dM)m(F@_(A;KWzP{{w$BCa{pTd=f7#|Hb_OY2?2i z{I^|7_LJ+%xBeAxl=<0EdHgGs|J9@Ve+KzK2md}#0r?YK$?PW#PZIyOA^+nP{fqM- z+mU}E_%AzFjlb(Tx&GP2zeBgHss4{qtp8&E{{r&g1pYfNSL3faOXhbB`5zzE|BJ}q z1^#`W0@nY!t>ya1RyI@rRsDwnKIIsP5uzfk$F z>R-(NUq}91!GH5rBu)eJHU|EnzjVe3EjZx^|LG5>!P`ELXN)mN+e z?;`#kL;fd*_D`<=eFOQw2LBDTP6v(u3+4LntS_(sRvb^>S55W5Lb3jf`TyI^E*zZEybuj*fX{`D5}f1AZ0w*FCmR^l%%yppY^Z)LI_^-cOZT^#-Df_n##s9jB@h{fD-$no3;6HJJ8h__Sa{fESf8~D) zQ~y?1tbbzu`#$owg8$NM$$kdRf2&F6XG@#O|4C8(e}Meofq$Q;fc)*-lK5ZU48N*> zG5`G#`Tqz0%jT>3ucY&TL;UMS_5U97f1l+)Z2hPHEkpdO{>A(^h5UDc|MKh9{M*F8 zwT7AapRDL#tbc!m{6B#I6s^-i^FJZyKO_82Cy@75)BJZ0#riMizn>ug-Qd4n(SHwF z|8WREe;cvU#9tNF|EI|RBl!1u3h2L%-2aS?GZX)+{>A$DXUKmK_>W&t;xr(C*EVwe zTZZ_jMD_nM^8b|OKWzP{{%u3?AKpK?{^N7x{~7qL6V?1D-<9WoHu2w0x2q}t$0^o7 zG5`G(kALoi__uFRHe+@ADKe|9ke4^WQeauj*gSf4@Nf z`@w(ZjcWcYE|%lpnkTP+;lRg#(-i+3M)kiC`Fpbbhpm6qKPz(oV*a}b`P;yM)lF*t zyNQ1`!A$;d6xu(_L|)BQe*N>^F8}Gx<6<-6`q$E!p6g%PdwJsDmk@4;ZRq+}vHtTV z`u`Q;KY5ax|JD!X{C7zF*PKkYt117-D~^9+{{J=dKLGJ>wUGVfp7Ndl*t8v~|Ayj! zW5xJq7LWgLT>fc2<6^TQ{@XOgzpWVmYy~sde~bA47XAMQ@$ZY%fc_Kv$^IQf{#D~& z9RGA9|AP?!?eD6^e|@K%|7=Y&^?#G_@t?W=y|J3d|939`+}iQ68i@b05>560eZ~4; z@c4JfzpCk+|3}W>Ha@l;@H?9LZAE^zVxjZj{rtD~HJ88X_EDM7f3~ig5Zej(o5yRq z|HlW4{tfZ>yutnd?E0ToHzBqw@V76fC;n|!{*}!57x#bq#pSOnUo*Bl@Hh0+!_Pic z^UvaD_{IIddR+dkYS)bI3H%+J_-#dg+YrC-|EtS?P~)1h1n^h%*W~{rMgOZ5+P}O0 zQPIlp|5u0WKS%V3^`BaI{11ElTfKoi|FNd!;ny_(Uv2GP4y1bNj`RB;H^*H5#im_n04 ze`_r>>tB)i`yu~dS^Qz+pYl7zKN{n|^_hQi{{H~v{~P#AZ4##e{r7w<$G=1TmtREA ztJTE6X6X1Q{H4gBF2cV349MU73E{6a6aSI<2O@tgi$84qQ+}(+`NjA*2>DBZzoXn8 zmubG{tAACW%Koj1vj3W|NM31*|Fsn3U+^!E{EGplUpT3{&D!i{Z zbVp?V!N}h)i$84qQ+|i|_ks1Xe=+}A0{Qy`e+!LMzT^4gKXo-Z{-^%GE=>GaD#pLy zUlRET06(Mq8IZr~Kso;HbAneXH>Yw@vZ>%8Pc&^m{G4{EW=H6&xC7*1r^m~8rwT;j}37%cS@2}>y&VONlpuh5NcR#!~1^wCUW!2yCdz`O-it~Smq5ns~e}|&~+V|!9ZyWNzX-NMEwSx!nU&=jt zZR)vnT!07a|M|2ZCe}s0_cadvx%^nrpN{Y<}P_D`Jq7w7*DNB@t4|BCn3>Yww0?4KDr{@pCB|4!F`8~5+E zsdswu|86h-p+Bd8=+EgN`g8ivY(Iy8zJ1T9@XxpJdG}iOUO4~a{MQla|1t32sp@}U zGXFQ^fAg^ZyIlWeFSv2;wW%+9@&9En{-Hmof9TKYANq6p&ul-3f4+U6f4+UsyVtTs z;rxs9KUYBi4*0M9KrR2uTdG}hjxcj=^^S%Ad z9{bb3$NBg#=Km|B|0lqI)rV^NUqe3svd_%(`M;*)zv*H9m%IMUUvxRWHZ`Ib|I7E{ zANq6phyI-Yp+Bep%=UBm=iB#u3jcijo_DWhD}?he=Krgp|0ltJ#}Kvk|4Q=tmqph< zX&`FyUmezeh3mhb`}f+^>b>}1qZj|spVL3|=kyQ#IsIq0pTj@jzRy43zUSR**|>22 z#r%I1`hN=iH!0?S-2w9a&oShGMp*wlfbNYw=oc=T0&*7hM-{+ri-}COZY^!ko#r%IP`hN!eTOX;7|7GO!U&oOD zt-|`Rb^TZU;?DoPHnmGH{&(%gKlJDH5B)j)Lw`>HneFHB&$sXM&$sV+_gc1FIR9e) zzdHJV7W_9W`tO)6*MG~<`v1(3{?D#+{WtLZ_uBYDx&2$|ewe#>9=v&V0{V0Lx1m3m z|0MM1@}J6V-|wFt>~7zCU2pyuhyL{TJ?~y?@qX|5-hR?)SDeoO$D#jr@ZYWIzm?{{ zA^%&4^nXyJ>%W8h_uAB%x&5=Va{G@%e=h$P^yl)Qfc{+mlbP-N{X2a7o=?wzif`ZZ z?zQafkoo@+KhJmq`hO1mSEtnKzeCP{u?&6wIV+_9v)Ww$6)(G-UdtZL?LVIG&yoKY z^yl)Qfc{+mZRpSC-^py>??1)2PyMrpa_4`X_j}LJm;Yk^zZUv`9{eX2{U<+@*Z&+t z{Hb{)p+Bd8=+EgN`g8ivY(Iy8zJ1T9m;daAUi|ZZ@A>)s zi~0XV^#20*?@{#MO3weW)-!YdLrqBk-uNfZ|C=*7bNxaL94`UqKeTy+i{QWJV>N#J_~FuZOO7G_ZKL{M2Kk3%`44;k3-!+o@vHh5^Z!Z6 z{}TAOmsDH-Ya-`AIfmAMw^Q^l*1sns|I5J7K2eMR$_4WHXHPa$|F&1;7w3PTj`eRS z#DCqliu{Mj_0KWHzm8)46YJkq=>HY)U#sZ9)OT@*lSTRTBSJ z(fW6<|Eig_hC5!ZkNh3rzg5wHijMz={O_pfKVHfCry&1Q;J>_EE&uBm%Jt78{PlFZ znm+$oH+23J{~IFztKdKJsTzOXX(a!rn92X0qWa$m`IiR&K2IlU2{D-ao)W1XW-;JWI|Mpq_6aND5e_%+Ty|Er(K>;E+59}fQG-;p>C$Y1`Y z9RC*K@1Wb&6#wgmum73*zX<=;$p1F@_jwA)-$eM?hI0P<)M(<5?0*LGmxF(wr-1x5 zhs*WfGQ=O*|CY$#3I02oTKuP||Fh)tUpr`B(d7T@sQEt~`A1~=4_p7Ke~09Mq2fQX z|Cz}D4*2(Z3K;+PBDwxKhT=cGe|P?qn9t`wTOt4Q;NSjUE&gi>zfJfne<0h{6#tVI z>%a9GAOB|||GVJ7Vj&u4u~tZx!>u?OI;{w?+Pu;J=a9>7e|Z$nnnze~NBb6MvOr z{TKdsK>iQFzt2-Ze%q4y9m3BygN-Ks$o_Xk{*}PL&r?AD6p4Sfi5&k3&VSRyAKt$^ z{>2CL_}>ZnKLr0Nnx_HzTh1W)Px!08C`|r$N6r83k$>eZ|6%Jt^=})B|H%Gpk^dv` z@ADMUzdeoQKk;9v_*eB`dL57dosmBd{+oUzaT<`HeJOwbX%qe~x?N5AKP7bick@3v zpO62$B7X|}chNiz$lp0#_HS8o{jlrR{{S%PXYOzxpMup34fvD zKeGSbk^f`x@ADLpzj2<-?-=5b?0*;JUp32r*!oZXGei8U{u{b^{o51yKLP*EG*1Ki z@7a>%|5Q2uo#hI%{{OvV{?{cr{~pLc3jA9?kvbKSzq?xIXN13*ZdX(NTVJvM3;zk^ z{}lZDJO$)$oGJ5Lj{NyI-wZaI_#^w@8~I0rf1js-{1uI){t^EO&VSRyAKCvt$p0Dm z?^ewJ?yY72Y*RV^s~3^H(!~Em)coHI`B%&GAGZEe|MtJd|9;5-Ir#T^3K;(_XUXwz z6aR&Ze^vj^HN5`si~M82f6Yo{oC?U_{^WAf`92om?=DdN-$1ecC%56Be;G?13S7O0M(tpE`FP3w3IMwp`Prj#2_4Q;r>?=k~^T^!K%I>wY|B?6iI4Dj(sWZj- zTao{yf8;+s6u;FkPyYADe^sIR-Sux#{}0CaAD5N?VaI=(|BS@HPmHGcSIvJh|2-V} z#{+*49jEw?=ez!)r@wsu7n>&gulc1gt8y|JW9?e;@R~gTx2gZ0!sP$PA@kq!FZdgfzY_Qv z-OqsW-*z5}|1HhLe`NmSkbhzpf7tk^{0{X`6F^h`N9I2s`PT;iT1EfKD`o!{@!v|f ztBHS;sPTUS@~;E@zWods|M4c7-y!@|zpmrI$o&67{&lnX!^S`5w~L%#od13z@=pT( z#IK}I2lU^*vwZx=wvy{#*>7aKn&RJ5jDNv@GV-qn{J#AR$lrN^9RD`qFI4!Mg^R=afAie+kK`rtI_OYVQUYJo6@2|;XF30U@!wm=YW%#k-u{2YesBIK{GW>c zr+|N-C;oc*=D&3p$@y>1%){Tu{yRo;|EIb9V{cxpk?|j&!TB4x|L6LZT%8{Of70XMQT4yNVgF~M|F6Nn z&r`tsuOP=imZ9|zRsZZ1{`uBf-2dwRORfd~O`7~$yDH}Y8fN^Le!}DbZ1n#P_^+pV z8qj|kJ^mw~|HnrbCjWaB^S@?0&VP=}zuFi5OKt%F$zL?(zpDRnhW($5{=WtPK2HJt zmkySX|Jd|A@vo`=tNQPp#{Hk?@^7)mfRdZRe@l-Z|JH7K`1$)v8+&}A{kzA%)iwP5 z$MeyDH~4QkR_*-HL`wer!y^7GRw_*X|Eik*v$_8!m;dR@2bA0n{%e2LG5yvo`;_%KL5A< z;pm*7KlbwU(A{x<|F4R7IsZlI|9kM?N%NGyLcaB%HA`1g4V=)dJ+`S_3RnJ4}=<-e+bk^h&v{0ko( zSn>e)FaJZ2e@D^3J<+iL%h3Oi;6Fw4G@$?bFXZ}f6aP)|!sP$&iuqr01h0S1F8{oW z(vnBPf5V@8{9B~{@wYL5vyNf^m!tomz`xH^K>rPkWdCe0Gx@LTKYkSV|6lIEuC(My z@NfU6$G@ZMf07yh%)9^T73lwG@Nca`@-(3Ty8p@b-zNU6S0&rkRR8}_%>S-~x&JG< z|CZ8{cJSY+$-hPFU;e~*pJ7in?EfnC{|or{c?#&i_HKFopC!!XzpDSz-7{wx31l>e&!rxe=1d;Y8a4d=fG{r7B(F5_Z>AXkg8wGu z-vs!5`x%hG{aQKx9m0>|`ESL-esI=TL{ zS#tfW__Hwazqw-k3;tV>e^cQ1?Poy#%IoC#w+Vlt;y*I~&B(u57Ju0Ir~Fot^Nad- zEAnp+{5Fl#fd1>ZlkflN5PoMonOAD6f72A>U+~|K{L_Hnx1Ry|%Wjb4-`Ymb|3bxo zWd7Tbe~T>su<=j%S&{RL`gaHNPY3>v8RR%Mp#RFFmZNzmslPQ~Xa?jDNv@H}Y=<{J#AR$j@$)kAED(Unu{o{9^s@I^_Qy)_;8KGy(Y= z?;-iWkD2^eUH=jO??V2WS^mT3KlN`Ht$+9YujJ8V-1AKCMgBj)e_}NVB-_=*Umd#s5&!oi|DWLB z=P4k6&AoE|Tl>oVd^6Z+;*adV4f$t*f1js-{PA04|2FZD;QTjD{E_`1GB{HQ;L=9+ zSC;><^^f|upU89nCr$j3{ojZFx5@G!mY@2!{w@9=K>okMe;uvU0pq`$K~ir%dCIwfK|B6^*`eH|3T!h0sq$4WIqG)H{K%GKZp45rrXsN|1+Z2|3{FY4TR6X zsHcGZP4^N0{mj(=$o?Ni{%yg(&r?ADid$uVYdbUik^Mh}{IM+mVe23DZ~a^RKaBj_ zW%&=wPyMrhi~q-vzXbgE*kqkHVEi{cB+q}W{pI*?s33J!Q~ir6)_<}7}Np!mOEsAoA|HUhHO_8|CUkf|C7kS82I;j3drAcKdFBQ$o~0eu+hXH+5c0>zXSO9 zc?!s1cbm-5wl~8c+5h9n-!IF5*!oBPJ0$;6JpZj&{6B&GJ7)P0%TN6~B>xM=AKCxY z$lo9QSFBFzRKWOm+T{3mNd8x@LAI;Oe~DuK7xVvTkbfue-*E3rIj_IUcl}f4?J~bb z^1rsGF#KCZt^dy<{{Zms^Aym3;sKf8nQf;2MfU$Z^6w1(eVzjHcM$&$@n5L?kL>?h z_1D{{JHK?*jfywR)949mu~c`1g4V$e*}Vj(?l@FBE@d|1Tl`;4J@P>mT*+ko+$ce`NnJBmZt${=@Q9 z|JJ|7|EtKqIQVZGr&j;0hvfKoNd8;n$#yl>zkZ7KUwr=i8uITB{>!!_`x!9*D_RLZ z@gIMktgC6_-#Tjje-rta0RKKu0r}gg|AWlb|H%H|LjFC#zt2-Z{v`2l?P!KSvj5kS ze@K@9u=S7nxBe~u-$4F7v;2qUr~X-y`>$A!-~aAype<$@)L>AK!s&R}=p%#riM&zlZ!o!N1Q_K>q4S zi2p-m|9mspXyT9T|9#|7r1PJ83d+Ao_Rn@Q!ynoIJIG&_R)94pCJFf;NRyd zAb-QxvVVv8FI4_V_Wu#`FO%gzZ2hDD9Yg1TM)sdV{{6E2hvldK?SG5^PmzCF@LyU< z>Qun^PdzW^KRZm$|2Dc^P2>MS#riMS|35?i{lR}#o7(tS{*9dfjC}t~<4)v#)x=*D zwf-+e{$b$X=P987mKTWs!)5=4s(+FFcOm});NRydAb;W|ncpV<3&kJV|L4fRT$cZ^ z^^f|uN&Xj#KeGP?$Ui&Fe^`F%-zswdr33l(Utb{qaPVI?k<_Vx@t-2~&nEd_N4Kk~ z{*@}$e=-0668Y=W^?zqI{;sdc=fC9pf4b;)HSuq&SpS9puaUnT{QEow^xsMAU%i?7 zAKCvm$bTUC_jwA)-~F;&|5?88e<>FKi;#armjAHzkNRi-7XM!%|3O*)!}3%AHp%}& zjen8z|6Al=9{iWDtycfyF;f4Ikn_KtZdX(M4^piE;{JDcEh(;ld=&imbh-Rt{r5~+ zK{{{LxmxBgl>fs+*MIl=H*x&ajs6b?{^nXW|D7eWf1A|5CVE_@$^Ukt`Q7WE#rXFF z@~;5#?~Bub^*{9rssBfs@vj>H!v9ame+c;Zc?!ti(INBO`M&?CSp0v7{3~Yp51aqg zzfJ02q4Gbh|5W87wk+&S{MEznoO24cY$Ei-zbh}=Dbw$@W1&A?V!M`h>w?$D*IvZn za$%OfZalr6)OCks{?3B_VbJIOz1Jq7KmEF_?Xb-Ayw-;PLFwn;?e=@^9nhbC-O97v z*Y#R^U3dF6#~qs4j@Kr6e+m3edVd=K;;#e$&i?VP{}u87J^DX1EB?d!r}5AJE%E;| z@{ff0?^s8z{&)N+uYcL3{#C3?wyP=s2P=;M;{2~)kpD37pWKD)Cl8){*MHRgD35=P zeE(C+u4KEK__vQb{{4>pD}jHXr-1xruaWwHl$r4_tp9I6{+3OG`cU?=`#GQ2vd_MS z`WN%nt$4a0-h;$0ZoTx{&7i*q`n~#B`?kA12l{i>zZCQ@lYTEr{af|(^mby*t6No< zx^ZGde|kHhWzze{=@Q9|2Cf|8kT#{#zCNw_Q!@binxc@f~fZ z{x!yZul$c4KL3BC|0BRZ+f9wXlhl9f1ew2;Zda549YT+PWtms*dW?VnMF}4Nj{^T? z*QoK+H{CYm|I9dj<$wNna#Wn99}a(XL7RT8vYPui725Q};SV+jUH~4m_+x5CoTVR0 z{&1kpJU*z6eFDE*tGka=p-n$N=8yOqah850_#+8z`VsrEHueOx@p10Mf;Rmq)Q>Oz z7eoI?Lj3#UlA`9YgVdR-C@_ zKmXg_@S|AzIJfKQBQnR2UVAh2r{{$o^WE?N@!Hfz@O;>$H_x+0D7uRRU=v*SE@lN;wL=ugL|7q?zsta4H+HUxUh&vw_5 zyw-;P>^QI4#Eo+Y`Uk`Fy}X#p^J1}+-RFD#ja%}(fd1_K@;LqxI_rOW@h?9A9f1Ci zhWPJ1ZKSl0@BL}M`rrBoIsQ3O_Mh0D%qukc-%)Y?BjSHB@{fV|cQnPnV<`TQi+hHG zwaHJ1vh>5@kA={tAF2OIHvNe2^=WKAwCoG_ zF%{bM<68bmL7RTWzjPl7XwwfH{_ZqrQ~bde!QZDJ1^V&D{}Sl`7>Ivgobvt17yqSi z%JUza#J>-xkK@1kHD3RRApcm1|MDcs(}4Vx&pKAl|9ZMzP5cdU`pWuYmY(r*X=|DPR86sIy7@$FC)Mr78Z8kJDHF z=YM|7ClS{p6d=$6xvv`TS#~od0!nyPEiSQXK#5ujch{8RTCb{5Mcf z0r}~>ZapdA|G9&1R}=q6tI}8g=YJQf{>AtDTygyWyie+%i2r5Le*?t7FHQscZ+=T2 z|Jg}${QInE@~;~IR>d0bJbxJSuL1F2F<&kJDW5~?pG~)`iGSme@gHaI`7b>u^88P_ z>%V8V4=Q~Hv?thxSek?;S`^_*ON_6CLh{^Nq> z|KE!F4}aGe^BWpOyb%=RY+69Ygb<@cGX&nP*Sp_dh5{{&A51oitB*kmeiz zeX)F;nfiBk-1o}=*a1%;oPI*nsXYHjxcp~T3@&*a^1q4c$$v*N|Jla>()|Buf!g>F zf7ciJFFyYtj`9B=$p7*^)yBW}m^}VlWc*L1$ma^0#=o6I&wt(gZ=T7oe_0Xv$3y-% zUZ=)Slg=`f|Mx&bhxvi0XY$`ZgXjN9p8t)5OWue4Z;t87e=Cuv{`Ioc_9p+*{9kLK zTK>b|nazLKf5SZPe--Y(YjDZO;J>;=kAFwi|J1_z_u{|n4nF>ma{0#&TB2k@dj6}4 z-`ZO-{x>zl-}DaWAMNs2Z@EOtBH(BJH2GKM-`os;=N&x$S9AH>Z(gFL8~7{u=Rc8; zf5`XW^-}J9-S!q{_?>$={}`A5i@`%megghhUH(=1tIhDYJjnUSy8H`khm`yZ{H6W% z#6Kh7f8`V1ONYIs8UBuUIe&%A|7`P+l0Shzp^4vC&7b{~9j;>NhW0(jWNC2Iz@@Ta|y78UCt8oPQkWA2GCK5b)P& z;%E83|D+fHti}v~`*)mwyvx7knL|s40Dt*FP5u@6?QPBQH+OOV37r4ep(RTJf4wGt zM!x@~H{HJe?alC~MsWT$IsbuWCBuNfT@$~p$ZzjZXnyzlSF!%Fvdf=7kLd(h|M0C- za6$Rj|0+7=^$&-vfA~E2@%l&UdE9>-`6s~oM@rNBhiz#66CmE^`0fk8uAJk$+9_Uv<5n^)H)z{_B&XDgN(M^xyFuKmM&m{*%Ced@nWr zM1MK|?RcK!e@*$w3u8jYtS$zF}J>;(h z|8=$Ga|-_EhV{=H%<#7XP?#Ujf9rL;{!d2!Q^3ESP^*7ErLup^kpEp3{fqfe74lC6 z|4o|4Kg*E+2NeA$=5zm3klzOXor?Zzn0)^moA|drA$g@~{M#+6|Mii7ZSdcv$-iyL z|ASHeZ-D%#f`6YUUR?6kzw(&upRHo1{;B#G^WP1Te;x2|-Jn+gXbpBonc;sps{gf- z|FkUsVUK^Pe~08heSh3h*w-7nBeMUEk$+wAUwxw<|Lklt{vT2F-*zpp{~ICy9Pppo zTaCZ8gyjDzGJn%PWV@Q`|L%(QU*x}q{FA_c&+dBW|CS;DPet`V75PsG|2|JVBlFe& z7UJI~{(XsEEdDn|{`J!SHRZo!$p6z({cnQ&XJq*gTmPwltH}L3JM-he&5?gH_;0z1 z)Tw~+?~Ctq{PZNzj+Km5~;^HL({o)<}3;)xRe;)YvdE#5mSO2T}$^I?d48N-X zhM9c*w;K7Ufd5)e{v9}(KG!;;kfbU8Uyh3{2KvS4e;V>PX88|W|EYgg8--!=ox+{oll=_JPqNQ8fNEzXtg?g7|OK75|3n-)oBTFRp*w2Kmnc|0z07aU=Q0 zzq$c(d|PDwyQzcZm8S7;uh8-DW}f)`YkTD182p#rLiRHtKMh>l(DCoGjsg&rlNl_|Je!o&jVHD9{>Pu?^WR;N ze=7K|*X93QnV*+YY&7w|9o7G?$lnD1eV+Ip=Ntd4OJ)By@sHsAH%ddc z6#TdA^1qrH|D93&*CPJ~S^mS;f9l^Va{nU#_dx#5z<>NUwfaZn+cK2@?81nzVqJOdevk&rL0{&~?P~%Symg~Pw{FlB-wyUZB z@1t1%J6GWT_ecKe;NRBe-_ZQ;gQ)%wK>ka?zt0no=zR6xT3q(ePB&BkRsDDW!Trxh z{%Y`FRj2s*pU8av%Xwz_KaA>sKjgnG%YWGVPyIV2|LNPK>+=s)|5c3N|MEcOp8@_W z?;v%G?|8oWr+k(n{~sy(7wbQD$lnb9n+K@Hf9Vo({@Y~zzw9mYzG|xf`zqFd;s0Rd z-xB<{9i!*`SI3b5R8;?mAphmy-{&b{{C80QhU$NK|L*r+Rb0XA|Dnjg75J|xlkfZL z<#pKnXXl%#|FB#Y>c>0(N#y@Q$p7Cg|6%Jt^=}oqfBV1O|KZ3#6a3qn{M%#9_=m&Q zP(Pl3vHo)y@?Qb|9a^XP*7L=G{SdkSJH&syvoQ64ztHucod0kn@?Q!3zWofy-$nSX zGtBsp%wLcES7q^s&40?zikx2@{~m?>R|9_sjnjbsD`(5+|Ja1zey1?;zrSMq3;tt} z{~F-;?Poy#>N=U9%{3GMk@=5C{$v(^*!ZXX4)M?5Mr<_Ae^vR#_e%5Fv{v-3Bg#0&W@rR9n%I^^W{B6WWQ~gurZ}sB; z6y(1J_-j8RaT?Hn%UW{$Tf~29ifmUC|AC?7-@X5R&2N1DV=b5e$)2T4hQs|Y8%p)u z|CG(n6aN?q@^3p8`u>+LfBoW||1_6>)auKWi~#-)RsNM^|F$B(9iBf_B*poa7iB-W z{PCOI_0DOxZe3Cf{4LWo`L9#-zjLAeyX!w9|4+sIzZLS|m!|>qzq(TP?~weLgB<=9 z%9`)5MTbKEXI?q+EPtO*clozCcvi_?;6E{4kAGXyzrBlL|2F!+Ez5t{@sIkqi`GAn z|91X9&vp5yfA{w(dxQU)-PHVByUFp-4phs3yKHpM^#>8~5r6Tmf1iQ=ZwLQvbe!g| zmv8-}Y9ir3Q|7PxxG>}YL7~Tg;=j@5UkUv03;x;eYW~?d%SqmBMgMFm!~V}i|960Y zpQnKSJBfdr`1ggaruwhyzw~>a|7W@UUv>X|$^qcNeRp^LFYNcfbQAyVAUXbh{JnJ8 zrv1-D|958j4_p7Kf2(NyyYt_kqxk)QmK&VO+Z%T{zT{o-U-hbD{u7_}A&UN&Hk1G2 z^N+L9e=GPe|Af?O&XuqJC)bwizeD`D)9q@?|ARxY`Q$YW9>&X7?EA#O8vHzxXx&J1Y|Ji>3DM^9SWD|JGG``1{y@;&Sf)QkVa%i%%%|5&XAl^6#knA8y$HMd%-H z*&_Uht^d?ND{}ueS8@N%F8`UIolx=%`0rfOJ^wrG@t>E!UTYnmC;q)BlGYw!#=p4# z|7GYOZrQ*pKPPpX?_a+8f7c|r{##>Y{uJG=ru;utvHmBo=KlZd^3U1t#F8HHU-q`9 z@n6wD2?y=}^w$4`|0~e{{ovo{DWLz>^<@8!q5N0%FOL7ObosA8{lt>rz<-@4|5m*m z|3O9C%Nx%B%h7*ZmjAHzpZd3p*1x;{EAD@P74km-{8b;TUH{WCS&n~pwd}unA*rjH z>fd3Z>mT7yBL9QH@7vFS`Cnc|_>Y(QeevIS{FzrSFXiX|9D)2>r>}ooO3(E#mZ9rk z;BwtiKT!WO{AGhV|9s@11^kVg_-#Y{aJgcrACJFoRet`%b;!RB@TWBKJBIl0ROA=_ zuSfnG;ICR*PyDkcGx^`D$S?fgfc)D6f0rhH%Mkzn6#1){;`x6g@^1(H)-rnh+lKh> zQsnO(&iQXb{_TOkTNA%yi2rUy{_>HWzXkbs0RH5%di=8s%;f()iu@w}Z$|zdfxkx+ zzh#L3UPXQp|FzZLm+2L2XJ{Ei|2_bc*?_`ePLYk|LZ zIX(W_g=YM>De{Z>za9B^0sdA^{FWj92Nd~*|2vR>SKvP?CE2bf|MiOg1^>Os?*Koe`x(%G z#fCCJOPcW?ng7Qjne!iG!1;IkNi(%@rR9n%5N7rzo>r? zApg_AU-uP>(}4aPKbG%*Vv)~(9J*ai{*P3Qf5HC{@;?LozWofypZtXIUu&lRN9KPJ z`Jc_=4;%lKpA|X3sDBS5e>?Ekf2|h(>}1)$P59&AknL)U|DzP+U+_PQ{LcZuZ$AUZ zfA?N;{kKW}du3m=#lrsx@;{%&A2$9ezeD^BZts`Auh);}Ic{yl-eyqe@G2Mf#3E;3X9A64WR{+~epy@0>I zS&x6q5dULQ`JY7oMB4udJ?nptq4hr}D*sc+zjxZdCVtzH|Hl>i#pgdyBmX|Y->!+@ zF~t8wRQ_j>e_!B_FRv&5*~Mn+-;+`KpGE%tfWJc%zh#L3si^$z$iF}E+bihtZ&jG_ z|Fj~%82_I`{sVx&Qxm^!$p15n{9^on9{Fbjf8~mL{5yvDpH<`+_5TIruLJ%@P5kT< zGx6W9$S>mmMdUva_-kHPJO7!^|7}D0|C}Pfi2s+6{~+LRn4xF>ZyEah^La&n5&thE z|G~hY(iH!;q4pvg+f9zccd>qB~UWq1} zIl2siET)-$6oViT)?ke2N3{qL*2V+@2F|95>NQnKCQ#_QkEP2T^p zu1xNK9skqT)l9noam4iB|4QEfsPy#z5E}o|%o_h+X#PJnqvQWVU# z@Z|V=+W70ohne;Mx1T!x-TU8jJ^eqF#=mh#ZJthJ|9kcCg5><~RX&sE|I;%%{y|Uw zpNftD^xpr}$KUytkAL_6|3Xjy52NvKTYl#3|IRNo{?APR_$T+jmwNhNr2bcDQva>h zewq1Sng0GKkAFM&^#2)}|4pwY_c2+weck`9zMuU5$GPg4>Hm>G@%Y!h|GnJP|Iupy z`~A$B|K2Y&|DT=F@qe+W|CQMIPw)PxkH7URAOF^M@ci2=J^dd;0JNQC6*x@1&jhl zfnTu#xxMRCf3NT>Zn9~bQNSo*6fg=H1&jhl0i%FXz$h?{3Y0FVXS7qerK{5M;`8aa zpTQ3^{HKI8(CnzdjR)0kMD4Djbn;lb-?<&n51a7CDQ|yr$gK(&>k_^iu{(Ac6X9b0 z$WKkTpI~wJ6DU9AyEK;hVy&B0+#Y_{7Klr@;!At#_T>1k#?RTz_rR}3`(5w@jo*NN zh2Yoyb@!{YRkvu%5Pm-eN9#mvK=_h`x2(y2#9Bv_|JZTfUxmw8BV74uUWeZ=F4k*d ze#aP&EA~pl3&fY>eEZ{E&pL+VTCL0%YZJaI@!S2;QGdj4O}L6%S(odJb&ut^#Wipo zhV=+napib!pN03~6R!F@Hzjp`bWv&T=r|t`J}}0YQ>DT7R@Og@(;ny6*ICaTi93m)$b1E{oV%NdLAEF#coZwIxe;B%g2AQBR^4ija6-8Ti8+gpEsI0Za}y?U!b2JMaNa|HopE3BfN)i-^;l5nc`c$_%?9qR}1(K z;ql{SFpiJsF5#*@!fzPM{;wc>p{SKq82^0kT5|tF!5xcO(fN=~xcE`{VSnL%xrEQ3 z;^!*(QRflr)AT#|`GWm0+Vg*x@CC?^v{UYP_=GFn^iL4sI!gB=GH~n5bbV~XRloF) zOL%I(2v_<@zg+3pSLuF+6TWa-`w5Th+}z0egc*LUu5|x)2CnyKPRj>tkB-)V@wh{y z^GLBF@WRo&{>9d=Gdi(;8piYA2X+aM=0_XO!(n~G=b~|ybzVFU>zQyFS9SjEa|M-U$0 zFQmT#;c5L1f#nv4R)Q>;t4=%e_R-B|xC2v_=u|L*hu4cNcp#y1CLFu&UZm-dTpdOVY71-y61MeDzMC+iq~#?}We>t5`` zgsbtE<8$F(c68kH-W!*gui;grqW$Cw!q*|btOK!~gbyOTZ8FyvYjuvZ)OEXq_K39! zUxIL%zhbu_T=|jn3b8)nYJQZl4~Y#UKRxsNB;233KHz@IylMQH_cfbv^OJ7NO!UO z5ndoavad}%hxHD@mv%~fRF}-hC}0#Y3K#{90+|Zb&L183dzJrKmyY)$YQWqX{xn*z z>^EAx8u;nb@Lm-)VDp8huif8Ir++P+$r=TI4GQ>gFA|;q%YCGWN8&yl@b>NadfmB( z&*$GKT%E7h-OA_3Vr$-AB=!EyaKhE~tvdfypKw{e&h!aa=hgZrBz*4Z>^WJo)_W>$ zjpZV)*qY8oto|u{m+-XvVP1qMeXHD+gvYOATMxr~e?CZW=U~Fq?pIwwc)Y*4t+>Bo zh9CRG^!~bpr?vki!c{xve7=0b@1lJxBs@(|>%SRzZwU-C2P)vNXeZYHfw*5C0GI2- z`n`A`=pnDit-UIy>;c4sNSuMSt;|Nb%|8Ei=@9)I5dHvg~r~7dUPuuT&!qeLSAmM52 z-(Dl#zmtLYR=^;0q5{Ev$4Bemn#A}0#D>7-zMt6I`;U*-zub2c>k_Wkv+NggKglOt z&11Q5CN>~^Ug8J$a9pvU!hh*3zE36AeUSageLt}t;VQ1&kCg8Vec*E6Pi#QAy1yvx zl>2{SXIX=3-DE$;` z6CT&u+~20bG@qZWK=5?N`UfuSUTp0%8S8=Y_`H<$;}f2`{s~WA|L|Wuo7cZs_qmMq zPk8G32QKSgY(RMG`j7mltpDdT`b&7~`X@Yf{S%(L{^6(B`hOu~{SzM7*{uJcJoQaQ zrN9OBds6y7z1Q!51=oK6yA9!ksG9sUyME`+cr|aq{=M-N%2z)7ldfuG%BN`xR?ll8z51ygsEpKH=)R zL-vv8!F=5jz>oayS1g4zAESWfy}oU<{ynTiu|9B_Pe-4_zi)3RT&=?#ezz|+{P(u0 zzyG)2ApbNg<-A|)7KE$cpU8Q83+C$sgsbanIbMsk|HFP{y^3`r+_I$IVqL=1)|*GT zT5r-0u>s+A6jxvWb)o7nsjwxUH-NR@WIwWA#X7)6H(CF#hRZ%;rl3*4DDd+s;5<-c z<$gZ*)9rcUM2Fwhq&A(IW(6EDi}&+3Z1Rlb<^m>qU6a{d50I z{=LAJgvYPLoeB7RBBQH(|6KdtaRtKF^8)hwmVy7~I0qB1?mILc%Js$89A1sS|1TWP z@x;1>t9FW?)*twL#*+w7YfnhHx-THt?ehIa%@N!lxlbT=JHl0a+{3s%VuK^AmU>^1 z_>t>>>!@nx@h9?>NGjCjZh-dH&}u!lSsGA}*|ZQZ@0sR(+XuzLM}XzJFFVdVZGC`x=Ahvzb2$wywna zCfJFvU9k2v`qkq$pk1x7E^G&E8Ft_tI=;GICZDc={cz3nt^X<0$=AX<(^=n@_C3OJ zL&?Lhhwt}%*Z?+^@BJR+dN!;B>%w}lK5PixdVX6BqSzGfc<95mH@@6YRgPSs)d znX#s&GgAQv&g6Gs#_~Qer|B>==alg^`zYX`sdL)-uIX>`I%oEov8JUnQvnCg=G60E z({J7fX6BqSzGfc<95hwFw>Fl)ubc?oMUo^#Nj{~=tSmr#G_ zr~COI!qxL0@|=X&nk_S){~(E8Itk*58YIhxD)qRp8FA7TS)J(OL$s; zeZu2^Ur3(+2?ISnSF8)X?MTMOdJ3l=iS7={uOVEGx4);&&kMqye5}H2EE#99 z)^Y!-QF^Jr52e=mI`a2t36GEK2Eg42r}u(A$j@Vm^?-+GF)sER!sGLx^FzISC8iBwB9CMy;n=x*|<5cTlWO^lYfZgiuDOs@ADOXwX+Vg)t;c-7j(l19TfFD`+Vy&_Nsi~#b=>2sFkNau+J^Dqs z8W(B5tbc;c=eMZ99vScd6I`2@TN19;x%}O4u>s*~-pG6Z#9G6W@5Af<``?5sKl1)S zv0fAN<-LDmuOwWpXPL+H9zknQjw|o|6KfN$-Xkb~_gn1NgsZsn{y?$rpE$1m{x6U4 z_&y@<5%dXH{gr*8`|p1fuHGXk>qpjq&0a%mS0Ge$5!+0-+8=wpM{sX$kAD0Q2v2KI zNVsZ`tb4K6K8(wI|HRtBrJeHkzsZI9%s~n`=&SiYjE{eFst$9|ls8>93K#{90!9H+ zpyrVwwdy|K#GUNuI#R4l_-bS6eJtAf{}wM1pUzk1?|z7V2)Mg8zb99$^YW0|`1^3= z{QqRam7m;W%ol5Q45?j%+9l`xVu!xR{JK21Q|xx{Gv0at|2;CXVds$Oy~A?eFLuEX zhSdI%{4YdF-FL{n&d2?mKV(1Qm+VKZ`{j^Ybw5nb^Ebr(h^q+yV+?N^%zm7&IIf&m z%lZF)gsbZg(M4=XxH@mwb+)=#H~sv7OTy!E+ZN%tA>r!2iJbR~o$G6kEBcD{2v>2X zopS!~&bw9AU%}=2|4PDDTzOx!x(TN4JJ|DW6~&eJ_=t4~m%lHrbZ*D}4wrBhS9oGQ z!sGKKe1q?+JV)u{Rvk(hhs2~u+IF<*YE%BPq^Yw!n_r0FOc3&f2pl% z=OZ0NAGv?@F5zlE>v4mnIj*{HRUdi(Pbc9juDm~6tks|6%5|>zw}H$3MzIdzaoyza zL0q{?Qa2y-#9o!#BkdQyL-_pE9`P&oK*Ci!<@#J~Ffi#y#_Mgu5CQ^EWR2v^tF`X|ir?{3KRS>7il_Bz7Vys9HdYJS?-2mFn= zopK+z+Y+w!rCy(*Th*>keq_9w@%M~|5U%D!!w5TCCt|IwSvTE}O}O+|m35%M4&h5u zzA|q2=vm)7?ZDRGnQilE-cKj)!}*RTwoSXT4L4># zt+?-B+z$A@Tu*OX{U9#)_hu{Q6L;Z!v&*(xVB3gxxM*M37{-gO?7!|bww*=P8_m`_ zf^GfLY&(u&TR5Bfl@`vsN3!)$-h342+fh&2S4MwZ@P4^2w97#|1GKvh`O=@*PaX92 z?_`}OKE!{=(8m5y!ueML{kIS2_Bo^2hC8yKhJ!iZf$<42E*9F=j^kZD^e_LJ>$Nm< zy{YMb^#Unr$=uHDVnU zu)a#;Ic^K)frW8wg3V!`RS<6==0j@@$89={{a1!@z5(;Fb+Z9{p1&@5>#_AVVq4mn zZ6|EqPVA@Q32sky6E1JxnenbaaK7&KWh1}VW}FW;XIpgG+Jo6vV68p5zPAPA6F*-e zs^5Wp^IlvYz;+H{p0gF(;@(`|IF$1~ti2D~g?!^YtiOK<$%x#B+?x_X=X)0^Wk_R0fY~t8q#jDr@WZn{w-cgZ@*9YlH^DKgoLZO z>iY%tnM>YF|MG~$?^uIzxL-iH@+0kZ_vCgugs0t~yy8FHo=LdxAl3>wZWJ{3zx4@M z{cUUH>jJUCTj~6_2v>YvXXkBhr}V21{c?fFLPr05>wnx%8CS7xwP(B(abftmjc_%- z?YMpwYk!vB&MgQ}Yo|}R(o_Eggs16w)sGxE!2KJs?=7-l)E@a>N^F?hFB)In|H6yz zXQ}U@`k|n7suf-T+V+0Y@2_?KeuT^SKB}zwcg(j|NcTU0aMfSYQLIOJT7T_)dfX9& z%l9uTZny}?4GCBCR{zwl%W?Jj;1Zr1*GZ4NAK~%-7SZ33@H9Wx;Qdm^>&l&YT%`YE ztwK8AAzaq*_T(58PMuA_W0_wQ=-BcRZFv#2on2J26$S7bGFbWt2i~_Tz z0$KO}gCZaIEBCOi8=X84XwdR{=bQT|*ZF$BJcIRhf76>UewXa;^wyu<`2)wy+5Mm0 z$8Sd4@6X}$e@68)^^F3vg92H{|4C;3&kn<9+GrFo3K#{90!D$Kq(Ij3e_$#7`p?P0 ze^PK$$tYkHFbWt2i~>f1S)zcmX-o9`KY4D|zL$SbHj41H-~YMW6Q6z`qkbWyes33^ z$b64*_4~hW{HjsW^QsRL9{o;Bo=<}vvIFCjF5}>DHs?K4{PIa5FXcGe!uux#P9vPJ#Q@YTk!m_ zSfB8;{sx4{`zz1?hrkn!r;L9_vi+jZTbFSA<@cLnM_kHy^LQS2u_56~WqCeZtbJLs zzuoWuBs{JCF5&U^i#{IVYF;fsNzIe%@H@hHZi3F*JoIno_9$QKvkRU}e~WN6pQYVm z-CJ7d-3au1(=mHQ^Ioh^_&kKG-)pLmJpcb7;p%yBHE-3Yt&!)+;9FbhcYtcPB|ldZ zo)*_G^E{OKDg7NmxSEHuF53IE|B&!S3D@}p{*mtACtSV%LfUyUbPEYr^HB6T82VVZ z@wiCbx_{z#tAqea=qolLd|=!G{v8sY_IpkL-j?Y1d@`TJ z?)N13SAM@K_UhLem;Fer`){5PdT5{U0<~U#k6V8+?;CFeSHFK%^KFvHI=FA7x6}TJ z+o}71=)3fGuC&lG(R`5hi46(wQM1RJz3?%qzt?mKSL;Y0FPHGN@$v|l@lySg`Q}Id zd*aEz9wc0iqpW|ic0cwnF)qgZaS2cRU8zTS+IsilN7mOr;3ptFb)FEOHczJfE?rM| zxpclyc-rqo1Hx6G^z{`27hQ}s3K#{90!9I&fKk9GFsl^s5O_}ed$*>)d_8D%FgoOB z)#hX38U>63vs3{O(dX3n-kW~&@z3ZmXX`LaHz5<;C}0$rB?@?mTD+h4KVyv!>Uz-3 zgE?y+%#zK=1T_j61!k!N>USSgd;d=bzxOZUeE==6&1duT0bL6(#qa$_FPhsJFTgfz zjl9?)$>$1+XL7y?R>bI-fO^eIzLYoh?-PxJ4u&-Geir@I}9 z+xZjgJE%ACC)S_t_L>St0i%FXz$h?VDexn;mR{*;S>MdV$MM>E*)9OP7;NMG5$+we za%6Kyv-M$v7S0!rVH?60kLA2|9NQACeLV2lN-fh^qkvJsC}0#Y3j9VC7(O!f{r@)b z!qNOZlUPUL)OG#+|1NO-c{q>o_;VZb9($kg=-ChL?*)W}&reTJ={Vpkh6GJ2j# zp5OBEzI1m#_9M@)$ov1VAbcV6(|Y)!(eqehYeupkd0wXl?-h3lSM3p8-v93rzJO|v z_IHp2!lUO@^!7(M>7%vZ+MjjPXN^sGnm!KUY0r^(ge!fdo$~(w#|T%?dntX?r!blC zUt0&TA9?Oi>|nx`KKdshJpTM*r@ZeSessRw%=(DFV(rnakN*CDC&G0vmgNGM=d;9m zgs17_6Rz~}#_;%x4GCBJ=%3Zb^ys6WTgqR>`nZR)ADw>%;R~nuv5!dVQ-wYb;i^6I z+@DyFa5aDQPe8buKl1+n!{oWT2-n$^Ka%H<=y@XeHsNXdIE1VAh>l`C!qfD5jPUsU zaiEWNH2YEOOMT?|zrlp3>2n3)%8$&?5>?Dmy%2sPC-MKar0XB2n134ui~>K80%~2S z{r$h@XVdR{S1w4$f1cJEuSNl*fKk9GU=%P4{2U5|w^XC+|Binj7F{QMm+lwYd2X#n z@Bi`fchbd%gsbZocTeVvwaNQC*F_XLTxZs&GN+}0mB&H%zw+e5f&kG!`b#QTe` zAY8Razn=eyaMhl6v`4IWXEpkJgyQF~c%M%|c>KCLw;ZmE2v>3S`wQ0n)#yDf`u&t` z2v_fc$)C?Ui1h>RZ^yYjeqtXaJgvX>1Iczue_g`W_)7cb{XeG@uKFu~|4{5z4|01- z_&fAs?T5Hu9VhWT5$h7J{MY}T@9&5`iE!0UiQCx5{R`noaC!faH6=s0XR6WrYQ(Qt zhj0~F?jOnfe-0o#tzRcs()(pSo17=IZXCjuf4S}#>k>XM^-Ik|^^y1gcoCoUe1P>4 zdnMs%<7GX^al7u~c`SAX!qxl~edK*CqX<|1l64}s=7p-YRtn!GTzL_{Vtv9@zx3<> z2MJFbFZ)Gqr{b&oEb=}v2ROlrj|*J2Uw!2LKb$lFHwqX9eoh6{_y2V&z@!EFd;h2F z*uDU}GJo%Htq!|3?0T>p!v36%G`@`jMggOMQNSo*6qur<%Am81Xvlwr~@BT}uFXi={ak=E%!JCBN{nu%KXSnW%Bwy-@?ZWd1lGkkq+O6Z$ zn)mvM- zo_DqS&4}05M_lpKK8-x#>$W_D^}A-UemH~m2hQN}CpUxjn`W@S(?|W*KFZs0+%Nyc z`SsCuLuVRp6!_T`2)zn!23sG$ zi|s-_E6~6h{QXmw-){VHZck+l+6CKzzfa&G-!&TThxK3!ur_QJ^(Ml0$1(pf3K#{9 z0!9I&z;952tmA*~M?P+5b-5Gg0a@kwbEaNDtDc2=6XiL83}VYq^$&k;AN3piD9>ot zYy;Q#(Z5n3`p-5UH4QZi7zK<1MuAiXvX1{veH{N&of*(5U=%P47zK<1MuFKvfvn?y zD~|t@%z40UF^;B@MggOMQNSo*6qp_b)bT&<`Tu&n|E7ZDe>1SZQm+r^)XN8ka%cl&sMo>9*zU=%P47zK<1MuFK^fvn?y zQ>|R*&%S*#EjJ1n1&jhl0i%FXAYFm1|`oG`kb|ERquuqK8S3? zzkVO_#XcC}HCE|!#>H-No8s4419xTrVgumqH`n8N)E;YaNCz#Dew z_K02R5$3n-#QhTMKg#1(+KJ2ec5pl6GEQPW!sFvohjH03V_ce_h5v_n z+)J?6KF7E|?pHj|xQw4z>jfT184s}o2v<7G_=)uhSK}z-@^|QYHTa$AuUO|r9!GC2 z)<>*Mc-lC6gsX8>Nsapi_zlrfI`zsY|5M|m8@Zuu7D?%s@x zeH*xs_K0=gPOg`WL^s0KJnRBr?0|O|x7XtKi+z~zw0*{Vm-Uo&)G>y~^AW<8|JGA^ zpAj3p$McGYAn|#N@U(g5ywCHhGH&;1e-PVDxZ=ycAlB>T{wADL#wR>&UIm1!In}V! zp^<;FA>lG!%2%0^IzBXHjMo95aDOKa;r@=eF{xHf5Z;>jPZ%U z#a;=#xrzOY9q{?E+8S$7t8xbPfxU)s<=@(q{fiy<1>-U=#l8hx##^lWCG+e4$>S*Y z8sL=?jEi-@8df_G=_K=^c-$e8uBQ>M^w;;FQ@YR|95*{*?XQ#im$2_`oT2}zHBG7W z)2VHW*1NPv=I2R-D}6*?vGdHucyUkGS?v43o1mxInt7Nn`?%PV!0Z0R`imVnFY_yZ zV*g^@`I@5RCP|d|oJ4rqx(EqZ`|XloKXou4XXmbCzU;GNeZtjoQ~w0u%kffdNVr-T zy*~4&`>_d^w)CoF0Hc6Wz$jo8Fbe$I6j-#`T7s@80W)T4IT2Ya_x{9fb#b@$VV@rPz=3cLMypN%%s<7rbFC`x(46`w_fr z5k3$02#=2UT7R7tnyHPXk9NN65w3L8KYoPw^jGu=GVqY_G<~cAJ^H8^7olGc;Yyzt zTtA2%Pq^q4wF!Uk#a@~Hi2m2W&v3$(KKkbY!j&JZCpEvOc;W zkML+-9nRMwd00QfQ}hAujbXmnknmJ}*6Yzn&4=rxJ%lTL^v`(0;r_0J}O3?=(8dF>4(6FNqYuo=tH>DNAx@qd_Tfd^Z_n9iVX=*)n|(y zeN>a~koFKR>r3G$10PR#T%U=j^7^v3Vm~q;?gxK3;c4?HAYA#85y(NG5Pqb;r%QWw z&d`VO)b$nNbe*its{pv_Q~VPWo~q9-+^;xS{o5ftb^Z_@*T;Vb`s|+WXE@;tcdO77 zB_KSmPrc}q;l~-Cp%3Ay`b2n7Jo#6Ufro^r>N6s}Uk>4^`Vb!1r$gq?{^@>(6P~8e z1B5F-YQCwD4SlS?r2BD3XXrzCsy-3UzT^K7GVqY_RDH%|w1@CieF%^1)3_G@9^XDP z-Oq5sQ}rP{uFpWx=csf)&bSPH2v5}~!sE*Dzk>`sBs^80lQP;vc&a{x$Mvbo{5dt< z&v3$1^&vd2kM}zqzfMc{V`tz_2Hsm4gBS&j0!9I&fKg!9D`2Au)hqb8r_RHFq>r_b z`WA!EZz-vBtKywFF4DiFahFK?(+5j z5S52sPkCLue1lD+_DlVnr~!%kLpF`-cb?x#zxT?X>>q#cin?#rQxgAP|GlH~pxC2-|5&+m;@**e5A|2p z>N`K|6V=bh^igdP|IU5;M&)sRlm^}9_q&mQslObRCF-v;JgOg@)6>4?f2WzoM^xLPB`9w`;LPn|D_9h{I3x6Z#{NsqW&MX`r)_5s9f|PNab<;!@W+3{I|r` zk7}dzKb(AGRNfwouQZl&zc?=PFZGwEvUq*_8ZMXkA5(cezSVSkRA2TVwRYqCqt$#m zA(mDBxMzP^jq(!Ts;7;SKCLnRSC5w;cxL2Z>Z`F$)PL+uRh>4d9(~uOtoZjnzCKZZ z0F}k-d&}RTYFi!W_S9dS^4;~v-jJxTv`f@Ko9kPxJ@xbP`neku^;gmB7j7hk_TSk4 zv>xTV<9jzpNmvnqu&m7$G3(( znW(>%RzLjk>8M=VujWp?{ow+Y$bUIDKR1r~4{vxeI(|v{pQtPYQn#2 zTf+aFUq$6IKh)fbk54%6d*#Ne{HL!$h(4WjyfY<_PQufN6~QMo(5N1vhb^1b(r+AsB&qF{;oXY3i( zFT~bwW4!*EdnM}k*Xp~2?}*B!{c8N;?RSUY#s2@@vwv(y92r0NlYd6#@%>}_c=;Ch zM*a(^ua3Wo`d8i?)sL?qb;K0^;iDai`nFa--1?QMetC3{e(L^Bcm2-S6ZO^j#N&ru zuSfO0Sp8jM^_@$?M13{4;`N;~-sJix_r%{VUVotvqVh^?e0PtRpYdT-9zXxuBUT>X z_unYK)K|yuczt)*AEI&(@sFYMczo*sE*Jgj_fd)VTN4&n)7P@k=xM*&14KXT^kt*+ zFt$JK6)&&*9sRzkr@lx3PShXxyQqGBY<}(&uYY~A{z-cMySaXIZ2hP+j_&qtvRoqm z$$I^5my6tg%Y{;~T0 zkj)bHFV*V%FKiywFUF2f2gK{&F*qtO#m?`V=N4$P; z&CsY^;{Tq?ZZK##v_ zW8^=$ey;BQxfu7~*_dd*I{qixU$;$E-`lsgyZ)GX{a3b0)K~jQyuQ89PTYR1pGT-X zK7Z_g?-cp3#?Bv(jQO_@*@fF5D?ch$Zq=yY57O}sob0KDPdjifAoj{;@5I{{Kkj@%~#6ak=b&e_asIT_tczt)-E2DCWzY%$h$9Mm5AN!xsv;UqJ^Y2dhqkvJsC}0#Y3K#{90!9I& zfKk9GU=%P47zK<1MggOMQNSo*6fg=H1&jhl0i%FXz$jo8FbWt2i~>dhqkvJsC}0#Y z3K#{90!9I&fKk9GU=%P47zK<1MggOMQNSo*6fg=H1&jhl0i%FXz$jo8FbWt2i~>dh zqkvJsC}0#Y3K#{90!9I&fKk9GU=%P47zK<1MggOMQNSo*6fg=H1&jhl0i%FXz$jo8 zFbWt2i~>dhqkvJsC}0#Y3K#{90!9I&fKk9GU=%P47zK<1MggV3B1>7h6eT8p-ai#j zp&IBXC{Ta+l99dxe`Kq>D1D!f>%3{rx1B$8{Y`6J!<#)7D46*&dk&mw_0OU}e)7!S zKi%;&*Wb+QbjPo>UDMmY=GkQba%$7hzoxgpzczm5%=G!)Fq@3a^y)dO-*0mqr&otx z8^1J@_w8R>|7O?r&j%YnpvzW@-6r_EY%5%>SQre0*~}{yF8H?R+;h z&zkktHhSuDD`uX~c5^AM!G6Yl+%&Gii~_m>`A4U|Pw4#V&3FAm-{-XK#r-J$TJCF1 zq>2m0#b;*AI0+^L-Zov6|WH`@!}ZJm2p8?zb^Ne(Jn3^^5}3qCo3R zy00@4-;YmA%s8hylfO5Q`<@m5?$oXi2KI4WEzTtU`|4{m_S3o}%)U4^tvc_SHht{J zXYhFX#0=J-S|@(NvaXt6$NkSHbG-irN8N<_xfN)!ejV%T=kDjU`mdZfZTs@H`kPt2 zi8J~9rDG=hn_2xdetsJYgtOUwfWB1sr|~?jYX^g59ka&&x zyq4+w{gpeDz6Wup^ZU5cuWY{7|H|5vHNFOC1^iije4Sb2P?^o{dj!9+^UrA=$CCEk zp8FH;mrrXv!<#)72({~!+-$Z_<+XV|X&UdR&#KYtI4k{pZC15sdgC_Er1P)ojjQvW zX}k{C>&>iutM{1d_{goOz^Gef3Q?? zULza(gm{PGS7zPHehH7fbJ z9h3O>g&L2Ny>lUn?@c(R(ADrW2&ZJ9qv4kjPAT-0xV82!H7a@Qk&S)adv~i*$$ntB z1nxh%Ta8NYvq{|jh%idlCrRA@j`)Ww#KF8y>)C7-|@H_mr}6XaY?-2S>*q$8f$S%v5))o+2o(nb7v><G)?7Klkn$kCM}NcM`vna7y9CBvsIe#o>yeFpoa!evDg|GBlEh12)Hsyf^S?;q z#qVnzO70QgC-C6KEoxPA-q@lx=H7Ci-nCXG@8w++xOdmET9vE^D8)X0`>@^f^REJa zHQ6{{;TKc7hElxbCd%JP>1GYTf%4Y_kNZ*hL`t_%iu<`0c$sXRukh63;Z zM);W;e|ySrM`;HQ-x2suWaDx7p#1KXhEa-_>_+)rfyem@--S{Wr8s|2;C~_;=PP_? zN_$a?myDqNa7z1WxJ&tcfyezQ{Lhp|Qi}W8ANXI$#`y~0htdI*;w1&jD}B=NZ3%DI z_^VQW6-om&d^O;!la0q+m-2Z^>rslAtV8*=fyem@UyIWEl;ZpifDa-Y=PP_oN*hv& zmuyD)O)33R!~a0}O@PP!D12i|n^TJWaexmd8|N#$fzlR~;w5WPUg?vDuT1!s8o!qE zHI(Mk@VSA{LpC0FA<8dEX<V@=BjH+#-B=jsNd&ejNKc zr8g+W{rm@bNH!k#eagQ_sgqK?icf<9vm`Md>3-@siId z|0$)IKzUdk(d((td_S^rzQX@RX(Xk1$qtlP`lR7o6TZL3Uy1T7Qd(KVR{_2%*?8QwDZdt_ zbtuJ4)};Izz~g*{uTCjXDb8OP_ZkMk8i52Xbu#rX>XUzlv1ukg7k^`jIoS(5TgP+CgE7pMGUz~g=tz9^-o zDaHNN1Mg2Z&R2Mj(lV6dC38_;>5zthPx!JLKXg8{JWAFUlwu!eOUhGnha~ZUc#5y^ z`27KIE5`kyN&X3+(6uS0v6N!&ErlOP=@d%wl4B`<4DdK#;VqO-r4;8MMtPMErxfQO zO8G-F@KJ;xMJZmx{quIUM+1-h@fxSp21BRRTH8#ijrZ5Ra7wK^VM=XCHjW1yK3r=J zdbrlv=-~t&9!2<(57)X!YxrG+-%0pClejnkBefQ#P}$hWUVw3L!AEN2?e_*fN^u{p z4U~<4He}r0=+Oi}eEq3fmy-3yQ;Bx^tJA$DO4b^c1a7Tasr3l+$j03}gektl<2tx& zRcb@Re6n%eUz_+Ut&{WdhqkvJsC}0#Y3K#{90!9I& zfKk9GU=%P47zK<1MggOMQNSo*6fg=H1&jhl0i%FXz$jo8FbWt2i~_$l1xjm9+xx@w zms*Lx`;ohX^TpSacty+W{jJ`SYs{lEeqW{+7#~)7h3*NBh=cTfTtt5c-AMyl}or z`ghMx=A|8C{Y$vqrq?*cb(eD8Rxp2pPm}y2`fqQI_M)O!VqOvbC?KBrEn(hBUbp3w zxPJBgWIW-8E$Mi55VynM5W1b16phn&wbBv z{m0o>F^=M=cv-Stf{P8^WO+%Ohr+XuXI^1hj$i3W)+@h?Jm#0wtE|QR>Iqz)m;K=(xzw|cOO|)z_($*rm;000mJdtk2ODtwqNaZ^knwK62XKAwm2^MCt5&$Yh;>~0 zFXw&qvp6BWz9-{``CaNt=LHus?&|H!@GI@g_tW|#1)6m*Uo?2Sv(Dwo_6O*{ILd4L zkl?y47TJ&2!0q?Z@BB?k|5C4rbyeZbqa7i$YDL_zUH`9?CFq2-fAL$E zdA9=di~ZR;9mzPt*KKY+=I38yzK`(|UUf3#!7|DA_|RW?Wo;kIp*>QbWvf{4;aMD~ z1YHYgmwPee9{g9e_7%0bc{%UEx(_uSLYzP3vA^W{I4_WP+yCQsNZ!Zs%fa#5$MILn zbz8!?7O=1Qnr1@Kw_NU{|APNiTgG}Uq5oCv;~{X} zudD6HPCK{9zLTxa&uPa$DbH#9g*T1!N$PjojQz9p5x1wPjYAH{X{m2x{!}mz1rNq^ z{qPF5m6zGNn4f`+!_quXHje9gZ9a;>g0`Ll?620P>{obM)?19@_*f4P+Ed6l4%s;W zuyFpK<<~u$;}uXI$bHGRC3$Ap0w#-1d_GrGAL>P|1reB7Rw$*JaGBP}{$xUjCExI3CuIpRrFB z7D@KY9+1pCzfa~RUIoXe{E_K#OY|DF9FfZt+2*TBUWoID5{^Gb%wI=aKi-nb_<5YS zNjs+1+Sqr5?_+*RKJO;mXJOt-x!5YM(tKj^>%UD<9r-bv%0?xmxeVp&+aD1z1`?C0}XxAr#=ldt; zyWkeqad-X{%rBWABa%9G^R$1sn%*{aw6)`-`|{NNh3h8US<;S!T39Q{IG?THc%R3< zC-s6-di((UoR9spbOG}mnNQ-N4;$k6TEKNp3G2so)8lr#dx6W#INx-%^A+J$FrTXQ z+DEkyTH3x^!Tc#_)Gr;w^{U$bTE+RF#3`X4-FbbUpuoL{{S~zP12)Fl{}k;6Kc`*q ziT^BX%f5p4IIteZwSs*-hxJ>e*JmnS3Ru5Im-8iU9y&Na1vvke_>OkG4-e=1dHAm) zeq|c>xj;KUNt_Dyxd7Kwwssy+k^5;%+%O0s_y98cZHxZKl@`yu9I5%V>`_)2qqjFX4<2wu35{Z%ku!!FKO5hqv~ z?Z`M^5Cy`jpR2mW!K$cAiy{;|K@= zj>Cl?xqcD*t<=|TY3bxR=;cM|YH9md8P_Ly948C1Uuq5t-*Y?c=hFKl^a}JWVO%TP zdKI3BVSkc1 zF4k>XyN)Sn^U}jStBhtpRUEg)&$Qa=Ke)bsYu2;qJGsO9IQ9Iv}IJyl`FVL>TT^u(H zxK7OJ#}VAO$>I1Ver?R_@~O}f-+P2uFBbN%oOYeyjc2~^v9gt;V;DXcd&eN|8@~y>Xowg8ExH%&`Ij$>)EfX zeP1BuA=Y!Coo5uFV;<{7_^uC~1<-8ns${v1{UML@fFkxGty)hO>nx9Pkb<&yo)Ki6 z$CX@;U&20+L;oC%i;eYAI6m3V0?tb$p3}IYI(CP_K zw?#QG!tp78G3(%Byee)|7Z2w-;-`T5BYF1(<~ykGVjnHycxk=L<(@Vlr2e$pV8!Hq zBlSYWakPC~%EcD3e-&_iu71w#%E|eN5Mcw%H&;9F@UX8{pXK`g7`9T~?xP*T%d#b{ zpTX_yzl7sR3Fo~z>Q}+M7G6m^f68Os=CB{RxPBMDSYKQJxzCbusu{;8sqbj(GlzaxwBuw| zI}S;G3+EYSv@ehQZ{6kEKZ=OwFOxpcHM&*A@u?RMU2N>jdU;OTf#aStjrYeroNwv= zvhszDaj|jy_qF465&LGKt*0#iI-Wm-$G4afw~Xs=y`DXd`=(y6JelK#+IkOgzEH(+ z(D{UU141LwX$~JpoO)H z@MojG8^DhcvEO?*KM`2BHqK)N5AI|?<>Qk60?ezbc3v*^rq_D<{c3IB>C2xZ_j_=@ z<$ufVEkWP>63Ow%Lx%#^oA*8Q^K!m~fHsaldC>vaaaC>p6>+{J?JP}Zf9~^1-O8H& zIn0X?wvusO=WF#Oj)&ulMf6I*WK{#8-0 zqFrB<<-83QN*V1Ef1Y-pDtHdZG0BT9pg&c)zQH`o!;g=4*`t%=kh?FL52fAO@ulo0 zc@kHwb32!paQ{VcSLPp%Uj^-YQh1?uo>)1H{Z;hy7mQC4>$`;c;N3Iz_Eoj>Z;9)E zmtL<3{k#jg+{U_)dSVMWzPl5d=OSOlI;~--TaR@PKfnp)VH`!kIh-6;syZ9d12fz3!^Qzi-xYsjYlzwXCE&d7^ zSL>K$yb$xTa(EJ#dI9z~AMFetWnQjda=$BR$8D*vTMxRGaUNNEp8b`+W*Y=(2XLuh z#5$9_h2vH}V;|3d$$rW!B-`0tKjR-Z?z`u(|2jpqCxb6=cqH?3+Ih8<>$ZS>st6q` zUvT{@bOTY7=(OSyydurl^HOFJG^^!)}E%i4Li_!Dd6`_%x)S;57I zSdWqy>q2KwYey*eV-8NXzkvPE_LF$t<9r_XWBgZ<$9xT5N%AGW*ox*)@Br)G&sf(5 z?f7A1zB~Wpcs}M+ad94(YQ}wr9QIL(TgCn+c}qLb$#t;*k{nlHbGM`4av$ed&U@p~ z9@uWb+COqQo@%gF(C!OMx%V0Sm3)>hXy^YyhMu8zzaz_^;6-ge72LUd>g}p(`(_o# zA*t`-{KdufY8m@i0p|nGVmzKXIX+;2E@50;tp5`B7YF-m8S_Ho6wjM_JB8PmEo7|E zvOYf#<#^SM>!B*X|E^|S7kDn$FJ#;=&taaIu%GGe&T02)ia3tsuwJ|QH*%b^oL_-g zKz!kq9${XwkM%A5Ube#ZyKz^`cNgFvm~Xaze9_LwTxmCS4z%&{ui~ChGQNj( zXUq95_O~L=*DLsbSeof!A1U3-eoETDD!fqkq1TvK!11MweI|$V!4l3(q@K5M^7vB4 z`IeMB*mrUmkNh&sw>3Y)&*3=aYvWhC2s+659O71R{L4eX@Dk?vF53Y8DZ!ts>Fc1M zmbU(b%TfPn#FYlZI@+zF}L0p28Db z($3#(oM%Y6Bj+_4z zTbN(b`YZLbY~Uv2ROI{_6&$%gpW(oR4yAk8Pgz?Bc^t3ZgOhQ3x%-;SL;Mb{ApODq zQT~j}1FVxg)~AR2Gro3y<6wW%<9JvXMcL1^_Uil){VU&{-hL1BH!t%6`+nsg%&%g9 zEa7-vzi^7nD-rc)-B5?c$467^$nJc{C%6j3xszH^S%ME{^(@; znifR++Lwy_eGT5k!;`#r`1^S2`iR$+!K;ARuZ?+MW$-${JM?|#eVM@v!8>c!{!!d7 zGI*WBJAiqgXYf=vbL8o)>zMah2CpjqR$V5F`zd(3elGOe{%YoZlELeOzfqqvubRQL zR^;}bG54}j+?T;?JN9=`ySdd=^vHrye$*YyMZA~5tGhKhU+UoR6)IQ67r}EiUJkrB zzu`U!-(a;U z?vCK;aqE`maoZXGb^uS0+k$np2YB0O_zOh8_g0VMZkNI91n;_Q*Nk}Uf!C`a9nf!y zwIbfS8UCv9w*i$aVjeubA6?*W4Bpb<^@`iT`Ykk`<1PiBuAfEIN$pqt;crRs^tg54 zEf3yzKk)IWSKLhycZ0Q~{(cLd9=9I;exPzi{02Nd?m&$1T!{N-R@_Yy_iBzCX2i7- z_ie=ePgY#;I>CDcyk7nN3gf%MI#GWg22byA9{$?lZwh#Ne;dGi3cMS^>lOD*^mhu! zy#YKuZp)TDzBj|)_2B7oJ*;^g1aFy<9QO$DdbRI7nSbj>?K>Piy?q7vI|^~ffTy>w3B2RL+Y`KAaW6pJ z7dUPcczWDc=)4#F4FgY)+X($!@csy1uefc9J953Kzng)l$1S2C4*YEjo*uV^_H6~; zis1E%dlBNk!*K_Ir^jtU+?C;P1@QE^F8aGVcs6*ILz45rgTM8bSU>9TeBkwJ-z8|@ z6z0tfp5DG9;?9q_^MI$fuMKhgf%nn(8T;R5h&z6RsD1whPmk-v-^Wz0h#!Kd$DIh? zXW%^xUa$W89Cyvr2Ssr!;OTKa^!IuAdj>o`ZW(bqz`F~)UU9EOfA82ZihCz`dfZmT zodkb(fTzcugt-3#?_%(J#l0T=9kNjr_agB0xE1)j6#gy*PmkLH-j(2a;Pr}oBjS$d zxMRW7Pgp;yyWr<1PlC9=D9~SQ7pg1y7G_ zBknTbb$yqyzdX%4-}Lh4QGdSzPmkLGf8S8KB7O;;9@hcyNASJ?uQHCW2jxCPBY5Y% z%5h%@ua_Ft{YUEV<4SHaWU7l8LRc&~t`pC7nr-#zbh+yJ~@?RyUE zXbqZ(^tm5Ay?xE__aNfl2cF)(B6yF2_b=gfB#&Ed6ic0FfAChL3Txe)!RtVOKNz!3 z#G9POL);H)w~cuBWbi`aJxCXP^tn5O*VvESx7x`&M7&Ah4Xm@HcFQ~n(Y|et+AZS! z6TH#_NnRCkZ#JGvfMGru5t9H1>BJc+P^!xYjDn zyYY19mBDMggy(ZD`A{Dh_wkh~CJ;UdO!a!OO3eoPV7dH|0mgy%xOsD_9p9kGfZRJd_{B zy9PXc9yrpzyEyLE;B{&3YXtA+e=_e1@br1mfVj$!itA^@ElAu)*x%*gOEqEQ>+(I0dp>x%T(W%@-40dj=*IV%Hy*tF$I1EJjD9FTD(<=9HP)~{ zSx448>`(boymP?Q+t(uceaUf4;00RyJkjqf=A8vzmln4=f#WJaD(;yXaa$$syt^x! zbq09$SIPd?i7xXo@9z@#>*W2;68tGY%HQ8I;`$PIDfTxGyh+Qje)Fr!^r>F8Y&0G> zEzLYH!(R^V+h!H!jRh~TlI@!)`mM^m6T#ERw+x>0quOyic>4Id7+>W_@s0yeAK!Xu z--aCbSn%o><^Ia?!v^oBjhJ@~c>4O7g!U;vD(+F@Pus6bJMsEZeiZLW@bvZtG9E)Y z?h)X%Ywc?X@0P8ZHyS*Bzbax~DnBZ2F(Yn8;_kuz4g;^WWKx%b(B+0<%sT`;eZQ(; zJd__5cT`5)P~!fD{T&Qm+fvE6t&YX>?*Qf<1fD)$I^j?GQE{8W)8|Ww_9;J#cK~?$ zcvPi*M{(T0h`*(i?dt-sd^Gb$3Qs$p=i9g+%8!b>Uq)PORpxDT8v7doUY8cP4!nPy z&b;B^>AK`GZpx2}yDxaUF3!6gSNT!AKZB?1l9Tpb%W?MsuXXO^InFTye+`fk6T6X zlphs$bMW-@x@Mg3DnE+%NAPrATHtS+_c-om;B_p{{grX^z`N~z=4}F=e%$g9SNTzK zH_nLLDsh(@rf60Jc&$q$c1GNZ5_b>ww-$KrB1v7Eu-H?=w&NQE^wuh+CHNc!d4g z5?8zaodn+Pk1}sL@bvlDj`^qjsJOq&h#N@Up-qZrEd!pepAY?R+?sj)GyJuSzoVG9 zG?pZ`AVa{bZFTLL`qmgIGO7y5Bi|2?DjEe>Ai8g?|_WZ!66l>Pnp&-+BY#lUMC zl$f4O_oiE{j-4!Dv-k0F%{`{@E zeP2_#B7Om$e!s4Se*6I5>)`dePuRh6KMD_s;=Tr+9(UkCj{64uy$YTlH-OG>gZBV< zz2d$q{cVoo2H@#&8xZ#)_`4rGJ+1>@J9zhjr_X~5^n2o!L!-F=0#Ba@6QQ5-qlour z@La@w`Ze}989Y617kD>*SB&D`li|;zpMj`-Qu$HDyTO~ZVRD|~B1Hjq5Xy zZc9d=+@#ebf7hHaI?5lG!K+*g-kHqXHiK6<1-wg{w{iy0nF!v^%(F6h!Kuu9_+QL> z?HgVndOyn7!{1ZPyDNid-w58nnRiYGFMm3C|Hr&hS-i`@`<{7QXYec!yoJX^IuFR; zm2LuWIp%%;b$WlTTfke3dEbCnx+b~*6{~zazxMdUqqtvX@G7T+cM0=8&*1su?_TEp z7rcC%9nB-TpVM+H-_NPr^vEb~XNJE?@b?LoE8>4L{54z+f7`Ra*E9T8;O|}ddp^To z(>3t7H~Xt(`0IqfSK#l_41a<2cNF`ZlHt#4Wu2dbzsVW?>dI)}@$7F>mcLKf-vjV> zYlgpq_&bCB-IU?49{%oxzpFC*c`_cCus=V;UmpIhhrbCK{@SE{H?hC*8U7mK?^5{t zdzQcJpx?dhuQkJ8aV^&G9QYfX;jj1)_9b;|sEo&6Ov{I$T} zG4OXt2CoF(wZA_qT5kts@ai%DuHA`w!@<+n?Gp0_pGN%-bG3y&u+X7`NA%w@rq>4*1)J%2i+|!(XHL`-uH* zmf^1oe?#GKQ}Fcjmx(w|U$^G*QGeG3&$^HIQ~DWF^a=jM$L(#8JSobroe{VBQ=ZQo zBkqbB{`~vd|F);HKRd%;3FEN_{4JT`Z(;y{=d-`XGW>aH-*WIbUxvS?2jK4-_BVHi zzc%<=1pdCp^98zo)pw!ao$T*R@bu$l8UAYE@4p%T+y~LVhuL3ehQD_B`;5xf!2LVJ zU-Luo_aggyHN#*1x;(z`!rwC){@SO&-@EMZ$qava_;V(pg zAA`T!GyHjvpndb49L?u)hQBWOn+$)~WcbTJ3V%zozbiBR!=uL-^GUf*p17+Oo#$;k==5mZP6kiE?hdeTta;3t5zhm!>297!b493S z*?(nS*4*Uc2sshF;urkfPAzz)x%qjbo92BoLQVkBUOD-EPum*YzV?2d5$|~L{NE>e zA^New`X5BRvP19+=G^S_996nOeR z)V$PEk-t?|{50Ynp273L`^);wD`xQ8gm*jh4$0t^!MpY$<{gy5EB%MZ?b_#=cOZCe zt0i^rKz~1co@1P?;Oj#9WwlR@VCn2NuKVn9XhY{1oO7d@YexdPP<^Ps2@YXYq^zmnHRzYC-M32 zc@vU6J#Hv*FPb{fMt`r~WZpzv-Cq$p54mCLyu1zl?wN0@{&G7o@9GbjH#kF=Ds=hF zrgf1&;py$mqaPzTW8NP#{MGfxe4d=->HZqvZ^*sO+XVhPi##54V?4sT+Gw8M@B#BS zmbeu=!lOnLw*k5+KdS16!qe{O*l6D>OU)lu6`tNc2mV%CntAJI_-lZ_c@ItUbbkXe z9&;bYynKeg(zU#f9(kI1Yh~~Xi2F$Y1)_eep22Gd@4Xi0t(w7Wll6N8^Hu_{@dO?Z zIp6T$uX*x+GX_AKb&eV!H&cgj=DTQI|4yXg02lBfGC zqkU7pXI@=~zcS`u>nil(5c&vD_vd21Oj(P0^JVDLgnm4BT9VhxA9zEyqX+KkBmQ(= zfPTDl3G?PgT>bnYgf2s$VBTCA?Q^mJUH>Kh!AtrGPmfzffA#18^?A^a_Q~`A@}24=OG9EE~@%PMqCeZZ@8X$pM$5b%NCn;QGQh1 z&%kRtKH0vB7`MmwpcgsEczXM)=*KC?GVjw2e`WD^T9T*x^K5S4kQ>aT*h?>w=>RC%rF$CP^pOqExKzbUJ)G*w=k=yEZ= zz=u8`Ll=EMJInAse(g8R`)>xX3A}lip%+!rM|iq^^+R|(=3bV0of-a$@HcdmBv1Ee z!{3lUFz?+Ae?I&@avbyC%HV}^p8fYEPmengaaTHndH>1qHwkh7a&eNU`zv8xj=Y3< zuV?tHh%S@q#bERip6)L%y4=gWS2Fx{O8XX~7uwNBc)GtfY2U(A=lS5ha~bnq%7|+% z%kyg9z1EE4J`bLLobHn2;IOqK-gDsT`+Xz&``GEsdnUtQJ>s@bVBV7%?aRH1^Uh`0 zj^aL+!OKfO_D=G2{R%r`-tWV_M>701ioY|M_b_<+^STA}cgz9nMD3dbo_>F=32{Gs ziFpr!H*vlJiR*j~y z>Cg(^B76Taf+m5d-=AzbwA?P?U{FHM*BK;V_iNx zn0a@A7xvS}7wy~Nb>`hJ{_aX1r`s_PzBqVD)V|xm>sT@AFTi+w`R!H_?;jcdLh!y= zqY&}hz-v90W#CrK8?*xR&I3=^IS<|vYcua$@X8k@?-MqlA4hD# zymP<{R@8X#r~Ih?mcZ+3OY$7}>%SxWI~zQ`zm4$s;Zw{zD}z_JJNI|>ADDM$1}_KR zhd1vV>32p3&sqUG-+Xz*`+Ej2?|}C`^Zo{2!>IUczWD=#N7n`HUzI% zT#Vc1;0*$=^|j=mXdK}-ZJ3n{cu-c{g$J0 zHE#XE)B7aJ$QOQeDt^9|8d+Ozs&fZGyV4`<6%h{>{9%GTPS&UEZZ~rQe(2>FsNV&L4u;4qmTu8-TcL zy&tvjQSfwK3W)nS{5=Am9=D9~cm}+i!Rrlm)=>h zufg`GHd_8pM4Z%HMZNz)zC7Zj-XzYWs}MHn$s18y(G zNk44#W1rdWU99Nn0$%TGI<5W^|J3ujNkQuTOM)JzV7WM zy04ptqh14X(!LPJWo5)Ihq%&Z+`a)-?$%Je!Psh zUgP#(wC{Aly@WVvUlRFVMZGT~PTH43+#86q5hwFLjkw8c&TQFtH{yEPw_c!?&(lW( zZZhJeeOWx7-h+B4Ax_$tLA?(m?k>d1ymxROO}-oSUWT|{_FawfdlGP$B2L<8k8Hkg5yEcP-Ss8K5Ax_ToCi*dX zr{7xs4nbTm`<8<1tLftaHy7fheI?A70O}o#xL)?{0`|?1xNl}^j?eF4p56_5ry)-2 z4WPf@&Tj9{)2|UH^#)My4~T0ZP99&%=*Q&Ivs!VPia0sXEgX;c_Xpf-i0c)<4{&_5 zfO{2j(vK4IRcE(%`|%3mq#tF(y^Xm05Z6oZC#bgqdhbP?)LTJ+A3(l)5GVBpF@BFA zu7o&wT(gny?$Lj=;x`F#^8H6)2Y7yP>+fByM{|Ue&v%2HLB8Dl2jK3|@RgA7`7v{} z_-;mA_#Sx9HKaSJv;P&(hIKcu#{hQ~;(}$s(K_zPG`OBIx8pczUmW8yd@Y@PSM!cbq>bQ0^Bhg z`$9Ls{fK!d$4UEA6u(J;J6dC3itPIZa4C&_VY06YxP3MDS>Iy(W^tUfFGKeI0l2Xm z`?6%;o^!VHZzql3@(j>xCjhs-hOdtKeD0lq+f2ika)2*)7vMJ4@P!Y@{F@56bu@hD zO)zeD18{32PF|PTm{*fF7}WB24aCX!?8W2YdHb{t0k=BhlE3rk{8c<|bn|r2)720s zuXAdMn{*}cnHs$n(t8!)Mr!od(2s7OZoR`1*Xwvi=Y8o%9mltur`wO;5hwkKk{{;*-}i`< zel&MNKXQO`5GSvP3gpK_fSZoEUVfYc<1x=8fcpk<(hmd2qnoGOj|SqTA0^7GslfLU z;-nwRJ7``4?nA`M>z4-R^W??nYK?CVang^j6`4ZX*&#PmAZy&_T zd@=u|@deyo8ov4w$afy#cGU1?XVGyDaNBA4!erkIfQxGQVkaY?4Y<*Wljr?<&v^@Q z8zWA}*}&uEv|j$4CB1)=IM^}hKQ5r{RZjXbM^wd+5gtl=uP7IPTLD`>uU4{ zV{l*5&C|`d7UJai#wdR00pAG3$?>g@$Mb#;a4R8Bp7%qjchW`Z3Rv zfSV6-(vJw{K{rpgA9Ev4`jH_&#sJ@+KfrZ_^dmY4`Vj-%ABdCZ{Vx2zZ1M!a{fap0 zN7t!%zB~zVO~gq*0?60R)9uGkh?9QUbl$%W_@*IF`r(it7T~@{oILNFmBd2 zlYT_$`sIDVeStXXM;Q6KdAj}h6milIi^gNYDIC(9zR(HeFW^qq@EOGS5a7}pzEm3d%78mc!xtgGp$oM9O=|e6#1{bE z{)m(3!5HS%t0MuoAL8VBD}={`SFZ%z-WvPrbUb($a64-3%ToMmfZG9a@;qaZ-l4-< z{%)($8>hI80o*8!UYqhX2DnWSC(jEe>V0hj;5O9g%}_o+1h~~SdK=_#8E~s2P9Dd@ zq<1RdOpV?w`8zV$ipx?Oz3~Z{S0><=M4UYC#xW0G+Y@k$YxL&H-zxz(k4CRG9`zOg zH#g#X9VgM>DK7wSh(@o4dbggnP|IJ!$>&^AJpXR_JKzRs_zD!i4Hj-qTS z@O=Ep-AA=>ZzE1V9}mr5xZC~SzBaqP`}qGB;^g!3)L_7Ugt(^=mtPtDTe!RP?0=aT zS8VaU_@7N%dM9ge;q4K3GvKb);F3Ea?tZ}KG`ReZhfa>)Hb1 zNBL5~vb7)J4nv&GgVe5YKAJxF4lTYE;^ca71J|=2``eB!+@Xl;wcdL!7~g3d?$p8^ ztkE0X4fL+|dZLBf196dU!4HZ{9pe)D9&lSCE;$x(3t{|>@hi3B)XmdfwHe~%^-C1> z?tr+B5tkG1Kk_&)cSPLkhzsq^?Mst=bL`dfV=2T*`|1~fece3W_Jt59?MtA2!x6U- z;-r1q3*r63N{H)1TxLtSzoNLLF9f|CEeQ5abMSd0#&7nr1NfJO<7qcfcg0l1N&6f; zPX02xy&Lx_;-q~Qj9(LRb;5~tEk(@dRqg@%K0%zEM;7A#J><|9}tq!>6wj39I3gX;SI{UvY@=ba9 z=oa4x$X612^N1UT-#HL2@G3m#>ES~^P98h1#rM93uZnS*ygdO#!SOBJ8;ElXeB5ft_ehcBl9&f%UmbDdqQ|xPUPr$Cm7K4ExCirqt0FEUacJK| z@#9;3QxI1bemIDGunM@>5Z4fV4(csuPiXPIin!QS+`cB_9;*ZH6~skFT)Kuro<3Zi z(BgX;aZSmG_B|fXv~VvWP9Dbt$T#hJz`cMtc|7P!z;XPm5hu3zp4H$&h&vLMcmdl;P%tt z!mGn~PtR|CYRiwkHMk_=zS;|Lam2~|Gv0%IX^aKj4jR4$`FkGVw$h=&S?32 zgW#j%ZuCdYzrldJPQw?N1^#}u0pKPIKFXIOj&CCZxQjJ>DH@OQfICCO7og{?#{up% z4PO}Jck2s)%OFnfx8&e;`+YXY$>$6fULS1vGT@Ha=#A01{Rp^m8okE3a6j|rOpcR! z%c%F@UjTQcMz4Y6@%;ERTjP5O;wrd)ZT4kV>t7u8esUb(4$|-?$&W#2wfOec@MVc_ zFyO{&__8>@L&gAZPsGXl^8(`TirmoByPJkDgZ7QM7I3>FPF~klF@AS60TO%Nx~zv*Y;ddPg0``ug zPcj8?8*22%F<(Zkc2mpWbu|9g(cg7e2b_sGvjpcyI&K7;aNKxzO^%cH8MIHwI)GbA zV_ya1a_iB6TS0@X{|k@1CBQ9?I2pgtuXtR$2XKpM_)3_6Bj&rg6_>d+d^Yl#LBI{s z@TCs{`$pUaxLM!v^D4#9oCWrolK|I5oIJ0laNN!vc1z2?pES4{#&7F1;C|5HGKYeF zw@v}v3=Phq@i1;}>HPw6GR~1dzz=JAj+1%N6@Wawc}2i|s?nRJJUs<)?`ZTkP_KC^ z$4R{b)I0oiz`d!_8#o%zZ!-XAYxKtOcX}EQ;GWa)*_2oN+}4WUBN{$?N0?XUzJPm3 z!)KsCbR{-2e8ouyQ@FVvb$4R~j z@qGcfaT>l{1CQeu-r2H`aFVZS;Bow7z#WNv@^}!(aXUABSBviejoy3!{aB0Rq}~|$ zu@2z&(D2!-!n&ovXB;Q_;>b7n3&3rs;fu`!_QlSe)bfLHk}rXLTb>QLsD{tN--$9; zo800foaBq(`DpkWfLl+)*EJv5XHMrh$(Ka?hJWXdOCj#r?AI;#iGW*F*f$I=JG<%=;eC(!;XN%r z!b!duj>i`t11=!==)NL~??cUT_qOC*a~+S*xBkg-(!SY` z>)`ro(0whvKWX?%7{4Jwj+1-^eC~brB7plr!&jj5;PxEXix0=+<~ZPHX!vZ(t5-Nq z@)gm(o2!7EuHh?@ebYHk@|DRx2XJ3&`08ZeCil1EOgPDB6JHc?UupQ7#5e4L7T9~Lz8vvA2Dq&>eCFlI_c-7-*YKGbzeAQUxBMNg!PP0B z4*=XI8eEk4CIW6l4X%lNU)2G(z6O_~yjuF$F(h!kGA}nOQSc9{%-vV;O5leg1^JOJY>1YT6}*^hwBn~y-~(- zJ9iw%N&5PXNZ&QX-eqFLd#cLe4iptKCdey?)*I9-a%Yf0OmD~Z|MTK|2X!!XIgxO3#k1UeDuM4%IaP6Rp;=tQ6sfldTE5$Hsq6M;?yIuYnZpc8>k1UeDuM4%IaP6Rp; z=tQ6sfldTE5$Hsq6M;?yIuYnZpc8>k1UeDuM4%IaP6Rp;=tQ6sfldTE5$Hsq6M;?y zIuYnZpc8>k1UeDuM4%IaP6Rp;=tQ6sfldTE5$Hsq6M;?yIuYnZpc8>k1UeDuM4%Ia zP6Rp;=tQ6sfldTE5$Hsq6M;?yIuYnZpc8>k1UeDuM4%IaP6Rp;=tQ6sfldVee~du# z0r>q6@~w6W{O&E4Nv76--*-tq2ftHNIRkK^GeKsSV}_7ks8+7G$=qw5!3uy6fzd{mzvX|#UdiOR;F z>Nrrlm#l6AzYpz&%gzgWvZDZ>UzOY8)qkMc3y<-*MivHpqEWRUsi!zzXGh{Q_c&Vb z@b=PTJg=(_UZatxA_}4>qB)si8nPC{Ez+!emNWX z+5Vc+}w`b6wqsa3icPysh*_$7;i7^4fZzf;Pr$jS>1kM#yS5f z=qbDcvg9+5>!0)dtj@*DfgHr8a6a(nzu@iUM_`zH{0P^sG}7+zBR-?d^M>jNT87pJ zKciQw^NRF2r@*+z?@*6#a|-l#_E5)@ct|E*2YhBGk4NMyu*Z2HctTroyW;;=>nC24 z^`jtu$wU91aV$Op_En~Fe+!Scr>}ZLdwBAXq`5D~aefiU{dwHd`+=VDe!QM|qCctQ zTD;ZWzU1TJe{&8suKX3Zi}aDq{J`)3tgFDj=9k>g#^Jn7{dF>Y8R)gYRof-|#dq?D zqkh#feB7y?WM~k#x6$Q3pDSmBy_t_eCgoCmt9Sr$LSs2^Dulmj91}7j-%f(O^WkDcxR6Dva_%4 z@t4*9{ZnM zH+E6$HMRkN%p?8TPkQ{y!kucpe)|(Hf!FofwfJ#@+DXR#1b;&J^W%Z}Z})z-xK2#{ z(4O6?7r8#Nhh+K`(4X1_?4x>;UFX{LCq5$ZQzH#K%Fl%W~-rf4s7vESLW49+$x9?)f13WZ4n-W5u!D&-Bs|XX6ZBFL|OnsK-O% z!uvy98tZ^xwP!hR{&^@H?}2piI@x+2`XyiHc*!5%m&c>NB+oyIr*h>dK3?^hd)%p? zUl~mTUna%%`0YPjGFH=7$GrPEttHe{ejQrt?xc{jSVO-;9`HOP}@xXdDBbsJc-}P+nY;*{ecGOE#C~d#7!KZ#{0qAa@?-qEgVO7IV*Ess_&~z zb#XoM&-nAH(vRFJi_2$k|=TB*As87wWwyQQ(-7kLy$HxsQ=Nf=_c89Vv zP2E2{iuX@`!Q-3$3d+%OF#dLtAK#19IX<|6dOV6l+^^RuetBDMC$;OO`4rb1*`C|k zNI@Ps#{hp+tY@jN%=0^X7~rj=czksFgS)Hkj()^>Ym<4I_!>+4i%+b<{i6N_kN0ha z^DC2sK~Ho?wY@r?;!f@1B~SVybsQy5S9XH#aST2K{3(>g6Z#RxJM#MheEn+ocEU+nEWq(G`yLx8rsO?{wEw zljoHW-SJ+2HRe>uxq|CA1M~6oO;$WN@#6PtkDmtm6Q^@KGQaY;)ED*Vr?~*n!>H5V zc#yr;s^E8KCGJ19d&%^#+}<)iFDre??bGqpaQ(5az1{lqX6||`U-IiF;;$X%FMgSO zfj{DNopfx1IXY)wCG z&l!Av%Kl#E(m2pxJlUPc#&wWhe16+=&vAW)xxtRW+iHKE2FH`0;z&MUs6H?q@R@DZ z{Rk&z7VigRH^6vS@H>RY4{Dy&mVDk6H1~s~r~Dq|OBm-r)u*#+erhKfKLYG(EXMJP zw|LxQ_&lQdJH$1yH*Y6CFB#v8>(SvIydO&$Fdp`y>bx#*5B3vJW(B|p45%+0$@>LX zQIBus7{D2;LwhXCd5Pb4`1zRX2Ub%e4brtE0j!++GsNEjN^P+jAKfluWeWX)>{4|U1c}n_9O^l-r zddfSi^VgZ=&ko{EFV6j-`rvJ9p6XaNp8Dxz`8sZId>M6oyIL9aD4FqHE-=W_xWo)!gLf$HBf!Js)(uUiHSJ-2cok;73xtHw^p&dTZ}<{i(;*b_el#uX!=>Wmo2Y zc-b}3?TtO#)1SOm?N=hl{SU3j<5xYmy>TBXKbvE@T{_;%5 zcIt0FsOC+dr{lXEr z;P-j~To0DP@7?m#;CvB24E(imy|m6Q>s!DV>AQ{wKi`z*<#8jP;34YqrFN3Z72R?1 z&D8uAaU5xU(B6C{{Ujrss`XI2lvRB0+kB|K`D=gDo*t=JSI%$9^DX_fd%hA+tg4QG zdQE?JMh=9yH(zZp4n;$)m+b1VY+S?Rq2tT!5BAr_sQt}+1ND)Kz-No&cVmp&?*_(2 z>NWBDqKWfKwpZ_0+aYmOPHNVt1;ly;!s}!zrJg^*)716p!+3pSq&nWte2|A}+=oW$ z4}H&%C$c>+)_2QxDp&D25tY4U0qr7OL+lHXN~--Kd~6)|pXvjTsPm!Z@mzrVle8`b zp29tR9v5zGFF%N{ztVYw+tFV>>K~g4ytcT0r}k_V+M8c<{nd#3`JDPonO_mcHNCaJ z<4;Abb4?t>$2~P3%DG#C*QoRH$>BQu&;go!dQ5Fc2%oc%{ps(x|4ngUOgJgigMq({ z*WlV` zdzKR7L!a|;ApY>K?tTz1ir=kJnPhrX&KqA=?N4oO7|#@5ms|K=ig=`~tPk_VS)KDI z8p!jgT94!je2sbJvCoF=*Vl4Id?%SWUyRq0JRchs?niW9-rlwy!`thh_t=kv^d~lI zkC*!CWORnVyrce!iy%&+C)E9FZ}9VRJYd@ug;}d8plZ8vHdE2AM@k?cqhB zJ|n(ksGSFP*0G)NUNR`&a|goi@wQgxdE>>O9}52Feueqqg-_u7SHe~BxjB`+WGRC4 zPV=5j*S~=4S9R^tx!|}E8ld;Sf#V@h^1r#q#mK^Vq{V&^f%U+i;-1jIhWGEy$?o|@ z{u%rD!-epB)gpe+8efYaSBOu_!WKOL>nmWt<=yob@qJjGcfg!48R;&~C@)cyV?pm`ri z`jWU#uZqtvsQ#apwSszH_SKH^Njz@mPdskKTbUDZfi>D2C+e@0(FN7|ba<*SuG6=E z)Za@Mzv6y|MZU#%=lbJQIX+h7?W8ZVGT`jx)aSwM^6Gl(|98p4Tkd+T*SJ3pt}i2d zG8^+es)TsidXM*~e(lQoO>i8I+>FOlB#7R^%aXU?(N6fR=DDPKG>=c?0`RXsH`f~; z$8p5lu1tq{K6&*Ip5NYaA#SPh>HGM&>GTH0`lJkgCukp|?jLD$oqbfSuWD+(%PKDe z@eUlz$ARq5hY$i_mYiG-19hj0oda##m_gzrFmKEDd7EqtfzA1#`f|db0E*d z(DI-^j_WlFxPB()VHfH5E0YJq_~(CB=RxixZWr+ukLC4=J=AfIm;A-Syou*`Hm>F) z{gGQZp6Ye7ngM&OJ8@ns!R-sJz}rpDe)6OzyfNUNK~}^_$3}yk3Zq1OmBg_m-9R*uJ3MF@^`g8lHXb$cpQ8lXltIwP`~UE7}pQMk2v5znG&QztV$zd~|k3e&WxybU0aGs`GfIaX(2L zzi%ge9^W4)Ug7rS)`$M_@w}e;#qc|@u7&yW*ueXl`U~oQ)ZedcpnVb_9K!vh_WHZ( zcvHKVtcmNB{Ml+fUOckhz2SC@8miF~H^xL9Xg^!RQyxee$u&v&<% z_?>G3pAYi5Pvb z<3~Is?cwh2g!{iHYxsV;zjj6Dg?Q!e=5fp8_!ZXjH;%^fd|YDqK1JH+Tmrb-2^=qR z<_0{UsJ$eTP^W&1KxgRthaQ8>*k!5>Fu1B_O%lCudNso0S z#W~!^Gam4#-}Jb?D&C{klimyXvzqn9TK_~tNPLHE-J*_r@E2}JVh}G2+OG0M;0f%h zjze^Db$)gI+PC`^(x1fp=j?*$$6jiG2%pE_d!TZ2dv`qHNTwf#dEj)Z;}O~i_^P}3 zSS6g7fF@QuC#8T~=W@pZCP8lS$lvy0(!z z4|M$os=n#*{dc>1N-OaA#Bg7n2JT-V`O5F8^E@WLr>A~_Q+XZ*{>AkX&Pzsy`8#jw zc#^xQ?bhMjtq+Uu!rJXG@%apoTfE8hysUXX6O6ctmBqf5p_Mp3{W*+FWEakxKN{+DVn6T*?)MhEO+B6#{+>;G8+Ci& z0bXz6etPA7d3^-;BdgcBT{14RT)_R+WPN5Ch<9c@_+NaOkCTD>@ukH5X9?G(R5bgy zN9=@Z%XV2V4RIfb;26-G!FW|`{_K!?yvntM)OLh%A4#wNUhP5rJ)-8b z5FZ=go9X&lxSvP$FFqc@d3ibejym2pt~1J9&&OM*uPOFt$6@RVM<)%R_n*meU}p}$lhyInai5Wpn1@k(U!K{W$3w?M z^|d`XK2+o7-~;M$i)o&Zl*IeUQke5OMK~@6PvH5H)ckG~+1Xzi+DM%TetFCHtK;Ce zfBq642iecktP4-?tj^2GqF_(`^7j0y9m(yeX`Z)A`$D_%e(^W`#iJWm(9F zfXDaQgts)`D>Yu{b`m}>?%TTF@@GHwCt2H@pYL-!L%BMd>#b|nkEb{1*9F8Yr6JZ6 z%62Lj!+ai5y-tQS`J}@qzX$)4_&tcx$L}DEAE@(Kr&m{R-3#N^SV-hOez%gvbpTbL zzyFl42_BtdQQw@%$6GZ2PjQ-io|P7X_@?lEeRa?F#`Av^@xMaXs{IPz5BhRTf~-{l z7k?b=44>uGFRrdDsQEoW0qZGR6LB2HzW9+1-TklNet*G^Q!bYf9@#z$#QD%_Kru<7v0B8^7pqK#r3H{&F{wq=HlZR6Z`8} z8}j%Rrt)&v*1W&8H?+vW`kTV%Bc#W~eZTB;AYZEDcWDUMcp2J5VqJAn^IVnswJW3e zJLi7;W!4|q_=NGfVBvK4d8V_khR?mJy*LzjlDIxRjQ2O0-`vNY`X_(m^T`bG{E4pM zk0&*X>v?tUe(NiDf}MqN?)FMP^E9>n5=Z5R zcpgsmk!4{#(s;jWY0hhbpLyPvMVa_W+D(q9dXlBv!QWI&?ROEsyEE`TN)=^oa~PlO zvhMu#%iQOG{}AGw9jVU$l=!{*hS+bO zcrDF$kJL^wgU=!9>d(CF)xUZ#_>q~!?XHRMnJePHGtuQwPwsFSkHFoaC)f1XkL(WO z?@mzJOXj=4k8~Fthr;6bNOk?IwtHSSPvzri{ienn7*Cy^uKhTV7N==wuBy)O`YY~n zb(V$p0Isi-^fB5$<^Z){gs*%7_BS-&i4rb~_k+gCYQEBZ;74;awLiq8lh$+G-%5}l z*Uc$BpLINb>+J=&K3%_n_`W7x<;R`OHr!4fPZRgu$<5>LM*{B$B~Nlo9#{J(us>M= zzQzOUagjW_a?{}aT`!2Tt|Qi$KXv!ZqkFIB$hPh2Pp%LCm$%{bF}IQWJxB9Nj*|v7 zCPI697RdNP!k%NfzcwD9h$mw5{0fWj3RC!=iSUh$!OpCB50?2C_?7m!A0!@+n zTo+qwg8k*I`j*B??xAKAAO1c z-!8|*I;?@Rr@SLS&Pd+)J20-YzNh>L?_U!8P4?i#AIWRf`DmKje7m^W#(wlzC5l&N*v}sK2{3aOX9w_vAa6{(%!&b?)-$0 zZx7>^8VT_(Xx1lM8GqwTynU7RJGmb7dR`{p1U?6)azXPxpz$d`-Vt6Wqj*1<6Z_j{ zHP4N$72)_-enV|1>8a<`cBGH>H=e{pvNpn9AK?;P4eaqb{5JO^bR6d|;_vj4ev;Oe z(65pPyCXOcLN9VZYNH??&Br(|@%WX7$9K{?p8Wj&=8dj@yY;aH`S{mv^yhcv2;Q&y zgZuSDstNPk#NRO~i2ac(Yq{$+aDOS|GCp4EH+Vjf{~2759r{XbS8;y#^E~nBWb_Yi zZ*4U`ZixkX*}~(TSMUS zVEj@%FD=2xGimej@N0J&-{<$4B-r?#1VyZ2!B;LGeDiT|JpEATEKAxZi$x zieem_$NGyG@n>J=dSi3Ck5g?<^>K{&yktRqhZJo>epJLhU0I*kyOnqNxCaj8d7b-= z`zP&73cPHma!qqzk{+s#S78x;Ja437T!I6%o|NpW4(0w+y_BZMIuMDca#8cW5Va4K zOuYheOx?)yw}kt2kRC(+e#;y@&V(!D^YW_1BcS;>=(Cnkk00^Grn?{C>(4>|m{=EI z{|ov#$6(cEv+U;hUB8*RQHr2bMCt_FLv$3fhRA@08=zNeS{sT>pQ zg%hLH_7lFCd6{q|&0W>wO6^`Ufa~Z8*W6jHFZ#Co_)>qJOwR}7)0_!$Y?}P| zQ`G!!TzYRfE`@PFQUYv`&pgu&K5kLk$*$J)?QcR^ON|vJLmKKCi|rfiSLdACh#|}0sT3T_uj;3{i3#u z+6(gc!}kIH#I1OI+YRgu>3$DQ>{CU&B=eempwpJWyda+NWA1(sF01)H0BR>$xR3MM zI{&DHkRf~yXIFuuBUh} zFB2}fs{3_p=})zv)Zedc;&(dMfB1OG{*?tlpM~!~9I-AxhTpSAD*onQGV88S>X+r( zzahVyn&VpHJ~-ag${?+mxxVsF>i9)hf%?jM>UOdtyDmSTrE~6h>Q{MJJ>Dhp{Yhpw z;EychK96I2Kzr~B&~F}~<|q9m^J95DsNTkX!l>*e!+74Uy#?bQo=@=R)p1Fj?d})p zjaU8Qa(Ep|{d&pO)pqp4X)2t{{pB@v4}axv9BQxeJZjwK&tK9bW%iD~^>^ZY+{$h4 ztB?@;ky-dWx%!Mc4)K$@-_DL|9Ql_x*x&eBecUIbOV}UA@5oC#yW2(fmG|fIi}-vm zn%J20=N92{A%2|*{0cL7qjPYfrD_vsd>wuYz;A>nT6&?oSoJ zPpd7!^%=iIzxw%n-c*)y*C+j;a!#|Zxq;v35KhX-9blJrAlOle@VtT@=GXPh zeg^nDejnZ#p|(TU->W|Sx!N8liTUC4xijghAIS5`IggK9bUn2`>hD)pu2u7-mjiwI z-8}NuLs3|>ZXr5^$3KDB$5Ff=j4dwa^XA-+^zGd4*zugt!z^uc5Z4boBh`F`hq+!! z6gi&TDck#7jxI0af`q|@+TP&4YP?@Nj9>fL->;r_alx59&gsv%o#orqf8> z-rRQX@hPv){mJ5eujG~Gpjc-w+hsZO1s+$P;r2;f5cf%?`W#-5P&t}+_rE0Wi=C4= zK6?=4cQvH8BPZ71k>1GRJWf>KUs>P3z4;y%--RW&SNoC0=ScyN@0rQ|jM$f`u(^BQ zP(Qyi7gpOT`ljQMTp1}Eh_Y=UT&*M;d>Gtv{rdh`q8s$DdW%*sx z_v-Uo>`SmGzp{HC*2MelEbezeVMuHCqoQ__#=lX|qoCK&>}Ob^{TDR%gDH=FsDrD) zxF$9CQ)G{ng)WF|w8!Cln( zl%es$-y8Art6_8fUU+IxO;hJzP4hb@iCKK!*3RJemtN<7XKv?Z((CNN`%yi~$k*-p z)9{I}czlOL`bpZy^Ya+hldONIjvuv4+5C(1<>qM5&#q(K<3{>&@B70MUMCY*gMX#H zfiLwsAOGB@-2dp8P>$ky5FM|qH%{X`vi+YbM^@wGLwXBGsPmZGb+URR@TKtgX6z@q zpSe}l`a*4fAF0zX>mzUa%eT@u+^*zhF#g5wx&76NcpN+n+8ZcIZ$YyTh}w(iw3nxe zW4T?#Lo)Q8dwUY!&qwinx^uKY{nZONE;WLe%R~LemF$!!vkxQcw<yI!uwHu^ij~C+*xf0;YeB=sClUUe@lkH zRmV9~85nz`d-Hrt-tRA7x_C4fb+;?NvU>b=eAN};Jxinn#~%lO-#)tru5-clP_lm- z_bD%nbe;Q$Y-=n#Ysv(~2up??eOX5DO^evA+_1DSd zcYrSr=Kb;q@$*L(_oL7F{7zq|&k)~NI4AHp$$kcom#pu4k;l7NyQU&3_T@0%2K{9* zUYhP*<~#28Qa|%g^?iHbIrTVFKPj_fe`DGHca`Jw`18}R{z%e&9;X*Z z$1%L0F1LAJF>oKH0zQYV59RTcb|vO+Z+v8bzvUEu|C2hx-*_}G>DzoOegxxIUy#ou zI}d(VHSYy=egv;q=RpInGj;tMxUWL?1m54A3jUYcyw0g;>>&N+Z@3<+Cu!34ELHSV zX2o~L)s=X>b@b+N7>C;Y?VX3Jzx6F2$d1eyJ`W1=e()Y>FVD$w5&UkEc%&?9zN?Zr zT{#fq`gAy1A6*mjsQfaIOYC2~O#SkBUqWRsS$Iu7p6Oj7&zj=9IWNAytKFI(?5W^B zsLec|2j(W+kLcVG?_i4K$iDPe98dNCS7q@`VeiT?uX5sd+NAwCTt8kD>-kIP@O+GT z{BDZm^(q(fcYI>2^Y}*(hP*XS75*S$;XSCYAI975!#EG=Z@$lQRNqVD@5)epazpNa z8Ozy8YCY+V0bdRK)JKYhv^Doh`I#`!GYhHp3!0u{?GJzF*{(bN;gXU5`PZDgfBkzL z6Muv>-=9}L;o~T}^(uz0;Kxk^*L@Xn-+tMl`WoOXx42(FRjUx+n&$qo@ifGxayr*< zmEC!zJ(aQQ_@`b$bQiYhqdAsT}_p`ce7+sw`{=KM0pt%$?7;n~xjyYgbn13fdX4IqqUQcc zjUKpK2frT);`?}FE{X3%sJ_3_I**T|D1L9W{zhhR|(O+DgB|u-==l=Y~J;ZS#!OJ1>yW#fU zyj>Ts#KQdeRK|V!LaPkS@vnBankOW$(}aPI1dn3??aFH2zlrYp;=B--q~?1YYZtY> z));lYUXi*bfO?zac&JAAzqZ=uc`W^ndj2Ga!@MZp&gX|Qo#WGS_q>aEtShOUFfehZ z$c299_QfA@w~zX@Er)Qs8#B0G$rsoRuagdiJh$=pHY%Fme=mvoF8K=L`mDT{KR>hL zz9ak~^fN+WUv>$!Q!4!bq?}B{I0ZE8^vXHN_w)e&J}ZT<_zu5br~1E37IxtCm-JLV z<@NQ?{N)ezj~xvCLk^z@)K1ct`y&0R)|353T~9nDoihLz#P>^7pPuY)M(o|| z5B5tSL!bDwgY=TDW_djAKh^pO?^ot81iNbQasJeBsMqlXX7cvTRXjchUiUaF!11VY zG4R(<;yB_j;Pp~$MSh;9c9JRlomDFLk_U6Us68b1*|x4%+d+7H8(~M0<5Tz@YG5sa zBLX2)_`X(D_Y|F*gxx;(@#rD&_@gSmkBA?|^DtKv`Zatu?YEE57i_%WCwOEj_q;6h z^LJxRpYyo#GS6qSuU%Qk^B46?ug0%$sh(s3-#buQCyfJnJ`pasxqJL-x2XHoZ-;() z@qVSc4a6Zi2OigcQ1ctx`paXoQzt9;x#v;F1bb?q^8CxJ4Ejrh-R-b3{?@+ zLRs(b|N8~7wLHb=u{C$(gT)=BT#mA-K^*zReV1MCOo{wc*2TS@% z#&DnL_=|wA?+kh~;&~n6y=3hNb^K(%NSWtlXd1*Tw}QX^l5fDuTk&`kZ%A`L7+wyP>tudiz*lCt&j($9Szla)$Empu z94`~U^6R3?iBK>5o7;lFv8SOud=9s({4w`0i~E&I9$9YQ&Us`zl?$5piqxLMef26R zsoox<9;Y1c6Kwe0*FU_tKRZcpBLw*1oILK-PO`BLv{$C9?JOM!Jh34#PYc@u-uZ@) zTkuO>CVrBQ=hXbvo)h;oRPR@s)489c3cN$k*JL{_-Gz&#TQj;kZ-2gWDB;QmvoV^;Ozgt|wuEy>+pl zMC1c^Kl0cfe}K=^<^+HFQNs5nef5L-WuNEzseYhkW?>$;{_@v;bB{0a*CqijH_IQM z`VEw{Jl1J7Zh-MluIGN8oAcU_YZZ0A$A?4QQ=7T-OMk81fiLzIKVC?jEH^dy@UuMr z&CB|hcln9DUvojVU-|w0%_C`lVr|YZ+q;_T_A0(NFvagtQvbvNuWv~j>hUIhB;#kh zkDvXp+8^p)JsI>QHNSIfK7->rnvX+%2lafn=5p6ZdJD_K_(gvc*}t#l)FglY6Th(q#5MJn`#6>#0^Y(Vd>n|UzcP9>pTGU(OKHBJ?Zu1xgw=Kt zd4NEBRC{)X@cbS7vAur1?DAP*;(cZfe}A|BfqGs9kLLN9T}th5SUew%J^|w%d&AwI zz+iQI^J8w0xwJaZ@^^82YNOSB@k^k8d;!i&;R@WtdAd#kp8Qpuuegf95dq5N&w#IC zoC2Gu_2qZ+H{bGibNxbHPqDHAAE%xM{G*QR!DT&_>v( zxZht>|Ju9i@pTph|BHAZ7R2{awL#q9{FXePR>)u6NPk~t4dWDF(Oq9~Q8@l(@qJ?j z%R0SDvCh1{k^Av8Df1VJ8z-pas?(eDu&Y-;d|%Y7-e-k52J$M3<1D-7H-T|BH^=kH zC@en#GPWs51NYI1;B%qWZNO`dhW4%~N}-_X@Vrhv;U2Hjy6)pZ^r<`C^MP<)GI}Am zkMO4E_eX01cfAF9-9m(Yl+`VHTno7FBC`{(?<0Lrx7Zf$e)Ry`{3E|U@P@^Hkh#eo z`c{K+$-k-|9|!kcE=M6>3a@j%zbjjECB<~-J`5W)b z7{KL6xcgDU@3y60E6(-Gb}EN(|IlKa_k&%U`@z_$d^{67s`Jha^5avw=r1m0cOHMw z&%Bh!C-E>ZM^5JU*oXUz3+W-5(A-B;d-_Mvn_CF{ZDiE`)ZYMm(#Ju2=mu_&J&4DJ z_{|g4eAF&wW=Y^NG`~+I@l?+33HB86elKvV+Me>sd|a)WU|(_#s1Lr#+lfDMD)%>q zzdu3kB=d)>^-{Z(Ma^?9iKBA;P@X4L?~b!+$h zEdQpyzYJvhmUrc05Qh~0ZWGy66Z`2iAN-PMUZ>Sa=uXc^RL##Vw&6DnK05 zD2dMy>%^&^WJaumq56T6hWH(zrqAC!isJl^i|-&4xX#5n1pLiE)3>;K`B%dCfnGRj zkB{JaO!e)`UN6B{E<2Vr*1Nmd&`)}F5-E#Tgz}LJQ{lMqH z=2qMv9dCY7=qK9?n)`o=>uWi=g8Okq$D8-Lo=VsM@2Zbp3;9?;8CnR&CI2`cCmJvw z)*z@SI~v$d<-c3ja6jnSZeUN~O+KHEonc%m_xc+jQ#^04tO5OkXS6pzb2HWF4ZraS zz0Lio&f)L5P-3b-KgkZuXb&G=kmGZExyL1W1#d4t#^+~g4)D|5o!66nBx84}=YI|F z8{)YBJpG_M5Ak`)_zbl^>K8o{><+EN^Pk$=l@;+FiDB@#g+{9V3U9;ng!D%6y+uvL z)maozmUcGiW~C&WM9(nzRYK+{U)Bm z<={`~ba$MM?Xi==9{X~@XEA@Q*TLUp&Yg$!I=Fuam31Rs;s7B6t;4T=4PEsx)mBRfbYo(29G`cL(J zmEj>g-nDPJzmm7KF~l$YC&WD`p3_QvPx-%GPfxwiKhpTTu(1Z{&EWT<&8xuPz~kzy6sI)cKb3_%2N9ui$qT}{7JjcIs{34w%>!{N zY~Vf*ycC$4_tyDg>hpGOP4&DgF3QI(c|GK3rVLVNN9iKY7g&k=6FNnmuek-(_DMa) zGhBcDC9Y56+b-k#-{eH@e_HI{K)jVrz`rV*8vk>eght7s*ilyw|K{PUw~iL-T3%f znstJybJh8k5c}hH1^Dr^EY?XR-c_Gp$*zHt&MFY6ux4GmPEQ@jyM*tX3qHT&)A3P# z;(nfQx%GJ5gSa09;iZh>ciuI8zhpfDe3dQvxEOQc{Cb+}lYD;5@dG)(u3vU8z*!}A zeinUxKULkB>non?&yR*?U4YJBuX^Kp@FRbld%ng`J;?h}ef3c8f9*~+ zj_@QCFSz4!t8=>owmY79Nha`pZ24Ywzr6UpL>uqVW8(Ua`25QH`s(qodR+eze{)AZ z&!T6l?I(QwV2D%W5#FyJhVzk`;Bjnd_D3K-DbsoNc}?Pa%6LCW<(g*yDf2wwb$;M> z_w)<#<8tOG@FVMSKS=#a+M4TTYVVPQ)OPf=d;F1Hh{xFj-qT#3uFjVpK%0Lg`gvd5 zrn(+@{d9gD2+e_c6N9)ogVgaUZ>)}c=pr?~M`4?PWbk|SDjp|g_xe0I4&pnCC_Yci zjpY8x{<^Y*_Z9V5)$=%ZW_!H3%K`5^(_X)V=KD{b-Mab`?pLd8r~2B9{J4>vU+q8P zb+VX&e(^_n|HyB=Ec;vQa{aR1Z#i}=+S zyzr^1{Toj&ermUV;Pb5TBlw?NlgFR%QihjPpHB?U?;AxPf6f_}ft@@ZgVdG&bIHQ#4v=Hd3})P%3%GO9=QsVop$WY)9M}Q|L_G5_c>@VN)52@`Wzmo6qam|F?@zhUBBlY);qxk^X6Cdh+ z{5O2gKWX=&$Jqtk z=X2@{fB8rH{7UN&e|Z$feJhf<-c0g`ukgns`%&3`gZpnC0p-R)Jnn=~z09vW!b7?K z%w>?rP4V6%^eX2oitk#9za+k+D~;swcMj$}(O0&vN3vWDNyW%0X;u;#ie z_$}9GJEr*2h6SD&x5wg){i^ETZ`y z!0h7jB)uf#7jqt}uZjI}%lMo!_8cF7!b_Q2jmM!b_60UyR_jgT`fAB1%f`wO*EHS_ z%62LjSLE>z(f+Cg(8%=FV85{j_d~*Kxc<|)25^CcxnG4#__)dbx^lgN<0iguDXa#3 z!F8eC9?JbAzR-SZz14skPyI-SJ@%h#EDHRwSKZ@7d|opA9Jed_0x!${!B?O?KfQ1I zW54^$DkmU^Dq`29^ViS76uZF)G*6XGLTob29CxaQAlz0}^W%y_K3 z^2?XT@4oW$s>iV`=1KlQ_c%+v&Ov~$reXYZVjr*KOwen+rPeR`s9buxJv{Z(N%Oxj zJ~fp2)qp>DHPlxyFJj;Dag1EU%aXr|_{^OC@;~#rdwio}pOO^*ju7b$UFUDU5WZcR z8wL4Z!u>_4f8HYwg!7V3ai8IZr}pF)V3++l=F{dp4(Z3#@pmqT@pC3~Jn>3dNvL@w z&Z}H;;Jzn6m|vI3ez7&$%k$v;5QmV)U&*g4I}bxVA~*2kn>mg9UpwDDZlN7HUZ?MW zyFNJ|_mk{NPvG-AF7~}8oRI!f zjj!CtC5GQ~G;iQ>p#GlHQuAkUe+1j-x}LIlp6jJIitkkk=M49kM}#L?TUc#BwP%y= z?L9c$?|{njls|hiVqGrvuj~SP50y zOv@v{UTaYvkMj8T=0!k*kG4CzjR3fjXiLEy=If%J}?Bz`TodtL>wXY4QCb)sw93#N%2T?w+4nT(3p_|0$We z6UN6Lpzi{u-64;45fUH%i=U@uyDZ!Id`#AxBY7Ukc3nBVDP9j;0`n=eD9CW$eSX!k zy>^H?Z>q~eoHL6<9!ElIzM{BZi)`$k_f5oSn_zb+%6YSgxyKFT(8_4C_aecN9gy!f1w`aBU?N6nwd@2`sD`D<-oz^9IGZ#=#1Yqvf0yT9Xk_6)V( zq_22t|Hd!)I>aG}-$xiVt}k#Mlp|ul*&H5+GI)JP_Lv2A9+&O|p5$KY@oG%-7mxY@ z+`bwf-$}ntMqXFjrNdKwb~|;yvSxqaxW~S0xgXmbuiBN|U$QGTFN|AsTXj4MC#56s zwZ*tS)nV=Ng*H{khxFE`aQmCzyPtQdAIXHHo~LCz|3&dRZdAO-i{W?j#AAx@L*f&; zUDm!l4&{`)U&PyAnV!buZQ{NOb-WKK9jmq@c)GgY%bw(`+|SU0JPxro_fd;(#Q9R! zbG~|&+Zn*;T(-~m70r8j{~rIAQ|Cqe3w3=@Km4Q8)bI*mGRSd3TyIf2lItn8c^wyd zhxae%c^*`s=5Z8eb>+qLd1|ko#mA$D-rHo`lC-ulwq52?=( z$CncB*H{?B<01RCTTY4f+s&onej$kKhZ57cf7R3Q{s#9w2~Glkvbb+-Aj{)Q_GI=^ z`ikB-M5|aX%!9*Oi-(K-_8{@$+{M zzspHX;dW+{d_L)Tb@c&}r#c+f7k+|xJBM*Qs9nkwt}lum&hhmd)aR}2_3AiEURka# z+_yNS@8Nby-n7TQYZ5VZThuTSIKUBw$+DRIk{3)E^o{!ck?r|gj_?$d$ zRIihPUHtLZzT~*@_q-hV5yuUmvsCf9cVktsr-|#^QfK>%fAbxFT+-R!wNZQi5>Mh% zfBoWDp81G8~#&h1Rpc{$z3 z_uNJh;#0-<@rXpY9JY`+Jp> zJGtkFw*Tuq9_c==R|t#e7NoCo2lyMr?@|*rf5(67AI9HHa@OT`QhN~h)uOVOG{yJs zc~i~n#UtBeAM?B^G}}8)6Q8+v-}+I1FPXvT9RYlPlEB~BrhbvTd4AeowKra+YoULB zPtH?Vo|j1<$zrxWzvH+LIyEPZUvw?^>$_0CJ$|w)brA1Y-;9ql;VSP#oC-mAI|wgj z_9>XZsa4he%Xpn%Y5*>Y`{k5Af^t0rb|wFWc$DyYU-E19aUr%b9*-VU`y=gZB0hQ_ zKTkCFh4@r(AFt4Ppx;Jmj|lz zWOO7SXR1%^td5WIhx@!JiG6BH6M#SXs9F!{BWa4~km)Pbc9@!V0;vG_o4Jtp%WCkX zS1T8Bx4Vq{s79x%$1#t2QpEk{Nl(z?`5D0P*Q4`sy9uw84Y5yDdKl-`^$WiMaf*D$ z^Ce>Qd~;&le`f~A6MueT)H@99uRq3l2q$GsT>ph}f2#C)*k3#sr2aYaJb>zT(prGW zHMAV?H#~mdvF`A3Eq)659|?fJal9XlJp^%ze9!SZdvx`|CH##a^^Zl><3a5tQ9-p+>ce&o=dP5R$CW&a9?P`<$hL=54C6MJ&VuhNYpQU zC$}qs=f?o9Q%P#p<5U0CMBbn3|0x+h3Fc{Yei$!fdw<6jvM>D;*dG)7hLmTx=L_|( z-|s#yg!3yC`+@z1cAsZ?D2QAPc@;afz4$anw|BfDGfLvUSQ&rkklLlRrt$e!(cC`< z7gpO}T3CI3NO}q@^E{0Y;`#_@TYzg$SC4yUV2Ak%k5B4rt|x!5+FsJO(k>G~K&m_e)=@w_ejQ#p5&dz=Utj&fXTclCG>K8gFK zm*?XCQ@dZ8*_p>H@B%MOp8U;VXL(VGPwE0abBt)DCyw3ljUeUz+)+|P4lf4T0SuY~g}!)F3t?pybK%Du_+q9N`d z{p#y4uKXs?$MD+jc6;e-{04k=+}F?xPwh3${wLNZJpUb!eK3fxqPhN|_WYxe?^$tO zLhU4Thw}N}xCQ!^?}qxs0lc01{arG380as0?AOu6?@A*hxP8H$`1oeu<>Rlj+s5~R zx^}V=Rt5IcRckYSwVam*8{{iYVZ7= z*qY<(c-|s@DeJ=_?u8NR_}9dK6|%oqIkJ#?+^AnwbDu`-b_RC&;Q(fJpYI{@;h9=sE2ycshJE%UrHovaQ zj|aZgTD+d{hIr3F^~srhUSzg_{Bw=~yYeD$0=N!1_@LTe;?>FU7Mi$-`)^%;zx6?% z*S&uEN@5>L&wf9<$0r$9kCP`a0%8V?n^EQQ%si={=Sg{gnsc|$uN^vEaeJOugsX^k z>{Q=h85-g*o~eEP;esct<0$QH)Bu;p_XrLAt}G_rqs6ZQy^dymSWtY&YS;MqWHK<$ zg*_my&gR08#nkrJ|K#}*nuX;s=O@2H+o+}9#263@PY37 zNN-X6o=fC$?ib;tEc#rhEc?lFdI)O=56odI!3Xx0gmJ;seZue1Ld7{4-)^YIJ%j930cuqU%G&j+%XWM*~se5Q6O za~A`z@eA-~eup?#alN0!>&lrn-k5$F%7A^lHe0Xz?ElB!o4`kQ zRQJMnj7`KEc>%;?++!P%4aPm=O=j&LsWlST(pGE6GD~i^q}FsZEvctln$b8A+5{72 z1DP#?B&5w2k-Q}00YO=5C%{vd7XbhEt9g^>H ze{-kQ|NFnEPMunA?RBY)N5*Y8{rB$pO+R^W@3Xwbr!{~1F74L;mVUq19dCutx#ib? zR`MHvDt~WU{hqNNnXXu$a+k*2Q}X>SYNxDUtHZteJ=x#J@3UK9ck9W|_v@~YKD6@I zXkJ$5-^p~bXzhR9{D`ze*FM+Ha5%GX(fV($X?dG(aoeByQEuC>y3<`0KlU~4PxH78 zXB6MY(<3q;+0S?Tz4$emPCCw)_8dE_!?XBgT@EdOUGk&k_kC=Cc8HQ=JN3O# z>(l(ogG+Z^G=5#a-yNP+Yo8}ukEO3kyBGdW{$_p~t)of&v->&oY`62LWIV)ondh-k z(e^GMl;4Z4U)1>4zwT_OcG@4x)?@2k4^2F_|GEs1?GOK6|KQI4wOym1*RAy6Y+qX#nnt!0vSJ&fYd^P?}^TvKx=hwcHe6Q<4mKRZa#U5~%KZ_CbX<1HsO}>}D zP3pPV?_x9?>)}iw6bBxwoFpu5NcggR}qV@e` zp6zbD*=--@Ez>wv?LTC`;pbgf5I(rGoUs?{@@w;5`?L4rg*(e-J@)Hv-{#ii+@DK3 zE**38cJpuTMjd}`J?{56Z`A(OX`blX6>i>c{&YM|>bo2N!9HKM=7raG*~gjviBtW8 zf3v&#I(NJ#UbnyS)JCM7=KOx`DBoxOY`6WF-07cr?U|jw!(Ff2`8msBw_wd{VEo~7 zS6{95+uUV7RLxp96s1oiVmxqbmvO`>d1F?8P3*C{JlUSyUwVm>&v^Q#ozu_Cx83D( z`Zsn?A1t5U#rM1A@blf=jq7x{7wmnvenY0S_~g!dt<%1nTfZdpL3v)vVSUDKl03!> z-B)-?iQ3ES%QyS9p^SPv@q#V@FBG zQ&&ZFDDV}I#ollCLD?PmX8JD~L$yGF52?U&VM%@167gSKak_ABD|*=>KW+n>!&iEq+4F2A>%o0!?g4LhY@e4A)#lJ4o{lYKG=eB?Ge|76qJF~xZ(<0Yu|E^p6U!AMUa>jn2f7d@v z`rqM>w+>pb!F=1@yjg}Xo0Rq$`=)$uzrWYtOLWfi_6MZB6A}Ho^?uTW>iyo6+~H&Y z%kR|BJK}EM)^E#j@q4?uvB$aJTYb5V|3z9~(Xi&jtX=Mo$4%>dw3{CMympE9ckD54 zxy-ZO_7_Th`T0u3cy?iz_9DN(o7?wncYI{?8sGYY+rGBkrZxV;&o`+5nSZbT%l_=b z@3mRw`udZkUVSgu`Jg>wT`J4j&D~yh>$eoKzH{+9xBV9Xx5U@qtbcc1FY(>c)Gk;da8^Me$H-()gD|psnh!^&4XZG`# z56tT<$mg|)^(@SfS@W&p|MuYO0ex?fcJJ8Oo1DJ)yUXc~Z%BEpukB{vv$K6|{=@xy z<-_jq?APCw`?Q?em)+$b%j^5Yo$b{2TRXqsWsRe+{?vohKTZ0wUhCFA%C&FkblF_i z`65g0L+01F^z(C{mFbtCucj$K(LQ#yJ{j(=Z_D5O-uf5hcboCOx}9Ipa%=C{n_bQk zfAI;@?u+|8S8eqcce-BuBI&codRA?h^OV^RZLiefJ2$4?=3RRWFTcN6cZ13|o4@&Y zGXByXI^No?dCB}<-{mr1WAAjQo30PL?Z|T2?fYf-`&*yW@3+%_C(LKJaG{K6#@XGV zdRQm#N5BsrX1DFqo#U^M>#3wi`II~S9dB~u8??{zs&(#L=aaR)&V5I_>HjI?ss2f~ zysfj6_fVN<KpqXniv1UgVT3&Ud!9E&W~li zn*YPC@3OT&%u;NB{;%Jz!^Qrv8>9YA{@wQTJEv#nvD@`MX&=UIx9exz{ue&Hzi@2b ztL0?>Udk)bIj-%V#BDwJclH(g3+HA;|4m|5>VNL7?)YPW*R1{P8DEI#r&@ZV)H6OR z<*$5B*R$52FL9R3ZsD_1PsXF%xV5g4d5fQRmn-qx-8jGZ!@3Kf(&4OI?XtG6y`?|) ze~tJnf3&l`n7>K;S{J^d?YAB=E}UJGdUSl#ZSU13x4&z&j-~C{I{kLg_zdgOLGu*X zXk29ZYAvV3>VIMWgLTtyamQns&MmBc$sMkmHBVx%{x3e?onJd1<<=ugZkE>DCTM>6 z(sepM`X12vr|o8G_dZ(xn)n;d+x`iuN5?MtY4v?t-Uf}AEqzM+lm42t&stgYRtT?s zTRu-bNB*|Mw@Uk2ZqawDY>hK5FKK^Qk4yb+IZawewmB^AI(GHW@7Z#8``x7Y+DNXdYklh za-QRUJxp|Idu~|cIGaCYzfF`L&BszYwe}B<;{ULC^9G$>S7@E=#uH>diIRUVq3yC} z?f=b~pL}p~&ShkN*r0V1ZTIb*&)WW2=C97H zWVukwx!;dHozmOCxyz@*DXC9Xc%$(8N3|W!Q9nZbC$&H6#?JOxq37+d(*75wNRM60 z-!kp*)c0%d@OEywan`^7Ew>%`dHPlE_xrvk@y65i@AbDyoaHoMB<;HVW&OMSYKb$S z-M)*Ye#>+6H}lpW*jWzq*j=M_2K;+Bci~rLxK@5g>(Mc(-S%h6=ex<{=Y2FUfq#26 zuVHOO%iFkqZ*m(np0V(II-S*=aJJv4-z$*2^)fAg`SDVp!WZOw9S^c!u3@b+we^hpz4!?C_pg4~ zjjs+#yR+Pm|K+wTKYy_9xm9hia}oQ^BqGj{DSybV=Wcow9{=Fpi;`QvOqTQOzboUP z-&=X2+uts0KX2x<+pyMeF>br<6^l`^*32w$pC!+0WDeqV2KvT(@1;tbG&OrrqVq(jNEwTE1PDtF}J;d-+Q`fA;lA zeuMhUHhx~}oBdarpIHvOg)4S`&OF;)e1;5fpD%xp{l(7dZ}~E*r!BwJTGzDExwAZe zf1B!8D}VUl!o_laRPN@b50BpU4QcO=J??v6Taod4ZkKbm&RP83?AS;9J?_Ti=ZkyX zr-Avqxoy_@bLCN)uR5*r{@kE0U$*`q?RFlQeD<&WIh|e;pOkjz=j^uavmV{K%Q*7l zkk+d?x3_e(_F<`if%nsUjh2(3_21s6I~?s*nJ*Vkxc%MuHJy%@tbN$n4xNwF^|!u= zeKKk{Xgyb`|0BN3IBegCwEisrhjkb3li^?dZ5__+Q*`)OULx~J`%^W(@NH?|#dm66 zfu7rX#qN>z-1>z6oqdrGPvbY;_HCp6IMR1&`5pg9>SOz}+wU#fU&ZES{hjT)(4+mW z-?Kme8!z5jF6*)WTFG0#ME+)8l)F48?aREy54rW-u4#Pr$?o^~eRel#UIYJL>e!op zW9Q3sQajJxo?*FB?z*+VY>dWRR=?oZW9$1mJ;iU+{%;VU<=4wnFUHwz`~KeM2QmLY z%T45Ter=<9|GW8{$hhOb>jiE+{%5j0XkPo^;*0faqy237H@jVbCH?Ps>)z7g+RHVs zFe3To<2oIzK2PH5y!<^jC4YB5My8+GE9G<6_n~rQAJ_gZkjrv6tlx}p{fE}4^Al1} ze*RFqahm`1P|Mx3JZoMdzt@PE-@?zE2OeJg#9lAcEBm`ww@&NMI)4;3yZOt{+lIBhRzJ3LdSO1h z3vb(ByzqOSJ^DMa{$2Tf;O8+~@6oa7e$G7GUEhVjYVV`?32EO=>%2Z&e))1~pNk;!9`Mp}Zj-Sov z>}-!EYd&p(&gWe^B*Rz#vOB&T*J^!g*Ghi*g)$zuEq#|>qTkyje>PsE`SDL`w=XH< zcY)Sx$B4J|S?M2#d#fbhV?4_3dWDp;S<~U{J0SIsdf&zyt5P06Z$B&XE}EawPW;3_ zNdL-zNp^jt49~i?9(bMR>$F+tFSYgW{2gEYfz)SfTmIg>O8Z;BZs+vF;bXVf=HeN?~CE_gLCdgJwD{$O%w)bHs(>idex z{2KAu4f*{;{-L;^8cVA;n9p+AWxPys*xe0h|JcRwqaCh=8||=E)$KtW-y)pl_uZ}S zz%Ju#7j}bi^(8ZYPikm*WKf0cD(@oiC%{j<(J#IbzXX2ZZR3vw3~v+nL1_1Nhix-^ z0S@M5Tf(dAT?{Yki{ULlRmU6pdkiqVP5JmY@*f8`^4sqU`2eZQIg)_IxIA@izI0cLIjDjb9BI-X@NJoB6c%c&(@J zXZl~78t(P`hei(_?xNh~d1#00;T^n9If&l~7~VDxS>MCk#Mxg=Z)pEI`HOOT0K?nG zM@+@nDBJT%-Vk7ToBXT1CwXbW@HTPZAD=Il=87|ZZgR4cuU2QLfZ;)UX1rRMpPDM= z6>8$MQ&ZLa9MKK_>71XdoFKZ+7yX0D0slyUkKYT~F*%CHLmf;zcRhmb%>EYUPvrg6 zxssOT`^Bn1S1Fz@=1Qfr{={tgY;GL1YJB#*Kn^lt+N3U5{mf`jx8I)`hSKfE>u=-; z^Fc^%rkb0WE6&dN6SoaQSJi!&$uN%WrR zog^v$LE)s|QhGK|KUwG#Cw}b0Ulrv; z0@zq?1o<7!s`H+fQnS0p2?dvsqrS`VjRsi*exH}UQ}R0__=EkUP}o4e zys#qVw>{l0ANeDhjF(MH{xW^{>-R`JZu^Vj%|P-&6Pk9=`VSvH6z@et1ojDWRUWqB ziVfv@wkq^rfP{$lX)H;+4j-mgyA7rWhevJ)vw6+toRE{S^;h}~4)^pbb-cvA?-cw6 zD*vUP>EQuQhY#jy!Ee9VrB8bJHV#)@@;fMAYWGTfiNY)W&7>fw9!Gn6_e=f;#h1nJ zAL<@f8PA2IO0iqd2>n-__Jpq&$iX1T?v(sKvS(ve;>&LR`-l3pA(~Cek2%vPe>EZA z6AMDmm@{57w~maG{JP|ik$q|h&I&nox1OUtM}~)0zB?rOS(1~;Nj&XLS5US?7RGd# zxLfj9$luz%67O`|VRWQ_=x7E6S@EcFCI8ktM7UNd9=$sy-bd*(_5q2n5x?;TiLXZ3 zXJo7wYODiZ_QIbQ{-!BjykinSM|QLHzdhskr@J8l+503vOZN2M^(rC1;noM_WO_zX z&Zi{55b19wHHiEJuNLw#Yhig(zhB}Tk^Ua*A4WL`e@4hjxZ@E%^dqUGAYa;HG)c`V zudyoSj5*Ue@Pm9L`Azb-+5Q@#&!*E3AcxAaMndw-&h$Jwpb8VTPhIlc$Zj%R$GZEH zBVZjUH$El#X{UXTjrI?w6kp0Yp1Cd4t!$LIw~NjWu=leqW|!rw(ZUi!O-hmQO3Uj}N*p7)!t zdBXvqsAjvWZ$pg~)91bSX`I_li?*KWWcMw}qbXJO0{+h=->BqV27jZR*ypvJUpS@l z#}MBBdh7eea*mCtlycx6&1Zj?NdMpaw8l|4l)w0MPf&V#TT3Fm*lt5k(Un2dp zACUMK#aHcqi5Doo8uz|Q$SD(^J@96MFO&RQQsPHh0CKDIF^}r3_7x!zj8>F9+RK_3Zhw7NlVF3=G5GY`vMF%g#l|A$} z;co&W6zys8GpW=qKGe#*?2_bn0$15Tw=CqONlr8Q4uP*xxEgm#JZ_guSP$$S7*1lV z)6@s?fnF{)yxN9UA0~ej2YyZX3&Vg)&)AJW6u>CX)5Pn*Rb=yA&* zzy^cE-=KnS$$^SBvRm}m71k)c)jq)QQ-Un{nbDC^mGxZs0JNAb96!ubPPeWDDkb5+ z`s9a1x;jVstNz447Wf9Gx2sYByo=>(`ycCc_^5YCJpOu(H@Chd+6o;p8m`z)cr?w*1qm=7~ah7gU3@N{?Q?*IKtK3lI2Vs zFf3=hH~ot6x7}54blvLVw7kP|l=MY4}bZlI86Zr4z{ys)1fDEBRR0 zL%Rw7NOGuWc+ejmIRy1>S#CG%?-h9kbJ0yQvbX-}*_xaxa#_8Ilv zZyb%Oa)I4^@3TC-j~vx^16;fl-#;hhY?HsSzx=$w`x3gGNqk=7o1{Cwur**8jjnfNbx@mG}ndH*|hjqxlPuNg1S zO;LO52(%1!Eo=yS2L=a+hg3gF^Hy1}>m+}hrzD;x{k_*pd;!9zz6-j($1OPgOsOmO zCdsdp{?7X0As9vc*>4K_)X85b|HkV*@6D25crnG-yCptGa$+Bp_)0?ahyPsHW1GLH z>#^)+yT2v$iIaVz@@W(v#>?cHTxH6in93>pgm``-KT#@ct3mk#1A#MhetE7kS)7{k z=lp_x67q}H;>^?}RH?Nb6~9NZb7nyszBxH|o2O^9L|rtnzn17$=>Efyvnk67O9G)IdA@|XWf>w)!uylfoDg7IRU^P!7ylnj$ zkCMM%oaM8>G39HkzmOg2dT{Z@_JQHw9p$h-<@Z-#Na1RQ9QzJYU6YTT5!%U;6w}>Hnkh_c2lCf$<9WwO?FIX?E#xh1z>` zzFVi?+vGM0XI}fwnxA;D<};6VsuBL9vfGdS<(SxSdU$yGVLfdoHxty-P}lwWE9L0A zybkgH-MWBf5-W||0wd* z)MsICZWb!(llaKyWBn8_#<@Pg_1XEsiG_vhCX1(23)nP+ zb_CBetWM-g?;{I+le zS;ilHxlx@f??FyzPvFmlFWBW+jfx%Lub!Qm@bTm2<2{w1n<)6$s&$u3ru@ppbeY2? z@i4pspPYB|XTk@9U&_16tGUVy%qq@n&jo)bR7l{JFk%E=opZ$3RJj5lDNYa}zdS!T z;m^-NpUBBPmRP&lXX;F)IG1Pp?9NB|g&Zp+{H=!mhInMj*#=uQ6 zMtVMN(t}{MKToeON`F&-uMIguAx>}HuIKNj$u~U+@nSVsnwg&_A5DC`l$$x}z$a$r zDx6VG{)tMi%mt{4muAo8TkTw|mf^!N=a645=O#EJO*!*rm`vZopPS89CyGS}Zu)E6 zhx<27`DYA6Sa`XR(;f(XvUs9M0T8%h2!X4Zx8*>c$WS!o>v{zR%Sb1%&cdHPov%#6 zTlmzSFMd>bs6Uh$<_F**($kK|HZqWnx7I%=)OWDeo*HjW&l9LV7fXiyp%4p;LmTJh zyzh7k?KWj*Q&YacV{dzk=m%bWuI|^(enjG39fW^E;!DI2{Z;j}AiVXrJypnu;|ElG z!N>Ik{%~(EOnHYTIW#K{<|o{EspR((Kd2`|Ib-D0#+NS>`~t80F!)CH@*XkuOfL=n z*O=O|AA7B)*IUN#qIH*aUfwG0Tj=|_Iauy9K0lZD%k!0dxPFK0?ZxVX;eiiJg>c=G z4`t6uKl~6H_L-ICPbhz8b_Nm!F17I?zB0GNl-Pj*|F+?g9-L*UQ(P#gSUqDFtP%Ob z_Xm2848V+wp8k+A5SZO`aI2N_qy+BJbn$uE4jXZWZ;(W zAy}H~kNP;dSDV56?eE;G>j$?EnCZ50rw(8J18!Wc|AN7$o{X(0r(0gvHie^lM)?4vRvJ`NaI<9(|y;q+E= zzEJzV?wupm}AN1HL~!JDG1SAAEnNRGc~4@}T*Hmj?MlWt2WH zHzuJXTxsF^KGf&n3vL%cgcm2RC-vt)O@yoQVwOKwoObA$_-n~8Q@NCV#ic^d0^wi> zXgbf%Ov378(-x}kglmjp9VxC$)w4!m-SvT2sPE3$4Z6Hyx7PP!A%BtN*PfLWxR=oS ze?6w_UG<@dT{XmfAzP`?X%-Z?l8# z=6(a#O@lpQIkss8&_m_F|9fg~mur3(?9Twzz`^90xyc6Ty5IZ@dX`Q?!`+TY-=C_wp7^7E zFx$7s&%i>lR1bZuz)G<{$cu1w+@kH1d(xD`dH%^Vh4;=iiPu9r==~7VM$>&LYh2-R3BJuWXv_5yfRN|c^r}mP9&_7Oius;LqgLN>_=f2xDKL{7` zv#*qLR!N`w9TH!IxWal!;};~}L3%bnFYz^!ll_6j8zcwX1;gF9_{o9(qeFwKAzgWZ zXTCo?1PkjOczLb>J+za41-coaV9Y`1oImF!9&=LIAraVNqLk0g%$NPCiMg;11@c)= zsaSHZc`L z0iT}faerdI;!o$Gi4kRo|1P*AzEp%caAk-1f{fj%sbdc@-<^K;uTPYoQMlV*oSr!g zO>t3K0!u{M0cso03Kq2QUP zeK)JcJM5|;>Jt~&ycz_<@99*r)bgc`FCf``NAqhx?+bsIxcq;+{%&%9T%__U`zf}f^xp6$^5khTN&qxya!cN)6P=%W!7aLng&vJ;I4 zmyO31iusrOD~dVT?y8(SePSGESvc@B4t(PDTy^qrwc5h3mP#&u8SqJm9K=sK@k)f8 zN`#zBl$@MfpGwZH5A22{$KSPmaF?VK^yl05LA=n4<5+3cA!mB_v_zCnQ5V;rRHz&JSY7C+M8IdfX>oczg*4FPtGzvH4in(>HN$b6rBMF!UeeA>?;J} z72nUpplL{CVKz?c0KZymD z7`ujyB6-3^)V9V|{RR5qf8;us2u^_DP$qOzNT4YjFcExYquf_KBbu zZU^^5`Wqd7e#pDXgHM(hf0wQ=GKKMVsL)~ihcA}j9GCL_V>)?cUODhee9iwi1gTC)Jea!AIhjT&v9_c@N zGzBZQgRTbUH}pS@^uWFY1O20;pbl(t(w`iHCyc{eAqaYLc&YgEnt^;RC*1?10xX31 z*zdRX`?_D0U6d1rb39^uc8$Wd7ds#y3TA5mrbkD5`g?m-TOu%XP;PViT*nO$;fj*q zXnUr26Uaqq7uuT|e7dClL8z+Z}J#(Dk^m$^~$qi`61#2)G1WJV3S;%-VR zX>ok9{%vF*#ve)HYJ03q&y06P;E4!1W5kE=TDc6L>*5@I+{$w>lCOJ=Y<~-a&$R+S zH$SI8@HT(R(&y2n|LW_c{#e#yd?o%ue+O6&WGjU)So*V^4U!Yqm(=(y50iS0_sj9h z#TUE%Ex%Oz8x>zaDm?p+r;2uE0Stv{F7}}p2)sskl%Cwsr2es>y&1)i!Z}{h#rUex zcj4OkYUSD@OhBHW%wMazl%5NR{jOnkt=Q%naBjEa^xnfI zp@*J%E$6z!W6;T<_KF^a{hKkvMCtisT(7(Tu^s+%>;O|xXJ=s2e+j#=pkpczQ;)F~ z@L$dT*qv;S$N9s@U<%TIJw5kpx1ik6s{0ntyXQrp zRplptU$THni1-1;nyV2{w6fsV&@LR8{1j&{cVp(Kb$^V{PlDU zFwS~D(egJ47j;0`{3k^6bqv`2ODz6k;%b%db?M5daq6t< zM>OP2l{oK`woau5&tGebFWtc0)w>pxY2iVvSs zVaOM18aPZ}h4n;JN_#WjHQpLtjq{S^ARjHvRydu@`MSi{%QOvtb$`C@g*W{z!nh)8 zq!kLotM;qGSz5}V7S8G$@)e)exA93*N8mVvn9N|~PC1z5IH8;RAdX{kc!fBOXuvoE zwCkZO+8h@sR!eZ4Na!z>4|>5I=4}`qG399f37G4GJ;#ClL;m$Pe||=Fd#ir(P@mH5 z%n2CqAdek#ta7QGgLP+TImv}`G|mQU!Rdj4&z2`<=Vw~-OPO%J#?s(d@?o|%?5UPx z1_g(uKbE1E{zhgL_JndjG=m`@mO4z~Tt01}P@j3|oX^3OPdzjf;xK5%iCM{)@dzIn zD;|N*gIPi!WAMu@$BN(C@mIni2xN>qP*uwg_+hi`05enb(@^&0VczOVBfJX7rJybx zXGS93mXAptd^OW2e2LYH(n!9KAHvXX$cL3ifqX8<6b>sg^#j4zD+^onJT35vv#`je zGOOBxIJN~NL$HV~l+$|*_Lc1)9#ZPt;eyhPaaFIN+y&O89BJ7ZOFxQV2Ona9>L*eT zd_7xmOu1knCk{S1aYzvkeQ4c;r4I$HMGgc&$4d)e1>cFz5riU z@^tfE;YB&E;YID$lq$Es4m(qfweS&F@+~_c?uswU0WES62g|wf>mzWSH=_K-RE7eA zk}piR&{JGES@y?gCMV_tI}5&%ek88!8RjpRQ-YSX%U>hBm@0SG2TE9$Blw0s5)b27 z;-UQ|9_Ay7hw%cDB-8|bR4Ac-R)Mpu{9tJth1cYp>0jWWCddJUV;cdc3|0Jb_<&7P zeOSep;2Y^*;Fv<$&LAvM)UXd?As*UC;-P&c9@+s@Yaj z;-Nkg593SXp`I$2n2M4<5(kCcc#yv=KISisFPv40@ing^Oxr=lm)TB4nB|+eN)On+ z;!Ncb_>Du2LI+U}t9GC%%R9Y1|pcij!lh9*ue)^D$-3%!1DJ z!1lLE*$Cs!u6FHh<}e9IwIWcy*4l z92%bu_V(7}Xu-H`rf+yeon)uq3;k8?pwes(_Go~dWc$0_5?;kumFEJyV98NI8J5;EWjZ}m^k~3-D2o(o#KUYNPY@$Sm(ep?!89qb2+Z- zhM7*+%+J7l;mOP4HFaGMJ1JD*C`TKQbxsH68~WP?g#(rk?C-VkH{$I-qvc193&3|) z&G(wqtH-e;PWc z$0O5Vy()h8BiAckqpSwwuOHR+Vi)G+boaq5Y(F`a>G%75lz|t-dnKPglIihJ!mQ803QwxMhL09vSiJaXd6r&g?Gy$KR;=B!!NHD!$q6 zo&Kc4+31IeSA!~ReT=H}z7CX{uR_Z;u> z;NorSgMVXv1HU_{Pc0~~!ZmrgO9HQ_!*g%pldf)44&pdQgSU<2m=WF*zsS1+FuWyx zu{whq%K;mI9$-2)6S z;`Pj*2+|M!Y=Qx?yyEj=VO<4m8^*Z{&d)aIML>T`F*laQ#}a>r*=&4Z)vm6y-=68oA>klZkwTHu{}9GU_Ama#yMUXk4jhj#clbQXm105 z*=|vI-QqWXz~R&nSU%&dKjR${e8$;YHa{w#vivAJupG8CsUL)QWmB)mwDUFNde(Uu zFO0+ILR~DMaV`gJJQl&navd+5Z`+^sw{cD<7i%$r9LD1jcp?JFz7V`vAC{BWa0}iS zfn(bRFI&!>hFkF0S~#aej$d2O&su!eb14E}jKJ#=_;Lik8iB7w;Ef1;Edt+&z&{p& zpR;hbTNGZS4950kemp`>BZ8lx3<>Rs*2N)s7@{42Nm)lezR=W>bdK;rh{ zaEZK+SAGOk4lkDjWS-D&-__-OOL_7gd0s;xhj0$Pjq~>?>bvt$;p{KRV}fjJvaZcI`=2`Y<=Diu4^Oy zp&N}Cc->sWS~nM^ry&P7+6&f|(0Y>=g-qP^*u-1_qZ# zsQoNel(QV>Z&81djkiNb2g+d_UAz{^U#M4rY}le*ZFdEml;qCBs6)tS`P&ilJ;?A{ zPn0tcQ_XREuM*5ts^m%_$@aGv5#Dx^!+iEPCgfLgGq6~7940Zs5U?7t*ZN~W9?V&U z)wOxGIy&^1<#a~LC;MnQfsK_7Tz2Rb{0eMnHJ^vcOECRfFXSeBT6i_E1M3qP;lhbs zMKwpiqPA^l<#$=}$Z`@9;p!9eK|%l2Ja{k#d(b%JH!b+Ugx;sQ{B*el9i;ez9WPnI zKarowS0DmPx#{uAoQvOp4tX;jvi|E4csU|m3lVsqh!?f7D~w9R94wetfg!f_uSLjN z6yeG*OytXRFg&1a=1LFgz~7@|V=%YB--m-{Gr{zkz+bGUV!qz6!pnF)LZ2}!-Y+IO zowObe_k*ItgVio!J}Ltwt@v7_)p5H1>@#j5YI!4y1J zmn}bjmz2+P)~)=`_=*)?#y5y>hU>Qe9$3?>L&p9xe>I3NUZ-iYLpw0P&9Xn^wIIA| zyaVD=eOmA%G33WXIasend#+jfbG)?EdOg;Y?cYhb`tIPcr&JTld80mn&nY4$PK(Px z2Z0;1*k2A;!_qUzcNWg;7MoUjVE(3MHxAdB87{6@2>pZlLzfw5))QT{XETV$fDhl< zP!RK3pG6~InEUJYeM|QX8ubm36B@|CX_Ql@E4D)nIu5wJ+C@Idamt5kNT|QzFW@1c z!^QEn6r@8{521QdD2Mr6ZfqIx=+bjycJ^curZkpjVd8(dl?B&xlzh|BDBmT=tY4Xi zV|} z49y?#+5Wg4FULF9-&jt)MUIH}7CBjx6NcBcLRg-#{Jt?=ehPkso}iYuN_JrTb9(R| z$My;8v1arJdLkdMF48k<{P)V^S9*9i>Gp2B(!={2PYnaNjPs%$@hX2*>%lJLON6t_ zIP=(LoX3yZ4c5)Ud?9l_PZXbV_K)4BceB`!dJGnrVZ2B28E5_2WxVjlC#(0_<#@sI zK}@&xpVsX{<~Q!ve0Diphpxw?W;3HO2Vw;6h~u-U7pFSof2s>{{AS{9^Re#; zZyU!l9&d?1$HP8 zrTmLMToZ@4jduWsw~gbPM7$+_k%wy`@iuY%+iY(x()c*q|1x-n_fGsJgMSdXc$<8b z^9;c7HgWvh^mo~i^DKCVx5-C2&jt){8-EU9cuV|ZFAf;qHhu^&yiFYIMK4Va_XhJp zd?3JuhY$+Go8-=VkQwh42h-laF{e zV0cTs-Ae(6w~5>Gm!W{cvI0-RJqj+~CLi%W!0@*5mjH&hjo$(o-Znk}7~T?pk~at# z-ZnlA7~Uq1f1CDcQ2K%WV@Fb>Fo}(qBUtr+d=JaFI20^gHkxu4o}_V@_fX~T2y?!K z!ppOzv(vMca-lc@;?$LR#(_W|1wa5%KBTMBo^awIr7FZ>0`*K4=1@Z`5jp}&xdmEJ zgbTaV!vV!@3)aVgKadIrD zqCiiyLlzQ-)-(9-o7FUBbF|MTa3g;ssLup^Q9ohx$1*wTvpPQi=KaeM9+e zP>`DO!gAs-lkG%~$5o>~Z^mOg$x-tI{nYU!Y=)g0?Hks+dFr%e^4B8dY+WPuVSfwo z@iX;ge4Fx-_P1qvW?)YaFJ@S6f0#e%3HD-4s94Zd|`jSm_F~ze;cCEPJy2z99YR`MP407I;_huik2(5Es*F1N|`^ zn9j$9e3aw159_l`^)cHH*+7n-_iIg$1w8{?BrKM50qL`8*@5l0W#Oz(!Lldg+ZG?c z%NX8xS*AnA6Thr+(leFL^h3v#S-vU#tzB}$^uThmG+&qGv_uStm+fD+^k*C^PC7p- ze_JBPma`DppXWczl&jJ|mZ(<5n7A1+0Uj}*neE&j=&Aj+XO!D|E?VJbyKT|DYxdWU z0G5OGE{w;7Sw29x?1*7Gb_B2-bWzTdWjExTImYI9P6`!k>I7PI6q z-a+%*136ZS!g4rY#B4sqS4%vCK2h<){;rsI0DhGHIleZi+-5y@vs>IuCm`QW&`J(0 zu7*w(VK@#imy>H&`eFUMO!-QVOz4JuF+rc@bNSOS?V$A$24z0me?3B3?1lcC201S<+NMhO?-~&x$_z>H&lKci?S!%En(UX_W`pC2&E6>M#2hlSwOI! zY@c(MeK;QL5#N!f#fRjr!d15F6^y4%d!n9}Jy{GN>=OY1x2cn379oj5d}dA>xj{|`nqT#WNRMFajA ztMOtvj3*Qt;ye#rRm2QF?|Z}ZuUHQAd7pn9_iEY$#(Dk>d0YEO`Xg{Y`)I0H;QV}Z z++WvqTKIpb`PZnP3a_QV^cvM8;li(1UUI)DyVt0m3Kw6uFqy~hHL3^0^SED<-D}he z1!$)&>3&FduTec1P_HGNT{~Z|QN5jUE)Tb?@`v#iDz8+zcjNW$a#G>$@{qqTV`h2F ze4|`teYpI@g(N|{4EffFocXM0)|S6Zd6eQC4xvC2c6zhZp{Sx!62 z;dHzHQ`oZ;UeJC?byE+3YdzghkUkxOKALX@H)!whxLeHPXO11gCKWczp~Bz?e4wfD z#_nSKgM6&l$!Z0*zcenRJ&?oSyEysF_Q7HV?HPNwme2T;2+z`ZG|P_)7u%uB3>WAb z6)sLEX_N1)FG0At{$oTyxDFyWFy99ih)kg#0>{ zOB`NKhhq_P)<{m+ACBYdt>dI9594|{_e`kc8)xbWy-v2~ydOA0yj12$T z;VP3IYr28-``Ihi@6n^eYhlDTXIkx_|5eSo_C#4?64lr^QEae zAJp3!CwhRhoLYn&uDjU&+H$ylj`exCUc>yt7xnsrn#Lbsy!}fWf57sW`B3z!i}|c) zRJb^vna}b`j934}#X)+*a&wU!(jL`~42Vj}brdU5R%R-n{Y2g5OMOeZqQ6v4WfYaCk$!G?6csf^x&a zC*e367hbBsRs>uDGWZAw{OEJ&qRx+_eYDihCwlKO)HRepk9#CJ_7PS4a|YvXAs=S+ z!nUau$aoV4bAQ6g33KPjkdOOS^65mTzxq&~R=b(II-2~cGVk;$^;i2hI`&a4R&lc* z4nU|6;IkF@P-&k{ocBt!<>S7Kd7Lf`4?;f9ZO83SZ8@-?C+sDsPwO%HdjCVs7C7x^ zsCP^ZcR^*&|+9}2f|*iJ&1 zxrV=x-*Z!~`5Masg{v~!DPM*c_;a&oa+OJZA(UU9J##1?l=C58$xr9tpg7w3sYSlp z(G2%JWBmg@>0{uh=4UAyB_DA1SjYjKzenMIO?+l2@7EN_$Il>(G36u9VhkKlTpJJg zoc`Ob^Tk4a6u%UfW9%>CL3!S~FCwNlE-U8MX~b$uiZVrceh&6%g`M9lJoL9%g@dBc z@WxvLFXK^o+M)ulLLr%V;K8nfX1s&^1+_jyy%5TQG~(oo&$VGsv0b-;S8;F0;QP+? zv@)$r)mobRK!U=27vvYV^9<(;OV1$vs~8CNSLxXi??L*s_$nTQjg><=*rFL%-y-xF z>zgVYADPBp+#7rbno<%Cn0 z{LJvNk#49q>g%ggK5npsb^XM%Zc{%NBY-ql;>G5 zQ+?R`uEgtvH|H-Ec1V+)*t4E4@G-_$B%UR__P)ymKStpS?FRKo==fv1-T7V3=l+~d z;>X^1P{>&&J#9Ih;9{S6Cd}JEU!@mpcQo$Q`%A@+KTFLairszu_Yh|{yKt3|UnBkF zcj@=MCta%SyZYPux9M*cjVb0s_4(jK1B^$@3D(%bf!?^oy>1Ix@&o(e z{=KyB(Z`M3xaDNxGjM!p3AQ7`XTA?#ni(kG6d4a2EzM~>S2_c08)3+XsY+EiuTz~Y z3Qck2G0K7Ug>$&gJ};WkA@ltcrQ-MmmY>Cw`O;YqukYi|huC)po$hK)!ZBQ!1#+Ov zKrPXtJs0tOLU@VhwwmMES<&%d7X)YAk%`+SjKQzwbayrB8OReVfKR?s=NR*}dvB#Q!yo_mO+m zm)*GCueJFYUCzAu27Ru5{2Cn(?7lfg__uU^iIaQXTiy7{_iB8b^k+BoakuByB~Z;1pfv%--vfOA1xfefc{(PV1lI!JsId_ z4r93ZRxM}ydwN|KyH~x}jr)E#ZUxuhBczz$9eutqrUks-{29{UvOlC-JhKs|Z@@;h za0Wd5f>E7ONT2+Dr_E@!7{L3nZ!h4(FU7CDEhEaw^--N38lRAOUrRX;@^ROAl7GcB zMwOiN;kPQEsl5HU4-a^Fzx(&~edHqp9^OJv*aVlvct_tmsP2jP4SIN=_nZ0-`Op}I z9v9|E$&Zo~#m9O$)>xp^8xKhES)twe^MW5WzvA70{IbA4sQWtEr~9uZo+dkY|AWNa zpa8}CKxhYSbr-1D*z>-A@5@!b*nGCmN9;m*8?2vAC;La(ZhHUBBe##HGPfnuxO1ky zYNvdW9yUl%>2I}c)Z43Pa%I@TZw3~r&&<(w?5L;2sfo(v&m+M*Oeb-ghbiRa?*F8Z zg$L>9@K8+y*S!gvE%@R=DCcz5d=TQrYOYi+zP57+O|@yMGC^jUJZ?h!k{P= z2;p!j*e749Kwm_03O0E-0X_J1^bCFPpqoi`?EB-B`k;3x4>4i2eDC_7pv!Ik4zYXH zhc(XSBfIaP*X0}Y*nRT_8D}{kl^>(>`_QX&z8Jefm(T3tJdNSxsH)ZI{hW1#eZBn^ z%HOpcHJ@E!|0y_w1y5>)7?`~GpHzOifa0<1Le8f+jt1LH;>j;iN7K?Fz47wvzU1+g z-*4pe^gkCUUYM^EWB1tD zp+mUo1I)+zWJ>T?DZaQILl?`RZECj~*e;z*p)ZZoc+dmBNx^SR7aihN! zJBMHg*%^HZj^fk!2yAUpz}-{;!z(x^g>heh!CLV{5q#9rC8sL_M=cFL?s(51M-$iM zIQ%&c_0+glrj?JTQCFb9=4)l(iG^!rOdNZWf>TBeet@fE5JEX2t_%^#4{@cF16MjZ zaHUg#V>g&fp8)4`c6j`Y`FLuJp?}Di^3B60On!jd;e~!}-5W3EhkPqs0bly7`g64) zjLaas2CmaTh0DOvV;3JicH!u8faA#AiWLsVO)Fbz^(ih z@Rhd?zVgOR?R43A*_E+H|9U8buhXyXvp~f+_ke-yzLtLh- z5SQsn<9s}q9WEB{z^!z}a9lOe`nlPebE|enDrRI?pH=!2mua z0UX>F$NQihz-M4k$A#nkAs0Ra8>GQ@?8Z??S`KKgz*2AklEn2nJJ_Kn@qkV^pUb1= zU{2z5aBu+GJO@YO@C(UsNnC|d9k#=`I^fO_#JD=(E*cL!V7@+=Cx8QggY$YoTYL)P zorl>0#TnRV4$kGF(Rwp}5wF6?4|KPx{K)*mJZ$v_`>35#;R@xb^JprQbJYoa;KIwT zcsU3C!4Ccuw94}{r(5Jql_nKz%SV3oOso8<8JP32(2B!}f;z~So>L1reW8^#MNn3sdpY(4zUs&r8-zrOv!Y9E47hY`jSMiHrPm8b5U22t&I39oG;up$p ze#wE4SK+i7hn)eRbm5iB^0YIZ&z4R(`Lm^h8?R_S?_2BrZ@Hhq7$|iSDn=LYYkLfS z<6akhHEF-wK+cAg!{geW*0{FlAAtUu;;ibP3EOL`y+6l?J!l>AhG&&Z&96gzZ6$l1D(`X!F^k7m>!phJE?tRWo5gOtDz zIClf4NWfM~MJO2NVD2V)pmAuyIdSMhws6jOyuPW83kyf$^1_{pD0S7|J(598-GUhBh@KA$Gn=r7obxJ`-SZIh2>W2;(hN{?v5#5 z`cJg`f15q`8(yn?NRJGU4x>R6pI;RAuaW(sUl-@`-iE8J`8+H=zC4qM(P^j|P8O%8 zg5ePl2R~x!zxf%gDszvc8c%_-(n-vHRllHP5y~0f#?mUv!txCccZ2hi0zMv{rAB7) zh47h=xOFBLzNGMxW3bG};)h&OfWk3ZQ11C>)TE&~L(f2lphI~M$LryCg~@^bqeC#@ zMi{~N(yA-?xgiPw1?@F?~)!#_0@ zKim`6KME_Lp=UcY>K_@n1tU%y2!Q11kz>8~gNeV;^3Mkv_8+d2zrXc3eU4cBTlKg$ zyZK8sUb{f+&+g(i8eiztk?Ed_#HNG~l z$5+@z6Sx9g_;t-+J*efg>%;I0&hmhozuF0zl8@&fPeOhJt5G6n{F+mrSN-Z7Pwb+< z$A&rR!kfv3vL`w|-G{_`zJxnOE9my>vc`0pxf9Hu9! zcv+)(|BEe+2jf3PK|iEmK)LHqQ;7K)?Ldp-0_h*(Ns_lyysrYUm!hEpYCHLBT(ZSxE)^_)rZUVd|L9iNWORLNl|}Wf{H3U^4@!& z=JUA8Hu3ZKOB^@vL;f=k==15Azd_+eefWI3;nD8oP4Us~6em z7&hdCtLiYvl`FCjmPcz)vDj149#v=e@huUcGZ}W)qXEmE4pE9;nl+Y z6n0nG?RV&Z##VY5-Zfe;X0Id5ewog%p$8l;=EJ91U5qpT0eZlA+gE5k+5?i$>&`Gw z;Kh7iPsjZ;jI$ig4*499fGbUz&p57`Gv%|tF%ral_7}e=crhNtqlN?Aqx0Pet}&l+ zT9y~A*Gqqm?5SS}_1ThQA!|F@?hVQ&?m* z1ziJbEmRKntR$S}Grz;aS$-7WAU@10JMHJji!rOdCz?z#Xo3)5HAkTR5R=U*M>|Wu zR4qWiazG9R;dCA7vDHnp$=UgFTC!({YuySLhxacmoWpD5oi7jKMdU}uBlF{vwFkC7 zS5iV@{M;4#T*wEk@`Q0xvnAe_;Cq1=%i(ani4sT&vWI>$PeQ zT+LW?;Hq`+z}2EU2d>uMgg8tmcdiRlxWjIMPaksFP2mpyRBqh4{!Za4OlY}KAB6`! z78V{X6tr;1dLooF87xqg{BQxGg}eMM&CXUF;e}FqmS;~2{VQMz7a#G^K0NPkI73bB zj7mVEK57|I$PdQ#6wcc-z`4_7qMpCT?FGp%@e84R9`Cc$C*#^{2VdFLfm`X5<>=lg z2j5Dc0bi$2woiBZm}wwG&e`&8xNhCT9d?7!Z|8b>g}eAFf_1Jo1VbpZ6w;AP4&7kq}e+7H1YA4ZnVd>7=4Qbhb}JkZDDvj>L15$p9z z3U|m68QYfAnomg%J+S$lu?<`qLR-zWTS;sfVe=i~5(WzT?Q#BRH_Sg(eQQ#_nK4ZH z3MUUt91{fVdFD`7%@^%Ba=B{CvTO4l_AHqjWC*^oVz>ow)o1pE^E(LH_fVY8W28gG zUFE#OUHpjjFVr{W<9-eB2_pj;`pf(hrcZ^l$IaNd_%1BbeA;GH;+xd}*{n|pevJC5 zf_PV*%H6}6Uae3I-Z!8ggnCYtD%Ekl=>$B9-Io{g<4*ah?!Nv3-TwxKKJDiw_SX&N z>wP@92#WoS9ADmqgC4ML&-Gj0$A;^%&DDa?C)O|dd~UnlPUQBrwnD4?i|GN(bHlS8 zt=%O;KG)~DddzwHL?iPb_HHIM&x+59gJ&&x`n4eY%b>eC-Cfd7U=9`dlY<+!jn0P-n~e=r`?$ z38_o&Odp;DC5|BlzS0Ng^Mw;_K^?$xe>eO{3GvKFa`1xoH#qk}yr9qd!UG;c9W`Iu z!IY!-wZL;f$BQsC?ku0Pq5Ij?xuUr_x(?SuW6kAxe?vpRzHO|aiGR2x); zkulIfFh2p$K0N`;NnzDZ-k+&XP8R`ZIq0ICvbA45CRfDI(R_R6Gv2gtOs>f98x7+T z^~C&xc!JKqU^&d+c&y~(d<*1ny-woHKWFgGbxAya&+=K%w51Q*ZP^O%C9J=74kP=! zP5y@IL>vny(@%KZTwrI`ryj&tkbZE_ao$c6(_0l58~AfD!4pbE9`5#PYwg}mU>AtSn6~eE$Q{tV} zPU*f|;#)Kh(sPf-d7NvT@bf<)@i@u(_=d(gz7m9AaG%6iNuQ5zNqmj)sRK=wUwB_H zJopK}BfS?&ypQDLc#xW>YefL$BU*0-`!eBKvmgVn5Qq7ivp5q{Um-p@>(9>5IdSNN zD-@^HGr@ER`Tm+~_w<_b!bz;S8-JZT{X@Hi@wx4yHb9R zJ7~Dv=6)Vnj;XG2*MLHC5~ges?9qBL=*WcS3%H#L9@_&UARHzv!xZOMyf_=6u*)C_ z!~B33@3YJ<>It)WcUX5OcU~d>8T$pqVf~sDpUTfpxz@G8lxtj~C_H$$$G=d|skzEo zOmnae7)Og5m&AS3X6E5^>HG<_avtaCD?UsiheMnvPQo+pQV#Gl@`3NqPQmUhE#*n` zgL0i+mePOh-+my*#X2az#LoYBftQ(oiNq6BE@gWp-of=lH9t@fLt zzmxnuc>V(l=kha7_`9#vIG0OZgl9)J&gJAH=~4!zVqL1=RP_KZso4De$w;v{CK{+1#=#7G3=Y01qiKj`tXvo>c&}rSSPF3#Vaih`Fu_&;a?qkp(>X; zkHu7dgNm-uM6NGD}V57`&@2z-UVFR|2tt3iI(TlD@*?0)## zlnPh&QM!ML-N0YkeSl{U(s-rW#8Q^ltt;5uGJi%q3*U2HBkwH z|Hl8%pwegQ_jG)*`#}4U!rQLadb0Z`F^zAW(DB0V_@8Q=-)Gm~aLc*0>6SzLa?qwp z*f8{!s<5xo%slMr2^Gf4@lx2&{E3QxIS|4_6rz#>|3e>NH=a6EZ8gGnyzQX<- zJ^utIh>YX2z;3GFX>howw^zMl^I^Wqd==hkY{>qBK3L?B^>&-D79yT$#i4dot)3Zg z;a5u~wNS*CQ?2Bnc7^>C3nIK}x4#gqs%ny3a$r+ECk|@PD<_^B~C&tb^#h6jneYeIiaYj}I*mkE54%Bx%M zeYwgnjVpA1VK=b<=-7~-N%nF9(SrLux8t|%^rw6!r#-3lXLmWL`_I>@|D4_Cs_gGw zqwkuRl>NQusQe84Rp~7`nxrk}B;K9sAJFNru_f0BZP?#U?l;zSh(}o1iaYa6!Um;& zDR-9Ix`|Is3A=4N^?^>iOd8GadH2fx-VRDX*~VLhoI2&l?5(oDw~yKv-hC3^a_XNN z9UDE8!J2}!1FW9X#ZoKI;pOzB?9kf{(`|MA=YF~0au=t6$xjU(*G-<-opSzdTWh}! z%yNhI2>qk#+avXay=8_+biS7I5m%Zv%OzpAGPl1Ze}vbIN%=70xIYcY5W-T9TW5rv zO-lcg-=Bf=Ott0iE(`v)lRtO_r|ZKS3NLZzoZ#1-cEj(5N+n)nRq_**9;80$;oB&_ z8rjoA{vyfu4xSM>9^9S3oy1RETT$pB3`QD1NgC?+|#L z%T-Gbl-p|Hq+`VKWt`8!VmH_~AlNVEdS&QXPL{(96fUe|V1M!@aASL6jrx@&dI zgTp;2KlV6EZ|YoN>;N_n;Ue8IycjOzcM3lE-H&HRg+~Kl1t-5_-yPm&xYYPa%jk$c z&;3cj#oOfL`RO=y4sR1@{n15z(t$o|TK+)t2%LdooQ#Bah9stLQx5IV*%AQcUkQA? zO+MmR0fx7Uw&xgpMKJ%O{?~wux5-ERxq#tqUQxFQ}GLmq5dp~<9+Gz5@-G@+27``(s>!^Zvy1ujU2uZ zPr?tpOSi)Q?eb}PI9~hRUyC3-}gfjUv}1i28NGPJt2Eg)+@Te z&MIEScX==cr7oov|q;FB&K+DA@4wwqjh zTn~aC+wCcA&_?0tfz4O#ba-InAV;;|ow$P!4aky9KHvox4xeERR*S#9agXgUv=g0t z)ewaM+kAyP^i()_?ckr7bIUm~=isY;iODl9a&R=q)n73UhCbtv1N|6hiViyft~RQ$ z^+dkQZrC3Zfm3-R(Q{;I7x+$pVf~RC&qer~i|WsDg%|cMnXaD1eiE5a ztEVbzTNfLz@B@nv2huqEVPHefa`kYzXv+b-T0IO~msoNjcAat{8#!_8Z*lcIO%_i( zam?-!d?&7wIZCqh1iVE1eTnpdc;3xF5rNMrL9OyMqCsxAI3f6EZ@QMhycCY;iuKKw0m zQ~~Gc_l5pHO@ws0yZTlSAq#i4@_@ilqsFmwf5atL?E@8n_FaH^GGo^+R= zh&$y#I+;{$jhi4GkAxfR)g6!JdbKRCpd6lbl*5?bsuB7?dEOE(EVo_XFD!>$IF`dM z9IIU}9FmU{2l-B1m)ju8wx=q$-FO}~ZRJC8>&7GaIIhuRAJ7NOc{h%NTK$EoO%b@8 zkLA2e4iv*q{ozzTCywR0OAeOjZX5-*>W}4l3y$SE_}XG;EYF=dl;=(yhHG3nl;=)4 zs+`9cEIpw(S7K}&%Xyc48dquw7nR#BxN6tnz>MWD;%6do=lBlrPr3MzVa6kHr+nZ$ z<$!@uOsk&ofpp2I;U@3-IX&Lgd4(RYVK->ECNr>2#c2QVPzIyj8b^Q~Rbc89wr72q z)m1LRv0u}$9hxylWsh6=MaaP*CviabiLYMG`A|5bl^8yz#?AS>B6gdz$3%O% z?i?RE-g}$cJp;yJr{#LInzKJ2#tU?C!|-A^#BHhMEpWaO_63>iL#w%|V4hpE@l!&d zb>}#d-dqXHCgtP06+RD$+Uc;LIQkqs`GW&`9IcSl@x^WsUuqoZw(bm%lX82Xr9gba zK2@#$DwRC%%-vdkXAh+ZauavnDZ*8=`V(&Ml6p#glEK1^R$O;jG}Ce%aGBzzd8foT zoc2rx0~?lnz_tAPMRGiG3yj~|AA;kFhcS9X`vl{Rhqa(nQclB}-cXJb6Us>^yKhMz z#f_dua3`DQhLqDu{W;A8a=fzcOrJQuspU7blE3cMr+XN>&QfELQM30-zDNB_(ryr4 zeI!37*Tpo+{>`++S4huBP2z1%`FKK@9#=|yK=RKy_3s&gkx49Oy!xRxiF6nPtTi4} zN0L2*nWOM5cA*@%T_rthr=*;&%barbMnAB9WHu?~v~$1QDT!~B{>{3?yPW-XFlgVO zQ~{IrhjHW{NJFUq0XdGmMf$h!;cSvyfbZobzv;9mj#G~y+iNaKej-9o+*%F!vAf?Q z?B8aW+bX|+{L##@H1ZG1@#{6W{=+b@2?l|0^J;fWe#6aAr)b~KX8o-~p9Shiwd?~& zmg$)b&Gw?;Z#&Bq7%m=6!Ca$Jh17nEx2Em7ds{Sos>@M_egx5!j=77 ziN~p2tsRi#?_=a|HupB6{|fONamn8x`Hif^<1b=cL^br}DWW<=`PDnD4xU za@;>_+egnUP~-kcx8y4vOPbgRq?~ikc-LppU^x)GPx1@ouXmxGCy=G|;3Xx#!TsC( zebjme1M`-ifRi2SQcl8cPn?IK3(!N;BEH(#ZaIm!lRnwIEu7=GA@L^Jr@1BZKBqqF z+#IdXK{@|n!5LqQuL3OX&=0dlk7G1?&6<>xcKQpG2h^!)7+;d#LE);MlKX(g2)F#j z@4MFjQ<6XC_80j&!Vbv!8#PWRIf=)d=|Rl{aoHhr+mV4J7PyIfrJPREzka{O7oB!i z`x{fd$nm2rg^R}lc|D8HbSesd{NIl)@M8=7*aAPcz>h8PV+;KM#R6}5y!ga7?$rG- zEy06{RI2_>4{Y9f_6uztg1<`p1KPax^b-Yd{i%9iPn*Z$SAJU07w6wCJj-8}$9!+~ zeBqxRj)3<+cjnpt)*h?pWAXdhEA_s6HgD-x8Q$g-BEoBhgLy39`_TUM^DKE>zq9pg zTKYwWqc-y3!omA%+WtoA7lilsAD-~WGBO;TUiPiu+Wz#*{;u?w_w%&CS3a=dw z<^|z6aDgaCBI}8d*dyvE%hhiq>J`Qx&k?6RA`e4c~ND`cgeqj+{WqIhe2l-JxNFa4`hzs4`P+xy{IkDXww>!wm+5b>?ei#J-LlKtFS+d!8<*jYlDF6RsP+ls}D zDi5|TUX(mrzpm%HC$DbZmr4G9A13KJ z_f(xzb?@6>YwI88r{b2z@f9O+7`OMT^ggHqpN1O%oVH!SxcTGK<4#2Kb({jeDBG=C zx7-fq>HE%byD)S!@F~}iPzQf68S=FtKMmIeT=DAU`>T)-<7(UU(y3C1hU)@cY+P-> zX%P4{Tzx?1r};7pe6jiQ_no1CmD6Ng4c7~}*tl9>4S-&49Uq3c8ejf&sUtQ&&F79! zNj`1AsRnU1z9GQH=BM?kJ45ED;d)R<Q0l>xT)qKWzuJvihnbH>xHv#!+ zam&CLt3&f8cZM8`O*xOWzQ=V)TXzx1$46f8 zuVzO_$FjIS7-2stp(*+OM&^h0Xi^;aYl(}k2llD=<+mC6V4Y+gSYPJHxQOdIC-D#G z2ak6T%KXq5C($GR+EdKEq%?;esm(3fEv?|v_F zv3jlf+qhoNU+sJ+=i5);E5U!GFFl`;e7rqET<3Y|IOcT^XVcpUe3lN&mm%QObQJ4} z4yzC9gv0rPzTo=D$F<&<|C7F8zf4dZ_Xmly`elU2Q6TlWoBrMEgVORBt*tm;Z28hW zKk*NJ@p{Lz>ELlzeRCJY)vZK0HNQt?eprtNjdzbooK=rl9gMT;F&e42aG_C;=VnJo zKgG5BW$?2}eym&Dj~KReTpqs8#Qbhj>c#rjE~0#%m$=ya4qcS&UkyH!@ZfqdMEq8L zbBm1q>=(lMdA%EFyKb6aV#NKgjEnvayodaIQQ~6#v-)L%_|^IAvgu`?thhbzO?0Vo z*OGD3mlln8FO#@fUveAE`wFnHa_>v>v-)cA$n^RmUkQ$x_awy--E{2ajDdy^MdC27#)mld`Y*)Q)+^-Gj`s_fgWh)f^`lB84&&yP`)S5u z{#Kt%kBfXA%6&_1$WL4E^H)f{8V=+3T$A2cIXG{j^=TL2wBySm$WOyze%kriu`QDK z^W%OAZqMD7(icrfY}`8VX+Af=7cFkzL-IPTHjm1EQip~cjEozr7jb+Xk3KgcKkc}? z1vt%@almzUrS~c3H+FP7u5^|3Ps^_ha9Vy7f7>kTyg&o^G#!PjWqum20yr(dUchO3 z(Lb%P5U0iMhqxLpmaiSjm%m2(r)@tv5f^zqRGa68whqgFZY``T=Ss>SNdJ@(>hPn*OKcCU*F=sulyn$7w0dJv(6{F4<>Q( zybq5bd?H)i!l2Z_`<=|^o(}UdZuHM_xLRc2SD%aHD?A&AbFU8f71pB-zD(S@qqu** zPRE)_{;0QbgX}A9 zyIO_!Z*c!1Uj_KI{Y2C;IW}iy-H@*z__X}G7D*jyTr#BE+9ugQrt7j8xAr;7r|D&X z`Dgp3pW(WaMp2h z^Ez1%-fyye=Jg(Nb&AV+wBwJSAsJWmWd!)N{;Sb-94l`5BQma5-xlPj^=Ymj_>|*{ zCdAdwCw3em_wTj*qWd29@3rH2#}(!N3tkV!brSisdN4m8CnMhk>QMTx^LXi>7Pkz~Eym7E zZGCA0pSE2X2b|U~xlhFDC;^VQAMC5!S=J4Ydpz#{vh6CKdrBd1F~+~dQb(N#y1JiDQWBJ2=J-(jnvzQ=Y=$%``~#T4OfnQex?e~ zlW01cz?aLXZ!de`c@3@qu&;P~gneIv=NvTLz&>%;)f#Z0jMguM5Ldg-J_&q$eURsa zdnDVsi@s?6HwpQ1T=cJUE6fjNJ?)Rg^#V?dI}A9j5AvUe{FLo}8~C*C`2aj0pv{k1 zpSh0K`rLamtj~(iL!ej9?>6a+Hs4BoKRzX@?I+fOPh0;60H^Vd08Z1<{;JfW^)uE( zo9AV?zg@%STS;8=`~lqepsfd(AM5R;IIa}l55sv`ru(kBzqI)=4tmwPy)th78*0jW zFdygP9?!O3wJ(%>vGvt_uG9H(&WC+Q|0;NX_o?*zRVLpY=Swf}u`d{RI1<)**Z^rZoOeB6yV=Ck^5kob5%qW9VKxRZoKpE-_OS8iv_ z^E5ONuS;5@+=R^IOlIG>D(; z%j0ls2wwX$wF-v&6J zT_i4czFGBfbe<4(`26n6)-N4jPWnLA`?~4ru+~Y=*V5af{7^6UeeNrUj@L^aShp@3 z?{<|qt8UHjq{qelSTF83O~JwWU2VT)l=8Lw1Rtvop5Tu%$GW_9wRi~y;0&Uy?x(H@?+gvJ^0_z7yjJ+Dcd?({(77*O~R?Z9FR>f z=ZiY9uX1!A#Hw3KIbXtYTt()Gb!*Ugcc8>sbz}b6^8%=Y$GZjD;#O}@?-$SaRJJ~- z6Q5e&gJgc_AJ%O^;X|DJzSP0n1+U{T*>v!@*m@w2$GZ*I6ZgSdebA?zzw&&4pBWvV z@7bB*!+O-eozz3^gXd-^?t~Th`PqrvL;E>6FVUCY@5(;4)@O^aF)aCdUr4`yw|=(7 zX>rFR_t)|VCg&}ie&FAI@% z8v-3AY+c^&jid6f@xD}P^O<^QA4tH4(Ns@+#rg1%z^kgo=MwZ4jt zI|y;LzMACY5hCXG9`oy8Bl%uSYaZok-Q_&B^C0~1{8PhKq5m{riiE>;5_Pm_UUFP* z9!)@8&A*Nx$n_w0zG?UCabEtX^4H13tY zX#Oz||70ClH~x42so@48u66yx;+q6MEiUu$PYqZ3A^2jPM`Awhx==sx@$laD+4ZTJ-ogJ+5BrlTuq1PH~bs^vDB;amB2sN>*H*e z@p$GZGOp(HAjH*hqmj7DNZiOzAwQ+BD&QY)7rZZZ|Exerx}w>*t_DS^x4_ z4@GZhB#!grpPG)`uj2B<>z7)ej>YB&^&O?}o1Lv8)<^34n5P)F?-QU~|5kGp?1zQHAN^C!ghbkJUTAS z=i{CbiR+2Pof3&VBNEpe#-Y!($7LUMZLrJAd5E|XSjVdyB{=WPS=r)Zzi4s$j!5Q_ zx{fc)7PtMR)H{0b&Z&Cyzlp>30j~bTbiScT9QvZoU&LuT5U1sbxZaU;9f<3=Kf(Dv zsAsDO^05xjw@;YQ(_QzclKJV@0Ua)#`J9bUtX3p=z)r-qMTXD7X z+2|khd0*Z$Gx>SG_lEgA?tPKCMi^)LQrI$mokU+o2}6-3bz*n#va`C6JM)|~PB@!+ zCMk|PMDpQrGWy5k+x77GgE7vkTkrqH`7%s6)t5tOM@RKTNnc@H^rdq=UB}qI^nT5Y z*Ae?4md|~}hjH0g*Cq90A9&m`5{Gf!BQy`I2962e6~>`2Jk08Y(Pz^A=4T|ga$#}fTm51-#@v*ZiZS9^c)Fy)7OeSSyD{II^L z7q{np9N)?36^@X6Rv)w}KhB5ybV^(TOt)W zmt(_vS)Y4%w)Kj~S^15&jk=vE^TWCo_&nM15@*$|aAW%Z5a;dA$;Q|7??i{C7w3m| z-fWn3;r#XaeKdUh>v1P%)4}7c^{V(#qSxb<>#%))j`L-VaH`%@r4H@_8#wEH#5noP;WfP_IJZ8t< ziH_Q)$@d#DKl)eBh#Nas>SbQHBwKwszviWq5A(~@`2%aa&pL{fAJ0GJ<9zXWl|OeM z%H}hVv$oTmAI8P}O8<=O7xs_&a3r=-9mCXbR@_n0QP<)|@-=8bn|&Ek`0~#s`mFqFkvQhD`l>II zZ*m*CebeeT^a0ri+I#bcBIB|SYyS3}Amj3T40*i!RJQebXo2L@>NZL1F4wn%&X3{z zC`=~xwQ!v8z*m#)@5JwuJdh9LmX){zJyJ(g!PVa$heJNCzPN7mU6Q_T;Ci6paDB=D zH+?<8d9Lx{Jg+HyIDa)<8`c9YF7k~jadAE9zbxH9To2l?U*x`&t?!##()Dj@#Qf9g zad|sk-moC{FR@QYUP|gT0NZKqb9ZmH{03;h*oxaj`==I;^Q&Hw=;XXmNAHoz{6HOu zV_z&B@4r~M2AvPI*1ra=LruERL))(#JdAW)Aoa3t_h`2FOiVtJeqI@UVSY=;q;)>= z37H?BhpW6S(dQnMIO{xI?u~{o?QDFpdfSvQ?uYSs_q2?QdOO!7y?>TCOE2?V^eceYbrNwyw0%Myh?`g^y&i}gAsq5~U#^ro zta|V`+`eJl=DJCK7#DFZ!m0gymCO%)&aFrDvQOe>N=Fy*TRIwqQ*~TDJNZpU=2uuh zy#%Dm$+D; z`Fx3X{-wBKqJz&X$l=WamqVSeR} zXx+F$;xIogF8k->@h`WA`55LtCvlkHIOq2niNpLn-{&K7Uz9kE+m$C@?vgk)?w2ER z-;g+rJIZle5~s%fb|mfx5{GdsuOz+Sl{k!>xex9O^ZB~{RN^qdHs|*viNpLn-vg1j zYWO`ip6?;ahxzqwO#b~=;?(>eo8JB@uWQ=*KetJe2hU5sF6niQN9Ok@i9@}0isK%W zIMkcDU;Z5C^E#f9ILxo(RaB3^N*w0r`L=(BI3KCvo{!{vN#Za+ANP|R2IIC^$G;_? zn%~F6d|ExYulRbI&+lW|__{Wg{m17MJzsyA&*RpNtjC8V`EH2BttaDR-Fjb5eYLj4 zVLddTSs&lm!hgGsvhj5;q&$dVa?3d@`v~LKHjBgI{b6IJ;P`zls3SH%_Lu8hCqI#|YYXY0cHbQH@lUnBa9^qBAMetz&LhaLvPBUaXyy`r~3S~%nyBT(s=iz#Hl{F!#LDiJV$O< z`TeopzrTg~Jnq>r4&(ATtDlGYejm6`2KmM>Hl7#ym&^}+p4@@@`8kPGeO^Dj?y|n- zozwe10&D*E@0jGP_SMT}eyF!inQ9(d2bWL)&6xhu`LqQt4bd^C(h9kKPzz24Bk|L?x{&sqNZ3p2GoBRLQ7awo`0cU*Xy~9n5d_OI94?`F#rfxBGhddS)WM&-6SMipKn+&4&^8h1a5!?=ZgNXJ_x4*9SioG;%;#(yJj;L{1e)mQzL2lgrRx_6sbU$oc#Kr2h@?&4r{1~vx&*XcwSNUMYucylVP)CE_)998;T&xbR zn|7c6DDiVY^L_eQx6&PPbt}9z!KuD{Q0hRv7?<5r`Q9Do8>W2RnG$FDH+HA&XYDwp z_=PxMI^Sma@-dko`qD?^-A5$O(qZ~X0A6oa{JHA)z4Lf?o{Wq670Zb}caFqa`Hkvp5e5B(da@$N$sm(@S*{Wf5?~I-s$HZ zJzq=eK)pkhkNc{`#p=a+__zzE$EU7C^TT{T?k6P<^?Drrl3(S6Rec_qPyKw8%kO0ip%%C_K@!y4t=KK&V5$;g8f&hkPn}h zIP5FWN55!&s^!Q1r)^jJDGy%9wf!~BgZl;Jb}o?h)$S{;0Z#3M$og`AT(`mRBza(d zd>)DQYV*y#UFxvr8^_mtsRCcD-eJ05-qO(<`Tof+dhZ?bO+bFDtG9fR^iS)99>8Vw zg?;Cr+Wt7|<@Z$PHkR-EVjj0`9BBJzmy(KAUvj5ph00`bAq05LZ~`gH_jY z%x@Lg%3rm9E*v83t6i_f>$+-vDKO99(Sy_HFW1d_AIdO44@bP*&tBhs+3J>u=h~QW zy8fXrV_)AX_5Q0qh^x&bWb&TGeoQGE9 z{v_LVze(b=;`R=t$Hn~e^!x(L=KEv$Z+CvS>w|-TPxr<1{Vtnc9%uDIZE+G;_4#YF z6L-vt`;lhQY2&){a5n!cYZ&Jp z=VZ%|b*cWnHq6K4-5bL=tXuDGhA(?(hn5by*%FiFx)R5cW@-%pjiz!;bFaYtpV8~WTk zvUBQjckP|&>n`RuL^#fe`S@@5lkogNzWTdleLL~UvE z9Im@LI&bOj4CBye=4W5{J`@e7J}=apG4AK%*3&`KW!0B;;C$oH-B+@$FO`$B&2!b4 zW!Zcg&KTG7C4X}Idf?oW~r`xN==k$u4Vsy=U%EiUt6zhHih z*SzMzisQX{|jX3MXK_;CHhxSSvR$JfvKb2lO5V*lk% zN%D4ol{l-fm>=uQpSw%Kd>;2;cpcaD#@5Zkjgo%!+2_}mI?z8YKlBB0y{8)evV)9k z)uW&IR2|PtzE~aTU!I<~k(~Um(@buzZ{Wm~yv0pSD*axi7y(sg;zUn!H)|VF~Zc4vwMs<7Ez;WP@ zhjFN5?89--i&rTRRc|R<+|rqee)O4TxSPX#9{1lc4)yXl>_7h8-I9%Ol60uP+!p5Z zabLE!cwYwg3+mweY1I3SUK>77*xyV2=VaU|{l^IohIL?ml`YbbkC@Kgk&UnR?(}}a zxct4tIM03DwZeLlkH;Y&;)-V_`C%U*u1Ywy?>CeAVIOcl?n`0+JZ{%;9}G}F?iDgF z_5tc(esvx_oNfQ5e0H3F92b4&&)tv0zMzg4#l?Ccj`^)VU>y2_d|k`p^p+GH$8lT8 zx?#VJ(s;MI#KqPZeMTLHbJFLf&u?8B7xU|-@opW7i_OpSd6@Vu9c@Ji>SbNn2mHBv zjnsj9J#P2#ysVv@`0BQne3ma`!|CfT>KG$_?0cWzKsdk70_~TqpDjP;x9V0uFK&Je z5Kh&xt;`SWF+t;9LE_M7&fDcB4*Ae$9*6x>u2X$Cl6)8!`ARp&oxdubPyCd?l=qr$ zmn|-yM_2F1qlwp`Ka?@zn9bVJ(6v|sSbLX4}B@WNBY9oL%ZlX<29BiaOwM;Tk&(x z<^PpVNahFsL_Vw=^LZV=4g2D8o#E|_6<51%+5){AuCRmbQ|rBqr^7Pj0a^}dld zfpFu$K$J~qxxjJj`2txJ`egu zeU1v|@8sWiO7)NV`1zyKrHP-GFPhJTG@g0K4oi<)xJ=fqxHuh$_2B0#to*dN6^P3^ zIA8bU)vK?jBY(Nn%Y9|((Dv8L^!^ggoA0MF`ILFYJp41ZueAJ_hx@9J^vCAMjKl`|^56AVm z-6C>u~jNT2r($MyMjM&jNUiJKRR zJ1`P=P$cfqFb?ZhZ6?0r^OxS2#bG{=dwaOAFz(O-8JFKT;`xq@jQfsATz43U`Q@HU z_9yZD0pbdi$#b&opZ4B7e$Qw1ifzU9F686)Fpr%Z#+6!e=firBOnm11{`r10@AGiB z`?Qdc-@oDczL$*;pG)BU&==;n>d~b4NvrQk_(3>7j^pl)#EnGaeiX)Odig#c%NNFR zJuJQ{?{E5fI6v>pFTyx2u2na@U)0CrUmgg@WtjVQB<{D7xCg^H)QdW%`273T<7+&V ztT$fo!`b+F9M*$BcaLV{L%rOmp6?go?KJv_`)k_sILy!c2Yn~Wx;$L zUQIsE+Z`YNUPjc>c|+oprK68$h}NZ%khgc)UAC=7&1a zKOSe*cZA|v`At~)y(^qw`NP!rM@yXLb7fhwZmad}k$mV&i{qXkaTu5Va>s>nn$Ony zQu;_-KX(yM)q9G}5A_bxcz2S-q2B7bv_0$%<52GajkEft&~Nnf8QJ1;eJr2*DXx{@ zu$A9AGC%Y=|557avm_3EM*m`U)QI2G!F(2Oi1@ItrkkJpSX@6B35RhxZ}%SQANpLU z@$N#2i}l&^WyH#_PsYXkI&PvqxI*Hr{P_Ei_`Cq0-a0Wv-tW5r}py)q<`r182fOY z#92Pa>R_Cuqk3~v4^_vfWqzmw{o}Zn&m$Dq%5TET@5ABz$^+DIH%Of2bG2d2qdO%Z z`qJXKw@VzxWxrg17&l#?OP@;gTRwLYPVIw_%luF;=7;Y))XqQG2WfwhjL_!!5Pa`p z^WW+3fowi3&qMKbUCfWq4`HABdVDkdzABIVP8f%A`FuOZMcn8=<@tMSJ8d0rl{(Y= z!0UK@w)0JxAHO$rkm9&F=5F`MoI{pZm12u2nMfQ6lKG&+mXRpT{kdIGjiP z-sRr!xRuvqw4W2C&mAK9aDBnP;yh3X;(Bf~`sJx?eLs4HQI8|SIyi4P5sn+{AL<>s zAz6oTo%C@h!*P+X@tJhJh{OGy*!ws5{UtuXBpH1{~9LDkA zZmn>AF>dFev3mC;?51@PzUqleB;mEC#J`zZl`Yz^ZB@+iNu{8 zuAArkd?eppk+?60aZ`MT^ZeR&zkIvwD-Bnn_x`dzzTb@hcDqIT@{O<#&-d*xZi-$S zsP@%;VLl)CN0GRnMB;uHi90>gztJ#XW?z1pkq`Q+>rcsjo4s$PK6-zoj^C_aT=jVR zPT9|08>HV)-3PepM(Ma-dfylK2jlo}HnAI0KRo_hXT-_C=|Kx6_Ez;(8rVtX{vc4vael`Ni(vGoR0| zJv;eT?~(rTemm+I0UYmVBhK{s&)Ia0&rR~f{auVZdXJoMd>=RBwEQOar1j);+4`?* zza&4t&yDXh!nnCFOP~3<7{qD$`97$H^YgehbK-tZYaVHFF~0`rsO_+G>hmO%fE(X5 zeSaf1F6*+k`-QJ0KI3tGcXxG3Wzqb(`*$C5_>%cu-3t$2Jb%&R?zsmnnZKy}pal!} zrvRw8LVVbN|KnS9)6)!yfWh?$;eeTP$zPO%tch5U?(W3eDmUJ&zd}#N)YPEaulKl@}uwQqj zySnJmC5L(*{^bLb5Bq>&tygRx>=(vW*N(%r4cz|(C(Qlx(&stHZRFzOcB~V|Vchny za$fTK%yHdU;`|#j;xb=l-E8^sIP81=eB9t;Tz$Q8T*l?skHZZ{;>sJu@r^~|dN+*Y z%WV{g>&(aDMhzVHm7AZw4zbVu8;9c}-{{xF^J8R_FdxTtUyJMK+NI=7F*xgEne ztjFMi;eIad6z1c4)aJzD+&AL0MqD5C>>bJ18HekS#JMNJ&pEJv?uBgEqb8O2 z$F8_uw&EQl*8j5LR&Whmb=F-g-d{3IKUMyhh3l~oWyj}TnWyuH?N;uu4mP(;J^sMs zibj1-I*thWd5tl8{x6H(SpQapiuPsQIA2&7`_l2@#Fy6f>AsZdJ*Rj)lSOYP9mj@` z_c?F3aab?oMqGHl;d;g6@OTh$T|Y?Q9u3lcG45kw9muD}jrDotPC6fPPdIKYALiHb zh4ky)EBIFY&+1d;%l|O(FB!f3|K}v<1^nNYZ0}LR`OAE~9#p!L^RvvK`$*FFjVpHu z&U5R&8|LHnVC3zIF4S8iy;ffh5f0}Y$8opG`r`4vyN`UmMdGyMc(;D|ywBua)K}jO z^Pyg>2fy!ubxf`io|lYsCuWRG1F>$NZ)rBZfiEWd)p~qE@?kxiBUFz&Bu=YG`R+AV z_9N$uIP|&nrSy4;xWZ49^PQ@W7vu7CcZYEpmvvx05Lft-Tn~6Z5pm3C&7%tNY2T;L zeEhSrX8L`C{lLfT3+6W*iE9H+dmm%|$I=%Khx0A}+Bu?++z-RsOVrT^aW%a|k+?Cy zsqgFiiPWp&;5z&8&WT>s!FA>JdG!8-A8{SuN}oqO-hF>|`hI})TK(MdQ|XH}KREA_ z($77>$Lllt(gd8=f2~NI)~6UZ_cN(i%dZ4DtzWt#ahP9hUrkUQdw)RN%cp0jUq(rX z)i32yW4-^+?Bv(`^Q3N8e*J_~w?`8)KisaiX}tTJ#97-*o)=broui2kHNVGYT+FYJ z#=AdCTx@>U_HvB)EgkL`hK^@teyF2Lq zFi1FczU8Ga=-(ubcN<6?`iJ@T{wm3j_3(WZh{Npy<9M9=XSRCqILp7@2eQ@8;>-U! zt{y{#<2+rvn0lPtNjR*V^3Gu)b6HXrQH+`7K=WH|f6cc(*~e_d-;O&+=u0 za2!W_&nNbuic@@He)lrzGtLi>dwC=-7sg@T#(yj4n{(;MTRso^Mca=pjY+i!RkM`-_*3$S50KZdzy zNWMz8`PTV6>C5W&RUhzGc1iDpA;78i_`S?e>z8Uf+0QYzzi|Ak@v-k* z-#p~&UKLr7E5p~Ba2|2o|NTs#=N%78Uo@Y40GEF{d9NVGEdx%i2l%JWj~4J*=aJaw z0jf9V_dh?9-$q~BRGz2VEV3S3gmDoA|k6~Z`xL^2h_n+`Q z^0v8#YMV)Z}0ORsFwXa?yby$33e>Cd$vT%N!k9&2t zxa~)hb(hEUx-rb3Z+d$Kxzta6ggzp2xd?h1ZQ~$E5)5pO44CypS#KSl;OS*TrqOI6VI} z{UadiKwoN)rO#iE<93~;{2n*rzCK&r;wufGcgx1d`YoSF6dmYuEMLbH>AoOeYhy$2 z8)il?=k4A&GkmCn`LR#=bGOI;-?*4x<4@`J@cHdEJNXsbM%=x##U0%wy$3WO z*vfC8Z285;?R?VkhyfE@@rCD%+JT&CA^=*xPecuA&ygUzbW^0qR%awo(|k! z!@lYwe$;`u2H|kOoprb)vgKF#3+eI%>E~7WpDi8zz^9#OEfCJq%W?Uqc0Wxo@u4s1 zU*}(?UOvCe{LbhDP*;8n@| zvifu!bWEw+yRyZ_x@q^duuh!k{JGmIV_X`Dd{~dJzbAFG)`MImu0c5T+3VO&>cI8h z)NWJKDjmEp8#92O% zZYSp@e{Uq~b6?5!d`j^-=^ww(1AW%&I|WCHSUy)NuH|!`aH`L5lm4O4BdqVO5@-2b z{>SS1;_I<-wz%kX$JOcA%a|X1=Fid|WrR|DMRU4s}v~Rz3O%r`Dq)ea3o>u@47IoK+7^FZxn?o%F9>ogn_ zIgVQp#$j9@hxI_*$iI?4uza2%oa*yIGC%aWOy?Ec+a(Tt=Dgi$VI1lh+As0h(!u=o z?{6*YfP9Rz{LB42&c71jRR0c@deJ}5$Gs!`J&FyA;|`I0s?WV)9QsnG^R}@*qkmq< zyR*gRama`HwO^F$TI}~xX~%D!|Ct`2bzEWj$KUg4>1AImKKEa#qjF5L4xxWVz^$%- zb>P$Dj;$~6k5c23VDx2lFIs1hnqFU_f9$I}H_Yd8?+oM6XM8Vvhw>hE=EwYyulZ6^ zUv+)?Yk1w@IBp|(9|f*MIY)Ks&Zd|7Egh?i5o-hu5uKqRsJ_^J!KkDVr z`DcTFS^hJ(^7rH^c8w4F-Ve`*pF{IF{$-ViRI{5R_V_{zyH)7y4UwC}!@5PlqXgDpuaw{&s;XlRUCfZ?KY<}I{$DOnEv}H@r z=wANY87Fj~aqL-Voq1k&@3OPHk2~|6GfqfWN#~~U!F|mW%6;qX8~S4Lm0y>f*W>Z- zz1jMz`5$AxeKS1YFu!tFIv?UVUsEpu5y#`*2f}(i?pxV(@HmW%I_jTEzpoT=qwA)x zyNH`4oVA`7)=S@haNh3QVZ9!Aao9i1uW(ZOI^_BGmG@7o>)$=${4j366?a(j;qiyh z@A_)<-Nr(~bv{J{Jgz^CekKHxq@ zKF$N{!JoVD%lvR2A>ZWj+17jOeu4hH^pE@A=lAJs^EcO%YAbP3Z~m1s zKaCIjC2Kt}ZYRaH`n2nm^!dj6-DPtAVtt2L-^CJV^=V&Zew+vPAL`AWp41I-Jl;Jc z`xNu@xG!eY!Q(J4<~Oo&(g#=%9`CM`ana|FO{kBqmN?Xbahp7j0%`A^X#tL(dqO^+ zum2@{{~G$@hkaP;K)tzFk>2Yi&eF^L*84X+?%d?Q&BC*Z4*uNzP4)}shrV=CzNi;* zo}Yfv>cKdRZqOJhUu*z31_bo8|p_7&rfF>VwN=epVk0 zoD+`g1|=WH?c=z&Nt_k8b*`}v{Ucjnu}@YXFwW}x;$}u4d?tKeet^ciyR-Si`B}$D z6T}~@mwB!A%Hr$kFnsx@)QkPnqVeu)5@+>G>7t}xSO@RF;QXDS_k&tGD!u8)Tgb=p z_<83t<*(r|ZqGUNob0GPUxL1H9Cxqu1#y#`(>(v4#996^ztva$TM$1D7=L~GaS!f? zY4^WyT=a!McR!UnP;cyeT(jU-#J1k!>hrr*=7&D>dsq2AB|NU(pS*Xq(3h;+*e}Do z8T*rK$mas5>xiLpfPf-WvSNuWx`Ijs{uX0I?ZJF{j_Px67Grmu!mwX<+Qf?pJ zP`GZWw|REldeC!kx-V1swl>zu4q0EUhd1h;unvz~Tk>JQV1C8*5*@fdRC*2d%gZGn z=7)ToN0Z)Hpgku%Nc{YKo`z#S%#S~Jt*|dzez^X5zHduD%Re56e6evgoV8!l-X^J! zx}I(z>t^Z57mPmLM)FyGP@wlhs&(5i8(;0#xOwS*n66{GK68E1XXLAIn;w_PyH{q@ z%j2xL6IR?!WL)fn@^(qyZexkF>Z|29kf;5eOTy==(Z43;f&GHG{tME#mx#-4pI#5d z^<9|ou^v9}$bY+^g}0X;HyVliWhAaUj6)r`AC}*3r%cxek*~5t;ve>(*Zcd`%a5P` z@O;N+cqFd*wq&V1vM-?x}IzDIG2UJ5X@ ztGo|X!&&PP=gU8}{k7iLC-vp$=!fZV9_KzC?q`qtY#grketEtK`;`f)3MJHPkD?xkm(bY^$&*(aWJ!kH^_)9PWJj~Koz zeH~)GZjWroZ^cqlH(WQmyAPZft z%oX3;x8moX%m3>;DtT`n|Mc)rOz(K6@4RhS9=FwBkk?l+?#Qu8T>goAYnRLV_WUS0 zp2@u-sT1-Q-nP}sxcn3OSQqwHclWW&mYucqxO0}B*nPr^``V8`cG-z1bf33$S4`d--7G8-n}>Up{AL{O%Rs*FCTM$hphEE_}iKdEI-J_S|!y?gI{AIB#+H z{H`S{xmM(oj$3k6b-u)5T-^WjeQ@CNFA1O5)z!V<`~w#(>|Qwckok+NbLY+PK4SUT zpf5OdA?ruJ${XeOh@bQCX1@8$8~uN5^A26OWbT56^A~A+?h0AA_O;1zyyyEL*TMVm zcX0Qii@KL*z5DLW=W#Ob6s*Usn3a`9hb~-j^xP%ObuOQ()$06(iT{QW%llD>EVr(E{{<_)jD5io^C>~}kMo|=SAuW(x4L)D?WQlNpS%3~ z=@%^Tjzg-;Cnxfa?V+qg%(wh|?Yrmgv(Jj}qfff!$a%}ZkG^}wd|zRr*RcY(cwYCy z<=+}VZ~o%Nhb~&&edxl2)jlZhnZ(8IAnS9V39knp_j!rK^K~BghVVM+aeGAKu8?uH z?V#H$%!l>(QSrF7sJ&8+)hsftH_jon(~wR{J{1 zcf|S9Sb)dT~|0G0BJhGV&(sm;2=XG}tehbv!BKt~TFaBp>Q%zL|79 zC2_HFxo-SE=~%t7IIg>UR_2E~G(POpu6;@G-z8tHUbSDIn_<3xNKn??uUnI`VHN9sicN>FUt>K&{&W^0*Q68{+)jIxF}0xgTTmv(|C+;q>xDpS|Av^!Tj$7WRwNTOpjPcjMW~Z#Xi)wvu1#$8>+_t7a#^+Ppab zxQhtz8KlB;66^Z}folxL)r= z;r$$sdpL~4xbE=u_uzWI|C4;Nb+ddKJ}_PHl>8_Wi!WbE=kq!q4eO}Uc=w3J%~W3v zS^52OcH$Nn7`{9%<6?d5G~PWXak0MO{Kfi?5WiL52}{Q<+17)hcO`vq#qD{!;oqNT z$Cq)6Yvq?aC_O*)dHA?Ey-bFd!6?PG^iEp&t(`5u+;i#AWubq)8Q-&G z>A>qV6Z4AVIMJ<_O$XPsC>p>rlcN<7tY#&(pjam7ERX0sEw=g@RthW<^*ADd4vuC-klr?^(Xt|m`k?lS z^yf%%ziHsl$$nF8+$^}5daw@8gZ&#J9mAv}OWYOrELs0s!MEanR==E-z}&=BiBD^; z;TkJHYV5Fbf3v!0@;%k81Mj~r-;~s2=&CJO;&FW`JfA)OXnu}_5DWTCazBUfZEB8zl!oR;*Q^v@C_Td;;WN>Y1}G( z!MOc=Kc~T0pzqBo+#>l+1hq!*s$A7zK#`83gU+-tq z^XpUMHr`9~GNXU}9ddt-b@2K;_#b(mphfHR#P!Mg?Df{e-?v!#d6M72ZE}9#d>h@E z^0`CqZy>IN-}_;#S6TW#X1?X`rTsl)-H6>@_SI>A5G_LMDpRh)Zz{uNBwxgw(>j}H}reM{md|TOL(4p+-|a; zt@AWFx;}&31*}_tjrvj3u~W9VoG!NIhsd~?pF58F_aKRj%@2J+|Ek2V=6Bfa#O>K5Ss%2x`N>m6ZVeBAvd4*Rch0{J{o;;{cb z-)FPEUo^jWxDQ-+I4=6kd06X4<;3)L1NnLhhdy&0cf8CG{Trt7?pTRK|Ni%W^rdGk zUDkcVdB>i0((*5oIJx`mr5Bvoz3kZIPCIdBNX(D(u=Fy{S`Qeq z^`bA+)^T!N-HL?6{F?jF{5Vc)H)ZfIX)Jw09OKwo-KN$T!SlQ`_tDSF?M9(M|kgjnyt zsuN%AdWAUl%k3-sz|=tl`Mn>bOA|j(N9U=@=eQmqj`OhUR(@-oe`6FE^1BSa55|cf_40W4P`3TV+!^VMNlapLi=7LMz2ZwcctE|0_f_;a@`+*ckqH(T7?QOR)t#>M=Gm!(((vMRx?$9~3&Jm&Z{&772tX-esykd3merG4;f%%Qm=eWLb9Jfr? z4c9e~n=f&=4q;p#XYIE$&eA(_?#%W<$9d^|oR7Om>P26AXuP{X;$nTV^l~1!Jwl&b zmX7y^^W!*fK_spoiMvGN&_5sd5Q#(o2J1Ax8etszGD_@*BG#eg0y8%_Gv!qa%*s(o;I*k_+#GmM*Vev=t&%FmB^LMqhnodOCRjAV>V1x4R}AU*{){$o_*ZivfgJa22oE#948H;l_V zaQ}}#ccas*hm~LHl5}5u-0S7_nVFiu%x~p4YUOv+^zuWWu^#!k>E{_ZZ}-*d#kKS@ zKjQdv_sMWvkNZX#hkAJ&#zkCpzjR*^SGz2|uV(r_H_qFAE37y6J~!qo?IZ8=#lGkJ z4jc73;yPmEBXmD-UveKg`cit)I8XhZuny$oe6eo)dHzy)e=_PozS5OR-9|1ctklKh z5!Z1=dVM*r`|ix@Xk^qeN;>M7COUXL>gX%QZTGu~54T6GcOqkc{e6jl#mkcXcs%CE z{8(SaO&a;tE(`Yo$8q;%t6S}=L`UiJLO@E9 z6^RZU@4g=Ph2y#(hjAEp;=s7$1?ES+Q}{^7=nctxyUUj+bw`{doYv3or(qpEl_YQX z%`k3CToPjG=(#4T$HbLMJ%$t=qpt`brxdOT_dVuUx;BYB(3iyJ@rdicXJ+fxBE4EY zni+LWl8(Wv5*;|+JuowMR6;L)qeXY-G%jKV;)${jq(3da)j@ zX40p~$8p?vw*1D459f#H`(>EV;~ov;P{-)PncXgoelYO`bzof17yXOH@p$*GZ08v& zA4<>9^NnTmuU1X`n<>5d>y7*_4bQjC{ymvZZ=aRl!`b+%ho$@H>rvcL9IxW>pvOIx zEiR9X?LTWh7`VZx+g;)OI3IU%_`Imc-5ut`KIq-S$nU}(qkL{g;tChV@wxLO^$tYh z`e%54d@dXpedhXD{WAICq#m*TXW=RzG3xtC>C2SsA2i;5T;g!Pq29(}#&-Gx+4$H$ zOK)etq4$e2F6u=cv2huP_2tjqm&5(yaW{tZ^SGA5cWJVIy01t+t8RUZ)9a@Bf_f1* z^3n8u_By^B)`5Hz#E08e&v%p5i}mgKSdx$XsKi;mOkN(hKhz?A%nx;NzLtNvo6`M5 zz7pXuF2`}VNWJJwgT}j?B@TV@d_Rylk7q~6IPt6b{XART+)&b|T)*1m$$M9@zJni) zTi1qeNuQUMkC89G$d(`HW%kvrarLbdPWA7}Z267dl-|$PkCWb~vhl_0ZQm{HHhS;Q zE00gHZn%F?erQe+{G7jf94&%`0@(JnN4~|>fB+SP+SIgFa zwQq*wy5qupKJF25xZ=K%I+n!oxkZt<6XI}%x5eex_trRE&kkW+-}=tZcZG44Q)#>ML^y7&FNmw$ zkNd)_Zk_d%)s@)da;fX7j&gY!lIG@Nzcbu3@+ zz3J;8#w~3g*H;z#J}S+Z+8UAT%fDsa&_CAaz9xO1?r~`DF6yIy$+#9@{pWG_dl!ae zpSn58_Sft9j?{sAu^t2TUR*z(_z>4p-m8W<=E1(=&)t8+-_z=G|H;o8K9{fB&RF>YNYF7mBMxL)F`elgLH{&mp%pwT~G?Ep?IU%Vm7bNpQiZ{f4@y{p*wJl>ri_Id0ZG`|c!)Y11q`uz2AM`T>g5BYc;`ci*q zlHc%W!g`zckdAw0TKykadE$-_T-$@HI0w1K-Du zacd*#J|nJ4K4G77KCTtHKlDP_XV3TbaKCt5E<7*)hl}LeLe8` z?Gp9{`TD<}^ey(E=X)_5ACI$ijMDdGU|h^EPx~L(FC*tC{Z=sgl=E>rhIM${u&ghx z2OjsUaD6@Qzu~yWZ_>K)Eg9EZH^#3{-@iitI1g*xV4PLA3Cb7i#^c@V!+Je#tFT^= zdqbG7bwSbxWup(!m+DVeZ=Lk{?G?@s;|`9-t&{!R81wRuY;ieXs}Bahoy5iYhB_t* zhkby!%6H=UMwEJR-frW_^?AL>zWQw>?tY2G^#Jv9zLw9m;q>};(&z4nGOo2A#K!F- zeylH#cWZ`y*7V}K;rU*bjj#IMbYGfBC724OvX+?QvIJ3w*K7fr8K-}3j;b@=?A z%2wYV;=}xyuV8#Hl%_+gTg$lqrtw+6jU=FTGtqddiitr z7g=BIQ`B4eL7XrBgwymkU^|F$+ce&75cY+2G%g6A-^d-EX*6oN$~szh8>~t{Ll9lgDow?o*7*{QR@DX7Zj0{yTSZ*gwW~UJ}M(+|iN5 z7al*fPNgr5!I`*gJIDq3!j?EEqhx@{Dd0aIT*MC_yUxx2b ze5rRQ^N8c1-p(IM|J-hg4#edNSF9y`tPgQbIxevKw2%0jk8HEjH?9-%;rUan??A@- zvhQt*%j2iS{ju}~k(X9Z$+Wof7vaVLl)CvFRQ6 zSo4Va5yzjqABFQny%Xd!_Mhk5Uh?5~+T%tf4!0l8pHP2n8^(FQd&4-?!Q=RScs;x> z^FMqq8(-h%;q9B-E*sy_BMBdWe-x*s>A?CTuKuWz-%c_=tQ+!8{xqo%_Ce)mRJR=^ zAJ!N7Sf8b1nD{X+k9TusCvNA@)AjneJIlD}UmuNkMTxU~X*`x*H}r2X636*kJ~IxF z12ArJ)bQnXQZM>~d{yGZ{08WA_gcwk`Nukt594KLT)Zg+`89auNc&+5~jcKSTx@otZ7aVIHX%NORi zaQzP${&mXy(7!f~cY8@3`p5aWO~U8-r|a|Jlj%MqU+q_kUdtEG*TRhvpSoRmtMmo^ zEB-pk$L%X|=pX8c&96@UYJTO}i92D%-CxE1AerkBTA`7w^qH|2Lsd_o=d|4a9e$Gfd(C%?|) zlIu*Cj`FyX-^;`Kc^%t^ap((=v+`pc|J1%Wcihsk{p{wKRfluQ^&a$P@R9U-AZ~Ij zsW1C7S*_;Ytzwzxdb+8-KxBGHR+F~6Qi(zjb2$GvuT&UaS+WYps=;ePS?mBTpHTR1(v zPZ7ubmVf!Sp<};n`DtM)BQsn z^To!UDcp#XALrv1WUB{{v*xcmb7uRr_2+CpV}6{sdo-Kg;x%#Wct>xX-qEKL9h?u} z*Mj{r2{?XE9dUU7MrD`e{v5DB84^rcO4Id859|Lr~$-oAO<8^bt^%j2+55jXUgL@)ZnqdjdySGT3 zwH^!}ki;FkIQ>3VH#Zv}*OBkHEj^QdJUv=S|9)5=@8(S}uH|$8-@`taKedLq{}Fv| z(|9+3dim8hP3{w9oj89xpGoqwbkqo^&hrJ+%Masnp6;M9pT`{%#-ZNk4oM%VaSzSL z$9eRfNB4`ql-_>>&n7G&?^-6;|m>x(td*}wn&Oz+d7BNP8r z9cN50KWl$z`1vHRrK3$aoWI!5`F|QZdZ(v@{p0;{{@a}u=JU8^VI1nsyjp_Mf#hrX1y>6Vhd#8+x>n`do{5yRfRp@hfjO2@5pRK;)d=bZ=yLZh_ z+|C!%_4>Fq8Q1c!{X+V6mp+Q)x+Nd_=i_b??o*H3Cd`NR?f7q^m&fCC9Rr^YKQF}N z-1>3(bqK z7{4Wqn-Z4>TK<(@GJH8z>P24~G~O+hIP`^ev~LdUU|cm4H*j9~d!f*meA!r^-z{~Z z-d;z?5obyq>czOM%c{pP@vGa_vu7u6=Njqj73b~FlX1}(kJ~-G9`sQhcaG$<{42gJ z?)a?=I6eo{&N-ABT4k#Fqmaw&_B$t&EqIhwGY-v^jbRduaNV6 z`0DiQJy;L*J?fN~6}OY(s{Vak`hx!Tao#scoaLWZU;e!P#qjnL>oI2O_(Zn+2L71T z!}5>wMI3+b_Rluo2G&mEs`a>8>cDz*y`OI|8C`1TF3DD7MUOVjCu=e!F5>5uR(F#rzBt2dT8^!u-MqI zyES9nNdJ1*HT*ju-1po^?lzep`rM{C?$Z)y`lsmdaX&LNeAowl>lwb>F5{x!F&gg% zCC=1q&9`UP64#kbKE*%OTVLPMdzaLKdXcZ=K{=0j9U7rH?oP=!Q##5Ur0c-^T7=_1 z;&lyi8Q}TWg#4*2h9fEOuf7m#^mnD{u$Ga=C-6zB2to+&= z#r0|9PC1V{k6ArmYWcXh{eO(RuZs0reZ@GwZpwda^|1H`=)Nz@XO1&dxcV#8=Ml$o zrEJe_j}Tw%d_x^R?(X5Z9(PT)?{naBRy|rz#P!R_?Q!c%?oV-igBkC?xB9PZleqbz z`NE&O8^S(&TxVq6zCAnJOU?uP3g>0<&vEq_D5al|MLv$p_W|TyOuvrJIP3aR=ceiN z664kg7dzjqxI>X~$CS9N&s{OS`dZgRtFMmprA|2X#pieB^zs|JD7l|zP`OWLg5p~9 zlJl_Eq4H+w^OwiFzOW9D`&}4^ebss@ZhlO@FMa*195vUwVm8?fdJp=_uC{UpT&cK9K-ce)%noetv(p{Cr-< zyzHa6)AgC-xDQM(Kg*ZmmWD6QY;lX(LmdC4wEq7UYeqi$NG#|E^9UYZtfK?Kr*qTHBcteb2Y0m-Dc2x$P2P z7~gS!`gypXZPWeZaqe?rU$DM2eci7_I?VM2&O7pT2(ROgY&sg?U+wW?@H!LDqba^n zB39iB+o#t9`6ekp91BfmqsULNnh5Z2*w8%=Ls znsrn93U!Q;4$epImmTH2tnH9KFFXDr>oLCRF00jlb&6}%V}Nit-&mI`XY;uUI<)iN zEy7v(jeaA2KNjoJv6J*!i`xWT{;_19d%gQfz1DT1uIFXlwD+dqI@!85y$?7Kt4~XG z{e$t7^!=^q%OK>(&j%o`5y{t}>p0ji$TtdnQ+%E$eYUQbRnC+9VSN0-`dvphzLxcV z)-AK~)pnNs$M?DU{9cod5Br7hhx2^fX5;Jsr|eVi1J5@n8y}Ce`gDp8rBB^1iGR2r za2&UDw*0EZhkfe#4#>ubI{1Dw?0e?tw z#eXIJg7rWhb&PkVuYdXX$a${i$1>{Q-#Yzz?Q1jEmk7;%W`DJ~Zwl|f zpf7_Tj=R3lN4}uX?1MWvtk>gC592UD9+x{#KCjE4yEA5(@5~wIqeR#D2|Jft`Frv` z<^JQlv(=5qS@Xl~mOejty!(obYwd3oUQFgC_Cb~6xO*g@wO!>rPzQhR4x3&*@c7sB z4TbabxXDOdD~!|n8TD$o*!95T>!-R|IM#3B#!Kmag*r;Rr{g$|`=;~{`)`!SyRSG@*y0rO*A%&)v>Twk>ahxI_daRtZuxG||0`^w{%h3nC^7xmR| zB_H;c=X;0bQ{#RslJ6YJhjGyt&I9`oas83^*D)W~gFkoQ3G2YPJdW>cY5qG|uMs!# z-}Lce__pH1iExTpj97{`44H{v=z9(Nvz$75Xn-2EWzpU0gyy*^-{%Zks{ zeWZUC!#|woKEL|(^27DT^Zg_23)X|jvEGpv()(b7^kO}buly$I3%_rPoosPO6dhVzE5Dw%8NM7IzVDy)x%IN?;Bi)dvAA40 zT?hJ7ip0gnE$^M|zceqE@BhQNgGyYEU-)zP>Wq46prvDAUXmZj;pd+CZ`T#>mnk}k57!~YO+ef!_eboQ zQ7_cDc4PQDgyly`E#=>VO#uH!#y`{IOuNxf4{W9Et z$TvuQ*ax1kmd(H3gW~#N7;su2a31J0>cIKSeSo;mgX8k+r~ItGuK}OBy^O4Hp7_*y zJP@ug`^7&S{LAv6sq59r;rjaFzY51ipLrbCjX&?dJ==R{s)vO8zH~=6z5(LXd>%3Q zSV!&i;kb-*C&c+YTo1o*j`^zRhjCf!F>dg2T>o>G+YM6t>et!&Wqe_{zV4OT_Hzc- zOurAs=l`lOpU0gZt{eJ1d3D_OvQka-V*jnRJn#x@2X2(x51$YI(h;enC!3DJcf?)) z;B;`Fqc1~;$#qv?O*pR4uQ%KW9#;tS zp)Y-F$NAT`bX*zE594CLbZxLpYQL~9tQ+!`K9Ihh;qmUmZ267Q{;5@8cVv2fF+a}3 z(otR~t{zp2Yvos0^5cBm@51l>n68eFuJm=o$8E@Z;C&fgOA{a5rfZA)f34%j%8luL zpy{yu<9x06R^-n~^2O~Xk9Vhqb$Hx)VI1n{`)IcP64dMC?v?HRSG~&lE6?|$+~39e zR*p{k!@VGJSYOZgzKp)SF8%v<(7%DT68}_R{u|B@`8Z!|o_Ai5-Y>}4`Hu8?gt$J! zsr~mdxn00|jL~@KBo6C=abxusk4e|TJlDFG*X7clT-Nk_;{Sv2UF&+ay@iH@deklQA@`{sRR9M z9!Gt3u*6yZ#p)d=e(WpMG3e6kfjIO}d#*P&zsB)K|D7c7V?_TjzvhOC4(tQY$1RaQ zBcI2;GrYf6IDzW6Nb+IbMoFJLLFzyp>fk(32jYe)53DbbcSnTtLp~m7#U0!zyFz!esE>>^z@w_H)XvVn?{7<9UqSCamR)A#>Pe5B>9Pbia5?g)p3%{59`L` z-FqYTo*2fpmr@^`Amd_vV|8da>$tn`l=S(5e62;)XJkbCrA<@MPYw|u`iy++r-iGY znw}qzciYa4f1d9&$%lO~LHW2-B+jZ^^E9eA1)6eQ=;Uy}Oz{u4Tg->J$t_lIo+BUo zgnh-IyY2oTd*1=xMwPXF0|ZPLU9?3&0Edu7?lM(LFmaX;v?-v_tQ05Ck|NSDU3Ak; zTgVrr|M}uP&Pd~P-}9dL zoO|caozcjfF4#_02N}>$)z72z6!o&JJ3r*Z7K(PX4lKKKz2z;kx$``y7kIO{=vP%& z+4;_OrJFZu7hB+rXT|$~w|G;)PnBPKT$Nof3jse>9Zv^%ad_;ES z{msHX()qa`-4KULmq^^Xo@H@RJmkTSb}* zwC>xs;_|u91%CCE|o-QfiLHSWUwnW5}-N#LJL7gdHGr`NdPx?`B@#^|T zJyr4gmx}RXKc{i%;!%DX$@jaoO8lZ9_C#^IG+p4_KM-Gfd`lG8e^okDU1Z~*?`ZLO ziN}59%~IZUNgprfS9*Uo8SnG%tGd|Tuf^|lcl|88Wtw$#enTgSI%D3bU5wbF&eX1j*vaaJ)|G6$>Lz&7Iyg~`L&h&c>}33snszh}94DzR zt?N1Gm)dm^zp^-}UzvXXlSEx)`E4b3x_;v`N*(8QCELRB6ADwNvu+%Tr}gGdB`1sV z>c%0<8|9~KC({}GsdOBF%3J?UK)iGuM?dUL_i=;PUmEaK^V9e#qRy&#kq^!{@ICvx zw|KL}uXH@H9Pk(Dm&S``G#}J1{)}GzwMp#I54+YqUdyh_-H!6Zb~qoe2OiWeFp?jq zX}wT8b{fwwtpoJKlJ5Mn+d=<-(cLc3FE~);19_%{oB7G!DuycBX<~g*SeYXPx_bp5LJJIy&-ZRqlQ* zyLY_hqeJ4C@o)^G4%{lqu?OA8&r6=ji1P`Kj{T3wSiYG>){y4*jtA+;ygST`FB7;{A!L z>nZKa`FKF%wfG(2P3P>n&UI?xz3(kvdR!=xtcxN(jf3jf(c;XH+94jTQ{2zSc+-WQ zr&oWOa_73I{33v-sz2nb(xpp+hwa%1?s>E9#(LBR8mjmqK8-iN6U?6H4L1$cG*3G2T|a{35>8?<9|YHFZv3;H`g1`5o?!Uw4(WE~o>W>J1OuQGT=zQWrYM zi|yHw1LHSzk;3oM1LL2KWs$%?+`Wu|Kz%*c!^e7 zK1RCY;2(#uAii|nVtz-tTCoJ?O>M{Xp|;~XtL?acYCEor+K%g@w&Qhwx~48_JFbh` zj_abfJ87zmtj> zu=J$V_Us)a4_vgA0xi1LsKd^N#Zf4uz)-QGQ z5zxd7Yuf3KLo&Zqm%#PT=Udbc>Cy8P+|M=?pL3#GkHvO)eL4j^WPa)TB(+Ok%jX@G zAGPZOJ9<8dd|1NU`daf1&g;t5FJ0fo`lEJDqxthZkdO5Hn9%^Xvd`_Xm3+QN45g^LeWll98&RPH!ApD=55?SJym|2RerA! z!KSk zwTs@YsHT?KC8yxFy)9jzA{Z!7Sib#M8-!5bd7qj=PB z3i#6FAhu_>h<<6jzFQ&Qn?yTRyogW7d&;l#2)#Ou0S{HY=vQUe0eDhf?iAyty3jau z{mSeT?NFx=Xx8anB0t@HsC4Q1r=nlpBl@MfgxjHB?iTG-{CXjNnh&aT=q?zSKuFbd zB~kCZZKu1=)Ncfy6Gr)2xEi%(&AI(P;+Ox+*J5@f~CC?9|@%GHq8z<9}I4GX3 zet~=R>YyI%q;>GEs0-B(`6PD{zkh++wSgb@jfkhxIdiA;dQL;b*fC=o>PH<`*Dz`7 zgfR_c4m~6?YGPf(s0jx)Ogem2q@j#6)74Lj7jnl#9T*e8x5iv&Kl3#HT>@3c>z1kf zx#zgm<(Fr7uU>xJJH&Cfb7g7ndT&F+w8e`T&Y8Ysabv^r(-zKeSTcXfqQ;pG3mX?L znY*~50pn>HJAT~gG0`ZOder2}6UU97GP$nduyK>djUG3C+~ld;(y|*}H+I~Fh6$q% zshboTHKxu;%!J9K#!aZ3h={OV>3+T{#T$R%==oIJtT6sIs8y>b(^~=tO6?r?QfBYgJ_C){S(QzZusfgpLf$`fb@k{w({HlD^ zKjIump?GcmjF;_aywIcl8*fWL<8}8lUg=|c@kSqZ9uIWuz?#-fnPklQYHJ(DA39+y z|8Gov-I#;19w}Z@lVAK|KF?9jU(k=L?!%Ak=_13!{jAAbKW{D4FV(N)iQ?j*c+q~w zYwu^gUJ0I+j}N`&1KX+UCH|zd&e)!PG%$X%D!-Y5@f&+e5%0(Del1-BTjlkh#g?nmo1{jBqOJho@6yz$GB=OU_}H>c`v(U+a|qj4Z#6<)gp z58JcV-r~h}D!<{ooyRq7&zQIG-NbgP>-N1bDDpeV-7orK*SlXIEHodXSDo`~`CZGM zU!i_GRDRbU7{8^jImb)mh~A^9mvsh)UzdcRm5;&wxc!!nVm}K7KvZbw!#sp9azug5P8c2a)-5$lxlYlZgg zd(loc&%roU`eju7ei#_P(GQ&a5%Oj~iGHar?a-e6DB7uX>G^^m7o_?4*&816Rq0&+ zFGaln75&n9+n_z`741~<>hjB~`28|4eq;Yu=<=KBm+I01?b)xQU4QAqK6K_s$5UOM zBNDvqhy1*RZBp2{tE#^)iC^T+d;{Y*{E@SMmfy`qzcjzC(4K83+R^-4crD)QpyeaQ z`QR4rehaOGXhxySR-#|3OFOh@TZ(p6mqPjVs`%|SFn;47D|GRTeyJ{b@sf3A*?k$= zU!9K&d3aE0s{R)GL=ngK?s2q0d$yfu*I)U?{-TP5tx&|Vv&c`G4{%(6w)lO9GM!cP zu;%p?{5}xpf4cgq{Q6gNzbgI0U?-h#?BT9oE3{|3iFW-JNAMHp@vqQ)1V7c&B?@*@ zU51PC(zF(o3+Y7KR3`Ax3`*Z+5RU9nq90!dTb)n-1?q}Z>7O#q5_xsNM z*Yf+hH^1R8c)ZxYWB4A9-|I&23&Q(fWV+Be5T6Zlzu!WJXSIjVK~lSxF7dt**?n^~ zj&{lS^7!F%Z8Q$*H~6KudQssqIA6th@%|U;H=*m7%!m9hIDd{W0@pQE`~qJ&$BTSf zM*JKf9mg%Z4czM>4u05&A|4&@+r~ow|Ii(e>KA>}xgSwGGmRJ9sdS0Hq*!(s z@fOdAROg*H5$^Y)`L+D^x*y+KUV-Dlmzr^WR#<;i)xE{ndcpgp^%hv>`&0` z`=iW`>KytG`U^D0<3}G7e-*avu=}NW^mys}Z>f+cgpuLl-*KD37sl4^*S0(NGGW`{ zX!jq@{ALF>zu3>?J)-XHSj~EdI0LG9e{_#GFK>WH>(u5Z_cCGI;i&Vj?r}6UOkXl* z?&3M~8)h^e8*iA`IB!wo;)eMPrq7>g{BP{D;oDy-{i3n0J2>)F*y-vbvqN~*=MrS& zc*&#U^GoQsww>|hg+Xf%V)2i8zgkUx&_CrD{lR&>N4)y4-0={X{pwy>NyMXdig=Od^zd4~(6jR$+rM^+<$8F5FZJyF&+FNBDC}rGxBM*5 z$HRN^^D@-AzDv(98={xD^v8O5O`qu5u@#zj>*(=oQ{YkkP^Z2vnP1)N?w8{Ayy?7t zVBv4zj)!)=pK9u|u^wLQXYP13j#4<^myJWrr{_1C_2!q3&n(NwXUdP-MZOTnakjm9 zesz-TU?h{*0a?R zU+{4)0e)CW#G}V)8V91N@GEn>%ghiJYK}bbtLMy7x>a~h}y*gPnC}l6US#< z=SLo_+FKo9JC!cJcSXN=K278B0Y6o|F|ecYA|JNDm|t2i9jL>8qFteNVENtGn||?e z&d+nBxK^e``9M3$kLr?@_{H{YmZ%HWIkW-vkC~z! z)eqNCljkkWt)He~Yx#i}lpp?G6-Ni~kk(6+J3n2&$cN1p@u)754MCT`igr{NUBA>W z3HZ`@=MRiu|3=PrYU#32^h!;$E06S@Z zn?-(9=QOluOGP_fomKn-n<(la=ITss-JID=)Wh6cKxMa z4DhA-EqC{eIvu9Z7l= zSw2d)5_OUJjSxF&K1dy4f1~+L5(v0VLzpHh5Ol_?)kOs;02B&=3B@6 zRRWrLySv*_olCY6^DDbQJ4ozs9i8GOBz9K3r+Pcj)6H+1_?5-cOYGVu*Bb+VQ5TsV z<%jiR#arqvA1UION$xYJe#2KguXAMyo-A*^ZN+$HcGRzI+-Toj#FNF*cC>h$PF1^) z<8;1Z>3py^ov|J5zqFpwj{42B+m6Re=Ox&ljW3L!%5SsE?}UNz+oSS(=)m~(uMq1> z_Pyp!+bi-Bapz~{?Jw?jd368{Re1~Upy1ayFn-%rerLP;wRC|O{8+``*pFL<>QcX> zLYF!2{0jA(Qu#f0VEl&uq=!#Cx1KzlnXFuY*~2y2u^RvV#}) z`st5)_6HR4E^+5)=VRxp8edvfevkL&H*$bN=M%i)VJxaRqB|?}J85A2rd57V85qCy zyC~v4ZD9PSRDMtQ=C@;vqF&DQhNoLEExRi8J8NM4vLOn;XAg|uW|iM_2F7oX%I~=Y zh4a1nO_TF2+4*W<53V1^C$ozlb%~zQ&-FKk zx=cy;p@UPj`$!&@BjLq)%`I8tAVcCm{j>&j&QQldE? z$gVH=7Hi&5Nc_si=V(xjL*_Rzh1Wej4$?Yp2Ru4&qIMm3>fvF3QLUo~%6J?qe)V9d z;uriz)J1lEL6=`jlV50>^Y}vb%WB4f{8YNc%6Yt07i`a-TSvIQPw!K(?5fsxwWD#+ z@t|pi^LT*xsyIq36mitJ^Fu%EP;)wT6R<2?WoSZuQ}J1g*VC@9=4
^;h7T(zUwuX^`O z>TDc0VW~&i80qhAx4C!foP73;g1ODgLGqs9-{=9sSjgX!n z3iV9?T~9B1sDJr%cJ=QkqaJlEoFnRafscfot?TvYn#V1i2_dI#-lneRRaWW6-9CQD zJWcg*(lPgae?6OL`On)x&yl_S+okq(l+MROJttV)BYA($^dAPh?qWHio;7eOJ^MZ? z7PrFnA;mTHa?k5g>jKjA6QQ2vNA&cvhxzN-5SCBrI+o>w>Zx=Kt7p4P?M%OXX7%&u zdZHe!D&#~xLU_a0BhFb^%bzo??!$g2jC=hIyFNh>X}_cZ$G&Y zongzDd%ypa>uDRmw|+?VXkOvCqjRA??x-B;uV-u2f82rcY2%EXK%B9VoarC@-*6@s z=OQ6FCkDl7S$9!X>%rC+&d>ApVCAFy^&IqiuqTA|ov*LsKI#wb#DLc)KPlwwuyxej z2OsR{y;T0;bBlT;ZI_-Aa+V5uoVm|A62kA9^7RJ%dW3YJ7jljqqjPc}>A_~zcQ@d3 z3q2<`)vq5W&MRl>reN=XmN(PWYcp=n;RyRn(sjT86zVy4tga{bIcG+=E=YRc@Ks^E z#J`Wgea<;9{5}GIznm%VuL(I5$Lo5wj?;b48F@lh-);A0knYRExEFt@b8#Q(!A=O{ z&fnW+()0C@dUAci2U`<BFZ@X7 z`!iu}yJ*OUM~JQP;D<$^rObtHQWTukRgU-19}9 zll$OgoFBfY-eN2X`&UK!^nAvrmBpHKaf5pvqru^`rw7(D(9;U^&FW_=UqCT_)?6U z^A&ca`$T*@{GfV%7E({HFY=e#pn4_)>IsgpdZK)Slb0XUc+=^3B@rst&A=;=9B$2#iC#dIE|+g4m-zaT#NSa*SZYHB@8VbXgY zV0>rV9+Y!U;CnA7?2bBgyjsZr^;|6A!kGBSi6&Sgb!|RTZXt}KdGLH7{&eT0Xgfx zCeHlX{&5#`E~mH4{Q6!~>n@_gcAl@hh$&v^!>xGTg=L)p^!!FZJ;4)J&#>h)CFG2j zDbDG4$&UWUKkf}xu5e!5O3NpX`({8+90zXr+>S2d-F{*}DQ9F+N@vr6oVnkUj^j#S zhPR)wrD@#ysj&Zqv@=fruvB;<7dz__@N1eJ}w zDGRehfxFz%Uih_`Ctl*V1knGVPa*}`)2dL*6y+)v0ksdSw9Bk2hr+}w^E z=E1O^H161cDBh)i>9&we8 zrngkj_8Rn@-Ooen*<{?{gSC}U%qMd_P4me+Qu(ybd-L{~`{0vWsh))t)%Vjw>KVU8 zF9)2@Rz9Vi*-eP^S3=Gxd#_Q$!r9th_MDWoo!_}vkL>gFg^zXpxX<;h8~RK9`fh8N z#;+wk&km_)>@uC3a}G++jym660_qu6>jCQ)PLrNEA8Gl_uTOdwgnD*v)35KNm;37( zvApjBoVM}_J$DVLC-exbCoiAU^`Gww*W1jr{*$c-1wZVVa9yRX9!;ut>9@kT^L8nB zrGMO|^@v|DO#S&$VcdEDo%_%c*3_Tpakp`%)VSclpqzgu9cya*0WNM$oY)Wb$QJje zihDU^+_Sa+o47;I?*-LU2@+OM9(S9b&W6-}{!pkVAIDWy{1HcPrQX}jN zz0=oHyy0^`_+yKc4)D1}`IN3x{g1Hy)>te!#3XKEwT^F*PZ{JTu08~o!g z{Z5lD?kN@b^Mss;d-^1rPaYZf=ak0X##v62o)-u?3zzHVvu)ul3(KdCv#IVMog(DK z{Uemmu^avMl-@tGaU#E`h3^x{?Wo@;kM5xRNDnr8jQ4yU>JjFbr0W&ea_hU~J2)SxcB<`_+LoJ%Hs5U z-#?quM?U$F$RGKHEY1tIsMgOT?$UPY$3i_DiZfOxUiiqL+r(CM9pT&I2jv_Qa`N@b z+(-VfBLiBeiu6tua&rB+kMv+odZK(v^(@>$arsF=&e7W`?sXM^aB*wm#C}0J#{zO9 zpRk+iCC?*7?;stKo~d2H?=}lgK2K}nJVwYl&N$nv>GR7rF8;eT z?l|sPVcc_nB|QtvQ~L=Y>2RBzKA3i?snR(ujGu$sfk0_c>?$1R1Bae9jq?lXG*%kn_h~}TuHUadXbX ziL$s$ubcCR3bj-7IMZP(e>m$=bRMkDUEwf$XRUY_hA~0n{(z*@sE3N zxZ@rqU6;N{ciiF3SH$~Rcz*Et_aC{B{kX-t^kP|Gzm0L6^gH!0_7b+QQ;j{Q$DR9} zFMra2#+!FjTuv8`H*>2{yEOU_;;l1o&KcXk37)W=7#D+6T94in zt_$MteT+V?mjm#_7NqNfEbnJPdKU`ybS~7#TaAuCXF|RA1Np#0&$-B>*xrtm$=i>g9tVDkz?zZoD)b66|#YF-2%j zncnyLls{+s{K2%JC?{tN%V$+_O+HP0@R1I;liLV6E$vd}ZA#~EVcdDUlu^8#4}SUI z{?Err>k-oXbwE9FTv$EPeo8sh+mfEY3CKC|EXBR@jDPu*#@+V*kjeF^{cH;39(iBC z9;Fp8^yRkm>0sgxJ<9?01W#B!5qCG+Ud~7l)-*rgZI&eKm&(uSapwNmpX2I_#45)Q zeWAE?Gxd*?_jvb{ZP(4>0u=Xqg>fHe&z+^(IydxyZSEyo|7q)gCN?0>N2Hva>0BKP zr}+7IOZ$oQzCu_&bL-IeKt`7&TY6sSMtZRAg0P*p^h1!|?}eNr|0J&R-qc@$k94@r zZ71WjwM)$D_m{2rww2GCI^S~w>Y03zbRB!aKkiaJrJUym zK7YZ-9b+$2`ME|I_mP+NxVMz9;O4geV`1Da^*wzoab7Ld6ZJjz z8pXT#l7HN#_1#vFO8ZegdQzxohrQ1#@v=W>$MT(J#NAdt6NeG!GeXYf4mwxU!WqAR zFmcCt^K~I7?uOxR8^-hbL~CXBhN#^H0Kh1U<*qd`;N-5a=!~ zpQX1+&o_m7R-V_}rTnY@agUrbnDU8s=^CM)XqTWz*mfysJD+@o+RvMWdbU|RUsvrY zxVarURi>xydQ?@MHw!sO|E-UYMql@j``Caui}TaG^esZpu~+o+8MVAWxh3SZweyJ6 zdcyLFb<<7td`H;#JR{%U{Acf-iP%EcG>+TC{W;~tt?xO>y{X5U`+9D65AD+EqbXj^q)PUgw)sP9tyW+(-|$^GD(M-O^t|de;f#USnL`M|!Ze<7DFw+qf9% zT_2Kj{1g5DG17z088~_SY2!?&^+h)X4(BW>%)_<^w`b%rj)( zA-<}Gvtqd45tj48fSkxDEGOcQ^`DqeN4lnV=@FMxGQTvbbVPdG$9Abj+->&}klw>W zJ^6WaAL;e&fZhv-^fnQ4^7mwieZM#24n3vU%}0ft6YBlro&Qihf{*j%HY;4uV2eBM zAN@_p$>SXM{?SZ&TCPX9-*KCe6XTA|Z>jxEDP6ga@CS9@5a~T8^+=M^*HBs#$2KN-dEXTTqE!L_dnBz`Tq{i@fY=Rhl%qE#o0A}oW&2>c{3m70oKMT ztw&k)9^JffT+H9Ul=w*J1|O{SJv`Fu`}@M@r1<+o3PjC*n(y`AAc(u1v(yvOe-pS^6|ou%tkpK%Y6tW%9C9l^nUZ08p1 zR4b<&?!OE5{4`+P!4Wp@(9_h;SARw4(^^|UujhIJ7_wfEMjeWKbcif`aC2+Z8=U;Q zY2s`PIl%{>&&w&j9yL@s|4)z8-hQIq=%^ty?~s^CoCt*XLp{~ z@tCJIeQ!7G?p}0gPSdX+68VbWE^#0HQVTt8<6@-u0@JfPi_U}nYK)Wn*bla2S?3Q< zTR$YG-eXo2_Lq1+B>PqG^8u&rJ!Yuy{5|BR`hKvg@7?(`zqmVGXYK<~+0+O6{So$a z?>+L}^2y_3ny-7&<&@0V@$$fZ&SCSVaYs5YvGR%S+-7E_I8Q1IpYI31x#nQT#Ypev zfSfokEGOC}sh+JLQ-9`_fSlwN zNQc|nhq8XMw4HxV$eFxSzhBIK&RI0PFFmZDlR{3eANM(@Nzb61V+T>Y@j*b&;tdq{ zj*36$gKy%*@2Ky#byn3es_$uE z4?9hddyCCGfDd*=U6nWR!F&boa!6s||dSd+ET2@atKTPW}$CO2S2lxK4f0wP!IJuAXU{j~)^ZD2gi+YruTc+o_ zLOn|j{k%sP)P3X+TmG}Zp5T;THw|BR$w?b+DW(2{~&qoioCG@WGB=I#|w?LvnI%@WGaZoYL#&Dnice zBBbZ!5!4TZ4=!%Ym&^2&a;_%itS+j@-Qhk19j|)dFUD?Ym!zDlhvb}z8vx4Y)c2;@ z=Dr)0Gb!Zc{iDocOy52M{gJWsm$3e`eTLqjH_a!n?T+Il^U0Hnt9T}*3!mYM-JtKE zKfE{I97@^V7sTIh4Zot^KVMPrxexsQdCNLLocL10@q2m+J*jymxG zr4tXyIl;KW2b;f7#wo4uOA9$uOX+%+m(+dm!KNM@Eax&IIXO4@VA})YEIvf%yKG3# z4$~KWur@u>E}=f+I8(cHw6I;m`{wZ;diY2`s14fAFDKMrevYgj**N1rqVt^=l5=bsUEi>rwstA`AaO1)pR!eR^O5CalL+>{k{zU4hHv;9<20x6Sn(YNN+)*p79l^9cm~GAL($LxWd1_qaH~) z7YfJ;p0J!j<+yBftC@2fS)%eSY;_p}r5WfHr8{e;zRIzzG|7 zT#th4xkOMs6)4wp^1obcRv{<xwdHT^kL-}8SD51&uYu0+=}(>njtdwR}qoll-nT#;YWI0-)VLq3TWDZj}T z{I8=ZpVIrV^9bY4zbjH+%U{o$@H->Y?>Njafvw%B{zO!a*s zAt(QCLx+9OgL5>6?>(q~qK~&toU5^Z$mEsY@hq)F+eg+V3!n4B&pjrq?^4dy8E3}A z368LwxV|Iqwsr~meQmbxU-o&1w$c&DaUa`ZTMgNI@5xVPaZfTmkq@_H>ruRuBV^(8 z{optLA&a||bB%zU;0Vjf<1U>KSyRZ_QaUC!AU)xOo7+fBrl<5d=n-MN)Kq-nDXvev z@VQN0;6Ls_J(B9VRzN+$6IM?icd4H1ht!kn3x3#{t=jS&N>Y3kI=ZY&{=*Mkqz)>te(96l z;+@^pKkm}i}MREChKs_7tsQFJ;4!{R1EuYeMelww-`DuFlQBLdS6@0LrB?sG2P7C$q{kX9G zWL`e`d-hE8idzWv9NAjeucP|)(2v{tzhw2@7Wc>!6qhXn>X}MX{7YNu+?-Q7?vUy^ zJ*1voU(Q)tT2?-#?dK*!J=-eo$!$qT_?!=ZL$xRHxy86cdY>yT)HAYxUf;*I@sE4$ zU0L~*>bYq^J)uijJ$Zf4eN8ql-b$!vbs=5PmWn^PxlJrLnDSYAn&Pr~NIh$;9B@uk z`Q&;=*?US&?dLW^JrmpO<&pcGb9{N3o>Is$$iclPxy1r**(C0pH(}nmrv6= zmhD|m$-1@Te!8B8jP7$zn~!$Mc0G!2M&j>dNK zkNcp$HvwHP4akY(#_kKp$@QFU>FJo-&wYjMd~07ly(II&51X3Dd%liy+P>4&RL^%@ zBCPKt8|cqjMt9McmCsyE3uc}K9^qh zUboU7qV{Q0SpZ>u9Z%QP&hPJXO4|88|L$}ieIFSIv}iwV?L3m*URXXOyXiV}AL+r? zR`kDaN;zXIQ#v~Y%oO^UR1@#?#;Q73qs7KPc|3TQV$>T#xn&$O#^B!{;{hsdqiXenIuzJ0xdVJ$c-1{bXle>L*++>?fCA(${;BXEb`^6h|}$Oqi;xs6Qok2~hU__yqz5~y#x?M{4a&KbkhAa|owLcfIY(*0oI8i)4if5_|E{hl_rV97Sl+)~ z3R;h{LeAKz&dGi7!Dd&H#a-Gi9W3OmGfwV<54JKOJ&Wpm_YiU-f7sCjb$ziNc2Moo zq~hE&Bxm${{+uacyJU-d`$Ot)?-i1B+`^gpK-QnPagMD<<@{Sh&d6N)dt`G5`RiF0 zepg-EE^RM-elv2g&c%I{%f4Mu_MB8~T{bU$4}CwZsw~nwM5t$tadIE&!NyjQwV!n% z=b=K*>>;|I+y@_QH6i1S9-zP&V4OkwAx8?!=ftgg`@wyFe(m?Y+a-*Pd(&_3LDKI%GFrt3LU)7ukp!A@-BuO~Qd{duIfx$t^aK3uPt z+(&w_?ic3t)-$6xN0mjQrnsBx(bX=eq#p6>2KTFTd2==tU)zh* zqg^s_UL)j0{Vp9zafc6mQgeHA2CeTV&TEC7(64p0YTwy?^Ok{gPUP@2#gP?&!};?{AI@?;G;6uwr9|!f5QvIX;c$@W?CIjk;dBp~s zzc6tg4Jnfy-E?MVkCm0v^ z!N)D;Y59FC=o$S$7Wa3B^NN)P^mZt@nC^4F{13h7KY97I#l7_-s*fiLT zHRd08)Ab1FgSf+oHMR41v+EJ|pUJB0Pxd6m$F4_(CB55E)AhZ_8K7TxkB}4NjB%{< zXPnigyg5z%x}cnmfSje%NKbG>_f~u`oTlsMy)I{vaq;Mnh?9>uBg=Smn#LVL%jbPU zJ<;Fnp#HG9k1XrW8MJ(w^t?Zyp6#D{>pA*0Z_YvK`9MHD$A0Er-<{>WIeqm+;hthm zdOk>ciu-j{)eq(Eb8>laPE)_mR6b3d4+Z2bo=$pl&Ya;r*@NPII3Q=@3~$a-BAA{S zckp#Vrt48tSU#~%Gr0#{*WsgR)z$mQ;oGb!?k3K^2|3X&wSMkhk0#W6**Ra(dSv4K zdqB>3$(u92ig(-x#ra4;&W3?=JPc=me#oOjPF&ANR67qJaqg_@t>>WnA&&**jQx`0 z&N*YN|93h65sPkHLQb?x`7^!idvr~2JqK0a zp9sh~{wr_J)LOwfG2Z0Y3qH?~P~R&V?_C(|^9;4O^!FY(6U?6yyY8R4V=MdX z3q27Zq+_x_6zW-3oJi;M>M5;974;tGy09Mc_uHiY<6n;w+xyp}pzA+>)YEguI#uY! z?c{G&d!&BgetQZ3IP>&^a-JaMto%;rDrqHE2DO zmQQ?#@uVK7y`AUfGwgR5+pExhI&kvw5x*Yg)%PM#7II>pZ|WS1fB6r3Ie^Ttrggvg zJt*fX0XdORSWa9wc{`teit3@Me4Z&RpB<%R@fx~r!Us3QaW((?A5_m%g?d(( zrRQZv{z&mIo$DX>+~%_T9n$jolYpGiFDxhG?yfuZ{0_LOzcl7@O4b3km5%KvDemyW zonrH}^)vMKv)B)om(Pk}{uKM4*3;8TbuXWO>uJX-6zAl5WZ_3{qH>6Q@=N=dOXO>6 z=kYtYKV_UP#liOjAGUv9PV|#`x~91QOc;00&wcPq?ZRqDTRlR07YgqmrLNZNH}{bq z?8sjF`Vf5AEWamhho1a9@+Ljca5*LQDDfwqll$P4TC|^h9+h7=OX~TxhOqxxd7j?O z(YTO!n~aN{$PW995+dOftszf(Og zH_0~s=3VdOhtvLud;SJ}+-Qn>Nf`II(h<6FAKRriXx#4&7iJ$;Kc9T z2EA@x-fKVY!S;o9esi z{$|^adywaPnuhy^xK2Gs<_He5hr}4AJl>q-x|! z$@QtfW#XJ5&i;Gy!NqO+TAd$0<{6L=jvGCd;_kCv(Q}^G#QBbpbL={ull$Q7+v>Dl zWb1i)PQS3H{(c7Bhvnm=>aWyu{cG#{KilhA54n@j{`0iS>vc}<_xaQxvCsVPf1)0B zR?*kDo9g@hy>#v4qZZ@jKIcsA>b-s*`+<{}bIv(-5S5<~dwSYACnCC@ojG(L`NP&e z^yWl;2PYr5a!#c8mXMRbUy=Jr57zX4MR4-_2rab^#x$>ZRwexJS|yhl+a7Ov%x|^YptO=TM5zdxHlye>25Bb_-ef_#OFl?xOti z)5+p@ZcTAFasFP&2|nca-{Kq}CLJUD>er)lgq(GyBRD5+*ZYm_hSG0qvZGu1>v{1) zYdh<>iPd&pvUh!jePCgC`w8y7(KX_|?Xbl~)^-+f2LRov-IGsnoYJ+2T-CLe-gdV? z^B3}Ao9^~*`h}a8>ZJqQUTke=L3exNR@xudS)8_iMWtW7TBZM&Bb^1@eDcQ~+RG2N zuC`~6-nF+Kw(V}uxM_eh{T7{{bK8-j8}g5sfU?jcI2R;K-7okO}mcelISP#(~JzUFT4#&L9< z$}8-5j$PAj$7Zy*#Txw{KW-QS|l zGEVnCiQjs~k$ZJc?sxMD@-Jxl+|Err?yO*qdz*1`KL}%YU&P(^{1MWv3g?&bz1_O{ z&TiQ6*dpIP=STW@&{RHW6TUyWv#>r-ncqtHkw0weeA#@RP0x&a4&|<1uioAd;p_Zc z_v_^qe6ZzzdvoG<=xO_oSnYXArz+&+-`g!d;LiyjlLe=3{ug5E#+z-{NJuD5BZ`$zE?b-i%^ zXhhwg;r-jm+q~y#OzUlMUmNM+q)hjG}~f z=nkHC!M`5@J$YPAdVUg8Pp&Wcq!xPexR|b+pSqlq@n-Z9D!2JKwWFhd_b$hMPT~D` ze!eEo&jNCS1KjXuvKCH$|0uTswQJ4OX}-I9hCc5dbH6v?&W7~Y&!?aC)@fYnnR}Fe zhmZT($fu$1qt`d`ZclTE(tV|%oQn{r^?nDqpc{N}PAWa5oG73CdSQzD{5?*4f2p(p z8^M?eUsz3Po zMvkO<-eLPM(TltNeF9a+$$jMCw`~9ZcJ&81`TCH8y02Lq(&wiR=pAQYAChV5dUBt0 zq||#H_;&ccxDUabVNK<8I>o&|Ki}RY7)OWPQIL@SJoau@Exy5xV^)&Iq=le9x#d&3-g{iS{!^{ZxWVIt}pkIkJJX$^J@Y11PAnm&uydXzwS5ay7Zfc z>!`<`qd2!z+~IRR_*ujAGWb2Hp38;QGi>=pKRKwLw*=G^dW6*z>- zSdWU&>-C%a$cNj+KlS7AyUQ63ay|Nskdx=fedI5-LF0a#Fz!vIOW_652fm4`YNUoDy&xV>`&c8%)hi~F)4mj?A4af zd5{qD8GVI*hmU?8@+p)kztpMpeheJ%{BpK#58g>-F%K4u^B&^dADsPk*&pD-X87Q2 z{gU{Moa(?CoJfgm{w#kzpQO0==a=-OXL!*L=~#P>Ec`z2uau7Okc}vRMhf&-Md^w1 zDSdCuy~6T2t~i@>QGXsj=YT(Xt=_N0`QUeqH~Dtc_5D7VbL#ygq{A)BZA9q_pYJF2 zG2WDN-Y?_?A2>cQC!bHYmCvUr?kQV6LU{xyeCSaLSUx!?(v7Kh3G;l|{&bJiJ`a|C zo$3#cgAZP8ms-p(l^^$>&*JI)UOiA}o2PZ&&^bFTS^7Lb_(ALYLlk%GI>4&pOsq!p z^ze}{w<+uONI#-^HnnFHYW}mXEcSYa;@-b6gYDdA-XuLsvyqPQQ9hB+h|16T4du(z zadxNcQP6SRaY8*)-`C?jaft47p2V@<-)X`)E-2@+!u2-obxF_iEW}rNOE0gSv;C?! zC-&p@y^|vSTk1YsGqwqFh2>1E=i^M*&8>T!^VNT@^wiIC zhF6{-9aHa+g%8f$5yV+jyb}w1>sdG4-?VXVL!2qw_n^TAa`<66=R-ouMh>O(GOhpI zw#PZIRnLynvGgy}6FzwR`Mg2-HNWqzXZ-tAK7(>@N1RqY!37!MgR=rXgq*l;^7~vS zJu}4VjJW{a`VJ0mN8TkJTOZK6Z}@ya`02xFfB4+;b}8`#(%&@iy+e<4{(ieuxX!!2 zw-x93P4qi_l+W=36;-tD}Nb7!HR;DVm;!*Ze?m3PtaZ<_i`yYx8i z_q9vAsr5kLCJP_jEu|;?&aQg?*bd9fXTIpIKlb0X$7z2*ZQ^~s{=$cz$S1One}2ff z`^;02f4dQ9zn>h78p`K8v^}>U>BPs~krQQnVB>m@oJ7Z);-00r_xs6>4|Ls-ZefzP z$JOufp(paGDBh;Z7sta^4D|@dn>cqTPHVdaF60LvoY4u=L&}MH2Bd>@P5q@kTu#Y6 z1J{}R$VY0yiT)vuGjZ-IjH&d% z10QimKKMOCv>b)_0yPU($yw>MCaNgjU$-kY|_i=h}Ork{NoRqRSp4WHVxMLre z(_H{ztw$(F6Kb3UA9^O$ct|?#!1ajt>rCqab3M*!)_z^|6TQ9SK6HY$U61%s3*&f20hzMfV1Tx9$WeZD>Ssje^bht2&= zUw4M>uu{(WJ5(Rv9_}7#Uw47^-pD8NnLlTIZ}0V=I3Ap~=TM4Eke+i3^^9Gm>shmK z#(pEy6Yu8*KQEt+cS+BG3H2P=UVk1o>v;E9kYDQ_8K+H8=S)gxk&t>iL;jpnJ^6Y< zu4nQ;r007=Jqxevaj#l9o2Ly%&xF!*(U5v(h6kgk?fH(0g{U5VAk=f@VqMQk3uh`P ztM9gT>FG6za~YwYt&(1kDqr!}Gkc#b?l#WGRg}(3LQeiZf%I4XIc@I~K>KOqtg81C zEGOjb9Ifj)Vc{ITcQAUQom(#8yf=;uJMTTy{Jfdk1U*N z#W@_3v-3GQc|RHVbxh;UXX*ZtwV#apMTk3m+&>!qHTCBQeg9}=gyO!MP|pf`-^ED8 zKkl~oUG%!W?nz6Z?|9DDQ}P^2n{ja;I&+KrzRivF`$5unDYHK5xrR{B6l<5pX7|@K z)9`PXFh1h^#ey}#Z`+8dH`~aR>B7eZ+B1b-%EFrmp8dm7ccy@5MQFJ-Ls3U?)!XAD8s?d|6MI_dhGoQUCKE z;dm3@6#_?6-S>dct?9c$xE=*vC-72FPy0BIuLI&f=QOPg!umSi&f|E~`jA(I^{6nn z9v}E<=aG-pBJR1D^mKXLkzPvpJZyC{y}ZTe(bGqIu-OZ#T*2oSoVIaX;wgHr;TyuZ zXExV4C#LH@=g2+j{oDk~Cpc~WPo%rKP|y4{T|e$4J=ok*bRB`uE#_&P?EZvlp7z`B zJeXuYnUA+j_Zv8m$q#yc-=xCvM3P*`pryzoVsoFttnH z>2ccI`P}@(nOcnOIO9hCeLL)5kHBf02Sa)XFwWLex^CDHoF*UJVbhz*<{3Ia*T=CY zJ+~CLOOXY1e(r-0w!W-PPg^@*dYand&4lfIduwXfi`$W{F>dg|Hq>+eD6{84XLN?(!1y}h8Gj;VZZ zEi9kag>-)I<9uK<%lUKSx|uym?0{% zK9v}8l@=#EY2l1-DJ!2+&O;byb7^m#z=`wVKDNV_XYr4FP(2T2oCzT(*RxpB>yb@Q zluw71dsF#5Mp!<1du3`Dpr_43PrlB?RNuD~*7x$FdU@bJ=Sr+3i@UV_JdDMi=La9x z_vn_?-tm4&?L0m1j<6phC4ndE)JS`h1;J+RjVs`w>D;)bF&qUh#U=W}LQq zgz_onJW|M6yo%cS$@Azw5`2`4!k=_KTi@|7pS(X`y?~B4eaGPkJ16X$Pa#4PPCt>mq^#teje>|O0Ms` zpPw}J`;ni`f)nis_BU}BLUM9$D|tcR6k!kKY1OkSLgY{FZMWR%rC{3^Nwf! zYx;KhXy=j7=q29QA>;>(xFa2GH^u!#Vca=C_mPj(q8}pdC!f^Q(>@PYXF7AA^Od*r zAICvY-d{55d3ION_r+uwJ4uF?xu0vslxJ^OHkZ1tB{3n;u??m_mhKi{#wWx zSy3;a+~>Tdxd+QRCgiL!PVRHg=8pdLJ*b|)5prf%()Hv%=SJMh|+51mT?dR`=oaNQ^@>y9`_c>>z?!PVw^%C<~wS!B5O3(^JY> z3djkLu$;Vn+SYp`zuyZvdEB{=^kB!P%k;Ee-y`aIgsp`4<3_)s-#;mBrTgH6?YueI zbr;(SIU~Cf*Vru7@9ZS~>rr(Dp`Mm?YsCdC>*U{7CKJxEd%l9V0 z$=7dj&g3mres&jfb}rQQOsuPO_xaQxtx=htw)$S$fZE}8g`DZF^>KF7!kNF@zkJT# zdpjUMJNH{m>U*nY_TAOvT+X<&QvbQ#_=vYoh4u99)fM#iwE4Vj{tIN7XW;3Y<{5tI za!T%ZaDMJ1f2pOXj~$1fuZi;{mvhM3t3SUqa=We*@@+7kNA}mt0rrzx)FZw=gx4da zcdoEsSKmO7dwzZ0M|!a7t^NBUh zUz``LseGRAa!T4Il%t8?sQS~<>rt6;BHxB;uiLEM4$AqbfSltSd2=Q&)AbxQ=LG>d za~peemag}{|6|gV-{-Qu&+5Wn`JC}StLC+OJfRET6E*g4)t^`Ix5E9ShSD?a`>bs5 zU%H5KmhbT9#QT<7>U~l0!I`_9;x2tp6xt(BriC=P^H*YpU}|d7lr`P44V} zJqpTM6>@fN)35v72On%?(tCV__7j}^J&C64`(LD-o9p^zzN!1*gH0VgSUoQla^~LC z_2fSIV9SQ@nQ}d)m@6s!MzKJ|xfyctx_+k|>{7#H_Br>$KIT0ZOD@+nv+!0*2gs(ecO^H&S? z9GOn#b1Y33KGzX`VMkfJWV_$dS(Vb+TeyxovV}e_Y%6YXaXWga|9l9_r&P~t0_q8# zuzI5X1gC8t4Ea@if7ts=$u0GEiTg+ow*IZb#C>EnN@pKo+}oGy*Y_6V1|Mv67w`TO zeutjY`v{Z07xUTmtVMOs!jig={QLGCZ#{Y3qa%7crt8u7g?c8o*5l6oKA-xdzM||o zXj^?py2lEyM@`1beWV9lo!whc{EoP{cF@}qlb**5IVbng(<^MF>x=whCt9-dDV?wT zgRos{Y^!s{nGZhL)RrzUt9_rV8S zKGdJnowtc}zjwy}ndX<4aCemSlVgmN`#e7K$l<#Y_YY}z4p5Jz{p34B>dE!x zoVCSe_cx{O(i1|?!ngG}Cvv*aIkQK5$DOzH((&e#LeAWd#Fe~>+NbCa{+!Wcyg6|` zy?I5C@@c9^SGd=sh%;@ddz|0<=c6wY*JxI8Dj)gQX7`>~tgG+ZxvA_v zth8Nf1l3ak_4Va|%9rXXjr+YJIm5;s?NV=9ipM#c?iVlZ?mP83!)zr9COmV?QAapX(^~P1hsScZHU76V5oR^u{iJ{m+rT^zz7kDIfOx z|Jpkbz&463?ypTkoB%7pEnlEepu6Gt;Gh;BkN-PC+DJM&jO&pX<;vUA^;?<{bh-e@)R+y9%Hot>Rs zK~K7V-lpe&n0hu$Q}aNvnToeaxKTdWqP=tb`InjXv*~bCPwG>?=*hhH&TU7pRLGf~ zW6tAH&bCS3oU|R$=dIb|{;G^S<2pk75lYX{9qM>Q+bQMr^AUG?T(h0WMVaII^pR%V zsZY6LNAbqp{I@7N#cNympa&NZ0py<@AZc%z(x&pbopv%KRG zSI_of1-;;7omEiIQorQ0PN3tTs{Z_q*)PS2ZKBSqrSrIMUoqa+k2mWl^^J`g z4vt5e4b1Vp?WC?{#<(wao z6CB`%Pi@`vy#AA`=Q|a0R;nlZrJ#BinVfi@P5l7Xj}&zLsgCdyr}6aUjzhjSyceiZ^+h$xZoe^%L81IlF$ZI6q}_(m2O%H0uG% zhxLm)mlJya%;bcg;HXqj)K4yFDysDSg2_pr_nG*6`MAgP<&T>s&Y#VE=y<;QW;Na( z%)D;cv5I-V724bMp)+h$=MNt?sGf%LxYK-|74^Xf8#~^6-9@EwcbMm!h&wncjeAhe z=x(aLe_NrR^||u>Cs$AIdE8~p`_4MgH0vkzp)+h<#5?ZzyworGTrbAn$y3nVi%|eq8IW4-p%4e_wl?*p{pT~vFo z3fM0d&sDtj+S)++>Uads>VTZ!s+1G`C*n@8$Jye(l;Gs7SHyZ>aQ1fHFE{QeZva!z zx+WFxc5UG!A8Om5VUFvV{pY}doZzXH6LIJ28K158cjGRF@4}MrbJyAb% zN15YTTm3vqWX$R3Yc(G@sE>564XWp$fO>+XQayvl9p%+9IaAYAoFf-13m^GV+otOk zO^46b6Wb3C$cgV&${AG8@Ep~Sh6Lnnyh!QUrga53wSA>0IF|{?37$$hgX$UiRgJS& zXL8c>_we-c{Sx>5J++0|FVXXN=<;v(jsN|ydBR0~NI1!(< znVhMa<~#%SksoY}&pg8l?h0OPy~x_`=bG-GZ>|{iJ3p$q)QofI=H_{6VzfFxs@*`@ zuJy~GFL94Y?H{T3xK2Pl^OICR(n`1&DWcxl^u%^t&e|1KI~va9q}R0)mznyad|1Eh zhFnhMw>guu$L}3oUY;{vR63v>YBBySTx<68w(;ksVjT--{Fx7Lss|i9VU0fHs1ZZ?K#gb zr+aMxgv#31GrS`>gFH{5?n1>$@4IyBy*X{q6IezrI~APSU(Nls>3KJ^enzi0^P|40 ziodst-h?~vJ&RdCJ2YqOok~ymR-(hr`bl-G(et$Q`?htz--x)&CuGTfLaw7OUTf-x ze44LO=}jjq&Kfc=l%C@q_jA$M3K&gQ$Fr~=N-_K-k)yM^H3&d?H; z@WHnA5ogN^s=e=5A!oy_roP~V?Q1>9F*$R$nOq^_gAcZIgT9UXu@!PsZt%f2kLGc5 zk4JxIa<<-X>Y4n9>4OipWL?}>e*1Co>X7( z!PYVL^gA9Qzk`^Z&K+i)6Is(oez3)rd3th>?}-XIDL43Fv#XTn#CSfjo_U^N8_yps zI63P>vRcpfLv+66_aec^wHPmP<9-NJPdYw|&nO>v?l^?5x3RVNU6`CL6U=c)mk(!K zsC?X^CwCn3S0*Rz*E4sP*E8+Y-cdhk+->zU#;l*6`uTdOf4zOq9yn=xw{h-KAt#;> z2=1U3ap#Vc$1>wi&)Zt=Dj)akFlPPq`MvV4Q`ETb9(Q8b|G1glNZvo_jmZf;JIAYd*SD6hpEf>e+F<*?-2~RM$INH&r&hiTCvn>`ze6bKT?7qTgMOJ!$eF z-`e|CdeaF=3Frz$S)@0sHG-a5uC&vtzOn>@Zd!+h7zryfxGMIKbv_B*oJFFy-T z{O&Baw{bQGIjZlKJw)Ki96V95)%5#P^FXhaolz!ab z0Z0Fd{6K5#=O+tJ&hd!y+jK{HeiodF6SlW;rYhv5+$e`@X*+8EQauOQ7Wb=}}PI2q!qJG|%uk*NBZxjDCefqu7#(mp=o?0O%<))m;KIWXl zmC{XRx2PxHnZ8cUlin4%gEDv)HEkvs|^h zkEiA+bDi6D%yCGkKEKO9rpBl6!G&_1Jym%PW0l3{)I!h14rW|zdQN5P8GTyi*P(68 zQ)d2@!_NmN&Rem)jWZpPv-ugt2X5pa)Pj?%=NXcdaUKUg@cg&+JhMX1-s*||lY8EA zmf+-^9~Ebt^|7A#&>6PPr(X)nd3J@IlpB1o;Z4i;pF!uB&T%;xop;!dhv<({@6k?i z-jSTC`XTQ8(!h64a<-c4IJtcza;0*~zUQV_Ic@u^bl9VdCyC#^s*+2@owLOE>dsly z{hssgNzU+Y>BU=)pCvyZCDOMN+v5AMX_3B?NSEEQ-0tiXHmDYFojLCIRZjD5tGW5Y zCf}N0HC$|ma@$gB`!q>E?qrpIn@Ep~{IGq~Y?WW~?fF%*T%<=QjdwXSB7Lw(l@O9= z!bvKh_eJ_PA|0I39pw6K$4Smt`N*)z?bka+ZIAkyn!}r?9pN62{Kp~bHnSa3Utk!o zcwPB%9XP{V^EhvFbNA=0{g=r}eFIWBi6eOPHhCuJKbV{a!byF~SwEepC-;7Y-DL%I z{Pj#dYwAgT%Go@%e82SkeH**&J+zr>*RbgaHg<+jT~z;T?>#}a3z;qoL3?SwU!~6z z>9Sq7ueQ3|9$;^KXk(*)NVlr~A(`9QZSUF0xTUQi(?<))nZeagoj+TSoobgh4o|#{cbb|=f)kJ zcLn4`IhAq-)f462&E#}mQaWa}g^zrwZ9KUA@rbJ@@|_is6W^Fn#dC7WeaRN6-`PhUlkYl-=KQ#6Hre8RjMc2k=rjJvu@T_KObiHOIS}@ zgY{eFITCqGzhrxkg#0~P_hh^qqkL=Qe1yqaywO~TL;b`o@BWiulw8C;{)t)7ZT)AQ z8TXDEs(shbRJQ3&Gyf8ReiJ{?yZ^*?h&%UrzmGEerMkCFF6yIvYVo|^+?D2aE3|j| zJB%HdsqMnk&Fvr4?H%WFv>f>Dgp>N%4%Tl!f^z;-b2f;QNO)a%?pFmiO8qXI1c)y%)iXvskd?3)-TEHD`{s%H_vkIz42XB zKkC=rLpZ~VGdx%IgV}G*`4QAlZruMAFz(Q+(zv6&%l_KyWz$n$KH}(^*Yy&4Q@=>{ z)Enk?yo+9OM`qoutsTjqN2qa@uaf&$F76HQtGE|;Q1?s0M-i=a$vC7|#XY9up3)ZE z+v=x{Qyz{4=NW#Sp$`;iVQ0k&ALYjMIu!U$o#M=EzN8mtY2!t2Y@D)scITw`eIf^p z7jWJMAD_pLBYM^=&Sw35s62U2l&yZ+=I7=1GDkVTTQ2U&50##EJ1RZlgERD3!l^&V zYQFZKoSyxsjZ;1zOmL>bnaY~yso=nKwoAH!x7_-PFL$%H=fX)o z@m#pHJP(k1w%4iSPPebRZ*kqMX`I>*_}H%N38H6%;*9I(gEf%fcXl~FuFKds#dG8g z&hQ1^oVY)%`FDyFJ~;DF63&?7v^~GhRzGd$M^Z;|+$_yAS*K~cSpHoZD<7z3V z-T~WroJ~&~r@SuKozr$dF6J%bTPi)_L(jxhM9;X=(>4zlR8Kiy(|sHgy3jlB^t_Pz zxn~Hc-hnP%FKZW?=Q~05T%K^|ES&WGfco*-gfpS^OlZF7vmWCm1f!d^9pB~Hi*tOZ z&*`Lo)6;}Av%Ki+?AHkRn3k-mEwqwVqvMTqll$ zp8dS-xH(J|RK-|#LGQ1nep8s}nN)Fa(ww=T_0w_a#aO{&<6KdE#u+csaR>FGE45|D zA)cJJkw@HZ z{k%L+>E3@Le`;yJPJOyPd|N*+`vUpGI8k|yW1C-koH=iU`5NTc+j$%Jc;um{tzVMQ zi4D>(fs^)2NT=4;FX4QXj=N}kk4#qc6>qtE`p<`SJYgPBBj2h1lybqZ(bp;9!{U5X zw%;JHu-;h4L5@FL$#XK07p_MYeo*tu@bP)qhot|+2NnxGx$|JJG4;&;+tic#6sO>$ zCzmsOvWk0qK+f84RJ_w)myf%R6Z;dC^Ywt7D5p|R)K73?{Ed8RJ3{)~OwNMVvC~oU zhmU-y4W)SVirjUoo4aEx|Ms5x){HatDQA-TTupAj^d?hJ^h-^hinr2!3H##~D>Q2S zUgej&NA(xBb$5xt{=(sGWm*<`{OctoZ3w8*PiPJU^|g(`FWerv1a|Geh1Ohg(&k6 z+B-d7*xLIv=I@#2e=s?zPmvndEI&W*K2Dx~N%*#LNSn|z?QHC;CyfvF)AyP6(*was zvT@q#=fB)`G}?EZjCu6bHcD6cC_H?BFiymsj$>_cKZe9e zXN8_oXG7oTv0z-27^jX$@WIs@P)}RjZJf^q=4lZ}Y7@Wc`uVG}@NqnH3aXqMU0&e@Z|?kf z_1u7rZdZphr z_3Zjh)ys~zR62ZcHodCKX?{uB#4E~TznqVho<)nEew_bd>Ip8C3!lxYzX(nokFcH; z`Pz<0FS(rlPLObS^IY$CpYfz$psCJ>j<$;%(xdOnLg!AoMx_D!RNGo((4hnxNpzYvpB%i zlltI*jeW?|({G*u`NiFVpnv~abC7v_>ZmKPXLfy_p4_;%yTJaObxWIiQXl&bo7DG@ zz^4|+BW`=2?`Gi7*-kjAPdQSD^5Ra%+qU|7EOVVzRDT3a#5dhHXp{*lUqNVnC-nlIH})*^DOl|9hwdw^^>mGvg!Gr`$hlynHp^BNqv+L zTXQ&1&l+;w!p8XplQS~JyBJA5FZ~X4yo7OF<1&i3jc|hx);6xg=ZL%C z_!FGPfSf3&Qcil@q}QEoaqn~s_OGAeWzD!#AN;T}X58s|7#ruiOg;0Ovtc>K3m;rP z>?yo<#N~W1ASZY#8CXsB5azz^Fnvi!Uv+L520aUGZU z1L~PvUh(C8IGsL39d>x5qIcW!)))T25s*ew9@uYIl1Gy zZ`^YIk4IVEA3;y*BOSKu*S?8+gRVax2aJ2yimHCbwFMWoeN{if*%6QvJe6|NxYO%p zw)XxBlQT11=@?r{S@__lwq^=1?p)3V0Xe}_DQ8eU8<$t-gP#WEjIN^e?9{q~n_8}( zt;~LDDzjgr=f&Y~6ffn2A6w0P98#&Cp9Rzt9F^)xIl1!;pEEf-biA9xN=NwMrnbOr zM_kS?0&;?qnHYpIklt+EH?KRnO0;upPDjP@a?9j{M>d zJv#&HiMUs)CyjfEtdp=EkG^7ZqF--0PtDiXty*5sMqRJ4U({k;SD0<)W8=Jzd0nRK zCo{ixAI{_`@BS0K;N;GG|Kfhpe_WUO+2l;GX8I@}w&n)j@!c=(c^#K;1IE3uy5g(V z7F^VFjY^1-6pMXaKW*)?RCJQlE0>zx8hKw0?509}Q;K&)nK3C-o_3c&GAu z%KJv;i{77Zn^(M3#J$?t(Rcl4aV2#>xyoJSzmCa`bgq^6yLr9vd<;C#1KW%cZ_?rq z_w^v1T6*1#`t|pc=W@^th%e@8-SzXdz1#F0DZbx*o;G=rw@$b(sdGD}D|}LX$<34d zUrQh8H^bdkfi%_buc|*P=}De9gKyH`Kc_kby-y1B-ZWpEo~sFv?s{fVH2X<#I+`E9 zuMWTTdB8Web-%WC>1&AmBhI3A>Ghj<#~t%k7%##HUg2G`J`o>SEXGUR^-DvU{ZhQv zc&$VS3oQda|0$Po*&h)p6Zw2`|;R5 zxAmX4aouQAc&V@n5Taow(-&?BBQiZSGtccvZWbcl#|-ROs77!<67uR^Reln%#{$aOvbX(KvQKl4biaR~Z(?(zL#=JCC8D>LrYr@I!N zQ+~bo^Ye$>AoWJv(U!u>Ypnh9GPQ=~sytw8& zHJ<;jT7vqI=To2R=j*xqC7x%njad(La>*3VFF&4#o;{B5mggR9;pV(;sb4A;MBaqz zO)lyu13updoY@0-{rr|LkAMBl5l-rp-STz8NzVsu^;7;voa6Y{&*bk+J*n>tMm7Lv z{b58;OWf<-@B7ESW?Pe!`UJz*MLXi&&-JQ%p!IJ@t%Q^M6f8Hp{P~f5{-j(_OJBC} z{PtqQ8fSIi`Q*fQrk>QN<@x#U@5gy;WP5(y@5QzuXN2$b>zwUP&K|x;ndOpfoVIcD zjv}*&Gt&2XlqHFrSKV*!rbknf0@7qB&lu`NEuEMmew@x}Cy@rS;Q~Go{<(Zvi=rJ1bqA zcQW+_2ds?~pWFIRTio{&Uko|^aj(~WD2Mt;=UQ&uq36PYdV-@;JrQ?Xd$%2r_7(+4 zoV9(AM@_q!ai%`_xfXijx*5J_Yex=qJuTL))$Xo%>vlD{QBKL;RDS#kPQUZbwtuL6 zR$y{=?PqdD4>bJ}pMF!T^QY-f&wq+({=so#UsCn2bw z0|M%a;w#k?ad-9f7>C&O+|Sjs)>qFq9dB?_AL(2RJ#jrB-?R0f1DSf_evZ25)cT9Y zv1UC$Ik3^2dHtu~{l&;{7?U%+r{ZcoMp^jChuY%pz zLw%%kt*yP==D`jS8K)gJw<({SZ7Zi?FEh^6w|&o+&aI!#y8hHK?JW^`pK=k!6z*cfa*E z$YcmJ?lt=;&Q@*VBOhubx0Y}3K{=NR$O)cGIlCW^kXLtWi~GT1qqMV{?{$Pk+>AT* zyO+gz&($-pwWJ?`v{XHov&r`gxn4hq!vK<*R3wa8aLf`uRciTrQxVrSb`P zDP6y@>52LYPQUXby5JS<&Yb7ampD#XI$L=kwY| z2dL}Chr1as`n~edQD%HmZp#5?I`vUby)MuBXZh>#+_+<&Arvs~?Rp-h(s>5#x4f@F zzUc3_+Q!L8h;79>meM+E_sbstbddQE>U(^}O~U;ou-Fd2D@5Z$L;Mwc5T` zTWtRq_f3`Wb%cWE#P_I=blB+GN_Y6w;&ppx+fbK@`xve$w*bw-HY2M{}fprq%CS#vWI{E0iJi z4fT`eW2>Jhx*-1bv++n%PwHcTV7c{^yN=~=ZpQxOqNqRGI*68a5^xMg!RlNjn zZ#fZnR%{%5@(mi@tg*!0BbsGmLde~voN z=CsB3De;C=KdH{tM}AxzRL_+H>RIBbP*2oPaB`pLzcQ1vOUFCYpyCd{#7*AB?%-YT z;Bu}KkP|qSat75iulF|`khA44O3&DF-u(jhgR3WZJijh;Jl{#Us1H8a)Sl(X^W6Fg zJx2u86C9Q5N#pJ}PHy-@oo8*xvsnxluq)@KnkfR8N$* zF_W{nwVGcjo}lz>KE8ZAO1;4Am*{;`w)5ikneC`v^I`v}k962hW;^nWJM!B!pq}_% zrFvEx_cfTDb$?TFZr8Ty#PV^E-OY2Yer*AnU6>?UpXVAFE=BoW& zDcopw-<9{da;2af@6Y;H-GpL@$_m!Rz=6dhYmgaLL3R+iiQ`^1|@A&T5j^dxF z>znH_^+Z1(nW*BOnovIO#ZUU?xCzen19C#QN;!kZ9p%+BIWZ0iPf|LzXVprq^$2fHe2%z>J}~#!Hm=)-$r+k#a#A1Vm+X-| zPVVzm>zSN6!b$xSpMI0m#}S$iAA0(=qxjdVAFgAzBlPn%rzl;MDN|pR56d0Tb2&E) z$O(>0IcYnJeafq!+cD$bs&xb>^^p#nOY-WcpPtBXbEcl9aq$!t@5HI)E+u|pS%FykIgoAr_URL{bn`sR3)`9;<9 zZ3F7re1_ufAl#Ib+m8JDd2ntQkP|$Wa?-f_aiYBKnVdMj*PX5OtUuGN2gnaLwvg8^ z`QF#_y=sqpFgYVlI^K7yaahrZvvV(Ad*_}X?Z|9LO=p?prQ%}Sl z9F@jBX#Ff!tNq;}AZPj9E;9 zl#lxmx!y+fiQM}UP7xV*UmwzVzIVNA)BQX+`s#iJny+nL(5ZwI9MqQh&r;VpOFrF@ z>6g~qd~D7$*f^(%e7oyuD<*t_sWbI$-?OEIlh#ig=V?sNyyonhtDa{B-^SsW4o-S} zw{f1%H0bw=iix}p$pBpQ{Tp8O9v-i7i8m{%H+%uPU_ou zZ0X>n_p{hI(@akKJ3iF6@z~OFUQE}K+UC8_a5Gx8-n;87@8^EiOjmKwe62o*Z{u(* zzsrX0!AbSBah^pukq@=4niJ{NM|#OJIdLBjzGve++udN1p4gt+#KmSiqCVZ8t>;H( zKX2nahso(Q>$u;b>xK4v@F9V#=Vs>q+c+;_a%Kq^^?_HiOiu3e70+XG#xF7VoBAa_ zykT?z6LTp3mgWTx#k`{SqJEFgfXZY#ZkVOwQP4inHlf z)sEl;tA}NBa@Va*V{&$CPVi74=_TvKDer&qdfASfcZ>55&iE7K#Pm*jJxhn#@3jwD z$8+U=+iz-}c~M)i;dn%UpU4*X>FyW(`}ybX-QR zo0j9tKlc@!^mmkOdS2}2>#t|?m8PE5r<~m5Cini$W+rF-RVF9(gL2a6NYpH?>UaKf zRiBg7l|{a-?)iIFR6Y;B+;gJByPNC5;AgHF<+h)~AXQG|KxON-k8)t66V>*JJN?}j zTih>oGw_dlQ;Vr5^}$iH%yvY755>lL8I!Z_YLk=tB|f}ia-zS(*KC}Z6VA|sCJ(;f zt~qPhRr3t+@j120pLz51^nBCCc?IFDy+v`*a?{r+{`5NPbNF;S_)Sbszj<2ZH^Y77 zUqA6Xz@fDjFMQ-ft?hS#u^rkG_x_Hn2xsIqB~c**I@va)xd)IjK)M(@aioKYufmGe$+V%NH<}&lVV~>Hd1po7n*q7#b4?fO2(mSeh;<~)HbIj*-l=fr1dEUXD zPrk#=!2kH}+-AnThhG9wZ(4lxME}X<9Lqd^&k|1R6HKRNLHW4jIVarbSzRz#mN3kb z^NZ!qH{<^>^^6|neZ2v^jW3t~9C~u+KlgOci~ZxCxm|I_URC4MF2W5y*y4WW^$g0n zS3pj1fEzxwh5dP)-1DP5-2(jejAhNZQ=f8naN7~{ddEyAXD8vLKIII3*SC7!#pG4I~pQE4m)3fO( zmCybG^=!Xe@iyIMa-)1$o1XX_oLoJhalh!_&(~?bmceR#2Os59o9^mcJ^vU`Pw-T# zC#|2{{_|df_K}{Y;#|MF`W!yEscj#}Ywujn`v@m34}NW{Ss$s7?O<#5I&JvW zqJGkKLALYv1DSCz5Kih-j_@zM`pMPvezySsc9gou)RX#@GtShL%b8@JcSPJ2q*QCA8d-Lr(gYS(Df$~uzu$6SGqRdXX*<+*v!v;TR$IkGxo2a zVa*2)>LVRC)5m%q98gbiRH|pC{rp32!Tx$SJYdF|`rwCc^U)LQ73p<7+q#Pj#rZpD z-37g#NPX~eE&6$Gzm#(`_SZ8}^O&h8^}z=l8O9rba`k-N&DcNgv45JJ z)CV7Ij;Sa2{QU{SSramOP;RH@%rvU=clh|6+9H$FFYYZmE=L87d*KbWA1#l2?+r^a+!T`rw0Y{3GwU$sI2}$>i+NoY|;4Ucv_#wKdFn8}4=OYz3Z^-r3d)Tf+&K92A0`yipf^&egyKnsr|I5^~vCZ@;r=K5`^O6cVDYqXN z{T!V1yu+sF<$|-y8C%jb^qjX&4bPhCd7>}n@biOmUO_l>Ois$}$3;KKag*+^?f8DB z;N;AIQhuB6l*i_SlkTsL^QsCtDYuQsmL9bKY!RHC@n_9EvwkL@H+{;Jjr48*d3A-H zl$&yP^)cr)OwLxKC-o_3el4D!e&_GVceeY+|GXpdf*EJ(BR|+I^L&$g+`N{lr}J-< zvxg5rZ9}7YdeU*7?L2Odo3Fo~S?#YX6F9e+WR~vXUj`we$=O&ZA?A6_wByGP0s?8vqN*%=G445e98yEgV~O_^T{tVIh$WG^`t)dU=s1gewczBo_m|xa z7ID)2;5WTy>PdZU2U}pqo!j1DaWnSktZO$psSiHb=oH?3GWS0HSDBpcgp>N5M?s)zfrk;&&E6(&FWg~By+~9*v&*imuuAXnX z8T;$mM!2XCKG+nqesc937f?@dKwtRO)=lBXojVTs!7adF&+vRR&eW%z^$U5N+~*qI z$6TMBC!Ex$oS_qV=kHuSi$u?+>%7My4eywGQlD~$598_SS3lcVRQvnqfb}z1RJle_NX0%kj^ zdC%mcKKNkMXP19I80Nj(UowB6%r@^mPv{wq40HURXVpqLQ%{=tgO6)5o=<+ri~IX- z#{T_h;(b$3>QlbD!+Gt!=I8R9iB(nonZm4}SdZM&p?P&ZrF`%kM)K+>w;lbJ$%%FZ zj!N4RZSUOQL;27x*gx*^56!q!AN;VLU-9DZr)O>@6_?`!>Y4dS@pchz@WFEXB`)U) z0Xe}@DQBf||JW_qKkl)Q&A3w^{IF?ed#BH_w;hkVn4F!2lltI;ZDNk=xc$;;%($ap z0*6y!zeMBC)$>QDp3zUtxKqExuivyY^-TU$zMqe*qT2iTfO^({s(3pHH|0#M%u|KWo~|@rDH9#=Z7S#aYm{?sJnH`N4+5<=atd zocy>MciTAmX~D@^$I`C3;?Jpk;e#uvMckeB&Hc62&(GZg{NtYf!px8Ql(UN&ckcDg zlLE#aJg5ioscrR%JM`q%&q)<>R$4!4zr>CEm#z^0aZh!cai>1jv#E(Uujr>|e1vL` zCkNEC?JLC_(U$VT_iOLmxPxWO*TmX#G>_?z;aG3Ij*xZ}@nU10xqlqX!&$9}`ce&d~Qa>sSe%=x8; zZ%zHE4?ftYbD851=JUbkGUFcl&g7&%_+UE{{B+$a z>iO>QOQn48{XE6cLiIey$g@?(_4radV(R&wTabVKOn$HQ?AlR{!{C=V$(t5t{p7Zz z@0px6KPb+I?Gz_`f>&}on4Et7QgU@wf6~nQiGHa#Lh-h0?h+Vz!|j*2{rpdE{{C@y zel*)rqRaFNrqg^e@A%H;{JBC-%1t@zkL2~A-1>PYGwxZfXZ$CnBYesSze(3C_|&4k zb2-ln$cgeQ<)q^fdVi4ZyyJT2IHXJK2u|uF9X82a_sgxHzq%Rwx1-F@X1k$2_+Zmx zDmxyf_3!1hkl)R@O2j?ltl%sw3MhBq8LsE2Mylfxd~mf`jz_J!yyTHR^r zxZl8xd&h64o}Is#K6qg>FCZ-_g+-^v#E8!L=Etq0(R^^3c0TxZks>VWMirt2kb zM{O28{n`<|57ee-hN)*=wfVb3^^WO7N7!~||4H}P#wl)&6EFXER3u!~2On(WhVsXE zH}2TDo3+LLnt<&ns{1F}j*?xKwIl9v^QH>pPU}H8Nz~i5%lAuY@7(7aRWakIqxxh@e|+N=jCA2z>Xc|F0&U7x%ZGwyAK zi~8V$ZLKiwHF~@fA>)<{MBGE-KiN-|i#x`N&DZF81~T80v&6k#m)H5L_c+<_Ii=X| zTbXeW*O+mpKJtUjF#CD#^KG7Eau!}O=ach<8+@=Glgsx@w)Sp2zE4xfclP;FON)v- z9p}W`z1zFrxQ_N4w)TD-Q_s*4Gw#%fjVp@yadX55{jgp2wF zu&s~V(R60q(QcBx$3%}tVcUwCO8ux64ai{eFyj+X8bNl%kX572T`2qDQUsI-h zd#Ar679XkNVQcRfi?}<^u)N>=Qur9v&hy&B$M1->>bOTnsPe+AdDjDHocTLqv_0C| z(H+d=X3H?M9mQ5KeX3{Ox{Tuy{gUu)dNwoL5&Dl-^!Ma<)f>O|*3Z^|qJGkPZqsu{ zg?dtbsWb^6J;BLc=Rbtmj-o4?ai%`yY`&rVd~(on$R*6Uqrc4R{vAH}YQFJ~yRH9( zo^+nd7WZYCdNvPNde*$6=9A%rliJ))jCSOfZGO|%jxG(TXNQhI)iV=NPaKbE{j_n; z6z!(7BKGhT2~tP z`fn?1N8EXvyO{lFVT7q?yIv7I6xTnJ=C-spZY~~#E;i14E99iy;De1`#_Q*~ z_jk;4I|%>lu*t1VJ)7S(pLY#D*ka22z8<PLO(2-~t0kCToQXxx$C8B9)RZIiQyj|{b~9mwP4&d;yNJv;Sxhs#; zuN_71QuTa2W;^PbY__BLIz(Rr+VC%4JL2j&oT+CQ;i5jlbRx@_pSQs{g!|mrm6@EG zbxr-KPdV#n@Q&|(&tpNpt1vlZ>zSO?M}DyJ-FWqr8~1aWoSlS|`rw0&pUJDA+~>ZI zU~;ysZ|X^X@WF<6=jqA4FLET4Gg@nMQXhP<%}maYjmjT4k>9FJ&JMy!edGsQWO8!b z`x;En<_%0esSiHbY>XFoZhK#o$yqmNG$H~=m6qB=VBa@T*;Dc>qa&q-to5|TuIH?al*mfo-w;ip+Pda@!Pf3sKJKgN4Y|k7_r>o5bIv=mpQ-CH;GjOzVWYFnaY+6n_5H>})$_E2j+fSB z>RH&t)RX$)gYCG_HGmw%@_IaDdEt#i-wUn>NDP!`J1stgFf^tnEF&jQxO~-1a`2sb}M6rk>PC z`LK0+^Wx5}pBpkc!<(C&)CV7Ifyv3OpBphb^MsT7;Dc@a15ZzG+&5-&Hf&+)Nqz9a z*6+jP^gDk?ew#2kLtC1h)JJ}>?OaZuc`)R+DU<IH`~PU<-#a^<;9^F*)hHH}$~> z8#$cE8Qz+AezX~rvu0~E?$ie#Y`(}lZiec4oLewCTL~xi!3W#H)RQ}2+LCZ~-eS(j zqTIwbrk>QtcChjHczSZ%`&NV#<@B)iCZ|Jv@`dCP-J!;jSs%{U z!_41p$^NR>3+w%HFI$m)ldkQ$_I2vIHv4|qrYfatk9hs)J?@C>`#b3Uur^NHb?xh! z>sYW3uoLSP$#ve^pS(G3>i}(>Ha%|$sAv3l-g@ROoPDL|jRE!S(wxv2RV?vyFg>HAAl+&LB$I1Po?uQIdH1CVFwRcPzHhUg+`nn#wCR~u z^|Le%X@A7L-iq=t?#OJbbcJ8~+``#c$IUwgC+Gfm^q-dxYGgjrTr>*~#bwa-A z{am)Vzvs>`g+!$;f8TEH&Sw3jzFTOwe>%@K=S#bN3Ju!9id-u9-}zngEO?0H)mh<^D|XDVvj@WcTk+PpU+x2ZT)=E z`uV=DpG`uTa`%H&Evu>!6{b$=KbcA!&*oDehGZscUBmr%4r;^Y`yleAF$Dh>b^6?y)fMD zuWjw<17_S2Z@aY%LfbwP+bt>?D-d9SLUzU$I+dzgAs zANvFAr+3hHbYH-BRJ=-^$I*7wP!p^j1&w>Zrb#`oXMH~#Jpb9Nw~oW+j(C3^`F?T-}WoeuRy;7{R;Fe(62zh0{sf~ zE6}e%zXJUV^efO83XB_{sFr`#UoD)v%Y;Prpo!{lfbe%dDN((&upbCJNZT512WvY- z+hw#}R@>#Y9jfg=CMBxn-@PZRKj)N0wfh%vCqn0ypNH_x?x%sC*U@`??>D{O1oOO} zZkH?^<0Lzep~=EuxKJiWd&^tBG>>;_wOwSoomWm}Bnu6Kw?U$jm*UOzmUkGFcelar zekGgjyzUc$)i`b>3lk7wMcM3_6Q^lk1f?+c2<%-h3zQEgXuhMjk5@wMoc z&s0aRvGeA8%lk5uca*9R`7*rnQdV(`+0~hCW?S{`>@DxQ%=%lawo6X3>nqn}6erHE z&QG@UM$YeL{TZ0D7b z(PvI@q92^lgBHhQj}Q8j`W5I`pkIN01^ypYKpr#YtN97Jo__J!&raUlk$;(#`pXL| z{}$-K$Ro>Dk2`g9C#r2y+l;n(Z6i}QcjRAG|GDtp{_!nm$WT>|wn=R>+UB+GbvZMp zs&ceVYMaqEuWfJ3iEev_TTW8jw6=L|i`w?KoXE+loT#=*Z8O^Dwe4*=>G2P^`;*Z& zudOpdrAJ_UTMsr`R>eo#q_!Dt^V;@$e;V&q`=f1MTW7pVkHGeJf369s{n0k5ZARO? zwtoAA{vfUUgT-Z0PNOboaoKKNgZnmjv|8`msBQKObNw&2Z#_z-$Cg*?beb*OVSC?x z=M7!ov`uQ8(KfHGUwnMa*;evG0UQTwB9QrnESd2M@L&KzBi zwn=R>+UB+GbvdW%81a_&;cv#7R7Z8O^Dwe4*==`jzwx@EM@YwPTw(j&0FJf5ac)a7WK z*Vg%)E(f-kT0aZBpBews~!P zUCta`ueD8To6$C}ZEwp-ub{`H+UB)&hUxJrtWQ0_IHBM6EAao40{KnGJMyon|1v`- zIMthucar)qBdq)@>c2?cct`#v^( z!pgsl{woSA{~}wczo@YCFRA}-5?1~>TdF^q|0wZ3t^YE@%D;E@Uvw++eesvne`#Um z-~X-GjFz*Vt)@Co*JBZPz6I8~=4@xUNUyu>z*%Q?vk{ptVCA)YnO^++3GU}nksj}s z9{XYqH@~DvUrD6Xe9|I)MUkHR>O}YZuyaNFRwDQI3l$G+{#w2L83(BCwRNtOJXKD7 zvf_Y^h;+##uMtSjYdwH@xb1) zj!YN(oz(lS?au4giv6f6@z$NQrmJgFq|5!zoUHa6cB%D5K7yF$lNRZ6zv=6Fcl#c$L_2^G-7~i-3iO6rU_9r6$C8-hEu%naef6O{F5?vvZ=iQ6U9UgPG%20a)B5#> zUO}wXTWX5qru=Sqy-VqOy$0%a=Y{=x2hkbZO1-6~?#~P9#O`{R()D^()a&H*e!Zb# z5G(bTn!1li@X))IuGib5UKcLz*E@*L*jDN-HFY0D;-PmbU9T5Ly^dbeM|yMDAp>{` zw^DDZsa%7MSNHy;l&;r1qh7aO+DCeG*HHs*3Aa*jsp+6@`_WzRQo3HRje6aDMIY(S zT?gKcZ%KYD^_H5t&*jrQBK2N+(wJ&FUzI;x%~!w?Z3I(pC!`cA`R(@ zYu0kV=bS#KTF#%K+^tcrPOp1feIGWe)8$xD=6}AP4->BY!uY!s2fe<()Q?=%NA;U~ z-vGdta4YM#)YN?}yxy1Y{YfcZ-=Bbfq_L%s^yc38u!QRje5tq8)P3H#hu)=h++U&V zb@A#x(i`~#=>Kyo^_H5-dp7XuUcXD}`u-5q>-e>Oq&N4z6TmIuR_ZM^#X2^*JKgmz zrR)1!P_OgX^^xA(`(~DKoq;d)mYT|YX7K8+cPU-ppVMdc8ijH1`@!~0xRrWKP37}f z@sfJe>kXOT`gs0Zs(?yObzjS?Gq{q9Zm#)u?bh#fruFs2f&+GFd zUFu!aq;!JK|7^KF|BL1NyhxWkIDaW!pBL$p2mGb$^CW$7U7ydt_m#Wu0q0ri>yLKp zZBeHe-cs>|b>0`-3*O|xDjjxhk=|YJ>@0PDmJ#W4|FGXE=Sh*isYrKnYCQz(zz@E1 zud63cQQwCxiuA!krS_*(xv(34D7UY2vOB8nVKX0@H0`2C-)1Xz#t5F)*M zJ*(H>d*0o?s^@x$gk?R1PN(~x73s3vt~=Cv2-xDm-s>T%5Aj|Pkre5YlfKfH^o&k- zJ7w`Dx*p>BZ#Hw+pJ1K>HvQdZqTVm62etR=btN)g8G?os*B@t`Q8PhT^#mh<@;mh*X;E(oAg>3m+KcR#;`-bs-z_3m*# zFVa2F=S8|aUyPm|QF>~dzteI)KhttPFVZCs^edgui}ddCFP+bm^u={PKO<++`w@%Y zGTlpWk?yItNcYrRqK!{r=?$BI&Z7787QIEfr`{snQ*V;K*z|6<=>3L8Z<+3; zw@CNYTcmsHEz&*p7U@#&=ChREu=zJFdcS4STcmsHEz&*pCh3b!?+%OJ3oLrebT7R{ zx~JYE-BWLo?y0v(mwM;)d@OAKQ;Xi8S@ag^o_dRPPrXU{;?ldv{K?<@_Zax z8Ik{zG#;E$bB_1@fJ4slz8_Ggd)04|?peP@x@Y|s>7Mmlq|5qUn5Oy@*!(hjdwM_M zvXaN+en64#S-(ZPXZrRm2wU_XY0+Dzd+9CGJ@pppo_dRPPrXID)Vt$yHBSqh zU)7@bY8Jgkx~JYE-BWLpzS#7xwdg(CqPI-<(p#i^>Mhbe^%m)#dW&?ackxVBzhUzm zTJ+w?qPIx*)LW!`>P^xYm)_6Td+Qz9)?4qWO!v?`Dbl_4PK$Iey)z=+OYaVmF7=L| ztMrC-w)fUMD$>3BlcY%Z(mO5Ez4XqI^u?w3jD)w|&LQ40Wxz73os%{P{}nl0DR0Z|5*?y(1#sOYf*i_tHB_(ifNB>Hmo9zung5;(BpLr{g*? zY+j}dy>Xow_I;7wU2j}3PQGMbx5f41Geo-A_2StgeJhbat`oy%UiQ9T{HaKH+ry6P zdU0Ia-g%u4onhY->D_gW zUZwUkdhypry=ikA-Rt~+66sP`%ws_BnIc{4+BjZ)A2xZ(*Wx~mDyM6Xx(*MU5$Uqu zz;$`pr$o9JPvla?gL0wwjw0QQ=OU3VdGd{l2R3@S%7@PXR3x^{|L$)Lz3b+y{VeKq z=nU)365EUKVZI9bjS}fz`<)i)vVLH{vHeXVUG6t@gZ)UP%l$5#uJ#+Y*!qp)>&uW{Cnm+^JW*bx%X~181zR=iohrFbtvFrJt7&_*NbjDH zv!=?YDAHv>BpU{pO1N$*k0s=?Hf;0>FbJgFCB^^y?eP6 z^!Aav=es%#5_w5IZF5IUn(!K7l%)9yYyifBzk-nAS#Ql)4(SMG0?~BBJp0MYLbU6=;`!iva zk4sLmUWnYM*(B0s{-I6P^HyLpPpJHx^mB<}^E#c*!^*ZN_m%td+m?R5xP30S-*yqb z!IE;EUtFBfVR8MA(2|mGzYgkn3LO?#eOprUg$_$f{asv~(4qMWRX_e$ZNCm?|Inb% zv;J2t>O)MQZ~w1ar~lQjK)(Y03iK<`uRy;7{R;Fe(62zh0*gg~+z`i^C?5D&BQ7qq z>IWikEYjplJPy)XOZ>@sZ}}X2y#~OY>!owD;^QUeRV^NJnU6Tm&4O6&-)`bh?ql09 z$2mb*`C487$@j;I53dn_M~L_93!Ro1R(`Ke{K@M(^0l2ZrFrmy`o{rI+3BTOU!CyV zgJ(XI7?XJS)^GG?&a(0%gLv&aY4@Yo7&LF4*KgYE?9hAD4^pX)v!)h!a?70b8QGPG zueH`$sfKGV5-a}IE3&e((;oZ%nkyWz=cC6ybmN;7$6t60KHo@A%8OTiqy1JHFy^5{ z_8s`vT~orh9ivhmXHy;Hr$2di!>=wXeEG*GZ-4sEr8l_-pKmDz5w9~Z89Aom^4R;w zt^WC#Wp*EVfJ$|otz?A|uYIS_nip!EdD~}=gAQD{;F*V2s^e@euFc5Tx_`d*rt7!5 zVY5HPj$L)F?`G&!$N8OnFt>Ppcc+1>ao79Ter-p5zP)@-^Fy?gJ0F}qxF z@1EEF=aF;IUT?}7o8j}_b^K<`m^|XPV2wTtGQn&^K5MEzz$_P6GiHDhC+{dmqd@63Mcq0;B?sdo=8H#D(e*r0s|jQMEd z7wR?#_k&6LVZ~E_IN{562Y$9-{4bCEb;yI4J&5n8^^QDx+Og|h`N&mc2j24i??-Jp zTwX46UrqYq(*M3{_1w_4-ui9tm3A7lvUAhE`1}I>W{>;dJ@Kox4*zi0oA;g-9rAGL z5y=*1)pbh{rutV^k=`^y~6GPyzL*Y=`El98K2*w>))g+ z_g#46+2_6f+#go{qEbFnw~ph9ej>JUOukz>Sa=2 zZvVuew>;^OU+g~{pWmnByJGU*Paa*l;j;_2KV@XqEyHEE;=bDT!yWab~Plbr{`>Rs`(Nws@lJ$c+E_pJHr4F~SKp!B(TR-}Ag(SFm(vz|FVJ>v9N zX5G8PQ?IL3@yx&x>fNu2mnR(ZmoYmG{ratQ-uUj+Gw}Jtx_`QVi#?7X_{qHUci8Xm zKW#nmsFFU9==jg-{2Q)7p~DI zW^~o-aoI_V*P##A+@DzWlGwB(8&(=Oe!V+Ys^dJNzklfb=G$J|d){hWk7|xjUO2GS z|2(ZXeCpxUjBl?$Z0Lq-T(`-pQ&Xk>?`h3{;EWr-jh(t+sci-xyUslyE{pElY18pt zdeuqy>UfSvP?f3Zh>Tk5_j`N(3^yK;b zx4f3ya{ZaR?)vViSH8Fe{4eM?Gw0m1*Wf>&Gxf8rM_;t_nAN_<=P!*`@8+DAzIO1J z)9-j{V#AcDhD?14pTDZ>_oJ(I-g3@f`yRPX-Iw|IMn3gw>GNIGyQMBZ<=JV2POG2y z@J_S$8ITr7DD`?xE(Q>SZUs@OT|Qe|MsKH~N9quUzi*q3yf3yx4HT zaZRZ9PKS=~X4}?Wz4tZy{q^5BZF|qqvz|Q$-(RqjdiTmlv-Vs2!lPRrUa-u4Rr&SL z!{=Y<_^kTtjq`rG=9T!y({}B8aM Date: Mon, 26 Nov 2018 14:41:28 -0800 Subject: [PATCH 08/31] pixy_parser: fix misc errors --- libraries/AP_IRLock/pixy_parser/main.cpp | 5 +- .../AP_IRLock/pixy_parser/pixy_parser.cpp | 93 ++++++++++--------- libraries/AP_IRLock/pixy_parser/pixy_parser.h | 7 +- 3 files changed, 54 insertions(+), 51 deletions(-) diff --git a/libraries/AP_IRLock/pixy_parser/main.cpp b/libraries/AP_IRLock/pixy_parser/main.cpp index 5cdf348744..2d78f670df 100644 --- a/libraries/AP_IRLock/pixy_parser/main.cpp +++ b/libraries/AP_IRLock/pixy_parser/main.cpp @@ -17,9 +17,7 @@ bytes_to_block = 0; */ int main() { - uint8_t tempArr = {}; -// pixy_parser pixyObj; - pixy_parser pixyObj(17, &tempArr, 0, 0, 0, 0); + pixy_parser pixyObj; uint8_t input_bytes[] = {0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x17, 0x01, 0x01, 0x00, 0x69, 0x00, 0x56, 0x00, 0x27, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x17, 0x01, 0xF1, 0xE0, 0x09, 0x10, 0x46, 0x00, 0x27, 0xE0, 0x00, 0xF0, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x00, 0x01, 0xF1, 0x0A, 0xE0, 0x10, 0x55, 0x00, 0x15, 0x11, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00}; //array of 15 bytes of SOF // uint8_t input_bytes[] = {85, 170, 85, 170, 15, 1, 1, 0, 104, 0, 82, 0, 36, 0, 48, 0, 85, 170, 144, 1, 1, 0, 229, 0, 86, 0, 37, 0, 47, 0, 85, 170, 85, 170, 23, 1, 1, 0, 105, 0, 86, 0, 39, 0, 48, 0, 85, 170, 23, 1, 241, 224, 9, 16, 70, 0, 39, 224, 0, 240, 124 }; //array of 15 bytes of SOF @@ -30,7 +28,6 @@ int main() { printf("%u, ", (unsigned)input_bytes[i]); } - uint8_t input_bytes2[] = {}; for (size_t i=0; i<=size_input_bytes; i++) { // printf("Calling recv_byte_pixy : %d : %u\n", i, (unsigned)input_bytes[i]); printf("\nNEW BYTE IN:\n"); diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp b/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp index b417661a46..01612f529d 100644 --- a/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp +++ b/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp @@ -18,6 +18,12 @@ * * */ +#ifdef PIXY_PARSER_USE_ASSERT +#define PIXY_PARSER_ASSERT(x) {assert(x);} +#else +#define PIXY_PARSER_ASSERT(x) {} +#endif + #include "pixy_parser.h" #include @@ -27,16 +33,16 @@ #include #include #include +#include // Constructor - pixy_parser -pixy_parser::pixy_parser(size_t a, uint8_t b[17], size_t c, uint8_t d, size_t e, size_t f) { - pixy_buf_size = a; - pixy_buf[17]= {}; - pixy_len = c; - blob_buffer_write_idx = d; - bytes_to_sof = e; - bytes_to_block = f; +pixy_parser::pixy_parser() { + pixy_len = 0; + blob_buffer_write_idx = 0; + bytes_to_sof = 0; + bytes_to_block = 0; + blob_buffer[blob_buffer_write_idx].count = 0; } // Destructor - pixy_parser @@ -48,6 +54,11 @@ void pixy_parser::empty_pixyBuf() { pixy_buf[i] = 0; } pixy_len = 0; + + printf("\n--------------------------AFTER EMPTY: "); + for (size_t i=0; i= 10) { return false; } - writebuf.blobs[writebuf.count] = blob1; - printf("SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); + writebuf.blobs[writebuf.count] = received_blob; + printf("SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); writebuf.count++; print_buffer(); return true; @@ -187,70 +198,64 @@ enum pixy_parser::message_validity_t pixy_parser::check_pixy_message(size_t pixy void pixy_parser::recv_byte_pixy(uint8_t byte) { // printf("INSIDE recv_byte_pixy:-\n"); // Read 2 bytes - pixy_blob blob1; //%%%%%%%%%%%%%%%%%%%%$$$$$$$$$$$$$$$$$$$$$$$$-------------- should I put struct as prefix or not?-------------------------%%%%%%%%%$$$$$$$$$ + //%%%%%%%%%%%%%%%%%%%%$$$$$$$$$$$$$$$$$$$$$$$$-------------- should I put struct as prefix or not?-------------------------%%%%%%%%%$$$$$$$$$ struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; printf("The byte inputted is: %u and pixylen is %u\n", byte, (unsigned)pixy_len); + + PIXY_PARSER_ASSERT(pixy_len < PIXY_PARSER_PIXY_BUF_SIZE); + if (pixy_len >= PIXY_PARSER_PIXY_BUF_SIZE) { + // This should never happen. + empty_pixyBuf(); + } + pixy_buf[pixy_len++] = byte; // Append byte to buffer enum message_validity_t validity = check_pixy_message(pixy_len); // Call parser printf("Validity Check Call: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); printf("Pixy Len: %u\n", (unsigned)pixy_len); printf("Pixy_buf: "); - for (size_t i=0; i<17; i++) { + for (size_t i=0; i= 10)) { + pixy_blob received_blob; + received_blob.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; //Extract blob information + received_blob.center_y = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; + received_blob.width = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; + received_blob.height = pixy_buf[14] | (uint16_t)pixy_buf[15]<<8; + if (writebuf.count != 0) { swap_buffer(); //swap buffer - blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; //Extract blob information - blob1.center_y = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; - blob1.width = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; - blob1.height = pixy_buf[14] | (uint16_t)pixy_buf[15]<<8; - writebuf.count = 0; //Turn the count to 0 - printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); - - write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) - empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' + printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); + write_buffer(received_blob); //Writing inside the buffer(the count increment happens inside the write_buffer()) } else { - write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) - empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' - - printf("\n--------------------------AFTER EMPTY: "); - for (int i=0; i= 10)) { - blob1.center_x = pixy_buf[6] | (uint16_t)pixy_buf[7]<<8; //Extract blob information - blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; - blob1.width = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; - blob1.height = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; - printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); - - write_buffer(blob1); //Writing inside the buffer - empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' - - printf("\n------------------------------AFTER EMPTY: "); - for (int i=0; i #include +#define PIXY_PARSER_PIXY_BUF_SIZE 17 + /* pixy_buf_size = 17; pixy_buf[17]= {}; @@ -24,7 +26,7 @@ */ class pixy_parser { public: - pixy_parser(size_t, uint8_t[], size_t, uint8_t, size_t, size_t); + pixy_parser(); ~pixy_parser(); void empty_pixyBuf(void); void print_buffer(void); @@ -57,8 +59,7 @@ class pixy_parser { const pixy_blob* read_buffer(size_t i); enum message_validity_t check_pixy_message(size_t pixy_len); - size_t pixy_buf_size; - uint8_t pixy_buf[17]; + uint8_t pixy_buf[PIXY_PARSER_PIXY_BUF_SIZE]; size_t pixy_len; uint8_t blob_buffer_write_idx; size_t bytes_to_sof; From f73a0e93abba7a8cc27ad51fa31bf45c843a9483 Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Wed, 28 Nov 2018 18:24:53 -0800 Subject: [PATCH 09/31] Integrated pixy_paser with the firmware, still doubt the integrity of the output vals(x,y,w,h) --- libraries/AP_IRLock/AP_IRLock_I2C.cpp | 164 ++--------- libraries/AP_IRLock/AP_IRLock_I2C.h | 20 +- .../{pixy_parser => }/pixy_parser.cpp | 10 +- .../AP_IRLock/{pixy_parser => }/pixy_parser.h | 21 +- libraries/AP_IRLock/pixy_parser/a.out | Bin 30320 -> 0 bytes libraries/AP_IRLock/pixy_parser/main.cpp | 37 --- libraries/AP_IRLock/pixy_parser_old_working.c | 274 ------------------ 7 files changed, 55 insertions(+), 471 deletions(-) rename libraries/AP_IRLock/{pixy_parser => }/pixy_parser.cpp (97%) rename libraries/AP_IRLock/{pixy_parser => }/pixy_parser.h (95%) delete mode 100755 libraries/AP_IRLock/pixy_parser/a.out delete mode 100644 libraries/AP_IRLock/pixy_parser/main.cpp delete mode 100644 libraries/AP_IRLock/pixy_parser_old_working.c diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.cpp b/libraries/AP_IRLock/AP_IRLock_I2C.cpp index c320a40c44..8e89667117 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.cpp +++ b/libraries/AP_IRLock/AP_IRLock_I2C.cpp @@ -3,12 +3,10 @@ it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. - This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. - You should have received a copy of the GNU General Public License along with this program. If not, see . */ @@ -28,9 +26,9 @@ extern const AP_HAL::HAL& hal; -#define IRLOCK_I2C_ADDRESS 0x54 +#define IRLOCK_I2C_ADDRESS 0x54 -#define IRLOCK_SYNC 0xAA55AA55 +#define IRLOCK_SYNC 0xAA55AA55 #define IRLOCK_SYNC1 0xAA55 @@ -56,88 +54,6 @@ void AP_IRLock_I2C::init(int8_t bus) { synchronise with frame start. We expect 0xAA55AA55 at the start of a frame */ -bool AP_IRLock_I2C::sync_frame_start(void) { - printf("\nSYNC-FRAME-START():- "); - - uint32_t sync_word; - if (!dev->transfer(nullptr, 0, (uint8_t *)&sync_word, 4)) { - return false; - } - - // record sensor successfully responded to I2C request - _last_read_ms = AP_HAL::millis(); - - printf("\nSYNC_WORD BEFORE: 0x%04x", sync_word); - - uint8_t count=40; - - int temp=0; - while (temp < 9 && sync_word != IRLOCK_SYNC && sync_word != 0) { - temp ++; -// printf("\nTemp: %u\n", temp); - } - - while (count-- && sync_word != IRLOCK_SYNC) {// && sync_word != 0) { -// printf("\nWhile Count:\n"); - - uint8_t sync_byte; - if (!dev->transfer(nullptr, 0, &sync_byte, 1)) { - return false; - } - if (sync_byte == 0) { - break; - } - sync_word = (sync_word>>8) | (uint32_t(sync_byte)<<24); - - printf("\nSYNC_WORD: 0x%04x", sync_word); -// hal.console->printf("\nSYNC_WORD: 0x%04x \n", sync_word); - } - - printf("\nSYNC_WORD AFTER: 0x%04x", sync_word); - - return sync_word == IRLOCK_SYNC; -} - - -bool AP_IRLock_I2C::sync_frame_once(void) { - printf("\n\nSYNC-FRAME-ONCE():-"); - - uint32_t sync_word; - if (!dev->transfer(nullptr, 0, (uint8_t *)&sync_word, 4)) { //I think this conditional makes sure if the I/P byte length is atleast 4 bytes - printf("\n1st condition FAIL, frame END"); - return false; - } - - // record sensor successfully responded to I2C request - _last_read_ms = AP_HAL::millis(); - - printf("\nSYNC_WORD BEFORE: 0x%04x", sync_word); - -// uint8_t count=40; - uint8_t count = 0; - while (sync_word != IRLOCK_SYNC) {// && sync_word != 0) { - count +=1; -// printf("\nWhile Count:%u\n", count); - - uint8_t sync_byte; - if (!dev->transfer(nullptr, 0, &sync_byte, 1)) { - return false; - } - if (sync_byte == 0) { - break; - } - sync_word = (sync_word>>8) | (uint32_t(sync_byte)<<24); - - printf("\nSYNC_WORD PROCESSED: 0x%04x ", sync_word); -// hal.console->printf("\nSYNC_WORD: 0x%04x \n", sync_word); - } - - printf("\nSYNC_WORD AFTER: 0x%04x ", sync_word); - printf("\nSYNC-FRAME-END!"); - - return sync_word == IRLOCK_SYNC; - -} @@ -153,50 +69,45 @@ void AP_IRLock_I2C::pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, fl 4.79331390531725e-6f*((pix_y - 100.0f)*(pix_y - 100.0f)) - 1.0f); } -/* - read a frame from sensor -*/ -bool AP_IRLock_I2C::read_block(struct frame &irframe) { - if (!dev->transfer(nullptr, 0, (uint8_t*)&irframe, sizeof(irframe))) { - return false; - } - // record sensor successfully responded to I2C request - _last_read_ms = AP_HAL::millis(); - - printf("\nBLOCK:- \nCRC: 0x%04x - SIGN: 0x%04x - X: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x", irframe.checksum, irframe.signature, irframe.pixel_x, irframe.pixel_y, irframe.pixel_size_x, irframe.pixel_size_y); - - /* check crc */ - uint32_t crc = irframe.signature + irframe.pixel_x + irframe.pixel_y + irframe.pixel_size_x + irframe.pixel_size_y; - if (crc != irframe.checksum) { - printf("\nBAD CRC 0x%04x 0x%04x", crc, irframe.checksum); - return false; - } - printf("\nGOOD CRC 0x%04x 0x%04x", crc, irframe.checksum); - return true; -} void AP_IRLock_I2C::read_frames(void) { uint8_t buf[142]; - dev->transfer(nullptr, 0, buf, 142); - // printf("\nSTART: \n"); + dev->transfer(nullptr, 0, buf, 16); + const pixy_parser::pixy_blob* temp; - - if (!sync_frame_once()) { //It just sync's the frame - return; + for (size_t i=0; i<16; i++) { + pixyObj.recv_byte_pixy(buf[i]); + temp = pixyObj.read_buffer(i); + printf("\n\n\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); } + + printf("\n&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&------------------OUT"); + printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); + + +// pixyObj.pixy_blob* temp = pixyObj.read_buffer(i); + + + + + + // printf("\nSTART: \n"); +// if (!sync_frame_once()) { //It just sync's the frame +// return; +// } - struct frame irframe; +// struct frame irframe; - if (!read_block(irframe)) { // Try reading blobs until I get a sync (Nope! does not work!) - return; - } +// if (!read_block(irframe)) { // Try reading blobs until I get a sync (Nope! does not work!) +// return; +// } - int16_t corner1_pix_x = irframe.pixel_x - irframe.pixel_size_x/2; - int16_t corner1_pix_y = irframe.pixel_y - irframe.pixel_size_y/2; - int16_t corner2_pix_x = irframe.pixel_x + irframe.pixel_size_x/2; - int16_t corner2_pix_y = irframe.pixel_y + irframe.pixel_size_y/2; + int16_t corner1_pix_x = temp->center_x - temp->width/2; + int16_t corner1_pix_y = temp->center_y - temp->height/2; + int16_t corner2_pix_x = temp->center_x + temp->width/2; + int16_t corner2_pix_y = temp->center_y + temp->height/2; float corner1_pos_x, corner1_pos_y, corner2_pos_x, corner2_pos_y; pixel_to_1M_plane(corner1_pix_x, corner1_pix_y, corner1_pos_x, corner1_pos_y); @@ -212,16 +123,6 @@ void AP_IRLock_I2C::read_frames(void) { sem->give(); } -#if 0 - // debugging - static uint32_t lastt; - if (_target_info.timestamp - lastt > 2000) { - lastt = _target_info.timestamp; - printf("pos_x:%.5f pos_y:%.5f size_x:%.6f size_y:%.5f\n", - _target_info.pos_x, _target_info.pos_y, - _target_info.size_x, _target_info.size_y); - } -#endif } // retrieve latest sensor data - returns true if new data is available @@ -240,5 +141,4 @@ bool AP_IRLock_I2C::update() { } // return true if new data found return new_data; -} - \ No newline at end of file +} \ No newline at end of file diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.h b/libraries/AP_IRLock/AP_IRLock_I2C.h index beee279b2f..bccb507dca 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.h +++ b/libraries/AP_IRLock/AP_IRLock_I2C.h @@ -5,6 +5,7 @@ #pragma once #include "IRLock.h" +#include "pixy_parser.h" class AP_IRLock_I2C : public IRLock { @@ -15,27 +16,14 @@ class AP_IRLock_I2C : public IRLock // retrieve latest sensor data - returns true if new data is available bool update() override; + pixy_parser pixyObj; + private: AP_HAL::OwnPtr dev; - struct PACKED frame { - uint16_t checksum; - uint16_t signature; - uint16_t pixel_x; - uint16_t pixel_y; - uint16_t pixel_size_x; - uint16_t pixel_size_y; - }; - - bool timer(void); - - bool sync_frame_start(void); - bool sync_frame_once(void); - bool read_block(struct frame &irframe); void read_frames(void); - void pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, float &ret_y); AP_HAL::Semaphore *sem; uint32_t _last_read_ms; -}; +}; \ No newline at end of file diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp b/libraries/AP_IRLock/pixy_parser.cpp similarity index 97% rename from libraries/AP_IRLock/pixy_parser/pixy_parser.cpp rename to libraries/AP_IRLock/pixy_parser.cpp index 01612f529d..e528668623 100644 --- a/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp +++ b/libraries/AP_IRLock/pixy_parser.cpp @@ -1,3 +1,4 @@ + /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by @@ -111,7 +112,7 @@ const pixy_parser::pixy_blob* pixy_parser::read_buffer(size_t i) { } // Method - check_pixy_message -enum pixy_parser::message_validity_t pixy_parser::check_pixy_message(size_t pixy_len) { +enum pixy_parser::message_validity_t pixy_parser::check_pixy_message() { // printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); if (pixy_len == 0) { @@ -202,6 +203,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; + printf("The byte inputted is: %u and pixylen is %u\n", byte, (unsigned)pixy_len); PIXY_PARSER_ASSERT(pixy_len < PIXY_PARSER_PIXY_BUF_SIZE); @@ -212,7 +214,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { pixy_buf[pixy_len++] = byte; // Append byte to buffer - enum message_validity_t validity = check_pixy_message(pixy_len); // Call parser + enum message_validity_t validity = check_pixy_message(); // Call parser printf("Validity Check Call: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); printf("Pixy Len: %u\n", (unsigned)pixy_len); printf("Pixy_buf: "); @@ -248,7 +250,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { if (!(writebuf.count >= 10)) { pixy_blob received_blob; received_blob.center_x = pixy_buf[6] | (uint16_t)pixy_buf[7]<<8; //Extract blob information - received_blob.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; + received_blob.center_y = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; received_blob.width = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; received_blob.height = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); @@ -261,7 +263,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { if (validity == MESSAGE_INVALID) { // If message invalid, wait and read 2 bytes pixy_len--; ///----------------------------------------QUES---------------------------------------------- memmove(pixy_buf, pixy_buf+1, pixy_len); // This discards the first block of the pixy_buf and makes pixy_buf have everything except the fisrt block value - validity = check_pixy_message(pixy_len); + validity = check_pixy_message(); if (writebuf.count < 10 && writebuf.count != 0) { swap_buffer(); //swap buffer diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.h b/libraries/AP_IRLock/pixy_parser.h similarity index 95% rename from libraries/AP_IRLock/pixy_parser/pixy_parser.h rename to libraries/AP_IRLock/pixy_parser.h index 7375aab1d5..46412bd98a 100644 --- a/libraries/AP_IRLock/pixy_parser/pixy_parser.h +++ b/libraries/AP_IRLock/pixy_parser.h @@ -1,3 +1,4 @@ + /* * pixy_parser.h * @@ -26,20 +27,25 @@ */ class pixy_parser { public: + + typedef struct { + uint16_t center_x; + uint16_t center_y; + uint16_t width; + uint16_t height; + } pixy_blob; + pixy_parser(); ~pixy_parser(); void empty_pixyBuf(void); void print_buffer(void); void swap_buffer(void); void recv_byte_pixy(uint8_t byte); + const pixy_blob* read_buffer(size_t i); + + private: - typedef struct { - uint16_t center_x; - uint16_t center_y; - uint16_t width; - uint16_t height; - } pixy_blob; struct blob_buffer { //Frame (full of blobs) pixy_blob blobs[10]; @@ -56,8 +62,7 @@ class pixy_parser { }; bool write_buffer(const pixy_blob& blob1); - const pixy_blob* read_buffer(size_t i); - enum message_validity_t check_pixy_message(size_t pixy_len); + enum message_validity_t check_pixy_message(); uint8_t pixy_buf[PIXY_PARSER_PIXY_BUF_SIZE]; size_t pixy_len; diff --git a/libraries/AP_IRLock/pixy_parser/a.out b/libraries/AP_IRLock/pixy_parser/a.out deleted file mode 100755 index 6a4dd3bc153d1c7de0bd49da667bb95a2b995281..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 30320 zcmeHwd3;pW+5f#W$;?0?2?;wY69qvr2?>F)1+ooHlt5%r+&X5NEShBEECF096{4mX z8(R0;ifi3orEjfL(F%wGv`cJVsI`6bwxB_5n^y6qZv4LAv)s%~lIo|Q_mAKE`EVik zIp^8VbDr~@bI)^U?w#vB%a+(o)6j?ASY)u)>6Dm4McCe?3IK)1Tw@r{XBej&4%8C_ zPSOh{0978xm1+%L3U3Fb++3SP#KTh*pN85(!bC+I4D6gNu^JkNTOcS$TU#4Ps>k#-?hQPD;gW1C{b>lDoSP#Tt{J$ImPd~fy7k?}O!X1xf z9pe@X*Hq7#!LgcS_hhAtK(l{!WmThJ z(gvsa>ejFKwfKXfKyzhdLwJL)btW6CtFHEi*iMe&ThqL*p}EGl(jSU6`AMvn2DC)N zAy@$es;~4_*I((Yt!!vCfUT~t3>q!LhURcB=+)~heYFkLezo6d@;5aFT49lodX(`^ zl?~0t(vlM2tgM+v$=bC=#bv&ntXam=Wo5-BzTB)ltCX8H8;-EypIw}7A|ey5_@tXm z{JR2B`?uoE4M|*i{){kKnFiDfClcwbOSw;4AnI#Ht=8b&hW|DkY^i4DVO z!{;R8(Cd(1KRQ)my;^THzCsmTGu=W?<8}RDw#0KS(DRLqJyCcqLws)(emD{8=!?Rm zBQ8{IHyc5M2Yo!(vS3M zxBXAvO^5m_Rxj&F96ri0yd5LIhe-2w6ubwn6JxR<^Kr`LQh_=jl{Mau#4X z!{G_&qK#E_apYwudTO&$CT|w{FMFB2>aRoPC^B};9xl|J^(ExJyT7!1+xxt`dl!4n zF7NAKhQ~wUfoW3V2r3*(-^PO7U^61w-c1GTSXx7SMtHXr+=E*0NOZZ^i&IzP-Kd*1 zXCn>!=w+xxf5?8>ky>!Dw95Of5ATAnYrI<$rcMW&x82j5v#YDE?#mM=VD#;T-j247 z1Q^*XjG~`WThR`lMe*lwAH??cCSy!6)~Q`>E!5uCb``+mU2Q>G3&~m-Af>A<0$_Hv zwMwuK!02jQ4^ZFLwn5ge23XnEc8#oE3oxat?K)ZeCcw?W^{ROJly5E3Gn6%x;*WG-=5m#*#dY=c9*9E@K(ru2XdW&TLHg2uFLa1 z$liv(+d;phq04h8;9Zcv8}OcKU7qg)-aE6)^8>&iLhe4uZG+tXka^(mU7iPfx;zgJ z>+(FD+U0pGJ#{;36`ES5KP3iLd8Sv1|F3(}ZyRU6M!lsqsv9GNjMaGPGizs>* z2;#at#2CXxqs{J=XN{C+ceQt6;%vr>E&{FhtVVs?8I>FX}~!*kp``i9`$CwM8UHE;URjXqJR zH|5!lvOL20983;5x@9j9%xbaM3j^2(?T@b8Ql9IU^$7SA@VBd|{kVvnTC1sh|B0qH zdHT$wcSzpC3c+!q#c?$_Iu9sc>E5+RdcYplLm`xJ33;eChT&_tK=cJY-E@3dt5bO5 z=ylSliV6wK(dsa7`v~@{C*`?9xS&rJRqu&a9Y@g+eeM&+?ZNg!y7$rJ!ZbT6=Z7L#MoAU1Hpg=8LeOIx497MYUbQ26K!aSVluA)l z4LaE1q(K|}!lg&@wPR=y-Wa)#t{O>^UZ8e}9by-vI>wrmwhvTWaIthjO558+brcMv z?2}4eO3IB)VS%1V^zA^`?(-Z12J4iAlug(5rL0?mB@KS^^jQn0xL$F-_IW$JoN5@% z%`T26*2UdDu3_D^*i)rE=jp9AJ%_jy*^d51+4zFsqA(-i#aNjSAoD@(0?#2a&ac7& zy(d1_c-?Ah+e*h)ezlWS}f)n{k1Y5#|? z8BZM#x7bAu*2hHJzjd4Z#ccL6O& znYG=bW<@qHPekvDVR|{1=^u(|ZwwRH%cywySTSJ-64l(kSf)?Fgx!q1NFa(n!37fF zV{8oo{(&6@L-TRd+t0Q)1%J8w@YlVe88U04xB)S$Ow=%-jZzUagFc-}CNzKBsu zNNHOcJto*Eq})^}G4%1zV?6UxtY`Ebp9ChGtRfX zvdFR6*Sngla7RJF;y?U1`t~6D0^c4S(zgc(`gT87583AZ(6PyLQ2N$PX}cB5qKBxX zLbcyNjn&qebM0GusKwh6#F~z3$G1fl*Ua``_ud4}Qd7UEj3_4}3M&AJ)-)_TK9u?rr-^*q!rxeg9xt`=`s=KPhehThWQp?|L`A zYP-5 zGgf&#?$zG1Rhc-TWDxb#W*Dp1RkpMYP$;ne8h5|KmHx__0c;vs8w@n5mX|aHLt%GS zW1#vOgZ%j6hM*paQE_EOD2t zD6d%NS?$R%miuAe)QGz&5cIpNHiZ2l8e1J`YH9R`{q9OP*oPa%%T|<}7bRtUwOlbx zA8u%Sm-(CP!u9S(nC}kPS2nwI@?v_UThtxOb%!=ISBKn{t++kR+tKbybT5Rv!R|!` zLRj{^qGA08=yop+`YUk*Tj~x3-Ttd0m5uC5&K&o;2DGdcp5v~rY^;tnR*KQD4pwL3 zFiKXIxR;?8it{psFq-$ zwV_5LL|m?}m&4$0XvRJ9Fbrx432t`31)Xg~XB$FRd|tpPz#VvZNxdJTQc~I22=*HH z^qKShO)bFZ%x{pP;?6}$yV*T!zK9#Xr#)b4aU@JB&zU$hCkixTCTjum^A#AP;`N#lyUMrD3j5H7AX5x;jl~D)IbiZ#-<7K?ZdU&Tkk~ zKqr6wkrO9c$eWzHBzgR~DM{;G8;!*i7o0t7%IQQ?z7&7k!H0dCbx@Xvd3D7yVTtqm zr>41$NzxvvpKW{>_Eg#N3C5l1Xi;+Njkc1J4(}$reT^NKOB)^n-!J|mZ<$#JdLigc9{TkkwCGbn{}l9NG4wu*UJ80Q z#_o|A`u!HY2J{Osray_HKV{K3gZ=^Nh46#bzI}mk0R8w7=*$j2O^Bu+OQ3>Mp!R~^ zhYPG9WurJb^*grWBCeJNOo>`PUy*Swo zKJXVOyTs>7BM?L5vAeM+BOYE6hrdbH^>^;XXMVup%Ov7>X1s(G zR9%0caFVL)djb-89f~e)QUT*q9T2%c z>dG8rjAXaYN{!K}zMrRa+)l-z?}OkYBXNvV@N(6##^0+JeE4uw9J>9}R9*Ao z7LDj1%oQkn)j-t8D}DH`kEm-qaXUcN#b=bzg|s||uGIgp0sX!5c!g)Gj?YnWiGmj> zSgT;Gg7NZSRoCAi)qMCO?R@w2HC4Dr9&zVq;XAdNx%m-M&G}}|+^m^-XGyei4n*WA zN*~{&T+O>lgB_CpVFa>d{9J|1TpikRLiYpD8!n8o4vbR59Z<|$G=nu{GhOB2vDuub zAz*9?&ZjWYHkb1;0@J}eDE1A|W}BJ`g*IDaF)H>0q)y8NCLtjaUpR(Dq8%;RM^ecx zVG!&)SnOai(dBU6O=;6{0rWXpcDT0T?0gs}7rtJNY56#G4$Fp;gfE6Ce8JD2lkC^m zz)?x|jkgJK<8V-u?CsM8xTQ#djtd01^-2N0vr&Mpj|*_yD+1i{djanLM1Xrnp$AF! z@0SShgK7b`Z5H6cI|O+60RbL)Mt~o^A;6;_3Gi4Nx{zdlV!8lNE*GHhHDTbfPtb=X z`zH+od3>_~|9o43Pwy7svmF9_{&xUl#AP@ooEQb+k)r3OnVevnKNVW`OPvR$vOh~@ zhoqLnQp@{NbuX2r)HJjj_BS7ZMhd3x)hCV$%83VyL9)5+KZ6%+sR?|(!j_QGz>#z% zOhDg&91SqaDBmFg&Y3kGnEB!4Lf zUGaNZb{TeB>R1wx{N-a18#GYzFK1EluVC55c={3r`&ckKD(*uOG0EGBqi=@!j;Zz| zKsj80!+8uXV(_I}Cs2j~F?QTa^v6+QBZr$DJb`#7!1xKTlDNi3Kn8}BWSE%4R{c3p z&frRY7*u0o36b^WWT+{mm&hyGM+Tlmj+;Z7bin35=k)k`Cw}NhryN)^^7H;tp%Z5@#iJn5si=cH}IlKBpAJciMv%Bqmz@QD7E zQknw<;+!m0lAQTsm37YLL`ZVZ6RWIqK7&2Uxlk;3&P8ICbry*>1OmdcrRo3Yd ztE_XWSY@4FvAjCZ70avhJh8kwmx<-oSuU1W=W?;UIxEET>O7yz>*QBqkUI;dgRWz1 za1BhW1H$!*Ff@%{kaK;;p>w6p#;CYH7sHt5CjJYS$EWqM{3Xlov`Xl4onU!-#zION zCMz>DUPFIfrl`!#IGYrks1#+ z;u>$>4Q-n;4zic0n2(`ybHFIdSEm2DZnWhGlw9?f`% zm6@WlJ>$Pw$u$}AJ2JjYN6iwp?aJ6gLuZ>$qn*9R>7!`EJ?`hhG2XR}olGkw_x&sy zX_wHB2iRR#+5&d>5e`o(Cefw9Ib3f-*%`d>)9fk5C=koh6xf$EHr<$d5&Cx~S9aH8 zllU`7(8NMnew0QPiSo2X;2Cxk+niR2CWqZDirkXsvI=gzK^U8s!>s#(gmA zK5(bifqTT1^H4O>T3DXSvMp^Q_(z<{aza`!m`6-w*NL^< zXlukd9Eb|zY#)F#fotQ4nID65#wDN{Gp2&yobeorwi#Pdw$F$FpJ1d>>4?nl2t_-o zXdxACPfKD01@{5JBQ2j+EF!);Eg$1GVsRlfA57cARtkylNqd5NidgQoe@y)JD)2bH zNL$XK2S!Y4hjz0O^-la{J`K%s@&Bn+qSpQk0`|Ls zS%0Gs=Kcds?gV8P{uWsrdr&g6{z!A?1!41k)Ystea*Kn0F|yBP6Z0PgAIC5hOEu1* z!#EHk%7+z&=9&!)Hy>g0K(xS+Gg6$hJiC(tI#2bIOn+0j+stZ#qZzE zd#}S*KbN1ho1-ai-}?5oxmmE$97~<{t$o+#UJHHZcrx0z_IxvU9jlYr5Bt{MYjcls zP%=6cbygzG;;}*k<1!HP8VvJPDRA&wWAHnhPoj7KOG!#1ofw;`Yyd`ODl9r&PS+2~Br}yn zmYuGLaZY?3CzYu@4U_sam0chpQ)xg~kg0HAoMgW-1wBEga*hDEED@mN5&>>)5#T#* z0&IO+fZJXb;Eo;v?*2@Gd&Xkuk*RnE_yM1ZOR{fk7vRC~3-Iud1bF0U0{rNA0zAsx zJIVgoI1DZ_l}rJiTqQtXw=nS7XXpbmm1coF-Y&pD-xc7~9}4iVNqu)EXQXm4*?gKsr(fvr|V;!MW*7y(56}^Q23Z#Or|oG z96W(I17JX=!f=udDpO&?!Qe_|kVa=J3^j$6nF{;Jz>`RwsqmR@#$mr*sT^r}`V&f4 zrb1UURK+e)ZWVQ=!fPqRSE*K+3VqFJPG!sD6qBhi!i9in%gR*P`W%wPiM^6^r)wdw zDpN^hIXY9}1c{f>nF?o3D*GAVGo7h$KFJOZmZ@-l#bhdU`EQ97#<7Iaq6<`}!tQb! z_S2>Es7!^^GoBossc_y3x|ONWExcQk%7#)!i72$pZFY2~!l@{^=p-vs;e6xtjGA*Q zQ(-W3#>xg&ra~m=Z@iT%Q~5o}oYw=$GE>P0ne)A$tTUAYP*QP)j-nt_5o@M%hFCM5 zSz?)U&SJnJQ(+iIXDVfs7TX78Dzi{QrXp5Z=UlPMI_HU1);V9Svd)EKxpOWOtE{t7 ztg_A$vC2A2#VYIch*j3PRIIX2uUKB4=ZfXkd7fBaoy)}X>MR$_t8=+nUY!+Ud3B!8 zK{6E%oz7ImFse+2Wu2+8tTPpstxSa#D^p>`%2ZgfG8I;=OobIIQ(?u* zRK5!ftxV-ERK7;0vJnctMyB#ZXtOevr%1J`aZXgGG8WhjO-ZFy(V5CCpv=WziN)~?l%g}0-=Kam z{`?jP{Suw2a17VSQjIg{Fb;%>a%3uu5)Oc_3l+ed~_vXWfd5xs&?rTc5c;?-Evj z&SA7|y*%$M)^<_Iwsmcuo3&Ti7u(ilv*(Q#`i(*f3_sHhq$3B|dE3?sWA=ZkPt(p- z95*SB_e3VJwbaO8pgu3t9F+g3q{=l61L}P^2Q-Ih>oLi3fo$t3S^Gx*w-j@9TaU}O>hn7lF}AHIr0k_s zpTnRuFZ~O;v_$#lC#qTVUSdZl$M|OLT=eBqH9&daqUk<4y7fj5r;U03JV0pFcsF5Tqmy4&r<@h=wtbYm1pR6*|7Dv@e%@&`xYc zoc8=16&r64@}RzKHBgvrT;t3c#^n$T;ctPSVhf7l<1hslQstMpy4?d9RNByWahUfK z`yl=bsKU0j-k5(GRc07JLH#5ASt=J*0?n2eRiVJubWyd&)S$qryvVOHwW?q&rgnbp zIu^OVPV-x>_K7WETWGuB1pzNFctyaq1-}xoqTp=-mlgB~SXgjGKnNyR~lkCZp zl1G_o&Qwfm+Y}=yX%SFZSjHOm+!&*%2eH$k^zTggE%!E8t9@k^Q1E%v>44{7o-rdS|X-rpo?eOVwyTT0o6rG z98f)kGp0ik?*yJ>^#K0PO{cdr)wlVdmtLuhEx?aIsMeKbOvAH z_&bWl2;}zLYa7qIjfm1TC;gEJiW*o_W=jetwQvGgj(;(%$*t)&Nb;epc65XI8{VAv%)D>md+|eI;yHdntq=X8|?Wy*yln))FhafWyUvq zr<_OgHN~AIC*%Tc2d-*aW=?u@a=)ocrXbPC5q2%=Z^bYc55kSf_9*US+KkmWo91W9 zBXKrSHdxP&go4?4?yoUY zzHGeuZ=m{o-ExdVd|v?%-DXv{w7^CqyrIP(%BrWa)%Ye2bn){RG=b+?Ya8l7!DbYM z8h|>G%lHW;=V-gR1`V zPJx)7@}NDi)}H1{vp2gI0(K&|FwI_W?u|?S&x}>Hcm6L8nckt<-KOin;r}@N_Tj^e zZz$h{p|Lw|-~c&X=>)C?>kcp8X`7ku8XZM@nf_k}riF)ukk z!}wwr31IN~n`?|FJnh{qFzfJ;zF**~`E;{S#A1_t0-kR&ZI0kQq3aD_ZDVB}UMgB0 z3Hqu7jgh8iV;$cnidKA0mBB0Vo>D_R+U^Sne4zl$;HuEf=6x40pJyqWh3_+Yps(Ds zYE{uvkFRXGeoo$~@mDu;rJCLxX>4o>2hTEs{_0jAwF;}yonSZsnjvh&lhjqzos$za zeR6We+fCU|ysE&{YJ~9409BLnjWr538ori5h&~EL!f;49u&!EoBvjcd9inX%k53!5 zje*LrQO!3TSk_-qw5+VuC!X9NU`k1zr>Ua8slKVn!24e7+~O2z4mH#@`|-p%w8(B? zMEJ-(e9iSTXAV8ek;1!MBQU)(gg3i3@>^h);Q;!MH@0Hv0tQC3r3l{rW>oJDD&n{Y z@g%#kuAwGeFLdF#{Tiu>%qyy{FsefS%3yUpdyhA~Vw~1Piqaeam?AoxlRFo$g%$5Y z@QEkc`4(DO7w_{Nsb9Jran=;5@f)*YGMG6^+W%I3h=<^XWioX7jl{4US49FGj}Qk0 z5eHw$7!|HyHP@Ge_tU~~UzBI*&?q9tlyBZ$;S-}NM5_V;xR24ClOui4Igni+X!2)Q zUKy&d+)#DJ%-r0Z>{5T|%5b11o6f2b*R19Kb+I++Y4QF55ukkCE}#3ygs5#sx2>yh zY?5&#q1J&h5JH@l|yydHWF^)@T|qXLk@ zDU47{NG+B?L@7d5Eh&8Sw!37;jGR3AJ#KeqQ#jJ>FR1flA#A8dm6NVOzSrBGS?A8I z74K-y#49So{_1cbmQ-Xv)Z!})4)?B`or#Em9OWEpXHiAu&JE9*oE1HRVL1woLMnJLDTvtF4|?t!_+x> zuo3eh67n<6E ztR&U-!8#$RUtQv_5iycugzFnHyW`p^$+Z@DhA7pp3j`s8iS<@rNB-_8o)b9fp41BwEI9IK_w1(Kwdv_};>J?Cs+ZyD`kT zc~JatLqAUvEn_#54EJ7JD$$b&jH2a$Kv-6+|ejew&QEu z`njEGqMc9s%p8n=f-!zjynYHPS_{WOjchk0>= z@%Iz)0=%DWGm?#6apTJy<-{Z8VvY=j*UxonVm=C{(eDSg$72cp%t8F$1U&WY=fud% zV*~z7yyZnd*CmiR-G#rw?7x2q{80Vm*k2gK)Zgr0%%^LxQR zdO*B=sPOUq;((Zg#M>BjKz)iMB=zYmflnTABfb>)RK#a|9G<86<3Cv`#(Lx)B%ZGU z|0rnE^ORph;lY;_o-T_q=SP%&eWyS_4fO=|;Qmtl^HzM{P#VTP{HD?Np3UDa2*hlkM5FM3A%e}Xy=52bz5BrdCD2z>SRyC4h{p%pUaFef^zZ}9`qbA_1!)Cp* z(N}|AW5`z-!OmR0P_8B`f6lx)gER5>J{o+L!C>VETm1nhYbx|>r5cR7ig@yX3NBDyy19oLO)~?Lwuc-`I4&cc7s$78? zqev~eC53g-zmXE#xJaxp5}|+(@7k+Dsugd}fSVDe7iI-W!?L4b9LeAu?P+X~q4#hCp*n#Rpo@-&jcjRcdJr8(Eyu zMiz=$b+~bpg}Vnh3vXrx17a3t`RmonQeOilx(4m|F(d!_YJW@EC+=iOWpdGxI&>Lr zRyH+M!%9x;EJUi2g$1t(ix_bJsz@C;E1T=EI;v_zb8SGEE32x4{#ISXuWR{r8Gegi zs{gGrci7kpV2>#eo!@E5FY!emQaM(3aqEwA%M4X0>E z1>@yQfyZkX1G;^kS8Ay3*J+>LFKM;QQNSnXmi;@FA`R!N4&!?z!cSUWU51SdfXAiK zlGk~vhWb4SU=c^W|Goh%-!Y)==a+AJXs9zIZNKKz@JjIVodvqC^Ii?bXK3J|{j^it zkD@sEOe~w!@;X1(@StSlhiT%_^1A<*12n{Ujbe`Y{y(PV_4w(0M8lDB0@`k^ROWg8<3H5z3u^v2bq4c3`d_!N z??Y%z?+ukU}X z&!o2gc$KyOx|aV41UaNAc#}!S}pQKSv=dq$by#FFjdLN zu^Gim{_;42meXi{|2Q5;+5<}dn7#lgfp}g%TON-i>z(CNV38iUA>`)`A^+woDR5WZ zgo$sx&+HDIw2=^%A -#include -#include -#include -#include -#include -#include - -/* - pixy_buf_size = 17; - pixy_buf[17]= {}; - pixy_len = 0; - blob_buffer_write_idx = 0; - bytes_to_sof = 0; - bytes_to_block = 0; -*/ -int main() { - pixy_parser pixyObj; - - uint8_t input_bytes[] = {0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x17, 0x01, 0x01, 0x00, 0x69, 0x00, 0x56, 0x00, 0x27, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x17, 0x01, 0xF1, 0xE0, 0x09, 0x10, 0x46, 0x00, 0x27, 0xE0, 0x00, 0xF0, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x00, 0x01, 0xF1, 0x0A, 0xE0, 0x10, 0x55, 0x00, 0x15, 0x11, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00}; //array of 15 bytes of SOF -// uint8_t input_bytes[] = {85, 170, 85, 170, 15, 1, 1, 0, 104, 0, 82, 0, 36, 0, 48, 0, 85, 170, 144, 1, 1, 0, 229, 0, 86, 0, 37, 0, 47, 0, 85, 170, 85, 170, 23, 1, 1, 0, 105, 0, 86, 0, 39, 0, 48, 0, 85, 170, 23, 1, 241, 224, 9, 16, 70, 0, 39, 224, 0, 240, 124 }; //array of 15 bytes of SOF - - size_t size_input_bytes = sizeof(input_bytes)/sizeof(input_bytes[0]); - - for (size_t i=0; i<=size_input_bytes; i++) { - printf("%u, ", (unsigned)input_bytes[i]); - } - - for (size_t i=0; i<=size_input_bytes; i++) { -// printf("Calling recv_byte_pixy : %d : %u\n", i, (unsigned)input_bytes[i]); - printf("\nNEW BYTE IN:\n"); - pixyObj.recv_byte_pixy(input_bytes[i]); - } - return 0; -} diff --git a/libraries/AP_IRLock/pixy_parser_old_working.c b/libraries/AP_IRLock/pixy_parser_old_working.c deleted file mode 100644 index 5ce930a831..0000000000 --- a/libraries/AP_IRLock/pixy_parser_old_working.c +++ /dev/null @@ -1,274 +0,0 @@ -#include -#include -#include -#include -#include -#include - -#define PIXY_BUF_SIZE 17 - -enum message_validity_t { - MESSAGE_EMPTY, - MESSAGE_INVALID, - MESSAGE_INCOMPLETE, - MESSAGE_VALID_SOF, - MESSAGE_VALID_BLOCK -}; - -static uint8_t pixy_buf[PIXY_BUF_SIZE]; -static size_t pixy_len; -static uint8_t blob_buffer_write_idx; -static size_t bytes_to_sof; -static size_t bytes_to_block; - -typedef struct { - uint16_t center_x; - uint16_t center_y; - uint16_t width; - uint16_t height; -} pixy_blob; - - -static struct blob_buffer { //Frame (full of blobs) - pixy_blob blobs[10]; - size_t count; -} blob_buffer[2]; - - -void empty_pixyBuf() { - for (size_t i=0; i= 10) { - return false; - } - writebuf.blobs[writebuf.count] = blob1; - printf("SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); - writebuf.count++; - print_buffer(); - return true; -} - -// Blob buffer indexing swap -void swap_buffer() { - blob_buffer_write_idx = (blob_buffer_write_idx+1)%2; - printf("Swapping Main Buffer: Swapped to %u\n", blob_buffer_write_idx); -// struct blob_buffer* writebuf = &blob_buffer[blob_buffer_write_idx]; - struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; - writebuf.count = 0; //This is probably wront. But helps me get rid of an error!!!----------------------------------------------------------- - print_buffer(); -} - - -// - read blob i: - -const pixy_blob* read_buffer(size_t i) { - printf("Reading Main Buffer: Reading from %u\n", (blob_buffer_write_idx+1)%2); -// struct blob_buffer* readbuf = &blob_buffer[(blob_buffer_write_idx+1)%2]; - struct blob_buffer& readbuf = blob_buffer[(blob_buffer_write_idx+1)%2]; - if (i >= readbuf.count) { - return NULL; - } - return &readbuf.blobs[i]; -} - -static enum message_validity_t check_pixy_message(size_t pixy_len) { -// printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); - - if (pixy_len == 0) { - return MESSAGE_EMPTY; - } - if (pixy_len >= 1 && pixy_buf[0] != 0x55) { //checking if 1st byte of the message is 0x55 - printf("First block not 0x55 .. Message Invalid!\n"); - return MESSAGE_INVALID; - } - if (pixy_len >= 2 && pixy_buf[1] != 0xAA) { //checking if 2nd byte of the message is 0xAA (Combined it verifies if the message is 0x55AA) - printf("Second block not 0xAA .. Message Invalid!\n"); - return MESSAGE_INVALID; - } - if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { - bytes_to_sof = 16 - pixy_len; - if (bytes_to_sof == 0) { - printf("SOF COMPLETE!\n"); - } - else { - printf("Need %u more bytes to complete a SOF\n", (unsigned)bytes_to_sof); - } - } - if (pixy_buf[2] != 0x55 && pixy_buf[3] != 0xAA) { - bytes_to_block = 14 - pixy_len; - if (bytes_to_block == 0) { - printf("BLOCK COMPLETE!\n"); - } - else { - printf("Need %u more bytes to complete a Block\n", (unsigned)bytes_to_sof); - } - } - if (pixy_len < 14) { // Looks for at least 14 bytes i.e. "sync+blob_data" = 2+12 bytes) - printf("Message Length less than 14.. Message Incomplete!\n"); - return MESSAGE_INCOMPLETE; - } - - if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { - - printf("2 syncs available and size >= 14..\n"); - - if (pixy_len >= 16) { - - printf("PixyLen Greater than or equal to 16 with 2 syncs, calculating crc....\n"); - /* check crc */ - uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 - for (size_t i = 6; i <= 15; i+=2) { - uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; - crc_calculated += word; - } - - uint16_t crc_provided; //Getting true crc by concatinating 4 & 5 message fields(original crc) into a single 16 bit - crc_provided = pixy_buf[4] | (uint16_t)pixy_buf[5]<<8; - if (crc_provided != crc_calculated) { - printf("CRC Failed Message Invalid!\n"); - return MESSAGE_INVALID; - } - return MESSAGE_VALID_SOF; - } else { - return MESSAGE_INCOMPLETE; - } - - - } else { - printf("Only 1 SYNC available and size < 16, calculating CRC....\n"); - - uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 - for (size_t i = 4; i <= 13; i+=2) { - uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; - crc_calculated += word; - } - uint16_t crc_provided; //Getting true crc by concatinating 4 & 5 message fields(original crc) into a single 16 bit - crc_provided = pixy_buf[2] | (uint16_t)pixy_buf[3]<<8; - printf("Crc calculated: %u Crc provided: %u\n", (unsigned)crc_calculated, (unsigned)crc_provided); - - if (crc_provided != crc_calculated) { - printf("CRC Failed Message Invalid!\n"); - return MESSAGE_INVALID; - } - return MESSAGE_VALID_BLOCK; - } -} - -void recv_byte_pixy(uint8_t byte) { -// printf("INSIDE recv_byte_pixy:-\n"); - -// Read 2 bytes - pixy_blob blob1; //%%%%%%%%%%%%%%%%%%%%$$$$$$$$$$$$$$$$$$$$$$$$-------------- should I put struct as prefix or not?-------------------------%%%%%%%%%$$$$$$$$$ - - struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; - - printf("The byte inputted is: %u and pixylen is %u\n", byte, (unsigned)pixy_len); - pixy_buf[pixy_len++] = byte; // Append byte to buffer - - enum message_validity_t validity = check_pixy_message(pixy_len); // Call parser - printf("Validity Check Call: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); - printf("Pixy Len: %u\n", (unsigned)pixy_len); - printf("Pixy_buf: "); - for (size_t i=0; i<17; i++) { - printf("%u, ", pixy_buf[i]); - } - printf("\n"); - - if (validity == MESSAGE_VALID_SOF) { -// pixy_frame_received(pixy_len, pixy_buf); - - if (!(writebuf.count >= 10)) { - if (writebuf.count != 0) { - swap_buffer(); //swap buffer - - blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; //Extract blob information - blob1.center_y = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; - blob1.width = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; - blob1.height = pixy_buf[14] | (uint16_t)pixy_buf[15]<<8; - - writebuf.count = 0; //Turn the count to 0 - printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); - - write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) - empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' - - } - else { - write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) - empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' - - printf("\n--------------------------AFTER EMPTY: "); - for (int i=0; i= 10)) { - blob1.center_x = pixy_buf[6] | (uint16_t)pixy_buf[7]<<8; //Extract blob information - blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; - blob1.width = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; - blob1.height = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; - printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); - - write_buffer(blob1); //Writing inside the buffer - empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' - - printf("\n------------------------------AFTER EMPTY: "); - for (int i=0; i Date: Thu, 29 Nov 2018 14:36:08 -0800 Subject: [PATCH 10/31] Fixed data integrity issue --- libraries/AP_IRLock/AP_IRLock_I2C.cpp | 54 +++++++-------------- libraries/AP_IRLock/pixy_parser.cpp | 69 ++++++++++++++------------- 2 files changed, 52 insertions(+), 71 deletions(-) diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.cpp b/libraries/AP_IRLock/AP_IRLock_I2C.cpp index 8e89667117..057417ff28 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.cpp +++ b/libraries/AP_IRLock/AP_IRLock_I2C.cpp @@ -28,9 +28,7 @@ extern const AP_HAL::HAL& hal; #define IRLOCK_I2C_ADDRESS 0x54 -#define IRLOCK_SYNC 0xAA55AA55 -#define IRLOCK_SYNC1 0xAA55 void AP_IRLock_I2C::init(int8_t bus) { if (bus < 0) { @@ -41,23 +39,12 @@ void AP_IRLock_I2C::init(int8_t bus) { if (!dev) { return; } - sem = hal.util->new_semaphore(); - // read at 50Hz // printf("Initializing IRLock on I2C\n"); - - dev->register_periodic_callback(20000, FUNCTOR_BIND_MEMBER(&AP_IRLock_I2C::read_frames, void)); + dev->register_periodic_callback(200, FUNCTOR_BIND_MEMBER(&AP_IRLock_I2C::read_frames, void)); } -/* - synchronise with frame start. We expect 0xAA55AA55 at the start of - a frame -*/ - - - - /* converts IRLOCK pixels to a position on a normal plane 1m in front of the lens based on a characterization of IR-LOCK with the standard lens, focused such that 2.38mm of threads are exposed @@ -72,37 +59,22 @@ void AP_IRLock_I2C::pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, fl void AP_IRLock_I2C::read_frames(void) { - uint8_t buf[142]; + uint8_t buf[16]; dev->transfer(nullptr, 0, buf, 16); - const pixy_parser::pixy_blob* temp; for (size_t i=0; i<16; i++) { pixyObj.recv_byte_pixy(buf[i]); - temp = pixyObj.read_buffer(i); - printf("\n\n\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); } - printf("\n&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&------------------OUT"); - printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); - - -// pixyObj.pixy_blob* temp = pixyObj.read_buffer(i); - - - - - - // printf("\nSTART: \n"); -// if (!sync_frame_once()) { //It just sync's the frame -// return; -// } - -// struct frame irframe; - -// if (!read_block(irframe)) { // Try reading blobs until I get a sync (Nope! does not work!) -// return; -// } + const pixy_parser::pixy_blob* temp; + temp = pixyObj.read_buffer(0); + if (temp != nullptr) { + printf("\n\n\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); + } +//} +// printf("\n&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&------------------OUT"); +// printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); int16_t corner1_pix_x = temp->center_x - temp->width/2; int16_t corner1_pix_y = temp->center_y - temp->height/2; @@ -123,6 +95,12 @@ void AP_IRLock_I2C::read_frames(void) { sem->give(); } + +// +// } +// + + } // retrieve latest sensor data - returns true if new data is available diff --git a/libraries/AP_IRLock/pixy_parser.cpp b/libraries/AP_IRLock/pixy_parser.cpp index e528668623..23015abcf5 100644 --- a/libraries/AP_IRLock/pixy_parser.cpp +++ b/libraries/AP_IRLock/pixy_parser.cpp @@ -44,6 +44,7 @@ pixy_parser::pixy_parser() { bytes_to_sof = 0; bytes_to_block = 0; blob_buffer[blob_buffer_write_idx].count = 0; +// if_swap_buffer = 0; } // Destructor - pixy_parser @@ -56,33 +57,33 @@ void pixy_parser::empty_pixyBuf() { } pixy_len = 0; - printf("\n--------------------------AFTER EMPTY: "); + // printf("\n--------------------------AFTER EMPTY: "); for (size_t i=0; i= 10) { return false; } writebuf.blobs[writebuf.count] = received_blob; - printf("SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); + // printf("SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); writebuf.count++; print_buffer(); return true; @@ -92,7 +93,7 @@ bool pixy_parser::write_buffer(const pixy_blob& received_blob) { // Blob buffer indexing swap void pixy_parser::swap_buffer() { blob_buffer_write_idx = (blob_buffer_write_idx+1)%2; - printf("Swapping Main Buffer: Swapped to %u\n", blob_buffer_write_idx); + // printf("Swapping Main Buffer: Swapped to %u\n", blob_buffer_write_idx); // struct blob_buffer* writebuf = &blob_buffer[blob_buffer_write_idx]; struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; writebuf.count = 0; //This is probably wront. But helps me get rid of an error!!!----------------------------------------------------------- @@ -102,7 +103,7 @@ void pixy_parser::swap_buffer() { // Method - read_buffer // - read blob i: const pixy_parser::pixy_blob* pixy_parser::read_buffer(size_t i) { - printf("Reading Main Buffer: Reading from %u\n", (blob_buffer_write_idx+1)%2); + // printf("Reading Main Buffer: Reading from %u\n", (blob_buffer_write_idx+1)%2); // struct blob_buffer* readbuf = &blob_buffer[(blob_buffer_write_idx+1)%2]; struct blob_buffer& readbuf = blob_buffer[(blob_buffer_write_idx+1)%2]; if (i >= readbuf.count) { @@ -113,49 +114,49 @@ const pixy_parser::pixy_blob* pixy_parser::read_buffer(size_t i) { // Method - check_pixy_message enum pixy_parser::message_validity_t pixy_parser::check_pixy_message() { -// printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); +// // printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); if (pixy_len == 0) { return MESSAGE_EMPTY; } if (pixy_len >= 1 && pixy_buf[0] != 0x55) { //checking if 1st byte of the message is 0x55 - printf("First block not 0x55 .. Message Invalid!\n"); + // printf("First block not 0x55 .. Message Invalid!\n"); return MESSAGE_INVALID; } if (pixy_len >= 2 && pixy_buf[1] != 0xAA) { //checking if 2nd byte of the message is 0xAA (Combined it verifies if the message is 0x55AA) - printf("Second block not 0xAA .. Message Invalid!\n"); + // printf("Second block not 0xAA .. Message Invalid!\n"); return MESSAGE_INVALID; } if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { bytes_to_sof = 16 - pixy_len; if (bytes_to_sof == 0) { - printf("SOF COMPLETE!\n"); + // printf("SOF COMPLETE!\n"); } else { - printf("Need %u more bytes to complete a SOF\n", (unsigned)bytes_to_sof); + // printf("Need %u more bytes to complete a SOF\n", (unsigned)bytes_to_sof); } } if (pixy_buf[2] != 0x55 && pixy_buf[3] != 0xAA) { bytes_to_block = 14 - pixy_len; if (bytes_to_block == 0) { - printf("BLOCK COMPLETE!\n"); + // printf("BLOCK COMPLETE!\n"); } else { - printf("Need %u more bytes to complete a Block\n", (unsigned)bytes_to_sof); + // printf("Need %u more bytes to complete a Block\n", (unsigned)bytes_to_sof); } } if (pixy_len < 14) { // Looks for at least 14 bytes i.e. "sync+blob_data" = 2+12 bytes) - printf("Message Length less than 14.. Message Incomplete!\n"); + // printf("Message Length less than 14.. Message Incomplete!\n"); return MESSAGE_INCOMPLETE; } if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { - printf("2 syncs available and size >= 14..\n"); + // printf("2 syncs available and size >= 14..\n"); if (pixy_len >= 16) { - printf("PixyLen Greater than or equal to 16 with 2 syncs, calculating crc....\n"); + // printf("PixyLen Greater than or equal to 16 with 2 syncs, calculating crc....\n"); /* check crc */ uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 for (size_t i = 6; i <= 15; i+=2) { @@ -166,7 +167,7 @@ enum pixy_parser::message_validity_t pixy_parser::check_pixy_message() { uint16_t crc_provided; //Getting true crc by concatinating 4 & 5 message fields(original crc) into a single 16 bit crc_provided = pixy_buf[4] | (uint16_t)pixy_buf[5]<<8; if (crc_provided != crc_calculated) { - printf("CRC Failed Message Invalid!\n"); + // printf("CRC Failed Message Invalid!\n"); return MESSAGE_INVALID; } return MESSAGE_VALID_SOF; @@ -176,7 +177,7 @@ enum pixy_parser::message_validity_t pixy_parser::check_pixy_message() { } else { - printf("Only 1 SYNC available and size < 16, calculating CRC....\n"); + // printf("Only 1 SYNC available and size < 16, calculating CRC....\n"); uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 for (size_t i = 4; i <= 13; i+=2) { @@ -185,10 +186,10 @@ enum pixy_parser::message_validity_t pixy_parser::check_pixy_message() { } uint16_t crc_provided; //Getting true crc by concatinating 4 & 5 message fields(original crc) into a single 16 bit crc_provided = pixy_buf[2] | (uint16_t)pixy_buf[3]<<8; - printf("Crc calculated: %u Crc provided: %u\n", (unsigned)crc_calculated, (unsigned)crc_provided); + // printf("Crc calculated: %u Crc provided: %u\n", (unsigned)crc_calculated, (unsigned)crc_provided); if (crc_provided != crc_calculated) { - printf("CRC Failed Message Invalid!\n"); + // printf("CRC Failed Message Invalid!\n"); return MESSAGE_INVALID; } return MESSAGE_VALID_BLOCK; @@ -197,14 +198,14 @@ enum pixy_parser::message_validity_t pixy_parser::check_pixy_message() { // Method - recv_byte_pixy void pixy_parser::recv_byte_pixy(uint8_t byte) { -// printf("INSIDE recv_byte_pixy:-\n"); +// // printf("INSIDE recv_byte_pixy:-\n"); // Read 2 bytes //%%%%%%%%%%%%%%%%%%%%$$$$$$$$$$$$$$$$$$$$$$$$-------------- should I put struct as prefix or not?-------------------------%%%%%%%%%$$$$$$$$$ struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; - printf("The byte inputted is: %u and pixylen is %u\n", byte, (unsigned)pixy_len); + // printf("The byte inputted is: %u and pixylen is %u\n", byte, (unsigned)pixy_len); PIXY_PARSER_ASSERT(pixy_len < PIXY_PARSER_PIXY_BUF_SIZE); if (pixy_len >= PIXY_PARSER_PIXY_BUF_SIZE) { @@ -215,13 +216,13 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { pixy_buf[pixy_len++] = byte; // Append byte to buffer enum message_validity_t validity = check_pixy_message(); // Call parser - printf("Validity Check Call: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); - printf("Pixy Len: %u\n", (unsigned)pixy_len); - printf("Pixy_buf: "); + // printf("Validity Check Call: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); + // printf("Pixy Len: %u\n", (unsigned)pixy_len); + // printf("Pixy_buf: "); for (size_t i=0; i= 10)) { @@ -233,9 +234,10 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { if (writebuf.count != 0) { swap_buffer(); //swap buffer +// if_swap_buffer = 1; writebuf.count = 0; //Turn the count to 0 - printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); + // printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); write_buffer(received_blob); //Writing inside the buffer(the count increment happens inside the write_buffer()) } @@ -253,7 +255,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { received_blob.center_y = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; received_blob.width = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; received_blob.height = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; - printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); + // printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); write_buffer(received_blob); //Writing inside the buffer } @@ -267,6 +269,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { if (writebuf.count < 10 && writebuf.count != 0) { swap_buffer(); //swap buffer +// if_swap_buffer = 1; } } } From fbdace84634690275d68a4a1392d432720f9e8a7 Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Fri, 30 Nov 2018 15:37:08 -0800 Subject: [PATCH 11/31] Added thread safe interface(between AC_Precland and pixy_parser) logic --- libraries/AP_IRLock/AP_IRLock_I2C.cpp | 87 ++++++++++++++++++-------- libraries/AP_IRLock/AP_IRLock_I2C.h | 2 + libraries/AP_IRLock/AP_IRLock_SITL.cpp | 10 +-- libraries/AP_IRLock/IRLock.cpp | 9 +-- libraries/AP_IRLock/IRLock.h | 6 +- libraries/AP_IRLock/pixy_parser.cpp | 7 ++- libraries/AP_IRLock/pixy_parser.h | 3 +- 7 files changed, 83 insertions(+), 41 deletions(-) diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.cpp b/libraries/AP_IRLock/AP_IRLock_I2C.cpp index 057417ff28..81e1f371ae 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.cpp +++ b/libraries/AP_IRLock/AP_IRLock_I2C.cpp @@ -56,44 +56,79 @@ void AP_IRLock_I2C::pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, fl 4.79331390531725e-6f*((pix_y - 100.0f)*(pix_y - 100.0f)) - 1.0f); } +//void AP_IRLock_I2C::convert_pixy_data(uint16_t x, uint16_t y, uint16_t w, uint16_t h) { +//} void AP_IRLock_I2C::read_frames(void) { uint8_t buf[16]; dev->transfer(nullptr, 0, buf, 16); + pixyObj.if_swap_buffer = 0; + for (size_t i=0; i<16; i++) { pixyObj.recv_byte_pixy(buf[i]); } - const pixy_parser::pixy_blob* temp; - temp = pixyObj.read_buffer(0); + // if (pixy parser just swapped buffers) { ----------$$ + // take semaphore -----------$$ + // CONVERT frame + // copy frame data from pixy parser to target info array + // update target_count + // update frame_timestamp_us -> uint32_t timestamp_us = micros(); + // give semaphore + // } + + + // printf("\n----IF_SWAP: %d", pixyObj.if_swap_buffer); + if (pixyObj.if_swap_buffer) { + if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { // take semaphore + + const pixy_parser::pixy_blob* temp; + temp = pixyObj.read_buffer(0); + + if (temp != nullptr) { + printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); + +// convert_pixy_data(temp->center_x, temp->center_y, temp->width, temp->height); // CONVERT frame + +//--------------------- + int16_t corner1_pix_x = temp->center_x - temp->width/2; + int16_t corner1_pix_y = temp->center_y - temp->height/2; + int16_t corner2_pix_x = temp->center_x + temp->width/2; + int16_t corner2_pix_y = temp->center_y + temp->height/2; + float corner1_pos_x, corner1_pos_y, corner2_pos_x, corner2_pos_y; + pixel_to_1M_plane(corner1_pix_x, corner1_pix_y, corner1_pos_x, corner1_pos_y); + pixel_to_1M_plane(corner2_pix_x, corner2_pix_y, corner2_pos_x, corner2_pos_y); +//--------------------- + + _target_info[target_count].pos_x = 0.5f*(corner1_pos_x+corner2_pos_x); // copy frame data from pixy parser to target info array + _target_info[target_count].pos_y = 0.5f*(corner1_pos_y+corner2_pos_y); + _target_info[target_count].size_x = corner2_pos_x-corner1_pos_x; + _target_info[target_count].size_x = corner2_pos_y-corner1_pos_y; + + target_count++; // update target_count + + _target_info[target_count].timestamp = AP_HAL::micros(); // update frame_timestamp_us + + sem->give(); // give semaphore + + } + } + } - if (temp != nullptr) { - printf("\n\n\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); - } -//} -// printf("\n&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&------------------OUT"); -// printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); - int16_t corner1_pix_x = temp->center_x - temp->width/2; - int16_t corner1_pix_y = temp->center_y - temp->height/2; - int16_t corner2_pix_x = temp->center_x + temp->width/2; - int16_t corner2_pix_y = temp->center_y + temp->height/2; +/* + copy_pixy_data_to_target(); + } + } + } - float corner1_pos_x, corner1_pos_y, corner2_pos_x, corner2_pos_y; - pixel_to_1M_plane(corner1_pix_x, corner1_pix_y, corner1_pos_x, corner1_pos_y); - pixel_to_1M_plane(corner2_pix_x, corner2_pix_y, corner2_pos_x, corner2_pos_y); +*/ - if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { - /* convert to angles */ - _target_info.timestamp = AP_HAL::millis(); - _target_info.pos_x = 0.5f*(corner1_pos_x+corner2_pos_x); - _target_info.pos_y = 0.5f*(corner1_pos_y+corner2_pos_y); - _target_info.size_x = corner2_pos_x-corner1_pos_x; - _target_info.size_y = corner2_pos_y-corner1_pos_y; - sem->give(); - } +//} +// printf("\n&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&------------------OUT"); +// printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); // @@ -110,10 +145,10 @@ bool AP_IRLock_I2C::update() { return false; } if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { - if (_last_update_ms != _target_info.timestamp) { + if (_last_update_ms != _target_info[0].timestamp) { new_data = true; } - _last_update_ms = _target_info.timestamp; + _last_update_ms = _target_info[0].timestamp; _flags.healthy = (AP_HAL::millis() - _last_read_ms < 100); sem->give(); } diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.h b/libraries/AP_IRLock/AP_IRLock_I2C.h index bccb507dca..6032118e83 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.h +++ b/libraries/AP_IRLock/AP_IRLock_I2C.h @@ -23,7 +23,9 @@ class AP_IRLock_I2C : public IRLock void read_frames(void); void pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, float &ret_y); +// void convert_pixy_data(uint16_t x, uint16_t y, uint16_t w, uint16_t h); AP_HAL::Semaphore *sem; uint32_t _last_read_ms; + size_t target_count; }; \ No newline at end of file diff --git a/libraries/AP_IRLock/AP_IRLock_SITL.cpp b/libraries/AP_IRLock/AP_IRLock_SITL.cpp index 5601347e2a..c6d6f31cca 100644 --- a/libraries/AP_IRLock/AP_IRLock_SITL.cpp +++ b/libraries/AP_IRLock/AP_IRLock_SITL.cpp @@ -69,11 +69,11 @@ bool AP_IRLock_SITL::update() if (s == sizeof(irlock_packet) && pkt.timestamp > _last_timestamp) { // fprintf(stderr, " posx %f posy %f sizex %f sizey %f\n", pkt.pos_x, pkt.pos_y, pkt.size_x, pkt.size_y); - _target_info.timestamp = pkt.timestamp; - _target_info.pos_x = pkt.pos_x; - _target_info.pos_y = pkt.pos_y; - _target_info.size_x = pkt.size_x; - _target_info.size_y = pkt.size_y; + _target_info[0].timestamp = pkt.timestamp; + _target_info[0].pos_x = pkt.pos_x; + _target_info[0].pos_y = pkt.pos_y; + _target_info[0].size_x = pkt.size_x; + _target_info[0].size_y = pkt.size_y; _last_timestamp = pkt.timestamp; _last_update_ms = _last_timestamp; new_data = true; diff --git a/libraries/AP_IRLock/IRLock.cpp b/libraries/AP_IRLock/IRLock.cpp index 7bdddc15d3..63feca3f40 100644 --- a/libraries/AP_IRLock/IRLock.cpp +++ b/libraries/AP_IRLock/IRLock.cpp @@ -1,3 +1,4 @@ + /* * IRLock.cpp * @@ -17,8 +18,8 @@ bool IRLock::get_angle_to_target_rad(float &x_angle_rad, float &y_angle_rad) con } // use data from first (largest) object - x_angle_rad = atanf(_target_info.pos_x); - y_angle_rad = atanf(_target_info.pos_y); + x_angle_rad = atanf(_target_info[0].pos_x); + y_angle_rad = atanf(_target_info[0].pos_y); return true; } @@ -32,8 +33,8 @@ bool IRLock::get_unit_vector_body(Vector3f& ret) const } // use data from first (largest) object - ret.x = -_target_info.pos_y; - ret.y = _target_info.pos_x; + ret.x = -_target_info[0].pos_y; + ret.y = _target_info[0].pos_x; ret.z = 1.0f; ret /= ret.length(); return true; diff --git a/libraries/AP_IRLock/IRLock.h b/libraries/AP_IRLock/IRLock.h index 6d888b2568..56ba58a925 100644 --- a/libraries/AP_IRLock/IRLock.h +++ b/libraries/AP_IRLock/IRLock.h @@ -1,3 +1,4 @@ + /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by @@ -60,7 +61,7 @@ class IRLock uint32_t _last_update_ms; // irlock_target_info is a duplicate of the PX4Firmware irlock_s structure - typedef struct { + struct irlock_target_info { uint32_t timestamp; // milliseconds since system start float pos_x; // x-axis distance from center of image to center of target in units of tan(theta) float pos_y; // y-axis distance from center of image to center of target in units of tan(theta) @@ -68,5 +69,6 @@ class IRLock float size_y; // size of target along y-axis in units of tan(theta) } irlock_target_info; - irlock_target_info _target_info; + struct irlock_target_info _target_info[10]; + }; diff --git a/libraries/AP_IRLock/pixy_parser.cpp b/libraries/AP_IRLock/pixy_parser.cpp index 23015abcf5..795b87fc30 100644 --- a/libraries/AP_IRLock/pixy_parser.cpp +++ b/libraries/AP_IRLock/pixy_parser.cpp @@ -44,7 +44,7 @@ pixy_parser::pixy_parser() { bytes_to_sof = 0; bytes_to_block = 0; blob_buffer[blob_buffer_write_idx].count = 0; -// if_swap_buffer = 0; + if_swap_buffer = 0; } // Destructor - pixy_parser @@ -201,6 +201,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { // // printf("INSIDE recv_byte_pixy:-\n"); // Read 2 bytes //%%%%%%%%%%%%%%%%%%%%$$$$$$$$$$$$$$$$$$$$$$$$-------------- should I put struct as prefix or not?-------------------------%%%%%%%%%$$$$$$$$$ +// printf("\n---- IF_SWAP BEFORE: %d", if_swap_buffer); struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; @@ -234,7 +235,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { if (writebuf.count != 0) { swap_buffer(); //swap buffer -// if_swap_buffer = 1; + if_swap_buffer = 1; writebuf.count = 0; //Turn the count to 0 // printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); @@ -269,7 +270,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { if (writebuf.count < 10 && writebuf.count != 0) { swap_buffer(); //swap buffer -// if_swap_buffer = 1; + if_swap_buffer = 1; } } } diff --git a/libraries/AP_IRLock/pixy_parser.h b/libraries/AP_IRLock/pixy_parser.h index 46412bd98a..9b5c72952d 100644 --- a/libraries/AP_IRLock/pixy_parser.h +++ b/libraries/AP_IRLock/pixy_parser.h @@ -27,6 +27,7 @@ */ class pixy_parser { public: + bool if_swap_buffer; typedef struct { uint16_t center_x; @@ -72,7 +73,7 @@ class pixy_parser { }; - + From 678deb4c2fb473258aea7f47cc5312ddb6c8c500 Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Mon, 3 Dec 2018 17:35:24 -0800 Subject: [PATCH 12/31] Pixy parser driver complete, still needs testing --- libraries/AP_IRLock/AP_IRLock_I2C.cpp | 107 +++++++++----------------- libraries/AP_IRLock/AP_IRLock_I2C.h | 2 +- libraries/AP_IRLock/IRLock.h | 6 +- libraries/AP_IRLock/pixy_parser.cpp | 55 +++++-------- libraries/AP_IRLock/pixy_parser.h | 23 +----- 5 files changed, 62 insertions(+), 131 deletions(-) diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.cpp b/libraries/AP_IRLock/AP_IRLock_I2C.cpp index 81e1f371ae..c00df6a1b8 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.cpp +++ b/libraries/AP_IRLock/AP_IRLock_I2C.cpp @@ -56,85 +56,50 @@ void AP_IRLock_I2C::pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, fl 4.79331390531725e-6f*((pix_y - 100.0f)*(pix_y - 100.0f)) - 1.0f); } -//void AP_IRLock_I2C::convert_pixy_data(uint16_t x, uint16_t y, uint16_t w, uint16_t h) { -//} +void AP_IRLock_I2C::copy_frame_from_parser() { + for (size_t i=0; i<10; i++) { + pixy_parser::pixy_blob blob; + if (!pixyObj.read_buffer(i, blob)) { + break; + } + int16_t corner1_pix_x = blob.center_x - blob.width/2; // 3. CONVERT frame + int16_t corner1_pix_y = blob.center_y - blob.height/2; + int16_t corner2_pix_x = blob.center_x + blob.width/2; + int16_t corner2_pix_y = blob.center_y + blob.height/2; + float corner1_pos_x, corner1_pos_y, corner2_pos_x, corner2_pos_y; + pixel_to_1M_plane(corner1_pix_x, corner1_pix_y, corner1_pos_x, corner1_pos_y); + pixel_to_1M_plane(corner2_pix_x, corner2_pix_y, corner2_pos_x, corner2_pos_y); -void AP_IRLock_I2C::read_frames(void) { - uint8_t buf[16]; - dev->transfer(nullptr, 0, buf, 16); + _target_info[target_count].pos_x = 0.5f*(corner1_pos_x+corner2_pos_x); // 4. copy frame data from pixy parser to target info array + _target_info[target_count].pos_y = 0.5f*(corner1_pos_y+corner2_pos_y); + _target_info[target_count].size_x = corner2_pos_x-corner1_pos_x; + _target_info[target_count].size_x = corner2_pos_y-corner1_pos_y; - pixyObj.if_swap_buffer = 0; + target_count = i+1; - for (size_t i=0; i<16; i++) { - pixyObj.recv_byte_pixy(buf[i]); - } +// printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); + printf("\nBLOCK:- \nX: %03u - Y: %03u - W: %03u - H: %03u\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); - // if (pixy parser just swapped buffers) { ----------$$ - // take semaphore -----------$$ - // CONVERT frame - // copy frame data from pixy parser to target info array - // update target_count - // update frame_timestamp_us -> uint32_t timestamp_us = micros(); - // give semaphore - // } - - - // printf("\n----IF_SWAP: %d", pixyObj.if_swap_buffer); - if (pixyObj.if_swap_buffer) { - if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { // take semaphore - - const pixy_parser::pixy_blob* temp; - temp = pixyObj.read_buffer(0); - - if (temp != nullptr) { - printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); - -// convert_pixy_data(temp->center_x, temp->center_y, temp->width, temp->height); // CONVERT frame - -//--------------------- - int16_t corner1_pix_x = temp->center_x - temp->width/2; - int16_t corner1_pix_y = temp->center_y - temp->height/2; - int16_t corner2_pix_x = temp->center_x + temp->width/2; - int16_t corner2_pix_y = temp->center_y + temp->height/2; - float corner1_pos_x, corner1_pos_y, corner2_pos_x, corner2_pos_y; - pixel_to_1M_plane(corner1_pix_x, corner1_pix_y, corner1_pos_x, corner1_pos_y); - pixel_to_1M_plane(corner2_pix_x, corner2_pix_y, corner2_pos_x, corner2_pos_y); -//--------------------- - - _target_info[target_count].pos_x = 0.5f*(corner1_pos_x+corner2_pos_x); // copy frame data from pixy parser to target info array - _target_info[target_count].pos_y = 0.5f*(corner1_pos_y+corner2_pos_y); - _target_info[target_count].size_x = corner2_pos_x-corner1_pos_x; - _target_info[target_count].size_x = corner2_pos_y-corner1_pos_y; - - target_count++; // update target_count - - _target_info[target_count].timestamp = AP_HAL::micros(); // update frame_timestamp_us - - sem->give(); // give semaphore - - } - } - } + } + _frame_timestamp = AP_HAL::micros(); // 6. update frame_timestamp_us +} +void AP_IRLock_I2C::read_frames(void) { + uint8_t buf[16]; + dev->transfer(nullptr, 0, buf, 16); -/* - copy_pixy_data_to_target(); - } - } + for (size_t i=0; i<16; i++) { + if (pixyObj.recv_byte_pixy(buf[i])) { + if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { // 2. take semaphore + copy_frame_from_parser(); + sem->give(); // 7. give semaphore + } } + } -*/ - -//} // printf("\n&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&------------------OUT"); -// printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); - - -// -// } -// - +// printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); } @@ -145,10 +110,10 @@ bool AP_IRLock_I2C::update() { return false; } if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { - if (_last_update_ms != _target_info[0].timestamp) { + if (_last_update_ms != _frame_timestamp) { new_data = true; } - _last_update_ms = _target_info[0].timestamp; + _last_update_ms = _frame_timestamp; _flags.healthy = (AP_HAL::millis() - _last_read_ms < 100); sem->give(); } diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.h b/libraries/AP_IRLock/AP_IRLock_I2C.h index 6032118e83..6707fc8b78 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.h +++ b/libraries/AP_IRLock/AP_IRLock_I2C.h @@ -22,8 +22,8 @@ class AP_IRLock_I2C : public IRLock AP_HAL::OwnPtr dev; void read_frames(void); + void copy_frame_from_parser(void); void pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, float &ret_y); -// void convert_pixy_data(uint16_t x, uint16_t y, uint16_t w, uint16_t h); AP_HAL::Semaphore *sem; uint32_t _last_read_ms; diff --git a/libraries/AP_IRLock/IRLock.h b/libraries/AP_IRLock/IRLock.h index 56ba58a925..5d87748ba2 100644 --- a/libraries/AP_IRLock/IRLock.h +++ b/libraries/AP_IRLock/IRLock.h @@ -59,16 +59,16 @@ class IRLock // internals uint32_t _last_update_ms; + uint32_t _frame_timestamp; // milliseconds since system start // irlock_target_info is a duplicate of the PX4Firmware irlock_s structure - struct irlock_target_info { - uint32_t timestamp; // milliseconds since system start + typedef struct { float pos_x; // x-axis distance from center of image to center of target in units of tan(theta) float pos_y; // y-axis distance from center of image to center of target in units of tan(theta) float size_x; // size of target along x-axis in units of tan(theta) float size_y; // size of target along y-axis in units of tan(theta) } irlock_target_info; - struct irlock_target_info _target_info[10]; + irlock_target_info _target_info[10]; }; diff --git a/libraries/AP_IRLock/pixy_parser.cpp b/libraries/AP_IRLock/pixy_parser.cpp index 795b87fc30..912d8dd7a3 100644 --- a/libraries/AP_IRLock/pixy_parser.cpp +++ b/libraries/AP_IRLock/pixy_parser.cpp @@ -41,15 +41,9 @@ pixy_parser::pixy_parser() { pixy_len = 0; blob_buffer_write_idx = 0; - bytes_to_sof = 0; - bytes_to_block = 0; blob_buffer[blob_buffer_write_idx].count = 0; - if_swap_buffer = 0; } -// Destructor - pixy_parser -pixy_parser::~pixy_parser() { } - // Method - empty_pixyBuf void pixy_parser::empty_pixyBuf() { for (size_t i=0; i= 10) { + if (writebuf.count >= PIXY_PARSER_MAX_BLOBS) { return false; } writebuf.blobs[writebuf.count] = received_blob; @@ -102,17 +96,19 @@ void pixy_parser::swap_buffer() { // Method - read_buffer // - read blob i: -const pixy_parser::pixy_blob* pixy_parser::read_buffer(size_t i) { + bool pixy_parser::read_buffer(size_t i, pixy_parser::pixy_blob& ret) { // printf("Reading Main Buffer: Reading from %u\n", (blob_buffer_write_idx+1)%2); // struct blob_buffer* readbuf = &blob_buffer[(blob_buffer_write_idx+1)%2]; struct blob_buffer& readbuf = blob_buffer[(blob_buffer_write_idx+1)%2]; - if (i >= readbuf.count) { - return NULL; + if ( i >= PIXY_PARSER_MAX_BLOBS || i >= readbuf.count) { + return false; } - return &readbuf.blobs[i]; + ret = readbuf.blobs[i]; + return true; } // Method - check_pixy_message +// Checks Validity of a inpyt byte stream enum pixy_parser::message_validity_t pixy_parser::check_pixy_message() { // // printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); @@ -127,24 +123,6 @@ enum pixy_parser::message_validity_t pixy_parser::check_pixy_message() { // printf("Second block not 0xAA .. Message Invalid!\n"); return MESSAGE_INVALID; } - if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { - bytes_to_sof = 16 - pixy_len; - if (bytes_to_sof == 0) { - // printf("SOF COMPLETE!\n"); - } - else { - // printf("Need %u more bytes to complete a SOF\n", (unsigned)bytes_to_sof); - } - } - if (pixy_buf[2] != 0x55 && pixy_buf[3] != 0xAA) { - bytes_to_block = 14 - pixy_len; - if (bytes_to_block == 0) { - // printf("BLOCK COMPLETE!\n"); - } - else { - // printf("Need %u more bytes to complete a Block\n", (unsigned)bytes_to_sof); - } - } if (pixy_len < 14) { // Looks for at least 14 bytes i.e. "sync+blob_data" = 2+12 bytes) // printf("Message Length less than 14.. Message Incomplete!\n"); return MESSAGE_INCOMPLETE; @@ -197,10 +175,10 @@ enum pixy_parser::message_validity_t pixy_parser::check_pixy_message() { } // Method - recv_byte_pixy -void pixy_parser::recv_byte_pixy(uint8_t byte) { +// Logicbase of Pixy_parser. Receives the byte from here and adds into pixyBuf if valid. +bool pixy_parser::recv_byte_pixy(uint8_t byte) { // // printf("INSIDE recv_byte_pixy:-\n"); // Read 2 bytes - //%%%%%%%%%%%%%%%%%%%%$$$$$$$$$$$$$$$$$$$$$$$$-------------- should I put struct as prefix or not?-------------------------%%%%%%%%%$$$$$$$$$ // printf("\n---- IF_SWAP BEFORE: %d", if_swap_buffer); struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; @@ -220,13 +198,13 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { // printf("Validity Check Call: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); // printf("Pixy Len: %u\n", (unsigned)pixy_len); // printf("Pixy_buf: "); - for (size_t i=0; i= 10)) { + if (!(writebuf.count >= PIXY_PARSER_MAX_BLOBS)) { pixy_blob received_blob; received_blob.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; //Extract blob information received_blob.center_y = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; @@ -241,6 +219,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { // printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); write_buffer(received_blob); //Writing inside the buffer(the count increment happens inside the write_buffer()) + return true; } else { write_buffer(received_blob); //Writing inside the buffer(the count increment happens inside the write_buffer()) @@ -250,7 +229,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { } if (validity == MESSAGE_VALID_BLOCK) { ///-----------------------------how can I store the block inside a frame?----------------- - if (!(writebuf.count >= 10)) { + if (!(writebuf.count >= PIXY_PARSER_MAX_BLOBS)) { pixy_blob received_blob; received_blob.center_x = pixy_buf[6] | (uint16_t)pixy_buf[7]<<8; //Extract blob information received_blob.center_y = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; @@ -260,7 +239,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { write_buffer(received_blob); //Writing inside the buffer } - empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' + empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' } if (validity == MESSAGE_INVALID) { // If message invalid, wait and read 2 bytes @@ -268,9 +247,11 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { memmove(pixy_buf, pixy_buf+1, pixy_len); // This discards the first block of the pixy_buf and makes pixy_buf have everything except the fisrt block value validity = check_pixy_message(); - if (writebuf.count < 10 && writebuf.count != 0) { + if (writebuf.count < PIXY_PARSER_MAX_BLOBS && writebuf.count != 0) { swap_buffer(); //swap buffer if_swap_buffer = 1; + return true; } } + return false; } diff --git a/libraries/AP_IRLock/pixy_parser.h b/libraries/AP_IRLock/pixy_parser.h index 9b5c72952d..d0a6c3c99b 100644 --- a/libraries/AP_IRLock/pixy_parser.h +++ b/libraries/AP_IRLock/pixy_parser.h @@ -15,20 +15,10 @@ #include #define PIXY_PARSER_PIXY_BUF_SIZE 17 +#define PIXY_PARSER_MAX_BLOBS 10 -/* - pixy_buf_size = 17; - pixy_buf[17]= {}; - pixy_len = 0; - blob_buffer_write_idx = 0; - bytes_to_sof = 0; - bytes_to_block = 0; -} -*/ class pixy_parser { public: - bool if_swap_buffer; - typedef struct { uint16_t center_x; uint16_t center_y; @@ -37,19 +27,16 @@ class pixy_parser { } pixy_blob; pixy_parser(); - ~pixy_parser(); void empty_pixyBuf(void); void print_buffer(void); void swap_buffer(void); - void recv_byte_pixy(uint8_t byte); - const pixy_blob* read_buffer(size_t i); - - + bool recv_byte_pixy(uint8_t byte); + bool read_buffer(size_t i, pixy_blob& ret); private: struct blob_buffer { //Frame (full of blobs) - pixy_blob blobs[10]; + pixy_blob blobs[PIXY_PARSER_MAX_BLOBS]; size_t count; } blob_buffer[2]; @@ -68,8 +55,6 @@ class pixy_parser { uint8_t pixy_buf[PIXY_PARSER_PIXY_BUF_SIZE]; size_t pixy_len; uint8_t blob_buffer_write_idx; - size_t bytes_to_sof; - size_t bytes_to_block; }; From d708c47dd983ffd2c47423fd900493c6bb6e5e49 Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Tue, 4 Dec 2018 15:30:56 -0800 Subject: [PATCH 13/31] Pixy_parser driver code-complete, solved semaphore block issue (print statements caused sem block) --- libraries/AP_IRLock/AP_IRLock_I2C.cpp | 31 +++++++++++++++++++++------ libraries/AP_IRLock/pixy_parser.cpp | 14 ++++++------ 2 files changed, 32 insertions(+), 13 deletions(-) diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.cpp b/libraries/AP_IRLock/AP_IRLock_I2C.cpp index c00df6a1b8..b9cc15458d 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.cpp +++ b/libraries/AP_IRLock/AP_IRLock_I2C.cpp @@ -1,4 +1,4 @@ -/* + /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or @@ -31,6 +31,7 @@ extern const AP_HAL::HAL& hal; void AP_IRLock_I2C::init(int8_t bus) { + // printf("\nINIT"); if (bus < 0) { // default to i2c external bus bus = 1; @@ -41,8 +42,9 @@ void AP_IRLock_I2C::init(int8_t bus) { } sem = hal.util->new_semaphore(); -// printf("Initializing IRLock on I2C\n"); +// // printf("Initializing IRLock on I2C\n"); dev->register_periodic_callback(200, FUNCTOR_BIND_MEMBER(&AP_IRLock_I2C::read_frames, void)); + // printf("\nINIT END -----"); } /* @@ -50,13 +52,17 @@ void AP_IRLock_I2C::init(int8_t bus) { based on a characterization of IR-LOCK with the standard lens, focused such that 2.38mm of threads are exposed */ void AP_IRLock_I2C::pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, float &ret_y) { + // printf("\nPIXEL TO 1M PLANE"); + ret_x = (-0.00293875727162397f*pix_x + 0.470201163459835f)/(4.43013552642296e-6f*((pix_x - 160.0f)*(pix_x - 160.0f)) + 4.79331390531725e-6f*((pix_y - 100.0f)*(pix_y - 100.0f)) - 1.0f); ret_y = (-0.003056843086277f*pix_y + 0.3056843086277f)/(4.43013552642296e-6f*((pix_x - 160.0f)*(pix_x - 160.0f)) + 4.79331390531725e-6f*((pix_y - 100.0f)*(pix_y - 100.0f)) - 1.0f); + // printf("\nPIXEL TO 1M PLANE END-----"); } void AP_IRLock_I2C::copy_frame_from_parser() { + // printf("\nCOPY FRAME FROM PARSER"); for (size_t i=0; i<10; i++) { pixy_parser::pixy_blob blob; if (!pixyObj.read_buffer(i, blob)) { @@ -78,33 +84,43 @@ void AP_IRLock_I2C::copy_frame_from_parser() { target_count = i+1; -// printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); - printf("\nBLOCK:- \nX: %03u - Y: %03u - W: %03u - H: %03u\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); +// // printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); + // printf("\nBLOCK:- \nX: %03u - Y: %03u - W: %03u - H: %03u\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); } _frame_timestamp = AP_HAL::micros(); // 6. update frame_timestamp_us + // printf("\nCOPY FRAME FROM PARSER END----"); + } void AP_IRLock_I2C::read_frames(void) { + // printf("\nREAD FRAMES"); uint8_t buf[16]; dev->transfer(nullptr, 0, buf, 16); + // printf("\nUPDATE CALL AFTER"); for (size_t i=0; i<16; i++) { if (pixyObj.recv_byte_pixy(buf[i])) { + // printf("\nREAD FRAMES BEFORE SEMAPHORE"); + if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { // 2. take semaphore copy_frame_from_parser(); sem->give(); // 7. give semaphore + // printf("\nGIVE SEMAPHORE"); + } } } + // printf("\nREAD FRAMES END -----"); -// printf("\n&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&------------------OUT"); -// printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); +// // printf("\n&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&------------------OUT"); +// // printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", blob.center_yr_x, blob.center_y, blob.width, blob.height); } // retrieve latest sensor data - returns true if new data is available bool AP_IRLock_I2C::update() { + // printf("\nUPDATE"); bool new_data = false; if (!dev || !sem) { return false; @@ -118,5 +134,6 @@ bool AP_IRLock_I2C::update() { sem->give(); } // return true if new data found + // printf("\nUPDATE END ----"); return new_data; -} \ No newline at end of file +} \ No newline at end of file diff --git a/libraries/AP_IRLock/pixy_parser.cpp b/libraries/AP_IRLock/pixy_parser.cpp index 912d8dd7a3..0e1e1807c2 100644 --- a/libraries/AP_IRLock/pixy_parser.cpp +++ b/libraries/AP_IRLock/pixy_parser.cpp @@ -180,7 +180,7 @@ bool pixy_parser::recv_byte_pixy(uint8_t byte) { // // printf("INSIDE recv_byte_pixy:-\n"); // Read 2 bytes // printf("\n---- IF_SWAP BEFORE: %d", if_swap_buffer); - + bool if_swap = 0; struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; @@ -213,13 +213,14 @@ bool pixy_parser::recv_byte_pixy(uint8_t byte) { if (writebuf.count != 0) { swap_buffer(); //swap buffer - if_swap_buffer = 1; +// if_swap_buffer = 1; + if_swap = 1; writebuf.count = 0; //Turn the count to 0 // printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); write_buffer(received_blob); //Writing inside the buffer(the count increment happens inside the write_buffer()) - return true; +// return true; } else { write_buffer(received_blob); //Writing inside the buffer(the count increment happens inside the write_buffer()) @@ -249,9 +250,10 @@ bool pixy_parser::recv_byte_pixy(uint8_t byte) { if (writebuf.count < PIXY_PARSER_MAX_BLOBS && writebuf.count != 0) { swap_buffer(); //swap buffer - if_swap_buffer = 1; - return true; +// if_swap_buffer = 1; + if_swap = 1; +// return true; } } - return false; + return if_swap; } From 450780d1fb405c46a59271f34b8a23ff057c80e1 Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Fri, 7 Dec 2018 13:38:42 -0800 Subject: [PATCH 14/31] Added multi-target detection and contingency landing logic. Pixycam driver completed. Ready for Live testing --- libraries/AC_PrecLand/AC_PrecLand.cpp | 16 +++- libraries/AC_PrecLand/AC_PrecLand.h | 3 + libraries/AC_PrecLand/AC_PrecLand_Backend.h | 4 +- .../AC_PrecLand/AC_PrecLand_Companion.cpp | 3 +- libraries/AC_PrecLand/AC_PrecLand_Companion.h | 3 +- libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp | 87 ++++++++++++++++++- libraries/AC_PrecLand/AC_PrecLand_IRLock.h | 12 ++- libraries/AP_IRLock/AP_IRLock_I2C.cpp | 25 +++--- libraries/AP_IRLock/AP_IRLock_I2C.h | 5 +- libraries/AP_IRLock/IRLock.cpp | 20 +++++ libraries/AP_IRLock/IRLock.h | 3 +- libraries/AP_IRLock/pixy_parser.cpp | 11 +++ libraries/AP_IRLock/pixy_parser.h | 4 +- 13 files changed, 171 insertions(+), 25 deletions(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index e9d51427e9..e30beb4f60 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -10,6 +10,8 @@ #include #endif +//param show PLND_type + extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AC_PrecLand::var_info[] = { @@ -177,8 +179,7 @@ void AC_PrecLand::update(float rangefinder_alt_cm, bool rangefinder_alt_valid) } } -bool AC_PrecLand::target_acquired() -{ +bool AC_PrecLand::target_acquired() { if ((AP_HAL::millis()-_last_update_ms) >= 2000) { _estimator_initialized = false; _target_acquired = false; @@ -187,6 +188,17 @@ bool AC_PrecLand::target_acquired() return _target_acquired; } +void AC_PrecLand::set_target_acquired(bool _target_acquired_value) { + if (_target_acquired_value == false) { + _target_acquired = _target_acquired_value; + _estimator_initialized = false; + } + else { + _target_acquired = _target_acquired_value; + } +} + + bool AC_PrecLand::get_height_above_target_cm(int32_t& ret) { #if !HAL_WITH_UAVCAN return false; diff --git a/libraries/AC_PrecLand/AC_PrecLand.h b/libraries/AC_PrecLand/AC_PrecLand.h index 05cecd4b03..7e352ea8dc 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.h +++ b/libraries/AC_PrecLand/AC_PrecLand.h @@ -77,6 +77,9 @@ class AC_PrecLand // returns true when the landing target has been detected bool target_acquired(); + // sets the value of _target_acquired + void set_target_acquired(bool _target_acquired_value); + // process a LANDING_TARGET mavlink message void handle_msg(mavlink_message_t* msg); diff --git a/libraries/AC_PrecLand/AC_PrecLand_Backend.h b/libraries/AC_PrecLand/AC_PrecLand_Backend.h index e38ee89edc..2ec18760c7 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Backend.h +++ b/libraries/AC_PrecLand/AC_PrecLand_Backend.h @@ -10,7 +10,7 @@ class AC_PrecLand_Backend { public: // Constructor - AC_PrecLand_Backend(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state) : + AC_PrecLand_Backend(AC_PrecLand& frontend, AC_PrecLand::precland_state& state) : _frontend(frontend), _state(state) {} @@ -43,6 +43,6 @@ class AC_PrecLand_Backend int8_t get_bus(void) const { return _frontend._bus.get(); } protected: - const AC_PrecLand& _frontend; // reference to precision landing front end + AC_PrecLand& _frontend; // reference to precision landing front end AC_PrecLand::precland_state &_state; // reference to this instances state }; diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp index 05c2122950..b64544ca9c 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp @@ -1,10 +1,11 @@ + #include #include "AC_PrecLand_Companion.h" extern const AP_HAL::HAL& hal; // Constructor -AC_PrecLand_Companion::AC_PrecLand_Companion(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state) +AC_PrecLand_Companion::AC_PrecLand_Companion(AC_PrecLand& frontend, AC_PrecLand::precland_state& state) : AC_PrecLand_Backend(frontend, state), _timestamp_us(0), _distance_to_target(0.0f), diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.h b/libraries/AC_PrecLand/AC_PrecLand_Companion.h index 5b45e03e09..939980482c 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.h +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.h @@ -1,3 +1,4 @@ + #pragma once #include @@ -13,7 +14,7 @@ class AC_PrecLand_Companion : public AC_PrecLand_Backend { public: // Constructor - AC_PrecLand_Companion(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state); + AC_PrecLand_Companion(AC_PrecLand& frontend, AC_PrecLand::precland_state& state); // perform any required initialisation of backend void init() override; diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp index bc014a3e23..ba511c63d9 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp @@ -1,23 +1,59 @@ + #include #include "AC_PrecLand_IRLock.h" extern const AP_HAL::HAL& hal; // Constructor -AC_PrecLand_IRLock::AC_PrecLand_IRLock(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state) +AC_PrecLand_IRLock::AC_PrecLand_IRLock(AC_PrecLand& frontend, AC_PrecLand::precland_state& state) : AC_PrecLand_Backend(frontend, state), irlock(), _have_los_meas(false), - _los_meas_time_ms(0) + _los_meas_time_ms(0), +// _multiple_target_start_flag(false), +// _multiple_target_timestamp_start(0), +// _multiple_target_timestamp_latest(0), + _multiple_target_timestamp_log(), + _index(0) { } // init - perform initialisation of this backend -void AC_PrecLand_IRLock::init() +void AC_PrecLand_IRLock::init() { irlock.init(get_bus()); } + +void AC_PrecLand_IRLock::multiple_target_check() +{ + if (_index == 24) { + _index = 0; + } + _multiple_target_timestamp_log[_index] = irlock.num_targets(); + _index++; + + printf("\n _multiple_target_timestamp_log: "); + for (size_t j=0; j<24; j++) { + printf("%u ", _multiple_target_timestamp_log[j]); + } + + size_t count = 0; + for (size_t j=0; j<24; j++) { + if (_multiple_target_timestamp_log[j] > 1) { + count++; + } + } + uint16_t multiple_target_count_percentage = count*100/25; + printf("\nCount: %u -- Multiple_target_count_percentage: %u", irlock.num_targets(), multiple_target_count_percentage); + if (multiple_target_count_percentage >= 80) { + printf("\n----------------------------------------------------------------------HIGH COUNT PERCENTAGE: %u ------setting TARGET ACQUIRED FALSE -- %", multiple_target_count_percentage); +// count = 0; + _frontend.set_target_acquired(false); + } +} + + // update - give chance to driver to get updates from sensor void AC_PrecLand_IRLock::update() { @@ -27,12 +63,57 @@ void AC_PrecLand_IRLock::update() // get new sensor data irlock.update(); +// size_t no_targets_tmp = irlock.num_targets(); +// printf("\nOUTSIDE Number of targets - BEFORE %u", irlock.num_targets()); +// printf("\nHEALTHY: %u", irlock.healthy()); + if (irlock.num_targets() > 0 && irlock.last_update_ms() != _los_meas_time_ms) { + +// printf("\nNumber of targets OR Count: %u", irlock.num_targets()); + printf("\n\nAP_HAL::millis(): %u - _los_meas_time_ms: %u - irlock.last_update_ms(): %u",AP_HAL::millis(), _los_meas_time_ms, irlock.last_update_ms()); + irlock.get_unit_vector_body(_los_meas_body); _have_los_meas = true; _los_meas_time_ms = irlock.last_update_ms(); + +// printf("\n_multiple_target_start_flag: %u", _multiple_target_start_flag); + multiple_target_check(); + + +/* + + // Logic for Contingency Landing + if (irlock.num_targets() > 1) { // If found multiple targets + + if (_multiple_target_start_flag == 0) { //If it is the 1st time found multiple targets so put the value inside a "start variale" + _multiple_target_timestamp_start = AP_HAL::millis(); + _multiple_target_start_flag = 1; + } + + if (_multiple_target_start_flag == 1) { //If multiple target is seen again i.e. repeated so put the value inside "other variable" + _multiple_target_timestamp_latest = AP_HAL::millis(); + } + + if (_multiple_target_timestamp_latest - _multiple_target_timestamp_start > 500) { //If we are getting multiple targets for more than 500ms, go to contigency +// _frontend.target_acquired(true); + printf("\n----------setting TARGET ACQUIRED FALSE"); + _frontend.set_target_acquired(false); +// _frontend._target_acquired = false; +// _frontend._estimator_initialized = false; + } + } + else { // If found a single value within 500 ms so put the start_flag = 0 and restart looking for the multiple target + _multiple_target_timestamp_latest = AP_HAL::millis(); + if (_multiple_target_timestamp_latest - _multiple_target_timestamp_start < 500) { //If we are getting multiple targets for more than 500ms, go to contigency + _multiple_target_timestamp_start = 0; + _multiple_target_start_flag = 0; + } + } +*/ } + _have_los_meas = _have_los_meas && AP_HAL::millis()-_los_meas_time_ms <= 1000; + } // provides a unit vector towards the target in body frame diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h index bcf78f57c2..60e8c77950 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h @@ -1,3 +1,4 @@ + #pragma once #include @@ -19,7 +20,7 @@ class AC_PrecLand_IRLock : public AC_PrecLand_Backend public: // Constructor - AC_PrecLand_IRLock(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state); + AC_PrecLand_IRLock(AC_PrecLand& frontend, AC_PrecLand::precland_state& state); // perform any required initialisation of backend void init() override; @@ -37,10 +38,19 @@ class AC_PrecLand_IRLock : public AC_PrecLand_Backend // return true if there is a valid los measurement available bool have_los_meas() override; + void multiple_target_check(); + + private: AP_IRLock_I2C irlock; Vector3f _los_meas_body; // unit vector in body frame pointing towards target bool _have_los_meas; // true if there is a valid measurement from the camera uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured + + uint32_t _multiple_target_timestamp_log[25]; // array of timestamps when multiple targets detected +// uint32_t _multiple_target_timestamp_start; // array of timestamps when multiple targets detected +// uint32_t _multiple_target_timestamp_latest; // array of timestamps when multiple targets detected +// bool _multiple_target_start_flag; + size_t _index; }; diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.cpp b/libraries/AP_IRLock/AP_IRLock_I2C.cpp index b9cc15458d..ee695c1551 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.cpp +++ b/libraries/AP_IRLock/AP_IRLock_I2C.cpp @@ -77,18 +77,21 @@ void AP_IRLock_I2C::copy_frame_from_parser() { pixel_to_1M_plane(corner1_pix_x, corner1_pix_y, corner1_pos_x, corner1_pos_y); pixel_to_1M_plane(corner2_pix_x, corner2_pix_y, corner2_pos_x, corner2_pos_y); - _target_info[target_count].pos_x = 0.5f*(corner1_pos_x+corner2_pos_x); // 4. copy frame data from pixy parser to target info array - _target_info[target_count].pos_y = 0.5f*(corner1_pos_y+corner2_pos_y); - _target_info[target_count].size_x = corner2_pos_x-corner1_pos_x; - _target_info[target_count].size_x = corner2_pos_y-corner1_pos_y; + _target_info[i].pos_x = 0.5f*(corner1_pos_x+corner2_pos_x); // 4. copy frame data from pixy parser to target info array + _target_info[i].pos_y = 0.5f*(corner1_pos_y+corner2_pos_y); + _target_info[i].size_x = corner2_pos_x-corner1_pos_x; + _target_info[i].size_x = corner2_pos_y-corner1_pos_y; - target_count = i+1; + _num_targets = i+1; +// printf("\n Num_targets in the loop: %u", _num_targets); // // printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); - // printf("\nBLOCK:- \nX: %03u - Y: %03u - W: %03u - H: %03u\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); - + // printf("\nBLOCK:- \nX: %03u - Y: %03u - W: %03u - H: %03u\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); } - _frame_timestamp = AP_HAL::micros(); // 6. update frame_timestamp_us + + _frame_timestamp = AP_HAL::millis(); // 6. update frame_timestamp_us +// printf("\nFrame Timestamp Init: %u", _frame_timestamp); + // printf("\nCOPY FRAME FROM PARSER END----"); } @@ -123,14 +126,16 @@ bool AP_IRLock_I2C::update() { // printf("\nUPDATE"); bool new_data = false; if (!dev || !sem) { - return false; + return false; } if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { if (_last_update_ms != _frame_timestamp) { new_data = true; } _last_update_ms = _frame_timestamp; - _flags.healthy = (AP_HAL::millis() - _last_read_ms < 100); + _flags.healthy = (AP_HAL::millis() - _last_update_ms < 100); +// printf("\nHEALTHY COMPARE STATUS: %u", _flags.healthy); +// printf("\nHEALTHY COMPARISON (AP_HAL::millis(): %u - _last_read_ms: %u < 100)", AP_HAL::millis(), _last_update_ms); sem->give(); } // return true if new data found diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.h b/libraries/AP_IRLock/AP_IRLock_I2C.h index 6707fc8b78..8c42433b4f 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.h +++ b/libraries/AP_IRLock/AP_IRLock_I2C.h @@ -18,7 +18,7 @@ class AP_IRLock_I2C : public IRLock pixy_parser pixyObj; -private: +private: AP_HAL::OwnPtr dev; void read_frames(void); @@ -27,5 +27,4 @@ class AP_IRLock_I2C : public IRLock AP_HAL::Semaphore *sem; uint32_t _last_read_ms; - size_t target_count; -}; \ No newline at end of file +}; \ No newline at end of file diff --git a/libraries/AP_IRLock/IRLock.cpp b/libraries/AP_IRLock/IRLock.cpp index 63feca3f40..6276539832 100644 --- a/libraries/AP_IRLock/IRLock.cpp +++ b/libraries/AP_IRLock/IRLock.cpp @@ -32,6 +32,26 @@ bool IRLock::get_unit_vector_body(Vector3f& ret) const return false; } + //Here there shold be aa check that cmpares the timestamp at which the previous velue of count was plural + //And then if even after 500 millisec timestamp it shows plural count so return false + +/* + if (current_timestamp >= prev_multiple_count_timestamp + 500ms) { + if (count > 1) { + return false; + } + } + + //REAL CODE: + if (!AP_HAL::millis() >= get_multiple_count_start_timestamp() + 500) { + if (readbuf.count > 1) { + return false; + } + } + + + ALSO CODE WRITTEN IN PIXY_PARSER.CPP : RECV_BYTE_PIXY() +*/ // use data from first (largest) object ret.x = -_target_info[0].pos_y; ret.y = _target_info[0].pos_x; diff --git a/libraries/AP_IRLock/IRLock.h b/libraries/AP_IRLock/IRLock.h index 5d87748ba2..42415937cd 100644 --- a/libraries/AP_IRLock/IRLock.h +++ b/libraries/AP_IRLock/IRLock.h @@ -38,7 +38,7 @@ class IRLock uint32_t last_update_ms() const { return _last_update_ms; } // returns the number of blocks in the current frame - size_t num_targets() const { return _flags.healthy?1:0; } + size_t num_targets() const { return _flags.healthy?_num_targets:0; } // retrieve latest sensor data - returns true if new data is available virtual bool update() = 0; @@ -70,5 +70,6 @@ class IRLock } irlock_target_info; irlock_target_info _target_info[10]; + size_t _num_targets; }; diff --git a/libraries/AP_IRLock/pixy_parser.cpp b/libraries/AP_IRLock/pixy_parser.cpp index 0e1e1807c2..0196533a19 100644 --- a/libraries/AP_IRLock/pixy_parser.cpp +++ b/libraries/AP_IRLock/pixy_parser.cpp @@ -203,6 +203,17 @@ bool pixy_parser::recv_byte_pixy(uint8_t byte) { // } // printf("\n"); + +/* + if (writebuf.count > 1) { + if (!AP_HAL::millis() <= multiple_count_start_timestamp + 500) { + multiple_count_start_timestamp = AP_HAL::millis(); + } + } + +*/ + + if (validity == MESSAGE_VALID_SOF) { if (!(writebuf.count >= PIXY_PARSER_MAX_BLOBS)) { pixy_blob received_blob; diff --git a/libraries/AP_IRLock/pixy_parser.h b/libraries/AP_IRLock/pixy_parser.h index d0a6c3c99b..a846958718 100644 --- a/libraries/AP_IRLock/pixy_parser.h +++ b/libraries/AP_IRLock/pixy_parser.h @@ -32,7 +32,6 @@ class pixy_parser { void swap_buffer(void); bool recv_byte_pixy(uint8_t byte); bool read_buffer(size_t i, pixy_blob& ret); - private: struct blob_buffer { //Frame (full of blobs) @@ -55,6 +54,9 @@ class pixy_parser { uint8_t pixy_buf[PIXY_PARSER_PIXY_BUF_SIZE]; size_t pixy_len; uint8_t blob_buffer_write_idx; + + +// uint32_t multiple_count_start_timestamp; }; From d68e06e984bb21fd128b953712bc8e456110f7e4 Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Fri, 7 Dec 2018 14:20:50 -0800 Subject: [PATCH 15/31] Cleaned the code and cleared garbage print statements --- libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp | 57 ++------------------ libraries/AC_PrecLand/AC_PrecLand_IRLock.h | 6 +-- 2 files changed, 7 insertions(+), 56 deletions(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp index ba511c63d9..7a65c3fb1c 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp @@ -10,9 +10,6 @@ AC_PrecLand_IRLock::AC_PrecLand_IRLock(AC_PrecLand& frontend, AC_PrecLand::precl irlock(), _have_los_meas(false), _los_meas_time_ms(0), -// _multiple_target_start_flag(false), -// _multiple_target_timestamp_start(0), -// _multiple_target_timestamp_latest(0), _multiple_target_timestamp_log(), _index(0) { @@ -24,7 +21,7 @@ void AC_PrecLand_IRLock::init() irlock.init(get_bus()); } - +//multiple_target_check - Checks if multiple targets detected for 500 ms continously. If yes, sets target_acquired=False which calls contingency landing void AC_PrecLand_IRLock::multiple_target_check() { if (_index == 24) { @@ -33,11 +30,12 @@ void AC_PrecLand_IRLock::multiple_target_check() _multiple_target_timestamp_log[_index] = irlock.num_targets(); _index++; +/* printf("\n _multiple_target_timestamp_log: "); for (size_t j=0; j<24; j++) { printf("%u ", _multiple_target_timestamp_log[j]); } - +*/ size_t count = 0; for (size_t j=0; j<24; j++) { if (_multiple_target_timestamp_log[j] > 1) { @@ -45,10 +43,9 @@ void AC_PrecLand_IRLock::multiple_target_check() } } uint16_t multiple_target_count_percentage = count*100/25; - printf("\nCount: %u -- Multiple_target_count_percentage: %u", irlock.num_targets(), multiple_target_count_percentage); +// printf("\nCount: %u -- Multiple_target_count_percentage: %u", irlock.num_targets(), multiple_target_count_percentage); if (multiple_target_count_percentage >= 80) { - printf("\n----------------------------------------------------------------------HIGH COUNT PERCENTAGE: %u ------setting TARGET ACQUIRED FALSE -- %", multiple_target_count_percentage); -// count = 0; +// printf("\n----------------------------------------------------------------------HIGH COUNT PERCENTAGE: %u ------setting TARGET ACQUIRED FALSE -- %", multiple_target_count_percentage); _frontend.set_target_acquired(false); } } @@ -63,57 +60,13 @@ void AC_PrecLand_IRLock::update() // get new sensor data irlock.update(); -// size_t no_targets_tmp = irlock.num_targets(); -// printf("\nOUTSIDE Number of targets - BEFORE %u", irlock.num_targets()); -// printf("\nHEALTHY: %u", irlock.healthy()); - if (irlock.num_targets() > 0 && irlock.last_update_ms() != _los_meas_time_ms) { - -// printf("\nNumber of targets OR Count: %u", irlock.num_targets()); - printf("\n\nAP_HAL::millis(): %u - _los_meas_time_ms: %u - irlock.last_update_ms(): %u",AP_HAL::millis(), _los_meas_time_ms, irlock.last_update_ms()); - irlock.get_unit_vector_body(_los_meas_body); _have_los_meas = true; _los_meas_time_ms = irlock.last_update_ms(); - -// printf("\n_multiple_target_start_flag: %u", _multiple_target_start_flag); multiple_target_check(); - - -/* - - // Logic for Contingency Landing - if (irlock.num_targets() > 1) { // If found multiple targets - - if (_multiple_target_start_flag == 0) { //If it is the 1st time found multiple targets so put the value inside a "start variale" - _multiple_target_timestamp_start = AP_HAL::millis(); - _multiple_target_start_flag = 1; - } - - if (_multiple_target_start_flag == 1) { //If multiple target is seen again i.e. repeated so put the value inside "other variable" - _multiple_target_timestamp_latest = AP_HAL::millis(); - } - - if (_multiple_target_timestamp_latest - _multiple_target_timestamp_start > 500) { //If we are getting multiple targets for more than 500ms, go to contigency -// _frontend.target_acquired(true); - printf("\n----------setting TARGET ACQUIRED FALSE"); - _frontend.set_target_acquired(false); -// _frontend._target_acquired = false; -// _frontend._estimator_initialized = false; - } - } - else { // If found a single value within 500 ms so put the start_flag = 0 and restart looking for the multiple target - _multiple_target_timestamp_latest = AP_HAL::millis(); - if (_multiple_target_timestamp_latest - _multiple_target_timestamp_start < 500) { //If we are getting multiple targets for more than 500ms, go to contigency - _multiple_target_timestamp_start = 0; - _multiple_target_start_flag = 0; - } - } -*/ } - _have_los_meas = _have_los_meas && AP_HAL::millis()-_los_meas_time_ms <= 1000; - } // provides a unit vector towards the target in body frame diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h index 60e8c77950..fa46658615 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h @@ -38,6 +38,8 @@ class AC_PrecLand_IRLock : public AC_PrecLand_Backend // return true if there is a valid los measurement available bool have_los_meas() override; + //multiple_target_check - Checks if multiple targets detected for 500 ms continously. + //If yes, sets target_acquired=False which calls contingency landing void multiple_target_check(); @@ -47,10 +49,6 @@ class AC_PrecLand_IRLock : public AC_PrecLand_Backend Vector3f _los_meas_body; // unit vector in body frame pointing towards target bool _have_los_meas; // true if there is a valid measurement from the camera uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured - uint32_t _multiple_target_timestamp_log[25]; // array of timestamps when multiple targets detected -// uint32_t _multiple_target_timestamp_start; // array of timestamps when multiple targets detected -// uint32_t _multiple_target_timestamp_latest; // array of timestamps when multiple targets detected -// bool _multiple_target_start_flag; size_t _index; }; From 994bcc5da3642b76140c81106212eedfa14ccf50 Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Wed, 31 Oct 2018 15:41:51 -0700 Subject: [PATCH 16/31] Added finally edited pixy_parser file that seems to give the desired output. --- libraries/AP_IRLock/AP_IRLock_I2C.cpp | 103 +++++++-- libraries/AP_IRLock/AP_IRLock_I2C.h | 1 + libraries/AP_IRLock/pixy_parser/pixy_parser | Bin 0 -> 8344 bytes libraries/AP_IRLock/pixy_parser/pixy_parser.c | 204 ++++++++++++++++++ 4 files changed, 292 insertions(+), 16 deletions(-) create mode 100755 libraries/AP_IRLock/pixy_parser/pixy_parser create mode 100755 libraries/AP_IRLock/pixy_parser/pixy_parser.c diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.cpp b/libraries/AP_IRLock/AP_IRLock_I2C.cpp index d0af466ac1..f30922d924 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.cpp +++ b/libraries/AP_IRLock/AP_IRLock_I2C.cpp @@ -32,8 +32,9 @@ extern const AP_HAL::HAL& hal; #define IRLOCK_SYNC 0xAA55AA55 -void AP_IRLock_I2C::init(int8_t bus) -{ +#define IRLOCK_SYNC1 0xAA55 + +void AP_IRLock_I2C::init(int8_t bus) { if (bus < 0) { // default to i2c external bus bus = 1; @@ -55,8 +56,9 @@ void AP_IRLock_I2C::init(int8_t bus) synchronise with frame start. We expect 0xAA55AA55 at the start of a frame */ -bool AP_IRLock_I2C::sync_frame_start(void) -{ +bool AP_IRLock_I2C::sync_frame_start(void) { + printf("\nSYNC-FRAME-START()"); + uint32_t sync_word; if (!dev->transfer(nullptr, 0, (uint8_t *)&sync_word, 4)) { return false; @@ -65,8 +67,63 @@ bool AP_IRLock_I2C::sync_frame_start(void) // record sensor successfully responded to I2C request _last_read_ms = AP_HAL::millis(); + printf("\nSYNC_WORD BEFORE: 0x%04x \n", sync_word); + +// printf("\nSYNC_BYTE BEFORE: 0x%04x \n", sync_byte); + uint8_t count=40; - while (count-- && sync_word != IRLOCK_SYNC && sync_word != 0) { + + int temp=0; + while (temp < 9 && sync_word != IRLOCK_SYNC && sync_word != 0) { + temp ++; + printf("\nTemp: %u\n", temp); + } + + while (count-- && sync_word != IRLOCK_SYNC) {// && sync_word != 0) { + printf("\nWhile Count:\n"); + + uint8_t sync_byte; + if (!dev->transfer(nullptr, 0, &sync_byte, 1)) { + return false; + } + if (sync_byte == 0) { + break; + } + sync_word = (sync_word>>8) | (uint32_t(sync_byte)<<24); + + printf("\nSYNC_WORD: 0x%04x \n", sync_word); +// hal.console->printf("\nSYNC_WORD: 0x%04x \n", sync_word); + } + + printf("\nSYNC_WORD AFTER: 0x%04x \n", sync_word); + +// printf("\nSYNC_BYTE AFTER: 0x%u \n", sync_byte); + + return sync_word == IRLOCK_SYNC; +} + + +bool AP_IRLock_I2C::sync_frame_once(void) { + printf("\nSYNC-FRAME-ONCE():-"); + + uint32_t sync_word; + if (!dev->transfer(nullptr, 0, (uint8_t *)&sync_word, 4)) { + return false; + } + + // record sensor successfully responded to I2C request + _last_read_ms = AP_HAL::millis(); + + printf("\nSYNC_WORD BEFORE: 0x%04x \n", sync_word); + +// printf("\nSYNC_BYTE BEFORE: 0x%04x \n", sync_byte); + +// uint8_t count=40; + uint8_t count = 0; + while (sync_word != IRLOCK_SYNC) {// && sync_word != 0) { + count +=1; + printf("\nWhile Count:%u\n", count); + uint8_t sync_byte; if (!dev->transfer(nullptr, 0, &sync_byte, 1)) { return false; @@ -74,17 +131,27 @@ bool AP_IRLock_I2C::sync_frame_start(void) if (sync_byte == 0) { break; } - sync_word = (sync_word>>8) | (uint32_t(sync_byte)<<24); + sync_word = (sync_word>>8) | (uint32_t(sync_byte)<<24); + + printf("\nSYNC_WORD PROCESSED: 0x%04x \n", sync_word); +// hal.console->printf("\nSYNC_WORD: 0x%04x \n", sync_word); } + + printf("\nSYNC_WORD AFTER: 0x%04x \n", sync_word); + +// printf("\nSYNC_BYTE AFTER: 0x%u \n", sync_byte); + return sync_word == IRLOCK_SYNC; } + + + /* converts IRLOCK pixels to a position on a normal plane 1m in front of the lens based on a characterization of IR-LOCK with the standard lens, focused such that 2.38mm of threads are exposed */ -void AP_IRLock_I2C::pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, float &ret_y) -{ +void AP_IRLock_I2C::pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, float &ret_y) { ret_x = (-0.00293875727162397f*pix_x + 0.470201163459835f)/(4.43013552642296e-6f*((pix_x - 160.0f)*(pix_x - 160.0f)) + 4.79331390531725e-6f*((pix_y - 100.0f)*(pix_y - 100.0f)) - 1.0f); ret_y = (-0.003056843086277f*pix_y + 0.3056843086277f)/(4.43013552642296e-6f*((pix_x - 160.0f)*(pix_x - 160.0f)) + @@ -94,8 +161,7 @@ void AP_IRLock_I2C::pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, fl /* read a frame from sensor */ -bool AP_IRLock_I2C::read_block(struct frame &irframe) -{ +bool AP_IRLock_I2C::read_block(struct frame &irframe) { if (!dev->transfer(nullptr, 0, (uint8_t*)&irframe, sizeof(irframe))) { return false; } @@ -112,17 +178,23 @@ bool AP_IRLock_I2C::read_block(struct frame &irframe) return true; } -void AP_IRLock_I2C::read_frames(void) -{ - if (!sync_frame_start()) { +void AP_IRLock_I2C::read_frames(void) { + uint8_t buf[142]; + dev->transfer(nullptr, 0, buf, 142); + // printf("\nSTART: \n"); + + + if (!sync_frame_once()) { //It just sync's the frame return; } + struct frame irframe; - if (!read_block(irframe)) { + if (!read_block(irframe)) { // Try reading blobs until I get a sync (Nope! does not work!) return; } + int16_t corner1_pix_x = irframe.pixel_x - irframe.pixel_size_x/2; int16_t corner1_pix_y = irframe.pixel_y - irframe.pixel_size_y/2; int16_t corner2_pix_x = irframe.pixel_x + irframe.pixel_size_x/2; @@ -155,8 +227,7 @@ void AP_IRLock_I2C::read_frames(void) } // retrieve latest sensor data - returns true if new data is available -bool AP_IRLock_I2C::update() -{ +bool AP_IRLock_I2C::update() { bool new_data = false; if (!dev || !sem) { return false; diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.h b/libraries/AP_IRLock/AP_IRLock_I2C.h index 862274beb3..beee279b2f 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.h +++ b/libraries/AP_IRLock/AP_IRLock_I2C.h @@ -30,6 +30,7 @@ class AP_IRLock_I2C : public IRLock bool timer(void); bool sync_frame_start(void); + bool sync_frame_once(void); bool read_block(struct frame &irframe); void read_frames(void); diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser b/libraries/AP_IRLock/pixy_parser/pixy_parser new file mode 100755 index 0000000000000000000000000000000000000000..a897cf89321d075807e6a639a3c67ff80e4ab42e GIT binary patch literal 8344 zcmeHMYiwLc6`u9RiQ~lUt&_A)(vqblD1mz8B#qjhR|Xh>H;9~D1FghG#5)|(N%8PNls7so&`J{}uCy<*QxJE)BdD9ds=cGZe=ymx%!+_=#V9@Y0LlZGQD;rsb=%Z!}Dgy)nbOc&PfJ zO9x4YDoC#(tf2zVepbRiz6|~-;URjwB}+ia3le`9J@;0?6~%9m!_}fj3szo@=8_p} zNSWr~Sj-$sW@4%2nFO&cX6CI}&N9=nWJVq8>5jIWyTiM~dzIPUd)SO8a*5$&-b&

1;+cOn~jy3fFHrtGno*Wv>=_(%;B}Q+pe< znH>wHZ(LaL8^w9!!rX&~?`7lig4IX{FR!)@u4RME*_$}{3W=%0PGj=m_qo=`{;V~g zIrt;u=IUt3a|ZpqT>UNLeeBKzJNE7@nWXWsc>lE_lHeM7_f2Y?W{J5A3#AePU*r0V zR6o~0J9IAc*~rQ6;_oAU5sKBezpd1vXkz+Mq?JPe^^35z82zCV;KU2Tv zi!~GK!A%c*V$W8+4Y7U)J!2$S!*Wts_Yr!|kiTq8MFPPmtJ>>Un&c3%tn(#$Ca66@ zR7C^9=c}TD#^?NRw1-6yeHh; zw5z3{**!aK;1-tnT<0sF>z%@W%AIfycH@3!VWJ%kemY5FojG8#U#+md-1tg`b?C-d zDa?->uThv+H@;e7{kZYk@;YM1E#n&sELa5>&o{bZu#{J`+ytYK=&abC#36sb*I96>umJ%TPo*2H{Pg% z6>;oRi_-kQtx*3cEh2V}_q!?;Q0G1I3z2&due6<|^Yt5%$9F)p^z){! zEL}hE5$>xnzqK@g28w@3))ijkO@xQEE%(n^jW1mfE!vJ-mN|p)Agv$oI$5vfm%bNA zm$5Ur4F0&-_pZ<92@frGM}33vJF4zd*e@aSW5&r-ypQrZP(LS}<8xjGU|MI5?9eEtlwMa%|ijjpg!*9C>D%T_+-k zJI&4`9VT6Zxy9qk?0EP{r-@59IS=Mqe?SCfy_=WPHU~@!rsVQ|We1h4bTSD>gvX z%Gq=THM-_ZtTke8XnFPYbD0$mlqicWp((&i4j>=BXKeU&Q`V8 zm#u+1^$<%Z2gxU%y)Z>kg=uZ4X}wl>iT($O^KyFi%6F5kvay09FNbNCb(W72!&@@; zW8__+A*V3av0nk+MHQz$@-tBEGm!V{cTmH1%7xKC@;FfVkI%FBGk1ja`K$o_X{mtD zP#YKC_IT{jM_zxDFwViDkGv2R=MfUo#T&mCjxdgid{)Z&EzXtn z1$PxOU&c7TPJQITpy(e8h$rY*Jo?C&LE$g-!GnI?qmSCs2t4_f0HKjH?nuTX_^Xq;n_C*prX zuRM6r-;!>-R|q3lJ3Q)&CC%)g!C` literal 0 HcmV?d00001 diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.c b/libraries/AP_IRLock/pixy_parser/pixy_parser.c new file mode 100755 index 0000000000..dc04b4fbf4 --- /dev/null +++ b/libraries/AP_IRLock/pixy_parser/pixy_parser.c @@ -0,0 +1,204 @@ +#include +#include +#include +#include +#include +#include + +#define PIXY_BUF_SIZE 32 + +enum message_validity_t { + MESSAGE_EMPTY, + MESSAGE_INVALID, + MESSAGE_INCOMPLETE, + MESSAGE_VALID_SOF, + MESSAGE_VALID_BLOCK +}; + +static uint8_t pixy_buf[PIXY_BUF_SIZE]; +static size_t pixy_len; +static size_t sof_one_byte_index; +static size_t block_one_byte_index; +static uint8_t blob_buffer_write_idx; + + +typedef struct { + uint16_t center_x; + uint16_t center_y; + uint16_t width; + uint16_t height; +} pixy_blob; + + +static struct blob_buffer { //Frame (full of blobs) + pixy_blob blobs[10]; + size_t count; +} blob_buffer[2]; + + + +// - Write Buffer +bool write_buffer(const pixy_blob& blob1) { +// struct blob_buffer* writebuf = &blob_buffer[blob_buffer_write_idx]; + struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; + if (writebuf.count >= 10) { + return false; + } + writebuf.blobs[writebuf.count] = blob1; + writebuf.count++; + return true; +} + +// Blob buffer indexing swap +void swap_buffer() { + blob_buffer_write_idx = (blob_buffer_write_idx+1)%2; +// struct blob_buffer* writebuf = &blob_buffer[blob_buffer_write_idx]; + struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; + writebuf.count = 0; //This is probably wront. But helps me get rid of an error!!!----------------------------------------------------------- +} + +// - read blob i: + +const pixy_blob* read_buffer(size_t i) { +// struct blob_buffer* readbuf = &blob_buffer[(blob_buffer_write_idx+1)%2]; + struct blob_buffer& readbuf = blob_buffer[(blob_buffer_write_idx+1)%2]; + if (i >= readbuf.count) { + return NULL; + } + return &readbuf.blobs[i]; +} + +static enum message_validity_t check_pixy_message(size_t pixy_len) { + printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); + + if (pixy_len == 0) { + return MESSAGE_EMPTY; + } + if (pixy_len >= 1 && pixy_buf[0] != 0x55) { //checking if 1st byte of the message is 0x55 + printf("First block not 0x55 .. Message Invalid!\n"); + return MESSAGE_INVALID; + } + if (pixy_len >= 2 && pixy_buf[1] != 0xAA) { //checking if 2nd byte of the message is 0xAA (Combined it verifies if the message is 0x55AA) + printf("Second block not 0xAA .. Message Invalid!\n"); + return MESSAGE_INVALID; + } + if (pixy_len < 14) { // Looks for at least 14 bytes i.e. "sync+blob_data" = 2+12 bytes) + printf("Message Length less than 14.. Message Incomplete!\n"); + return MESSAGE_INCOMPLETE; + } + + if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { + + printf("2 syncs available and size >= 14..\n"); + + if (pixy_len >= 16) { + + printf("PixyLen Greater than or equal to 16 with 2 syncs, calculating crc....\n"); + /* check crc */ + uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 + for (size_t i = 6; i <= 15; i+=2) { + uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; + crc_calculated += word; + } + + uint16_t crc_provided; //Getting true crc by concatinating 4 & 5 message fields(original crc) into a single 16 bit + crc_provided = pixy_buf[4] | (uint16_t)pixy_buf[5]<<8; + if (crc_provided != crc_calculated) { + printf("CRC Failed Message Invalid!\n"); + return MESSAGE_INVALID; + } + return MESSAGE_VALID_SOF; + } else { + return MESSAGE_INCOMPLETE; + } + + + } else { + printf("Only 1 SYNC available and size < 16, calculating CRC....\n"); + + uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 + for (size_t i = 4; i <= 13; i+=2) { + uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; + crc_calculated += word; + } + uint16_t crc_provided; //Getting true crc by concatinating 4 & 5 message fields(original crc) into a single 16 bit + crc_provided = pixy_buf[2] | (uint16_t)pixy_buf[3]<<8; + printf("Crc calculated: %u Crc provided: %u\n", (unsigned)crc_calculated, (unsigned)crc_provided); + + if (crc_provided != crc_calculated) { + printf("CRC Failed Message Invalid!\n"); + return MESSAGE_INVALID; + } + return MESSAGE_VALID_BLOCK; + } +} + +void recv_byte_pixy(uint8_t byte) { + printf("INSIDE recv_byte_pixy:-\n"); + +// Read 2 bytes + pixy_blob blob1; + struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; + + printf("The byte inputted is: %u\n", byte); + pixy_buf[pixy_len++] = byte; // Append byte to buffer + + enum message_validity_t validity = check_pixy_message(pixy_len); + printf("Validity: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); + printf("Pixy Len: %u\n", (unsigned)pixy_len); + printf("Pixy_buf: %d\n", pixy_buf); + + if (validity == MESSAGE_VALID_SOF) { +// pixy_frame_received(pixy_len, pixy_buf); + pixy_len = 0; + + if (!(writebuf.count >= 10)) { + if (writebuf.count != 0) { + swap_buffer(); //swap buffer + + blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; //Extract blob information + blob1.center_y = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; + blob1.width = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; + blob1.height = pixy_buf[14] | (uint16_t)pixy_buf[15]<<8; + + writebuf.count = 0; //Turn the count to 0 + + write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) + } + else { + write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) + } + } + } + + if (validity == MESSAGE_VALID_BLOCK) { + if (!(writebuf.count >= 10)) { + blob1.center_x = pixy_buf[6] | (uint16_t)pixy_buf[7]<<8; //Extract blob information + blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; + blob1.width = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; + blob1.height = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; + + write_buffer(blob1); //Writing inside the buffer + } + } + + if (validity == MESSAGE_INVALID) { // If message invalid, wait and read 2 bytes + pixy_len--; ///----------------------------------------QUES---------------------------------------------- + memmove(pixy_buf, pixy_buf+1, pixy_len); // This discards the first block of the pixy_buf and makes pixy_buf have everything except the fisrt block value + validity = check_pixy_message(pixy_len); + + if (writebuf.count < 10 && writebuf.count != 0) { + swap_buffer(); //swap buffer + } + } +} + +int main() { + uint8_t input_bytes[] = {0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x17, 0x01, 0x01, 0x00, 0x69, 0x00, 0x56, 0x00, 0x27, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x17, 0x01, 0xF1, 0xE0, 0x09, 0x10, 0x46, 0x00, 0x27, 0xE0, 0x00, 0xF0}; //array of 15 bytes of SOF + uint8_t input_bytes2[] = {}; + for (size_t i=0; i<=sizeof(input_bytes); i++) { + printf("Calling recv_byte_pixy : %d : %u\n", i, (unsigned)input_bytes[i]); + recv_byte_pixy(input_bytes[i]); + } + return 0; +} From c01757ef369a43a8401af4074732ca8ad76a6cec Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Wed, 7 Nov 2018 14:34:20 -0800 Subject: [PATCH 17/31] Tested more edge cases and added a feature which tell how many bytes are needed to complete a block/SOF --- libraries/AP_IRLock/pixy_parser/pixy_parser | Bin 8344 -> 18208 bytes libraries/AP_IRLock/pixy_parser/pixy_parser.c | 104 +++++++++++++++--- 2 files changed, 87 insertions(+), 17 deletions(-) diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser b/libraries/AP_IRLock/pixy_parser/pixy_parser index a897cf89321d075807e6a639a3c67ff80e4ab42e..6ea4e6c399d4ef05080a115d9ba1e474092ae28e 100755 GIT binary patch literal 18208 zcmeHPdwf*Yoj-RblT0$?0ZA|clna7FF;5VA7|DYR6Ach~Ra6`%$s`#`X3}{CaJQNo z5o3sgcDrb4p+&8=+SSzsG^j!9P^;Ub^?{YPlm$0{+SFImDrUdG^SGIr4DEjQv!BoY zvnQXqzw>*Z-}#-#J?GqebDL4K$f9XXB`dp%5!R6`DCLr|`zo0MC}(q6Dz1~+Bt~LM zoF@3?0)Q*hpfs(ZUDB<9q&LSR2=Q=&lv7Z7NYEyEiNLh+f~p{6Iwz1G`MTpmjsogD zqu@sA#}0CgC!Jr3OnQ$>y+@^OIPudD6G;H=jQ+?8u2G=xOrdsj6&mQb2c63LVQiRjbMLtlIzdN=4ge(`Am2#M@J2)Z6G47?b>$qDET z?NCo)pUv9Bp&)a)f+2VPdRKk(dRL>{+d|a(W_N(K1-!mcBlz_j-L6Kj&)wp^#lu=X zt*!oc56EPPbORw*tJ~{ii)*SYt6Zgpv&>v+;pNO#y>f}G!4vQ_d4nNOVC9mk7QfH4 z(p}d=Hkw-fK54@xL=y^%o?t=yTX>(Kexdq?hMWdm_0JryH=TOQ8c7R}^QMw?y^Mt# zziQldqzJ}tIZhS5T+;2j&IJ@*;YTM5I*lRa3ke>NqDPOf{wTUMP2y}IiVjE3G#Eus zGpUR{Dd}W`>aEiLD7rZ%f!P;DS7V=aejY`So*$1y(N&#E-r4zq-PvtBm9I1B=Dv_+ z=!moPXZAyE=<>Tk8k)Kl*UX9K$PwO5DyNSRAx*uVaB}tZ5su$NIECzVAIAfPlgp={ zSt4UkpN9^18m&bfomu2Z3WR3(j2R3&}w(DBB?%!zk!`)dzTErxNJ%qPK~ z%g1mt)4zhg^WaxjXV-x9VE+QA7ID7*RVWVzU(XW;N0Gtv+3P5K7h)`2tPe+yeow!77PXX7+oepyBlS43x`jGhA(~Xdzob#|TNL-ZO3vuUMV=$QK z?8*HOA>GEHQ#%p?x6>HZ&c5e7Y`YJ1O54^R;_96rWM%HP-34mq-acpj5ogyC=fUF^ zs5!Mhx*j}kg}E(c4pMPOlzY2n;CVZqs5UdvgxnXD6FZF@!esXM#A*$-cjUBG?ivdyOKUdV#^ zqF|oCA}>HdRfNKWQk|WHsqHDeK4;s>S7&!^t$<7Vo!zOXEdF_u>lf?Y=r4o*DSKT&(B z^Mp42rLH4)*?z~Fws(XK55m)CK~H_jgYcYSo<9iBLLfQ_hs$euYo19M@b$u6B7b=K zH<;y@i1O#1U*Y^dO^x%38fLE1ACL``O)cQ;$$6O^PU9gz zeHhaVCxj*;qFuQv4PU&y$h-X-Oy!$2e{%q!sxl-Eag{_@wMp|j(_nFbDz**=g(=Qsx* z%=PDR7s>MPDEnAw;eJeO%JQE~U(CgU@AC?@rP%-5fk_Pd(DuMI+1T zZ`6#Fn5G6SXZOL8_qbGF=HA>lc0tUBi=v4{lEXUL0O%%w*BOy*~`nj2JbRn zYjAcaO`S%rV=gX1glw;lp@{yC$@>=&5W^kQneE%ax?alMYrMwYc^+j7cY-Jw{18dg zEY+3k<=Nb;0W$Y4dF`%IS>UfEV%OpR4h;4#<5;(GjN5tGv@=84xeRig^Lvvsnm9dW z$4mkv!eQe$szcr9c-DqObf4dhMhV@cZHJK}8nID5$ zX)@==GCu|LQj>X6Ec0{jo1AXZ^q=E?0`MvBB>*4eJ^}!Wd7nIt6_{w9w?3!XVHhFw zXArjjuTbf;&5HC6k_(txka}l729iyuY(?X2jU6MT|S~+rlEoUCj}r3-Ipc5u+P$>y(Jm19(qy#JCr58}znA z@4jsj<9_IT8^3=7{X3^3#yB8r4i#NfRCfxCjfs6y?=q;lhAt#I{*5oi1GCCi1AEn z#Q3+Yh_QE3#MlS9{m^?B^yiT89f%kQp!YoVUVy(ZLaz_MgW$ace-8ov4CTEH7=gcs z0e=pEUjh6D^j?MDYtZ|5==>7DUx9uEdanb%0li-Xz6rgz0N;k*JAg-__b&8)gZz8Y zIR-y}n-(#CcRXVJ9)2DN{}14u$c-5PF*;(Lgx)FO?}PrI(CY_04R|IqVw{Ek2l#ym z{zqt+KLQS*UH%04G1}!5z)y=K#%H+wZf?V7fO@X8^Lfg)Zzys0tm<%fb4Khex*oR_ zF(&T#7~QUui)d$GhLw%ORw&D@l)Vc1{<$P7ED~qf;^F>v=&i6qWLV*ro!v{QV~*l? zDRfK+v|pjk%N^t+tN41w>guj{Dppls?>2Q&D&LwF5L{8wb*{SW^P1_W_+IniIcxux zKf(Ow4?}v%drH5i>#sFkpD*nCW5rO;F=yu?%{lkC;WM-sy276b&TctfStqT~d3^z7<0`u4nQ^S|(!@sqc=}g!40{p7{VP9w-cyyCtUk`Xg zUSE^G1ZN$(RMr(SBSo_zg#aY)R%aIL3fi!ulBX$1gBw=C>`Z{>ixck z7=?<8gbFK`Ez+x&Evc`^paUIwNWLi3YF@?O}_e|?rz5+79B6? zZd5ObGb{b7GOjFYUhCbs3AXjc0goF8Qo^=BpnJX%cDGPfN@nXDyeL^3yiBimx73GQ z+`RSc1NDVStZI3cz6b>&7Ruqc059{kY|=~g6>FAOCGzP?loM+jCb?%dL*5{lrs}t$vMs2rH)!_H)zk~Tp-p;Kvj<(J z%H7fe@dkZb@jOp!8|WqTyrQeoe!^{^O$FFiYlnZ=0URD5g4sDh3N-uDWpJ zJe|?FlJzMsFaK{1jWilKiBrX*mBw=2SW>%k4Q$KwH{{7mtWMfeuSt zg7Mb*ZLourBew9vp`inS4*{M8dmJo$1(M?_dkY&HviWDU*pz`U~;f4>>IC z%tX33;`bcNqqAjJk&$($r7Au77B~cy`2UFCyWl?xX!0$4xB&5Y;^#(OPQ~z#oBRWy zUxIj19EbI{nEYcP-v|Cqx{ey)BCJ+yCJ%QWHWl7QeOOq7; zO7K6zQtyEn{cm%9iph=Ox8V-vL7r7+WZi42%*eaPYGmj=NtGGXw%VK-#djt5c7E>s5bW%L9V+Jk)Bi`{{~`h%*o#mqmk?c&Ck1g- z%G01c?58=8(lc^`$rq^koKrp)WophCC;7WC)On7^A0@^A?5iPqWX5*LK_H7^eRLp$ zq@IQFV;SK5<^}i+F_CbJ$Wxw#xe_WM&9EKv`Ggv48>N7nCuQ~71(Mz&9Z~c?nk$f$ z-+dfocs?zXD*qyhD>+Qxyncu$C*katk!6n(g8y6 zoujtT8bD6_6a?Gnt+=u@>VCE_?#I=h_MephlJZ$;DTs*e9Od)U-lF_hl-JX$V8Av+ z`DuqAGC5a2(fTnb^{_9|CE1{GO0e8adqNc#5oLaU|rJN#%^u{sEkgj&wrCY82%T$04$IfmRLV zcE@sDZF$ES>rRxt&po3{j~yIrW!{n$0pVM?UKeF17_4 z(X-wld*vb@fS#>_=SQc2nY@L{9Q`6?@8a1T;C6Bs&prpmlyT%pIyFHd&@pWErKm#6 z_=|yzewG9-B7xDD5OpF^v!8&4l%)BfYNKugA%`D<=g@?x<=l^wEICJUwdULkN)k(d z7?Srwj#n#-lCpKwzUg{WV0e3 z*Fek@#5PGBYuCnI3;N}7BkkYG)c7ZHWod6yegfq!Xl< z2jNx<8A!bkm+Q32H-K?L^ByOBlr~%9`P;I&7F#3$ z1|VbOyiBw6erw%+{8l#p?Km0Yr%QhSt>^*|Lzygc-@^i51bhNrZln3Y{)=P1da258RepL!5mS7|Zr`xq0OIvm|HPeqHW6B>KWK z&@9_)@@q4My)psVD=2p&ynKm*YuR4Q@}JBUELG35QsVd2MJ?MGvhlykij^S!j|JC> z>CH|JGU;k^VjUH`RjwZR#sHey&I!1gT*N!$I#H}Me@HGV`0fHi{{ruG)2XlY@IJJC zW$t7O%KZYne*9>8Bf3`j!Ygr)u(oczE}8QsGuKAm+$(gi19AM*Qi2{iQ4(eSP)Mv6 zW&KECH;sQeL0Nl5SLb^Lb+5aPq`Od zZQ5L1)e?a3T#34K{5{e{fiyu~Xu6CjNsQK}W@J088RIiXYhzNfus*a*VGhStAfd~T zW!8*&j`@yi47VgnhX=Myh+tkJK&+HY7yQohU8AZ$kAf8P`dLsE>$$j8BuJ4afO= zF-((J($8ZsP7epgMlI(a6O&tiN8Hw9guK%fOL(Fq!sQ?Sn^tvZ^zY= z{0d!%HvDu!r==*{o@1%Zw(lzMwI2ZXPP@IyQju*hTeGI5(=sKS6MNTG^jb=CELFrV zDtTdKJP9LjvCPaS&~b~s zcUSN3-Fwb2vB}*iYHtw@&#g#rvO zRMK0KbN~$n*Yzbc`SGfYdIlaJv~wFJ%oS|*2SPA~w;`!V%z0O=cwMwT>h2@idxXaT__dd5D~cLZj2=ADtH65Ij2R`f z#0FC@XbpvZp0Xy7&lB+019b=Lo6E$D#(F`MUeL&2buGXdddO2B@&^inp#WmU_{lcT z#JSm^E97_alWi95E3Y~%uJ;7Q2xfQ|;8M>9JPoYb<85jViJ*slL2r}KgR^)FJYu$} zy2fy|wS+|kglV%JoPO!A5HUxTUy}7bkoS{ikj+$bi~gK zll{)?bBS6(nO@u7;18fzz!^~u>IytZ-tdPIF77rLAt$K&%Mgfpkp%1M=>s1Ou2%7c zin-eS2#*MHkeP81FC)jyr|8P1{Pkqn&32(kP^VDOXrR&NZon8P03Qg< z6kwJBct1Mq3kN;miUH1|MkqI2hj+8Xm<^~P)zqSu_#?LHnFzY|?L788u6R|OKlyX1 z-VMiu(*1;L#aYpL1P#Zs}H2f@NJ*pqSXNSk4z55&bd>yulCDm56kUTN)we_1p-nBNF`!f2Mr`fDOXU9y zZf6XelA!4m$m@z@RLXZAJ3XM2|18e`2SJamk#O$EppUj(!0d7Idx;K9 zYW`Hy{mYM_GyD z`330Yf4rR(+~;CF5e3tkBl#15BvcCeWa(Qp_!TdA?GE6X>-w5GVrzl5risw95J+jsdG>GD*OZjT zF1bOOWm3eZ00v5;4Uol>IV0Dzt?+o!@`@#f%UHV5MJvk~pRt5qxMpd^lIp5h4*#MK zBy4V6hErN_E?mxBi))ruR@AtbEn2j~Sm|0>QHd=D1aV-1eMm6Oqo=;!D=$}{Pi58wCJ~NE7=OWL< z7la5!?B|58hM?btH^&<2Q$yN2(YcF@R@>20qecN<7Ys@>d`&DrbBr$ypD(J`r0*IN zeyoUU#O||Wzo3jWIbtWn3WJ+ku|)w41q5tXIqYvdfi_l%_xn7B6_wQmA$OC+a9&kd z7xv=wT5kg@B&^vTY-WWGn|!b*AWkJXr`;0>di}l_#06f!)8ZxtnQLnau|gi6LSze@ z{6Isr5h|o{3L!u57KNT>IWn6YU_@a;RSZ#~q4Frf-RiA}Pt>al5qVaK>7f-v9yCu~ zxCxSOUlZmMiF$pFewBCE)df853d6U=9+gLwq9?ZhVV;%~nCh_>5lQW16r3RG3Xp7c zx)=y8&6K{{?Ekq)r`5RP)?w=R5rU-PGXgcQ@$tI}9D0{R`LFhE z3XYYU%6}!N;Ck@s-3*1R{hflvQa|2*NoKboLorqQeKNo%l!B`K`1;==^(&>E+Ak`& zF-o8660d&`XcQBMN-H zRb~{fAU#Zq)>rEy1xsmz6qQuDinIrrXnpm5l7jL%l@cE@etss6#W;Pn-&U}nDi@XF%YOwt3XvQ(=DuA0zlC^tg)8_Lbm?)c z(pUTU-EzyTvH<~m;&Dykf1Kn)kUL%R8 zk^H~PieIA!mNXJCORxSAExw-TE)xpLYT}I3S9S=-6~QI#r9xp)o_pv(>Fh*>L*0L9 jeo$?X>~O;S-jvqGF;%&OOMAk^`s>Ps#8q($aVYyQ`(HiZ literal 8344 zcmeHMYiwLc6`u9RiQ~lUt&_A)(vqblD1mz8B#qjhR|Xh>H;9~D1FghG#5)|(N%8PNls7so&`J{}uCy<*QxJE)BdD9ds=cGZe=ymx%!+_=#V9@Y0LlZGQD;rsb=%Z!}Dgy)nbOc&PfJ zO9x4YDoC#(tf2zVepbRiz6|~-;URjwB}+ia3le`9J@;0?6~%9m!_}fj3szo@=8_p} zNSWr~Sj-$sW@4%2nFO&cX6CI}&N9=nWJVq8>5jIWyTiM~dzIPUd)SO8a*5$&-b&

1;+cOn~jy3fFHrtGno*Wv>=_(%;B}Q+pe< znH>wHZ(LaL8^w9!!rX&~?`7lig4IX{FR!)@u4RME*_$}{3W=%0PGj=m_qo=`{;V~g zIrt;u=IUt3a|ZpqT>UNLeeBKzJNE7@nWXWsc>lE_lHeM7_f2Y?W{J5A3#AePU*r0V zR6o~0J9IAc*~rQ6;_oAU5sKBezpd1vXkz+Mq?JPe^^35z82zCV;KU2Tv zi!~GK!A%c*V$W8+4Y7U)J!2$S!*Wts_Yr!|kiTq8MFPPmtJ>>Un&c3%tn(#$Ca66@ zR7C^9=c}TD#^?NRw1-6yeHh; zw5z3{**!aK;1-tnT<0sF>z%@W%AIfycH@3!VWJ%kemY5FojG8#U#+md-1tg`b?C-d zDa?->uThv+H@;e7{kZYk@;YM1E#n&sELa5>&o{bZu#{J`+ytYK=&abC#36sb*I96>umJ%TPo*2H{Pg% z6>;oRi_-kQtx*3cEh2V}_q!?;Q0G1I3z2&due6<|^Yt5%$9F)p^z){! zEL}hE5$>xnzqK@g28w@3))ijkO@xQEE%(n^jW1mfE!vJ-mN|p)Agv$oI$5vfm%bNA zm$5Ur4F0&-_pZ<92@frGM}33vJF4zd*e@aSW5&r-ypQrZP(LS}<8xjGU|MI5?9eEtlwMa%|ijjpg!*9C>D%T_+-k zJI&4`9VT6Zxy9qk?0EP{r-@59IS=Mqe?SCfy_=WPHU~@!rsVQ|We1h4bTSD>gvX z%Gq=THM-_ZtTke8XnFPYbD0$mlqicWp((&i4j>=BXKeU&Q`V8 zm#u+1^$<%Z2gxU%y)Z>kg=uZ4X}wl>iT($O^KyFi%6F5kvay09FNbNCb(W72!&@@; zW8__+A*V3av0nk+MHQz$@-tBEGm!V{cTmH1%7xKC@;FfVkI%FBGk1ja`K$o_X{mtD zP#YKC_IT{jM_zxDFwViDkGv2R=MfUo#T&mCjxdgid{)Z&EzXtn z1$PxOU&c7TPJQITpy(e8h$rY*Jo?C&LE$g-!GnI?qmSCs2t4_f0HKjH?nuTX_^Xq;n_C*prX zuRM6r-;!>-R|q3lJ3Q)&CC%)g!C` diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.c b/libraries/AP_IRLock/pixy_parser/pixy_parser.c index dc04b4fbf4..9245956473 100755 --- a/libraries/AP_IRLock/pixy_parser/pixy_parser.c +++ b/libraries/AP_IRLock/pixy_parser/pixy_parser.c @@ -1,3 +1,5 @@ + ///---------------------- Check all the " . " that were replaced with " -> " ---------------------------------------/// + #include #include #include @@ -5,7 +7,7 @@ #include #include -#define PIXY_BUF_SIZE 32 +#define PIXY_BUF_SIZE 17 enum message_validity_t { MESSAGE_EMPTY, @@ -17,10 +19,9 @@ enum message_validity_t { static uint8_t pixy_buf[PIXY_BUF_SIZE]; static size_t pixy_len; -static size_t sof_one_byte_index; -static size_t block_one_byte_index; static uint8_t blob_buffer_write_idx; - +static size_t bytes_to_sof; +static size_t bytes_to_block; typedef struct { uint16_t center_x; @@ -36,30 +37,53 @@ static struct blob_buffer { //Frame (full of blobs) } blob_buffer[2]; +void empty_pixyBuf() { + for (size_t i=0; i= 10) { return false; } writebuf.blobs[writebuf.count] = blob1; + printf("SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); writebuf.count++; + print_buffer(); return true; } // Blob buffer indexing swap void swap_buffer() { blob_buffer_write_idx = (blob_buffer_write_idx+1)%2; + printf("Swapping Main Buffer: Swapped to %u\n", blob_buffer_write_idx); // struct blob_buffer* writebuf = &blob_buffer[blob_buffer_write_idx]; struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; writebuf.count = 0; //This is probably wront. But helps me get rid of an error!!!----------------------------------------------------------- + print_buffer(); } + // - read blob i: const pixy_blob* read_buffer(size_t i) { + printf("Reading Main Buffer: Reading from %u\n", (blob_buffer_write_idx+1)%2); // struct blob_buffer* readbuf = &blob_buffer[(blob_buffer_write_idx+1)%2]; struct blob_buffer& readbuf = blob_buffer[(blob_buffer_write_idx+1)%2]; if (i >= readbuf.count) { @@ -69,7 +93,7 @@ const pixy_blob* read_buffer(size_t i) { } static enum message_validity_t check_pixy_message(size_t pixy_len) { - printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); +// printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); if (pixy_len == 0) { return MESSAGE_EMPTY; @@ -82,6 +106,24 @@ static enum message_validity_t check_pixy_message(size_t pixy_len) { printf("Second block not 0xAA .. Message Invalid!\n"); return MESSAGE_INVALID; } + if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { + bytes_to_sof = 16 - pixy_len; + if (bytes_to_sof == 0) { + printf("SOF COMPLETE!\n"); + } + else { + printf("Need %u more bytes to complete a SOF\n", (unsigned)bytes_to_sof); + } + } + if (pixy_buf[2] != 0x55 && pixy_buf[3] != 0xAA) { + bytes_to_block = 14 - pixy_len; + if (bytes_to_block == 0) { + printf("BLOCK COMPLETE!\n"); + } + else { + printf("Need %u more bytes to complete a Block\n", (unsigned)bytes_to_sof); + } + } if (pixy_len < 14) { // Looks for at least 14 bytes i.e. "sync+blob_data" = 2+12 bytes) printf("Message Length less than 14.. Message Incomplete!\n"); return MESSAGE_INCOMPLETE; @@ -134,23 +176,27 @@ static enum message_validity_t check_pixy_message(size_t pixy_len) { } void recv_byte_pixy(uint8_t byte) { - printf("INSIDE recv_byte_pixy:-\n"); +// printf("INSIDE recv_byte_pixy:-\n"); // Read 2 bytes - pixy_blob blob1; + pixy_blob blob1; //%%%%%%%%%%%%%%%%%%%%$$$$$$$$$$$$$$$$$$$$$$$$-------------- should I put struct as prefix or not?-------------------------%%%%%%%%%$$$$$$$$$ + struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; - printf("The byte inputted is: %u\n", byte); + printf("The byte inputted is: %u and pixylen is %u\n", byte, (unsigned)pixy_len); pixy_buf[pixy_len++] = byte; // Append byte to buffer - enum message_validity_t validity = check_pixy_message(pixy_len); - printf("Validity: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); + enum message_validity_t validity = check_pixy_message(pixy_len); // Call parser + printf("Validity Check Call: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); printf("Pixy Len: %u\n", (unsigned)pixy_len); - printf("Pixy_buf: %d\n", pixy_buf); + printf("Pixy_buf: "); + for (size_t i=0; i<17; i++) { + printf("%u, ", pixy_buf[i]); + } + printf("\n"); if (validity == MESSAGE_VALID_SOF) { // pixy_frame_received(pixy_len, pixy_buf); - pixy_len = 0; if (!(writebuf.count >= 10)) { if (writebuf.count != 0) { @@ -162,24 +208,41 @@ void recv_byte_pixy(uint8_t byte) { blob1.height = pixy_buf[14] | (uint16_t)pixy_buf[15]<<8; writebuf.count = 0; //Turn the count to 0 + printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) + empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' + } else { write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) + empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' + + printf("\n--------------------------AFTER EMPTY: "); + for (int i=0; i= 10)) { blob1.center_x = pixy_buf[6] | (uint16_t)pixy_buf[7]<<8; //Extract blob information blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; blob1.width = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; blob1.height = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; + printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); write_buffer(blob1); //Writing inside the buffer - } + empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' + + printf("\n------------------------------AFTER EMPTY: "); + for (int i=0; i Date: Thu, 8 Nov 2018 14:13:41 -0800 Subject: [PATCH 18/31] Resolved writebuf Buffer print status issue --- libraries/AP_IRLock/pixy_parser/pixy_parser | Bin 18208 -> 18256 bytes libraries/AP_IRLock/pixy_parser/pixy_parser.c | 6 +++--- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser b/libraries/AP_IRLock/pixy_parser/pixy_parser index 6ea4e6c399d4ef05080a115d9ba1e474092ae28e..9756c81af436eefabfa34381356209af471b972a 100755 GIT binary patch delta 3298 zcmZuz4Nz3q6~6cFkGsplEA9>LmF2h!_=R&lqPA*R48Mo zW@9&4S6pc`;?K$tg-O4m~ zhI{Wh=R4o|x%XZ6^>!L;r$-BD&{udyTVo;OsPTPxIdLvs5@IVmOGnK|KAW$JIA^zw zZeO;yJLOc)FWX+cN&!e&4xh%}=DS;5d8~;H(E~QK3{9Wo@)OBA^NFTC> z%Kj6H2!nhW1)+_f5!%YD1v?+!QzuEzu%Wjis5bP11+9{-H1z)UQJFLJ1|_)}@Jjd_ zaCl}sS0QA3EY$EkgmUv?I%)f@1TL=@A+8wY0zi%qz3UV_p9$`}R>89`Wav?yWBWBG z%>l51aD=_4vC?*SS+mFW#T+n3llE3qaqp?F4sC*}`mh@@E+e>JOSKY1&j0{D!N5#* zAe2q7xbM)yE1uv%)p^mVIwN7ky!>&|F71avKyXMh3eN=vPf!T3bDAWZ2Xq1j1$GDi z2Ft6lm!Y@6wv=`3OKqWsN_0AwtNSK5ZDO^$XI-@>EBThQDHU3FO9%e;hjIxM$2m9} z_r4MO^Bl-wHR8HO+$V@jjNw`U2Y@7zsQD?_YD8>vMV}E*cNsq-cvNQ432h=uXdP%y zfOrGI;|dM^I}(}90Mks0m5BBCf?m2M*TDvSePDqck@`GtyPGQd;C@A^2SEq^1Gvc4 z$1ug8Mwwp&i^%+&81o*mVR7a0Em-;~#FvAv4~iiZr{N4Cm;-}34Xu9z9f)gC>^8Js z!_eN+v*@E|_v2FS)3cFC{UARMdbrbSw7d6(4K3>huW2F~(rV+wa9D;Opur0p7Q6x# zysGQ0T%RBJM?k>+F!Y$ZSff6NzQ8*4h19|N^_HwBB=4C=y=P=^Gn>-q>!*{V-glE& zetdq~`!mqAUjAPFI{x#fWJvUk7831byW&@IzfWSvHQ9z^;3Hk05H#-lED)bwumRja zs6Z3mX^+V+ZcQ0tfGzJG)EmK`$7q7p_3$eZJeMdp_U{lvIm|5AfC@#F|T9j<>tre59G_N%@5Pb0DEA_-aT)KCN(AQ7SwttX8iE~je{}cUltm%)^joAN!DU4t!kM5 zU#V|ENgHsOR1JkC6|_t z-j76v-mN!ezk-<%$9BiID$i|))3J54H$PQtB~HP+0@r68p7|=zgUyBbuxo_Cydt#S z|C5yGl{qQ@j70juw+UAGaLFsM9)`93UL-OH>vcAp{zEQ&m+dyMq}9x4e%yTUZX^OH z6dReatAoEo?4~(8`798Kjd3Ix4{#ge)!YYuMaB;l>~~qkbliV4Yd^<*tYbhmJyfqPE39oa0nSL)VfqL7J#nkc@Dlvy(h zLKY!|wgaXbYJDEr9wI{yZi%iAaf{iFyyeg2{sMuDm*oV~f*?`_{V~99B*FyaRS1ED zb}ms7lAZ(fR7r8K@P%JWKZkN0T`SAx0k$PSEoTwM$`rn_mxx83BKng`X(1UuB2>>> z^NU><#vxo6{Nli|9CL#~J9Y3LKjy(CFJLDXzJ8Z!Gg^AEEY7#nl#W6B5XbpyOt%sG z&QqY{e4EWLCm;(UrP4x%AhT=;8NiG|jAYecXS(K*`Y>=3n~hH}dJX38z%3e+4tA9>O`&@QquQUl+DYj+^Q|!{j3f+enmPKjUd}>X6eNi>`U7i@bF`oB zT5E$h*SEHX&M|F~jgB#UQ42l5-YVJ%RI@OjV2uuU``QsgDd)F6f!?F}+7eR_9G{p3=V zl-hS7)_Avbx{WEP*jhbv(}n}oIwf=~qcVprQ>x5T*7by9ZS-svi!}Sb_mZrhdC%eA z?|#4U`+a}zy^oCTr``MMfh^kXwjI@GS%^Hc+#jAZjwULb@XC(StLEg^rhZ5EO5soW zd*|kt|3mvhr@E7ZA!VC|1a^{3_Ka~uDnn8v2Gb}793}T0)QihyiXd0jc zBkxp;(!a#E>sC?P^w?HRSP(Wx5KkTTK8}-?JYk8Wb>uj1;3f)6&i|$)oW;~O0PdFu$ zl{{R%D;|1vNe7K?oDY^TbC`p(XxlSEpG|`zwxiu~+3p(J6^HFw!43>cWTM@VftWAb z?%pt9fRw~+VM3JD<)9NgWGk_KaCbDs8w4Jw@6K0&z-$sgSzsa8-w%4_)E58)K3|-i zBT`>O@%XL{18`qL)VDzg{(fA7)W60Q4~Lj903tL0GR)iq7#8PUSpo8rW+#cuK&tqs;;W6}in5F6C?U~?NKP-F#`eDHziFn%{Ki^s+ zx=dzFt3&X^Vex%HgSXT#xskA(SICBH}8X3@ZpKhJ`6;3U+16(7F=3a>XduH5Ka0piFZr?DgJlJRf0-&YnL9 zeI`B$6m5GZReXCjC2TA@XU9)~0-hDL?Z>k8zIR%q9jliFKb+O~!(i3D;4J`4!l3pSICA~YlbY{Q)^5Z z)c!wsn-6vAhAf3WvDV2j_yId=C@g>FKmRNB1eE0S%C#2`J`k$wS+E!uCX~7+l)9RL zC0LiNaj6|_h0(lzE!egR6Ho&j9NqmSv>+Qz+k9}l)K(NbOlDkM>iK9`%ucUjK*SyR;a6J%!6AF)Hkha3#X-1P$V?P9fHxMh1HoVBKkBa1a zJZqAkQn5PAgY1=*eA?@|nDR4@JE3P6X*{i9Pg||@gs0PLS5ZBCcZr?G9n6Sxn%)Kq zt*X{)MJ{5(fHeL!n6;|9kg^#*Q#3)bYzQf*;HyOw6=ic!8Ly#9n?e8W2tss!MJmfl zn2GKZ%E>5my2p_%1?31`K{9R@<0g`*zJrvhb1Fg}KnCqWm}+Ty6SB=C!x9vUZY$bl zunQSETQZ+RL)G430tsWVr4jT;V0Op|6O3O$2pqI)shW_)G@z$yin7Y>e?IYdxYyIQ z!M*tado(j4O+&FVm3!)WV!0G6`;$^-AxVvdMzQwHe5dCV2=@&9iolVBxxt`aI`}3p zmM}>Vc2ea&<1}qVq#w)T+;yfz4Eh$@aqe2vWi&ne80a|nMssB}vJg_JEMx>SONEd_ zm=Wi$B<7R60y#q&%?3?A!n!&424cBlP)tG=NN`I*MMA6^0TM~8z%1%8ZYO^AV0;?x zRWdxn#XYit5?3?_;Fki9w zVXg^MbRrK7+I0{plw;qd9D4&v{{qjwpa|x1KwFqT%ksT~t03Z~kgv$PkS#~K*CD1= z31mjcRr{c6BVdg~{uIDUyNvLJ73b9<=Zu#T$zt7E+0^D4&5Gb?8N0arW9u^d2;m}B zkw1r-iyXl@(E9tLHZC_-6UUXrdj6T+9OmR+%LqHlO?50z=?YSvPctL=?bLiMs^C3)Jx;BJu3z%G=~D6_54 z(>lzGrNh&>zKo-r*eM~84zL-aNc-k;1$u<7D$U~-a#&O8I;vsEO5qsTOlgs}F8J=& Jv718be*vZytC|1+ diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.c b/libraries/AP_IRLock/pixy_parser/pixy_parser.c index 9245956473..5ce930a831 100755 --- a/libraries/AP_IRLock/pixy_parser/pixy_parser.c +++ b/libraries/AP_IRLock/pixy_parser/pixy_parser.c @@ -1,5 +1,3 @@ - ///---------------------- Check all the " . " that were replaced with " -> " ---------------------------------------/// - #include #include #include @@ -49,7 +47,9 @@ void print_buffer() { struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; printf("Buffer:"); // printf("[%u, %u, %u, %u], ", (unsigned)writebuf.blobs[writebuf.count].center_x, (unsigned)writebuf.blobs[writebuf.count].center_y, (unsigned)writebuf.blobs[writebuf.count].width, (unsigned)writebuf.blobs[writebuf.count].height); - printf("[%u, %u, %u, %u], ", (unsigned)writebuf.blobs[1].center_x, (unsigned)writebuf.blobs[1].center_y, (unsigned)writebuf.blobs[1].width, (unsigned)writebuf.blobs[1].height); + for (size_t i=0; i Date: Tue, 13 Nov 2018 13:12:44 -0800 Subject: [PATCH 19/31] Made changes which prints the block data bytes --- libraries/AP_IRLock/AP_IRLock_I2C.cpp | 43 +++++++++++++-------------- 1 file changed, 21 insertions(+), 22 deletions(-) diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.cpp b/libraries/AP_IRLock/AP_IRLock_I2C.cpp index f30922d924..c320a40c44 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.cpp +++ b/libraries/AP_IRLock/AP_IRLock_I2C.cpp @@ -47,7 +47,7 @@ void AP_IRLock_I2C::init(int8_t bus) { sem = hal.util->new_semaphore(); // read at 50Hz - printf("Starting IRLock on I2C\n"); +// printf("Initializing IRLock on I2C\n"); dev->register_periodic_callback(20000, FUNCTOR_BIND_MEMBER(&AP_IRLock_I2C::read_frames, void)); } @@ -57,7 +57,7 @@ void AP_IRLock_I2C::init(int8_t bus) { a frame */ bool AP_IRLock_I2C::sync_frame_start(void) { - printf("\nSYNC-FRAME-START()"); + printf("\nSYNC-FRAME-START():- "); uint32_t sync_word; if (!dev->transfer(nullptr, 0, (uint8_t *)&sync_word, 4)) { @@ -67,20 +67,18 @@ bool AP_IRLock_I2C::sync_frame_start(void) { // record sensor successfully responded to I2C request _last_read_ms = AP_HAL::millis(); - printf("\nSYNC_WORD BEFORE: 0x%04x \n", sync_word); - -// printf("\nSYNC_BYTE BEFORE: 0x%04x \n", sync_byte); + printf("\nSYNC_WORD BEFORE: 0x%04x", sync_word); uint8_t count=40; int temp=0; while (temp < 9 && sync_word != IRLOCK_SYNC && sync_word != 0) { temp ++; - printf("\nTemp: %u\n", temp); +// printf("\nTemp: %u\n", temp); } while (count-- && sync_word != IRLOCK_SYNC) {// && sync_word != 0) { - printf("\nWhile Count:\n"); +// printf("\nWhile Count:\n"); uint8_t sync_byte; if (!dev->transfer(nullptr, 0, &sync_byte, 1)) { @@ -91,38 +89,35 @@ bool AP_IRLock_I2C::sync_frame_start(void) { } sync_word = (sync_word>>8) | (uint32_t(sync_byte)<<24); - printf("\nSYNC_WORD: 0x%04x \n", sync_word); + printf("\nSYNC_WORD: 0x%04x", sync_word); // hal.console->printf("\nSYNC_WORD: 0x%04x \n", sync_word); } - printf("\nSYNC_WORD AFTER: 0x%04x \n", sync_word); - -// printf("\nSYNC_BYTE AFTER: 0x%u \n", sync_byte); + printf("\nSYNC_WORD AFTER: 0x%04x", sync_word); return sync_word == IRLOCK_SYNC; } bool AP_IRLock_I2C::sync_frame_once(void) { - printf("\nSYNC-FRAME-ONCE():-"); + printf("\n\nSYNC-FRAME-ONCE():-"); uint32_t sync_word; - if (!dev->transfer(nullptr, 0, (uint8_t *)&sync_word, 4)) { + if (!dev->transfer(nullptr, 0, (uint8_t *)&sync_word, 4)) { //I think this conditional makes sure if the I/P byte length is atleast 4 bytes + printf("\n1st condition FAIL, frame END"); return false; } // record sensor successfully responded to I2C request _last_read_ms = AP_HAL::millis(); - printf("\nSYNC_WORD BEFORE: 0x%04x \n", sync_word); - -// printf("\nSYNC_BYTE BEFORE: 0x%04x \n", sync_byte); + printf("\nSYNC_WORD BEFORE: 0x%04x", sync_word); // uint8_t count=40; uint8_t count = 0; while (sync_word != IRLOCK_SYNC) {// && sync_word != 0) { count +=1; - printf("\nWhile Count:%u\n", count); +// printf("\nWhile Count:%u\n", count); uint8_t sync_byte; if (!dev->transfer(nullptr, 0, &sync_byte, 1)) { @@ -133,15 +128,15 @@ bool AP_IRLock_I2C::sync_frame_once(void) { } sync_word = (sync_word>>8) | (uint32_t(sync_byte)<<24); - printf("\nSYNC_WORD PROCESSED: 0x%04x \n", sync_word); + printf("\nSYNC_WORD PROCESSED: 0x%04x ", sync_word); // hal.console->printf("\nSYNC_WORD: 0x%04x \n", sync_word); } - printf("\nSYNC_WORD AFTER: 0x%04x \n", sync_word); - -// printf("\nSYNC_BYTE AFTER: 0x%u \n", sync_byte); + printf("\nSYNC_WORD AFTER: 0x%04x ", sync_word); + printf("\nSYNC-FRAME-END!"); return sync_word == IRLOCK_SYNC; + } @@ -168,13 +163,16 @@ bool AP_IRLock_I2C::read_block(struct frame &irframe) { // record sensor successfully responded to I2C request _last_read_ms = AP_HAL::millis(); + + printf("\nBLOCK:- \nCRC: 0x%04x - SIGN: 0x%04x - X: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x", irframe.checksum, irframe.signature, irframe.pixel_x, irframe.pixel_y, irframe.pixel_size_x, irframe.pixel_size_y); /* check crc */ uint32_t crc = irframe.signature + irframe.pixel_x + irframe.pixel_y + irframe.pixel_size_x + irframe.pixel_size_y; if (crc != irframe.checksum) { - // printf("bad crc 0x%04x 0x%04x\n", crc, irframe.checksum); + printf("\nBAD CRC 0x%04x 0x%04x", crc, irframe.checksum); return false; } + printf("\nGOOD CRC 0x%04x 0x%04x", crc, irframe.checksum); return true; } @@ -243,3 +241,4 @@ bool AP_IRLock_I2C::update() { // return true if new data found return new_data; } + \ No newline at end of file From 3b522dca28b36dce03768f5f8c4095a7caa15c04 Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Tue, 13 Nov 2018 13:13:56 -0800 Subject: [PATCH 20/31] Renamed the working pixy_parser so that it does not get confused with the refactored pixy_parser file --- libraries/AP_IRLock/pixy_parser_old_working.c | 274 ++++++++++++++++++ 1 file changed, 274 insertions(+) create mode 100644 libraries/AP_IRLock/pixy_parser_old_working.c diff --git a/libraries/AP_IRLock/pixy_parser_old_working.c b/libraries/AP_IRLock/pixy_parser_old_working.c new file mode 100644 index 0000000000..5ce930a831 --- /dev/null +++ b/libraries/AP_IRLock/pixy_parser_old_working.c @@ -0,0 +1,274 @@ +#include +#include +#include +#include +#include +#include + +#define PIXY_BUF_SIZE 17 + +enum message_validity_t { + MESSAGE_EMPTY, + MESSAGE_INVALID, + MESSAGE_INCOMPLETE, + MESSAGE_VALID_SOF, + MESSAGE_VALID_BLOCK +}; + +static uint8_t pixy_buf[PIXY_BUF_SIZE]; +static size_t pixy_len; +static uint8_t blob_buffer_write_idx; +static size_t bytes_to_sof; +static size_t bytes_to_block; + +typedef struct { + uint16_t center_x; + uint16_t center_y; + uint16_t width; + uint16_t height; +} pixy_blob; + + +static struct blob_buffer { //Frame (full of blobs) + pixy_blob blobs[10]; + size_t count; +} blob_buffer[2]; + + +void empty_pixyBuf() { + for (size_t i=0; i= 10) { + return false; + } + writebuf.blobs[writebuf.count] = blob1; + printf("SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); + writebuf.count++; + print_buffer(); + return true; +} + +// Blob buffer indexing swap +void swap_buffer() { + blob_buffer_write_idx = (blob_buffer_write_idx+1)%2; + printf("Swapping Main Buffer: Swapped to %u\n", blob_buffer_write_idx); +// struct blob_buffer* writebuf = &blob_buffer[blob_buffer_write_idx]; + struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; + writebuf.count = 0; //This is probably wront. But helps me get rid of an error!!!----------------------------------------------------------- + print_buffer(); +} + + +// - read blob i: + +const pixy_blob* read_buffer(size_t i) { + printf("Reading Main Buffer: Reading from %u\n", (blob_buffer_write_idx+1)%2); +// struct blob_buffer* readbuf = &blob_buffer[(blob_buffer_write_idx+1)%2]; + struct blob_buffer& readbuf = blob_buffer[(blob_buffer_write_idx+1)%2]; + if (i >= readbuf.count) { + return NULL; + } + return &readbuf.blobs[i]; +} + +static enum message_validity_t check_pixy_message(size_t pixy_len) { +// printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); + + if (pixy_len == 0) { + return MESSAGE_EMPTY; + } + if (pixy_len >= 1 && pixy_buf[0] != 0x55) { //checking if 1st byte of the message is 0x55 + printf("First block not 0x55 .. Message Invalid!\n"); + return MESSAGE_INVALID; + } + if (pixy_len >= 2 && pixy_buf[1] != 0xAA) { //checking if 2nd byte of the message is 0xAA (Combined it verifies if the message is 0x55AA) + printf("Second block not 0xAA .. Message Invalid!\n"); + return MESSAGE_INVALID; + } + if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { + bytes_to_sof = 16 - pixy_len; + if (bytes_to_sof == 0) { + printf("SOF COMPLETE!\n"); + } + else { + printf("Need %u more bytes to complete a SOF\n", (unsigned)bytes_to_sof); + } + } + if (pixy_buf[2] != 0x55 && pixy_buf[3] != 0xAA) { + bytes_to_block = 14 - pixy_len; + if (bytes_to_block == 0) { + printf("BLOCK COMPLETE!\n"); + } + else { + printf("Need %u more bytes to complete a Block\n", (unsigned)bytes_to_sof); + } + } + if (pixy_len < 14) { // Looks for at least 14 bytes i.e. "sync+blob_data" = 2+12 bytes) + printf("Message Length less than 14.. Message Incomplete!\n"); + return MESSAGE_INCOMPLETE; + } + + if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { + + printf("2 syncs available and size >= 14..\n"); + + if (pixy_len >= 16) { + + printf("PixyLen Greater than or equal to 16 with 2 syncs, calculating crc....\n"); + /* check crc */ + uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 + for (size_t i = 6; i <= 15; i+=2) { + uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; + crc_calculated += word; + } + + uint16_t crc_provided; //Getting true crc by concatinating 4 & 5 message fields(original crc) into a single 16 bit + crc_provided = pixy_buf[4] | (uint16_t)pixy_buf[5]<<8; + if (crc_provided != crc_calculated) { + printf("CRC Failed Message Invalid!\n"); + return MESSAGE_INVALID; + } + return MESSAGE_VALID_SOF; + } else { + return MESSAGE_INCOMPLETE; + } + + + } else { + printf("Only 1 SYNC available and size < 16, calculating CRC....\n"); + + uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 + for (size_t i = 4; i <= 13; i+=2) { + uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; + crc_calculated += word; + } + uint16_t crc_provided; //Getting true crc by concatinating 4 & 5 message fields(original crc) into a single 16 bit + crc_provided = pixy_buf[2] | (uint16_t)pixy_buf[3]<<8; + printf("Crc calculated: %u Crc provided: %u\n", (unsigned)crc_calculated, (unsigned)crc_provided); + + if (crc_provided != crc_calculated) { + printf("CRC Failed Message Invalid!\n"); + return MESSAGE_INVALID; + } + return MESSAGE_VALID_BLOCK; + } +} + +void recv_byte_pixy(uint8_t byte) { +// printf("INSIDE recv_byte_pixy:-\n"); + +// Read 2 bytes + pixy_blob blob1; //%%%%%%%%%%%%%%%%%%%%$$$$$$$$$$$$$$$$$$$$$$$$-------------- should I put struct as prefix or not?-------------------------%%%%%%%%%$$$$$$$$$ + + struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; + + printf("The byte inputted is: %u and pixylen is %u\n", byte, (unsigned)pixy_len); + pixy_buf[pixy_len++] = byte; // Append byte to buffer + + enum message_validity_t validity = check_pixy_message(pixy_len); // Call parser + printf("Validity Check Call: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); + printf("Pixy Len: %u\n", (unsigned)pixy_len); + printf("Pixy_buf: "); + for (size_t i=0; i<17; i++) { + printf("%u, ", pixy_buf[i]); + } + printf("\n"); + + if (validity == MESSAGE_VALID_SOF) { +// pixy_frame_received(pixy_len, pixy_buf); + + if (!(writebuf.count >= 10)) { + if (writebuf.count != 0) { + swap_buffer(); //swap buffer + + blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; //Extract blob information + blob1.center_y = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; + blob1.width = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; + blob1.height = pixy_buf[14] | (uint16_t)pixy_buf[15]<<8; + + writebuf.count = 0; //Turn the count to 0 + printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); + + write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) + empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' + + } + else { + write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) + empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' + + printf("\n--------------------------AFTER EMPTY: "); + for (int i=0; i= 10)) { + blob1.center_x = pixy_buf[6] | (uint16_t)pixy_buf[7]<<8; //Extract blob information + blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; + blob1.width = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; + blob1.height = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; + printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); + + write_buffer(blob1); //Writing inside the buffer + empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' + + printf("\n------------------------------AFTER EMPTY: "); + for (int i=0; i Date: Tue, 13 Nov 2018 13:16:01 -0800 Subject: [PATCH 21/31] Refactored pixy_parser to OOP so that it can be ued inside the ardupilot firmmware --- libraries/AP_IRLock/pixy_parser/a.out | Bin 0 -> 8776 bytes libraries/AP_IRLock/pixy_parser/main.cpp | 27 ++++++ libraries/AP_IRLock/pixy_parser/makefile | 7 ++ .../{pixy_parser.c => pixy_parser.cpp} | 84 ++++++++---------- libraries/AP_IRLock/pixy_parser/pixy_parser.h | 59 ++++++++++++ .../AP_IRLock/pixy_parser/pixy_parser.h.gch | Bin 0 -> 3053776 bytes 6 files changed, 131 insertions(+), 46 deletions(-) create mode 100755 libraries/AP_IRLock/pixy_parser/a.out create mode 100644 libraries/AP_IRLock/pixy_parser/main.cpp create mode 100755 libraries/AP_IRLock/pixy_parser/makefile rename libraries/AP_IRLock/pixy_parser/{pixy_parser.c => pixy_parser.cpp} (81%) create mode 100644 libraries/AP_IRLock/pixy_parser/pixy_parser.h create mode 100644 libraries/AP_IRLock/pixy_parser/pixy_parser.h.gch diff --git a/libraries/AP_IRLock/pixy_parser/a.out b/libraries/AP_IRLock/pixy_parser/a.out new file mode 100755 index 0000000000000000000000000000000000000000..af923f1458d7558a87b0dffb78fb95565b977a3d GIT binary patch literal 8776 zcmc&(3v?9K8NSI92(Qh8L{YJ<6iz`7O9Bys95kC`VB!f#c_>w3*z9h|YLd;#&MJ6{ z#>P-r1S49Ct+raNR;;aB+oozY7(0U6indl;wT%ikSgi5INqw;W{yX>I%uY5vwx{Rx z=FEQge|-1;bLZYWbN^hW)h^A?%M)BY;%q@u$tYV>p$vtmstTY&l#9{$JxxpzBO#BF zI@?}h1FUu#P)#!yD!m6tyz+co;l?S-kC7uJEKs(bFkWdHgMYxk$kDFJZwg&-Y`~*L$KCX3r6OB z6+DXbix!`9T&4OOZd}?_{EYk@<~GLa7L?6xjLd0_H77UE*<8M0&VsT)A|9A0@0;2u z-(@S-%AROgd8jDnNw`Qy_FXStaNn*OQyxe4Kubu}!a zc+a>hn1?Mlz%nt1bsu!oa_Ao(#{bS?^i9L)r$X%MKmkDF2zRK3GHp{~Cq$xe( zjR~!Z;tF#}h$eig5pKBDs1L;&5o36B$OxIy%`q^fP#yov`OwqM^WblUoPjj!NMp~&Jm4*m={c0(niPv+rH>GADqZrF z*l3!mMywGSn~N|fCLoYPk0|FQI%`ezQKBHjP2j)()X)6kfMsfo+b)+|qGUG{-DWoF@rThrVG?YiWrTh@d6xxvoq`Vh$eJ5mDO5d$X zy|6(~y{We!>R-90c1OV&gsblue-kMBjwNryD_y(|oR5m8R!h~r5Z3BD3hn^viw5-6 zVe@2!ej$knef;`#Z+)O>>NT?c^*t2zpo}JCDQV$QR=~o}6k%{QrN6eUsik{L2O1mwsZLOtUz1Pyd0c;0eQ)Fo! zd6u>f*EfZwUE5%3Dd2UhENwgR`stRo1Guxq(ry5Df_Ec$yE-lHCU9=X^)2XkAGWk_ z1NWS7X}18sGsDup3%qr%rQHVn9(dme?{?rFz#p7sX?KEq7p@<|es|2$?g9P?{Ck0W zzhY_k0e_5s?+5+_yq|*i0C*3A^U(X2_Oo6~dw8^^{oH41zgTK%zl2{Gc)x=F5!4^; zx3tH=`!#rvBi<*#>&CSYwkHv95AZ4U_Zy&vc%KIDN4y7s&w%$Vc+Y|NTX24d>v`x8 zg7*UOMeu$P`~!F|0sjcz%fMH_`xAJ7M*UTAUPGL(kFm7B^jg|q5oa&#Z@~6uv8BB= z!O{+acNp^9(Ekm*KHw4HJ4KfEckqwmdKdP8;JLg9?8kF?ANT>D%ZI>^N-XVTVRdY! z=Wcae3D|3OTqS40(;Y29S}^){S=Cb(W^GRarqh+5rPE!oz_fNCqR*csXNg(R*8#(U z9yx{DkNQ$uKT9PC+P8j|mz;O?)`4^y6Lc2Z=p2bQE`h7Qqxd4UhgGl@D$MmIB&DA2 zn*(E~-O%Gidx92r-(3iZW^T0*!3%=t*Q8z!t_@-EDP+$`-)ayO#APrYYO^(>}uwnAJD=w=VF3)l_Z4{QLwh?{u@Sd8%LeX;>K z88@^USPtw1w$Tlu(DxISyen3Tyv@G6Q^$=e?93bGBRzdHuS1)&$w8Ie{z6QLo&5KI zl1{HAU$1Yeck;PKV=pgk6X%?=_>B3}r;(cY7*5d-Ke`7l#Jw2T2k5VgZZ+ujZOgA3 zKhkq{K0=ahe;w-L7BgO zqj~*1MpSxdUSFVlOSX;Fz2)trmU}B&z2!k~Nzgm9((8vG{42eM^8G#nW496Q*iVES z`~MgIKH%>Ge*de-oOyS$Oy4S0#@Qgc)XQESPsAGa5`NHq{A@_@Mfzo^LHm&>ZE&hpP(TbFD$lm3N)`GJx-^A;wh zSbAk?d7z|hmaYB*4SO(q`CRXG_h3)t^KiD_BTOD}hk?G_c^*2{m_r4b`IoI9DR`b{ z>qiNGe%X3V0iNIvg9lj-o?i|%`W+*99%k#uX4Yf2ew;YS3&vsai1EUojdK3DvANPnM*sOQ4{(z}o1DRss3 zEcDdxR<-fUcPn(CDm}kXc;BV=a`jsTLmuYCXZ%8eAD3MIr^&#E&Z`pH&d~X=Ncx{J zWd5A1^!$F}KG(~3hR&Y^^ttjL*Fo>Yyz;r`)pYD5{v7k|M)*$vgVzi1-?u|Qje~ID z80aTroX=7(4*87(`(xBj{z-!OO{VNdzY}w;(*v>{_8P>Q(tmKh&sL_lhVj2d`VZY_ z(kdSJIE;mVuDlQ>*l66`>rq2HKFqgrHQzYWxzc~~ka1ot<6*Bs+$i;4(W~aC{C0!6 z1$zIWTc&os@?WXuKSWt>mHLcZrt;`8?L0G#{?IV(h;XZ!Fq8H5fv_0NgBfO%5vEL7 z0tu%`+}P9@uM0IA5i{PJFha@AA{=jOX^fiDNMPZDMU+*`;bb6b6*EGut)VSOwApOk zBI;X1O;IC~Y--v9ibFEsX=b@nYAX8Gh<=dV2n~`kdW^SHAj%M2CN3s<%znJOayroN5Yio=(!OB_< zts+Y(bAS~UGIyu4bVf81GDFBZo`-vg#F~v{B1)}NE|AlIih*n&<@hk_iMY{#d!uZn zBWdV%%g!$jTFbyf%9HOF!zr_ruDA?}%g#8$zb=vBdhTqen=SK|;Y3o7*S}A=+PO{g zrKy9?T)ED{$nD!7n#%o8(zV%via=sZlNqW5nyofAa4pu1+;EEsG{?zE@hWqF5ZARwvXEL9oxY-q`(ALfTZdGCQ)8L@cXE0Tn&*!uAp`$Y)^Ly0+ zk&(}paFInd$D-JP8lBmg&)@ls+z-dkevFrbPiH`uGv@(CSgCrV_{oRkS88zuDm13d z=W_!ipG&!a=5t)vD1N1Ckk1#48=RSK1HNFth4x?0_q>*B9{`Ep803E^xT{i zdG0w~D^&m8YT)QSGZz=f&-(|>Z;su`r%!w;qg_Vs*S69bAvb@tN)#SvM}= +#include +#include +#include + + +int main() { + pixy_parser pixy; + + uint8_t input_bytes[] = {0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x17, 0x01, 0x01, 0x00, 0x69, 0x00, 0x56, 0x00, 0x27, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x17, 0x01, 0xF1, 0xE0, 0x09, 0x10, 0x46, 0x00, 0x27, 0xE0, 0x00, 0xF0, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x00, 0x01, 0xF1, 0x0A, 0xE0, 0x10, 0x55, 0x00, 0x15, 0x11, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00}; //array of 15 bytes of SOF +// uint8_t input_bytes[] = {85, 170, 85, 170, 15, 1, 1, 0, 104, 0, 82, 0, 36, 0, 48, 0, 85, 170, 144, 1, 1, 0, 229, 0, 86, 0, 37, 0, 47, 0, 85, 170, 85, 170, 23, 1, 1, 0, 105, 0, 86, 0, 39, 0, 48, 0, 85, 170, 23, 1, 241, 224, 9, 16, 70, 0, 39, 224, 0, 240, 124 }; //array of 15 bytes of SOF + + size_t size_input_bytes = sizeof(input_bytes)/sizeof(input_bytes[0]); + + for (size_t i=0; i<=size_input_bytes; i++) { + printf("%u, ", (unsigned)input_bytes[i]); + } + + uint8_t input_bytes2[] = {}; + for (size_t i=0; i<=size_input_bytes; i++) { +// printf("Calling recv_byte_pixy : %d : %u\n", i, (unsigned)input_bytes[i]); + printf("\nNEW BYTE IN:\n"); + pixy.recv_byte_pixy(input_bytes[i]); + } + return 0; +} \ No newline at end of file diff --git a/libraries/AP_IRLock/pixy_parser/makefile b/libraries/AP_IRLock/pixy_parser/makefile new file mode 100755 index 0000000000..96a27f72d8 --- /dev/null +++ b/libraries/AP_IRLock/pixy_parser/makefile @@ -0,0 +1,7 @@ + pixy_parser: pixy_parser.h pixy_parser.cpp main.cpp + + g++ -o pixy_parser main.cpp pixy_parser.cpp + + clean: + + rm pixy_parser \ No newline at end of file diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.c b/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp similarity index 81% rename from libraries/AP_IRLock/pixy_parser/pixy_parser.c rename to libraries/AP_IRLock/pixy_parser/pixy_parser.cpp index 5ce930a831..4a5e6b0614 100755 --- a/libraries/AP_IRLock/pixy_parser/pixy_parser.c +++ b/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp @@ -1,11 +1,33 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +/* + * pixy_parser.cpp + * * + */ + +#include "pixy_parser.h" + #include #include #include #include #include +#include #include -#define PIXY_BUF_SIZE 17 enum message_validity_t { MESSAGE_EMPTY, @@ -15,47 +37,37 @@ enum message_validity_t { MESSAGE_VALID_BLOCK }; -static uint8_t pixy_buf[PIXY_BUF_SIZE]; -static size_t pixy_len; -static uint8_t blob_buffer_write_idx; -static size_t bytes_to_sof; -static size_t bytes_to_block; -typedef struct { - uint16_t center_x; - uint16_t center_y; - uint16_t width; - uint16_t height; -} pixy_blob; - - -static struct blob_buffer { //Frame (full of blobs) - pixy_blob blobs[10]; - size_t count; -} blob_buffer[2]; +pixy_parser::pixy_parser() { + PIXY_BUF_SIZE = 17; + pixy_buf[PIXY_BUF_SIZE]= {}; + pixy_len = 0; + blob_buffer_write_idx = 0; + bytes_to_sof = 0; + bytes_to_block = 0; +} +pixy_parser::~pixy_parser() { } -void empty_pixyBuf() { +void pixy_parser::empty_pixyBuf() { for (size_t i=0; i +#include +#include + +#define PIXY_BUF_SIZE 17 + + +class pixy_parser { + public: + pixy_parser(); + ~pixy_parser(); + void empty_pixyBuf(void); + void print_buffer(void); + void swap_buffer(void); + + void recv_byte_pixy(uint8_t byte); + + private: + typedef struct { + uint16_t center_x; + uint16_t center_y; + uint16_t width; + uint16_t height; + } pixy_blob; + + static struct blob_buffer { //Frame (full of blobs) + pixy_blob blobs[10]; + size_t count; + } blob_buffer[2]; + + bool write_buffer(const pixy_blob& blob1); + + const pixy_blob* read_buffer(size_t i); + + uint8_t pixy_buf[PIXY_BUF_SIZE]; + size_t pixy_len; + uint8_t blob_buffer_write_idx; + size_t bytes_to_sof; + size_t bytes_to_block; + + +}; + + + + + + + + + + + diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.h.gch b/libraries/AP_IRLock/pixy_parser/pixy_parser.h.gch new file mode 100644 index 0000000000000000000000000000000000000000..d6ce4239147433410b7ffd6742b89f682f564ca9 GIT binary patch literal 3053776 zcmeFad0?c=RUg{6*&$|!7%&z~z!!5bYDuHTc+*I&8To1?SuNd}G0R6w-I98y)vf78 zi){=99y|zyK-dC-up|V+P9P8n#KwL&fQ@O-GFZi8bYyWEND}L%1-|*d^{<*bh)a2j! zJB{S|kq$renc{ecgEb#cLzlnLs9h~DKEAl%C}nsOH1e~Y-#fdfdxVq`?wO>K@C^6s zqB?5nOBeoWP<01F1S`(+WzTq*#52us?4?njQ9J4MJHzf#B}earz|Y2CQ8b&oMRR{| zXZu!B%*=ltM&wso=J6C^<-i%rlN9X57Ydjuy4=3Z!Xl8D9 zc6oN?L*exS;(f5Wy`yR@>n zyfnXfV}1#QxrG~x%bmyPmp7PqP5;)~TCv$!D{kCaDb{xG>~1yg&CGpR@Rp*ToD4fB zt#PO5kJ@Kll&?NNyYP_+W6QT(?BCyQpnQ}5sC&}yv}cY^TSLBxMMeE?zOu2iQEY7O ztnM$*B3yluNxX-6qLx@WYtKJ=Z02a@qdsb8i;ePL;*Tuu`bQ%G+ovelyth}M zY81`;+iTLmt9y-Nb$h*N-d)`->NEAH9d_;=2)i&--@yB|)j4|B8{0d3cU(Vh4`{&f1g3#$E#>jQvFGI2r*nbFA7AlDN_n?jhrAn|D@GfKBp*`Vu>{b_E0| z8c)INPGkS}&N_Uh7wE8JKRN97Tf^(3*By6;tseOT#|;}-!yo}Po_zs($@3%!%vh9r z^h>ajvIGpo#FYPBw1(YQ8{Kl;IXmxRunHeqnq7E4f@p??4{d-A;jO+)xgHfB2V3mL z8or4lyZ5_c-R+NAL1nX&DF(Lm{Kw~KmmXv7DPP#w+}_-0KgS^4+1|R(8p>oET_MRd zD~XxVx433tewF)z_bx>5knwtZwds2p+Ng{iN*r^Ek44(r@~5p)(d{4gChgAi!S)}U zDT;_x6hdTbt~|;ckdsj4`DHd`JQmB0&M)8KYu*iiMIoF@SzDQT@*e!+~_>Mu(G(gfym^H zI&rg#nG@H&dxQQ-Id!44zdJ&{EB*=$;{N1nrq05I*2aKLIPc>6#ti&FTq0QRu-`1| z%ZrQkVxGf*or2;^QB3+>q|0hl5rkRd3?yx(Vgd)}0Vf!S0#myuL!q&^d8e_x5B{@u z@7^qhiaMEI7&Rg_#4-ySxc(T~UOW>b0J3wyMo8+{3~V%Y{V^6^1BH$YfyVdT`XXPg z152l0UxuaQlBb|rRGdNAcPzC&&j!(mZoZRTJ^%5di08k@XX=l!Be79rKw(%!!om#5 zTJ;g%+}%M|IUSd5lfzH@V_+>IFE{3=a$l4*;l4~pE90Qa7p&fFY!$nEjg3t<#mnFu zT7m;7>L^dlE-%bsj4jPAEZ?{>i*C9wJG-=SV{RF8>&U6fB;0`zCo;*_ABk zk`6Kd#Qfr1eHN^1zFx;$A?7a5;lCxkcxfILdSh;JmctyJi$g)X6z113o>rb%k$;U9 zjMa}q5RNLHKgXxTPOCj?9e2EZ*X?&jx?7%IOxO>bGhsjTPe6pJuYjM{mzU=jmKGMl zg65VNW^b&_&o6=})mN4w$AID1*`}O9IUt;{sVsAITV_knku4kiWS$mp&w``Nnv%Yh16AK&oFP8Jc z&COf48qNJ;b!+q1HfN>aA0#Iy!-P6QQ&XmAMd|=-cY0i8cKavA(V#yX4<|?C!BC`F z^bfvEGoyTol^Ktjm%_i~W;*k@Wk&sprIn>cG|2qI@*?D&8%wjxb+Fr|g}HgiK@gE4 z2X$V63~k92r#*%O{IGQiW-vsSRG6;Mehglt^~EWWvUK1rvsZq6a=zxjEoN9NfGpN# znNv;ZxvqLJ7gv+v3*BIi*3YP75tB8$j>|=}z{-NmmKqVc-QC{{oMCZcCS?7o#I+^*JMNvqdA?sl|SEY)W@-v4oiD|uo>3eMz z6YNZ#2`i75cVD!6lTI=09CwDD{*f-N7VERjonv`a5J6-smndvB^-~$f&u#N_FAUky zuB@GP{t1+M8Crrx3gUCi%Qse*>+GEMW%OIjFNCMGqnZqE@L}*WJcY-fOVp8Z-6z`s~siXGP67I?Vd!#zqiDeRcZ2u~l-D z)>#`}s$RCV%pKc1#s2NR#_D>L?0^$X<=tN41^Ik_F=1+)rj|I|w0{flk)Kkk^cm6T z))sq$hIR}~)GVSiBAZe6k!w%%xLGtOtJL?!^PubUx;(9LnZd9QiUwL;1nbJnMbpHW z%W747X;}*29TpeTu12Awi(dY!&Jc6lXe^8e5(ukS%T{(8*V*QlSu$-imhQB3RUG#Q zEebF7#o2lKYE;e)t2Z}`ry6_B&7JL;`fOdee2_-imn@qq6UUp=f=76YrS->qHL6(}Xs_VZ4%B2RKVKNl}fp1wdfKX+Bm$zI~Sxw&3!K+m@-0s#9) z+)QRoNo7$fW4M9kQ_{8JoXEnuLU62(i3syv#4=!gi|Omw+H2g}#Oi3TT!eAVXj~_# zde%XPQC79DqjFLz>o3e$v8+*H;F_hUt$d#s{d$?Ryw;p;t%C%7baQ)ab6cdYlELCfV^!vk)Z=c; z7AcBSGA)J5(dhttE^+lSTVVp@Ldi~G)U&-4{#4V(LThIfNnkwg&S2@jRIjrmI+2OH zGjXos*HJzyhi)Xcr_u~lPvYk|6t8CZthH|;DLY40r5g#*BDz~i3 zm~^aQgrZ+G4{mZ>j(b=#hs{1A+B>&2VrWf|l};{Z^eb_f-(r8z-Y#s+YjoiV+?t?9E&)D&AM8LQomvc4yF~@!)>mdGYgIEED5!CjXUfjtixW#8DZ}uSWwgOKi$yV;&CEU}|Ez3r z`~!s6W<%x!JF7?x4a}44>#XdOJ2>@6xs;(EU-=GqTg#VLnRdBs*xg&bb!QceP)z6) zaT@pbw^#3AHCoP2GVaT_l=5z~ajV#9Do4~V7Bj85Im>R~OBts4dbI9jg13<1YA7dK z0ln2tsZRF9O1(a}vb?akfK>og&$CO=fMcr~n@#i3gs;>W>+?|e-T*@>D=gYf^+lPV zV|$kMDf$c3)xm7pwUn`;bhc9APc~yppPOug1m&$TSXWq`^8Kvqg5rT2nYyxESt^%~ zo&zjLqvRzaW2hy{4_f2d4aVggOVEbTEiQ7G13Qem!RUA6Lh-1iirdW(K|Z&*6Gzh{ zw-?7*PDiE8el|OJY)fUi}W)lYvfer1Y$Cx)|5{-Ln zjop1LoY6zdTJvfW->QpIjS9<-)VhnQ9usYCg_WdERqZQ^+NZy1%PoeFN1m(Gn6P;6 zszrTKE1O$uCFcaTjhN?HrhYRK2=)+~cn*Cq73OXS>NGzJ6|Cd~c6O0`o@m#^YX;*WzwJIu+ zMk!>S!-N8wa_Xk_rA##LmT{M)TP-HE5BX7ohAq1T`>4K^CHGr#?4aNr)j2ls;EX1i z!Y9?nNh|D&=A9Nj*mU3DJD^R zPhr-V+c>Dh5P(He?&zc|F+L-=LiQIaY#848_UfOBC6lELDe7F8=hxTCOVn3&f5sHf zbya0qA`5wiwd>Hft7_?8wwt$iutS>c;Xt*^La-(^sInX6NoyH)ilUmNw66J*R(I|C z^tVO8QOc$lRWDy#&d*X>-`{o4(@w@tBxUqd1G_Ybv(`cIPKFEXI4(}vY1l(qSdERc zh?Eciz_6i=D;cw^IK0KTHeao+?HF?umAl5wwZ7V^$DtZuy@&mPS!x`$BeOG>>zznf z__X#hw;oFvyiA(Xhu(p`ZBCkgDlDk-o2hdM>d0ijT6Rk*)}+qtWxKoa2OBC@M#;5I zS43Z>pEjebNWa2?%)l1Vij?ig-PQdy>?Aw|3kYmrmFrWymL;qR<>c6bYmh5gPUCs( z7MEFNU!uU76K#?@6}I*c*C{4VR+m>sK!4i1 zq+BO++R{XB-iL{wvhb<;FcwP36>`Y7_Ssupph%#VE@Hu?KklBvOl3H1U5}ucSzfBo zal$L7Vl&CaJd^2^dPY=Eq)|wPMQpIZ^v_yKvSzfip=NyJzN0cfn@Pn*8Hr`jriWIU zh)rb`l(NSzOu)h6GYdErCYE~QQkTjeF1pHqahOHCyA%dAPfvftk^NE|fNdn3^PQ`6 zir6&OEPI%2HKHf64#V&+GX$Q(j-bQD@swaquuMrp`v_msxjO2cQzm35pmvVjs%)F8 zlwO(Rgaf<-${!WY&BTPv`*xb2V-~a;TrZAW1chS>G>aIz!r8;rg|+>Sge`LBs<1^y zPNttVEHw_e7A93|R9F*=zr(RS&!rz*r&N)RVaO&BF7hOaUqp; z**ko%^?cYr528Ka-Azg#b5wpL6LPXveg`(=z*SfjSA%XpJ)YTL247{5stJoN%HIJK zEIC!6lO<{c%LU~UQ8%Wt9o@Jbu#QnWd&L{2z~$F|rYBSyve|e=vDVz5xlytq&wSBO zLm}0GnzN&J1Hbf$laGh>EJCtvW$6ya_;=}@yr9Z@b`y>7spuC@`!6gxs%JCS#ImU@ z1_!GMaoXYUTHi1C(3h*yCi;%SGY@=PR&YI_}~iNo+;W9eK8a z_Iy+%2U|K_&M#7OU^bJb(w1GZG8wHwX^-ldEGJh4FfUojs5a4`rVpNMo>Z`pwyQYb zY5mJ0ArX2)>vMxFEb+h;issJ2-Wpg1*^I_!)6krtIBK0^wJlaFY?w;#gb@afKxV2w z-ZW(X|NUzui+>;28p8^wd-M<-x;w6Y-1uw;M}x3qaaMbxn8jb6f8r3=9N|2F7Wi|6 zKa2cX;?FXFR`A1MbBr~|SaSjyYmTwz7>kI2ZYIF^jJ{HP;R|ao>h@uw({0ZT&T-NL zdnYfct=3l0&wE`}w2x}#>auq8U;|yRR?024wc6SXUQj~^+A8)NH~|Hxw*)F~HTIh| zoLQY8>+SVQ)o9OHNbd(SFb5dT}*xRXXY;FPI zhdNI7l$tC@aWH2a=5wwO;|$)$&TeB{{RhJu_IYZu4^qsblD(^5L%Y{*Z`NqNxk#IW z;^qdnt8EqBdp+y6>EbXH z*ZAzb-#V*pbq|L)*HXK4vsgP2bzSXFZK(1bwLfX{7~ncJqTpn(bNc{^++_#w&*uK>{z0>LcXJ~Ou({!bY@&zV+FspaaJct(c6Y_Oy}e(% zyS;OJb^8{dcUL!ogEt+BSGx-%hCAXo*xuh;T|-pX&Cc3taT~7f<|gY)9Xjeg*k51W zyA^rvugfkuy!YAX9FM5UURuEcAZNgkD4R=9sI&HZs&c>JJ2Q+Oz>B}m$V%mqq`GQXx?w$SzX)PX$FeC2E)rxQh!ih@XhriO!BDoo4|Vq*rwP|fo@)`J0gdC2;qPUA>3Ni zdukQMZ0;-Yi|iCdk)u{aOQ374u{g}@TDSL*s&D5SowqLg-hJIaf^&eAVVx^F`fVu8 z2JlA8s|OhPz9X#ooh>-`uz#655~z z8YX7Mb1uACor}&fKNlR{53ElEVLe`x!;73v#jLnM4ROOeG>3txdwOei$8P80YF2&9 zY8Gy~yIbHChdXV;_vof`y)NXnm2fmR=S9&bN0%Nv#RKW*d?Z_?2P|bcFF1WtbfO532-h-Ph|OS1C5K+c&SF`Gg(h4kU@~dFx!jnZzAQ$t z9Q!*GaaK`LI^?;iXjGN(FW2X^b<1GY9#E|99&p^EOi^WFd9fZh4f7N6YM=Ug4FP^AT2&k~sr zX5VE&DRM&`h=z5s0a@mLv3?&Vg^~s$!zSi%&nINraLd^`$5foVUR~R1Ze(atkCOA* z!sBqZOJ;f-z6m3M46Tv|I@J9;C@0o(FlFE0d@3rGzGZ)Pd#;iciIucK%mu85LtWfF zfD-Vj%_d|4NR{_(R`+R>fn7q%N5*fhvAJbmLz;b!H+m~MEh-(=o2gxpZdZ~7t(s)h zl2~mJMC?n}w>H*9GV!BGUfsC4x_+mb^a5lECkVFJU{Q~mISsvbdvmKo++5$gV*~1y z0X7fNc8I)dQr+HxVd#^UBzBs+5yRB%ZtpZB9vEnlek*D2qxbBfAFbl3PsX=-uxqId zjit=p3jHoP?>Z!H>#++Vw?f<7*^fB6W^o_KTx~$opgOdjsj+`=|7O#6zsB9212PXB z0k!G)4Sfm~kQ~r(lpz)%prmbg54!m64H0vV$FA*Zn5=ED+5m^Q!APrwTif2pF(LEv zjmGvkXVV2wO%D4Xq9lgYg?G~ZBF-4O_k^* z+W1(1Z|<`0O$xFuPh08s{oNhgBZOvOBt-k7P0UVDnU`QW!0m=S70ZWo3c%n;1YKO% zMg(iDa8se#ya}-R8SLu$4@y40YQ&_Ut9os9EXtSVHn~Tga0;w|Hla`5EA-!U6 zzw%ztD&e45;mOttzl6*!H&xg^#r0E0j!+RjlgeIWZx7;Y^}Wu+PSGlVCd&qyER~*n z!9G-&DZ512{hf+L0_wpU_X0!^T9;kNYQ%dRxXY)KTNOPaf!@UB9f%K68CJDWmvFkq z=EUwUbObiB`#8tDvzFl@Q1=v@ySVcp69a0)RZ$EjV}>!HpAgkbHd=GNI^{7^vyo4X z1No_qOf@qO{PHik&rVvE75E~lh+Kj4vj(FasCF$aDD=!Y?qn(^Bd~*185^Y8rUR`) zf>kaKjoQraZ`t8{AU7-7a0lB^X{}eHA7pFbsg1i$h|RW#KGn>VvsBgS*lgUzvbfUo z?*^4wQmc3Opy0I}E4zLZqOCAYchxywh}Dp&@5(9+O4`gaOsKYEgjh*6x0EV!YpL9# ziL^>r5n}Z{I~Bvsv^ztav#T~U$9~!v&wwyRiJ$F@}EjBVU zt`MuKW+y^kE0(DQp;nT}iK<0bR#j>xft)-ErhpDushg}siLh0XQi+)aGD0P;w8#}V zD(qI5-!(VISHxAiAY68<{_=}mMKz?tQ9MQjH6bvk7mK>s-&G` z7ob%~A&I%zRa!=#DViC9h6=1IUsP&EB!FVD!kS5|W|YKAra-LFpr~7QcLRWz$=2#7 zH(pB#MJ_rjv8>L(j-U;Xh}&yh2kVVu8;ZOFf`Z%63yHWxvlYFc7y&rTBeyFU;=s=M z7I(^I2d8{hso*qf-qIu0Pp0&YZgP7^j}t`iaFk**>OnqO0g)$K>ICvD4pyUTgIQ1m zdoh>qGV8kZwt-VGn&3P{t zyiCMXRWPm6_gDAw5e{OFgHI*2Ql&{L5N>TXqN?ze?3Tms-j3|VhXi+)URPP&kt1wOr zf%09r0u-HLd-Ij6+=77u75mcL&0=)}J1l>9u$v9+@kLc(I+j3o^wpb*n7@B-yJ)U% z#1S2ZeXe{hH{f)edmo8xHzHLcz1FxHC!(eqf#SKck|rcucDEa`#?OTV6Ol`9GvU<( zM<}8Vs}M_eS+iblQ=polXzsF6f}ZH@`}$qVY^c(3YAs*TGQiXvrh6Q|tRnbl-^q@R zb?sEYNK5AvLzHA&%G1q$p^&Mf#e5B(g-#mjuS-wdCWB4Fn8S!)WtUVpKe?U6oyfFl zyrq~}-dL~dt`}dh4lY|wXk+a*go`u8zbk zu?;4*7BLmlQTdfrwl++l(C%p-AjClkX*43$J(Jvy7j#0XOiZLY!;WI_t~8P<9}RSN z?o|5)n+rxa(W;DT;dV%Dblu-<#G;0JXsMx=+}UgL&RD}An&6Qs+%CUfd0`EMEf z9`422TW2MLrrU_pf$va@DN2KNw|jv-U0PLfyMj$XYbuB;bU`+9W;w9U;m+8dJF9GJ z2lk+SEFo&;=GK!=-3t8+{}+>va$+rx&j%xDzsF32Zgt^$j{b!@FIsX#QLWgVNB)Cd z(&o;_P1MZh&Xzv5^?_-IvkgkP3CRLNpLarothCK-++U#1?VUAr9d5}oFr}K^E$s9w z)Qb+(4Q=kgfB?x^;l!b|A259lvfaSo)9w@zcgmdma69|D zl^G`{Y8tE)l6+tc;%Yh6mxOeR$g+dsEw`zR#}oVuwj7jL1r#?SPjWAj$afH5y&$ms zKH06thI9@HTQI*0RBV2_O1ZOoi*p8&5*L1(*zW^`#4DGOc_4Zo@Jx6?@hDGrOzJAN zYhf%wXDJ?go40POtGTvGv#<^K4p{Bpy@^}XBou+%)D$6oLG#JY-Mh|7p-=+sZ=waz zlQ;ng;b0r(*=W#Kk-38IY=c2wesE`ZpIfk+0Lc5k+|Z>q_SXFSr2&GMTt_RLolFb- z7Fu2=8#>xy>*(PG*OTL{w7l5eaX>4Fb$GjSjB_lc+!{SzrtaV&*RSESc1@j`;l>7#>0+g2>0&|Y2YTI z=rrDV8LmESos2XHV}=Zr{EV?3L!)!p;kj|Ck{0fO)u<$1R;c6Qb(*H;u6)O3x2?rJ zrmHw>T_1LM#W+SauKd7F=aTwKXM7YKX%XOc8T>AfQqRDAk?jYQvvcxcID4%T?v24m z2{d))(EEtf+t5qkv)1roN2{>kp+E`=5aGu@+*~y3k|)l1o88+z44lNz?;w zw7I%b$yzAh$>Q=kirt|ubw<%x<964@qN{*ew025_!L%Y_CZX8nU;NP;&WMgN%v{D#@Zb(5#8nUGPKAg4n0RjSLn;GNGpl#qq)Ncl(+IET)C0L zl?b+a{mB_)wR-2L%tG@}hHdk(*XpyoG>`h@VUG^EwTOI#^T6M#?!y zI32J_Jz^(qPR?PePsf#uzXi)>n6zy*&Db~ zHL!gc+F*tV^2m0hhSelyZJ4UUoDj0;_FyR257dM+a!uprj2d)++$e>Cm$T1R9FV`5 z2LZhk;za4@83Hjm$Bcv70utSR&D#r?e$6$A2WS-7c+-A%n^%end?gUcv>x`)K%l(g z64ww;J%c$T#f*W?Da;3WmeVlGDc0fi^>*RjB~e%ns2!~j%p2U8gWje=Nf|_^j%YrG zJN|ryaD!?M60K~J=}y`f?9L<^?vbe-G!rF??Y9kqGcR=zB!|5)0@}z+a`87;YF>A! zdIcvjtF?a_T~_QE0qw4GGr@k83%KMd8jh=d--eMBbpo?!u}ILT5ZtmA_rQrRqE;OA zF*w`BUS~8pL)Uh&`C#h-XeYSAll?rV9`re#Dm|EfI|p9jU8;LS<9dQrLs*VD2O@Y^ z**!`MZA6iTAw-eTG7XAgD;GmdvXNDw{(oe2y}a$DZg@ir6_nG_tDkWe7k$m zxPsaCE1To_*5RlfT&NdE1K)G5li&gyaWt@3=W?ka#U8wI+NXdX?~bYpy=zX0*t>;< zgwv2fYPidaz;FV>+Cj+SY6()&pR|X$8rC3NPr~>L#aB;;6H0L@za-we}n{w4q;N|1eTEL0#D-(juVS@_2mv5k}CFbq8y{WhBNqELU-V~B>9b-MvklzlCBLxSt$b{>*&T&hggYnP-h zsj1t>fxPVDV0N`k==q2&se|j|^8jwyhALZy^*$C#y4O;0)21O`AyI{fCdtd>pu#QV zL#ejcc!f`zYm(SqhT~$zp1pI~l!Z+7pj+No^g!fN$!p5kI{vLcCpgeT&1eC5y*|%Z z`Wsl8Bxz-thyo**ut;fd6-HfBGQ{Ommc?s3TL*WxJz9r}1hxiotdN~e6nh%1;=xfb z2^b&pjtpHGNtQk(Az?9@2+D87!{*WBkfIVojs%t&aWD;CzE-^L+jx^lv{&cLDq**= ztk>}ZHtv0HHDGK^^L*G}%K)N>a;V$5I+IA5(IyU5;uA8_$l2W5#bJL2LEnu>I3UIs zcqNpU{N#XmYOr$Laj5x87E`JhNxAEV=5>-OsQ1e#a%{x!KI#V|u>Qx{OZT-10UW#% zP?4}qL)xZxH40P>Q@9|FRaO)(df9;bjaJ_fq~jByz|_Bsr5ndI1Mpfzw^NG#DfJW6 zWD41lJJG1r(eM&rcU6i4{Wwp;xha!9-yaTzi3_MOTx@s7 zo-5)UTHIoQNY%HP^F$1#yH{XR!N59?PpM`8_zp9`-;?@SgT548H0EM?30X-G+F~E2t}oA zJh#D8p-Gn=zT(ME>Re3-@?2<^sE!UkPRZ{QB~#pkPSkp{(~GXKaOZ5x5KWkDb8huz z5DX~+=XFWc?+UQWUZLYrx;KU_DBdYuI>y@k!5dKeK}-m7upt}wh&|w_OAykVsjH9c z6is(|96Xxf2A;~WD)X^#K#}W<#bG4L82ZiCy}eDGo_PD-xtI{vP)qq#>6eQm9b{T0 zw}rqGrFqvjo))d#=5dQSmjG&!qX9>d<-t)JRTQC0GOoH{oq#MmAOkD#0*IFsLhtg5 zabY9n4vwbHTR7ZyL`jg~&1K$oNr8tHg3wAf$O<_MmQvOLB*kVChYf zGm}Tz)u@Q0%~)#?6wOF)U!?-ESsmYY+eZcoz=nAcRs~UVR}!f*7@}}wwuwTRVEPuUaqL%g%pU5E+}_X zz)8&l)-SvqgNV6Z;{_lDyvxFYqQLgBh-y+Ry5KIiB#NRqJCx0fVw_NMPyVO_t#?eM z8a!z9ic`FbH(V8})GM*m>j?qc>!NkoEyk@Ac|Y!nIf0(3kSF#($hXCP*6EMEn;TF{ z#SWB)z&?q-N8u&zr^CB(5o$+*Mpz@9wU1k8xY5E@bRAv7&G- zPC^pJK$XZLS)p=hR)`BZBFCK%*^@ev-6-y{MLy7%+H84JlC6>$XDd+SYz1PRtw4;j z#XU`F0Id(%nHzR^;oK>2kS=p+ed3%|{h|z3JfnP8{G#ku{Nh}512M{GAzfIDP|doh z#91zBQC0&n%3`2JSqro%OMw<;1^ctDF1Fp|_P(+zrLox?Go(0=AsjD>3LUAWM!77B zQ8r6rlut+GmbUMjfs}bU`b_5KpjKZFV)f-9R$kt3Ro_lp_4P`v6kf=c3<$N71EE&3 zz+LmS_}DzBWaUPyRtag9mxEY&HE5L=gI0O%XmV)Z0aEqFLae-*)XJ+#th}4V%FC~+ zg$Akmav@e;PHN@lBvxKdV)XLvNH)jCu%IkFF2RXq}bn@<5DU9ca;u11)+jzpsO- z@|YiLEXzK^t#B5`*%1Gv^D8CFfD)p&Ds5ntsZt^lhHtmGa3=2<|?UCMoVIp(UPbc#m7|-C$w7uA98Ld zz<4B|%ZVhf5DZ2~iC7doYzLO<)A z9f2Wa$Y%o>4rb`*Q^K>WYarUjF@p(U&8%ze6%c`#hIa5}I?oSDx zP2HO-R?@$ilKYFP<-Hi?qsZmKW%IQT@lnU9* z9D_6oFMb#aXXgW_Neb~!PGBYmfkmx{@d|1_^8*c4)Xcytyw`{5C$mMF(Elj=0=GAR_Dgky?M!JdLIepB1$ zYy2o31cY%Zh~qqgBPOFka2mmk2MLiBTq%`QQv!QZl1e z0=te4VY0~}l~hv#+AvAPbOP{0G_nn0USs=#L`q(Bn6RxQz@#j|NpRCdfJt!MK*W^* zHo*jUx)vt!;hp+l#r^mQAN5FsU!8a3DuREv62K;yV9FhC2JR0afW)a;zoI`#r&pjT zcHU1W@o7nyo>S9yLGp>qoIEY@(sOF!E=WFciWAe)4t`UU)(|G;?pcfb3}Gx1C+$T- z(mq`Fb&qu)B97S`BnbiHPX8!nAtXr)B~5#fz8oP^|KW(b!I0Y?Fftemi$|nYBBgz} z_o^h3S5=aDRhq!7(&&T!gE&55QY_#kIzC7Pu7K5D66yS!N~a7dO-q9vtD#>gHzp6p zK2GKbPAQI>REQ@hQ%49amu8nW>H?<)&~zUqnT=%%%al?fs=|`sou;48O6Q5>bOe}G z32+kod^kv&gE)-S=F5Kt^M5nAuKeDF8kiSJb> zS;%*Y5F4te(ag6V5EgITnJgL?x!xsI;`WLQAqMlq3heL9*t?T7HlWO(7&P&SJK5eAY@{0JVLb z{Zw8-;42gQDh-}2evZ%5wGVL`d=N{_*hFZjsSnyo@WC+FeI1{RRv+SBoMF|+R4LKn z+c1ufd1N;UnjYaz0w(?JeT&4& zyayJWotR1LXa-g66g~4UsWAf$)MRN;QnO*v-7KSlRbqG4o<`4SWYj*%CO>NDGXwgR z@YxKh3M13LPT`Sh;frzm(Of2m(yOg?f$lliu2zQ76RoJ$sM53Pbo1{$2R$2pH08ac zDd~V-od_;4T;?(pgrirdLtNX#7`Yt5C?L~o5gzn>_{D{3G3b+xGnx_u^la%!&z53p z!_gyKQ{XuHDyK(2#WeG^HqDVA-W7hwMGxI7m>-M^Qo{R zEH$gClUT_&h}G^vVl`y8@~|q+ya~i={BA$}O;Y37vc6qjX&+{SJXM^#o$IB$G^!I|DHnGLz<{ zS50#;tdEUS9u8eC>&lF6(F5`V2DX^zci82}GqmZ7B(r#y70pgUv6-g6! zXtj;f$>kGl!gd=5&b1=x$re^fVl*uyRVFEkTu#aNB%eIUQzK+rtKCLDPKl5Wo)4Vt z-nydp^OcANZ?zIZ%w__1snx(2Cz%EYF`L50Nv0Se<^szywwkt*r$(rDAc>GIz4%l! zq~s}YI2mWN1oG4f*({xmr)BA6oXrx*xi_4lYhPC1pyYgnt4!bKBr_%bD>)dFOw#8F zKFJmsGf*ydQnQ)q_H(I|nhh?qNVNgLr7`Q|qfC0IlWK*6F@v0a2YmA3rv>k2gZHKd zpJezJvIBB1J5{L+yQ8^)qgMN{nh~L9gP%^0tKDV*#NyV z&!3M-ofiDjG@t5pfON8zN_zIKQ`62CGuy&Q`!bvMWj^0SIc$^;uMvpZ;)9+^o75@6 zGx;92^7#fmoA$JP=URCx%m-pVZyu%}xA`XsKq(sm%L16=5UCV%2T?j!Jd=~F-icmXjk4Jf8YyzP{aYb=Q zuA9#7KJk`f?^|764hOx{%1{TfI)mVr>s-iTCZshN(p-|7sSza?{Yt$K=~Jz((cxjP zm_n|WZ&Q&k}5LROdlWV4l!6KeCTx_lv5RryM;Xy%1nRpcuVg`e6?ElLeJ=E9KF&47o8*AH8CzO>WkF@96aX|Lk}6o zkza*xlzvrZdGK4Pa*@(6F-S_^xA1n-T+XLSE1cpYqq*k`)pJU2)N?ssHPj*%qvLKx zEzM+U5q&WwRq@N@RqQ@IkFMGeB;HjPhv}!SU7g5+#IgB=1V~u7 z9VKZ{28wM{7{-!^0#m28Ya-Rl>0^x8Q&bB3@2SN$0^JtP7J#~$lwO}+vVsI}+ z+dmo6^iUzCU4^8i{zyox&l)j|NT}wM)Lg;rA=mB*7iPq5NLWwp0~WV_pCwRc@syVqs4 ze_d94(`B`W^}`xTPA{v4ysVb;(w;f)jxPO2DxyMGNDpSCmpw?#p&ul+&=2Zyz{F1Z zL1Lu*Anqd%l4gF8v~e%xMjTQp;8 ztCS>?SVBhi(Gx;q8L6b?-5DE84OLA$wX*Els;bmXwQ8z$qveQmohfUkusy@>dqPM` zCX}QUJQwyi6fE9Vi47V=jF~V&jkSiH$#S zEU*xo3?(PO;BUOsclS>oB!_Y8m|QNAJ+xZRo1diZ8Z zB_K}2B`21!<&ZlvACr@_bC|87G&$v^8XZ!SNsxqO3Iri8Bw-~9Qet^g0>v^W3HCKc z#$=Gni&GgBLE`!ajAcx~cwsrU1!Vkv^{8 zIJ{0p)<8?j;sYkBaoLMYlH&FTsdb#nfqhR)6LbM>g5v>>eZ>L^qbt$IS89^LfZvwG zU12AKaeQ`baQFbnk3`mwGK(*XVYnriJK##j?l>NjN-$?)lo-F*Q4-SN{0MA49%1K> zWRr8`T3TFeg+9bLUP-$ETj6)^wC9f#ZRSklC{=aym4*3jwDTTU}lUluF{!5qlMi{a4BXRO3v+%4;j+MC)yTsZ1 zQ%KLw65=t%2iLH42AN%+og~&F4f9pnOAM45&M-q^4cvErjn=g!{jt4 z-ZxAa7NAs023nl%l=hCui7-C89$jRX1fHBO3Ov;;3q08_4AOfF%ryn(mIA`KXA{Rg z8#sYhi7;0EKvWY-Ng|zce>QUhd^~6wMd)~7)l1`nRT4qCtOly6lAr{Rnf7>y@1n-J zBu)xWLY(W#lqr?;>_8Qdyw4QwHJQe}#3P>+zG#UH`HWV4q94Yj_B$%0qw*foWPo8~ zl$V{k>CN9gsbg(2g>jLd&(KuHg#~ZA1W`i4t)(cJ5w%FieRahQN;)z?FoOaVJ0AQc zd+|&Cmw^MuCvwyT$&u=E;Q{P$G7Qf zjF?j1uj{|CevI{IxB*!r#MfLNVVNqQ^v0{r7rm9DpPeq<(WSdb`b~E3Zpq{j@Bo+X z$rl=M@76%h^h92`JbQqTTywD=QMIXjf&&hXlQEAQM`5t7n5DbsEhA6*qtouOw1^|R zkGqG|Dj6GajQV$B5k1B?F(L|?iX0?_mBS%E%po0YfD`;8bn^2G;VNSR{wiYvSsbdP zz}G4Ia)+_Q5z;eJq{F3+J?OW)8Zu>@w}j6N53}c7yU3= z!ew9j;e_y^B7Ye$J<&t^BV3t^H$h{8RsCQ{8RBTno0*T~>Siv7oQpTm2gIvw&kl>D z$q*l;r@}`AmGfGHlc?oP=flWw@L`amY?4#zIJ$x|5f>(5NsX-mC{VQiL6vK&FS^6A zZtUSx!FBQ!K3C+EK5*d^Ef+$(J}GeP6S;s?19+?IhmI;9S2D4%k=x{DZANbg_TpU8 zNYJmTgK#)uzi#8!99Ek;&)IJ6POpO-jZX^SGeGE`;l>h{4{m;q9nb!NSEfWahm#3# ze92?n5_JczD;0PlJqalJl1;lSNp`Wq8_T`gT*=_bUi*mM0}d!_$K3^Wk34bg9arj* zw(lU1Bkg|`m)uQ+L@+_&;%RYA&dPhfD}<6U$yk&wtgh~H(dT`nSdKClZo?k30_h%| z!w{bi`Rd29+}aJdt6S$PBGTsFc5AgcU&lZO9#xD}K+J`-rrRb+aODm*5IpUJf39PnA#89i?7>U+jjHzjtG)U|ZpxnX*`Mgh33^QV) z+&Mp-@G}C)Q|coNVUqA&gbRM+DoMc;t0|N|l@vtMiQhKqcOOkUg;VPf`6-AIJ1V<6 z`w?I7rYB+JQC4w9__1nuyo&7aIQGP{y;JXpY%n2Cp<%qivWteyluSfNfhgxFF#=*&H)8Zd>`VNvQKv)EROXFr!1~L9Up{x7y{{COX@Yk zm)RhdLaJdbAb;t#Liyf=Y`DNrF0)cPc0y&>1=LP|!nqhOFh&su;p}n7c5FyJ&*dU5 zc;TMyYe-J#r(KFiAdKWfD#0TRPe65Qu_F54(%bhi6g19`O0T zqk&sI$Wl|t;hQl|py9BT?L99dl>|9S6+zYnpcXWIa*@RN6A1t`JaBja1IZ=ESP*MK ztrd`=sPSRA?xim#S@#guMl3~AN7OVVuqtDMLI&rYN-5PwpGz2A_9Y)U;Z9)&4+`XX%Bz|4WKbwvd9L#%}`l{r4-0|xrYco0g{`jBV%y4F>a z<`9}{Xp>slPDnyZQjWs@gHEN$e`M_&bACnjZKu-@sCS2_x+ z*>k#~Ay)LR`_rlUhsr`7m*o4cB^B3qR%y`7Pkz|1Zicmyj04cJwQ zCFyFT3bE`m5YPO#7|C1!9gBAYH6K{Ix|J}IdyjkpMBeQ_n5(hLpkv9C3{QMsrA2jL z-_nS$>Yz{1H~nx8X8wnmFQjVxDnI?A3xpt_o=dP?qJrzlU9a*~jlMW_2BLE!bsT^D zCjH_KTCn_Z4MF(24M0cu1RUYxYH;g%3XbTDH-e&=*#3g@i8?>1USJZZHztn8pdX!j zC4j(V$o$yYV8zh)*m}1+u{Rc%_=KDfd@>dpRU-C|PBG_s9~hKG;lLvX52a=J3bYz5 z9YxP7G11P-^nK*fXw0ctJ>4s?_1|^#`Up&)Tm)h(LzO6Ehog(3venTw*8SX3g47$n z{#PZ+_y2NaD&#YCviS^|{60fo4rFAanvs|oWh5n+8A<46MiO$Fk%SyFayS_Dw1431 zddv|&yXJG5^(-?s#XDp$?;kRn_YN7(dxwmR9hKx5jp{R;5X+1ja>!sx4;f3zAwwxS zmk|-drP-sfs8fmrIdU!|2%gIb$hnMwoXH5xEi+X@YA!2E&*VisGMN#2CO1OQWJe@s zQ-16oWom`gOh!P?WCPSpCP2+(0ehs?HsDTcCKE!=Ucwko~N0COxH=-yiv(3H(xvMw=Q5#2*g-WU)?g`Jmv&0d zC91CR;Be5UT5JrVQk2_nm)H50TD53D*{wSmtK4M9UM@bM%@tcr1fOhO$-*Nnq01!< zNusV*hb)LDkf~*FT^&&YxDUZPmFKq9*93Ynu{oHOYfF5)=TyHAIf=JL`4L*`WF~IS zFV8r2Bo4i|CQJ8X(Z$Z~Snc&EN|D#Y3C*|hbh>bc!(!2Ry5%E1%NJ17Ch5@t+-HvN z9!^Z4_n>Z=UHuF*S6!uSo`ARv{#(u$2!Tx+eqq`fDn-Z{D1qX>L+G}1r24&kEZQ6N zAV~?|!SPQDwih_YfR9?ymF`MjU}O2P3w8RnCN@A%SM!_;=Tv&4)(93!PCsbA0eUfp zwoG&jS|b-@d`$~_0KA>;$xSg|OIXkQk5!Y*4Hy@~Z9TgkG|7Z0C!oh;2-oGDR?m5# zQrx*bb)SWoJy15oWu&sYbeoK##!#(=nm2Hr>Rj06fJQ|ywDjEl@ECdklJSr&%S+!y zFXcF<>k^j}mVxoFz|gUW&ke-DNd4epb!QBIC2oy2|3PL=Dj3>zcY^ywpMJ11AxEzs`r%-tS5eV+H*6^XI zx2VYml%nt#A^1QL)e%FDiWPm0ic+dw#f@V*H7Ff;^ zssqVuH^DCrW%*DVeuSRyaelX`yt}gFtt{#wYbo$>34s5dbyQ+<5#|A zssn?+r|`z_u|5z@x~?7^!{$c|(fJ`<{|q0*6)Gkq%;5uE5JCw_oOru@510GVdRASJ zr$Yd#Q3$~}ZuPHcgk^*0B6-~|VEEF_3H6~-~!3)yv6^P=vh6C3N=m%%{ zi{O+J`6KoSbchH>2L({tY>8DaHgKo~)-R`4DBNGeR%J?$DYCbjMlMMvw)2RiyDz%( zOSb+UCCNm09&vQ)L^_#F9jQQTqg_Lw?Q`zv$t-q+cE2 z>)ufwcJv0t@)QXgF7z##?A!y%y19=}MSKS=K59p@C9BtUKzcxJhzTvW{`+b>tLk+p zJgV>5i;~K+#fDaVU}iPb9>A0z>8fGv45S2{qVWiFc5rinU_wWgGQg4rmYmdp^XGy5 zAnWoOSNy_6Q+~l1y%W6;H8jA=pbx27x7@v5i!+AHg{%o|N*@JkzAWErbZ{xQM; z|4V;uyZOD1b#r@Rx#pfK@pv!<8CC@PQB(btX&YUweT_lHSLsu`B)-czuJH#~pkOQV z7(W+ zjL(VjL;VMTN>&Tmg!QYBh^+gLIJArH$C!+~yRT~EiMQbgzt~$m(%&d7h!pnei6_es zm*VKex?8I0BZ^IXIdp5cg42hb4R%geER7O7yl+EYD4S4_Az{$?J$lH5iCIWp0nU_yo$}dW(pR+t3b~&iMy|<{DJYY7}q7JLb4$8^jfqO7L zc0zUreF_CF<1NG^`*3Fnj%zpAvG|K*CsF1#prS8 zF7@GYPszN9=>)61BXU`FUBRx;xt#+8QF=Om$|@wHc<7#qhnjQ4hY}ASV!_9!GtGk& z0s($U@-sPvtrA^eF!}(y0lciKJ@^S$6s?{v{a`9xqq#I^iQrIEJWoDrJ?wBI30Q35 zR2_#Bx$e^oCdeRWM6p1Z+JFQX`heOsyGL7}8e5H=#gG|f zs>vz%;ZK$Xc*=?ZPZ=0^Qu&Gp#|$6CW10}*)9=oj)<2>8b~d&CsT8rSE$wQ%?!H6! zlrSpc!h*Js^WRF5C91QdMS9+z)?aeyo)VTEO>|GfR@H@8R0o<-94-j+s3(ZsQ&OP5 zO4L;@1z=u>q$Ei}R9S+Vf`}vjDJkfkckrPcDipo)t~>I^w%w7QaCA=z_51U*v`W`H_of+=EnJRMV@S)o{w@l(j9VZSV^Y2JX#22n(Kby9?aF`atrw)ML1> zYiAHR5e3$>1KK>E9r9VD0s@y%@PVr*R2{(wwFP`~+0Q3sN7yTmTDZuX0uKK8+J|lK z7~+X_M(n^~_B6c8`BJ7kd*}nov!pPXkTjI0Mtw8{C$fH#pZIeuPSl92PWME0;$k

IqLUv)bHh}-^)?Im!p0!NBu5EyTRm)GC4z~+@LE-VPq?o4(kbC`IDCVnxSaW~~-8U9RoRKQXuyOWtrc%li< z=Hv94oDLKIIDAQ|Y*r{i$D`zspqXEz%_Ko?_-XS*X$AGbnCz2DkMWsRHOpwf8f|u9 z2cj9j(RFJAM(T{SL#$>!^(W{Q()B~+_?R3YljCDX!gSr%)t1$Zdo}+-ve_^|tmX&| zDWIXm8!o9`!m^2&$kDJ&|L8u0jt=e9F!$?n{K4dUUQP`I8>$=wIaYI*6KW@d@Dcc1 zh5*apzD(WWp)w*f7tC-)z#&FTD=UdIGePqnW=5kjA`=#s5!%TRt{}b4a8ycyB+Cp( zWh6pd1A`>XOh;Xf#7EOYW=5p0M%)7>vJV88HO*`Dj0T-=^aq2{p!83eWM3n5f0<++ z>l?zIPAkb~nCQ^3oU~-0@(5iaQ6^U#L;i#Moo3ui_jA*ar1e;JJcrMoIWM$-(hQJ= z<&Z;E9;x4kWPd}7u#&cOa0NCr?sBIIp($P z@dao*kyE*>EJ(#O`z%>sN9`8xds`;kLwVn)=}%HWyRy_gckvcY1k z)k;&TC_bH6n#qyVZz2AW(NzC>NF85NpTPA0gSEA$KgR2BIb0=e+u@8}A!Qd(+G zfO$?&?%|rs2tV;dbDvn>VFq8Mr|0$bKarl(8=7^t@*JOCOlN`=^!&-}pfxn*l#!K$ zX1z2}W*-JUA<_L9)LxtOOxL2BsHnnxX%O?JbbB--$#Rq*+aBq9Dhbi{S-LI*bmm2o%n3w9 zG)rhE+Enk3UuC&Z({p!c;t)P)TyN$LH64Ab-^+S9+Vq&hlJcWjA%+k1jXUb2QJ*DNc>YhlY-yn{!g;xjD6iwPy6@j?Hlv z6%-dOD46EV56&}(#=jI^bseeNNA&}do~E0Ss@M5`eIDa}Zm#~6nnQhVJ{Z+Mre7R= zox!l(Wu24mztH@vopR8is(b(_{>(?H%f>5S6@wcA}S#*TQ&1arai(Oq}y+@TuQTf zRWvnNO1tQ5iJHDX&)4!PH7pHVYWZ(<4^NVLdzJNk`(_uIAS!El^Y58Dgb%$A^!%z` z(^0B>U4>i-H0?<{-0Pe&c`XN>H+i5!&o9k=Uh7xqgkk1A0L5uSZC^Eg&9A1Ta`7Ef z9&PS4ebY|TOotB>d4_at@OmS@M5y1#(@2I!#>5w8&vZEH^qYyN^03St`!I1t?XBr} z3Td4ZCU|7sQmDUOM*o!8FY&m^N27^4x*7N|jxwZ#HNRS}?@L|xG!S*&qsFUt^ZDqF z2h?vwQb_ ze|q0jcU>>0=R0?t?1xsp=0oLy!mD1>SAR?E11T>k(d$%3hitcfX3eJ)sn0#M^;Cb_ zero=dvR^MJaX-;^T=lsyh+fCCOS`{btG{2G?tK2(^pDVT{!XaJBj!apIg>>3*EPkX;i0brUW=h z`%_@Kxhp!3=0o?MX}oxBmKc}o_*}UV`Pd!{G-Z_~UuUvoO3S0|2X$S{&+YD;Su|xT zX?(t!1(V5>`qzGwj+=NL21lUxeOc8-{RmqA!0S7xe>9!@N5t98DGR65iWA3KFw5(k zHMyAkO=f6Jq$vY4f6miyG=DA&7tQ-mOg`v=Aa#*U|B6Vf@y!jJ$lWS(m-!sd3;$@G zQ^}^}=ZjI}BLC6TEVGcIye4ek*CFefX+EbmXk3iDb{;86d6{^meu43?QPHHJSvWyl z#(&U!11~2@*n!gJX*zN**C2*v`hXIy<UgQOu|v|S(0!ZxpuF0T()#44Z|a=c)ZM0euVSu#j;`-U@C0bS zgf~>sxK?T|z2$|b=0Y_8BK$Lr6q1Ywe%vplWMo{<@nL@7^b0wC8P*f! zL69N2qq``iNA%oZH2EfSeER+uT62Jz)?_Pu_wPls=M+w!J;Na`np{Nds(gzk^9nGp z&w%JH;`%_G!GG{PTRok=f%=sLxzjv}NxbD6S&u)EKXw03z4R5C6(Z`+{Yc(=r2Q(9 z`rAqMr*!uVDZIIrXn5@p8h5HX>aP7LjYra@`D#j?Ynb-8RIk+jDfLTv8GWMtR=rZw zRoP8?sA&v`Wdjbqc8QyH^Zq6N!@PHi{s{0Of_~IKOT)(k{m9*Hi6Cn%b};pd zS`_VXYQJCeXY>?6*4LmO*3Rf(D-oyE?i*zI8&^8UeHH3fO?;-xRKS^EX&L>J$5kt;t+0_vWnWQ zH!?Por!2HSLzaKi^BR6y;w0WDXFRRozXkhx3)p#9!K^6-^T;k?@$~i~k2`$m?Sbl% zdFvXlW1K=Ebe_N+rS=QPK{3`v9WSUq?Z0V1NpGb}4X^9V68j_(ug1gsH2H7y@)x4Y z3B4;HZg-WnKC7G{=8v>o9%M}YD^;He=g#M^L`F6&tOcwEtOcwEtOcwEtOcwEtOZud z0+X(N>;v|gzWR>ldDje{|MQK-TUQ-tenG+BzNrgoL?OSEmOL_r|LTkkH~wkd&QI{? zFPOYw;e2xMcz+wyWp24s^vB%(x*3-=-z{=OOBxSnoa_%peq@^wX2K*dUDDt1neEJY zGJTrJ58wXRt=WI^43RHxShNMpPNB$OroU$%xp(G^y#4hfk7aeo6p?Sud}0Tdy+tBV z-p{uy%e{Mxyr{4JXqNM5iG1k&SAEQK59C7%-*|%Myg8!pF4^Y-mh&4#K5Wc`&#~MC z`Q$yGx}N3kCeeRA^OCPw_RJM|tIsc9m*vGu0eR|h(SZ+K-q#RpXIjw zMIIIW_-`!tHHvJO*Wp<-yURWdOmdP;Z!yP?64uiEWN9hQxblt{`LSG@Tc_IFznK9`mH9o^nm+H~;Q8T% zY<6;_%C!ELULqxLs1^&TY%T(FO7d^kF{jA%AU9P`&L8jaNY>L1j+FR#hevY!EGLI2 znF933FAI-TWS+lFl#lfMd^=gD9UlF%Ol+pg$^K<$N0Q#`@JN!)PLCwn?6XLbsU=C3 zlk>+rK2p*%J3W&9^G=UcIVHT=@zJlBh3@A6^8Oe889CH1_xqO}9!avypC;^8X|@dX z>t)ABvdkAvl5AGSC(ACqEB=GcJZ-;!Ga-!q9{u^1eIWe>pnV^_u|lh3Qu;KJoRS~2 zpgdJib1O;dnH?Xga`O40@U#IUMNd0GQsk8SC==O9dYAopzC8K-v78*AtjmpE7RaSy zI6WoO{%v~JN$0ZcDHpjvep$D>GTnbE(sxeEoXFwZ(H~CIo1K;^GM&(VS#~@o%e-K> zU#9*OZ7rSp&gs{3{1r#L^GD0dD86Ig+51ndFFxL_mz|0I@yX7^emP{~$G*bE4F>lU zHJ5Y7=_AK*{Qd%W{IYRt{uc{AWPR5jqJQS0hi+s!9qsMZXHPzi<>IBHKY8Tl>$2>P zxZ|Vtn;xw8=Z~|OY!7O`Xv;#9UY^?~?$4yBTpzvl)IyHGDJtKfLU??U%Vd zOHPmbTf9Hd?BC;8XPIA8dt%zCJ-@6mD@3A4xXZ&=L-P5i>Yb8*(x=o1uI|a{lT3N; z&mV#Llxyh-l#Wk=tT?rqm%ecE^Gx9r@bT^aP|2QIrQPEvZ@9wevF z*MIW);hngtdTs%~d}{+UK5E7IuRs61Q!Y6??~qFgZwlD&pX*oh^=}@aC*_aKNA@Va z?(#o!`QjM=^@o=oxcxG>7b)qP9o;RHUfrIpC9c{&;eJWruZt zd8qwJsXuZKvmAL3n?ICg;yYo~b$fDpdCT4Tmj$c+@sW8bzKgGVHG};-2fF>sj!xO9 z!%wc|*B_qyhvm-ntR{1%^!g<{zGLU3eLQqGcm%OG+-Vk!t2d#VYpM7V@{D6kv4Eo{!x4Y@T#$S=oxT=0j=vCgz zC9At~N0)vlm&|(s_^19yiI|Xgamf>0@+8Rfw|Vt*{xf=!lqbtE&7sqImVEB^=7Qz| z*5~=9JXy|U7M)(`vm7&B<#eaZ=WJE(g}ivv(NrsGKI#!Uze8A{U-%xn#}Km|6TOpu zmVEc|qLcQoG9Ipy{P20=Fhh-_<4k^U9b?~C%*Uu+602(4!omv%1*Zt$*>W>i@7hc88>Q>|aiyy9nLC?@Uc!?Um)2>gsr}k@K@? z-_dE4&V63s)cvwFUy(D!5!yXsb81+ z)(WuL*(33#-+N^q%W2QAIQ}zxXWzv7jQOitALg)kC*!KkO#X|`ywJ?oHoYeC-+xf> z0i%CX;tPcu>sgMywc_-(JZfK+nf!Zi^TI2b?O#iLn_peC56f*INPN$JxPhtPPOr#W z&RkYg1NVO>e;S|re7fa<(tq^quQ%f8@;;aN52(Myv{#=0hee4U7SEJUG%ckX9 z06|-uCV#AP4{Mf+iI(p|I04g<0ba*T|@l)d{gF6qs>JN z#!4S!tS010{&s|=(oaLC)O&vx#pIOc#j^1%TS>K%B4IVnjT>qZ+CB1~+ zEB=Rvk3WjNw+~ryeiHr{q}G>#>O+=O%+Wa&FH8S#yHg)6V!1a>;@>QHh-vS7)?RUX z-z}fS7k)+JbL-u5ma{J>=X8{>xW1@=&A4!tYhEQ6;CBxs%%eKo*^rU8OzEat<C>s({vCT|ITF6jbw0Ixntv@%mgDE>9sl85q_n4hFs^K0zxk{9 z9O*xvu=|{K*r9N1&2PZyTX)(tCHz44(eww(&+_qSo34AdKlOZReoijEr;HP9-bT{T zdH?zrmV34pS>qopefGyc^{?@(Y%)RmvV(@b!TvnkuRMNtdV|UC^1J>2SiP3#vVYI{ zjPu`}_xmroY~vFZn4s<}%a2D4zPm@;BxEuguWYTOi@z96iwt zczS27Jiec+eEUqhD8TlP?=9(%d|^l?%WWH{*5_5Vm)6HMI1>7)tl`)EL&V%LGxm`5 zGSAuVQubG|r^p{3J#940O?$1}9(sN>{_kray1bu4^3~Y=gzp8%hTf#duA^= zGLz-BMN+<3i*~qxarsv@ zJ&pggGxuoY_*$-)@*Y<6=0_~&M^+xchClV}f8EXgJO3u(@BDb~43>MkMb65hfie9m z9v6A^`g zJ|BHoi|+5d=}+Y8GZ*BJ^-U|9VJy~t+vx!gpZ%=#=X}0}^qq*}Io^WVWA~7J7;D! z@TXh(y}c#}9*L-V-Vw+1Uws}q|GxR=1w^#1Ox|Zp`!=UdnMu3pW_c$sAb+0d^vP4E znok^=2uP-1zfA8B&Z7_PB6dojUU)%!GD}B}q{K~l^TH(xU_^?KzpunUk;mqYn=mdf zcl@{sB2Vo4vYY?PyF$lzGPZMHUs^v0x*k-&&3p6z$niBkD&@^`yevA+uKuk1`c&Dx z1u8K+Oz+2BufR-TXM8L9)A6R~R*Apy&QX_f{7vhu{QA=Pht$m5mHo%pU9tZeXH0m< z=(p4Sqkr#D9lvROY7dpoJ}0y3OJ1wh#6? z@5Vb!`yw3bzM9`#=AqeDL4I(m{06+@m}5UalGE$<^J-}F^8J^8v97}C)EeX zu)ghr)ayad?>Q%~-^KduYecW}!_g+0AKoOe)4HsWekJ-duGz=j|N1Ug|7JSG$)s5; zJ~3f>Ju>YCrq_*_&s-+ts(RX(N&EFw&--|JA0NM6g!fhkIT8BNerlEyo1Xb|s5MnS zd5J#hS@!A25mYV>_T-(b@}rOC(i^IMwEH?(&1GVH)04G?{kSs`rjJ+Y`KYg^4cg+> zL{LgEzNS6$Y7Pp|Zx{+CPGHp%{;pD3A16DI6X{cW_2u-1Q$4||*8o*ZYD@&kE`=A_ zt=9-uAAtw%3WWo8X3m1+;POOjLd*1>XFj<#&GSv4O<$j2Jza3Lx|6mga&@HjkSy^# z0mUVuFH4mzIr8_0h`|F#gx!}L;=hCnz;bj)i)lN?NZC83%U6C1xjfEttj;3StW z^OY>G3z{^jeDq{LXS_LeCPXP!{9r9UCPOY9RdRTV-(=1BH*!+>Ici$nTjPt!zT$*T z5%Cw@MqPO9#vHKsc)5QZ7`vNVX&MidOMAP{KEvN;IeV(K*D7}wta!dMf6Tu(VgJso z73&{Za--ZIFP8XYHyu*I-eZ@DtoIXb&$*k&`o>!%e;rHKS;}(HUqoJhcjbL7r$4Rt zzts6}_k8%zFZb^e=X|-#qq6&cspVCDzr6DDj9K)b>o^_fIVpeXE9)J>Vk_i<%B$(i zcjRVGUQj6g=jI#FyPm^0y}WXJYWTt8xB3;Izkd6rKJWhS`TuG4_ib|ZHGF;xm&*Co z=SO)Ti(Iz)2Y+RKN4i{(d_S!(p|8YL$Om@HX6*L{>)SUJeP_odW<2cQD8)a$CQrVo z=cDILbia+zEx=ST+AmKpE|E>sNgJuDbu!^W9e3vNq?haP;@fUw?iizW($@*79q4wSOP*hq>G8qzzwr zdIQC`Np9sM9KLwO4-0?)HUBZ^qjjW&r}{%H^0c?Y?P02YR30cl)IQPdhOR#P{^2!# zwGVyYs)l-Z^3fG4=Vwdb+mXxLIqQd&_lbuh&vN+i#DT)ExIXot-ye2;_n&_WujQL? z(b47seajTdk8|2*r*ru*)_dw$VoH*5t^!D(Ouo}-C9ICA9@4xB#xDg1i z@^+BlIeVtV$Ix@-P<HtMpMBwq^@S}X-(h{m z%}8(lf@#wVrpv>0a;NeI>v#zV&6Vp)r}f?2g<&IQ4Q&Dh z{z$*9ydkl|`Sb%XZsG9JZA5>3`=w{I?93H;{;OZTV&rm>|8!~LG?oi1MgDNuOfz#+P3W=nQDKelqlS%?48B!piXjIU6MU9nMz)?}6f<|nypd$)KuV};; z3o`a7qQM#q`mM6pX`E!d_xFAOe9t}41C#f>d#zp0KKtyl_S*5MJWcpxYkMi*!(*mD zI|+IJCmbHyt8?-az#>=qC;H{CbV|SWIr9f?y08$#$Nb26Z06?eh+EV6`5f){()yVH zWuBjWZqq$9{%Y-F{QcO!XnYnmf#08CM;3kGyeBcny)=oUZ~aM-*L=pDzDC4ozo}b zCH@oN_^gK&wm!*Pf54Yc(MJ{|4#m*B~g_B)=p>nYeE;@jp>W|(wXOTYK#uq z@`ATt#qi-M&VTvP-)}`6cK~DGtel#O;9O6f;t__O8FMfYT!L{f4==$*40T**!~AvE zv|lTi()-qQILAlxZ9HFiB7SJz9dySdDC+*1+b6LXZ1{wqchgU!>HF__M%wcNoI)%r zqgGPWlD{n``L2!34~u!WoAf=;Shr{M@_HA{rzYg$0W|75^qPIhzO4BT4*$a9Tb@A5 z)6RJDM{m?4?ojJJlxWW2h=@xctV1*;)Ar3b>t3ybLiYy@Wv8I%aX{=g!@*brcB z){o&01-iY1o}SYDYM-1=i}6qMdckK(!gR_m;G|?vc5))T6jaBU&(6(F5TdL`Q-&gaLSQ{hc5Aa9&s>VQC(Ed3VrBsH`$X5 zPdo=>gy%u!Z>)FZq-N*p%OAi)b`1!a9=rqx%+F75=s1mQ6kv-2!HNcXF$QG~s(y$% z;5mIW(voNjxckYc@4$4&mU8G@2#?X}5HO`zzoFtcVH#eWFvw%i4%JDiV+_^Ff-UP!TptY{v7tb(k17CTLxGB4rB=lc@yQM1 zA-I7#J}ZX!)D1m83pNxmZy5ai_T)(Vv^O3k&j(Ii_N65!`c64z5|tm=1NpKOlG4aL z2+9MoSO;Nx5ra7q)Kd?1kB_;aci$aqo(2v6PVoySL4t#!bLjunY>C?m$XH9yEFC7CnkdrwG)1RFpatoG5qLbW#w+&qbl%fclo3 zotBu(TT~!_*~!V7x!DPsG)n^Eb5paEVZJ6OA%!xu@wPk9$MnXIRq0L1%FazonJEgX zJn_(o?1b!@R9>8aZXKz-sXU-LAcIgTAE=@90QM@+oS8YkL?{GRA@Tf${1Q`rr*kPF zSGn1kEO#PAvGZ!`C4das<6v4v+mYeT`4|w;ppD*8?t}%xOv- z^iNHm25k$pD(R>I`b(KfIzo*0pV+@*3A_C#^Uy)p(?J{T6-pK7*LmGsqCnD0RPE33+3(;j$pV0{WJjb!fxt^q1k z6!`oqDr)D8{WPX$QT}4=GSj&hydGOsVPI?z4GUUWAIqn>z)$)-ND|ri&=?5rLLq|n z5g|@3@^kP=H)v7k70+J`IMeFT4%5Rvznh##WY_T)yCuL z@h|7?k9;VK`Bv?Inkq>h$ok8d$I*O?M}40z{-ka)hHtxs`Jaz=-HNz#1>@E)r(w0x z8eV67!Yk94BkoZ9Gbg ze5l<{_B{XDd>TGHd_XeaxIS??<==ZKKi}_WXHfm>9?IAr9%lk_XmrgDy3F^9zJkd| zJc;S_$FltMf8T!v;uhT=z#2cye^k^!e+=smUgyoaoW_4qYgv9?*Xxht{opvp3$8!; z9mFoRUhYq=`VMhe_g4ZRCS&;(o)`8Nr|Wm7o!D7R@*}x^-n+2xTErd7URp-hvH7(% zl`zNhLV6Uff4SCkeXTYx_JQ1))SQkhtC)gXuzu837E~6|vqC)f*nxihbuZ)e+t<&i zKXGmXd~tK=i?DIf)0G&$bziQ(dxg){2hyii;lan#9M z@i%@LzkeyXGYAK(coQz@Z{P`4U{cGN&jpj#6nXe~^U^&9u*cW<;Kf6ch*JI;z@9sQ z4mu2~tejT{I-x#Rk_i}nefMrpSFM`91?A(CIel!;OGn7yZS9-vUk}0Gz}d_nKCu|P z1zPD~e!q7&1%E>vogwn*rqnocY@zMouxroXLo>e?MY1?SRkcQhV7@A^K7ha&UrA8CXhq{KX48iWTH&i=nPx^x4CY+BdurgSr}6 zznwqm)5Z59A9$4crGpm!fml=aSoZMm?HckK(ylObuAbK5oWwvoU<pt(C>agzU?N~2mRw>X#Jpjh<7pn(qAt` zhi_&~4&7E}Z<~nW;u={#_JuR3euj$}L;5FRY_eVvfK!X%l_;#DuMFg)GGK~6!8-CMuWk4n8{TQd-`eml8~)CQyKH#34gX-nKicrmHvEeXciZsq zHvEST|7pW}Y*<0vKb(3^^!G*DE2;m|J_z1V34F2UPkQrR=WzdD_$b8-?r*~f*zf=w z9%#dZZ1_MMKFEd#E1a}+;?MYJe5B`gF&gJI+`|5YbiCGzW19shP>N!1Vt+MT7VkbE zZ*+Xl@00jDbSqx`8@hVTPa^3H+tO>~hk5NK$v@+0=>KwgB$0e{4bQ)f(HLt1E3VV| zWC|Z>l>9JGRsIxZzpJM9yN=POQTVt@?*9n(%whaz{W6;0>G-!iKMo&Oy!bB+=;cS# z6I!G4XE;Wq;jdPzmlxw!9iL6{m-bkG(}{O&=JF7Kr0y_352+u<^XKp$6@HAyGt+fD zq`Vl{hpjl~Ex{QSpSwWHgK?nLinTJqnH0WN&p+c-b$5uvqe!OSnUSo{Ssy{3%|?)cw}N`txNRrTjnX{@U6lz2}mCt%LDv^2l<1?1$ELgtJg7Fuxo5pmF!{0zAk5|4NasfS%kn$%h;UnqmiJ$uHnLncbPF4Rz zpTsY?C;5GUpLGbzN9Az(B83-T^#3wwB;_YK9b^g@*HsAhSXMJWTt z###S1RGC9H?Vl`{{O?Z;n~a_|8v{_G9?=FS-4b z^606)*?Hr6!63GxL?2H}dN%f5g`XYGwTJaD`sxGfs(CNAraw}AqR$?`VByCN|6>fs zSGSP$|GoWE_!7c+bP3~}XOH>@vHzmp<43)CiGHac-{1EqHGpj@KZ9>Low{nxm-Mbr z(kJ>v|D1^jyovF|HT*OA7bh%Vj^XRB=J2bBb+-}zip%%U<5GtsZd>us^htUmmA|C- zkVhtML;ZoT|5<&J`sTf{_w+=Hzo+uMvHk5`n4XwxS-;e;Xq$g2kx#zhIr?C?FR;#M z^%Vb<+osU_(sILpmVUdwNLbSM{ndYS*Zd}quX^~LTQPriLB`kLbt%2ioyy;qJU@{a z{7>Wir{Vvv`t0eG`qZ)h_UABv-4FC$zIJ(gdPHAO`LWB}!^``fQn8KtFYR|ar{~zg zs~^MkdTjpD{;B?+(r3?4Bz+Qo^c5wvKPBcKPVc4nJkp5i3n~2H#wYqkK2mz5{H9L3 z^#F|D+sx@1*mpl3dfx9`o;~RoeT}QH+JpK$s(x(!y>cyL*Ile{Qu}fm0JJIGlRkTX zFdSYzg%|$ke&0}sy{p`seo3Fm+x7p`^6E)m;V8V_{|*tth>G~LmXCE!i)Ur zS6o2tfADPn{%-zo%pwdQc#Y-3{)Z0w@PU~I-nYyDe~q*6|Bj~iy58+Q|B|1c(j(>5 z6CX+5&Kvsd_7joDgU;bGU3l5+Ph-}z>+rtk?f)+S;*YW8BbJ|c_iME7tF7nyJn^9V zVW>Yjy}EBJ-j6 zIJ^m$>|d&2sN-UVwdjNC{m|TCD>FpXp5AZh8l>t^VSU5a41XJOV#zKfCNyGm z7*9LPOX+CX#QB@>spn9Ve~Izm3vcHB_sfiLZ#tRAYk@Y#p{FL$dT!@mjKBC{{SuOY zp64IFDQvtDvG*0mSKl{00df4Bj6eJG2kJk!D}R zNBSBDGcLdAO8QUTQ6sRWZW$`BG%OT4#$igyBJ~cD(3H7S5<)6 z{cpxcoi%9$;*K{MPc43!s$%<_jI)lPM(tlz3_tH-D+W`0)Y!)O$)&tMwq+_~SJx(* zI&Mm3yz!fpGf{ukA^f}^{r+LfU+Y}vPi~z@_0Ofo$Ke0643@6xn}l+||FoUPU!})! z_&{MPv`FA0v$C+bx*GTM!)dW#tB7Io`YUsQ7k|6e{ffhsV~qBoXhE8l0~>T;J=4B_F52UI9p&q~ zIDFo!?mH2O)PCj%e)yZ(W9>KQCk(hbhl)pVqU`E)K=!J7o+<)*r1fp zXFP&;(_%1>ttg~gX{;xN)B@P8k1lRP`Iz@v{_o2+(ED8a0pkrPWl;T%{*ZCtuQBl$ zzI7y*Pt^~9UX9rQ5%WhOfa^8edfVGJ{DHz77T&ZT!#8}z^6yQZO!2p?{dTA$7jgkD1pz zi+t%Ye*XquxP$uRK^NoOuIt-{y#FD_qF?%tooB71{&L_1=4TA}{5}j{ca}B0w7(*M z5(a`x)<2rn`pT%n`9){A;DtNGH46Dr;NGyZYBBxI;d#EiQJ+uE!P{C_A?HudM{wOG z^Zm430roDkUNf7*#|@GBW~%O5qw=>uMk^$~RF`Mmt^EIw(Ta$#*XM7!DQNnP>%$nW zgm_oJq=#|4Ixk|3MxQ6m{h*|;l)`JJGXKl3YwSCskFo1*#=b;$$iYJJJxeT`KhIYk z$X~=?G=&#eaIzH-Hqc67j7HTN&M)Njp}jLWd|_vI5JtzkJq3F5EGq!_ouon8|CSUL zv%N2b7oH>(4=yXjpB4GTnp0E5FCf~Nkw+0-Kk@SmOX0jZil05^`c!(+Ke6l`#9K;# zRq;Y_gGd;RwZH?74;-ZwL;I}w>gpQmKI+(rUm14m`fH&_kuSvq;SJkvj<42NU0R7p zrP2lV=im|1>@Tyd+Lu3P4xABAJ}}8XG+wOxFg?Iy+Q9CN^#O)09r!I#*y6yD!jlt4 z;jJDHNk7A`)cdiBQe7JneZ8~Sq4pkCJq;cZy_VM+ROa6_k_2CPev zV7Mnhr{J-`DKJm;{LO9b!%bpPiuKwke_Bb zj}Q-`1mjOVeYpQJ3u9DqR8)e0o?^pasLz*?m6WX0x<4Z+U+5Us!0V?wEQ9@KssLFb zycb{_s~@)v>B*vlR-^<7o8njgs^mCD&FWoN)0BH*G%;886a7~i3h-$g)|i<8sp-=b zaR)c22l8t^o>7yhDft2WJ@Bt<*k4yeOIli0Spi)>YWS5uEWMbZ{1cLrvPC__H$8c# zjxhe*vnnwV8-0Ct@du7+Jhi69!psx_>l94{)k5};v9;c@V{goLB5dIj&+smh?_%GJ= z!Fa+{UZU@Kl>lfz!DTZz%Lb>kC?fngl_0x*`2JZ0Bs>j5KpwuQ`9($GVob#^{1_X) zNa4cG*&6=Sw(vg*&%Gwphv_%;?VX;2`SWOV7sn{_lP7Zof{#)d*5l^SD>Urmg+EiJ zXK(*;9A2J?9$wd1Qf<~K{1jXK$EXL0^#{zC^%O{WacE)i9HTwI5`Ns2<0!=#eor~^D~u}@x0HQ&AdH6^v_&UqCZYupUNKAZ^!37PA?y5VZeX5XprYqv0AD0bJ6^W! zO|YLNhaC+vt=ZfiA`cGYOY;?t*y6t(aGm)ElvgD<=!4c5Iu;-VJPfu9_5Rl|tuLvH z+pXps({koiqRGsvbT7 z4uGY(*2F(pNb&vs7gEz69k0SGe~SgsF5nRG(^*?+exp_A%c{x$A|?th?C-NbMjof` zI6UJPydSOnnIoTHU0BAWP)(b@Uow3vyf5(l815f4^QXe-ef-3t{*I6&~)rb?|RAKh&x3N1?7^F>br5 zg<>22-ILFtXyXh?kK$!N6P8o{e7!?tsNXpD6y*?~@w~Xo==#+ll}AS|eMk#WZ+-=M3zZ6{ zhgTtxhu1;pp*CQ3G+}xhbWBNwty=~2`4zBw<23w*(yTkAx2&382VGwLiHeG{YCa)A z(gzr;yB@yg-IxzSjppg#`c_s=ubR?V-o2)sIf z%NxiCd>p`3}YZ@!8sGh}}0k>+c#Cw;B1yTa5IXYlL0@ zyK`>{VEE=nBfPnW)NMMS<^mg>`=Ttek>1j4Qv1M zfLl>tdk_9%|NV8vqsRxIRP8^=o1eH{|C&=D`WwT$RvGCt*HC+SOpm#S_IdnY^zG<= zp5wcza(gD~i@DR#NA0nyaV2->pN)J-@q6o6?Y9d5?y9r)#qiO0IhXIaKy*6tt%^T( z-nglV{dYTux5sD41CKmE7v4Tlx z?5xio{7d#2|K`f!|1lGxO5vF=@kAY;M5trH>o>lxrTm zt^M(*kJcAjpJ4vF;dL~!jA~Wk=_p}Hgc4e^V$wG#SGPmzyKvHfqx7gv*m`>OEzdr< zV1qSzP(}%uuYe80hC^l3(Zv{z=JS%fBmFkH|AW~SB9TW?a+${WjJ@I<#K0^e+rLEt z$*V2lcu#m;Kb!}(pcdw1R0o%4U3@TLDk`I47h_|{##qlj__L7|u*Q-pU6O3BOzUSD}4_=DAcLc8wNq#ZUczqt6d=mbaZsYju z_6hfYaLI$n2j6F2)>B&4dW~Hl&Nt7&;f8vCbY7t}D5dU(S>CdaS5Vd}h&C4baOh4j(K41V8J z>wUEc^t%ny-87!-i}0V>)*rvJ;qPtuR~x2}KIoP4>=ZR$A^3PTUY}#@uk-vrIz;0h z{1}b*KX~tx^ScW$xmr+PkJ9%K!&G${)Gr-ZR?OA3A5uH$d#gRI+9!jD{l(axNcb{X z_N~)i$lG`X>W{gF>)Z6SALx4%tYJL*g>#l6U)qmxM$TKC5I23s>toL!dv*q5_kqkW zyZ5G%h+T&bbKHKa$e(DTkN+8m>;pM)=}7 z@LR84vUxqV@3G3BUfK7{a9n%T^;H?_YdW6G|6kuHQ-95?aeceyu~Dxe-`q#qD_FoS z3@jFVuCgi1?nK`Im$WCvvUFTw%5dE4(I_`lrEtSpO^69r_~bYw+0fgD&^5 zKB&1UJjTp7!G=!)EcQh6i|Rm+fy=3%_4A_-k3jvgr*eFs{dvxLh?~+mzRD>FB_VE~ z&U{hfotGl6OJ^MW>mM}U=)Qo%f3*7D8OX=0{qBEvzjGbprhMj?z4O{Th{G>%`Cgx} zlj5)2!uZ9C$y<=`x{UQtf1#Y}XX&fVzxV4(`tWxg!Fc;wXHfsU`*+4$w{NBXKwMv5 zPyYGFg-@cs80F9C_0!&?=a)K|`QjJ$(D7g4bpM<2F)x2X{h_X{j6dEr@dFIs`3B?Bne`_i z?oj?VL!*ZAM1}Had3Rs`aOCTbK}R3dACb0{$&r+oywl+&-*U819ALT4*&2qFMf|W zPT4p8{NS6^Kdjrvd{*)2&m&*o#?Nn`{ZIQDaou2kAHJ?XzY%eZvVY2*ci9lco+Fqa z@c8yC5WCJ~eC0=v(0q$Of${ETk5m2YOk*6%_S}o%+p`$g>|5B0IIPaE*Wwjqh&=2{W z418-C=Fj^&V`V>us_3fRaXfq_z+OxF_f~vfZi)|y`GUkSJ@3YEnD6KPr~~;Jb>7Fre;@e};x6T1{F7bDe;{rf$>C=&om!4K<|xLa zzIZDKanwM5KVQ0kL=9r?K*o*@)|Y;`Hb3 z8nO{_=|a}`%iQy>N8Gp%<5{z3?L-{z$9U9>Rbym; z;}NoI5Pw_Z(E8XDH=c(2Qfpa1$s6vSK_2|~Vs}wF5GMb+R5$^;V|?sl0ZK?gp)|X z-wpaJGl@w2y1Xx`Dt}I8MaulelqB@;2_C=n_DRZ1xv$6c@aR-2knyR^2vGT%Zc_Xv z7iToS&CUbw!)koY<9Xd-FT@W6=yTI@(!j+Tn>3or<8Hk%Ha#xSD8R*g*9x=M=q>qi12TYELuU)(a z^#|PY>h8T@egOUd!5COgqL}_94d9;*{7rx8b~5Nsq4t&e)ad zd-U&ySeBn5{y9+j7eb{dp>_@42RQzhT#a#jKJXt}X!wi+dG;4a-r_L*kR0&FPl4e- z@^5B}P_RTu{?pKRDkqP^n^%yLH!lz?EaDVCU^19MzSf4#4)2gRJG4V=c7TWTRp5?E zswepW&CE&DZ=yeA@_(#*5CmB$UfsM7c(_wo8ITDBcz+gF8Sbxv*G0KJ6_ghUUdQ-T z)mkD3umuPC0+{bMy>B9)%SkrYr&uH8F9*E+!U8l!hvfwr9PFtZgmd8qOEmGBS&87p zIG5fh3=gh{lRfDPiEx9$Pfg3@(ENNe5~igoae5wv$;OBIyi6$Z6!2FJX#jaVVGVsG z(|29r8QE!Yj2z|{csw2>2iz)S9E7v8Ef^h4qAuadIk|EWh~d+6=p~{%h`|AvMV|Z- zqLq}=pOT(1EeBk{V-?2mIn&cTGbnW&e|mC?UZ10$WIw=u^-J+(<|b!nCeXNr6=+zQR384|B?WmHy@Izt{u`r2-n@Xx zyrF@y?w%Fur}$s2r17VL$xkz-*L=hr@I^lGq=<3hh3SJ76k(6tf?=A@f^nH%g;!^A z(+!ko%nA(53J^nT$%;VqAy(=sep;V3=`Vok%3AQbixHqa@uu`p`-;loVq;rVc|dq{ zCkSq-^XEVTtHQ^krVGu5@C&cw%K18#eb!8@#$lC(-erjy*qe3^1QhN096Bp+87|K;$43+B-O_ytsIt@|RhH2g*YtvCg8!BJp721~wlY z9@57#P_Y6J0$>YQMxzE!uj0|O1MpOvbdx-o&odua2z=#2?r2 zlvXHE0@DZK7nbPmK^5j1CrUr?)sR50EgT+;8>$#38RZen8&C1q8s{}4ErCD)~9zd;jC2;{18!KE6uTU)b=1F5JZfE!kJs&ez+6 zeL$!5XD|r|ZCl{M-}WE5Kfn3$QkqX|JAlVKnBGMu2dZ{?OJ@i4JapOWOHg0yfh-T- zo#|+Qiudrc%L|tIN(wI@QwX2@cKu3}Yl$}LgCo1JZN}@rm#?!JebIs=SOEPq@Fg z{z9;~tlEp0{I&NxWGd?G9LoCC`2(;Z!~KgYvQ~zJl+Pxj{O?PUq>=K&Rx-${M^ui@Wu%AX8!J_y6#MVNQ!N(ds~I919I{qGmn z(I6M@^Y{v0W()+E#4qWG?=O5z3OSw(|ilKbNbW*1HA*|UBk`p?@Ld4!w-x+n=@or*`oDfJ%KM+> z^fau!uL-gDsehKf88DR2$VmfB556RQ_VSnb9*8=$2t&F)V*N|+yMpY01KSy&RbQ|j z`RMRJi(lds{Wp(3fd1_M;=hyss{gkaVEnPlpV7v-<6lPH`L$JFPwnZ6FF$=5hL782 z4R0@xp5#BAltJ>*s(&l_`=|11{7L88pbfuWzV7UsLYThh-<;DoE9LD1mRU z9;d!y+a{jxx9bz!Q+}==Je$@lqkndeuP1q_-@@;UiGoY;ehi^MlBn|PweV723AKBu z{nB3TJ^d11^hY(>Rz_=-Nk@AJ(oUTng6HkbK)p3bp+j+OT|HQ#{yBXRpACJHXvFPR2M zyyPkjZ6^RT*WA~hq0=YlKqjnk z_5`{_#iEb>Sr`U+d!0w;vmCDg@hJ@Z_-gVoemwrHO4I{}{Sl`5u#%cU4#w3yo6BGP z7c}es3uw3i8;8aJ02o=p)soNeCzKD&ZR7F0YCQ;Mk7)lsg~Ir0|2__@D(B#NF)$wS z!TI4eRdDPxgkk$HvHn5~d@<}u(B%QwR+!F@$g}RJhI7YiU=N#qz7CvsYu><%dwtCt za+JM*Y`5KOzbcF`tH2_t3ipfRDcCUIhBHC>iU;o3Gw&!Y$J~^;^d$~RKkV1n&Dr$* zJu!Z6Pj~+I`PG!QM#fd&w$l1<{7S|zpT496`Ls zP*@H|pR_oJ?&pV?Qan%0&{y@cs%2-UYc)x0K>~Q?;I*R$@^VY*x z9@{4p8n{ zc(g|>)aZXx0J2gvVTrE+EL5W*-s5x6p{Bj*Q`${i#=oPAIvM;Je@bEc>Z5;LY8lPnSU8Q%tiG0ITj2D&|bF+9~>?P~( zV_y8##5~A&>YDRuJmPIp^0ovlv`)`xAG9`8+Z=A?@Unjh_|f@%^(B{Kc+W>%UM3z+j$91k3*i7&SaN~WA+cZ$ z9_&-?7-k_&e2t9<|L<1$s_Fu*s1PQYYLqi5&{t%ICVgn%YSv#|hh8v@_+ZV*k{XY54`Y8JP+`a~sv6XU@-2V!`|m56y9sf$ z@~?&Ap~cnp5r!62Zj3*E2K9$EWp6xi=Q+otyr-`bUzI7om_0Dj3|EvoFBJ5tCX5q& z%Jjd^M7~S;`viLcX)!2EyAS;7a^$;TROtoYtl;9Mc_$zrA0_dt21^yl1Dnsd0{Mpi z%&)s<;SR*^WX3Pv=<1KSUD+E${1ycT|5`2r!9Wnmal+Z_)^y6n7cfr<_Oa#1i!ySq6qjj9a z<Sev)E|u3cs^jx&AtK1M<2j=UCuhH-=(8C{2$9-qV+D1vhQ47z5Hwp?;XV9 zk8S^s><^oUFmCymo6;LTl<^%8kNFbA`$x0B&)gHKzP25~{C#^msekKIc(6z#G#iMFS&a9 zkBCb*Gk$#5Ge;tB-NLxwoOsHAcqgZK);?E|e6yNwcz-fP1Xth(=70Qn7RA@}I?EqB zd&z3#Bu(?VtncC>*#sc9m@C_?Wk9g4-92|+*|LCMjWO3gF}WK=|`NZ`kOC*f7mR< z?xQ(;PD=W0#NjcFf19)CbHp9WzVo!y6`K)9k7s`H^rNVL#EfJ7{f<8_MZQz*cUib) zE`{$>{sVLFsr~}_xC=S_PorP?8F7cg)osHP5XUZMzPaMpI}x`lyz$1zC_kY~nZK!f zSy$OjHgX|9h()c`AWtaGk>JDMNb3c zAx}=F`G?ehF>bkV^1T?o>1xL3?QEv?zxZnzAN|5M*X$fe#VNPvGxEK|e2im0|tjH4cAOsGZv9u-Y$hNZSSXA>TBS!(ZO- zBI-}ow{!TXcOJF~`B?Ff8nnbmd$)8PhuEXOch^q3mgdi+_i*@kC$9Jo`RKzK zKl;$e^nSJ~od0ym66F0uncoz13e`97FvbpFDLs_=x)(BbAzwd<@qpKcPMe zVcfm$uB{k8+Rb?S-**%ub{)vygSY!!cR%9hB<2f;Zu%B+>NLiuoiUI4AAy57{IdOS zxfc2O>C9)(9QFj_hIGci-N5HFbYw8z{q_!8k7z!OOaI5vA)sqLq}n_sOj9^9(>ktsxR$|zhvr8YR|jDAr6lJf`cE2 zULmyKr7ZvIqdyEqTw2C>OJy|07p?s19`n;`?%%2X*Ei1IkL3OHIJ_^f0`~qE`Lc_v zYs-tlFX~Aer9Ci5rSImecB1}}itmDB4oyMaGGEF2%4_GF{PRNpvUYxvdH)Ic@3mmy zP5V`zJmwPm-f9&leWv{@wH5O!Di>Ag8&q($(j~?;kPdji>*}Dq7f!%bLI0*=u^txj z(AD?si@!~Gu>KRXf2I62u4YWmK*Sgr!jUma1-XhuF|DX9AG~i?*OXB$gL;kD8m0{~ z;3^I+2*K+xOoTyr=>MR9pz1Q!;i3IF;Bu{|jE4v?-v$L@+)(z=K8lRw(Xx_F*6=2r z-wbx_CVN=0P0B-iOm&OTQ`LQZVtJsYo3eI8d03!K^x^&)u;TY=(U+#aiE%Z(#r5f| z*(bUXht&Bdr;T`W0pd=zpXS1s(&&9{e22piJ$(n&hw!_Mzq)4&^?w@PW8Ajy@AN(I z=wSTguy5U{ukJ&}x20!1gt$$uXT3Li+r5b6mA=XS7IY!*Q2TW}uNKn$KI-R~J%|n>~C2I5_3?KC?wF(A>7`4SUQoOUwsVY+wMN$a^yX# zy;=FyIXQ@1a=83fdk*ptU(fie-^SdAxcO+7-|+b@F2unxjIY1CjLI+d7{*Iqe~J1Z z!R7q^?fxP}?Pt@m%rAN@gTBx1SjN|d&+b5doeHnHrhYl%#<9%by5^@x5yz|jO1US` zPDb2tJoBxG<(DFkQ~Q@r8$E;C({^z177h0&R=rL6am6wI*ROBNX6Zm;u^74kO5xeV|FIn;x^$%Or_s4bD5}Hr-rgM7UetF;{7~Ye~_`1;t4M5zj z@Un_yZbe-8D(m0z;)~Q@31)Hl>3KhnMZWo7j&IUcyx%d^!~EK;5ibxQz!aYHlXFJkYBM;thX<3Huh zom3xUA7uW5wO>z0zFpz>2By~|u3N|a^)>Zw#DRwxhYH5h{6W`QtZ()!lfOW|w1xSn zzj*0P#I3OH4(r$Bqj%qhIOiVE)yD@x+Ie|8?*5m1|L7=gpk|rMHiw_Oey^U%&L>Mrx1zE`GjG z#1+tdWfZvW$MSgSl~Sr-Eef|?9VkJ4q0_m%Zt`|ooYYdqW4dq zhT-GY{=KW#q*8lP`V)umyJF7}o>!alA74=3G7#4lk4r4sG>cdY_-hTvRZERyZ;*k12-tyfaS0Zj2#eB}r zenG_XYCNp%*xrJ;eJt}A9`qNDM?21BJkC9bzW1?H7+38coQmNaM>Br+_;l*eyWEU# z`Rp{Tc3L2T@l!K@rSDbDR2BZEtEheJRP%eZe-YM)>7@iYv=;^Advw==YBZR>Hd*7t z{4$x}>&q(;eo-kH;1*M0_zzs;fib!?5Bc)6m|kca+bWqCPFVXF)%Z#L@GAMh`NyX|1R zjhfZe%(nh0Qc_d3SU2`ZY_k1FUiWw7$;-wMwT@w1T~02Rx3L2qySOmFSx|<)2&KO( z{%~?rv$JLxw)0p?@n2v*IDagKO(ts1y`~h_uT3t;b;mmp7B6xhU1{>i1N+;m%D`0* z(-1$5FD6WyL?02j2lmAI;J9agvFc#LXr`tNTtchhn!esmtv2YdtpXGB8r`9?o?rCm z18)w@kD~W8)A~AWPb@0aZ@_s1W~im-`m&~;os^a>>67x{6G)8m%$b>SZgMv4k0JX` z=?()9n7rF-+5#K)*=~Tb0+^HIN()~&-48zYqeo0piFoRfng2&W{ZrSs#} zU?Bh;YD0zL{pY6O@`E5Fyfly;pCI5>_&Pm)){kk& zOTr7Eosfz4MN9&p0h@jDvW+`by}{avgyBENMtqEo^*sqM`X#&-LwI$Acw=~q`q92h zf1eblJ_DvfVg3CRUdm6fq*$<|Sg@p6@Tn(rf&jzoth>YG{MH&bn73g_zeo^YBuL83 zhGEN}WPrj$`N|E(u-#b&U<|2MHza(W1w-l;ww`u@^#%Ono9xZN-U@ApO!jEBd)kC) zceM#yf@@amBk(6{@%9e+wcQ~5Hp84sBWyZwf-q!XzAtkAg4}@lA+%u1G%$H5H{L(; zhmf3}oX9OE*~iUF&W2sRxmnO8=vY-?_`Vdup3LfbI!;N-p+<^6wc zud-bp@yY4%Wj2LROqb8kUg7tahxP!c$W(@{2-BOHl7wxN(hqidKJ*D~#Am%@Jv{-& zSxKDE=w$wlgn7TDSpQ-CXhEoN_XG?nG?iCUa$>qKH#x(TF8PNCkdcs>4co?(VCD$s z*GzZ<%){bBYneLzg8l8nQ4zXJ9X<_5?+$3VTM8{ECBK5p^XJl;KsttMjXh8u=fn2V z;)R;pUMt0m80=Ye2>nm%9jo_z@NZ7xb$0`Lc)26t1#|fs293(TQa5l!4CXetofVEG zs)O<&1EnfB1V>@q;LGRw^>k z4-O!u^+SDgCO{uW_gG+H4ukfWRmEgVqU0ewJTS4!L>|9j=$jF*fI84b-dDk7)e5}J zokHu8QOZ7og#P#6|4QJ0CGfuz_+JV9uLS;A0{<(4{~weYU9QlCo<<5LKQOU0=bCmBEeyf%D>GNj^ z=O)8UOmbpcW{Sz5yCgC?N$KBXl^5PE{J6P}@w@)5@_&sp9~AkG&U~xzBj!2kcmJmJ zXE^g(vP%DYXFg8&?aq9v@Pp<%#_tz?vNP`*qv9`j=9@)+l{4QV{J3(*_+2SV|3+s% zUie+ke5vpwDjfB<2*1>s4-3ED%3JFf_{f5RRIU%VP)W_<->%=)^BYv@7=O3uFL&l+ zr>XpJb>;)Y&ki{1Zxw!{mA9rpJ<*o|6TJ!3$d{Qp2ldBD{a)#)zg_h2vg+4$q^k6f zSl}q%HdN_fYUOR|1J8)LaN?uxjz(7>8mIJcx5`U^ZqYxe$}#@f7#06yEAJHlxf#i1 zQzE+Yw{)b6zuYP>VcepBl{4QZ>EG(iN1dqj?{VhaMgKL`j`{P5{D>MyK2Dwg>>hEe zBVRA_8P4);^8PP%=Cxs}e78IEp@UTZ2Gv^Px0b&rD<{nhRWu_Z9VWr0Z1J~I^p9I; zk(V&B$0+@?t-P)uoa(8gM>Dcu1tKexT>|Pnd5JtHFAdHn#VLBxE5B~hKVp$%{I0`Q z{xh6;kMK*K`BLH6JM&(blwX}={M{nI%9(E$`K``;^bsokdz^W<@Z%Oc#_tt=wlnY1 z-_P3}<%1%>(JF6!J~_GB$=TUi**<;#Ql3vxp3g3;yzs5Uk67XuzcyUuf2lJcBm8=2 zK2G@U&b(jvK^Hp4pL&#fzU!U&W|7}+^&OZctM zylaHi4`;qp%6HsSi~haShl^iE+8p?qIi@b$-aPp$=fy^OxbPcutSY~ak>WRPb~nk# zOa69Q4@+W+^@PjUKw1sBPV{egmTwe((6x@~YmbnB zZx+}bLSeWkU(3a>S;uD~(ZAHHUw^+m35nC8UkJ{Jr-3uwtZdsCutVgxTjllgk5%O} z$a#DiCF94*R(`Mea}&T-?OxSGbBTPpO&~66g{6 zRaSXPf80yGKfijB-__{&e42zWzuu8=5q`Zh-zNMnXFh6u@97JR{Kgv`LzWvQ zd74|~cUk2nfLHk0H#w%iIYRoHr>gv2<1F8KwBk29^9>UJpqm}zkC*w4RnB}zg!FkX zKZ4)?JvaC1OPRL5|Lqe0xLX|K?~0&5R^~5eJIiaMRQfbAUFonTAAghjU zk>75W$Fj$(LCSwyg!E-3z(6iHZ!q0Z*n-61o|G`5n^~X|vV(O4RgDQ%-3l);|ZFJV(DDm%c z=0n1dTV+YVCH|bm)Z`@J%(UcmF~5}TX&n;(Y^%Hk=n(zaIP+b??{ellq^c~{qR5PtUpfXhc-IPdqn>(XFmRDRX;MU<0IcRWxj&nr;NPZ zWG@|PWUQk zK3@3CoOv&p=i>YAzrmSzi~QZre88>bH#zfu(Z9`^k3UMuf9lMqO8h@K^K}w`-`5?> zw^ZUE;>-txALY!)$n)Ryj^p!9Rebo@4oALG_@N&<^3B2@>&%CQKdlE|<`KsWZvMCrZjkGvzK^Yn?|7N_H-$Ss?z6v%4=LVN zGK%V7IBG|qekLC5;}%yG`U)z+NEbc(fvubmc4zo-lQFn^(XU3YdOxd&TfQ$6pgmRb z6Gu4m&2K6G=p!w>iXXRh_-cy5)gMI;_MBpXtRir|t>o`H$|4_|&h@&hk@M#-9IfpO zGEzQuM>8LnrsNBcA$j2?{cY=ceBw_$R-+A-YJQ?g$+s8qekK2B$7=hT^lL*|zxL+7 z{C>ke;Ql7QU6p^_yYl>YSe{>p;#;5N{i@;a9hT=8II9o$3&0ISH0TYNhDl!fFP%zW z8*m`=b>Tkd_$7bwQoowQmiNP}+68wJm!JFDu%&*Ks&=8iOz|IC`7RZISom+Pe7EA= zbCvv`R$e=Y%P%PL5B$UuzofrTrNjN~r;hE9N9E7G;xkMB)c$~^v>X_fgH1DaZN*q! zl*4bS$PfJ7A}>Meg#6p`{jF6#Ugf_<#>W?ZLE~e4 z{cMu>&-~IcePJn|^lu!?CrXWsS$RoDG#pb( z?aP5bI?m6yg@4YO4+x+6lcRi>ieH=Yw&q3~I)CI5ex)<7 z%~kr>I`b`XY$@hn`%3GJ-w#c-|MPx{*6`mAXYAA0-%TNimH%}9_TKpo=k@DVe!~&_ z_R4R&uy@`wEUH)e8_w(BJO51Y{DvbA=v98(83P=7DW?{XJl{hcpPwIA%&2ttKa8gb zZR-PVF^YfLnGeE8o8^Z(%C`tV!F^=(f3;*OWM_z+Y8Kr;d z;f{Rw!HR#+nGZ?*UU`IL`8J%R%0GU%Bi}0gE6#ko@UuoZ%10lf(l_8p$MnZZ{-!(g z9V-3xEoWNv`-gM?$8{6;e}Y9*`W^(8O8P%izv8kvf5D`)Eb_vq3O_o*k*^cJILX3y zC35^)4bM*nlT-R0W{Teh+w1AMb#wnKSe()qx`cZA;)EZq)PHP3HJ`a&xH&=)C| z_=WFOTKCx7i z&c9t;KSTGwSN&-{qJz5bN{zn_zEj8>EG~7gzx`_&grM5z<-_6{!g=h zUs_cC_gt;&|5MibA5wgMgW_MY@}fWfJ#HV|mw6oX?~?pASjUedALvl>L$V#^JB7c& znQv45H}?@t`a0Yn>ENtpWWdSA(p%C*Q#u*MCl z|NHSzec)3K7e9Y_emDH#+`kj~D5+Vqq&{FYewH9&@c5r1{zCjul=fh)Dpa^eZ;RU z_)Sr~wwvcSv=?UeHMbAZBh>frXT`rctM36IC+#mOf&bh}Pw27p9KT=QVVsW8=<^-< zpiA*Z&U~uqUt{IjAAwr<;Dtpvd=pG84HGX)V$}Kkd_v27miArJ@2yh&Pku+fJy-FE zlsNJ((SMUO-zoBsS$TN=a27ip=qzhDYK~vhCBHFwD*iEZ9OI7@{uC>}mwtz}A&etc zZ5*#Vj9nu6q9OSmT#4F5!Q+@^<~WjFgvYQw~bvrT*?)=J@(d@Z&G>&DRUuDCHLR8S^QiyFaH8hm+gmSP(T>kYOM8jxXUqsLf4lym=zpE#7yX{ESwA=nB>nY0=nvn@`df~0)~_|F^uKM@ z9~{g6_rN(Pr~hK-^t(^nOzH2+an|n_{bTxD%BT5Q*8jJpU+MR!sQ15=pO5=B+xiF< zChUg1i{D2#V8{OB-M#begO&YX5Ard}KBg!A%@O#RhkK9T)zUj(AAxs2(!0Dj0^hQ_ zcllT~zg7R+ELFbN@t^xcmal*RJV!pDc=vPXTln@)e!kK7^7qGGF`L#GrGMOYEc0+O zJJlEW4!`E2XT?;goPij_%Ez{{SQk1IK}5(VUceX{shGrTY1O| zUBMsu`D+~wmgg%xxHqQsX?%Pa+_u)ARmGOa|+&G;n2#BQ$_XVnpYl|w;pHO~PRX&_x zxj0Y^j=4%Ib%xa${u`Zxpg$=*f}$FB891o``z>^q)ME(fUsqDk+F2aZr}LF~^ix4` zl@St>7LuQfvaT7>z}x(NDH zBgi*K;A0#W94JF^`8Hh2=d_wy!&n=ey8*`JlH!QS8ec4 z>5sdu_w+~C^)9bn+dJPO`{$uZoyI5b2>JsN__j4h{7&T)j36JB{x_u0NxnUTe0YHo zzf<{Yi+kteBJk~zo^OQmk6CBL@034(g!mgH@LIso@05RcRquQ#g8qgG_1_;Mf6Wp2 zt_bmW^(22L_ZwWZxc}*f`orTdw6cV8x#H`4;3*LN*HYU1`xm~wcfPv^-shX<^}?QI zPjWWwjDcQvI_^!2^D1}d61~w9p=@%@a@zw$=lgFWzgUQhtszn2wO7U3D9;M}|r z=5ed_gsDGTdytoKZ4t^(TjgASDt=muzv%Es;Oipr%@O#R zkDT)-@pttg&-o{x^F?KaU}6o2x5MdEdzF8}L+rNnCAH8|b^N%5!e>~1Q|Co9l&p*P;Ur%Yi#Cd+x|0L`0?m@qMl^Q>v zXw@J5CYHw4u((0`>wC~Yb-)(-e1y(*PJdAJpTzp5e0%y`q6qg1Dt{8Np7SSm0KzAp z`ZC4uUd{Qim+z?4m~WV&r;nOTng7;udEBpM>+=J|hkxbsJ|ueW3OXX9N~zH_9FFWcWz{!MU`Cn%(zlMApf3(h1 ziAny0cdGX3)c%woS%36AWRo}Qhecjw&*Z@oSy=`ny&7nw|Ne z@b^3OA>kij9@{UxWc^k9cq_GUv9r1TN&p^j*m?IooDO-ud)2=yto5gUw5|LG={&_R z<*zN^=dM-h&)>?g=X7fiJLgY(NbxPsd`P8Rd&HR!3;(GzudPw#{{{0`*~;g#vF%iT zjmvo5ccHy}DL1gby@AU&R_$hx@{Lm8zo3f8UjD*|6yKBnx*qfokni`soDaKx;a!Ti z*N=iY&R?6-Z+eCT{WR(~yTMc~~L>>Iiw z$a^Em$49WgDD8oV`I+>zsW2r&hNxi5=|k@@nZ7tFSoPc1gS-beV_-Y#Sz?`E>qD#P zhLZLO-rm#ajlc&Z z@LGiRnJ)3~*hBdRAL>1QF7eOTgM51g`OXM@Y6SZve+0fU0w0RNH$})_*fxJG^;haw zO9c7&2=-H+2z=)!y+5Ds2=a}~dzTNMXPrN{=P#`MQ@A0+IKOV^L+AG{9~j&F{HLc*lalOAk z-4W6s`&jSkZ;OzAcLe!B1im!_9~0p8h0b`luhaLvGlIPKc<=d(i@>Kw;KLD~kNbk& zpKo0R{jpc}p8ik-d3OYPZv?(8g8op1`saG0_w;u~kS~oOAB<4G?(*Ktzb%6P?g)JJ zlfCCJHUi%oq5NBp@BRG_M9|+5fe-hfAI|qo&&A_bQxkH0aC|{B41N+a?W@z8*4=}= zw9l;(;*X8sA6TpC{rPFW-ual;-k(ou1l}KkuZzGpN8m#d_>KsCu!r*df7rVc__&Fy zFPqEU<~9Vvl8|7a2~L1uZiU3bX%k{{fH}Q6oY;`V*l}WxgaHbe+vTduX>J3Bn%ga< z70?#9e6%h{F;J+10xlFVN5S0R(`rVe8O?e%GqTnT^6!^OtEV?J|M!3I&1f`|QvAXD zb~5qT@!P@e)0IKqn@PT6aDI{*_$z*F@b*<^kT++Lm!?@C?fP#9{oXqUZ(m;q{i5HA z^;7)8`;Id4SCU4bw7;@lTt1Oo8SLMbsr)SmFTXv5eoqE@TZZzjZJqj)dyC)SnfU$S z?JLb7ugD+t1fB;miNkTE-On_&B#-)7H8$8eMOIp+vn4VZ-Lw2|MJ#hmr)*6AHE$f((lS(pJb5o=aj>D z8w8Dm_B933x2I11&{8I938HU*7A;Ky#qcbwJBIo(0p8 z`~Dtyeq-f|Wia7Bf9dM^r#4ijUSzqrzPdWqD*9hvn&;Ep>EYCa$EnXs!9z5YX8_EU zvf%wL3!N9dIAy;|s_5P$)qe7mY>B+^S+RVy0S|x){>ahM2E3R-@JEi0Hg*t54fp71 zV}wvnj*d2V6w1lb(Z)_fIXODo7%7yKqod&oSI0 zjym@a(;g9#-E$%<@%^r7t@srn!NfVeN zdeY4=$pI=|Nt>sM9P%x|b#z5?!G zuUPF}T#RdR3-;rY$<`bL`h z`6~ANPw<>(?ULp5>BpZ|)K%BR2%rhcm50AIYIB@jKx zzxMi$D*L@jQ_JARK~pBrg#kQ#sb)^<6i(k?04}HvU%w_tZ;p>R_&xdn(67$PeJ6P2 zU;v-ku;68;_H|FonNGi%{G<>f+V*MZ{S%zNzX06Y7BYYG$rfqs*OKJI-#YF%h;zw48z3h50cNZ^GCG&>KgLtltuGb z&WHUa%Tv$)6a3IMG%kaWFD!))f<(7Be&PEo)$m~k{5U=~ySwRm3j6PqTQT-0ClquM z|K6IB)AlW{U$KC+kbc~S%4-{z)K|l!L-p0CKvzi0rSiHJ4Yf`7D*{poh@5N_r2Z?m zNmIY)yE4@c?(<2s{Kh)48?0}uUU|~8I>>5^NztioDJg&9wrR>=H6LEJu%xPPK746n zX*JJZ1<^kzoj$y2VL8rm3u{hhDu*96ME`-JH1$_its0~NMD#xyOh0}7twewC?bFv! zx)4G8OSi-R(ZK63JQa*qzhZGMEN@)g2;T~US6NiM<0r}weoY(apHvRSRr$}s-~U)# z4V^>k+aJsA4}j2*e_(m)s4a0$q;kST^Ru}9b9UhHr~keQ(Y3c`Io7`-xPBFRi5KWs z68#4x^e565)DitBS$%RwAHnw~E64T`f4`-aXv6$kCC0bah`{#o&|nzPVg1oU{Z%kH z=06`pD~G)zqCX|DzSq1)3DKVuT;F3}qnzl&bMnr3jr6Z6{}8p``}rHAjqr0taD9*Y zjU=gmZ}$5+m_K3twwGhM@B286ap6Z3DgP5;`96JO+;rtvd5s6(%D;vEK9Ez2Vf482ojLyS{44Rk>LwUvE?>gWzZ%oA|GpVezl!Z43ZBRM zp9Ix+l7l-x%(o94IK3Pj5F5ZEfgSpz3da-L^Njvj5SpDL61e;WHS z!4K~*bia?ZD}H~1qfhujL_UX=)BF!B)oV_!t0JF~Te@Pk-HW7^H`c+GF?=`YFlT(4 zTg&ly~Q;flIbz52$laQ%e; z2gauOC+{ypxcmy@pHH&o6Mhma$@t#UC;mg^HAH{TZcKa);OhfpPv`w@$>(-U-FYL| z2Nk$|y=Oc37m`~Q!<+2r`=2Y$#qGZZ%crn%mmhfb*W#tsP4G6Xs`;zt*Dl3#B%|!{ z+WaNe;~JMYHdHT4tb%t30C)H&Tr}ao63mYYzn%PEkdl;tFfzqo(Y4OD;E|nEzdMn$ z#p*`$7nq-KUuEzUc~6@6r!eT>Q`-{JSgD^h}cW2_8 z)Q<>14ZAb#YsJTn37DUC_Dnq)unxX{E5~`y*ayo;@0oi49g+7E{g1GG3Ma?@m0XDP z$CG=e@(1C+7xSOE9>?c%d#1j>M*Neszr)Qx<9zuCX7?5}!q7hTbPK%C?6hh+f0=-f z4cPIQc-omCN!~J!dH*0OA1%V|n=+m$pU90QmOmht7giJfy@dKL^;kZKmD~B3w0}`G za1W2?z@s`|5E`Y=Vhc-e~OP8t0hIP=)a+i?88IU(g)gx^ZszV;`a=L3@s6NUU( zD=_{~CW`Hg+nGFPZ)`EPf2ny4m%r6Msq#tw^5UOgzp{35?ZR3Zi@Nv;4;6K|{#*7D z)^FU5?fc}ucx3@wzi}&;KPQ$~xbZuQiC+uj>c;Q4Nj^CV_n*%EN*9(F-izb^IaW^E z--hj+oI?6_r+ov2-+i6uF_Y`;&*bNJ;y;h$_HV_?N%=)^!_1DeWWxdYkW)U)|2Yqo z!SqCR{mRr8Ap88;(X(bxwck+>3kNFZ&Yn7b+BCSoc*Nnjl&UHsPkombzRcjf2Yqim zzN|`}jK7%YyqkJfh5hEp$um+Vl>EcV%Y|n-_A#D1BxPTczq%iB+HDf~i;kT5XT^^l z{i0j2{yT@H>`(Mt?sN1jvHgwD9XZi2#&#*eTVsPmQ|%)8uLhTI{MoUuvD=|3`;+p^ zar=#@v3x&PUV+O^G~)UDcMfI7Hz%4Wd3 zzWuLnHxOy(e)bc;_8;rtUBth3n3|IEa`=3R;~#s7<&fSS`2k{iE0O(7W5x1z zB0oti?;!Hi#PUuezfdeMGI9Iw63Y{_u>3b-xkbwVi&$Pl^j{XsyNLd~VtEJV&wPBE zkiRw*pK-Pm|K|N-{XSx!C&c;%FFJX|e0C;dA0FQl zeEs3zgX<6S_$Pet0aiZGESpm?c}ki6jxP5V@F@$FkoLVHZeNnfKNibNeueSnAHm?K z?Mq#K!Sw7xxWHJx0Y{*l7=58&%Bb4#(jgVaBfmHX{iCp2Ie(LapUC-&lrxZ6F6o!o#*nu-1>R-e@0M&uLI$VvMS6U#e^e70ELP2>y2^5WO9{p-c@7W{ov z^K7x)Am5+5SuC$1-@m$_m2>v1Yg}Hp@Z_bd+292uwUGSq#B5=HEGP9p%a%{<+ddLs zpKg4F(Ep6*o$-tL#%%oLIXiwZiGA|f?{kszEmHmnary0}eV3=vC-Ns)IcJ}Rt5&Y8 zYnWJ9OX_v~|FE*dVcjv!z>{Yj4qdWm{wd|3_VkOrLZi;T0fh@H*qL0vv+Wnu->_(6 zgTH<@|Ie6um@~fR^_Ky|E9w_D5P~^*9oz(MY*2}%KvH>okD65%9k#1Tgc1dE;<$Z?O)fhbm{6^Qn*N7zjVE z<@Z!G@)DTrwXf@p_t$f__p#q^BNcScb@H3_U^RX|(ur@FwN3wWd7=#4!s~E;gnjS) z8#$%##=+%@8wQuR)H>HcCKTw*Upw=Ar2MuF@4qM|{XZy(+E+-v@A2#7gyV-|BLA~k z-i-4fI+gwY2Wel?Y>e+)vAmPy&&^H{)}JK$BgOI-A|Ef7cjES&%d6P(VIgPAKU(qk zM}D=y*gs_>XMUoH$Oo{zVv%9r*&x@SB}Crld|%KsY79Gf5jnx%cD{o@vFkFX{${M- zo5a_@+q2&vX~lADHJ0zs$~%jk_9vRK{1{G-_1orSc`YmNBJC&NKe>RF_mKMW^EJjV zSUJ3wF=anQ>i;z>FNB4xDf_OAzmKx#DXA6d#6BfhUiT|!ey#WJm4+R8L|%&Jg}-y= zzj_~KzrT`v8Lu<7Ncl}h1?aDvnx%v1^0B^!@%3JG1~b3ViRB6W{g2*jS$P+h8wp(g z)9m+Moc9YjA6B&Ia;8k4Q3el?loQ^`Hu15;fA3dkGW=KI<3@o~e&U6*VC9_sj&8^Q z3O{u0S9g|UpTt$%_hBA#nOej6*V!}=BXWBEg@yc^3)9>Ve$Sh>;fl;8F+mcPZy zO)M|G3CsV-$`O{MUt{@t=cf22^Gh9A-v1jc--ea^1C`dvt5bs$p?x@y8nxo@6BUy06P+rScg(>&ULckyi2j{ox&4??q1}{Ui{-^c z|IcE136Z}fmX{Lw7h<_d@moA~=uT||DgSl&OuX}_^r zEHC~H%byaxgiS>Io`kN46C6VtSme&#a9%6YjkslzIcaiq}SS;@(`p1gp z9Yp^mvAj9M``Ic+;p>A-5OaOt@;epx6UQCo43AU26p_OE2Xg)XG<*F^&Zr>Q#|Ksj z%P%1H|3oZrItaJ#II+BEeJtO&QdoY?!B~E>SUy1J-)88q7~#F63bV>M|M_`p3T`7 zZA18Zo6#p{we9KjKgscZ!v4pY>3k0)Ir6>K`aiz^FuriEPm|-*$Y*2yLs)s$^jUyl z#mTks_0kpY>LBto3LN5zkvb{k8b`Jd$Yeq&eACF7qO z+^-s?Sbk!E>WO+HFX_bk19ge(*6f|7Ji*wtWil zHu)_~D8L_SUklc6#oOd&pD^+^e7v2=N3!x1KTE6UFK?`~A2~}6Q&+-5xl|$WUl-OZ zB=s+6^}DgWpnz7WdWe~jfvisgl*{Kv&|b2}%#dhh#E7+==Eoc!AR zxLDpp} z=E(;$<+oz|9SO${=IIBg<~N9clKR{6dFF^infVWT{~Y$<`5m%8uo15hOeZJH2YESJ zf9L3X*LSe%-{4oOX;h!cm#tV;O&7?emE!{ZTA)h`hZ_9)c>NfsPgj+(`ow6 zFj1HKbNWYr`Sue~bbVhsIcXx5r`EqX>x*g@tS0q}<#hd#Sib0#LG@vM$l&s{`VFVl z!}^}8<@IUw>-iJ7_Q62Ap#hfXxC_wya_59J<=g9vm;!ixyne@BKa@u9KH$#Fp?%P} ziRt8Z;GN4FPF~=ykn!uUtXniOt^HE#qZWDBN4f6@an?UU{r2*uLG9x`K~#UkAoUab zEW!rn^~w6HG;(|WPU;E%hQ+l_b`hL@9W2mkpwVop;XIQ^Df3WuR%NP0b@%l!0d1D&+Quq3v!-w^k zR^#-WMt?~LefoGkSN^j34JShvwdj;aTmdJy^LOeI>s5G-Y+5;9fSFcadP=Qbg+Pwi zcc#Q?<@+>bSpSKa@TM!jRJ=Zvt}o4?KVeeZ_S*xvRfCkDl4o9@>U7~;`{4~f@Nn|d z`AgtUV5tSHgUC|_aPrhU!n_3xCbtWqa_8H1RjX@P!i!$)mmH-$gvwKH!L6S4>Zjy2 z)${9^CAOSCyr6GkeQh0m!5@|5^|{;`R1RjfUn~Sq@K)EtQ|3PZh4(k59?pkXbu`lN zr}OJ~*9ARTzl*gESnFrMO^g27*XH*6UV4Tj>)!-lU+uJjxxONr1)E~|t73U6S^s;& zBB6c_kv}GucM$nZcKtA^zil$E|KP>K@;ixqnONRU(a=KFfYNWE$FiM%eu`kMZwgRf7oyLs^Tw~r(Kb&AkG+cMPOmqA{_egBaEzFJ4R z?=!(GHtbnTl*WDqSYB}}i;w@lVhQ*CM^b+w)^E+AU!F#v@RQ6SZ_e<2!|n|7^4nQ_ zr2VA+x(weRG}3$@F!g)!u2~~T0-(t{|MxWG=GJHR; zYX{u^gPVl@)tlk_g8dolFUatHz^)APX0pELl2e84Gc$ZYusF^8^@)9q4Brn-W{`Jg zC_ho_+}|^yLVFBA{DaN^bB>t-AcW!1EKbIU48#dw<-kJ~q{L0Erh5w8CPv3!8E|DKgX{a&(u^O;7W zJh?qC{~NKqoyZ?sCDiXB^7qB^R+67yUCrpT_JO61sZV53_vhua%Vy7>1z$Me%x5(1 zNccIODW9B|+y&cr*%^$SD<9%_&fLj!kD4}zHX&6+3(-Ge4Wm!WH^}|*OT_ZZk+^-= zpDEODCh}**a{HkfyPq~+5wG9vCHHrJ!rs3@Qyo2neBboAgPHq_r2WO@{?CX*nD%uh z9Q}$b@%ZQDLsIvz$o(JZ`{c`4z-#%c>*(uas#cy_=gvXcb+nQDLmPAVhurrkRKk}l zj;NYj1}~t7S1gluk!>5fzxCdsO#6tuleGWQDMEQSksmmfk-PlUCx?CSZm{dw~+F`nklv)`}{M0`kIsu?{_5nkFx8_ zU3{ret4y6W?=X12%z1@SO4*h3_I01IcIqfFaeTZtONg(Z_}^Dzc_E3fjVl;^w|=`@ zo-w0r27KFOPT6dGiFoSfcpAzP$1(Uw`H1L0c08l+)G}9uD)#_=w7PkRKQbMspqFs+RpP=6%|#fC$MHto?GrY z!!tndBKCXiM5g_u30(x=GgXY7soyg`AbMn5OxEXrBi8q<|HmT?qUmgVN&P1zh4t@W z>OMcf=#%z&w8nJwU;JZgGFC2~I<6!ag3GJl( zWny`P%r9Nf$_YN_`Gv`I?QfjIx7W%lr^A9e&tCzVU;BpDC#RH>`L9dF^K+G?{qKwA zt)%>&#PfGuM81ZV_d)~g{E{TkS8vEZzf9VP2>w@DeIl^h&9Bg|?`8y3dKR4@Wc#qmtSli@LP3_i9 z!R_0$mWdy7UMrCwES7f>`7*J*;A3a}*L%@g;rcl%&GjLvzc=0d4L+eI-S>;I96gN3 zpYYr1;Mn=YlFq^99p?-#@5&%Y_2TPif)D+E@bW9}8eHCK4K6nx7t7)KS^E9PROS+X z9??jScl3LodRgcnO+@~pSWa-p+t>oJ1!4=t7KkknTOhVTY=PJUu?1oa#1@Dx@O`vE zo`JMrWnW*b`FO5Hy$olrCY$<5y>igZ)3kuJ{`(uI<~vEFvu{7r618pIel@!ht=N9V z5^CGnerk3jTCx3zCDgXD{nYG6v|{@aOQ>yQ`>ENDXvOv;mQdTq_EWPP(TeRyETOiI z?WblpqLuse7l=Sn+Uom{ZvDFYO0Zp}nE%-Rt}`g?#Qu}({-Z#;M@651PhkqX`t>7) zTB%Chf9TpT*Y&9{sO-i5tINNN)u~Qw|JeT28|3$5|IzcGy&4NVu!s-w>zElXujKmL$PwXRO~@$0tVg`%{hZ-1p~ zT_t_{BeyJ-9ew=Su3rT;)zQaK%Tn3X=U=5(s-uq|(ZUq=^y^os)T0vH-(w7gU48zL zLakIKuAkaMWiPfLQZbvWll%5_p(yR><5#NIRm%PPk&8uTM<0K#*Pre7tFT6O^v56B z#;;p{uIp1SRrd7bSEW{}6W32|p|Tg-PsM6fC$=B8h00!RKNYJ{o!EZV7AkwO{Zy<* zbz=KbTd3^C_EWJM)rsv#ZK1Lk+fT)6R429{wS~%FY(EvNQ5}8zAzGNip8ougLZu!R zef*xn6n6FTBZXS2O7`*7wy5l7-+oA?*{+U$``x0HcJ%8Nr z*3!41Zv9%#*L-`n{r+v;_Geo^wx5m#vLC-Xtsf5ltJ{8EeWX=D_Tyix`61*#-THOy zpX>GOwqI92+xFLOf422=-G13_{|~)>UH^^kr(;3={#&Q^FvefH_3P>*tpfDN&${*N z>TAIdVf>Zt_UqQKs~_86#{${Ue>$xn4*65pe|7bB?We1++x~3p>*Ckd*TtXh`m^2s zY~#=M`gPkM>+4uRfBdUcyWM~4{psuLm7u3R9Pnq`{&D>}7Kr^%$9i%6#r~u1KkMq0 z5ZhnJdU5>5{uBF;js;@>(Xn2ffAWkCl?>R1#u$a5sqcSCseYoA`}GqfYFmB$YV{H= z{rV9pN@<(@`m^1BC9}Co*|(qD6s4WqzyG8J+f~Xwe&n`AWk=utRBEL<*{>hb#whIR zw?EtUD}eT>L1?&C)c9@!uI_+@Kk&)2UXu?0&0%KiE!0duG4 zK7Pa@lKZKTU#>p>Z2kHXU!>IU+^=5>uJ7dB$B%rNWDe-#m#NKvu73TE9gOe{6T9HpQm3x5*Hls zXzte^5NMjyavwiRgDlu#ef&n2*S};Nf41w7?H|n3#b@Qd|BG=2JsRKt32G_vc_H|Z zxZr?C~qBLje*Po`~fQRGyQ9w(H zPs@J)q1%34eX(7F9@Y21TyK9+ONr0Z_djvDL664u2ep*=yzJW#i5nL1X!hG5u%T&A z({DdYQ*yAw`uQ(dJ?YNU$Dgj`V8^qM9|db@nzOQRzcdXCcsRCyKtrWDO`m_1rsQCU zbHDyzIMbaK`)@kS1UsJl{)2)6O>>q${xk&#Jgi?o3Rsi)wA`;>j4SBTIDZ7Sl=!^d z_a7t%7VxM({(u#wIZeNQl&0ihhjYLFU^vsA72{85nPA7WZ$A{Qp=r+2Z-1JC10L3| z9|f#Qd|K|;FUA%0Xzt@jL7@uI)5k9?Ht@lC{1(_$!V_cr3C$AtpuYd3z;%gE%zpji z7JMpdtl*efTX15ULwRZ5fcL*N=ktg4{a=jWGrpoUzrU~bf1U;}e>fd~{CVkqi>;sT zZ2xh6edI4x;)p)~5|s%~)yFR=RN_!vzl5;_r^faZ7)9bxY(FGnE&r+d_RDtteoQh) z^zqBo=0Ep)(0}MY|E#O;H>$*un12al2~LgeCoqb{q3qjFqOpQgzX$nCfGYSQef%hR zWr8!a?>|5E_Uq!;)fYI0#G%-KvTc9e`g2`h!dV5U>gQiUp%RDm>qio``A^l4U)}n3 z_5GM+j_Bi;sm*_G?$?j}pd^my`@ckGf>U$9ek4E@{7~-uUvR9VGxhmLqGAId)3^T* zz5c+a7M`eYe_^qK561NeHkI(i*nUE@1U{&5KNPqw(TV!?i%JcCOuv2DnO_$4Y6oSOamk)Tz<59#xl?fQdb6`h%V{GwI`KbHIL4~|uIX71xhB3OZs>EjPv zmGH#u*Dq{V;Dg!E-+`MdJW;>>NLX&rgK_=2ZojzwL493xo__wzw*5t@f*;ezAG|Kn znc2@jNYt#r$CSUHetB5mPgnbXd&SwL{_NoIZ_IA}9cPgG15+(LQI-GhHQB8nok{A? z4*zxMgj4^ahLLX*)Ba7dQE2bH_Dt$`=hfS!ekX6vbB^0G_(Nz{=l5C8Ha&mI)cKkI z)6btMQx${C)3-k%);nNB#vYODbFGrD-_&fsuD)*jZ`EwSuD)*j+cn!CSf6Vs_p{?% zl0VY*e+f=Q{8QThPT5p1esuNgHS5>a=gcT=zxy=(C$N5!YpM9Bbo<}dY`;%mZv>qF z`887vm^+$YpF1(l&s^6}1Iws8$QeH*raIen=Skzgd;>0jNb;|%|32@(>5v6GF4=lt zp?OAu?^uunEtin|ucqH|sh)oKWqSG@4SM?BD~Wy(Yo$L&pTG2F2a&|}2eDH6b7K3Y zw@na9Y`-8@N`FrF?T6AgE`TK4?GMmI=9JRQ*zriV+aK4@&?EgLwx6`g7=_q=j5(x# z#P*Xm8KV%}k1>bzkJx_FCSw$0`!VK_{*itAA?Y@I74+{vc}tVu*RLPRSL)Hw=TEnO zU40K2h28AiUl+fwzJk#_DzW`M#!%SJzWo#$?NQNhzo#&TUH$x}P^m{nA3ySxCcmqX zU$=f;eR<4Yjoi1t7mfUW%s-Mhnny$5e>{aL?CRH#6l$d^vH$4WFWdT*OO?Is`(JE7 z72b$W_T!hdL~X0zezkguR`&g$v_x$iw;!n)4r}S#Ppf)(`+c_CpX>GKy8Yw!>sUZP zespR#;`r4wUz)Ff1TQrEmF6`h&=_9IcV0v`*Z{hIIp&U*U;+e&m|2=)^d8~B)h z{zQT65}lZR{GwI`KbHILN5R1g&eZoGL7@_d^y^0wwfRrg=U=yeU41_$nIp0NWBbea z3x96xKf3;tZGE0mx!?Ny%hku9tzSRli2+8|QDoO=OPf+YiZ9 z=Q}t1_4}G6bwEFUkyL&B$@=!=OO*Sa`}mO@VD9Yf+dpnUM~T!=egBoJ&UbR`KR%O4 z9niNQlB$nCS>Jzj>(|xi5y}0I?VoM?%kjmZt?$2liE_W=`sM7!pB>wew}{;DT+d&7 zH8#}mRl9uQ(#A#Ado`6#s+zRVxTUqr8=J;0S>CwUg4&f0d#$Xgub#hXTtm(L`szjF zR-Rf{-7vm}SSg6Ut+7|b%KFBIE2~!4E~{QOf2mu5zW*W86s2vh^QUh=C9}Co`u1~+ zQrgLW{YuStm9pP{F3W}uV1(Q+14jas%^9HziRC!TKfJ=N>bZq-+oA~;aE$*{aV$358hvt>-clM{YVQy z?)$$M{1D!MmFxD8?Wbdb?DxMqt+(Hwr}r1@$M(~)Kop+u|JZ&y7Kr^v$9nPjDfXY(e{?Jm`;U(G;`|f)PwYQB7Kr^v$9i%8 ziTx+`9~}$C{-a~PIRC`{6Z?;j1!Divv0j{i^!*2E5um^RNVk5i=7(_q;D_G+A3FZn z|8y*%pFebJxBCxW|JBux+plAR-0%N%(8vC(AHT8vbu19uU&nfJ{Kozh`;U$V^!*3v zR6h*X@5SxcAy9YxxM9G`zk@%~sk!gJy8frDFS2UzWBT?FUYF?1+^-*rU*@<>34Ad2e_i|Q>IbGuc%nXk!eRp-jN=~#ww36_+_zt@;}@|K z{Fr|H#r6wsZU342_D^>Omhe|5IHDiFfvs4#oD9FqYud*nR?| zNF0joCt)nXsj>Y8Mv*ua+fTw+f>UGr35+6fD7K%3u>_~a_7fOI;!y6}4@sc)pQ?ZT z=`T~}Nbc86MuU(#UQ>Djj*;#ws4GxlFy`^njxKRdR6Y=7P-WPWGgf3nS=jJ5pd>gVrl z*;-BFPrBr)S@OYlNHFA11CJ@@e=4w2kXef)Cu@n^^RgSUv>Z+-rdT!q}(xnDmANb+ay<42N++0*s$ zv*pSD(yt%MR>_>7{rtr=NBT$h?I+!2Mj`j@j~G0%KXRWxS;Xx5xsM;QfFytE+_Gi#YyjHpTD^M(xiD5V*iQ# z$KwvtyRrYo{v+))9);L{V*l~DgY<6fKe7KvJB>#n_Mg~)JnkU9oBRGF4Vh8M{`DWz z9O)nW{7F~IDCpadDNg!F_VFX>HhUGaZ$EEqMy8U$9pKX0z{&m~0TfeS;+Yp zETDh=ugjmVz7G1>fA!<{hi?CDsUZP|LfEq&tJ#(kNro-0NXr1(_n)}^It1$T7u#RY{<`+l)z@kL_hI~@Yd>9mUHj|S zpX>VBwqLgE*X2*Q{krE9O(ewPy!uPRkUTEaoH=noPuQ$YSZt66?6j(=hocbjGYtv_J? zAEx+M1OLV@;qY%vi6;NQsLTHY6#qXw{LAKlo_{pV`LFyl=D(BTZvy^1LgL?yi2oi% z{tIuy`Tr4$|3$n1e|i_C{MY;*oBxg5oN`ILH^0v22P35TZ&J+vJ=@{&|8FS%Q-Oc9 z$&O0+2~M&_5%K?$F8_~G{5`;%>9df6-2u|KC#lrvd*x zA@OfT#Q)2>{QsKbf62qYZ2tH0&&9vXJK4!H|LuRl`Tutm|LMSg=eUsi|EbaR|F0;Reg@8tM5Zg-QA@KRx(m^B<4j;{1QO;dih9 zpQQL-1^ngz=HfIU|L6lY{!Nbminq9OL*oB5`S?%q@8bU>#s3=M_q8)1{s9iZ#o-?+ z{z%0e|J&oSz2dzu;s}?+&M2!h7-^P9Bo~pRVZt zF8(fx|8>CcYiB_GeIK&%k2w6q4(@ii;D3tZf5U@c*8h3@<}k0^`0M_|l^YWOXDIr=i~nhg|KEV$*Uo_W`qZTv8ys&fCQyKY-X4{`X>d#rziHUG6n(f?iif2H`}0sOvp z2K4{dQ&{}QozeKeHvVTQ{yqlu2kRBBBZ6C7ou;TyB334SR3=aSE6#x5x-`CE7_^m@( zeCAzFxjw%q2SSQ}ZT!zs{2zGm%lbc$-x%iji|@w%{{qGTA>gm*XL%%aWt#shp3LeY z9{)$IT+VArEBsp|o&O#Gck#bS@%ICMgKsCUG82B($o7B6-O>2JHvWH5{2zJn%lbc$ z-{Se_sS7FoRq?lv#`phvDE^NDe}^Lf<*Qi!tqS)3Px9lT@&B_F{olp^GR6N1;PAFB9Q z#oxOK`~Pbc{{Z0c;{7xr|DC6@{2Q~`{FnIO(D?s3ivI87@1^*^0Q|mo2E<=^8jBxs z_=k#rZT$bD_`mevm-T-hzd3C2JI}wk>tCOs_}9SthvtyhKcI-#KfEfx{vkE;bk~2r zN%5}*{JkOJw<5y-nj(I8{o}tW{xbo8%Vy!Me=*9~{5Mqb|1U-S?)tyCD1HR^`$EER zMufjt5x=|s?QM$xEWmGW9uEH~BK)r_;&<17y+iSz4ftC_!f!={{|!a_ZvOA1_|F0S zB@;(6_pwOaW}5#X=egTy(Zv6oium39_aBP?r+~jdB>v5a@c&y8znlNwrTEVU{N;rq z#eYQj-%`Y1_c4C{;XR7~Jiy-;5`HTp{NE|!Z~ZHt|NSq;e?H(J2noM&cr@{EjB+zh zpdIr3w~POMioY4~S8NfE|CK0mXj-;BOBJKZ@x2_k3OaA5#1m0)Au5aQH_N z@xP8P{(g%8B0K)~4X6LNBEr9}G=As)PvS(J|Jyf8jd${Z`pxoT{^vVxo(5-?Oyi&8 z(~FpK6S`>~=6Bm6+EChw|A_K`u^s=D!r|X2k0$@Gr^tVC z4W9pdo#Our=6|~RdAfl7m!Hnge_7o85BiMrtC0Brsr3AxGymg`e?Fo3F9H55L&|?< zMEtL>%m1eo|JT63kEekA7oNfLZ_bIv|5f=%&*S+2AH{zu@ZS*<|0p8`R&Z>(YC zA94Jb4shj$l>g6_zW>kV|1T*17T`Y_692~ZX!75Ny8M4h@qY*W`*;e-e-p>QF*h3g zs{Fh8|0|0BXTX1FNc@`-@xPHS{{s}iu`cCbHvjYdTU`8OH=>&?$G=s8*FSwj@m~)7 z*K8e5{znnfz<=LIYU^K$*0TBE$%te`8NMNPXY6P3&+33@lOLE?}Zfq+WhBH{8s}1b=!m!|HhA_>Hjv> z<^Nmi|Lb`8m(Bk?|0q}ZUx)I474Y8`68~mI{BNene}5w$|L0Tu>jM96pQz>k$}`#g zZ_H!;zyFJ&8ULTJoB!9N_^$^36WfLp|5ilv|C{Ubzdpsk9`NtuDPaCDzlY@?ar_Te z{@3Pz1B(CWHvb2XV&<($yEDyylk>S1zcI!C3*f&y zB>s(`u>Bv&3+^@~{9EeszX`=(0Q~!S3dnyC$G>@0H2Ago-<0CN2KX=DE}Z_~jEMiO zbot+i;@{B2zij^J`8RTf|II1>Yk~isgTm?m&5NDuDmUKwosi;xYeoLu=YKY%_%{On zE51_8{}orW`5$roxAWzOg#QA?`@in|&lVK_bvFMY#lLY~H2iNP%|HJB2burcisHW> z@HZEQlmAde`EOfY{99A}HvsEa(j@!tmc%SVJ1|2IZ6{u!x@e@BY{ zcECRn7XFC%-&q&`P89zgfIoR?IQ&}?;fK!^N&S)azwY>dB*otj_&Yf#?o z@&6L=HysuZ|5il!$4KLMp8s&?f3~FfH-`Bi-#iV@u9@cl3+`j*e+)C4{3k#E!{INa z_&4$3m!1FQ@mt*dm#>q`+WZ&Bza_r^vn$2FDd4aCT5bNX@I;RPqgnn7zTwIZ3IB!C z_kTG2V=4a40Kc!D0sY^)pT&6q{p9bW=XBq3?h{Ip_Eh`V}{a+U;`oD{RcZz=t!0&5kK>SS)vi@&WvhhDu{A=Sc zruet?;FtA(9>2x$Kiu%QkHq-;?6s#)Dth|9SjqnB(sojs1Td#lJ1!x8`$x z8j%0GM_B%iW7z!Hw2&(|B>%reG5@>x_oDc>1N^>r2E^ZTJBuH2_=n2>wegRq_=`OF zW&NMWZw_<(?)6^@#lJn^@2=$hG$8*yoh<*xWY+(S7jfl=TgL=I|fO;vXvim&ecD{~t~9-vjd>#Zx$*0^;}Kn-vZIvC{J&9R7VM{(Av`Pe}O9 zi16Oi@%iO zzYp-YP74RW!M*?97iJ;#e|zZS-=E^YAMlqS9u9spBK&*m;y-}me*o}Tl!t@gsE(%p z`;jjG11bIo0lzUl9QR13@ORA!2ftY#4gV8#@tYL?uK|De%y94_twRK7{&i6;4hgK4t^97{(W@uPoemK3;26O!f!={e_v_* z-2MLv6#od%{EzJXA3y(NMKu2>KmWts|Ja-2-x2U5ex43rxMW)Y(fJ#8{>$X%znZJL zxC-g|=Q73lKllF6G>U&G!0&5kK>U@DviL0yKQ4xDh70~OihraBzpVfB_|Y)O@8177 zoZ{aZ@Ru&;{4^l{#dop%8^^Kze;;3NNc^|x-v60S@h1Skublz$xBiyJk2w6)@$uep z!Cy}C@8ZEP>;F7{bC~0AGVuM+A5;9J0DtQeHUDq9KUDs&jsGVU|E?bVvi{HGH-x_s>aGb#QtfWM-a^V5L* z_x+3IAMyB4;>r!l|1X~)dRoipZSH{t{{FR#e-_0*7VsN<6|Bs;fcLV-O|1X>W`2OGG$3MIQ zLW+OY{@?ZgITZgmkN?Z!=l$Ot=Kf#43HJY^DgNJs|Ci4W$N$ZU{J&Ju|BVeX{-Y@V z@xZ^eR1JT{+id=`IR1;4api{O|5qvYf8E#O?>`+&@ms+EKuG*s4bkMk{dM_2j^f`7 z`1kRI^H!$oAM+iSf3qqY{HpxB-~T(F;(r|YZ=b{YX+ZpZdPfn({{g!EA4Bn%c=(si z|2+RjuJC^%#s38GZ_Evce=8#X4^-qIZH4py2^9YX;J=H{(*gaz^b0or(K&4VH!bJv z8dCnhT6+H9x&CqEKS}XF3H%q#gxvE&!heu1|MMySiNL>)r-1ke z`dI#ri26TO{>!((-#=ME@&5t%?+l55)EEu_hwAcQMe*K-x+>r9$&lSi2F8_-u z{yzc#MMtaQck?>lu_DUi zAJ4zJIvV_k>GEGq@lW#bFPr~){t*}dynVu&|5WAQjsKG<{x0CZ_?U3w->8j-|0#<6 zyW{^_ihn=gzlYD$0pq`)i+^J!i@&#yvujBCzg2Pk@5cX9ivQ2Re@{sKqb3&rQ2GB< zUH+F*{H4IZkEekAcm9{n|A^y%sPL=u@5cXfivKUbKML#l*NEc3Oqc(YDgOOE{LAKl zo_}+g^WVG$p8u$$_@4&;n~&x4R6zgd{ToHZ|1?GZ6We0^D=7X0fd9@_YWTa~XXD@E z_;0P}$_*+1|3Y#6-?RAMjs#9M?`o{ta&ai}#PP#y^Kk^N*kZe`1U?KedwL ze+KZI$A^R8ipc-V74aABi1}}%`2Py{TSLNcoD@y}KV1=j#m*T2DvJMafWQ2NaQHVP z!vAAM{3dz-(Q1mn8}JW=gdatO|0jz0dv?S8H&Oh52mI|PhQq%V5&jv9`1{EEuTv@h zX90g@RXF&KlcS0MnTq%ecfkCgM)5xf_&Y+vZ$^aw2u1uor(^u5Q~b{Z{v`jNKE?hY zMTCErBL40*82=d*{|kU0U9yw#zE!6C|NQvIiU@y&BL1#3G5$3a|33hK&u>GD|E1By z|B;ILUH@N8@xKW8dmjr2zZnt!*^2mG|38!B?*aU!zY7OHiU|K4Mf}!T*#8m5{}SNu z3kkm!5&pS~_}%gESrq@vcKmN0PX05NMHBz?bn%}}@xKE2`+pyf|C;H)3zmhLEB>%rw(f?ii7gGF_0l%-E0r8h_!s0j2ji&$8#(x3Df0zfqtpD@)EslR| zM!Lx||8D<(5yd|R@E0iF|0&#*<=^1eztpVe;wmKk*D3nHi~kaee=6YjwKJgqcX0SE z4nHLx?+q9H7gPLY9{jTY&*MkK7k|p~on-#=Qi^{X;4f<8{4^l{K7P6NA6gjsIs9|8&6LbZSWce=6Jm_ngL+ zn~r~odo|0cuM{&y4p*9%+wU*cWo zUlO+VKMVBEhHWqYXS@gc_P-(e8!G(P{127zCl-A8{lI@yzZ(9V`@bLfclk&S|EQ0? zANcb=QNy4A$@c^QS&I12{+{4}{8KglpZN6q!T%PYtKr}B^X~=z-uYiB;Wrn2@%_Mm zlOq0`qs5=V@4s{3f6>2D>Us+{>K_%um4*4azh&bu3I8EPz3y` zn%(jL<#hc26VLcx`}%K~j{nK`kKFs8Kc)Czh5MfaA>IE(5#9f-RJ{M``u~j-|3TnN zK0n3omFfDgXg${dja^v(_jzfS{eOV0|Gkppp8@{gdpdWW9uPl|&*J>Q=yZ1ei;s_V^MB}Lx%p33|1W$I`~R)f|NjO4U$K2i>z|gZ z;rH1o!+~QJ{lDot{Qj?-DgHyCu5!ixub0dJCg=aH+i`XcDgUjfIR0_-e;dVrgvbA7 zbn>i=&3zk}lM1^@4OBAonhMD+cy<8=MMo#HU{a^= zmz@9eJPsHC{}shQ8~lHOAEyMw&%-nL>tDqARY>@6(jEUiK=J?E&i^C0>oisTE24@2 zDqa7-m*SsdW5xb2oBw$KH;1|ZyW^jS9Q;#1-!5+s_`iYuRCoMiJ*^o3lJh^>{{JxL z|1I$U#Gkl0RrG%|BL7b+`hR~CU;jKv@lOS;m5TYluz=0~7U%y3{J1it{I@}g^!Kk) zHM{da_f!0HJ^n8n|JY63jmhVKSAus!!msWBzoz)#2LJC4$^TJA{y$&Q|0_Pi{{I^X z|BrUMCBF=)A$}^G|C%}fH!fAof2DHQf7<@vN%@}#{@>ahPX4nv|L+*0@z2e=a{P|K_f6{NJdHX8gZU(f{in!S_EOqxcU85)0o~ zyZ&jK#EyRu=l_NLyh2F*e}V4&&!ZIo(H{Sojep+%4aNCSUpW~LX#4*Y6#sv~|4aWI zj{lnx`Trta|9_I=FSq@l_fu^DO!GfY8?ydyd>u{xSM~pz@p%0AIK^KH{*PM1;U97S z-}MStZb+5d0F z{ohj#{;5xm%sU4BpZKZn_{aF0TKuEDF;dSzYWsf|<^MhK|Ng&laT+lH@%&m5`Tt@? z|997a{)yuMF@UfX^Z&q+Z2mX7{9p7(&aNT(|Ava=A2uXS_7pPpodBKyq>-&zT5N0$$4hTK>R0D@wn_Uq zoM%5DVju5ayDTNY5RUH)$4bxJIaLnX8VA_t=lRMR1;;DA<(%v2AvnGb9Pg=j>LuGY ze7v{8sgGmAi{u2E2FaJmV|0htQFHhrIGWmaNg3bRHm;Zf@9WMF*FBJcAkpC0^ z3@850HEjGh@#Thu|5n}c|KBM7_aXmP{9icuQAF!MYb5iZ&;S2S@z3!1zij`{`#&0{ z{y$Xt-@5NhrRN_L_kS7b^N+xPD)MT`_0Mw-|1&q(CGU8Me-fwK*FSf#@gF$<6^xO( z{*jIUq2j-Hn{i70|1R5(i?sjujsKpf@&5tjzwVK0^S?a5W<=w^TIu{(xRKpfcmDfX zihm{?Z&JMfTR4a9|BY|h>;Gc@zFJ8A-$s(xe?#W~XMLrV|ID+$%1-_x^PkU9{!j4a zKiU3|_kYBVe|ULV*T1s)&lmqMQT!i5{8v5`&iKcQX#8`MZv4MY@gD&s`Qj84mudWO zjAG*-aq&M?{12P>e_S#CpU6)97w?Ymf4oTfKM~@;o4-y8%0Ex=T6X+{UghE{r2K!I z?)A^B6n{U&f5Bh5b}HgW5%vEk>&E{J6#p#1O5$HS|8wzg{=nkjJo?~#mHE#$(2I8d z)9HCDufX?zdL91D_S-zK3gVx{sqXcU)y0ng`1Fvr|9@9*{fl<|zfS%CBZ&WGNbzq) z6#q*V&(0m(G8j zgPUCc$BA((d`G1ZX#4+L6#vKI|Al`Gr~fnR+5X=LEF}Jy>H7cM6#tRXNS~kLhG!c8 z){JKT-}qKB|M?6x_yJY_@7fcO|Nc$!&jZ zDW7Z?z;W+=!GfPTdKMhF%g={@-usU5Q|m8*d!DYF@c8dthyUA_B=QzO{F6A<9se2K ziu|uXMr!_BJO1CJ{{Jb&e^ED=r?9m%<$s^dT(R< zKg7kq$*-#lDgSRGIsUun$u#l*$29Q|$L;tpneN0T*_wY!6aR4Bj{l`D{= za9kMwaC}JPpY;FlQ2rNs;$JrZ^Zsvf{XZ{Hd;RA-aqt7$@&6&k|38TTroV?1|0tsP zuhWhHeu{rCnA#Vo*!-FDU;D0H{6{qYm5u*Po)^b|@*m>(KM#)E@!yQ&pKOyaisS!Y zIBv&(@A1xffo$7e6371&aNHaJ%`2RBL5Y`-&EE>@<@^5yaJ&M_C&xSR`x|KA}w{vWdYfBWvGbpJas zX|L?w|NeyX{~6@J?vV1I6;b{>MK}Nbm*SrXQ9|;cZ2!mSKXaJoKZyVJ?PSpV59j@l zt)-(=n+ ze=IKk2l#SB>i;%{u*{`DK7SbI7LhhTLE@i`e?F%CFZRU0Z2sp#nB4e>mxty5+VTH2 z#XkV?-@dDJ-O9H&)A*l1-;5~!8+7CU8;bvE0O5;M3@j6VYYZ3v-24Y`pRo9sjsFDh z|BacrAO6z8Uu)GEJ3;?nagbd9kJ9x27T5oiatkkH`~RY=o&G;LANT*~W$6FT3#b3@ zy#?R@_=@ts1meH7H=O>@;^IHKW*2tc5>ozem%RS*_5Uy&w8wAuAnFT<|I+8f!H*(} z|CPG&{{`j05^O-?UpD{q@o#*`j(?$O_AeykKaMi(_+OXC|CbQ|eIdoa6;b>*O2x&GCT{{rg&UqSqvFND+o8y7}{ zf0b_hZ%FYU3ncpD6cd|i{9n8qJN`F}b(wtN^N%dWzpot;9~gH1{|1!*lkDsN%hd8e zZ$|Tc*8kgH=i(|P{_oTs|8GL^e+}{9A5#3A5yk&%-S}UR;y(^ZB=Iks|M~d0xc;B_ zkFc))Rr`N*1MdGfa`0Ddz1$cL{eO`u*Z;S{0!-2TzsdFgq}=|C+5W%a=Z=2i0(||S zq5n7a`~TGQk8NXcJ2s{K9}gsTC_ev{Sf3sLnOy!)p1|dmkm7%H`SBl%e=Car1im51d2g^K>~;@_6yPXc~lJ27#Y{J&&(7QdMn&G=6n|27o=d=GwE|L5@= z!yJG4Se*a2qxcs9ev9|hfcy_6S^m*AEdO=DeeCp{v9d)#emh<&Vcw!_hkLwxR#B7Tnya|7yKhA{v{s#vi|SGpFdpj zJL^B(_n+)U@z((UlIOVVbj(;L|L<7B@^5nZoB47>;(se?|L5@UO!3zOR$n^<;;;A- zi{Ik#<6`J0%lKPv9_w7U-mqC}d+s03$p3m1=>K1I@}KtopSleGPc6ajjo4LqJ;r>@EW2KX=P35S346h;2ksSTt_ z_;>sN1m*u^D4|91{$KKOHvWxuSo{TJxp75E@xQfV{wur(^FJE%KX*<3cffyLNc>xh z{G*|d|CHt3``?>;_=ov#-#j(;s!aVK?|fE7_rJ8~zY8h;Z(#nru9)*vMf@nD`R^v_ z`ERHHcjJFoihn6!^~GsG{N^||{!K3adH)D&{#!Nvjry@pKRd?3KlWUBVcDke{MSn% z<^Os%|M~D|=|BRne|6)3V-NqH_?PYfc{nIn;(s@a|67Rvfq$rt|9SjYMDc&BZv2m; z_?H0)692ON`{F;M`G3{;?|XQx6aTwA_{UzgCO;qIzdNM(w^ZYQ#~~m8r~3cmYw`U5 zSP%aY{}pe9pk9cj?~$-jm}04&uLfk8t{b<0AI{Kc64M>irXj=i}ev`hOpr zS&sky8^=21|9u_&x9_?(e*=jBl2=0N|5s+ne?EiY1ILdU>iPea<=y^&qKAKo{|C0ZFLlTNQz-uRpiQM=J^vR`{3FHqch`TJ z6#q)#x}6`V2jsuvR&M;y=l>EeuZG0`c8cTwil?yumpS;Ge|l#A_7ML){o%yFu}ZD~ zMQ+s=6~Wnqvw)gAvEir;@j`Ev6g^6~Gie{rAx*=*xf{F|0>&ZIRDA|KcD~1i2PqU z|NR5|{}B%U=5J_?rN$FHQsE@4lUj|A_ckj(^hs zAMN08z7pl{2Jv6|aX8mM#zPtWAKTTp85eQ<&+_o^iGSJgACJT0@;@&R>-tAE{@X4X z>%{*t6#qsL{~c38n*WF>{?FBo|JfA(sX!8me_8(d_(u`(uMq#Kkw@DDnEy%-e(?Y1 z8R6uA#O1%{vxnyW-}fqxe@idL_)nntH?}RaLpb=Yi2VONMgMo#KOIZ)p9b&?C#vCZ zxr$x?VC>D#f7I~hro7OX6{QbsFF*ce{lCh=KlSIE=bdKzKlW4Y`Ttuo^ndB_zbDuK zsrr9g7xw=o<$n`sQ)^h)f0ruam-K-1CH;S>zJF#N`FY;WeVZG`f1H1lVQc@p3IFSb zt^F_YuJbPmTl-&P_UCzL!?qXyGu{Jz``-}#CGh$eH~$|``9Iy`|FZp`uesMo!@sKk z_x~CD|3Zp?Q}F-Jso{)&%!vHISkgKGAB$=DN4;|WpDO?E_^*cYzd5w2V1(NEhsTE^ivJ50`FG>Ln&MyU z;a@iY^ZX+&{(1X^b^WW#zdQapiQ>0c1|&n`--?L;ixl}UC(r-XQv7EE|0Vz7@-!wc z)BJzo9_;wvyq=B!UcTHk@$d7K3eK(DD=6_dE{AUCI zeKXbYw~lA?Ke~a@!+@5X;U#lJPQsq1Pr{Jei#5%GVSBL6j);qiZi zgTL&N&GXK&`NurT=Kr2U+5C?bum6$c{Ff^KZv3yL{BHyNm(K|2`rl|_{h#-bu*SbF ziu}9re+tF_QxE^L`Jd$(Oo^r*Pum_*pdk zU#-Z$8~|4V^^lU3LM6x}`6>Hp56_%8zgH$LF{set(TcB7kF z|L@?-4JrRWsM!Cx{{K^oe+m|MC8BaqAy>{|IaR ztL^{iIryio-X!m0@PFc`y8XYUI{trEuK(Be|MMyTBfLh^qrBLDw|qW`<^zc`oT zUjt5R@#{3P<7UeLMO(7Zzgk@WFWQ^yS3}BwJ1DOIbo2i?6#pe2|Cfz_KE6%W^`Cq} z8GdW~|AiF)&cI1xB*#-g{(a57obCU7@{styM%Vu@qWITBBYl1v5Pvy$|J#aa{fnyq zC+{8WjDIem_%8+jPktEA_{ZY>zp$SxHzfWaQXK!d^M996{0V4N#|`25zZsGLU#si? z%@qHc9{-okf4u*jx#ItqIrz(#Y?*f%_&@Pe-SLmXjsJt@KlHxb_(#?M-TBWJ%Kt9l z|H&J}@qZMN|6ix*|L*hOms0!)NUGz^8f2~{r^ge|12QU=cfVvKgq5C zFck0q@qU!)w}Stt=D+$M9P5mKE~of^2L7M8S&jda{n+(S#%-+sTSGMdd027$d7sqFZtqKuvYH5BoqH{`}Ys{Ze;|NjN$e^>CyrjV|G&4~Q}Mn(U3=l_3B z@t*_!pV&t&|MhLnj(;rf{l`swxgo{>j`HIlHveBm@n7Nbf7$rw{U34pf2i`Gvj1N& z*6IJQqxi=FC&fFf@z3Kk-;E~!x9R%-^%Vb40ff&_F|bVI|1Oiwf2QjFZ{Cm@eyjR_ zX(#6YT8jTl@c+7xxOtj@_*x@Km6yLiQSnkQsif`hUe$c>HshgMZo`TjsTb{}Vrz9shJLV*MW}&i|ti%S}^8ecu{onom$DI`a1>kEfe^-nD&PnX}$Kclgq9Gdpj8q)| zxcUDMivJfL|Cfz_pZ|0D-xtQiCI8<`@$U(3YC0jL`Twif{%@%8->&QbzoPgrghu-O z6gNE6_^0(@Hvd_i{|^;@RsVOte|QhYe+~FQ`b2H~)3-4j|L9JZ{~o^Fko^DG6XaIX z!ut1A&2Ij`kK+FkNP0uc|7Jw~e}}IB|B~Xr$m9RA`H%O1bJ+U7^ZY~kSbY6|KgEAB z;P2u4setisbh7bpa_fIeCUO00NdCXGbpOZUf0*LG1hD$r84!Q-R1SYc*MHjhAENj# z_28HFe;&WZ@sG_&H(BPt?cCj*>)%Hx{>z|s&AgxD7H8`J5|6U{8wat^e^TIhFC_fC zDEfcvZaDsbP4Txt(|Q&0x8Bb7e}>}qkIzmS4vbR7Zx& zA7lAP5yk&#Mf`mP|DzQD<$$$C5q||Y|6@hO|E`Mon@-r>iT~eH{8s?}K1KWq&i~Db z?thO_#P2@;@)*T`CEzzp)%?Gl8~<7y{#L%+kn-Pdy7+%b@m~e_eeHx}_Fty>Pj15I zKa0En>y+a8f4Jc9r1-Cf<`Mj|{XdW29On4l_0PYj_(LgVG;zp;A;-X!q*-`)Q23CjO9P)f<>&i5br z0yD*b$G9CFdtyb4g(`8VeO4-WqGcReeA9Pr=ziIb;f?|<<2LW=ww zdqu;)i~mp9|L2~SUjq2cKMe=JrHa2~sPQ}VfA0GC2dV#$gFY$obU5?hD5CklcIo*) z$Nx(=!Poy!JNU=!bbJ1Bz<lT z|M76Fi1@!#n*V~-`sdaSG5>Ek_%~d3TmI3&e}A(x|1X>W%=6jnfAat}{*8$Eci(^V z7s~%$z<*yz{2N!Z_dj_5kh^Q)({>NsCCxt<|9^Jy|7h9m`6mGXE#HI`|BqzA?;_xK z4vr}P$@;JVqx_cu|K_N0;@|u*1AeG0jK8}T`7gK{$Ny6f{--}ZJO3cye;}m(-?&UI z{?Xpi@bC8jf2I6S08ToN4~hSX;{TV5{3r7<|Iax1-}>+E`BlKb`E5AyZ**qx|1{2z zqKf~nvCj2MH|2jK@ZWhtIQ*lC_`gSyfAk3E|L>Up8F%C_1pbpVoa;Z?{-3AQROH_{ zWN71msJ{P~`29Od-~U6P7wz}|oa-NV{PQgJ|GmNgtrJ7?|EDsmfH~%5U{D%&e<$qAReL}*2+XT%2ibSMhX0oT!}wpN{Feg%J@doK z|HfZ3_&?MY#@_?F{J-Yl|K&Hgo9#Q%ee{FfKt@lUUV|LyB;&7TAOC%$y>>yG~n#raPZ5&x}wWBjjE z{tp2DTaw}AfAeY9|6TtkJ0ZpYL(=>^*S|e~!~Xv!#eblUe_=TOZ$*UvVMYAKf5-U$ zP4OQD_{~M(;5Yv-8vY-V#_!z!aMwTlk>bA=eABm10sCvF`+td(+3SBRqV=z;>mLe7 zuk-LPyZ(vi z-{hWuB5BXvro-=^5Nt=4fA{&X4iA10|FZab{;i1ctMc!z|9hL_zaC6p{IXj9tGk+B+>FI3$@V^fI z-wojZ#7|}Wzs_0~zsdQ3Q2eM_uK$zu{{&wD>GI!4`M(hwN%)t||2+Rl5x>t)84jrO z@8-Y%c<_7pm&NbnKO+BE<==h(=lc|Y8`!$y0JZ+Fq=a4ni#Yu4e7PaT|DMwQpY!~y z%l`)+{J?+PWX0>>E!qCh{3V_zA^-iyfT@a(N0zY^L}(?qTEKxQESum3+A& z#s80_^S_h-T>d}x;0OLI71#fjZ^PoZIQ#|ty0Vb)|5oz)2k!r-)_=SC|8t7}R^Zyl zQ$YS(?q%^C_p;&YxDm< z%KvR1{$=wY&p+b)pAwJvvdq65|DSpAd-#{d&+~6aCg=KpUU{4YTMzXSLuJjv$&%I#VF7I*zif#bb& z_%D#l|JwY2Mfq=srV;*S^B>Q@G0gdQ^Z(Z#{2u;g@%#9X2)`=-?)yK#qxkOx{*!#3 z#_pOa|Dy;0pS<$`tE1@t@Z=g5J9g|>V+^rkG>U!g*s){B7O`W;nzducPOPY(iXA&@ zV%8GHjxA!xl7z&D`+?fy@W|FAjp=j9B6KX?!L@1T7;A%EL(YX4__Dt`k#uhJ6#vxdii zr2pBF|6X8?c}mD%a-zx~5dUH|xUj@;>RPYE|Im|e|8F>6<@XHvea-%# z+W!#re_zDEZvUhHeM5c>NV2c={qy;cy#M3u$bUcl$$Q~sHMIL5;V(h{2Y@xUoeBA?P9ph#MCBK&!Np+VpA-2XjPUE`pYjL9KZ1*|W*R>q z|K#~kb0PmjuxSC!so2~?`Oi*N^B)lZWgC;avczAZoqxhV5AwGGYiv6c^0QOa{QEDt z$$x78xsm_j2)}OrDZlsVVCCoiPv(DKuF9C`ftmU{1g8jbiJ1HzovHn3IF`a z|0uA=wlg7r`SL2i=ji&+)co@y|6>t;-TYI2Hpuzq`5y})|Kq^l`8Da&3H`Sa{{i9e znnKoVDgUDk^Dp@qME)m$HMX4z`O8*N^B*|6{xLOwDe^xV;n&SS<@W|TzkK~`A>?ld z{^~PGP80g?CjLEo{o9#jy_WL7mSO%S|02l$RF0KyXF~qEE7kdr_o|!mKQ;ft$p3VN zUpN1hKcN1_^C%ZH%|AK*l|ladBF8^;`RVZw=4k)N^!SH7{yPWq-w*tqhVOqV!hWtP5Gt&CDH%G5q{nJr~Co&AC|pb z&Sd|Re;MR|1o$fruYav2$3MJjYX9${>$SxHT-y9E$NBGs{67l(;dbigzk?kAW2XKu z(aXOnzx2N>`hP6KubY3$?-Tzr_u&^a*}vq^BLCyS-)wmOb9;l@|5%Tj|Efcav;X&e z+WfD;`Nu*2p8)=FJ9YEld8*1E82a}$^KZ&8{V$LHpN#P9=AZI=#D5rjxwMr3)cnJc zza9AdXimij7kd4tVwgJr2`K+z#mWB*Y4bmv^Irz}e+u}S*iPO2x0B-^KINC<#TWhg zzf`aPoAS&2uZaGij_~W|pYpTmYX777w(fte&(H7w(HY+VVhW!Bv=KPzHSGVCFL>Pz zf4lbmFF1eC+9UY=h|1Cb#=zfVSpSsYd&3R?Q-=H<@2fuZH}a1An_E{=gCcvxfZg{*S98{}#YscetJWd!26lPc-D0 z@Bgv}@^1d zH{_S&-zem-0{-%&?C^W=0Jgd-Ox+!uP{vkb4~FfL+J$k$*f~eg%(L!{fQ@CUQUTy~o#AJNJ5Q zQFyFrB41Cq^x^S^;qita`Qza-fXCN`wS? z^WU}6|F+=2;%H0xf7ea^Cu#Z*`Q`Y(4)SjY{N0xL14sNX8S=~Ve_iC?9{8J%vE=_f zH~wGN4a?kTb_V~fg=OxOy}Uki`~D~V$W!}} z5q$su6Mp<>>KXTBj)43B*3D+;{_mdQ{onnf-~XNPug~+}v-G{0qkzA9cRTO@;~Vm` zP4$j{>JA3b|MK_0kmr9ciuL~ttgQS*v->{!1IZ|I6Ls z`+si0`KNtyZ{}F=Up|MO{0D~q{i6Hl=fBJ2-z!D@!}0Gn)8k)95&vaFd4Ca-YY!#4 zvgH3o?bko}{73HpRU-cmuua~vcE-QJ(fHS)IsV1!e?#OS53XW$D*P2X{@Y9ZGe^h& zQ`i4SoPYWm_hpWU`fr@mPW`i|3(SA|X@34@#qR&S{^j|P8*~1%;q|}qQ2$|_>c0M$ zy;^wl*8FZcg9!Tj$C_1|l${=N4L__x&mUP)X3iy{AnNd4=+{z>cK zf6WcQLH+0FKl1&LHs$;)t#*IrM5zDD58}udvkrMyH+s zZ^`+meR6;16sZ3mOZ6YDP+E;!h{{_dA`9G=u zQu?}@CI6GO@BhN*|MK|X*2rHC+thlTS^nwsr z_Z^-8k-Gl3;r!Fjcp!5c)PL_>cE*3-aQtUmx~YFT|KFDLp9J&&iBSJxo$Aj2+pbaP z|30aIS|9zM|Mrg_ziIu;zXkFKk^0x2|IzwqgS`G5 zR~W&MPwl|@dzOAMa~9Np^*na!KQOKTt@QFAtE&PJgvWp6{C}&6|49Ao`lt2JX1E#u zOzU6H|93+EU7-GJPq0(}-Un{@-_Wjqa{rUln`eW&Q8W`Dc9cVCEdC|I!*eum7-T3i$7*PW>v!^}l1pKh%Ff=jjRkmz+TS z->dHb)YJ2-Ect)QaQ-ik|LuzWyTUe=o@l5314s4$X4?AS4f&r3*ReWH=)d7wb^ga3 zo&RZC|2-4M`#wl(gY%EM`4sj%)PGo~y7T|C z>s0^V0|okDfA!y_$Dg|X_r(0~2HO-^s(-J`kiVaCp}&XUN?ZTc$p1p5{&nYnwElfE z{>QezKmV~G9QXl)`p+N#uMA)R-;48){`8^D1yKJr^V*sJ`-b(;w$sc1z|T(nyRrHI zE)oBc`q%YO>pyTb|2M7wt`Xw;r+turcgSS@NtVWcNA=&Cw*G67|3!#P=~y%VPBQ=V z$@pJK*K4W%*VUi@=j*>?#0b9szaQrxab{cQBB=k``RvqxU|9ct(d(a_|Fd_*Kh%HL z@cjRt6V>^@_l-LKb<*`(^8d2o`9GzL3I7Km{~oYSt;cZxv~w2P|D`|geW>!&@ArHB zGxmc6Kk#i2q3a>-vw?KN?TTjGD$u>R%w|A!#|%K#D3dAa~AH2zoYwFK{{;S)iw|E%}P^J@} z{yPlk|IIH6|3@PKUa(F6DI})}^B=}OTn3Kn|FUfO7n3dF$JOh9jzazpSVgQ(#cB)H zfBDJk{vUI6{jYxgi|e0;3;#!R{uL%Xnz;|^zss=xgZI?@2N$caedexsyqMhA@v^^j{m;q{6BU5AB*|lJJ*wzGdus0`t?3m`yc(jt^NPY zv#~V~_yGL4TK{#({|fwOSpT~7KU)7j8UJG&WvTz`*FQP_bwq?el7C%(ntzXsf5qZY zo&OV%e;;sC(O_x(bCmxpAkaD=@Z8I0uNn4#>Hj?Be;ZuKJSFtsOXk16qwC*N`#(Rz z5B_7G67pBwtorx9cQgM>?f)F)e<$K!xBpT9Y*z7qZiGMLUzeZyXM^0oJpOe7^1loI zE6yc-I${26_aU$UlIvd@>3S{ozYWv&{|h7h;GY>@|66yE%I_2ZCG@&NOZ=}J_J8UB zV&s1h@ME45`e&!B`#;Rl`Om5SUlQR5|1nPq`P*($`#<}^P5)2rzY+Q0kNDT^f7HKE z>R&vKxUiJ})c!Au@JIaX@>Bl-sec3)Us>We^)Kgtmm>dU*tBlir^V(Ln*aBb`u9ow zH=Reu6-)dZrS1QhMfkygJMGg6`5VWo{m&=$Uq`Piv&8>~e*e$^<@TNt{QRds=gKc< zTsk@P+WheTXD9L3zk{jb`yqb`%Xn}z@_*n%JT&0K->$&%Z|~oK-GA84`42MxP3Zpv z*rZra#by@DfBPB4zoYYiQ|JH62tVXMmeYj%Wi9IX=k>Z7{|xec8bcb^g!D`G4N| z#ToxLPCNcx6X6H{Wro*3_WGp%k@~Nu*Hu~a|EB)gNJuZ!?U{Oj^l z{{g9g1Q%af;@9`j@Bb*z|2`G@_k(R}I+gTkvAKo%KjjM?o&R%Xmj2~|{|`T&?|<_3 z|8dCw3H)j^9jC89sgc8az^1NE=e_q=8&+QR@$bY%v^^cVgtMecB zlj^^9S@OJE;_pm5|G5kK4}@*1x|?_s;VLx#(+mcV@_#J^TIU0PT+RR8$lnbsise+S zybymAIsVHW@u$vzYlI*2AIoV%{<;oz{^OJUi`C#_u;l+9bAUwNOa z^-sTV>-xv*vavM}_yGL4n*aYG{}=F^Vg7Z;f0}=v^#9mKS@NGc|93|CBl*|mr}_70 zmHgk2{0D=R>Q+nr-%nwiFVFwE7x}-06?I-@R{!4F>iF-I{@-{BS+Ax1 zZ<==gb6I-+z&e|BmWEb^afY@I(G%IZepl^@N&#|KS4Xf6V0k zmz0g*$9Wz>{zGA#O76AP{~hIj90XeD1Abi1{{zVXHLNJizwY=?^Ur3L{684skK|vM zpXQ(a?56*j_J5iG$B};wqDx4=7>La{-2KU zL;e}fX+r+CXH@=x=3lHwE(S~fpF#dQ*rxjX?d0G4(oO%rDJ!4RL|?@6{{-?+gEfTt z*B$?9{(aK_V;g75f9m`{8R3uQUzeZe-=9_T|19z!o^$dk8K;D}Lj8~W4IJhF<}Cfo z1OGpq|H#+B#v^|Z{Aw$mr-;=R;%_9c|M;~3H2{YX57TMAmDG|J}6npXZSO2-v2E2gr6NOXbRA(Ne! z^3T3@!+&d52uiq!<$ogb&&aJqHjf3mik}n{J)I+ zN5M9AJ!q-_JIa4cHulU8_&_-Sk*|MELjG^yH){<0f9GU!{SO)c+UR;M`QJi&{=?7z zmB&9`MgF5gNJ zUq}99z<*h{o&6u*k^kGXF~tKu5cA)G{NKTEhW>T?KlLAw`j2hYV5$E%k^flOChuWO z^*_~3{oj#|J+lKo5c<#FEbf2&2J(LozgcpT8GqZyiz(-g2af80tF-;U6Zz}Gf3GF~ zo+JPNG4$UN`hOewe*pjOSDN*|>}Trh|DL1%x3#u^e&$`x5+itC-$DN4z<U*O1pm7)LYD+T|1$bUTeuYS~ye>Tlc|IcLg z&Lj={f8WG%p8xle|3~oOZs@=3b5j3(Zuqw`^v{+Y!TBd6{|Vr~>r1o#2Tz^y;r;H0 zpJkOlTkt=j|FT;}{y#wepWwGkFE-16Z@22-cjSLtL;uxF3IAQleVNj^zsMTkq0oOtm*D>x`G0}mt23 z>fe$7$%g*BLjRv4|9`=MVCcW?lO>hD;XCrbqqcv3{I6r75qx_;L;h31f87&y{IfsZ z)c;)C{`vW@EyGvl{GTKLui(Gz5;OkVY3lr+k^I-w^}=&)<6|d7|Gkrh|8C@OfNd&! z(u|+7_>TO~ouz+y;Qzyq=g)tZ{=Y!}-{4ncp2X@3jsLZs>iEyDb94T?ssFk~h5s*+ z|5WhbVaY#RYN*l=V^%EXe;yF3^8r7u`hN@g`(Q<(f8FE1)W1*aKemmQ_)Y!$>k0o~ zBmZfzO%3gK>figHoBls92-W$3AJ6;m-A&AYzC!-rVMX4jX8bjutK+{%`d=?yuO&!Du2q1pE?K}`JWGj>U_YDtNy1U{~xfTm?yFFLjAw)b@lZ>=7`_a zf3UIe--G;Tfd4K_{=L84)c^b-RObVJJnvt=|K&@_{|%h~(M`|O6Du#|zwCL{zemo0 zs(gvmm8JTBPy75o!v78Oe+&Gv?M%qu`GU$H9OA}*YW`P{|GNmk?)Xpned0fs(V6VO zd$Jh+zD54;fxqlmv*W*AlZb!9-&3Ugzi*g-$^Sj_{{Z~4?M#^e;4O9j@BQi~|Ec-E zL;l_fzi$31Kbuwfe?a~pf!}+X^y!5D%X`%Qe{WHB|F4;@*HZmYPMiN9k^d*)k8NjC z{N|+FUbF2;BQ#P?DZeksg8fF*-iet((?Zo`F{oemJYN2SNbjKe~$P+ z)aEbE&;R|`MgD(9{@;MV;&-$8Pxf8azwapjAEo904f*?kztNE2|3UR1IO6{}Eq@>K z{|@|>f0+4inM}sN#og5ZC))gc|F3IpasJEi$o~iMSHEIb|81qJf8SC4f2zsf^3?(? z_Zf)KX|T+F4w=F~4}@jzvqgM%!!q}|+Eo5Iqz8TuK5NCN56j$Vc5Kg(+hNJ3^UqCT znfts=e0IY!_nDo+KWkx``}E=W&VgmO_+;O}@8>>?^bubFP`Sua{cry1qnQWi zgX13y@%*=3yMl83egT%ruz}wHiROPof&HKU_;xS$`#V!@%FP zuo-{Z2WtI$ru=&po1Yy2oWl7*E&CHb!{eX2^Iv-WGa$#mW4bNv|L7n832-A36Tt_Zb;iE#-e_?bm-u{{IpA z-|z9vGm!u0Ma=piebxih{O{!^|JnJ){0B}SE`^QH^}n;gN%zylQ$qig-}}43_-Dy~ zX_o%wf&ULbuI7IT^8W?D8q29zU7`Fpy`zqQzN7j#%|F{h^uG+}A2#9f%tXk4@BViB zKYO--|Nb=X<0k)oTMGW!(EnJ-WaTq<@*gkhUw|DRZ3{Es~$;(>$Q zH&0B>%eeADVwQtK@%ik^f7d%uLVCf0nS* z{{z$fAMGapvj3N%{|g}hZI<%SGH&vJreXf&{qGh-{@Ee_HHQ7aW*PPT4@T<0jjq?y z{AV}A`A^F}qW>?+`M+MeJ@YN(zidf6`DcOQ{J-8!{$>AP3jJRQPHF>7{ohgk&q|yB zrICLQ$bT%SFeK(a3eEpIe^lo`0m(mKOXS~~od2c+ME;lI{8P4X&-6n6>n-KqH_iWX zZt^ehf3+<7Zv-c$&)La8o6SxCza$&URDv(V{{7MA{P@@M=>H?8Apa#_ znALwnR-ONNWc;h8>$TMXcQ>5>)a@qnKaBHl{YHD{H^_h2(suICo->>O_$Ro@zr6qD zis=7ha8m!gng3Yp9qOk4UuxL@W&VdF|6Gv&SWX34q4`hc&+7cgb5#EZ`OjBg^OEJf z{zoAHCGedNOaA>?#s3P(KX=5x?)Xpr2c-YS>SN~hzx-dWJ6!a?k;s23e5Yn{-v8+K z7Ro>Uc{aP7`rmg{>@N@aKvtapR9P$d|Cm!A|N0ZI|7bG2{-yM5QvZ&wfB8)F`j3#m z>+6+x{jZAt{|Ef7rq{m^e%}%Q=cfGO^*^g2|6joG{b`o}@+qqSz!879A-~N3>d5~$ z@HZRsHxPbS=BEC?Fyxo{UjzC70sdY?{$9fGIpY7)lt0XW1@g1mp>@7$HvjXclKeZm z{_QJ6ewqI@k$(vA*BJ8G5q>t#P5!?&P_{-5tC|5FV4gBfD{ zTMPMT1OC4Mnf3pQg;oB*5&u+8{$gGK8EpEC(eG1e>ndu{Z{a=gZ#4tf9dOH^BjW&SIXe@@`9{>!ZY^$>pF5&sNBewqLEkiP`@14I9{)7AV3j`+VZ8Ad_HRPB1-vIgN2L7@)%=%xjh&ulJbL;LtY;ok`P=LP=Qc5?iJ{4Kwb z`ge5vGd2Ip$Uk3%U-$SY<@W|Te{1;q*T%>{Kk(PloF??&FE{+w>|pPGL&~{Y%TrYW`V?>c68%`QOVh|B`YHUB>G-$2)EiGOdy z{7e3AkiQK0W7{co725wP`$Nrtu>4T|`f5zPUH_^1tB`+*2)}OrDL3S{Ye;>pAOaASVe<|RPZD+##*ZisG-=D{ge|>&_{9hjb z+YtHZf#W~*hR1(eW~lt0qvK!S8y^3W{!14f2Ce^+{QZw=J`%5g?1=pH zg8vRf|K2yM|9~9-%f3nailzGh!O*{)|LuVM%Ygrisbo77)_=nqYX4*Ns`cMU*K3J? zU+w;Gpw|8M??f8G8^{riske`^0bq5tI~{&o4Of1lKUvGT9)pCA7(zfrvZ z&o0Qn0Qhg9eL89Wzg7FcKTMtfchdD*s{dZY{xA1`c18Xy`0u8DIw61g+G_p#r2Z?X zk#WTm|9;y2pZhNzCj9Tg`M><%Bbie0A9~X5|G{^v|6qK9>p%MApQ3mDM{56jqW|T= zf6P-t{}t;H|MR=)|EB(B{qKhS3r76w_CM;ME#-zkwg26be}#yDU4H7H4O;*F{x`K- ziuqp+@-GDb%ikh>Dq;TX>ecr@^&R>DQM>>1{a?BNw-@pc1OH95PbcIrtyJruU9aZ9 zhpxB3{wMxk(#8JT{h#w!e-PT`|I%jsv78imz?5Ge|2P2oSAzU|J%;^%ed51Vfa~z z9}_#%>YwlbR!tN8zlWm#GVouy1>7Mewy}lJ|7>no=f9pK|Nk}gFOPp5g8U=Fe=qIR z;<+eP|Fwsz`S(fvS4}5%Wyyc7cK=^wo*a^V|L4Pye+ls4XjuPM$Ef^l88`L+Yg+$x z$iFi9k9kVy-y`!se<3&grvB?b7xjNQ@-GSgn`So~{~PL6|DGfNzv=tWS6=B6V*bAh z@?QquX|r_y1JBXV#UCiqTZi9c|}Z<_zwBSrlm zi~LstfB6`*{zv_Kj?RBI$bbI)hxWC_`~TG=|5d=>A?|-jc?#vfy+ZB(0pX9WH=jcK zSM>jXU3#uO1$oY@4^;+UTRGVL%|Fy2@e@k zOZ;QB`T6S~H6j1W$UhFY$y?42KO^V=#nx+y|1d-T-U*`qPeJ}0V4JG4X8biwegE5l zT>lqauOM z{!?tdmiUh_ek_$3N-u4>o9ze~|unB=Ro>$3MI|%;x|8c=h|2+-)Z-#BES%GY)nAjAW|5gqs{g327wq8s8M~%|klg^6y zf9L9A{67NuSB3ny(BrfT`J3tM9}BC;|N7{9E%6_yef*c?{|w|`8uA~@X+r+WXVv@% zB>!SHxUj^ppZ}8lUzYvzEd*HEdL0`zw*fWkL`55miR9)?Efpf9!cG@W4fe`R_ek?Ek@= zUWfc^;)WdA=9`In32U$_2g z{yozF$!5SrBld{V1E%>8>O}tGP2WQQx4||w)SK=9(2WmB{$uO4#DB5j{72>=-t;Tv zuYml=aw@ueB9)_@OWMgNoehd2EV z`PYo(U$_6!{QHjP|N8kC=fAaz{KK1`g#61x{u{P7^WQ<||I4|l|3A~_AKvsM#**|MyA$eUks!dM)LDeZ%}$9xeRCn;wPyqagonbe@v1{{{P~_3xAZU-B)PS6Sje zxMIL^k9`x)?#v(mYraSD!%06O{|dSOKi|LdmBKb-Uv@~;K?kL5IB{@agJ$A9*s8~>^E4=4SE{KFvs zore9t;yE?{o}>Q%SK9o;Nk1X~osh{+!~8ds{Cnj3zu0;$<$r^;`G=D}L;kfR`PZHQ z(EJB44DS3l-6#70HORjrB}dy_WJ{X_)`|Cj~#8^cM1uhWyvkc}l|m?;o%F_elS5r|Y%Ee@I1aiZkE? z;rvJL|H4U6A^&j5zi*iT?3pTm;HdxqlQ#cw(o@KPH#n&%H_Ja;Ma{oQu78QG*OLDY z)8-#edJ6g1f&9mEnlS(MH_7@czp;P4izB?*GC`Pa*$GkpC{j{8yf(=AUKV z^na#({EzSduw%shA5MA-`CB2A-ic=WKMi-Q`~k^-Y`vE9zh2t>!%43p|GJU<>&|~@ z{sXfA8;hfdve{~>Af4<|i@{P%#9Zo~dxw<_uX zuu>V)n<9{ou{V$;FwZwmDMXa(0d?1|v z$o#{Lo*{oZ@WpZ}R#xcsuiC}b`u9ox zW7}kj-!%Vn{}&E=hx{XR`QOHD{@eC~di*DFl>gaM=AXeq&yfESaMEKb|DL1sUsC5E zPI?OY*N^01cm6~3?+x<&%lqHKL64AsWypV{Vg5@i)a&2aZR+?}tok3Spa1;pAKuMk z{tr97A^)S0|K>9+^?zsik3F*kK5*0;>kSz_ma)<`IcK=cuDRZjMaB+cou3^0(7Eva zaOve9hc!ZJu-xO_pYiV>4Udn8$J$C($UlGK(pxL{^Fv^;O8HKsoQ_XF{G*Yo`M!)3R4y!&$gc({aBB>KpT@vn5O@V^rGzx7}3nLp=) z@n2m36&wFqMr-`{o-1(w&;GXdB)#+B`ddwZkB9t?z2$jt?0(Ka^`@sXe*u4wC4S$K z-#^(6f5T1U_&2=h5!U|(5b}~$%;vu>Wd84yhhYJ4> zaQ>d{pUw=KAKw2}T>q3d|AC=@c1p4R^W#6g;qfon=?(p_0^?uhwr2CcvPtUv&s*Nj z_&2-Z_$TxKAo6br`H$sP#Hi5xzhQB8{?A6Z;Wy2HTb;=NL!5v1PoK`r2Kg@)=l`b7 zKYQM+|N9M&^WTR4SB3mHKWEne+LuxN`;PKIhkpL^omb9(VW%fo|KIHUOlEfQ-*GJG zPwU?^^v_OpVHms|M~g9y#5Ie`h@%&L;v&l zH|ziH^!z6>{#P78)@y0}Kdj>4$NByq&4%;e@c#FYasH{FJd>F-mw$2oYufz#hWYo4 zo_~J*WA~Th`me{)|LTzc9>e_iEvxpwfcC!^Nnf?(za(w`pFsXiApfzPiXasl|C`DP zzoXYbQ|JFl&OdGG@tL_G|5E4b@>&u zZ^ZmpMDnlgpX8qn^8Cx|Kb}JVO(Fk{be@v1{`<)JuK~$_Wo>chKXr!lpQd_|{|TJG z=acc71t9wNj|LpT*|EFB#51&W5v^4)S$UpzfO=ABq;QU`NJt0$? z>;K~XkF@#s4f8LbpCWyc75hIj|IeZSQIP*wPQ`W<%6~n{KU>?4|J3;(kNlfQ@~=Do z(fqT)oB#a&KRcqF_qi81|MW{IWEO_}SB~U;DsBD))BJzoX8t4d|1A1nE0TX*|1|#r z>Ho2Ew$%Sj^DnRedmj0>fc*E+c}l|iuO;Wd`Xv8-UlnKn|8V{JPyU&g_y2nl`PT;j zy>y&T$WQ%xj{4u+hU35V-+}yFg8!JOg#4xC{2w;bP5;;RPd&N*f9(7@Z$YPFne_lcVqapt-+mm^!*t$aFKZWoe<$s>E`JaURTSfA(+y80)1JeKK^JDA&7rOZe z|1iqKasC^G|8{=-=gX^K%q#)l3E%%U#?MOs_52TScYgj0%aTkrSkI)?@E5( z!AJKng6Wl z|ML3RH#z^8!zN{x98Jk(r2lt)!~1{RRcimQ9mo5Br|AFetbzM~OX~j5 zU;pU|?|=CY`mcoicXp8d6cOA)^PlSV)&B31{MYPA>dI37=QqrMZ`l9eMgDCd|5XQ( z?M%qub*`F!Hpxx>AEljtKK@laQqJcQlaYU0;O{f!Z#rM)_lFN9^AyqnE%`r2o1f(W zW#nHU@*n0jHvcPd{Z9+YzfbZ{=*3=0>{0CpO!MCr`u_m=w*&v(my`2U#TFH+|EddB z|AC|af2_8Do`3IJG5&ps{M!S6^}%NKU)iYgvz6V{f4w1p({+OXBjn!!_{--1_x+hd z{#!0m`8`Md?>IyL%IgLH$H>1U@V6TJ@7qcp|9nUOkJsks{ZGFC`zOf16Y#S`%<|tk zL-ilLm{IzFSr3_4SnB^Lrse+>`KxpJr`wsZ|J84;`e&=SssGgcZy^895q{nAkMakO z@^8v7-~anFL;QQhe;Zw|rTm{{n19LNjr_X;e{4Gw=D)IvC~!u&T8es;Z^{r?6-{*Ffk|1{*^8~E!C z`75?l{RfWnf2uY=J^q2`KW_lXKicSVx`h7AHc2`k$`<+{wSW z&yEUl{);rmzi1m@t{k@vzg=>b`gqUDyiTgbedNNQYuu5~AN)tj&+o(^?|52_JK`7G zPUGt-8?Qdzc@}>>Adh#A<&S5{dfHFtkN0gO>RPP7>`eZ6xP4jC|E2%$(7zY)uiO8r z|A5qg`1j>TI_%DQZTFV z`F861mtMm!7Ijnq;h#&o%!>R=|G%LB&A@-mlUQ*f|JjYy@h>3$W7}sb|N8z({(naP z%_ID}{wcpdc=_|syuAN=L<~%YSO!Dtls`a1Ug*>m8_!rXdf4uYln}0YJfYl$x$7%Xh7UHKrAO64L zd+tBBUQ7Jp-$}a6QvbiB|1H6P%#&DgA^slXKOp{N+h>X2z(2qKD;)oSL;kHI{JQ;* z^816AKmW}CTmIox2v+g4-Te27{uf)XCI7Kp6?h;k^4~CdIG^YLiT<|+{|&THiS-rA zf9=NV_|Mi;`(GzruOkAJcCTH=pAuLT~+iZd_&t^dKPAgtwh zyZx_5@W<9W)A;%EuZjo7>tAfHd>_mm|JoMv@9%0>|K*#g{VyQ-uh@;O*Ao9C7W*HZ z3IaF4BikwRRH**NkHr=(!hdYNmiS|Tu)qV5?)>~mzW&{V{cj%#L16g$r%zu0WUHy; zUu?51@t>ys`X|qS^IYP1+iX1lv(0yBW;@7#nA6zne+BOU+(Gj1J!y9SlfS{h*MHFG zQ9u9W_5azi{`Up{WrvyNKfAqJ|NcvE{GV>R+D! zFem!oFXw+Ra-OaTT%rEgO#FL}>i-OF|2+R}esTPF4&>hf{P(?K#^2<{CBp2 zoBCfYt^awD{{ZkG^OTUkb_dme;Hdsh{WrZolJEb|i~Ku*|87J7{-!Fw|EnASi>LKJ z1?PXY5&yd5ANB7KTL1j`Z&M)r&yW7A!GERU@&8WZ-*Z&|WrqIc`JeM4|AFAYI%{_R zE89`cKU-bRe`k^U|5=9pUta%Tiu^l+|0YBK^_!{uKJj0y*MF8s>wiJyKM4HCJSFV^ z4aC3yn(AMy1{apb|J42$LjGOAf6P-t{?g4=|K5gf_*45|0QnD&_}A_K)W1jSAH|EW z28;g^Mhj#vyI&Fr}n=n@{fu5*X@7Qe?aQLSp6@x|HY7hkBEO=e(FCU^P3t(0?cK?>X{+c3S_-B7Y6|k9kVyzn%CGh=1ul{9-2i zm-oL~4*3rU{}o4&c}hb5`kmGM`;Ppdqv=0<`e)X1=HLI2*T08isWB+{G<8z z2YLSG{m+(1{v#m&9Y34B{!_Y(ntxW|X8b!(Gyhp}|HIB3NAly}@A2cmUmiRuvz)>G z57{37zQ5>grt&w;;P*dlx>mjaVVAi7p?@fU+%Itd!|csz?|;klFW>(#i~je9{5PLs z*8hT9;(ue6zp8<(*HZsq+Hm}r_kUXv`HzJBcN_NqMv{O3U6nu9Z!PhkubKbYb~t`u zu=Ia<|GN?B|0wX^bR@~Cczz1L{y$WG{~O;?|GPlbe^&HA`ToblIscb;Ov3;#~e;w0#|6|vy{jd54-ajkGi1QJ~4t)NPZ>j&u`~QtZ|3`!W9z*}$ZfgGv9QnUc z)4$_#kNvs9QvdS)hpV9fW59pcf6eAUHP5T(KLnHA^#4Xp|6%=CU0=@UKP!v+pY5g0 zaD(~}`l)|!bCtiYhu437vs(WhqW-%@{rd&#zuQv%w}$WkwHo?A7W_B zo%4S=?Bz_kLH%d<{P+EzfYg8cG+zJRPa!{r8#m|3>P6e>eUA zGEM(s{Wpyk=l_r5{F`;Xk=YLFziUC>|6<3#`g#8!zn}W|wov)ort;}Q2(`eq^*DMU!MOp8vUOD{;Q5Q>;KhjsrBzW@_)Ief5+t>`*VY({^jfc>!SY? z!GG%?X7%4e{0ENwU!mzA>OVj7__vGt-3Zn@B;ad*((L-j zrnS}jXDhlH|CY|AtuqyMh1G2kiJ~Tbb2AJJ*eW+5a~}|EGZelAFx@w-W#CfCBuM z=Koiv^?w`s-_v6M_X_#nw4Ww@o*V!2{m(W*{|(^3*3f@;9a8_qe>+{TCI45a^)LE$ zuK(`^{%h0re~&+(zM+5LwSRac(o%>bsAs3bKQT`triEVr35frI_>ZN1=K0TG|0wgn z6!M=I;g9YA6}bO1<@X0IKY9IoCFI`+UjL50PMy$yDcS$`$?M<6@~`{)cWgTxKM>o0 zaQ^<+#Q!k#zi-69ZvLr%Z;<-WGB!tE`3~ZE>q2wn`(O2m$1o@b*5UE_U;O?LFwj7M zp#EwP{rBU){!Z%rCtPps<>K#(-1*n@-wzHFk2elH{?}e$=lBl`U;o(>{qG0<`{;Qp zVmk}<|F#3k>%YW*>#1a3X{rA&qj~;|z?o?anjhx8{>A-2L;u^L|NX&#%u_=DUBth) ziJJe|6F!stLv`oJ|E5Rz{(tv{y#BVYKY_uaP}Xr-fAydF*Z2RGTvw3%llqrGH|D%6L_y1YZ|6A$>|IVEMjxEm390dMDPx1Nhz~f&p@$Ws6 z;r+G04eZbVXg&Va{&(U0i-Z5;z<+gM$A4hz|7tz{{+{0c9uNJ?`riTT|KNy!-SMCL zXI_E)_vgRA4e#gi)c$wl{Bwc-6Tv@w&W?Y!O9B3Vc-S>X_n&{}<^6AVMgNC@|IT&! z>z{PYr`urv6R+%lTgo=l>4s|1|Jl^1L1YzG?m6?b!eB=>M>Y zf8Ft)`VUC`$KpPd>tFicm-BxP{?7#er7zg=ADH@YEw+Dt{HrTG|92nsUkCo{$@_(c z-U{{qK2rZassF5aKeKRs{3wL{pYazf8210tVI%qe$=;lQN0|RX6j=9-cKow%4EukR zWB&)B|HHw5%#$!v$ba*pYXA4i^=~o3mg+yX|60z!8Tj8H{P)~s$-n9T-<6L2?}z@6 zi1^p-|I|MlJIY z-$47c__KxTKelz``j^=EE!F=p?f%clKY9Jbp~!y}@Ry7C*QDE9h`*y!J^#rk{61Z; zCH@uD@{d9Oqk%uRoeBL{A4d8=x&DDZpSH&T)cgk{|1lAM-Tp`U*&yea=l>pt{Kw|% ze^1{3sINl#uUTKszxR*2|L50`^;*jRaKrpd{=<>KKIflqXTtnfZ9w>sQu*ogX)FJx z{PO(YBar`i;BOS~|4O&FkbnPhQvZa%o37WA|CJ2=OMV#i!}A|c0RGr^CiQ=W%Fm8= z<3Bb3pZNYKCr0>n`(G8|4~T!7CtLY9Mj{HMeDy>&N}oF?>Nxvo0@W3{UPfUeh4{;z@4l65|^ z;`|TE4=;L$`9A~rW7{cKUTFT;NceriAKS*k!oLObpBdrT%|GS$206dH|Jg~%e-`kU z-C~yia&r75ApF@|$$BmMzt%ASk{@355A#13_+#6dF#m01NdG@jt^Z=>KQ;f!$nQt^ zb@Na8*&yea*MBu2|JlG_{}ee+kgWX+r<4^!VR!b^o`#r8xcn zdc*unet6M8%>VhoAKT7^{PpDcpYJIDsrk=9ez>$u^6TcG@_U1vUylE0A^(Lr{%6ek zf9Zzm{68T4ev$IuY?yz^?<0RB@W-|@Vg4Hlzjv^k{-2tEEb?Cz;n&SS!14fXBGeFBmWuTKjtZ6{!8ms{{eaZL#zfDGueN`8lwN5hy0g;|E39M(>YpCG8{m@sDee{~GY$@*mQt68bNzQvI_LZstEX8~T^$KVOaf=YjvSMl=4F zab)}_^`E_ntk+WiUtPQZ^ZI8`3;)+4|Fz)1&(MGSSk=GpsQzzB>;HP>KOg+ZJSEJ( zcZ2FbApVP0|N8#<@xQKB#r(e+`L6^2)pwGdCgiVLjlBOE@!v||C^D&5&XwICCq=#jcWh*93B5L^<+-~VJY&Y!#g{XTI2`w~m{zYh%Wf6vZek|_3%&kP z+pN|=KW%Iqrp&_@=;!@UyZd?n zQ=jm+PT}u=8r;N>yTIEHr1X*ME-x z^ho`u<@XHveMkIV;r-8ruN=QWp#Oy9|MA?vZ^+MXapPa|KZO3z9nilXe_+ags~i4? zuSES%LH-MXzkVt|{t?T6SwjA>_O>;vf4`;Z{Q3QVdHm-V&Yv4ZZj9{z>hAy3{ojBb z{|TQKxwN$Zqrd;lkAKMhzdMot64?KX?Wc(iF0}t&e~G&P7dSfpVX*&~_wTPJUjMlR z`ESaF;4ZSCnvlPTod4n-rsltfuGfXx? z=)aAe{}K@YVl}v!$^Pa2PaZ}7%fNpRJx-I5zw%~s{O@=*|K4S!t}OAdsek-Ot^Y@m z|CWe<-TYJk{;cBvN#wsA{Kq^c^xt$j>Hp;T9|m81HPig_{?`zm|Mdj&-wOWQXrE5V z->}=_%KkE|Q}bUe{@V@vzpVeqk^hQ_f8G33{~oFTV)5(OKld-s|9TqvTfl$G-K0+? z^k2D*dR)SDTK~@=|5XwHy8WN}_h%LV0rKAg{$rjJ=D(wn^uNR1jQ^(o z<@G-kk^gG&-+UZ7PbDFL#WgB_aJBmW7p+$mC;w|{_kU9V?a2S1h=1MuQ~!aZ{-4_a z3&?*B_>Xx?=)a~#?f>2hZt`#HU*7-cdE~zn{MXSwoshq2Z?*q>r2adnk@Lzd&42DP z?EkXBlYhS|4lED^;+Uz+pz!3`hOAm?~eG_%|G?;&no_3LH_H(f6P-t|IN3l{hyua zrvIDzm-oNwK>k+n9~k!kuKm>h&yG;}%kC*o{_i&I|FZsHM*ilAf8G33{{g9gY<%LY znOy(U|Le$q5BQIHN|^sLa{SXL{)@$L>R+D!{2KC)1OGj=PbcKByj`t-kJP{SVsY|6 z+OYpi|F0tdy%GPq`KSK9S;hZb$bSR)k9kVyzl-<}i2q{c-_(ES>f-g^HzD=4ex&+`hN%g-w*y{p2XS;o&Qiyj(>Vbs^fobqb!Yorv7FAJCXl^2)}Osqx@`; z^Y3H-rXX8t?Jsr~~;{vR~tm-+u3`P*~( z|HRCH^9?FLJHt)?f5?zu=D!>Hp920?L;l(uResMAf15Txzy4KT{~)ec$zA_)k&WwL z9_G)dw`~Fcn}#C`S>Cqdzm7lTry~FLB3~E&GAs6f*)XyHKNa`?ABX+_@;lA;|9h@d z=l{VfZu;N)hWr1r|9ye^e;V>%d9GRi>-${IzfbaC^C{^omgc_?r_KMDoIjWUOKn{L zB=YZ@=KuDh=Rg0<*H01GKg~e?D+av&X{gryAA&;sXZKU9cNCkS&;R7{|2HuIH%5;C z>dyb^@n3)N9{gm%fr_{{^9)HH%-pG z0r~GcX}SFTGnlI0A7FtJrZ@f-%D*2=1b<+o;hOW`e%8~^!%*G%>%ZjnFW;d5Tfu+T zBr;DE>nYU#dS6uMe*y8|Lf304|LYp|zxE#C_eaiu=>wB9o#4M~6z7lmXH3gK+g|Pe z{pg52>_4JA{>4@?-~%!L-=qH)@E`Le)>g=W&*SR&=bc=Df3W!fne$&VVRGgj@ZY$W z9si!Gf7kW@E&9JL;$OG_Q~zvM@&8}WfAJfWGw*@_ZcF}sL;vhiH}x;Cf9pm6w}bya z+NTrNe@Bmc{;x-_f2)3pj4PJvztXV(mxbf|Z=(Lco1FOo{5P#_r~U&||BpHL{|oxR z1N_H4CG_9>q}u-jNA+*&zx7*nes|ewA7nlP|JCc-@y|9>um2fvP>z1{amW6DLjV7X z_}A_K)W1K-{mc2^cbtF5rIRx~;J;QJ|1h5aT{UNZ{_gEiVE*GprQ_GWBmeUHmtWEU zo#4Nf_Gz(ch30?duc-5Xc1i($OZ|U6!~QS*|Bn7=fdBCR&uRVphW^H|KagZWB;O`1cm(j;)x{--?jh$ zq5r$VfA-R4{`L4nq57|UL-p@F^1ne^|9_$XAHaWj{4=e8uh974kAL>03_?PT|a5{J?)F8a{$?gIEHbZ{@S#|!)8r+P38>QtRg8cUa ze@TZ~|F55@@_UZ>H%`l+LH_%Izt)hSJ*V>fj`%mx=I7TxRD}0G-JjS0+kO9x_2Hhx zWiRsAe_F2P_azR8rv+FhlPi+g{d>b7pvzqgLJ=)d)SGX9a{AEmF5y0SF?_0swu%K2Xa|L21L>?Aw>JyZYp7TZ7X|K-EQ{{QTp z|J?Z=%{&19Lr=Q-Z+~8`e{ZP*`R~vFu6q2b{m;Sq9|!;NR^Y7Dl7HXOzwgMutp7fo z|2!D+uY3H1`VSoS|J43Vxc|GsKfDzx>-dKEDc$^s?K@lsrvC5K%YXRyk}k81_kaHe z(f{Y<{JHtxL*Tz|YqRs;TDsK!@13gFe?ZsUU;QTq5kI$S+WtQ`=N||D;jN%q_se$r zKif^^Pm1N=Uu^%p|NAS7{yz`r|9X>0Gi~5M^rV~r;6=6nGvYtS-;aM^v;U{|KQHIM z_vCXKycIfY{N7Ied#3&$aO6L%|GBXKACCCf?f=xjZ|FaklL8N<_CG)8Z@u7L25$w) zdOGaXzi;aQ!D9P|0S`V}7ZUw{KJ@=cuK&|{x_JHz9sjETSndDpk^=p&pZYJLJNE6( z()NF7hq>b)_danhgSWzE-Ya(ev)v2u$4K}C{zJv~&-Z^Drme*H{}x35kLK#%(0|KI zYXA3$|DFaiudw8Q^HDi_$v?8<`UkoHzmTZ^m(FF);J?|Df6vr^n;ZZ2yNL0BVa`A4 z#j`Vyf&b8x?)dM$tomn96nOo&KmTj$@tgW*$MgJ`{mPH?3?F`KrfXi9|8?@?|GNCK z1Rgb%*H`QtGxvco|FZrU!1{kY;$L_Cr~Z9X|1s+R{KtN9;0JX5FDq8pbm6ePpNjMO zvi1VL>=VoKM*jamENd>}|L+yc)?WVq#*6tfdkJ5*i)BYM|9^*AfAyvO|2<;qU&jC6 zb~#^mU%{89SMsHI6<>D!$d|R___9wdn{MF$FTas51F@{RiT}S>EE{j;{|}$Vta$&c z+AT%@Uljd60shNgCCBN+FBTgAJ3dv%|G<&|EwsmfzW-CzD&{{+ApeuVUvJ1?_L<7h zE}d=Q`nQz-Ew%ai`QO2C{`zm<<2DL?-^ZT|~Q$G@la`hS?~q)V9H z<>$Z6_Xz(>qW^aA-(l##o%r`0`QOUWe{H#V{eLOWKVy?0@-w5-Yxq1Zt$(&hf&BL) z%zwtQ|E1CYQ@Q%DBJzhZqomU6`227>i<>x{`37$UjO{{T={V-cl`Gm_$PLqa>D%gQ2sLu z)W0Qu)9atxMvDHo9QQx{fFBsV6voP~wbTE6!~FY2&p+S)m;OIS|KlV6b?5)oe?YE( zkG1=m=Rco+dH;{)vHm9je;d6{KVkm;H`M)KkL17PGtyTq@js$}{lCh;BJw{A{ITs! z$e(>v|LiQa|JOE>^;*jR zqlWpH{3DS6IpB|NXTto~zNO~hC;Y|Ae`@}fkpKAzzi$31zcLQP8Tez{nUKGo@H5{{{!{a> ziu@fBe%<_2{($%|R{fju%kh78RCggAVUgh^3 z`QI+B|53>QX2id4{||_NZ;<Z)5ZB8>mmO{@ZV+Vznl8MM1B3M;tkSQEX{v+Nb7%n zHsJibTij^69P zsr^@?|FfgYB{`KFIe?(l{`VsOb^9On?++pi{L->q&xlx)c>+(_3w|;8~;uH%lCiX z4E?_k{>#54IZasq?WF$MxhlU;*K2A1`?P-lSL=Th&}+=Q~Tcv z`6q+_n5TsPYd%o>A3IGQ|BJ=1@1I})*Bie7)t1Qr68LYTeL5k3<4-ETcZHh&V)0iS z_J3LbTOj`j5&ydRr~W-s|Hb0h_s`G&uh>SM|F{kEzYP9+4E=Wz|Gp#tI~)3!$N#I4 zzYF|#ePnk3w``Z1f1miT_==1xmipf_`u#uum*w?8+aZ4k`1jr-+nKQbX}$wT{&z|1 ze|zNr5d6nHCFJk^PJR8Co#&?i8TikS|NcW_|7Qo}e+B$E8~QI9uD<@~U+!l7+jW#) zA!Wt>pRE6Fk^iHJf8G91{RgD}X?^f69D7vz0aO1qO!WVqkpETi-)rc<_h+^Lu_iVD zJ@kFm^tAQ+yzFLJ|8oCtN96w){5R4*E&g($>mM6GRQWwp|J`)GmiWi(_y2tTOa5Ju z{}bSkZD&IM>W@_Zfbhoz4i^4uWJztxR|K7){e|ElF z|K1d`UQ7Nb80KH{?~eSR1AlBg6Xw62@cV?nSou%QzZ>#*NBDK~Px-w;&M(LRJ&^wk z;BTfmP3XV%6E*(<;jfxnocup)n19J%gZy6te{4Gw@>hMT@_QGk^=i`M-+r z>*k;Gvq8=;$N#;M|7+lHp*cM)69R+cs^TXEbQn1eau7W=9WM6Ww&^|;_5x}kB3Wk(fO`X@2ahidkA=S%{MiWpFWU4?JG+ zDBq57*$t29{%*MbDsf*@b_xHx)u$Yt|9jywD;^KGGvtF+C?8pR{OdsU|4r_XQBUHx z3myOP{#NUso$luNpRWIqUmpM38Tnt!z5YRuQzhhY`bFjU$?-3-8eCYK|Ck>ClJ#GU z{NG0W>-InD-=p=9MQ#iAzncH5^&b%b&F7KzTH@b5?eXu! zkpFw|AM=!y{~wi~T|~xzu^zdw#Gl%K9rC{k{$rjJ^0yNI{*`XVztsK@MgAWm{&o9b z4e=k4`j_6rF9wVMG06W`#J?^-_0O(!lYdkHa{upeh-VQeQx@nzW*|Q{$uF>803E&{I?kTul!B*?>q9pXIlS9BL7bj|GNE;`uA^e)Bp7S z^D{4G{nsP^JK(?1(0@3rh0DN^{~AO8a{hlT^8XC}YiXZOSpPkw{sZE_ovzo?`2V7I z|L6YY`LD+#|GPQ=dzp=Yq4#j@@ZV1lfi#UmTYIj{?|+V`;PqYo7VrS$p0Jok9kVS-;z=LKfB3I|1Ik{g3lE&n51EaX#lC`o^7^Pk=w%PTl(- zu*C@flZNkqsQLa^`uzOF1lVz`9DTG|J=XiZ$$pjfj_pL;+Zbw zzod-tU$6E*DJ=YAu<&1m{N2FcINZ#?PxyVpU%3)luO_Zh(Node5m@yWh{-_Ly(=_4!VKRt7Z z{l81l|CivuhvrmlN1^&}UP7(^faJe_GJolED|7!>A%73>w;A&H5q>sK?SJj76vzJwhW;i0)yO{`_+#6d(0}u? zs(+8>AID-5{>J49Kk;8j*K3LYL__}#;qlKik^j%g z@lV~?Kj`sKZ_pn9>@>Vgr&ZOa5QhKK@Vm zuSfpBfIqgK3Hh_LtNHf{zgP_}1`Gdn$p3eQUpN1h-y7uo>}iqzX5{||_#0_X6Z&s| zSiS#OK=`}qdM)|yFwDQ?zXADk7dghZGa-NN93=m@sP&J*7heq){&C1ZB*L$of6DI- za(+4f-H7}d;IG_}^y!5D%jZ=62ju+kCc0ir{$DZ7zvRCe`DX+E*mfr5?g%5#@$YR!>dI37Up36X{JQz4{Qe;4m*f9!$X^2d%`~S8{b%P^{j(Oe z|Mk-KTJryzVg4om9mqcy@W-|@A%8RB_X$4+Uwk!K_-{x4xg-3#`KSEeAm?uyxiUZg z^&jM)2l(s%A^Wij{a5d<{$4=%t2Qo9|9{;u|MK|HwaEVs9RGVGF09{-d6??nFjBK~#zU(Ek)>i8G4Xo)|y|9g=CJMbU#l+b_83aWqK(eZCn z|J51s`uBav|2^rt|Lp$a_}5Q-JK@k5TLALk zLdU6u{4Mhm{@dN;{|&?OPx`+f{r>>|W1bT7SFWh?d&Iw34K6Ize`^2tB7bSbzi$7d z{sTw-FSY*%k-r!G`)iPKDxv@0d)4zF0@DAw=z1;rKgF>AD_35b&wn34{sqB*^(JQg zb@QqD56Jwdm9Ezk|C?#+zYY0+1phHl3H^Kbss6ot-SofI{vSsEg}{HzQ$qgoHHd#l z{omAo%WPu&e+2n|0{<-^l5sjAe>e4ipX$H6g4C6z{5NRU|NOv{`=nmY{$-nOSNAvH`D*1m5`G1D|$8suU z6gvO2b}hC3eMkLIH~(;TPyYJvo`b~sFOMSsBDsWmq)rp^mn^LEvpdxKuc7O;RR3?8 zj(;nPdVdo6e*yoMYnt<gZ6-K-@-y7uqtA>jC&ojvXEBJ37 zWmf-Qo9ds{s{X6iBI~u3|I-ZXzhaE&|4$?T;^4oH_UVNAFS%dk4~YMgO^d_dY1sdz z{|U(d8~BfTO32^5uG;?s(*LpXiLVBW|7VfE4E)DDCFE}-^B?a&>iAzQepCOIC8GW( zB7YzF@1u2^kiWK4_0R5C`CHd6PX15Vu77^ywYFUFufX}I{qrN66J~~98^8aH_VvF+ zaIlBUPrlvnfBgw7CfX0{cLfE$5zc>P{~M3~mx$zFcl@LIXR}KFpF{rNA^)+Qis!S? z{!bUlzen;P(_*RrndYCZBJ%&d$o~RAvAH4t&6e`d_B6{sd)7_<8x9xae}Mj%g#6di zaXO*@ve9b)^GW{O>3S{se_Mb2&;R9?Z3X{}$o~iAzh*S)(+T-w`6lCk?K)(=miW)m z@BjJz|LRpm{wIn2FZUCh7rxW(Lx%*IwEf>R&Huz==bvByAo)8u|MWF}V)Fxk)x&ni zKi`nwFFt=hd2;-Jh4cTg(@*&$LoJs014Dimxbfe+y2$^loPXZ7pV&g+zxok7{#lJ# z|My+*b{Q3GX87cDr z2Irsg*3WDy;I9?$%aykO2ZsFY`J(&J^Vh5__}}FG-~8}1TMqckp0MMe?PXT~>_s>H zt>OIlEzUo!^cOY^_`7bfH2xd%`;*-8x2z`ocXIxY>@REt@Ymb&zrs+n{n(e?@Mm`r z{BMi;_kLlk0)K}ke&5u8ha3L-^#uPrg1`C~RssCkC+*aKV9Nh$(fNTA&hroFKkst> zh3kJ|qu@IYmiXD;hW+n#H~g(0_uqXgzYoZkce5cI0e|DmminI|zh7kjocriUDV%VS z+utknQ6heBAvi=hl+7W391a=C57>Rqf6#Ln;I@+g`oY(t{`9=?lP@g7R?YpwB12{y zlKa2S53rlhzdZi&63>5bE0zM7*l`N+#|s_*Dp^N8{=x1nkbg`2|N6&22>%PnzjTCO z_xLB}56JPKn8TUGAKQ-qXAgw=uRl^8|M~#^F9ZHdHzUWX66U|2y#D1m%Ky8X$N&DH z>5k!s{)3~0|BulBvf#hY(0^&E+W&k<{@*k7U;orFKJM+K-nSz5goy`&NBR5Wb-x48 zVC09Y&;IxO#YTQ4(UQzb|G+T+ZRGW@z)}9+ z*UW#&-yZURj{I5RFWcO#|2LBQXLq@o|4cUIFR2&)yODo+;IB92_itCvfAKa|&;N;) zn5Fs82ipAn^^frV&wG1#AI$Zi+)GJyPc5zVw{W`)&42wNi>tr4wCca(X|i5R{6n<) z`TV!$IN|>b^uGf5&u(Fs|B4ON@y~OV{|~kKRsZZuFzft)A3i*eD|4v47nvmbWo7DelZumb+>tFEY>VIwc4E^iw|55*Jko&JbLHM77 z{#OM54TkmK+^YKb9rgc@4gJgaKlvK@M}vQVyjlL6N&Wl8f5il{UQ6|#(dOsfg|R=|*b*_Z{{BPqg`Y|Cj!IkbfQUAM*r{j>-PVce^UPCW`Bw%1O@{u}P{0 zme^zeKX*Gj&&{(JZ+CWXa{hn$e9j5uWpBUteV%7#=XUqNe;YkdU(vr!u7BzJn%q}I zQ~f(B^!fjM{&PR){~7rwfPbr6E&p5Yll|MoztyiW^S=dA{r`gee}aFXCq@74b~E)a zvi~0BUo-8WdJ4!N-&H>TWjCAQSM}dm!`J_QMgG6Qf8AuY_~&nvXe{Et_PfI5|H)DF zzZ3b_%JLs}{zv^gB>%-5J2kL;SZ_6^8#5#rzlk z|3dzW;NRydAb;y_a{agFn3?}Z_Ww8X$H2eOQ$T(%@4eP0_226kt)}>o?EeqsUpvcx z*!u7Df1jE0U)6u@q!>{I`k!&a24#sww`v6zjk6zZmi_2L3DNk^KzFPv0+ghne_4HLCx9 z$iHsdKlK!lzkPSvzhkKWhxhLu|F)jT z!`6SFf0F;c{OG&ofuLzitl_|EJ6GUwJioUp4vvB7FVN_^&;m`yYh-1HgYu(SOq>GQVZ0{+}Jy z|6t^w4E}wd0{U+w{;m7XjDL~+FOK{J!GF`4Bu)eJ*IKfF+mQcrqWUjI{;DkhVe3Ej z&x+i?sDHbaiuwO)a1hY7&^`YlH2>dZ{bQ(^_}^2p{;?)r|AwIdQiy-+EVcOWA@T1R zivM#JwJ!>wjg)KM3N#TQUBfsWQK1X#RhmV*FQc#^Zk}mw)=eSZo@^ zf9rF4;@?q>e|u%a@xL_sUmxP%7pDQo{~j9uWd6%HgN>&7uX6k!$Mb&~Kinep%Z@bRB{=Tpb?{9o4PpLwgtq0+w*$jpY4{1A0xr&Z*jQAZ~6rV z|8SSTadJs)I`EghpoiZoUVfm2Jg?^UuiWK7Kfyo3<)8O# zNo*_NZ-2$TzB%&!zZCgxL;Q6caR1Bm{GYd2Y!>j>zo-`fsqN+ZXRF@-Y1Od)%hKT- z_$SWupYi+OuoYbXX~X-)YJk7vB{hEE4(zU2|6UHu?|bEc?C|lg$oXgYi){z|oiFR* zw^aE@8Rj49^3VFEUu*~9Z+t}$zpcn`oAU1+|E}cnS6|jYwj=OYb?D)D6#4%#cs2Y_ zFaB%1dqaV<+VtaE{zyTae#F0Y9|>sF4-5Y8G-y-& z!4|>arym9SiSzIO6zks==zl2qZ&mc4m`>u~kpGKA`v39Gv24;Q@aAr^s(bz)Z&{o>uRT@fw+!)Ls>mEh|r)# z@yNc*eI1MU``*uh9dTa&n;vrSd(Mt573aTP3{JZ0)bhXePx<^8r&O;0zU^xAzfVa2 z9>19XR$}}w3-ND1t9JfF;~Y8uEkp5tc}V_I>*kLCr!xKi_@6t;jsK<_-1o(6=dPDK zFYL)~oOkkg_1YHb&y^RcD);#`&PPwlofi)Dr{_iV`6=Gt-sy`ejFxo&UQ? z_55FN{!=qR9RI8c{;f;Y{99|w{MKDEzi(or>GwIQTDr zP0fEd@$VS&e?wINnTDS{!!q+R?&a`y5#uJQ2w_>^mVR|5lQWtD46DZx!pmnE&sH z{1xE8?7w6`1J=J*lK+;W^}pMr`rirpXMlg7r=a}%%l>UL{`1XX)5reB{C{WUUmg5A zivH`*k@?v@X2!oeqWa$f`M1pSAGZFtQvW3XQ9S>xkNu1J|1QYC2KcYPLM{KhsQ>-s z`EQ~4?^N_JzW=Qj`L_c9rN61w|Lz0i_;-l^<^t9KZpHd9=Ks4P|2Xg;zf#SA;#`^E zGL-+VQT^|Z{4>G7&l3;aeDnXd*@XWgGxbl^znK5;f&Amaf5(Sv{yV9EL;3%|sQ!0F z{;jk8hpqqAKPz(oV*bAu@=r+nSIqyK^W^xq4dwq`ivGp-KkSM8v%tUeyITG4sFV2} zvi{p$p!)xvV*MBM|GklaP4Hi#djE6c-!bI>?x_CvLH=#Pzt2;^`d?EnuYWj(@?X`z znE&sK{A+=KThYIDz8wGTUNht0JyHE9kiRC&f7tp@{o6(EU(EmaNB&Ci-|&dq_@5&F zZA0V#y^8+D_kZk%{M&;6nxE9x|2q#N@&B+K|JB!$_f^yJ-}j33U(Ek!Bmczo_^;@{ zqexK)|Em7Q{QqF&UkChmD*A6G{%u44+Z6qa`+pyV z{5ydEB(2i{JA!|or-1%j4wd7tG}UL!te<-+$IQo}d3&kNi7>|Hi-7)_)og zm-!t-{(n@g|6=}s6!K37|4oYilf=I>rJs9$DPQ5|9h%0!hZX%-dj5|_{#x)~GhZ$K z<4M^+d&Erq|D@<&%>R!;{wna_rRcx>e!~Bv8U9B?`**+pt-F@r|8umT+xwei1abNT#to6LWGxSI0+XT|sz z$3Mp*{}hP-jxE*r>qz|DhT{KG#rW^qmB)XB%Rg`6px9v${}u1(iGSYpb5#}wnga!(%rC%F9Q&K?vy0^+~%T|M#7p2@@COZ>Cf&BT9Q4d*}E<=_9= zL9wHOKlyqJRV&LG|@xWj6p&oummH$mM{1wM=|F+9tH+yjG zB;aQs>EUP3D#riYX85c6@%ulY>hd3W)8N=Cz@JFz;kQ-CzfLp!_2+W`XS@6}-X0R0 z5ByaNH1VtYUtpMjj>|uN;F7T$fWLd89)3rae__G-Gb3;H+GE}0^V2#1aZAQ-2L5E1 z9)6bZ^S@rkKid$0TN97}GhF^HZdx*S8}QeBp@-j6EUNLs`+Q1nc)}5|0lZq>HAXe2FL%59;c_@EcnTH{&yoe{&(o{zq=XyucqVQu*d%e zyZ`CaYbo9TGXBh3eRBUx;r~eVzk8Pdu%G`?|Mvei|2tNy`QNFsPyCDPKhHt`dw~C1 z#r&_BFR%YOWc|C9ZdX(O_k>*kdvQ)>=KEjDCc5|Y_gedm%FOq_q*GuHd_O=1zkhi$ z-4A`j? zXKwY}s6{&wO{>Axk7b1TmUH|&2t^dcjA)o&d{?h9U^ZCcGA?shk;{Q#x z_+RC%zKMU~{}S{MUs=X{o&wgt)OBS1Gj#r2(fHqgZMFJ$z}kIM|AhaG(Lda>UHA`M z|9t*Q{_`-xM$`CLH2yzV^uM5Q{EOqC%g{gEvV|pRoer4)_Vsf9vw8CIe;eJdCjY+` zOZ|U(9ku*_W}QCCf8qZM^beP8F`uV^{#$G1>mRMh%*=m_#{VVjs`yG4^YnoE-&j&Eo$qTC|8;b` zn(F`WA?yFs&rHg!TeNNKu77y#P0vCnV&esA3+{;<0}u0y$r^Ystm|624v z8~pn`@mI>X{?T;<8UGzK^*^-#Pjmaf<1^QP{6RPVz4o>Rx&0@)a{IS4{eJ(qLw_#+ zi7#{ew|RfT{a=Ir;g)T}f7tp@{W~Q8eF57?`R~QQxc5<-pLZbt;lQ67 ztoHd=VxT<#vk8CvroxQ>e}#^J!rzMg^}z4j&w%mYk|6p2xtaKn%zr2HACbi$HvTEU zL;Ul%5gSeQPnBQX|L}jveGuf2>sN)x`g|V*CsKyOIAW;P>rk zK>n&*3I75!@gJH0F62Kti$84qQ+~%#{;TqfrkKz>#y^E-s!w{LyM&z4N@OXub8^@e6 ze6rb7CCkD8>3F%9^&eJNl0FIUZ}`b(N$s$zwC*kb-&1n^Yx;VH%=0?VcdxsjI>>!y zeY5-b_51Sc@lX2a^Pf}mU@cm_NctBmy>u1$$LIfE^nYBI|FHQ_{o6(BpUi*mNB#!j zulYe523|;^4guMR0VC&!gtCZG1 z;{&StWc^Fr|LYO-zajW%_qm^o(s<36|1E8D{yT>JKOWM5oUeb0`(HhV{2Kv(w_^Oq zACURkGiK`F6CwGx89v25|Nmt-&&zn57%?St{(m|DJlkvSbUy?`=aDWP2nWqJGuboocq`1fQ;|Anf5$xEjw)xQ+{U0XB z68^3);=e1!?|<_qp8qhVKV1JY%RT=|E>`)ke@(70uYa?j&BXtbA^m&tFXq2bWBgBr z_^)|Vt^OxS{97Gn_@4>M|Hb%CGUI>GFn689Yppdm$$9Y^nd7d*MH(R_kH$SYep~rp+Bd8=+EhY%U=9Le@_2f_2M7; z3+Z3X|DQ+yn}Pq@r_}PFJtU8R)~janzdfY?LXCfHz$m5hF9CmNa{Mb4zx~c8O8gG| zok{*UpZ|&DpBFLyH;4F7Db~Ll690~&_{|#OL03-Dk1wA%Pr{;)j$Ifned5Yqp&&$r8* zhu^ZRyUyvg@dewl)#3V&#*5r_F0b7O`qS5cv~TY|-)leP{jG!e^&-5r7jDPKX3bmM ze?K_0ZkB}p$yxo@itaj>1N{}y@6CU0e&3B0^pDGWzBm7kcWuYkfc>G*ho=VmiSzm| zj(=W9|I@*LLeYO6@o&9uCjVay>Az6pe`@}IYWaWNetnYv;`rxH^j{7B+Z6q$h=2Bm z8UHU8iGSyl*-HN7pU&k?X&0$p6bl;y*RNPRYM@U0t8} z7xVvj(Epa;zfRG=P5iSr&E)?pA^o2*?6l1Kmv`N#*Y2}iy5B#}e+vES^(=3l%Ul1l zho2_h=PGsGA(?T0KJ=%r^Yi8jUdzf)O5(4T&O(+%$T6nSl+!5^OFjsIf){~r3^3j8~Y{yT_&+mQc`kp2a~H~;+r z`DX%u`Lk;EFaD@p|JYk*;{R1eelh?15c#(T{(43JX2Ne9;(tw%U(A0#LjGC6A8%Ll zU-p>n-+J4O|JN1y#rU5>{%wH2L6N_a@H>Y1-%#Wi9zf+Ol@%TSS{vCk7@_DuVFME#of7guvcNF>S-sS!m zApefQ->Ar+ApDLY{&yAmyDs71|FRJIcLM&DB7Z00x85`3|2;*1QUAM;e`nyY-bStd z*E}!Bzhj91eO3PVc>I5X{I$UEw5ip`CQF^54rxsA=iJ@ z((P(G|FuN%`WM0fHS(Vb{J#C<6QO+bpZYsV{2RLdBQpQP$bV86f7t6^D8F6g{Nnn@ zZ;=0F;BTdI8qj~u2lD-|S(lvur3*-2X^Q{FLdO579mcU5IA5QxXFiqb_n)`dxZ}9Y zdSmrT?*4o2GdsEcrIqe@>9x+z<1*`_o&0l5ukC{V^txy%Kkv+Iy!Ixe#=N}nI+{q3#pd5B)i^@#@dR=)nV8~vXG{(YVT`mcLe&VQTu7dznn z(ntP%{NEzKoy8wE|0%y!wEXV%Z{qtOzDNF3fxnIBX+Zy_@5%lh!e6$qF!|pvWd6tb z=l_ELN8~>Z_`~`>A+t{ z<20cE9^&67{0`l&Cjb2v<6rRqg8XLyzi&SS^4GsF=Rf<>O#DaY{~7t=D;orV*!ZXX z4)HJY-utDG{fqmb_aHyqvW(Si?tcHBx0_y@Z~kBQf$ZNR{_DF6Q~w7j#=qeI4fz{^ z-?yLq4ampeNcbJX@4b(r)#N`i|F6h@W)^?g_^14Kk@Gui^Yx$Kk^d~Mn@(0|2; za{RMJa{a5hkgO|e@;^{9{u6P|{}uA@2J1gvitAtYi!#4sX#FP@di}?p|0dq&>z{ui z|L(wVy-4a*K>rf15-~Ylf#Q%vZzjyu% zTOxD4eR@4$PvEcV?;g*4n!Gk&{dZoHv+`NjD!G34J1_*)eD6EDmBjv@Zf z6#2#ZFD1yI0RGkiYW_P3zm+oM|8qrtasJC<$iFx6mkw0puX%;|H^dKL9~J5+POty! zhy42hf14tIH{rKFHsgPxBEP8r{gHoP;IAuH^B;eO)PF<#U5fnnJN)zS0m#1}@Rtu# z<8SMbmR;Jnx^Al)%6d-{|EA)lf@r){fqKjMb2ODt$!_v@qaGx$G=cp|L7+E9m3y0 zx2ws2sp9&V;4ee|^MK#Cp8?~)?jt$>of-YeeTqp26bt`QuZ* z$nozG{zkf8P5u{GjDNvD0{Jfke&2oul-=$3l;y7`OA^NIg3AR{8N5by!>wD zHSy#BM)&w*J{HJK1^8Lzp{9FF9y#8$y|5aa+x}qunmk6K#?kigr?(xZrF8|ikhsT}+ z|JL_<{97-m`M1CO=kI@s8YVvfBhmkV!N1Q_K>rn=%JrXpn}@&e{DWl%-*eCXui^4< zK6};J@WtWy_g6jsZ8(`+{+=HGM&@gl;OAxJd!FL|kJJ2L0sUW*^@F09(vu=6**Zg&1=Ko7Zt^cE4{@d?gCAK8^k87I$IdCzp()d5fu>aN3e-ixrJO%V` z6aO~x?<;qj>c6Ug<{kg7hZq~i%ClUe=hX#pF95(`9Bu@ zUz_DWZ2hPHtz!4@&Hu-9|Ff5meF*-$bshh|DAzw<{P)sf8}i?N7q9>0(Eoh!-%aau z!2ECfUcUa_A^xksDNOwzs#yPfZsFtqnlAt83zv_50{*Li&@=u!s{Vg5lmEj1TIl~e z@bB{!(7&@l9{;WH^2EQU`XAYUrOSWr&MU?ifPeOrCjU<>*8g7(`=5aRug~%yw*FK9 ztZ4n0W+Jcq5nlhkDb0-2>FZzKhW}H!i`w~bJWWJn4>J@0;spc#66a?gG~dqa-`cMK z8MPy0iy;16yWKh+dH(ZK9{yhT*Z$2+{FmRu{ZGXBzX9UEYNnh2bocVDf3*#gzyHoA z@t-Wv_*bSl{t5q+T>j~eBV*m*zf9BmCwp1VKl{V5|Mk%Sjo{zsi3dVH|FwU~;~)Dz z55K1IPt||@e4hW4UH&a9R*L-y{_B6xl>e&!nVI8Xk^k$U|C_S>haLZ@e~08httYz9 z|5Ejzyp{W}aQUabJu0>`tbf!lrf2@c@_ql0?+tM~Y(wi`b@%f6Uxof#z<&>|(*g6p z`ENP@Et3B&-xlWhXQ|Nj-#z{p{2L*|5y~+P7Uz{-qZS@Q*nE{JVB0KmTP2 z`ac-1f2kUxHvjJ=*S}cLghWNi%P&Iz*P1(O=i2nyg{@PV}{%?l- zhXa32nHql^;b)(lng9Q&$j?S`{>_oU9{6j2R?GjEw`Bj8A^x8f`5WHi@&5;||IFwQ z*S~D%j(?%Y|BdD2e`|^v|H~-y*M7+Pr=kBNz<=8>YX0lrmi^oP`u+3gUz*0hpB4Gp zN1T5;@*kOw|E1LOzp7K_cMS3WqR3yq7(f538u^a`{>0L1{H=ta^*7_cN0DEQ|1*&P zXy9-7O)dV}JFg}j!n zx`@Hs#k~87d*6Q;hyG#E@BO{kTF{?fawB{d@e4b9nsELjDHeZ&&0mUqOz4%Mkyciu|ox@%isI$bUTW$A_u;ZzKG+A^yJ< z`71W&<9`kE{|ERx6!}{w%ky8y5dYsH`BPTz`p2f`u76{pKV65sy63g=O>@^j3;Kt_ z^S!#~wF&6YRsU@0&sG2Kfd2IBrp|KfpV!)(=dOQA-k-nzx$D1e_woGS2>suh{$u|6 zFZ?F`5uR1IB;LVluz=qn!VRivP&`J0gE;7Ju0Ir~Ir)`42jO{aAWjX{&VSIbNG; zT0gcdeE)gJ`|fdp*Rl(sAD%Df`5(Ife+}r*Y-iA_nRT8v-X=ehk}3!4b^6X)}P z@%>*rqyPVb{{+obzSVs7zq+3s|ISkK{J)KES5y68Rx$qt|E|b?7x4S`Ga!Fif0^H2 zTITo3DHi@(hWz&cf7$nBoC@f_=UI9E%OU)Abi11T4^xbP z!M_Lc-wXV{{S3&T93aQPGu6!JzmfTONB;Y=_`}9OD?(vV9|LuwV_XB_9 z-tO@htylT#e`=uY-y-}@f#QF;(D6_B6Ug5N{J#AR82>G$GQUIk>HDec_$M;|UdaDI z7Ju0Ir~G!&^1Ji@?l%7U*WSqgAn=#-^FOJteDU8rNcPW`mGi%2J~^(^RR4#Ej(@_x zFY-SG{J#AR82@F1WqzCR)Av(X{HyYd&%d@s{u5yRuVOj1_0QTBWq!7rnd3jUj_;lQ z$BsCk|BLwF2l*e)@*g(;seh};{a23V>%aRW|B2wgQ_+71^*>O~f1eah`5#mCU+vYu z{gD3=@ZYeHTKspC{C9}|ihap;HSw1#*1wL`x&PV7e-ij_98UI=i_2I4>qpA@ZyEAm z64iel@;?gxeVzjH*RCXg{$UL>6aT9I>&J8d2O|H;;NMwH?fl;^;@>vpf3c|k4?zCM zviygw|I|M#a{rwha{mV-|0&?Vsa!4p6D!I2?-=smPtm{iAfNvpg!~Tp@1%7)VE(r+ zF7w-K%k!Vc{mA>Oss4{ptpD~#-2b7-Z-f7i{%ZN(N&K@?Gxe{3RR4z||Ks4_=P96n zYYExEV<`Vs{l{b6|KZ4gD){eG%>SB|Wq!+${{d0`AAsr$IA7OZw4Dp^>1Kk|L*#i`23?D`JV*;Rr{;)mkyERpDicXzb3j} zP5jF%*8djo{O6;Pe-8MsUS5sgip%`Aq5Ln6>i=lue+vBjJOzyZ7UJJF^!cx<|C$t^ z{~Uw-r-OfMklOg)M*KU5{11xi|48JATeb-QVe3EjZ;|}R!pDE>NNU%HB%|7?(4{|d!FIJAFq{>!n*50`8*>j1U-SG}anZxjFBbi11Tub^1}d%XNV z9{J~j|C$xl_-*3fGUR{psQ&+h{Lg}apQnKJzl->1!_CCMs{f8se*WhP$UhJKvlZ3+ z_YnWKA^%H6_1}Q}?OFcA)_>~XA^BgZ`lsq&%>Pe9{zmZMs_4IdRk{8-hWrmv^e^WB zCnEoI;6FKAE&dya%KR3||C&0oT}}0WMaB9ruKzv-`OgIZr6b9H2CaX@KO1bO{w*2R zzm5FQgMXi=fc!OOvVVv8FI4`k`WM%~pNjlvf&Vr||5c-8erpXg$NxhW{fq10=OF*t zz+bnLTKuY1msaE#mr>*wi^lue-ZFE%~j)X9xMB2OPHyD<%;~G{-1;V7X!aFPmRBNjjzmg)qsQ(ut|9^qM{9Hx;)5!UchT?x^MSijVcQW$7khT63cKw&G|JX&o z{v)n`I}Q0?1b%j)n*XMyt6@muBP~pE5^UzzZ&`90)F3q z2INm}D#yP~_zUGfGXGV`|8^FC*!ZXXR+00I`Oh`T-wFKoVQTT;eujMf=MetN!^w6v z#s4bd<3IDt)=^{KeBHq1e|qfb*edY-H;uZ!|M|5%_1~8eZihXTpO@Rq|Bu=o=hr_A z|JS1bcfh~T6Mw;c$3L~3ll)&nu7AG$?qmPuZT$Xk^IiTec3v$u8vJ+t;okov>i6HV z*VX*9GQ<9p=>Od;|6%JN^=}oq|Jp~m|LeK`n^udB1^?Ecdi*=8{+BAa|4in!Jj(fR zbor;x8xtD`{3%WK&w4{K{+BkxpL96?O)mey<}tAez+a^){~bksdl@tQRZnyN7MH*J zrZKTf;BOzGC;qKB75y)3hQIv<&VMuKzkf_@9pG=)mH(>z!wSw1-|`4?-jAREeT&OK z`N`+iLu5IWztR|7|Y+w8>** zQ-D9IiQiV_w+-=&_`luduRm^VYy;r$EY;+{Q_=r$!~XAZ`De}>8`}u@dvy6%$0)2O@P1VZ%zK+QS)yXowb&ZzgCxj|KSy}sleZ&iQiV_XCut|kDuti z-n6zgV$*@YYOp5%?<)E?%+K!P@n1SFHUs!unR`FysK>vyB0pQc(EiE&FRyd?)Ayf# z4~~CRbe)PXT;yB-u;-EWFLM0bR9~3&uT{gZe`V%>;{3OZkpBue|D*9zwe#N`i>&_` zI{zac`uq>#{~qLjAN>0~1@vFFh0JfQXlDIO)xS9Z?_T7;68u-3PvSHnfBhU1|Azdp z64n0=$p1l>|FG*{)ITe7|Kj||`;q@D@L$=a=D+b*^7+@2hT>n*zxe#?KIH!p{98w; z@h5MW!Y z`R9ZGmW$Q=caYEj9Yg-dM)m(F@_(A;KWzP{{w$BCa{pTd=f7#|Hb_OY2?2i z{I^|7_LJ+%xBeAxl=<0EdHgGs|J9@Ve+KzK2md}#0r?YK$?PW#PZIyOA^+nP{fqM- z+mU}E_%AzFjlb(Tx&GP2zeBgHss4{qtp8&E{{r&g1pYfNSL3faOXhbB`5zzE|BJ}q z1^#`W0@nY!t>ya1RyI@rRsDwnKIIsP5uzfk$F z>R-(NUq}91!GH5rBu)eJHU|EnzjVe3EjZx^|LG5>!P`ELXN)mN+e z?;`#kL;fd*_D`<=eFOQw2LBDTP6v(u3+4LntS_(sRvb^>S55W5Lb3jf`TyI^E*zZEybuj*fX{`D5}f1AZ0w*FCmR^l%%yppY^Z)LI_^-cOZT^#-Df_n##s9jB@h{fD-$no3;6HJJ8h__Sa{fESf8~D) zQ~y?1tbbzu`#$owg8$NM$$kdRf2&F6XG@#O|4C8(e}Meofq$Q;fc)*-lK5ZU48N*> zG5`G#`Tqz0%jT>3ucY&TL;UMS_5U97f1l+)Z2hPHEkpdO{>A(^h5UDc|MKh9{M*F8 zwT7AapRDL#tbc!m{6B#I6s^-i^FJZyKO_82Cy@75)BJZ0#riMizn>ug-Qd4n(SHwF z|8WREe;cvU#9tNF|EI|RBl!1u3h2L%-2aS?GZX)+{>A$DXUKmK_>W&t;xr(C*EVwe zTZZ_jMD_nM^8b|OKWzP{{%u3?AKpK?{^N7x{~7qL6V?1D-<9WoHu2w0x2q}t$0^o7 zG5`G(kALoi__uFRHe+@ADKe|9ke4^WQeauj*gSf4@Nf z`@w(ZjcWcYE|%lpnkTP+;lRg#(-i+3M)kiC`Fpbbhpm6qKPz(oV*a}b`P;yM)lF*t zyNQ1`!A$;d6xu(_L|)BQe*N>^F8}Gx<6<-6`q$E!p6g%PdwJsDmk@4;ZRq+}vHtTV z`u`Q;KY5ax|JD!X{C7zF*PKkYt117-D~^9+{{J=dKLGJ>wUGVfp7Ndl*t8v~|Ayj! zW5xJq7LWgLT>fc2<6^TQ{@XOgzpWVmYy~sde~bA47XAMQ@$ZY%fc_Kv$^IQf{#D~& z9RGA9|AP?!?eD6^e|@K%|7=Y&^?#G_@t?W=y|J3d|939`+}iQ68i@b05>560eZ~4; z@c4JfzpCk+|3}W>Ha@l;@H?9LZAE^zVxjZj{rtD~HJ88X_EDM7f3~ig5Zej(o5yRq z|HlW4{tfZ>yutnd?E0ToHzBqw@V76fC;n|!{*}!57x#bq#pSOnUo*Bl@Hh0+!_Pic z^UvaD_{IIddR+dkYS)bI3H%+J_-#dg+YrC-|EtS?P~)1h1n^h%*W~{rMgOZ5+P}O0 zQPIlp|5u0WKS%V3^`BaI{11ElTfKoi|FNd!;ny_(Uv2GP4y1bNj`RB;H^*H5#im_n04 ze`_r>>tB)i`yu~dS^Qz+pYl7zKN{n|^_hQi{{H~v{~P#AZ4##e{r7w<$G=1TmtREA ztJTE6X6X1Q{H4gBF2cV349MU73E{6a6aSI<2O@tgi$84qQ+}(+`NjA*2>DBZzoXn8 zmubG{tAACW%Koj1vj3W|NM31*|Fsn3U+^!E{EGplUpT3{&D!i{Z zbVp?V!N}h)i$84qQ+|i|_ks1Xe=+}A0{Qy`e+!LMzT^4gKXo-Z{-^%GE=>GaD#pLy zUlRET06(Mq8IZr~Kso;HbAneXH>Yw@vZ>%8Pc&^m{G4{EW=H6&xC7*1r^m~8rwT;j}37%cS@2}>y&VONlpuh5NcR#!~1^wCUW!2yCdz`O-it~Smq5ns~e}|&~+V|!9ZyWNzX-NMEwSx!nU&=jt zZR)vnT!07a|M|2ZCe}s0_cadvx%^nrpN{Y<}P_D`Jq7w7*DNB@t4|BCn3>Yww0?4KDr{@pCB|4!F`8~5+E zsdswu|86h-p+Bd8=+EgN`g8ivY(Iy8zJ1T9@XxpJdG}iOUO4~a{MQla|1t32sp@}U zGXFQ^fAg^ZyIlWeFSv2;wW%+9@&9En{-Hmof9TKYANq6p&ul-3f4+U6f4+UsyVtTs z;rxs9KUYBi4*0M9KrR2uTdG}hjxcj=^^S%Ad z9{bb3$NBg#=Km|B|0lqI)rV^NUqe3svd_%(`M;*)zv*H9m%IMUUvxRWHZ`Ib|I7E{ zANq6phyI-Yp+Bep%=UBm=iB#u3jcijo_DWhD}?he=Krgp|0ltJ#}Kvk|4Q=tmqph< zX&`FyUmezeh3mhb`}f+^>b>}1qZj|spVL3|=kyQ#IsIq0pTj@jzRy43zUSR**|>22 z#r%I1`hN=iH!0?S-2w9a&oShGMp*wlfbNYw=oc=T0&*7hM-{+ri-}COZY^!ko#r%IP`hN!eTOX;7|7GO!U&oOD zt-|`Rb^TZU;?DoPHnmGH{&(%gKlJDH5B)j)Lw`>HneFHB&$sXM&$sV+_gc1FIR9e) zzdHJV7W_9W`tO)6*MG~<`v1(3{?D#+{WtLZ_uBYDx&2$|ewe#>9=v&V0{V0Lx1m3m z|0MM1@}J6V-|wFt>~7zCU2pyuhyL{TJ?~y?@qX|5-hR?)SDeoO$D#jr@ZYWIzm?{{ zA^%&4^nXyJ>%W8h_uAB%x&5=Va{G@%e=h$P^yl)Qfc{+mlbP-N{X2a7o=?wzif`ZZ z?zQafkoo@+KhJmq`hO1mSEtnKzeCP{u?&6wIV+_9v)Ww$6)(G-UdtZL?LVIG&yoKY z^yl)Qfc{+mZRpSC-^py>??1)2PyMrpa_4`X_j}LJm;Yk^zZUv`9{eX2{U<+@*Z&+t z{Hb{)p+Bd8=+EgN`g8ivY(Iy8zJ1T9m;daAUi|ZZ@A>)s zi~0XV^#20*?@{#MO3weW)-!YdLrqBk-uNfZ|C=*7bNxaL94`UqKeTy+i{QWJV>N#J_~FuZOO7G_ZKL{M2Kk3%`44;k3-!+o@vHh5^Z!Z6 z{}TAOmsDH-Ya-`AIfmAMw^Q^l*1sns|I5J7K2eMR$_4WHXHPa$|F&1;7w3PTj`eRS z#DCqliu{Mj_0KWHzm8)46YJkq=>HY)U#sZ9)OT@*lSTRTBSJ z(fW6<|Eig_hC5!ZkNh3rzg5wHijMz={O_pfKVHfCry&1Q;J>_EE&uBm%Jt78{PlFZ znm+$oH+23J{~IFztKdKJsTzOXX(a!rn92X0qWa$m`IiR&K2IlU2{D-ao)W1XW-;JWI|Mpq_6aND5e_%+Ty|Er(K>;E+59}fQG-;p>C$Y1`Y z9RC*K@1Wb&6#wgmum73*zX<=;$p1F@_jwA)-$eM?hI0P<)M(<5?0*LGmxF(wr-1x5 zhs*WfGQ=O*|CY$#3I02oTKuP||Fh)tUpr`B(d7T@sQEt~`A1~=4_p7Ke~09Mq2fQX z|Cz}D4*2(Z3K;+PBDwxKhT=cGe|P?qn9t`wTOt4Q;NSjUE&gi>zfJfne<0h{6#tVI z>%a9GAOB|||GVJ7Vj&u4u~tZx!>u?OI;{w?+Pu;J=a9>7e|Z$nnnze~NBb6MvOr z{TKdsK>iQFzt2-Ze%q4y9m3BygN-Ks$o_Xk{*}PL&r?AD6p4Sfi5&k3&VSRyAKt$^ z{>2CL_}>ZnKLr0Nnx_HzTh1W)Px!08C`|r$N6r83k$>eZ|6%Jt^=})B|H%Gpk^dv` z@ADMUzdeoQKk;9v_*eB`dL57dosmBd{+oUzaT<`HeJOwbX%qe~x?N5AKP7bick@3v zpO62$B7X|}chNiz$lp0#_HS8o{jlrR{{S%PXYOzxpMup34fvD zKeGSbk^f`x@ADLpzj2<-?-=5b?0*;JUp32r*!oZXGei8U{u{b^{o51yKLP*EG*1Ki z@7a>%|5Q2uo#hI%{{OvV{?{cr{~pLc3jA9?kvbKSzq?xIXN13*ZdX(NTVJvM3;zk^ z{}lZDJO$)$oGJ5Lj{NyI-wZaI_#^w@8~I0rf1js-{1uI){t^EO&VSRyAKCvt$p0Dm z?^ewJ?yY72Y*RV^s~3^H(!~Em)coHI`B%&GAGZEe|MtJd|9;5-Ir#T^3K;(_XUXwz z6aR&Ze^vj^HN5`si~M82f6Yo{oC?U_{^WAf`92om?=DdN-$1ecC%56Be;G?13S7O0M(tpE`FP3w3IMwp`Prj#2_4Q;r>?=k~^T^!K%I>wY|B?6iI4Dj(sWZj- zTao{yf8;+s6u;FkPyYADe^sIR-Sux#{}0CaAD5N?VaI=(|BS@HPmHGcSIvJh|2-V} z#{+*49jEw?=ez!)r@wsu7n>&gulc1gt8y|JW9?e;@R~gTx2gZ0!sP$PA@kq!FZdgfzY_Qv z-OqsW-*z5}|1HhLe`NmSkbhzpf7tk^{0{X`6F^h`N9I2s`PT;iT1EfKD`o!{@!v|f ztBHS;sPTUS@~;E@zWods|M4c7-y!@|zpmrI$o&67{&lnX!^S`5w~L%#od13z@=pT( z#IK}I2lU^*vwZx=wvy{#*>7aKn&RJ5jDNv@GV-qn{J#AR$lrN^9RD`qFI4!Mg^R=afAie+kK`rtI_OYVQUYJo6@2|;XF30U@!wm=YW%#k-u{2YesBIK{GW>c zr+|N-C;oc*=D&3p$@y>1%){Tu{yRo;|EIb9V{cxpk?|j&!TB4x|L6LZT%8{Of70XMQT4yNVgF~M|F6Nn z&r`tsuOP=imZ9|zRsZZ1{`uBf-2dwRORfd~O`7~$yDH}Y8fN^Le!}DbZ1n#P_^+pV z8qj|kJ^mw~|HnrbCjWaB^S@?0&VP=}zuFi5OKt%F$zL?(zpDRnhW($5{=WtPK2HJt zmkySX|Jd|A@vo`=tNQPp#{Hk?@^7)mfRdZRe@l-Z|JH7K`1$)v8+&}A{kzA%)iwP5 z$MeyDH~4QkR_*-HL`wer!y^7GRw_*X|Eik*v$_8!m;dR@2bA0n{%e2LG5yvo`;_%KL5A< z;pm*7KlbwU(A{x<|F4R7IsZlI|9kM?N%NGyLcaB%HA`1g4V=)dJ+`S_3RnJ4}=<-e+bk^h&v{0ko( zSn>e)FaJZ2e@D^3J<+iL%h3Oi;6Fw4G@$?bFXZ}f6aP)|!sP$&iuqr01h0S1F8{oW z(vnBPf5V@8{9B~{@wYL5vyNf^m!tomz`xH^K>rPkWdCe0Gx@LTKYkSV|6lIEuC(My z@NfU6$G@ZMf07yh%)9^T73lwG@Nca`@-(3Ty8p@b-zNU6S0&rkRR8}_%>S-~x&JG< z|CZ8{cJSY+$-hPFU;e~*pJ7in?EfnC{|or{c?#&i_HKFopC!!XzpDSz-7{wx31l>e&!rxe=1d;Y8a4d=fG{r7B(F5_Z>AXkg8wGu z-vs!5`x%hG{aQKx9m0>|`ESL-esI=TL{ zS#tfW__Hwazqw-k3;tV>e^cQ1?Poy#%IoC#w+Vlt;y*I~&B(u57Ju0Ir~Fot^Nad- zEAnp+{5Fl#fd1>ZlkflN5PoMonOAD6f72A>U+~|K{L_Hnx1Ry|%Wjb4-`Ymb|3bxo zWd7Tbe~T>su<=j%S&{RL`gaHNPY3>v8RR%Mp#RFFmZNzmslPQ~Xa?jDNv@H}Y=<{J#AR$j@$)kAED(Unu{o{9^s@I^_Qy)_;8KGy(Y= z?;-iWkD2^eUH=jO??V2WS^mT3KlN`Ht$+9YujJ8V-1AKCMgBj)e_}NVB-_=*Umd#s5&!oi|DWLB z=P4k6&AoE|Tl>oVd^6Z+;*adV4f$t*f1js-{PA04|2FZD;QTjD{E_`1GB{HQ;L=9+ zSC;><^^f|upU89nCr$j3{ojZFx5@G!mY@2!{w@9=K>okMe;uvU0pq`$K~ir%dCIwfK|B6^*`eH|3T!h0sq$4WIqG)H{K%GKZp45rrXsN|1+Z2|3{FY4TR6X zsHcGZP4^N0{mj(=$o?Ni{%yg(&r?ADid$uVYdbUik^Mh}{IM+mVe23DZ~a^RKaBj_ zW%&=wPyMrhi~q-vzXbgE*kqkHVEi{cB+q}W{pI*?s33J!Q~ir6)_<}7}Np!mOEsAoA|HUhHO_8|CUkf|C7kS82I;j3drAcKdFBQ$o~0eu+hXH+5c0>zXSO9 zc?!s1cbm-5wl~8c+5h9n-!IF5*!oBPJ0$;6JpZj&{6B&GJ7)P0%TN6~B>xM=AKCxY z$lo9QSFBFzRKWOm+T{3mNd8x@LAI;Oe~DuK7xVvTkbfue-*E3rIj_IUcl}f4?J~bb z^1rsGF#KCZt^dy<{{Zms^Aym3;sKf8nQf;2MfU$Z^6w1(eVzjHcM$&$@n5L?kL>?h z_1D{{JHK?*jfywR)949mu~c`1g4V$e*}Vj(?l@FBE@d|1Tl`;4J@P>mT*+ko+$ce`NnJBmZt${=@Q9 z|JJ|7|EtKqIQVZGr&j;0hvfKoNd8;n$#yl>zkZ7KUwr=i8uITB{>!!_`x!9*D_RLZ z@gIMktgC6_-#Tjje-rta0RKKu0r}gg|AWlb|H%H|LjFC#zt2-Z{v`2l?P!KSvj5kS ze@K@9u=S7nxBe~u-$4F7v;2qUr~X-y`>$A!-~aAype<$@)L>AK!s&R}=p%#riM&zlZ!o!N1Q_K>q4S zi2p-m|9mspXyT9T|9#|7r1PJ83d+Ao_Rn@Q!ynoIJIG&_R)94pCJFf;NRyd zAb-QxvVVv8FI4_V_Wu#`FO%gzZ2hDD9Yg1TM)sdV{{6E2hvldK?SG5^PmzCF@LyU< z>Qun^PdzW^KRZm$|2Dc^P2>MS#riMS|35?i{lR}#o7(tS{*9dfjC}t~<4)v#)x=*D zwf-+e{$b$X=P987mKTWs!)5=4s(+FFcOm});NRydAb;W|ncpV<3&kJV|L4fRT$cZ^ z^^f|uN&Xj#KeGP?$Ui&Fe^`F%-zswdr33l(Utb{qaPVI?k<_Vx@t-2~&nEd_N4Kk~ z{*@}$e=-0668Y=W^?zqI{;sdc=fC9pf4b;)HSuq&SpS9puaUnT{QEow^xsMAU%i?7 zAKCvm$bTUC_jwA)-~F;&|5?88e<>FKi;#armjAHzkNRi-7XM!%|3O*)!}3%AHp%}& zjen8z|6Al=9{iWDtycfyF;f4Ikn_KtZdX(M4^piE;{JDcEh(;ld=&imbh-Rt{r5~+ zK{{{LxmxBgl>fs+*MIl=H*x&ajs6b?{^nXW|D7eWf1A|5CVE_@$^Ukt`Q7WE#rXFF z@~;5#?~Bub^*{9rssBfs@vj>H!v9ame+c;Zc?!ti(INBO`M&?CSp0v7{3~Yp51aqg zzfJ02q4Gbh|5W87wk+&S{MEznoO24cY$Ei-zbh}=Dbw$@W1&A?V!M`h>w?$D*IvZn za$%OfZalr6)OCks{?3B_VbJIOz1Jq7KmEF_?Xb-Ayw-;PLFwn;?e=@^9nhbC-O97v z*Y#R^U3dF6#~qs4j@Kr6e+m3edVd=K;;#e$&i?VP{}u87J^DX1EB?d!r}5AJE%E;| z@{ff0?^s8z{&)N+uYcL3{#C3?wyP=s2P=;M;{2~)kpD37pWKD)Cl8){*MHRgD35=P zeE(C+u4KEK__vQb{{4>pD}jHXr-1xruaWwHl$r4_tp9I6{+3OG`cU?=`#GQ2vd_MS z`WN%nt$4a0-h;$0ZoTx{&7i*q`n~#B`?kA12l{i>zZCQ@lYTEr{af|(^mby*t6No< zx^ZGde|kHhWzze{=@Q9|2Cf|8kT#{#zCNw_Q!@binxc@f~fZ z{x!yZul$c4KL3BC|0BRZ+f9wXlhl9f1ew2;Zda549YT+PWtms*dW?VnMF}4Nj{^T? z*QoK+H{CYm|I9dj<$wNna#Wn99}a(XL7RT8vYPui725Q};SV+jUH~4m_+x5CoTVR0 z{&1kpJU*z6eFDE*tGka=p-n$N=8yOqah850_#+8z`VsrEHueOx@p10Mf;Rmq)Q>Oz z7eoI?Lj3#UlA`9YgVdR-C@_ zKmXg_@S|AzIJfKQBQnR2UVAh2r{{$o^WE?N@!Hfz@O;>$H_x+0D7uRRU=v*SE@lN;wL=ugL|7q?zsta4H+HUxUh&vw_5 zyw-;P>^QI4#Eo+Y`Uk`Fy}X#p^J1}+-RFD#ja%}(fd1_K@;LqxI_rOW@h?9A9f1Ci zhWPJ1ZKSl0@BL}M`rrBoIsQ3O_Mh0D%qukc-%)Y?BjSHB@{fV|cQnPnV<`TQi+hHG zwaHJ1vh>5@kA={tAF2OIHvNe2^=WKAwCoG_ zF%{bM<68bmL7RTWzjPl7XwwfH{_ZqrQ~bde!QZDJ1^V&D{}Sl`7>Ivgobvt17yqSi z%JUza#J>-xkK@1kHD3RRApcm1|MDcs(}4Vx&pKAl|9ZMzP5cdU`pWuYmY(r*X=|DPR86sIy7@$FC)Mr78Z8kJDHF z=YM|7ClS{p6d=$6xvv`TS#~od0!nyPEiSQXK#5ujch{8RTCb{5Mcf z0r}~>ZapdA|G9&1R}=q6tI}8g=YJQf{>AtDTygyWyie+%i2r5Le*?t7FHQscZ+=T2 z|Jg}${QInE@~;~IR>d0bJbxJSuL1F2F<&kJDW5~?pG~)`iGSme@gHaI`7b>u^88P_ z>%V8V4=Q~Hv?thxSek?;S`^_*ON_6CLh{^Nq> z|KE!F4}aGe^BWpOyb%=RY+69Ygb<@cGX&nP*Sp_dh5{{&A51oitB*kmeiz zeX)F;nfiBk-1o}=*a1%;oPI*nsXYHjxcp~T3@&*a^1q4c$$v*N|Jla>()|Buf!g>F zf7ciJFFyYtj`9B=$p7*^)yBW}m^}VlWc*L1$ma^0#=o6I&wt(gZ=T7oe_0Xv$3y-% zUZ=)Slg=`f|Mx&bhxvi0XY$`ZgXjN9p8t)5OWue4Z;t87e=Cuv{`Ioc_9p+*{9kLK zTK>b|nazLKf5SZPe--Y(YjDZO;J>;=kAFwi|J1_z_u{|n4nF>ma{0#&TB2k@dj6}4 z-`ZO-{x>zl-}DaWAMNs2Z@EOtBH(BJH2GKM-`os;=N&x$S9AH>Z(gFL8~7{u=Rc8; zf5`XW^-}J9-S!q{_?>$={}`A5i@`%megghhUH(=1tIhDYJjnUSy8H`khm`yZ{H6W% z#6Kh7f8`V1ONYIs8UBuUIe&%A|7`P+l0Shzp^4vC&7b{~9j;>NhW0(jWNC2Iz@@Ta|y78UCt8oPQkWA2GCK5b)P& z;%E83|D+fHti}v~`*)mwyvx7knL|s40Dt*FP5u@6?QPBQH+OOV37r4ep(RTJf4wGt zM!x@~H{HJe?alC~MsWT$IsbuWCBuNfT@$~p$ZzjZXnyzlSF!%Fvdf=7kLd(h|M0C- za6$Rj|0+7=^$&-vfA~E2@%l&UdE9>-`6s~oM@rNBhiz#66CmE^`0fk8uAJk$+9_Uv<5n^)H)z{_B&XDgN(M^xyFuKmM&m{*%Ced@nWr zM1MK|?RcK!e@*$w3u8jYtS$zF}J>;(h z|8=$Ga|-_EhV{=H%<#7XP?#Ujf9rL;{!d2!Q^3ESP^*7ErLup^kpEp3{fqfe74lC6 z|4o|4Kg*E+2NeA$=5zm3klzOXor?Zzn0)^moA|drA$g@~{M#+6|Mii7ZSdcv$-iyL z|ASHeZ-D%#f`6YUUR?6kzw(&upRHo1{;B#G^WP1Te;x2|-Jn+gXbpBonc;sps{gf- z|FkUsVUK^Pe~08heSh3h*w-7nBeMUEk$+wAUwxw<|Lklt{vT2F-*zpp{~ICy9Pppo zTaCZ8gyjDzGJn%PWV@Q`|L%(QU*x}q{FA_c&+dBW|CS;DPet`V75PsG|2|JVBlFe& z7UJI~{(XsEEdDn|{`J!SHRZo!$p6z({cnQ&XJq*gTmPwltH}L3JM-he&5?gH_;0z1 z)Tw~+?~Ctq{PZNzj+Km5~;^HL({o)<}3;)xRe;)YvdE#5mSO2T}$^I?d48N-X zhM9c*w;K7Ufd5)e{v9}(KG!;;kfbU8Uyh3{2KvS4e;V>PX88|W|EYgg8--!=ox+{oll=_JPqNQ8fNEzXtg?g7|OK75|3n-)oBTFRp*w2Kmnc|0z07aU=Q0 zzq$c(d|PDwyQzcZm8S7;uh8-DW}f)`YkTD182p#rLiRHtKMh>l(DCoGjsg&rlNl_|Je!o&jVHD9{>Pu?^WR;N ze=7K|*X93QnV*+YY&7w|9o7G?$lnD1eV+Ip=Ntd4OJ)By@sHsAH%ddc z6#TdA^1qrH|D93&*CPJ~S^mS;f9l^Va{nU#_dx#5z<>NUwfaZn+cK2@?81nzVqJOdevk&rL0{&~?P~%Symg~Pw{FlB-wyUZB z@1t1%J6GWT_ecKe;NRBe-_ZQ;gQ)%wK>ka?zt0no=zR6xT3q(ePB&BkRsDDW!Trxh z{%Y`FRj2s*pU8av%Xwz_KaA>sKjgnG%YWGVPyIV2|LNPK>+=s)|5c3N|MEcOp8@_W z?;v%G?|8oWr+k(n{~sy(7wbQD$lnb9n+K@Hf9Vo({@Y~zzw9mYzG|xf`zqFd;s0Rd z-xB<{9i!*`SI3b5R8;?mAphmy-{&b{{C80QhU$NK|L*r+Rb0XA|Dnjg75J|xlkfZL z<#pKnXXl%#|FB#Y>c>0(N#y@Q$p7Cg|6%Jt^=}oqfBV1O|KZ3#6a3qn{M%#9_=m&Q zP(Pl3vHo)y@?Qb|9a^XP*7L=G{SdkSJH&syvoQ64ztHucod0kn@?Q!3zWofy-$nSX zGtBsp%wLcES7q^s&40?zikx2@{~m?>R|9_sjnjbsD`(5+|Ja1zey1?;zrSMq3;tt} z{~F-;?Poy#>N=U9%{3GMk@=5C{$v(^*!ZXX4)M?5Mr<_Ae^vR#_e%5Fv{v-3Bg#0&W@rR9n%I^^W{B6WWQ~gurZ}sB; z6y(1J_-j8RaT?Hn%UW{$Tf~29ifmUC|AC?7-@X5R&2N1DV=b5e$)2T4hQs|Y8%p)u z|CG(n6aN?q@^3p8`u>+LfBoW||1_6>)auKWi~#-)RsNM^|F$B(9iBf_B*poa7iB-W z{PCOI_0DOxZe3Cf{4LWo`L9#-zjLAeyX!w9|4+sIzZLS|m!|>qzq(TP?~weLgB<=9 z%9`)5MTbKEXI?q+EPtO*clozCcvi_?;6E{4kAGXyzrBlL|2F!+Ez5t{@sIkqi`GAn z|91X9&vp5yfA{w(dxQU)-PHVByUFp-4phs3yKHpM^#>8~5r6Tmf1iQ=ZwLQvbe!g| zmv8-}Y9ir3Q|7PxxG>}YL7~Tg;=j@5UkUv03;x;eYW~?d%SqmBMgMFm!~V}i|960Y zpQnKSJBfdr`1ggaruwhyzw~>a|7W@UUv>X|$^qcNeRp^LFYNcfbQAyVAUXbh{JnJ8 zrv1-D|958j4_p7Kf2(NyyYt_kqxk)QmK&VO+Z%T{zT{o-U-hbD{u7_}A&UN&Hk1G2 z^N+L9e=GPe|Af?O&XuqJC)bwizeD`D)9q@?|ARxY`Q$YW9>&X7?EA#O8vHzxXx&J1Y|Ji>3DM^9SWD|JGG``1{y@;&Sf)QkVa%i%%%|5&XAl^6#knA8y$HMd%-H z*&_Uht^d?ND{}ueS8@N%F8`UIolx=%`0rfOJ^wrG@t>E!UTYnmC;q)BlGYw!#=p4# z|7GYOZrQ*pKPPpX?_a+8f7c|r{##>Y{uJG=ru;utvHmBo=KlZd^3U1t#F8HHU-q`9 z@n6wD2?y=}^w$4`|0~e{{ovo{DWLz>^<@8!q5N0%FOL7ObosA8{lt>rz<-@4|5m*m z|3O9C%Nx%B%h7*ZmjAHzpZd3p*1x;{EAD@P74km-{8b;TUH{WCS&n~pwd}unA*rjH z>fd3Z>mT7yBL9QH@7vFS`Cnc|_>Y(QeevIS{FzrSFXiX|9D)2>r>}ooO3(E#mZ9rk z;BwtiKT!WO{AGhV|9s@11^kVg_-#Y{aJgcrACJFoRet`%b;!RB@TWBKJBIl0ROA=_ zuSfnG;ICR*PyDkcGx^`D$S?fgfc)D6f0rhH%Mkzn6#1){;`x6g@^1(H)-rnh+lKh> zQsnO(&iQXb{_TOkTNA%yi2rUy{_>HWzXkbs0RH5%di=8s%;f()iu@w}Z$|zdfxkx+ zzh#L3UPXQp|FzZLm+2L2XJ{Ei|2_bc*?_`ePLYk|LZ zIX(W_g=YM>De{Z>za9B^0sdA^{FWj92Nd~*|2vR>SKvP?CE2bf|MiOg1^>Os?*Koe`x(%G z#fCCJOPcW?ng7Qjne!iG!1;IkNi(%@rR9n%5N7rzo>r? zApg_AU-uP>(}4aPKbG%*Vv)~(9J*ai{*P3Qf5HC{@;?LozWofypZtXIUu&lRN9KPJ z`Jc_=4;%lKpA|X3sDBS5e>?Ekf2|h(>}1)$P59&AknL)U|DzP+U+_PQ{LcZuZ$AUZ zfA?N;{kKW}du3m=#lrsx@;{%&A2$9ezeD^BZts`Auh);}Ic{yl-eyqe@G2Mf#3E;3X9A64WR{+~epy@0>I zS&x6q5dULQ`JY7oMB4udJ?nptq4hr}D*sc+zjxZdCVtzH|Hl>i#pgdyBmX|Y->!+@ zF~t8wRQ_j>e_!B_FRv&5*~Mn+-;+`KpGE%tfWJc%zh#L3si^$z$iF}E+bihtZ&jG_ z|Fj~%82_I`{sVx&Qxm^!$p15n{9^on9{Fbjf8~mL{5yvDpH<`+_5TIruLJ%@P5kT< zGx6W9$S>mmMdUva_-kHPJO7!^|7}D0|C}Pfi2s+6{~+LRn4xF>ZyEah^La&n5&thE z|G~hY(iH!;q4pvg+f9zccd>qB~UWq1} zIl2siET)-$6oViT)?ke2N3{qL*2V+@2F|95>NQnKCQ#_QkEP2T^p zu1xNK9skqT)l9noam4iB|4QEfsPy#z5E}o|%o_h+X#PJnqvQWVU# z@Z|V=+W70ohne;Mx1T!x-TU8jJ^eqF#=mh#ZJthJ|9kcCg5><~RX&sE|I;%%{y|Uw zpNftD^xpr}$KUytkAL_6|3Xjy52NvKTYl#3|IRNo{?APR_$T+jmwNhNr2bcDQva>h zewq1Sng0GKkAFM&^#2)}|4pwY_c2+weck`9zMuU5$GPg4>Hm>G@%Y!h|GnJP|Iupy z`~A$B|K2Y&|DT=F@qe+W|CQMIPw)PxkH7URAOF^M@ci2=J^dd;0JNQC6*x@1&jhl zfnTu#xxMRCf3NT>Zn9~bQNSo*6fg=H1&jhl0i%FXz$h?{3Y0FVXS7qerK{5M;`8aa zpTQ3^{HKI8(CnzdjR)0kMD4Djbn;lb-?<&n51a7CDQ|yr$gK(&>k_^iu{(Ac6X9b0 z$WKkTpI~wJ6DU9AyEK;hVy&B0+#Y_{7Klr@;!At#_T>1k#?RTz_rR}3`(5w@jo*NN zh2Yoyb@!{YRkvu%5Pm-eN9#mvK=_h`x2(y2#9Bv_|JZTfUxmw8BV74uUWeZ=F4k*d ze#aP&EA~pl3&fY>eEZ{E&pL+VTCL0%YZJaI@!S2;QGdj4O}L6%S(odJb&ut^#Wipo zhV=+napib!pN03~6R!F@Hzjp`bWv&T=r|t`J}}0YQ>DT7R@Og@(;ny6*ICaTi93m)$b1E{oV%NdLAEF#coZwIxe;B%g2AQBR^4ija6-8Ti8+gpEsI0Za}y?U!b2JMaNa|HopE3BfN)i-^;l5nc`c$_%?9qR}1(K z;ql{SFpiJsF5#*@!fzPM{;wc>p{SKq82^0kT5|tF!5xcO(fN=~xcE`{VSnL%xrEQ3 z;^!*(QRflr)AT#|`GWm0+Vg*x@CC?^v{UYP_=GFn^iL4sI!gB=GH~n5bbV~XRloF) zOL%I(2v_<@zg+3pSLuF+6TWa-`w5Th+}z0egc*LUu5|x)2CnyKPRj>tkB-)V@wh{y z^GLBF@WRo&{>9d=Gdi(;8piYA2X+aM=0_XO!(n~G=b~|ybzVFU>zQyFS9SjEa|M-U$0 zFQmT#;c5L1f#nv4R)Q>;t4=%e_R-B|xC2v_=u|L*hu4cNcp#y1CLFu&UZm-dTpdOVY71-y61MeDzMC+iq~#?}We>t5`` zgsbtE<8$F(c68kH-W!*gui;grqW$Cw!q*|btOK!~gbyOTZ8FyvYjuvZ)OEXq_K39! zUxIL%zhbu_T=|jn3b8)nYJQZl4~Y#UKRxsNB;233KHz@IylMQH_cfbv^OJ7NO!UO z5ndoavad}%hxHD@mv%~fRF}-hC}0#Y3K#{90+|Zb&L183dzJrKmyY)$YQWqX{xn*z z>^EAx8u;nb@Lm-)VDp8huif8Ir++P+$r=TI4GQ>gFA|;q%YCGWN8&yl@b>NadfmB( z&*$GKT%E7h-OA_3Vr$-AB=!EyaKhE~tvdfypKw{e&h!aa=hgZrBz*4Z>^WJo)_W>$ zjpZV)*qY8oto|u{m+-XvVP1qMeXHD+gvYOATMxr~e?CZW=U~Fq?pIwwc)Y*4t+>Bo zh9CRG^!~bpr?vki!c{xve7=0b@1lJxBs@(|>%SRzZwU-C2P)vNXeZYHfw*5C0GI2- z`n`A`=pnDit-UIy>;c4sNSuMSt;|Nb%|8Ei=@9)I5dHvg~r~7dUPuuT&!qeLSAmM52 z-(Dl#zmtLYR=^;0q5{Ev$4Bemn#A}0#D>7-zMt6I`;U*-zub2c>k_Wkv+NggKglOt z&11Q5CN>~^Ug8J$a9pvU!hh*3zE36AeUSageLt}t;VQ1&kCg8Vec*E6Pi#QAy1yvx zl>2{SXIX=3-DE$;` z6CT&u+~20bG@qZWK=5?N`UfuSUTp0%8S8=Y_`H<$;}f2`{s~WA|L|Wuo7cZs_qmMq zPk8G32QKSgY(RMG`j7mltpDdT`b&7~`X@Yf{S%(L{^6(B`hOu~{SzM7*{uJcJoQaQ zrN9OBds6y7z1Q!51=oK6yA9!ksG9sUyME`+cr|aq{=M-N%2z)7ldfuG%BN`xR?ll8z51ygsEpKH=)R zL-vv8!F=5jz>oayS1g4zAESWfy}oU<{ynTiu|9B_Pe-4_zi)3RT&=?#ezz|+{P(u0 zzyG)2ApbNg<-A|)7KE$cpU8Q83+C$sgsbanIbMsk|HFP{y^3`r+_I$IVqL=1)|*GT zT5r-0u>s+A6jxvWb)o7nsjwxUH-NR@WIwWA#X7)6H(CF#hRZ%;rl3*4DDd+s;5<-c z<$gZ*)9rcUM2Fwhq&A(IW(6EDi}&+3Z1Rlb<^m>qU6a{d50I z{=LAJgvYPLoeB7RBBQH(|6KdtaRtKF^8)hwmVy7~I0qB1?mILc%Js$89A1sS|1TWP z@x;1>t9FW?)*twL#*+w7YfnhHx-THt?ehIa%@N!lxlbT=JHl0a+{3s%VuK^AmU>^1 z_>t>>>!@nx@h9?>NGjCjZh-dH&}u!lSsGA}*|ZQZ@0sR(+XuzLM}XzJFFVdVZGC`x=Ahvzb2$wywna zCfJFvU9k2v`qkq$pk1x7E^G&E8Ft_tI=;GICZDc={cz3nt^X<0$=AX<(^=n@_C3OJ zL&?Lhhwt}%*Z?+^@BJR+dN!;B>%w}lK5PixdVX6BqSzGfc<95mH@@6YRgPSs)d znX#s&GgAQv&g6Gs#_~Qer|B>==alg^`zYX`sdL)-uIX>`I%oEov8JUnQvnCg=G60E z({J7fX6BqSzGfc<95hwFw>Fl)ubc?oMUo^#Nj{~=tSmr#G_ zr~COI!qxL0@|=X&nk_S){~(E8Itk*58YIhxD)qRp8FA7TS)J(OL$s; zeZu2^Ur3(+2?ISnSF8)X?MTMOdJ3l=iS7={uOVEGx4);&&kMqye5}H2EE#99 z)^Y!-QF^Jr52e=mI`a2t36GEK2Eg42r}u(A$j@Vm^?-+GF)sER!sGLx^FzISC8iBwB9CMy;n=x*|<5cTlWO^lYfZgiuDOs@ADOXwX+Vg)t;c-7j(l19TfFD`+Vy&_Nsi~#b=>2sFkNau+J^Dqs z8W(B5tbc;c=eMZ99vScd6I`2@TN19;x%}O4u>s*~-pG6Z#9G6W@5Af<``?5sKl1)S zv0fAN<-LDmuOwWpXPL+H9zknQjw|o|6KfN$-Xkb~_gn1NgsZsn{y?$rpE$1m{x6U4 z_&y@<5%dXH{gr*8`|p1fuHGXk>qpjq&0a%mS0Ge$5!+0-+8=wpM{sX$kAD0Q2v2KI zNVsZ`tb4K6K8(wI|HRtBrJeHkzsZI9%s~n`=&SiYjE{eFst$9|ls8>93K#{90!9H+ zpyrVwwdy|K#GUNuI#R4l_-bS6eJtAf{}wM1pUzk1?|z7V2)Mg8zb99$^YW0|`1^3= z{QqRam7m;W%ol5Q45?j%+9l`xVu!xR{JK21Q|xx{Gv0at|2;CXVds$Oy~A?eFLuEX zhSdI%{4YdF-FL{n&d2?mKV(1Qm+VKZ`{j^Ybw5nb^Ebr(h^q+yV+?N^%zm7&IIf&m z%lZF)gsbZg(M4=XxH@mwb+)=#H~sv7OTy!E+ZN%tA>r!2iJbR~o$G6kEBcD{2v>2X zopS!~&bw9AU%}=2|4PDDTzOx!x(TN4JJ|DW6~&eJ_=t4~m%lHrbZ*D}4wrBhS9oGQ z!sGKKe1q?+JV)u{Rvk(hhs2~u+IF<*YE%BPq^Yw!n_r0FOc3&f2pl% z=OZ0NAGv?@F5zlE>v4mnIj*{HRUdi(Pbc9juDm~6tks|6%5|>zw}H$3MzIdzaoyza zL0q{?Qa2y-#9o!#BkdQyL-_pE9`P&oK*Ci!<@#J~Ffi#y#_Mgu5CQ^EWR2v^tF`X|ir?{3KRS>7il_Bz7Vys9HdYJS?-2mFn= zopK+z+Y+w!rCy(*Th*>keq_9w@%M~|5U%D!!w5TCCt|IwSvTE}O}O+|m35%M4&h5u zzA|q2=vm)7?ZDRGnQilE-cKj)!}*RTwoSXT4L4># zt+?-B+z$A@Tu*OX{U9#)_hu{Q6L;Z!v&*(xVB3gxxM*M37{-gO?7!|bww*=P8_m`_ zf^GfLY&(u&TR5Bfl@`vsN3!)$-h342+fh&2S4MwZ@P4^2w97#|1GKvh`O=@*PaX92 z?_`}OKE!{=(8m5y!ueML{kIS2_Bo^2hC8yKhJ!iZf$<42E*9F=j^kZD^e_LJ>$Nm< zy{YMb^#Unr$=uHDVnU zu)a#;Ic^K)frW8wg3V!`RS<6==0j@@$89={{a1!@z5(;Fb+Z9{p1&@5>#_AVVq4mn zZ6|EqPVA@Q32sky6E1JxnenbaaK7&KWh1}VW}FW;XIpgG+Jo6vV68p5zPAPA6F*-e zs^5Wp^IlvYz;+H{p0gF(;@(`|IF$1~ti2D~g?!^YtiOK<$%x#B+?x_X=X)0^Wk_R0fY~t8q#jDr@WZn{w-cgZ@*9YlH^DKgoLZO z>iY%tnM>YF|MG~$?^uIzxL-iH@+0kZ_vCgugs0t~yy8FHo=LdxAl3>wZWJ{3zx4@M z{cUUH>jJUCTj~6_2v>YvXXkBhr}V21{c?fFLPr05>wnx%8CS7xwP(B(abftmjc_%- z?YMpwYk!vB&MgQ}Yo|}R(o_Eggs16w)sGxE!2KJs?=7-l)E@a>N^F?hFB)In|H6yz zXQ}U@`k|n7suf-T+V+0Y@2_?KeuT^SKB}zwcg(j|NcTU0aMfSYQLIOJT7T_)dfX9& z%l9uTZny}?4GCBCR{zwl%W?Jj;1Zr1*GZ4NAK~%-7SZ33@H9Wx;Qdm^>&l&YT%`YE ztwK8AAzaq*_T(58PMuA_W0_wQ=-BcRZFv#2on2J26$S7bGFbWt2i~_Tz z0$KO}gCZaIEBCOi8=X84XwdR{=bQT|*ZF$BJcIRhf76>UewXa;^wyu<`2)wy+5Mm0 z$8Sd4@6X}$e@68)^^F3vg92H{|4C;3&kn<9+GrFo3K#{90!D$Kq(Ij3e_$#7`p?P0 ze^PK$$tYkHFbWt2i~>f1S)zcmX-o9`KY4D|zL$SbHj41H-~YMW6Q6z`qkbWyes33^ z$b64*_4~hW{HjsW^QsRL9{o;Bo=<}vvIFCjF5}>DHs?K4{PIa5FXcGe!uux#P9vPJ#Q@YTk!m_ zSfB8;{sx4{`zz1?hrkn!r;L9_vi+jZTbFSA<@cLnM_kHy^LQS2u_56~WqCeZtbJLs zzuoWuBs{JCF5&U^i#{IVYF;fsNzIe%@H@hHZi3F*JoIno_9$QKvkRU}e~WN6pQYVm z-CJ7d-3au1(=mHQ^Ioh^_&kKG-)pLmJpcb7;p%yBHE-3Yt&!)+;9FbhcYtcPB|ldZ zo)*_G^E{OKDg7NmxSEHuF53IE|B&!S3D@}p{*mtACtSV%LfUyUbPEYr^HB6T82VVZ z@wiCbx_{z#tAqea=qolLd|=!G{v8sY_IpkL-j?Y1d@`TJ z?)N13SAM@K_UhLem;Fer`){5PdT5{U0<~U#k6V8+?;CFeSHFK%^KFvHI=FA7x6}TJ z+o}71=)3fGuC&lG(R`5hi46(wQM1RJz3?%qzt?mKSL;Y0FPHGN@$v|l@lySg`Q}Id zd*aEz9wc0iqpW|ic0cwnF)qgZaS2cRU8zTS+IsilN7mOr;3ptFb)FEOHczJfE?rM| zxpclyc-rqo1Hx6G^z{`27hQ}s3K#{90!9I&fKk9GFsl^s5O_}ed$*>)d_8D%FgoOB z)#hX38U>63vs3{O(dX3n-kW~&@z3ZmXX`LaHz5<;C}0$rB?@?mTD+h4KVyv!>Uz-3 zgE?y+%#zK=1T_j61!k!N>USSgd;d=bzxOZUeE==6&1duT0bL6(#qa$_FPhsJFTgfz zjl9?)$>$1+XL7y?R>bI-fO^eIzLYoh?-PxJ4u&-Geir@I}9 z+xZjgJE%ACC)S_t_L>St0i%FXz$h?VDexn;mR{*;S>MdV$MM>E*)9OP7;NMG5$+we za%6Kyv-M$v7S0!rVH?60kLA2|9NQACeLV2lN-fh^qkvJsC}0#Y3j9VC7(O!f{r@)b z!qNOZlUPUL)OG#+|1NO-c{q>o_;VZb9($kg=-ChL?*)W}&reTJ={Vpkh6GJ2j# zp5OBEzI1m#_9M@)$ov1VAbcV6(|Y)!(eqehYeupkd0wXl?-h3lSM3p8-v93rzJO|v z_IHp2!lUO@^!7(M>7%vZ+MjjPXN^sGnm!KUY0r^(ge!fdo$~(w#|T%?dntX?r!blC zUt0&TA9?Oi>|nx`KKdshJpTM*r@ZeSessRw%=(DFV(rnakN*CDC&G0vmgNGM=d;9m zgs17_6Rz~}#_;%x4GCBJ=%3Zb^ys6WTgqR>`nZR)ADw>%;R~nuv5!dVQ-wYb;i^6I z+@DyFa5aDQPe8buKl1+n!{oWT2-n$^Ka%H<=y@XeHsNXdIE1VAh>l`C!qfD5jPUsU zaiEWNH2YEOOMT?|zrlp3>2n3)%8$&?5>?Dmy%2sPC-MKar0XB2n134ui~>K80%~2S z{r$h@XVdR{S1w4$f1cJEuSNl*fKk9GU=%P4{2U5|w^XC+|Binj7F{QMm+lwYd2X#n z@Bi`fchbd%gsbZocTeVvwaNQC*F_XLTxZs&GN+}0mB&H%zw+e5f&kG!`b#QTe` zAY8Razn=eyaMhl6v`4IWXEpkJgyQF~c%M%|c>KCLw;ZmE2v>3S`wQ0n)#yDf`u&t` z2v_fc$)C?Ui1h>RZ^yYjeqtXaJgvX>1Iczue_g`W_)7cb{XeG@uKFu~|4{5z4|01- z_&fAs?T5Hu9VhWT5$h7J{MY}T@9&5`iE!0UiQCx5{R`noaC!faH6=s0XR6WrYQ(Qt zhj0~F?jOnfe-0o#tzRcs()(pSo17=IZXCjuf4S}#>k>XM^-Ik|^^y1gcoCoUe1P>4 zdnMs%<7GX^al7u~c`SAX!qxl~edK*CqX<|1l64}s=7p-YRtn!GTzL_{Vtv9@zx3<> z2MJFbFZ)Gqr{b&oEb=}v2ROlrj|*J2Uw!2LKb$lFHwqX9eoh6{_y2V&z@!EFd;h2F z*uDU}GJo%Htq!|3?0T>p!v36%G`@`jMggOMQNSo*6qur<%Am81Xvlwr~@BT}uFXi={ak=E%!JCBN{nu%KXSnW%Bwy-@?ZWd1lGkkq+O6Z$ zn)mvM- zo_DqS&4}05M_lpKK8-x#>$W_D^}A-UemH~m2hQN}CpUxjn`W@S(?|W*KFZs0+%Nyc z`SsCuLuVRp6!_T`2)zn!23sG$ zi|s-_E6~6h{QXmw-){VHZck+l+6CKzzfa&G-!&TThxK3!ur_QJ^(Ml0$1(pf3K#{9 z0!9I&z;952tmA*~M?P+5b-5Gg0a@kwbEaNDtDc2=6XiL83}VYq^$&k;AN3piD9>ot zYy;Q#(Z5n3`p-5UH4QZi7zK<1MuAiXvX1{veH{N&of*(5U=%P47zK<1MuFKvfvn?y zD~|t@%z40UF^;B@MggOMQNSo*6qp_b)bT&<`Tu&n|E7ZDe>1SZQm+r^)XN8ka%cl&sMo>9*zU=%P47zK<1MuFK^fvn?y zQ>|R*&%S*#EjJ1n1&jhl0i%FXAYFm1|`oG`kb|ERquuqK8S3? zzkVO_#XcC}HCE|!#>H-No8s4419xTrVgumqH`n8N)E;YaNCz#Dew z_K02R5$3n-#QhTMKg#1(+KJ2ec5pl6GEQPW!sFvohjH03V_ce_h5v_n z+)J?6KF7E|?pHj|xQw4z>jfT184s}o2v<7G_=)uhSK}z-@^|QYHTa$AuUO|r9!GC2 z)<>*Mc-lC6gsX8>Nsapi_zlrfI`zsY|5M|m8@Zuu7D?%s@x zeH*xs_K0=gPOg`WL^s0KJnRBr?0|O|x7XtKi+z~zw0*{Vm-Uo&)G>y~^AW<8|JGA^ zpAj3p$McGYAn|#N@U(g5ywCHhGH&;1e-PVDxZ=ycAlB>T{wADL#wR>&UIm1!In}V! zp^<;FA>lG!%2%0^IzBXHjMo95aDOKa;r@=eF{xHf5Z;>jPZ%U z#a;=#xrzOY9q{?E+8S$7t8xbPfxU)s<=@(q{fiy<1>-U=#l8hx##^lWCG+e4$>S*Y z8sL=?jEi-@8df_G=_K=^c-$e8uBQ>M^w;;FQ@YR|95*{*?XQ#im$2_`oT2}zHBG7W z)2VHW*1NPv=I2R-D}6*?vGdHucyUkGS?v43o1mxInt7Nn`?%PV!0Z0R`imVnFY_yZ zV*g^@`I@5RCP|d|oJ4rqx(EqZ`|XloKXou4XXmbCzU;GNeZtjoQ~w0u%kffdNVr-T zy*~4&`>_d^w)CoF0Hc6Wz$jo8Fbe$I6j-#`T7s@80W)T4IT2Ya_x{9fb#b@$VV@rPz=3cLMypN%%s<7rbFC`x(46`w_fr z5k3$02#=2UT7R7tnyHPXk9NN65w3L8KYoPw^jGu=GVqY_G<~cAJ^H8^7olGc;Yyzt zTtA2%Pq^q4wF!Uk#a@~Hi2m2W&v3$(KKkbY!j&JZCpEvOc;W zkML+-9nRMwd00QfQ}hAujbXmnknmJ}*6Yzn&4=rxJ%lTL^v`(0;r_0J}O3?=(8dF>4(6FNqYuo=tH>DNAx@qd_Tfd^Z_n9iVX=*)n|(y zeN>a~koFKR>r3G$10PR#T%U=j^7^v3Vm~q;?gxK3;c4?HAYA#85y(NG5Pqb;r%QWw z&d`VO)b$nNbe*its{pv_Q~VPWo~q9-+^;xS{o5ftb^Z_@*T;Vb`s|+WXE@;tcdO77 zB_KSmPrc}q;l~-Cp%3Ay`b2n7Jo#6Ufro^r>N6s}Uk>4^`Vb!1r$gq?{^@>(6P~8e z1B5F-YQCwD4SlS?r2BD3XXrzCsy-3UzT^K7GVqY_RDH%|w1@CieF%^1)3_G@9^XDP z-Oq5sQ}rP{uFpWx=csf)&bSPH2v5}~!sE*Dzk>`sBs^80lQP;vc&a{x$Mvbo{5dt< z&v3$1^&vd2kM}zqzfMc{V`tz_2Hsm4gBS&j0!9I&fKg!9D`2Au)hqb8r_RHFq>r_b z`WA!EZz-vBtKywFF4DiFahFK?(+5j z5S52sPkCLue1lD+_DlVnr~!%kLpF`-cb?x#zxT?X>>q#cin?#rQxgAP|GlH~pxC2-|5&+m;@**e5A|2p z>N`K|6V=bh^igdP|IU5;M&)sRlm^}9_q&mQslObRCF-v;JgOg@)6>4?f2WzoM^xLPB`9w`;LPn|D_9h{I3x6Z#{NsqW&MX`r)_5s9f|PNab<;!@W+3{I|r` zk7}dzKb(AGRNfwouQZl&zc?=PFZGwEvUq*_8ZMXkA5(cezSVSkRA2TVwRYqCqt$#m zA(mDBxMzP^jq(!Ts;7;SKCLnRSC5w;cxL2Z>Z`F$)PL+uRh>4d9(~uOtoZjnzCKZZ z0F}k-d&}RTYFi!W_S9dS^4;~v-jJxTv`f@Ko9kPxJ@xbP`neku^;gmB7j7hk_TSk4 zv>xTV<9jzpNmvnqu&m7$G3(( znW(>%RzLjk>8M=VujWp?{ow+Y$bUIDKR1r~4{vxeI(|v{pQtPYQn#2 zTf+aFUq$6IKh)fbk54%6d*#Ne{HL!$h(4WjyfY<_PQufN6~QMo(5N1vhb^1b(r+AsB&qF{;oXY3i( zFT~bwW4!*EdnM}k*Xp~2?}*B!{c8N;?RSUY#s2@@vwv(y92r0NlYd6#@%>}_c=;Ch zM*a(^ua3Wo`d8i?)sL?qb;K0^;iDai`nFa--1?QMetC3{e(L^Bcm2-S6ZO^j#N&ru zuSfO0Sp8jM^_@$?M13{4;`N;~-sJix_r%{VUVotvqVh^?e0PtRpYdT-9zXxuBUT>X z_unYK)K|yuczt)*AEI&(@sFYMczo*sE*Jgj_fd)VTN4&n)7P@k=xM*&14KXT^kt*+ zFt$JK6)&&*9sRzkr@lx3PShXxyQqGBY<}(&uYY~A{z-cMySaXIZ2hP+j_&qtvRoqm z$$I^5my6tg%Y{;~T0 zkj)bHFV*V%FKiywFUF2f2gK{&F*qtO#m?`V=N4$P; z&CsY^;{Tq?ZZK##v_ zW8^=$ey;BQxfu7~*_dd*I{qixU$;$E-`lsgyZ)GX{a3b0)K~jQyuQ89PTYR1pGT-X zK7Z_g?-cp3#?Bv(jQO_@*@fF5D?ch$Zq=yY57O}sob0KDPdjifAoj{;@5I{{Kkj@%~#6ak=b&e_asIT_tczt)-E2DCWzY%$h$9Mm5AN!xsv;UqJ^Y2dhqkvJsC}0#Y3K#{90!9I& zfKk9GU=%P47zK<1MggOMQNSo*6fg=H1&jhl0i%FXz$jo8FbWt2i~>dhqkvJsC}0#Y z3K#{90!9I&fKk9GU=%P47zK<1MggOMQNSo*6fg=H1&jhl0i%FXz$jo8FbWt2i~>dh zqkvJsC}0#Y3K#{90!9I&fKk9GU=%P47zK<1MggOMQNSo*6fg=H1&jhl0i%FXz$jo8 zFbWt2i~>dhqkvJsC}0#Y3K#{90!9I&fKk9GU=%P47zK<1MggV3B1>7h6eT8p-ai#j zp&IBXC{Ta+l99dxe`Kq>D1D!f>%3{rx1B$8{Y`6J!<#)7D46*&dk&mw_0OU}e)7!S zKi%;&*Wb+QbjPo>UDMmY=GkQba%$7hzoxgpzczm5%=G!)Fq@3a^y)dO-*0mqr&otx z8^1J@_w8R>|7O?r&j%YnpvzW@-6r_EY%5%>SQre0*~}{yF8H?R+;h z&zkktHhSuDD`uX~c5^AM!G6Yl+%&Gii~_m>`A4U|Pw4#V&3FAm-{-XK#r-J$TJCF1 zq>2m0#b;*AI0+^L-Zov6|WH`@!}ZJm2p8?zb^Ne(Jn3^^5}3qCo3R zy00@4-;YmA%s8hylfO5Q`<@m5?$oXi2KI4WEzTtU`|4{m_S3o}%)U4^tvc_SHht{J zXYhFX#0=J-S|@(NvaXt6$NkSHbG-irN8N<_xfN)!ejV%T=kDjU`mdZfZTs@H`kPt2 zi8J~9rDG=hn_2xdetsJYgtOUwfWB1sr|~?jYX^g59ka&&x zyq4+w{gpeDz6Wup^ZU5cuWY{7|H|5vHNFOC1^iije4Sb2P?^o{dj!9+^UrA=$CCEk zp8FH;mrrXv!<#)72({~!+-$Z_<+XV|X&UdR&#KYtI4k{pZC15sdgC_Er1P)ojjQvW zX}k{C>&>iutM{1d_{goOz^Gef3Q?? zULza(gm{PGS7zPHehH7fbJ z9h3O>g&L2Ny>lUn?@c(R(ADrW2&ZJ9qv4kjPAT-0xV82!H7a@Qk&S)adv~i*$$ntB z1nxh%Ta8NYvq{|jh%idlCrRA@j`)Ww#KF8y>)C7-|@H_mr}6XaY?-2S>*q$8f$S%v5))o+2o(nb7v><G)?7Klkn$kCM}NcM`vna7y9CBvsIe#o>yeFpoa!evDg|GBlEh12)Hsyf^S?;q z#qVnzO70QgC-C6KEoxPA-q@lx=H7Ci-nCXG@8w++xOdmET9vE^D8)X0`>@^f^REJa zHQ6{{;TKc7hElxbCd%JP>1GYTf%4Y_kNZ*hL`t_%iu<`0c$sXRukh63;Z zM);W;e|ySrM`;HQ-x2suWaDx7p#1KXhEa-_>_+)rfyem@--S{Wr8s|2;C~_;=PP_? zN_$a?myDqNa7z1WxJ&tcfyezQ{Lhp|Qi}W8ANXI$#`y~0htdI*;w1&jD}B=NZ3%DI z_^VQW6-om&d^O;!la0q+m-2Z^>rslAtV8*=fyem@UyIWEl;ZpifDa-Y=PP_oN*hv& zmuyD)O)33R!~a0}O@PP!D12i|n^TJWaexmd8|N#$fzlR~;w5WPUg?vDuT1!s8o!qE zHI(Mk@VSA{LpC0FA<8dEX<V@=BjH+#-B=jsNd&ejNKc zr8g+W{rm@bNH!k#eagQ_sgqK?icf<9vm`Md>3-@siId z|0$)IKzUdk(d((td_S^rzQX@RX(Xk1$qtlP`lR7o6TZL3Uy1T7Qd(KVR{_2%*?8QwDZdt_ zbtuJ4)};Izz~g*{uTCjXDb8OP_ZkMk8i52Xbu#rX>XUzlv1ukg7k^`jIoS(5TgP+CgE7pMGUz~g=tz9^-o zDaHNN1Mg2Z&R2Mj(lV6dC38_;>5zthPx!JLKXg8{JWAFUlwu!eOUhGnha~ZUc#5y^ z`27KIE5`kyN&X3+(6uS0v6N!&ErlOP=@d%wl4B`<4DdK#;VqO-r4;8MMtPMErxfQO zO8G-F@KJ;xMJZmx{quIUM+1-h@fxSp21BRRTH8#ijrZ5Ra7wK^VM=XCHjW1yK3r=J zdbrlv=-~t&9!2<(57)X!YxrG+-%0pClejnkBefQ#P}$hWUVw3L!AEN2?e_*fN^u{p z4U~<4He}r0=+Oi}eEq3fmy-3yQ;Bx^tJA$DO4b^c1a7Tasr3l+$j03}gektl<2tx& zRcb@Re6n%eUz_+Ut&{WdhqkvJsC}0#Y3K#{90!9I& zfKk9GU=%P47zK<1MggOMQNSo*6fg=H1&jhl0i%FXz$jo8FbWt2i~_$l1xjm9+xx@w zms*Lx`;ohX^TpSacty+W{jJ`SYs{lEeqW{+7#~)7h3*NBh=cTfTtt5c-AMyl}or z`ghMx=A|8C{Y$vqrq?*cb(eD8Rxp2pPm}y2`fqQI_M)O!VqOvbC?KBrEn(hBUbp3w zxPJBgWIW-8E$Mi55VynM5W1b16phn&wbBv z{m0o>F^=M=cv-Stf{P8^WO+%Ohr+XuXI^1hj$i3W)+@h?Jm#0wtE|QR>Iqz)m;K=(xzw|cOO|)z_($*rm;000mJdtk2ODtwqNaZ^knwK62XKAwm2^MCt5&$Yh;>~0 zFXw&qvp6BWz9-{``CaNt=LHus?&|H!@GI@g_tW|#1)6m*Uo?2Sv(Dwo_6O*{ILd4L zkl?y47TJ&2!0q?Z@BB?k|5C4rbyeZbqa7i$YDL_zUH`9?CFq2-fAL$E zdA9=di~ZR;9mzPt*KKY+=I38yzK`(|UUf3#!7|DA_|RW?Wo;kIp*>QbWvf{4;aMD~ z1YHYgmwPee9{g9e_7%0bc{%UEx(_uSLYzP3vA^W{I4_WP+yCQsNZ!Zs%fa#5$MILn zbz8!?7O=1Qnr1@Kw_NU{|APNiTgG}Uq5oCv;~{X} zudD6HPCK{9zLTxa&uPa$DbH#9g*T1!N$PjojQz9p5x1wPjYAH{X{m2x{!}mz1rNq^ z{qPF5m6zGNn4f`+!_quXHje9gZ9a;>g0`Ll?620P>{obM)?19@_*f4P+Ed6l4%s;W zuyFpK<<~u$;}uXI$bHGRC3$Ap0w#-1d_GrGAL>P|1reB7Rw$*JaGBP}{$xUjCExI3CuIpRrFB z7D@KY9+1pCzfa~RUIoXe{E_K#OY|DF9FfZt+2*TBUWoID5{^Gb%wI=aKi-nb_<5YS zNjs+1+Sqr5?_+*RKJO;mXJOt-x!5YM(tKj^>%UD<9r-bv%0?xmxeVp&+aD1z1`?C0}XxAr#=ldt; zyWkeqad-X{%rBWABa%9G^R$1sn%*{aw6)`-`|{NNh3h8US<;S!T39Q{IG?THc%R3< zC-s6-di((UoR9spbOG}mnNQ-N4;$k6TEKNp3G2so)8lr#dx6W#INx-%^A+J$FrTXQ z+DEkyTH3x^!Tc#_)Gr;w^{U$bTE+RF#3`X4-FbbUpuoL{{S~zP12)Fl{}k;6Kc`*q ziT^BX%f5p4IIteZwSs*-hxJ>e*JmnS3Ru5Im-8iU9y&Na1vvke_>OkG4-e=1dHAm) zeq|c>xj;KUNt_Dyxd7Kwwssy+k^5;%+%O0s_y98cZHxZKl@`yu9I5%V>`_)2qqjFX4<2wu35{Z%ku!!FKO5hqv~ z?Z`M^5Cy`jpR2mW!K$cAiy{;|K@= zj>Cl?xqcD*t<=|TY3bxR=;cM|YH9md8P_Ly948C1Uuq5t-*Y?c=hFKl^a}JWVO%TP zdKI3BVSkc1 zF4k>XyN)Sn^U}jStBhtpRUEg)&$Qa=Ke)bsYu2;qJGsO9IQ9Iv}IJyl`FVL>TT^u(H zxK7OJ#}VAO$>I1Ver?R_@~O}f-+P2uFBbN%oOYeyjc2~^v9gt;V;DXcd&eN|8@~y>Xowg8ExH%&`Ij$>)EfX zeP1BuA=Y!Coo5uFV;<{7_^uC~1<-8ns${v1{UML@fFkxGty)hO>nx9Pkb<&yo)Ki6 z$CX@;U&20+L;oC%i;eYAI6m3V0?tb$p3}IYI(CP_K zw?#QG!tp78G3(%Byee)|7Z2w-;-`T5BYF1(<~ykGVjnHycxk=L<(@Vlr2e$pV8!Hq zBlSYWakPC~%EcD3e-&_iu71w#%E|eN5Mcw%H&;9F@UX8{pXK`g7`9T~?xP*T%d#b{ zpTX_yzl7sR3Fo~z>Q}+M7G6m^f68Os=CB{RxPBMDSYKQJxzCbusu{;8sqbj(GlzaxwBuw| zI}S;G3+EYSv@ehQZ{6kEKZ=OwFOxpcHM&*A@u?RMU2N>jdU;OTf#aStjrYeroNwv= zvhszDaj|jy_qF465&LGKt*0#iI-Wm-$G4afw~Xs=y`DXd`=(y6JelK#+IkOgzEH(+ z(D{UU141LwX$~JpoO)H z@MojG8^DhcvEO?*KM`2BHqK)N5AI|?<>Qk60?ezbc3v*^rq_D<{c3IB>C2xZ_j_=@ z<$ufVEkWP>63Ow%Lx%#^oA*8Q^K!m~fHsaldC>vaaaC>p6>+{J?JP}Zf9~^1-O8H& zIn0X?wvusO=WF#Oj)&ulMf6I*WK{#8-0 zqFrB<<-83QN*V1Ef1Y-pDtHdZG0BT9pg&c)zQH`o!;g=4*`t%=kh?FL52fAO@ulo0 zc@kHwb32!paQ{VcSLPp%Uj^-YQh1?uo>)1H{Z;hy7mQC4>$`;c;N3Iz_Eoj>Z;9)E zmtL<3{k#jg+{U_)dSVMWzPl5d=OSOlI;~--TaR@PKfnp)VH`!kIh-6;syZ9d12fz3!^Qzi-xYsjYlzwXCE&d7^ zSL>K$yb$xTa(EJ#dI9z~AMFetWnQjda=$BR$8D*vTMxRGaUNNEp8b`+W*Y=(2XLuh z#5$9_h2vH}V;|3d$$rW!B-`0tKjR-Z?z`u(|2jpqCxb6=cqH?3+Ih8<>$ZS>st6q` zUvT{@bOTY7=(OSyydurl^HOFJG^^!)}E%i4Li_!Dd6`_%x)S;57I zSdWqy>q2KwYey*eV-8NXzkvPE_LF$t<9r_XWBgZ<$9xT5N%AGW*ox*)@Br)G&sf(5 z?f7A1zB~Wpcs}M+ad94(YQ}wr9QIL(TgCn+c}qLb$#t;*k{nlHbGM`4av$ed&U@p~ z9@uWb+COqQo@%gF(C!OMx%V0Sm3)>hXy^YyhMu8zzaz_^;6-ge72LUd>g}p(`(_o# zA*t`-{KdufY8m@i0p|nGVmzKXIX+;2E@50;tp5`B7YF-m8S_Ho6wjM_JB8PmEo7|E zvOYf#<#^SM>!B*X|E^|S7kDn$FJ#;=&taaIu%GGe&T02)ia3tsuwJ|QH*%b^oL_-g zKz!kq9${XwkM%A5Ube#ZyKz^`cNgFvm~Xaze9_LwTxmCS4z%&{ui~ChGQNj( zXUq95_O~L=*DLsbSeof!A1U3-eoETDD!fqkq1TvK!11MweI|$V!4l3(q@K5M^7vB4 z`IeMB*mrUmkNh&sw>3Y)&*3=aYvWhC2s+659O71R{L4eX@Dk?vF53Y8DZ!ts>Fc1M zmbU(b%TfPn#FYlZI@+zF}L0p28Db z($3#(oM%Y6Bj+_4z zTbN(b`YZLbY~Uv2ROI{_6&$%gpW(oR4yAk8Pgz?Bc^t3ZgOhQ3x%-;SL;Mb{ApODq zQT~j}1FVxg)~AR2Gro3y<6wW%<9JvXMcL1^_Uil){VU&{-hL1BH!t%6`+nsg%&%g9 zEa7-vzi^7nD-rc)-B5?c$467^$nJc{C%6j3xszH^S%ME{^(@; znifR++Lwy_eGT5k!;`#r`1^S2`iR$+!K;ARuZ?+MW$-${JM?|#eVM@v!8>c!{!!d7 zGI*WBJAiqgXYf=vbL8o)>zMah2CpjqR$V5F`zd(3elGOe{%YoZlELeOzfqqvubRQL zR^;}bG54}j+?T;?JN9=`ySdd=^vHrye$*YyMZA~5tGhKhU+UoR6)IQ67r}EiUJkrB zzu`U!-(a;U z?vCK;aqE`maoZXGb^uS0+k$np2YB0O_zOh8_g0VMZkNI91n;_Q*Nk}Uf!C`a9nf!y zwIbfS8UCv9w*i$aVjeubA6?*W4Bpb<^@`iT`Ykk`<1PiBuAfEIN$pqt;crRs^tg54 zEf3yzKk)IWSKLhycZ0Q~{(cLd9=9I;exPzi{02Nd?m&$1T!{N-R@_Yy_iBzCX2i7- z_ie=ePgY#;I>CDcyk7nN3gf%MI#GWg22byA9{$?lZwh#Ne;dGi3cMS^>lOD*^mhu! zy#YKuZp)TDzBj|)_2B7oJ*;^g1aFy<9QO$DdbRI7nSbj>?K>Piy?q7vI|^~ffTy>w3B2RL+Y`KAaW6pJ z7dUPcczWDc=)4#F4FgY)+X($!@csy1uefc9J953Kzng)l$1S2C4*YEjo*uV^_H6~; zis1E%dlBNk!*K_Ir^jtU+?C;P1@QE^F8aGVcs6*ILz45rgTM8bSU>9TeBkwJ-z8|@ z6z0tfp5DG9;?9q_^MI$fuMKhgf%nn(8T;R5h&z6RsD1whPmk-v-^Wz0h#!Kd$DIh? zXW%^xUa$W89Cyvr2Ssr!;OTKa^!IuAdj>o`ZW(bqz`F~)UU9EOfA82ZihCz`dfZmT zodkb(fTzcugt-3#?_%(J#l0T=9kNjr_agB0xE1)j6#gy*PmkLH-j(2a;Pr}oBjS$d zxMRW7Pgp;yyWr<1PlC9=D9~SQ7pg1y7G_ zBknTbb$yqyzdX%4-}Lh4QGdSzPmkLGf8S8KB7O;;9@hcyNASJ?uQHCW2jxCPBY5Y% z%5h%@ua_Ft{YUEV<4SHaWU7l8LRc&~t`pC7nr-#zbh+yJ~@?RyUE zXbqZ(^tm5Ay?xE__aNfl2cF)(B6yF2_b=gfB#&Ed6ic0FfAChL3Txe)!RtVOKNz!3 z#G9POL);H)w~cuBWbi`aJxCXP^tn5O*VvESx7x`&M7&Ah4Xm@HcFQ~n(Y|et+AZS! z6TH#_NnRCkZ#JGvfMGru5t9H1>BJc+P^!xYjDn zyYY19mBDMggy(ZD`A{Dh_wkh~CJ;UdO!a!OO3eoPV7dH|0mgy%xOsD_9p9kGfZRJd_{B zy9PXc9yrpzyEyLE;B{&3YXtA+e=_e1@br1mfVj$!itA^@ElAu)*x%*gOEqEQ>+(I0dp>x%T(W%@-40dj=*IV%Hy*tF$I1EJjD9FTD(<=9HP)~{ zSx448>`(boymP?Q+t(uceaUf4;00RyJkjqf=A8vzmln4=f#WJaD(;yXaa$$syt^x! zbq09$SIPd?i7xXo@9z@#>*W2;68tGY%HQ8I;`$PIDfTxGyh+Qje)Fr!^r>F8Y&0G> zEzLYH!(R^V+h!H!jRh~TlI@!)`mM^m6T#ERw+x>0quOyic>4Id7+>W_@s0yeAK!Xu z--aCbSn%o><^Ia?!v^oBjhJ@~c>4O7g!U;vD(+F@Pus6bJMsEZeiZLW@bvZtG9E)Y z?h)X%Ywc?X@0P8ZHyS*Bzbax~DnBZ2F(Yn8;_kuz4g;^WWKx%b(B+0<%sT`;eZQ(; zJd__5cT`5)P~!fD{T&Qm+fvE6t&YX>?*Qf<1fD)$I^j?GQE{8W)8|Ww_9;J#cK~?$ zcvPi*M{(T0h`*(i?dt-sd^Gb$3Qs$p=i9g+%8!b>Uq)PORpxDT8v7doUY8cP4!nPy z&b;B^>AK`GZpx2}yDxaUF3!6gSNT!AKZB?1l9Tpb%W?MsuXXO^InFTye+`fk6T6X zlphs$bMW-@x@Mg3DnE+%NAPrATHtS+_c-om;B_p{{grX^z`N~z=4}F=e%$g9SNTzK zH_nLLDsh(@rf60Jc&$q$c1GNZ5_b>ww-$KrB1v7Eu-H?=w&NQE^wuh+CHNc!d4g z5?8zaodn+Pk1}sL@bvlDj`^qjsJOq&h#N@Up-qZrEd!pepAY?R+?sj)GyJuSzoVG9 zG?pZ`AVa{bZFTLL`qmgIGO7y5Bi|2?DjEe>Ai8g?|_WZ!66l>Pnp&-+BY#lUMC zl$f4O_oiE{j-4!Dv-k0F%{`{@E zeP2_#B7Om$e!s4Se*6I5>)`dePuRh6KMD_s;=Tr+9(UkCj{64uy$YTlH-OG>gZBV< zz2d$q{cVoo2H@#&8xZ#)_`4rGJ+1>@J9zhjr_X~5^n2o!L!-F=0#Ba@6QQ5-qlour z@La@w`Ze}989Y617kD>*SB&D`li|;zpMj`-Qu$HDyTO~ZVRD|~B1Hjq5Xy zZc9d=+@#ebf7hHaI?5lG!K+*g-kHqXHiK6<1-wg{w{iy0nF!v^%(F6h!Kuu9_+QL> z?HgVndOyn7!{1ZPyDNid-w58nnRiYGFMm3C|Hr&hS-i`@`<{7QXYec!yoJX^IuFR; zm2LuWIp%%;b$WlTTfke3dEbCnx+b~*6{~zazxMdUqqtvX@G7T+cM0=8&*1su?_TEp z7rcC%9nB-TpVM+H-_NPr^vEb~XNJE?@b?LoE8>4L{54z+f7`Ra*E9T8;O|}ddp^To z(>3t7H~Xt(`0IqfSK#l_41a<2cNF`ZlHt#4Wu2dbzsVW?>dI)}@$7F>mcLKf-vjV> zYlgpq_&bCB-IU?49{%oxzpFC*c`_cCus=V;UmpIhhrbCK{@SE{H?hC*8U7mK?^5{t zdzQcJpx?dhuQkJ8aV^&G9QYfX;jj1)_9b;|sEo&6Ov{I$T} zG4OXt2CoF(wZA_qT5kts@ai%DuHA`w!@<+n?Gp0_pGN%-bG3y&u+X7`NA%w@rq>4*1)J%2i+|!(XHL`-uH* zmf^1oe?#GKQ}Fcjmx(w|U$^G*QGeG3&$^HIQ~DWF^a=jM$L(#8JSobroe{VBQ=ZQo zBkqbB{`~vd|F);HKRd%;3FEN_{4JT`Z(;y{=d-`XGW>aH-*WIbUxvS?2jK4-_BVHi zzc%<=1pdCp^98zo)pw!ao$T*R@bu$l8UAYE@4p%T+y~LVhuL3ehQD_B`;5xf!2LVJ zU-Luo_aggyHN#*1x;(z`!rwC){@SO&-@EMZ$qava_;V(pg zAA`T!GyHjvpndb49L?u)hQBWOn+$)~WcbTJ3V%zozbiBR!=uL-^GUf*p17+Oo#$;k==5mZP6kiE?hdeTta;3t5zhm!>297!b493S z*?(nS*4*Uc2sshF;urkfPAzz)x%qjbo92BoLQVkBUOD-EPum*YzV?2d5$|~L{NE>e zA^New`X5BRvP19+=G^S_996nOeR z)V$PEk-t?|{50Ynp273L`^);wD`xQ8gm*jh4$0t^!MpY$<{gy5EB%MZ?b_#=cOZCe zt0i^rKz~1co@1P?;Oj#9WwlR@VCn2NuKVn9XhY{1oO7d@YexdPP<^Ps2@YXYq^zmnHRzYC-M32 zc@vU6J#Hv*FPb{fMt`r~WZpzv-Cq$p54mCLyu1zl?wN0@{&G7o@9GbjH#kF=Ds=hF zrgf1&;py$mqaPzTW8NP#{MGfxe4d=->HZqvZ^*sO+XVhPi##54V?4sT+Gw8M@B#BS zmbeu=!lOnLw*k5+KdS16!qe{O*l6D>OU)lu6`tNc2mV%CntAJI_-lZ_c@ItUbbkXe z9&;bYynKeg(zU#f9(kI1Yh~~Xi2F$Y1)_eep22Gd@4Xi0t(w7Wll6N8^Hu_{@dO?Z zIp6T$uX*x+GX_AKb&eV!H&cgj=DTQI|4yXg02lBfGC zqkU7pXI@=~zcS`u>nil(5c&vD_vd21Oj(P0^JVDLgnm4BT9VhxA9zEyqX+KkBmQ(= zfPTDl3G?PgT>bnYgf2s$VBTCA?Q^mJUH>Kh!AtrGPmfzffA#18^?A^a_Q~`A@}24=OG9EE~@%PMqCeZZ@8X$pM$5b%NCn;QGQh1 z&%kRtKH0vB7`MmwpcgsEczXM)=*KC?GVjw2e`WD^T9T*x^K5S4kQ>aT*h?>w=>RC%rF$CP^pOqExKzbUJ)G*w=k=yEZ= zz=u8`Ll=EMJInAse(g8R`)>xX3A}lip%+!rM|iq^^+R|(=3bV0of-a$@HcdmBv1Ee z!{3lUFz?+Ae?I&@avbyC%HV}^p8fYEPmengaaTHndH>1qHwkh7a&eNU`zv8xj=Y3< zuV?tHh%S@q#bERip6)L%y4=gWS2Fx{O8XX~7uwNBc)GtfY2U(A=lS5ha~bnq%7|+% z%kyg9z1EE4J`bLLobHn2;IOqK-gDsT`+Xz&``GEsdnUtQJ>s@bVBV7%?aRH1^Uh`0 zj^aL+!OKfO_D=G2{R%r`-tWV_M>701ioY|M_b_<+^STA}cgz9nMD3dbo_>F=32{Gs ziFpr!H*vlJiR*j~y z>Cg(^B76Taf+m5d-=AzbwA?P?U{FHM*BK;V_iNx zn0a@A7xvS}7wy~Nb>`hJ{_aX1r`s_PzBqVD)V|xm>sT@AFTi+w`R!H_?;jcdLh!y= zqY&}hz-v90W#CrK8?*xR&I3=^IS<|vYcua$@X8k@?-MqlA4hD# zymP<{R@8X#r~Ih?mcZ+3OY$7}>%SxWI~zQ`zm4$s;Zw{zD}z_JJNI|>ADDM$1}_KR zhd1vV>32p3&sqUG-+Xz*`+Ej2?|}C`^Zo{2!>IUczWD=#N7n`HUzI% zT#Vc1;0*$=^|j=mXdK}-ZJ3n{cu-c{g$J0 zHE#XE)B7aJ$QOQeDt^9|8d+Ozs&fZGyV4`<6%h{>{9%GTPS&UEZZ~rQe(2>FsNV&L4u;4qmTu8-TcL zy&tvjQSfwK3W)nS{5=Am9=D9~cm}+i!Rrlm)=>h zufg`GHd_8pM4Z%HMZNz)zC7Zj-XzYWs}MHn$s18y(G zNk44#W1rdWU99Nn0$%TGI<5W^|J3ujNkQuTOM)JzV7WM zy04ptqh14X(!LPJWo5)Ihq%&Z+`a)-?$%Je!Psh zUgP#(wC{Aly@WVvUlRFVMZGT~PTH43+#86q5hwFLjkw8c&TQFtH{yEPw_c!?&(lW( zZZhJeeOWx7-h+B4Ax_$tLA?(m?k>d1ymxROO}-oSUWT|{_FawfdlGP$B2L<8k8Hkg5yEcP-Ss8K5Ax_ToCi*dX zr{7xs4nbTm`<8<1tLftaHy7fheI?A70O}o#xL)?{0`|?1xNl}^j?eF4p56_5ry)-2 z4WPf@&Tj9{)2|UH^#)My4~T0ZP99&%=*Q&Ivs!VPia0sXEgX;c_Xpf-i0c)<4{&_5 zfO{2j(vK4IRcE(%`|%3mq#tF(y^Xm05Z6oZC#bgqdhbP?)LTJ+A3(l)5GVBpF@BFA zu7o&wT(gny?$Lj=;x`F#^8H6)2Y7yP>+fByM{|Ue&v%2HLB8Dl2jK3|@RgA7`7v{} z_-;mA_#Sx9HKaSJv;P&(hIKcu#{hQ~;(}$s(K_zPG`OBIx8pczUmW8yd@Y@PSM!cbq>bQ0^Bhg z`$9Ls{fK!d$4UEA6u(J;J6dC3itPIZa4C&_VY06YxP3MDS>Iy(W^tUfFGKeI0l2Xm z`?6%;o^!VHZzql3@(j>xCjhs-hOdtKeD0lq+f2ika)2*)7vMJ4@P!Y@{F@56bu@hD zO)zeD18{32PF|PTm{*fF7}WB24aCX!?8W2YdHb{t0k=BhlE3rk{8c<|bn|r2)720s zuXAdMn{*}cnHs$n(t8!)Mr!od(2s7OZoR`1*Xwvi=Y8o%9mltur`wO;5hwkKk{{;*-}i`< zel&MNKXQO`5GSvP3gpK_fSZoEUVfYc<1x=8fcpk<(hmd2qnoGOj|SqTA0^7GslfLU z;-nwRJ7``4?nA`M>z4-R^W??nYK?CVang^j6`4ZX*&#PmAZy&_T zd@=u|@deyo8ov4w$afy#cGU1?XVGyDaNBA4!erkIfQxGQVkaY?4Y<*Wljr?<&v^@Q z8zWA}*}&uEv|j$4CB1)=IM^}hKQ5r{RZjXbM^wd+5gtl=uP7IPTLD`>uU4{ zV{l*5&C|`d7UJai#wdR00pAG3$?>g@$Mb#;a4R8Bp7%qjchW`Z3Rv zfSV6-(vJw{K{rpgA9Ev4`jH_&#sJ@+KfrZ_^dmY4`Vj-%ABdCZ{Vx2zZ1M!a{fap0 zN7t!%zB~zVO~gq*0?60R)9uGkh?9QUbl$%W_@*IF`r(it7T~@{oILNFmBd2 zlYT_$`sIDVeStXXM;Q6KdAj}h6milIi^gNYDIC(9zR(HeFW^qq@EOGS5a7}pzEm3d%78mc!xtgGp$oM9O=|e6#1{bE z{)m(3!5HS%t0MuoAL8VBD}={`SFZ%z-WvPrbUb($a64-3%ToMmfZG9a@;qaZ-l4-< z{%)($8>hI80o*8!UYqhX2DnWSC(jEe>V0hj;5O9g%}_o+1h~~SdK=_#8E~s2P9Dd@ zq<1RdOpV?w`8zV$ipx?Oz3~Z{S0><=M4UYC#xW0G+Y@k$YxL&H-zxz(k4CRG9`zOg zH#g#X9VgM>DK7wSh(@o4dbggnP|IJ!$>&^AJpXR_JKzRs_zD!i4Hj-qTS z@O=Ep-AA=>ZzE1V9}mr5xZC~SzBaqP`}qGB;^g!3)L_7Ugt(^=mtPtDTe!RP?0=aT zS8VaU_@7N%dM9ge;q4K3GvKb);F3Ea?tZ}KG`ReZhfa>)Hb1 zNBL5~vb7)J4nv&GgVe5YKAJxF4lTYE;^ca71J|=2``eB!+@Xl;wcdL!7~g3d?$p8^ ztkE0X4fL+|dZLBf196dU!4HZ{9pe)D9&lSCE;$x(3t{|>@hi3B)XmdfwHe~%^-C1> z?tr+B5tkG1Kk_&)cSPLkhzsq^?Mst=bL`dfV=2T*`|1~fece3W_Jt59?MtA2!x6U- z;-r1q3*r63N{H)1TxLtSzoNLLF9f|CEeQ5abMSd0#&7nr1NfJO<7qcfcg0l1N&6f; zPX02xy&Lx_;-q~Qj9(LRb;5~tEk(@dRqg@%K0%zEM;7A#J><|9}tq!>6wj39I3gX;SI{UvY@=ba9 z=oa4x$X612^N1UT-#HL2@G3m#>ES~^P98h1#rM93uZnS*ygdO#!SOBJ8;ElXeB5ft_ehcBl9&f%UmbDdqQ|xPUPr$Cm7K4ExCirqt0FEUacJK| z@#9;3QxI1bemIDGunM@>5Z4fV4(csuPiXPIin!QS+`cB_9;*ZH6~skFT)Kuro<3Zi z(BgX;aZSmG_B|fXv~VvWP9Dbt$T#hJz`cMtc|7P!z;XPm5hu3zp4H$&h&vLMcmdl;P%tt z!mGn~PtR|CYRiwkHMk_=zS;|Lam2~|Gv0%IX^aKj4jR4$`FkGVw$h=&S?32 zgW#j%ZuCdYzrldJPQw?N1^#}u0pKPIKFXIOj&CCZxQjJ>DH@OQfICCO7og{?#{up% z4PO}Jck2s)%OFnfx8&e;`+YXY$>$6fULS1vGT@Ha=#A01{Rp^m8okE3a6j|rOpcR! z%c%F@UjTQcMz4Y6@%;ERTjP5O;wrd)ZT4kV>t7u8esUb(4$|-?$&W#2wfOec@MVc_ zFyO{&__8>@L&gAZPsGXl^8(`TirmoByPJkDgZ7QM7I3>FPF~klF@AS60TO%Nx~zv*Y;ddPg0``ug zPcj8?8*22%F<(Zkc2mpWbu|9g(cg7e2b_sGvjpcyI&K7;aNKxzO^%cH8MIHwI)GbA zV_ya1a_iB6TS0@X{|k@1CBQ9?I2pgtuXtR$2XKpM_)3_6Bj&rg6_>d+d^Yl#LBI{s z@TCs{`$pUaxLM!v^D4#9oCWrolK|I5oIJ0laNN!vc1z2?pES4{#&7F1;C|5HGKYeF zw@v}v3=Phq@i1;}>HPw6GR~1dzz=JAj+1%N6@Wawc}2i|s?nRJJUs<)?`ZTkP_KC^ z$4R{b)I0oiz`d!_8#o%zZ!-XAYxKtOcX}EQ;GWa)*_2oN+}4WUBN{$?N0?XUzJPm3 z!)KsCbR{-2e8ouyQ@FVvb$4R~j z@qGcfaT>l{1CQeu-r2H`aFVZS;Bow7z#WNv@^}!(aXUABSBviejoy3!{aB0Rq}~|$ zu@2z&(D2!-!n&ovXB;Q_;>b7n3&3rs;fu`!_QlSe)bfLHk}rXLTb>QLsD{tN--$9; zo800foaBq(`DpkWfLl+)*EJv5XHMrh$(Ka?hJWXdOCj#r?AI;#iGW*F*f$I=JG<%=;eC(!;XN%r z!b!duj>i`t11=!==)NL~??cUT_qOC*a~+S*xBkg-(!SY` z>)`ro(0whvKWX?%7{4Jwj+1-^eC~brB7plr!&jj5;PxEXix0=+<~ZPHX!vZ(t5-Nq z@)gm(o2!7EuHh?@ebYHk@|DRx2XJ3&`08ZeCil1EOgPDB6JHc?UupQ7#5e4L7T9~Lz8vvA2Dq&>eCFlI_c-7-*YKGbzeAQUxBMNg!PP0B z4*=XI8eEk4CIW6l4X%lNU)2G(z6O_~yjuF$F(h!kGA}nOQSc9{%-vV;O5leg1^JOJY>1YT6}*^hwBn~y-~(- zJ9iw%N&5PXNZ&QX-eqFLd#cLe4iptKCdey?)*I9-a%Yf0OmD~Z|MTK|2X!!XIgxO3#k1UeDuM4%IaP6Rp;=tQ6sfldTE5$Hsq6M;?yIuYnZpc8>k1UeDuM4%IaP6Rp; z=tQ6sfldTE5$Hsq6M;?yIuYnZpc8>k1UeDuM4%IaP6Rp;=tQ6sfldTE5$Hsq6M;?y zIuYnZpc8>k1UeDuM4%IaP6Rp;=tQ6sfldTE5$Hsq6M;?yIuYnZpc8>k1UeDuM4%Ia zP6Rp;=tQ6sfldTE5$Hsq6M;?yIuYnZpc8>k1UeDuM4%IaP6Rp;=tQ6sfldVee~du# z0r>q6@~w6W{O&E4Nv76--*-tq2ftHNIRkK^GeKsSV}_7ks8+7G$=qw5!3uy6fzd{mzvX|#UdiOR;F z>Nrrlm#l6AzYpz&%gzgWvZDZ>UzOY8)qkMc3y<-*MivHpqEWRUsi!zzXGh{Q_c&Vb z@b=PTJg=(_UZatxA_}4>qB)si8nPC{Ez+!emNWX z+5Vc+}w`b6wqsa3icPysh*_$7;i7^4fZzf;Pr$jS>1kM#yS5f z=qbDcvg9+5>!0)dtj@*DfgHr8a6a(nzu@iUM_`zH{0P^sG}7+zBR-?d^M>jNT87pJ zKciQw^NRF2r@*+z?@*6#a|-l#_E5)@ct|E*2YhBGk4NMyu*Z2HctTroyW;;=>nC24 z^`jtu$wU91aV$Op_En~Fe+!Scr>}ZLdwBAXq`5D~aefiU{dwHd`+=VDe!QM|qCctQ zTD;ZWzU1TJe{&8suKX3Zi}aDq{J`)3tgFDj=9k>g#^Jn7{dF>Y8R)gYRof-|#dq?D zqkh#feB7y?WM~k#x6$Q3pDSmBy_t_eCgoCmt9Sr$LSs2^Dulmj91}7j-%f(O^WkDcxR6Dva_%4 z@t4*9{ZnM zH+E6$HMRkN%p?8TPkQ{y!kucpe)|(Hf!FofwfJ#@+DXR#1b;&J^W%Z}Z})z-xK2#{ z(4O6?7r8#Nhh+K`(4X1_?4x>;UFX{LCq5$ZQzH#K%Fl%W~-rf4s7vESLW49+$x9?)f13WZ4n-W5u!D&-Bs|XX6ZBFL|OnsK-O% z!uvy98tZ^xwP!hR{&^@H?}2piI@x+2`XyiHc*!5%m&c>NB+oyIr*h>dK3?^hd)%p? zUl~mTUna%%`0YPjGFH=7$GrPEttHe{ejQrt?xc{jSVO-;9`HOP}@xXdDBbsJc-}P+nY;*{ecGOE#C~d#7!KZ#{0qAa@?-qEgVO7IV*Ess_&~z zb#XoM&-nAH(vRFJi_2$k|=TB*As87wWwyQQ(-7kLy$HxsQ=Nf=_c89Vv zP2E2{iuX@`!Q-3$3d+%OF#dLtAK#19IX<|6dOV6l+^^RuetBDMC$;OO`4rb1*`C|k zNI@Ps#{hp+tY@jN%=0^X7~rj=czksFgS)Hkj()^>Ym<4I_!>+4i%+b<{i6N_kN0ha z^DC2sK~Ho?wY@r?;!f@1B~SVybsQy5S9XH#aST2K{3(>g6Z#RxJM#MheEn+ocEU+nEWq(G`yLx8rsO?{wEw zljoHW-SJ+2HRe>uxq|CA1M~6oO;$WN@#6PtkDmtm6Q^@KGQaY;)ED*Vr?~*n!>H5V zc#yr;s^E8KCGJ19d&%^#+}<)iFDre??bGqpaQ(5az1{lqX6||`U-IiF;;$X%FMgSO zfj{DNopfx1IXY)wCG z&l!Av%Kl#E(m2pxJlUPc#&wWhe16+=&vAW)xxtRW+iHKE2FH`0;z&MUs6H?q@R@DZ z{Rk&z7VigRH^6vS@H>RY4{Dy&mVDk6H1~s~r~Dq|OBm-r)u*#+erhKfKLYG(EXMJP zw|LxQ_&lQdJH$1yH*Y6CFB#v8>(SvIydO&$Fdp`y>bx#*5B3vJW(B|p45%+0$@>LX zQIBus7{D2;LwhXCd5Pb4`1zRX2Ub%e4brtE0j!++GsNEjN^P+jAKfluWeWX)>{4|U1c}n_9O^l-r zddfSi^VgZ=&ko{EFV6j-`rvJ9p6XaNp8Dxz`8sZId>M6oyIL9aD4FqHE-=W_xWo)!gLf$HBf!Js)(uUiHSJ-2cok;73xtHw^p&dTZ}<{i(;*b_el#uX!=>Wmo2Y zc-b}3?TtO#)1SOm?N=hl{SU3j<5xYmy>TBXKbvE@T{_;%5 zcIt0FsOC+dr{lXEr z;P-j~To0DP@7?m#;CvB24E(imy|m6Q>s!DV>AQ{wKi`z*<#8jP;34YqrFN3Z72R?1 z&D8uAaU5xU(B6C{{Ujrss`XI2lvRB0+kB|K`D=gDo*t=JSI%$9^DX_fd%hA+tg4QG zdQE?JMh=9yH(zZp4n;$)m+b1VY+S?Rq2tT!5BAr_sQt}+1ND)Kz-No&cVmp&?*_(2 z>NWBDqKWfKwpZ_0+aYmOPHNVt1;ly;!s}!zrJg^*)716p!+3pSq&nWte2|A}+=oW$ z4}H&%C$c>+)_2QxDp&D25tY4U0qr7OL+lHXN~--Kd~6)|pXvjTsPm!Z@mzrVle8`b zp29tR9v5zGFF%N{ztVYw+tFV>>K~g4ytcT0r}k_V+M8c<{nd#3`JDPonO_mcHNCaJ z<4;Abb4?t>$2~P3%DG#C*QoRH$>BQu&;go!dQ5Fc2%oc%{ps(x|4ngUOgJgigMq({ z*WlV` zdzKR7L!a|;ApY>K?tTz1ir=kJnPhrX&KqA=?N4oO7|#@5ms|K=ig=`~tPk_VS)KDI z8p!jgT94!je2sbJvCoF=*Vl4Id?%SWUyRq0JRchs?niW9-rlwy!`thh_t=kv^d~lI zkC*!CWORnVyrce!iy%&+C)E9FZ}9VRJYd@ug;}d8plZ8vHdE2AM@k?cqhB zJ|n(ksGSFP*0G)NUNR`&a|goi@wQgxdE>>O9}52Feueqqg-_u7SHe~BxjB`+WGRC4 zPV=5j*S~=4S9R^tx!|}E8ld;Sf#V@h^1r#q#mK^Vq{V&^f%U+i;-1jIhWGEy$?o|@ z{u%rD!-epB)gpe+8efYaSBOu_!WKOL>nmWt<=yob@qJjGcfg!48R;&~C@)cyV?pm`ri z`jWU#uZqtvsQ#apwSszH_SKH^Njz@mPdskKTbUDZfi>D2C+e@0(FN7|ba<*SuG6=E z)Za@Mzv6y|MZU#%=lbJQIX+h7?W8ZVGT`jx)aSwM^6Gl(|98p4Tkd+T*SJ3pt}i2d zG8^+es)TsidXM*~e(lQoO>i8I+>FOlB#7R^%aXU?(N6fR=DDPKG>=c?0`RXsH`f~; z$8p5lu1tq{K6&*Ip5NYaA#SPh>HGM&>GTH0`lJkgCukp|?jLD$oqbfSuWD+(%PKDe z@eUlz$ARq5hY$i_mYiG-19hj0oda##m_gzrFmKEDd7EqtfzA1#`f|db0E*d z(DI-^j_WlFxPB()VHfH5E0YJq_~(CB=RxixZWr+ukLC4=J=AfIm;A-Syou*`Hm>F) z{gGQZp6Ye7ngM&OJ8@ns!R-sJz}rpDe)6OzyfNUNK~}^_$3}yk3Zq1OmBg_m-9R*uJ3MF@^`g8lHXb$cpQ8lXltIwP`~UE7}pQMk2v5znG&QztV$zd~|k3e&WxybU0aGs`GfIaX(2L zzi%ge9^W4)Ug7rS)`$M_@w}e;#qc|@u7&yW*ueXl`U~oQ)ZedcpnVb_9K!vh_WHZ( zcvHKVtcmNB{Ml+fUOckhz2SC@8miF~H^xL9Xg^!RQyxee$u&v&<% z_?>G3pAYi5Pvb z<3~Is?cwh2g!{iHYxsV;zjj6Dg?Q!e=5fp8_!ZXjH;%^fd|YDqK1JH+Tmrb-2^=qR z<_0{UsJ$eTP^W&1KxgRthaQ8>*k!5>Fu1B_O%lCudNso0S z#W~!^Gam4#-}Jb?D&C{klimyXvzqn9TK_~tNPLHE-J*_r@E2}JVh}G2+OG0M;0f%h zjze^Db$)gI+PC`^(x1fp=j?*$$6jiG2%pE_d!TZ2dv`qHNTwf#dEj)Z;}O~i_^P}3 zSS6g7fF@QuC#8T~=W@pZCP8lS$lvy0(!z z4|M$os=n#*{dc>1N-OaA#Bg7n2JT-V`O5F8^E@WLr>A~_Q+XZ*{>AkX&Pzsy`8#jw zc#^xQ?bhMjtq+Uu!rJXG@%apoTfE8hysUXX6O6ctmBqf5p_Mp3{W*+FWEakxKN{+DVn6T*?)MhEO+B6#{+>;G8+Ci& z0bXz6etPA7d3^-;BdgcBT{14RT)_R+WPN5Ch<9c@_+NaOkCTD>@ukH5X9?G(R5bgy zN9=@Z%XV2V4RIfb;26-G!FW|`{_K!?yvntM)OLh%A4#wNUhP5rJ)-8b z5FZ=go9X&lxSvP$FFqc@d3ibejym2pt~1J9&&OM*uPOFt$6@RVM<)%R_n*meU}p}$lhyInai5Wpn1@k(U!K{W$3w?M z^|d`XK2+o7-~;M$i)o&Zl*IeUQke5OMK~@6PvH5H)ckG~+1Xzi+DM%TetFCHtK;Ce zfBq642iecktP4-?tj^2GqF_(`^7j0y9m(yeX`Z)A`$D_%e(^W`#iJWm(9F zfXDaQgts)`D>Yu{b`m}>?%TTF@@GHwCt2H@pYL-!L%BMd>#b|nkEb{1*9F8Yr6JZ6 z%62Lj!+ai5y-tQS`J}@qzX$)4_&tcx$L}DEAE@(Kr&m{R-3#N^SV-hOez%gvbpTbL zzyFl42_BtdQQw@%$6GZ2PjQ-io|P7X_@?lEeRa?F#`Av^@xMaXs{IPz5BhRTf~-{l z7k?b=44>uGFRrdDsQEoW0qZGR6LB2HzW9+1-TklNet*G^Q!bYf9@#z$#QD%_Kru<7v0B8^7pqK#r3H{&F{wq=HlZR6Z`8} z8}j%Rrt)&v*1W&8H?+vW`kTV%Bc#W~eZTB;AYZEDcWDUMcp2J5VqJAn^IVnswJW3e zJLi7;W!4|q_=NGfVBvK4d8V_khR?mJy*LzjlDIxRjQ2O0-`vNY`X_(m^T`bG{E4pM zk0&*X>v?tUe(NiDf}MqN?)FMP^E9>n5=Z5R zcpgsmk!4{#(s;jWY0hhbpLyPvMVa_W+D(q9dXlBv!QWI&?ROEsyEE`TN)=^oa~PlO zvhMu#%iQOG{}AGw9jVU$l=!{*hS+bO zcrDF$kJL^wgU=!9>d(CF)xUZ#_>q~!?XHRMnJePHGtuQwPwsFSkHFoaC)f1XkL(WO z?@mzJOXj=4k8~Fthr;6bNOk?IwtHSSPvzri{ienn7*Cy^uKhTV7N==wuBy)O`YY~n zb(V$p0Isi-^fB5$<^Z){gs*%7_BS-&i4rb~_k+gCYQEBZ;74;awLiq8lh$+G-%5}l z*Uc$BpLINb>+J=&K3%_n_`W7x<;R`OHr!4fPZRgu$<5>LM*{B$B~Nlo9#{J(us>M= zzQzOUagjW_a?{}aT`!2Tt|Qi$KXv!ZqkFIB$hPh2Pp%LCm$%{bF}IQWJxB9Nj*|v7 zCPI697RdNP!k%NfzcwD9h$mw5{0fWj3RC!=iSUh$!OpCB50?2C_?7m!A0!@+n zTo+qwg8k*I`j*B??xAKAAO1c z-!8|*I;?@Rr@SLS&Pd+)J20-YzNh>L?_U!8P4?i#AIWRf`DmKje7m^W#(wlzC5l&N*v}sK2{3aOX9w_vAa6{(%!&b?)-$0 zZx7>^8VT_(Xx1lM8GqwTynU7RJGmb7dR`{p1U?6)azXPxpz$d`-Vt6Wqj*1<6Z_j{ zHP4N$72)_-enV|1>8a<`cBGH>H=e{pvNpn9AK?;P4eaqb{5JO^bR6d|;_vj4ev;Oe z(65pPyCXOcLN9VZYNH??&Br(|@%WX7$9K{?p8Wj&=8dj@yY;aH`S{mv^yhcv2;Q&y zgZuSDstNPk#NRO~i2ac(Yq{$+aDOS|GCp4EH+Vjf{~2759r{XbS8;y#^E~nBWb_Yi zZ*4U`ZixkX*}~(TSMUS zVEj@%FD=2xGimej@N0J&-{<$4B-r?#1VyZ2!B;LGeDiT|JpEATEKAxZi$x zieem_$NGyG@n>J=dSi3Ck5g?<^>K{&yktRqhZJo>epJLhU0I*kyOnqNxCaj8d7b-= z`zP&73cPHma!qqzk{+s#S78x;Ja437T!I6%o|NpW4(0w+y_BZMIuMDca#8cW5Va4K zOuYheOx?)yw}kt2kRC(+e#;y@&V(!D^YW_1BcS;>=(Cnkk00^Grn?{C>(4>|m{=EI z{|ov#$6(cEv+U;hUB8*RQHr2bMCt_FLv$3fhRA@08=zNeS{sT>pQ zg%hLH_7lFCd6{q|&0W>wO6^`Ufa~Z8*W6jHFZ#Co_)>qJOwR}7)0_!$Y?}P| zQ`G!!TzYRfE`@PFQUYv`&pgu&K5kLk$*$J)?QcR^ON|vJLmKKCi|rfiSLdACh#|}0sT3T_uj;3{i3#u z+6(gc!}kIH#I1OI+YRgu>3$DQ>{CU&B=eempwpJWyda+NWA1(sF01)H0BR>$xR3MM zI{&DHkRf~yXIFuuBUh} zFB2}fs{3_p=})zv)Zedc;&(dMfB1OG{*?tlpM~!~9I-AxhTpSAD*onQGV88S>X+r( zzahVyn&VpHJ~-ag${?+mxxVsF>i9)hf%?jM>UOdtyDmSTrE~6h>Q{MJJ>Dhp{Yhpw z;EychK96I2Kzr~B&~F}~<|q9m^J95DsNTkX!l>*e!+74Uy#?bQo=@=R)p1Fj?d})p zjaU8Qa(Ep|{d&pO)pqp4X)2t{{pB@v4}axv9BQxeJZjwK&tK9bW%iD~^>^ZY+{$h4 ztB?@;ky-dWx%!Mc4)K$@-_DL|9Ql_x*x&eBecUIbOV}UA@5oC#yW2(fmG|fIi}-vm zn%J20=N92{A%2|*{0cL7qjPYfrD_vsd>wuYz;A>nT6&?oSoJ zPpd7!^%=iIzxw%n-c*)y*C+j;a!#|Zxq;v35KhX-9blJrAlOle@VtT@=GXPh zeg^nDejnZ#p|(TU->W|Sx!N8liTUC4xijghAIS5`IggK9bUn2`>hD)pu2u7-mjiwI z-8}NuLs3|>ZXr5^$3KDB$5Ff=j4dwa^XA-+^zGd4*zugt!z^uc5Z4boBh`F`hq+!! z6gi&TDck#7jxI0af`q|@+TP&4YP?@Nj9>fL->;r_alx59&gsv%o#orqf8> z-rRQX@hPv){mJ5eujG~Gpjc-w+hsZO1s+$P;r2;f5cf%?`W#-5P&t}+_rE0Wi=C4= zK6?=4cQvH8BPZ71k>1GRJWf>KUs>P3z4;y%--RW&SNoC0=ScyN@0rQ|jM$f`u(^BQ zP(Qyi7gpOT`ljQMTp1}Eh_Y=UT&*M;d>Gtv{rdh`q8s$DdW%*sx z_v-Uo>`SmGzp{HC*2MelEbezeVMuHCqoQ__#=lX|qoCK&>}Ob^{TDR%gDH=FsDrD) zxF$9CQ)G{ng)WF|w8!Cln( zl%es$-y8Art6_8fUU+IxO;hJzP4hb@iCKK!*3RJemtN<7XKv?Z((CNN`%yi~$k*-p z)9{I}czlOL`bpZy^Ya+hldONIjvuv4+5C(1<>qM5&#q(K<3{>&@B70MUMCY*gMX#H zfiLwsAOGB@-2dp8P>$ky5FM|qH%{X`vi+YbM^@wGLwXBGsPmZGb+URR@TKtgX6z@q zpSe}l`a*4fAF0zX>mzUa%eT@u+^*zhF#g5wx&76NcpN+n+8ZcIZ$YyTh}w(iw3nxe zW4T?#Lo)Q8dwUY!&qwinx^uKY{nZONE;WLe%R~LemF$!!vkxQcw<yI!uwHu^ij~C+*xf0;YeB=sClUUe@lkH zRmV9~85nz`d-Hrt-tRA7x_C4fb+;?NvU>b=eAN};Jxinn#~%lO-#)tru5-clP_lm- z_bD%nbe;Q$Y-=n#Ysv(~2up??eOX5DO^evA+_1DSd zcYrSr=Kb;q@$*L(_oL7F{7zq|&k)~NI4AHp$$kcom#pu4k;l7NyQU&3_T@0%2K{9* zUYhP*<~#28Qa|%g^?iHbIrTVFKPj_fe`DGHca`Jw`18}R{z%e&9;X*Z z$1%L0F1LAJF>oKH0zQYV59RTcb|vO+Z+v8bzvUEu|C2hx-*_}G>DzoOegxxIUy#ou zI}d(VHSYy=egv;q=RpInGj;tMxUWL?1m54A3jUYcyw0g;>>&N+Z@3<+Cu!34ELHSV zX2o~L)s=X>b@b+N7>C;Y?VX3Jzx6F2$d1eyJ`W1=e()Y>FVD$w5&UkEc%&?9zN?Zr zT{#fq`gAy1A6*mjsQfaIOYC2~O#SkBUqWRsS$Iu7p6Oj7&zj=9IWNAytKFI(?5W^B zsLec|2j(W+kLcVG?_i4K$iDPe98dNCS7q@`VeiT?uX5sd+NAwCTt8kD>-kIP@O+GT z{BDZm^(q(fcYI>2^Y}*(hP*XS75*S$;XSCYAI975!#EG=Z@$lQRNqVD@5)epazpNa z8Ozy8YCY+V0bdRK)JKYhv^Doh`I#`!GYhHp3!0u{?GJzF*{(bN;gXU5`PZDgfBkzL z6Muv>-=9}L;o~T}^(uz0;Kxk^*L@Xn-+tMl`WoOXx42(FRjUx+n&$qo@ifGxayr*< zmEC!zJ(aQQ_@`b$bQiYhqdAsT}_p`ce7+sw`{=KM0pt%$?7;n~xjyYgbn13fdX4IqqUQcc zjUKpK2frT);`?}FE{X3%sJ_3_I**T|D1L9W{zhhR|(O+DgB|u-==l=Y~J;ZS#!OJ1>yW#fU zyj>Ts#KQdeRK|V!LaPkS@vnBankOW$(}aPI1dn3??aFH2zlrYp;=B--q~?1YYZtY> z));lYUXi*bfO?zac&JAAzqZ=uc`W^ndj2Ga!@MZp&gX|Qo#WGS_q>aEtShOUFfehZ z$c299_QfA@w~zX@Er)Qs8#B0G$rsoRuagdiJh$=pHY%Fme=mvoF8K=L`mDT{KR>hL zz9ak~^fN+WUv>$!Q!4!bq?}B{I0ZE8^vXHN_w)e&J}ZT<_zu5br~1E37IxtCm-JLV z<@NQ?{N)ezj~xvCLk^z@)K1ct`y&0R)|353T~9nDoihLz#P>^7pPuY)M(o|| z5B5tSL!bDwgY=TDW_djAKh^pO?^ot81iNbQasJeBsMqlXX7cvTRXjchUiUaF!11VY zG4R(<;yB_j;Pp~$MSh;9c9JRlomDFLk_U6Us68b1*|x4%+d+7H8(~M0<5Tz@YG5sa zBLX2)_`X(D_Y|F*gxx;(@#rD&_@gSmkBA?|^DtKv`Zatu?YEE57i_%WCwOEj_q;6h z^LJxRpYyo#GS6qSuU%Qk^B46?ug0%$sh(s3-#buQCyfJnJ`pasxqJL-x2XHoZ-;() z@qVSc4a6Zi2OigcQ1ctx`paXoQzt9;x#v;F1bb?q^8CxJ4Ejrh-R-b3{?@+ zLRs(b|N8~7wLHb=u{C$(gT)=BT#mA-K^*zReV1MCOo{wc*2TS@% z#&DnL_=|wA?+kh~;&~n6y=3hNb^K(%NSWtlXd1*Tw}QX^l5fDuTk&`kZ%A`L7+wyP>tudiz*lCt&j($9Szla)$Empu z94`~U^6R3?iBK>5o7;lFv8SOud=9s({4w`0i~E&I9$9YQ&Us`zl?$5piqxLMef26R zsoox<9;Y1c6Kwe0*FU_tKRZcpBLw*1oILK-PO`BLv{$C9?JOM!Jh34#PYc@u-uZ@) zTkuO>CVrBQ=hXbvo)h;oRPR@s)489c3cN$k*JL{_-Gz&#TQj;kZ-2gWDB;QmvoV^;Ozgt|wuEy>+pl zMC1c^Kl0cfe}K=^<^+HFQNs5nef5L-WuNEzseYhkW?>$;{_@v;bB{0a*CqijH_IQM z`VEw{Jl1J7Zh-MluIGN8oAcU_YZZ0A$A?4QQ=7T-OMk81fiLzIKVC?jEH^dy@UuMr z&CB|hcln9DUvojVU-|w0%_C`lVr|YZ+q;_T_A0(NFvagtQvbvNuWv~j>hUIhB;#kh zkDvXp+8^p)JsI>QHNSIfK7->rnvX+%2lafn=5p6ZdJD_K_(gvc*}t#l)FglY6Th(q#5MJn`#6>#0^Y(Vd>n|UzcP9>pTGU(OKHBJ?Zu1xgw=Kt zd4NEBRC{)X@cbS7vAur1?DAP*;(cZfe}A|BfqGs9kLLN9T}th5SUew%J^|w%d&AwI zz+iQI^J8w0xwJaZ@^^82YNOSB@k^k8d;!i&;R@WtdAd#kp8Qpuuegf95dq5N&w#IC zoC2Gu_2qZ+H{bGibNxbHPqDHAAE%xM{G*QR!DT&_>v( zxZht>|Ju9i@pTph|BHAZ7R2{awL#q9{FXePR>)u6NPk~t4dWDF(Oq9~Q8@l(@qJ?j z%R0SDvCh1{k^Av8Df1VJ8z-pas?(eDu&Y-;d|%Y7-e-k52J$M3<1D-7H-T|BH^=kH zC@en#GPWs51NYI1;B%qWZNO`dhW4%~N}-_X@Vrhv;U2Hjy6)pZ^r<`C^MP<)GI}Am zkMO4E_eX01cfAF9-9m(Yl+`VHTno7FBC`{(?<0Lrx7Zf$e)Ry`{3E|U@P@^Hkh#eo z`c{K+$-k-|9|!kcE=M6>3a@j%zbjjECB<~-J`5W)b z7{KL6xcgDU@3y60E6(-Gb}EN(|IlKa_k&%U`@z_$d^{67s`Jha^5avw=r1m0cOHMw z&%Bh!C-E>ZM^5JU*oXUz3+W-5(A-B;d-_Mvn_CF{ZDiE`)ZYMm(#Ju2=mu_&J&4DJ z_{|g4eAF&wW=Y^NG`~+I@l?+33HB86elKvV+Me>sd|a)WU|(_#s1Lr#+lfDMD)%>q zzdu3kB=d)>^-{Z(Ma^?9iKBA;P@X4L?~b!+$h zEdQpyzYJvhmUrc05Qh~0ZWGy66Z`2iAN-PMUZ>Sa=uXc^RL##Vw&6DnK05 zD2dMy>%^&^WJaumq56T6hWH(zrqAC!isJl^i|-&4xX#5n1pLiE)3>;K`B%dCfnGRj zkB{JaO!e)`UN6B{E<2Vr*1Nmd&`)}F5-E#Tgz}LJQ{lMqH z=2qMv9dCY7=qK9?n)`o=>uWi=g8Okq$D8-Lo=VsM@2Zbp3;9?;8CnR&CI2`cCmJvw z)*z@SI~v$d<-c3ja6jnSZeUN~O+KHEonc%m_xc+jQ#^04tO5OkXS6pzb2HWF4ZraS zz0Lio&f)L5P-3b-KgkZuXb&G=kmGZExyL1W1#d4t#^+~g4)D|5o!66nBx84}=YI|F z8{)YBJpG_M5Ak`)_zbl^>K8o{><+EN^Pk$=l@;+FiDB@#g+{9V3U9;ng!D%6y+uvL z)maozmUcGiW~C&WM9(nzRYK+{U)Bm z<={`~ba$MM?Xi==9{X~@XEA@Q*TLUp&Yg$!I=Fuam31Rs;s7B6t;4T=4PEsx)mBRfbYo(29G`cL(J zmEj>g-nDPJzmm7KF~l$YC&WD`p3_QvPx-%GPfxwiKhpTTu(1Z{&EWT<&8xuPz~kzy6sI)cKb3_%2N9ui$qT}{7JjcIs{34w%>!{N zY~Vf*ycC$4_tyDg>hpGOP4&DgF3QI(c|GK3rVLVNN9iKY7g&k=6FNnmuek-(_DMa) zGhBcDC9Y56+b-k#-{eH@e_HI{K)jVrz`rV*8vk>eght7s*ilyw|K{PUw~iL-T3%f znstJybJh8k5c}hH1^Dr^EY?XR-c_Gp$*zHt&MFY6ux4GmPEQ@jyM*tX3qHT&)A3P# z;(nfQx%GJ5gSa09;iZh>ciuI8zhpfDe3dQvxEOQc{Cb+}lYD;5@dG)(u3vU8z*!}A zeinUxKULkB>non?&yR*?U4YJBuX^Kp@FRbld%ng`J;?h}ef3c8f9*~+ zj_@QCFSz4!t8=>owmY79Nha`pZ24Ywzr6UpL>uqVW8(Ua`25QH`s(qodR+eze{)AZ z&!T6l?I(QwV2D%W5#FyJhVzk`;Bjnd_D3K-DbsoNc}?Pa%6LCW<(g*yDf2wwb$;M> z_w)<#<8tOG@FVMSKS=#a+M4TTYVVPQ)OPf=d;F1Hh{xFj-qT#3uFjVpK%0Lg`gvd5 zrn(+@{d9gD2+e_c6N9)ogVgaUZ>)}c=pr?~M`4?PWbk|SDjp|g_xe0I4&pnCC_Yci zjpY8x{<^Y*_Z9V5)$=%ZW_!H3%K`5^(_X)V=KD{b-Mab`?pLd8r~2B9{J4>vU+q8P zb+VX&e(^_n|HyB=Ec;vQa{aR1Z#i}=+S zyzr^1{Toj&ermUV;Pb5TBlw?NlgFR%QihjPpHB?U?;AxPf6f_}ft@@ZgVdG&bIHQ#4v=Hd3})P%3%GO9=QsVop$WY)9M}Q|L_G5_c>@VN)52@`Wzmo6qam|F?@zhUBBlY);qxk^X6Cdh+ z{5O2gKWX=&$Jqtk z=X2@{fB8rH{7UN&e|Z$feJhf<-c0g`ukgns`%&3`gZpnC0p-R)Jnn=~z09vW!b7?K z%w>?rP4V6%^eX2oitk#9za+k+D~;swcMj$}(O0&vN3vWDNyW%0X;u;#ie z_$}9GJEr*2h6SD&x5wg){i^ETZ`y z!0h7jB)uf#7jqt}uZjI}%lMo!_8cF7!b_Q2jmM!b_60UyR_jgT`fAB1%f`wO*EHS_ z%62LjSLE>z(f+Cg(8%=FV85{j_d~*Kxc<|)25^CcxnG4#__)dbx^lgN<0iguDXa#3 z!F8eC9?JbAzR-SZz14skPyI-SJ@%h#EDHRwSKZ@7d|opA9Jed_0x!${!B?O?KfQ1I zW54^$DkmU^Dq`29^ViS76uZF)G*6XGLTob29CxaQAlz0}^W%y_K3 z^2?XT@4oW$s>iV`=1KlQ_c%+v&Ov~$reXYZVjr*KOwen+rPeR`s9buxJv{Z(N%Oxj zJ~fp2)qp>DHPlxyFJj;Dag1EU%aXr|_{^OC@;~#rdwio}pOO^*ju7b$UFUDU5WZcR z8wL4Z!u>_4f8HYwg!7V3ai8IZr}pF)V3++l=F{dp4(Z3#@pmqT@pC3~Jn>3dNvL@w z&Z}H;;Jzn6m|vI3ez7&$%k$v;5QmV)U&*g4I}bxVA~*2kn>mg9UpwDDZlN7HUZ?MW zyFNJ|_mk{NPvG-AF7~}8oRI!f zjj!CtC5GQ~G;iQ>p#GlHQuAkUe+1j-x}LIlp6jJIitkkk=M49kM}#L?TUc#BwP%y= z?L9c$?|{njls|hiVqGrvuj~SP50y zOv@v{UTaYvkMj8T=0!k*kG4CzjR3fjXiLEy=If%J}?Bz`TodtL>wXY4QCb)sw93#N%2T?w+4nT(3p_|0$We z6UN6Lpzi{u-64;45fUH%i=U@uyDZ!Id`#AxBY7Ukc3nBVDP9j;0`n=eD9CW$eSX!k zy>^H?Z>q~eoHL6<9!ElIzM{BZi)`$k_f5oSn_zb+%6YSgxyKFT(8_4C_aecN9gy!f1w`aBU?N6nwd@2`sD`D<-oz^9IGZ#=#1Yqvf0yT9Xk_6)V( zq_22t|Hd!)I>aG}-$xiVt}k#Mlp|ul*&H5+GI)JP_Lv2A9+&O|p5$KY@oG%-7mxY@ z+`bwf-$}ntMqXFjrNdKwb~|;yvSxqaxW~S0xgXmbuiBN|U$QGTFN|AsTXj4MC#56s zwZ*tS)nV=Ng*H{khxFE`aQmCzyPtQdAIXHHo~LCz|3&dRZdAO-i{W?j#AAx@L*f&; zUDm!l4&{`)U&PyAnV!buZQ{NOb-WKK9jmq@c)GgY%bw(`+|SU0JPxro_fd;(#Q9R! zbG~|&+Zn*;T(-~m70r8j{~rIAQ|Cqe3w3=@Km4Q8)bI*mGRSd3TyIf2lItn8c^wyd zhxae%c^*`s=5Z8eb>+qLd1|ko#mA$D-rHo`lC-ulwq52?=( z$CncB*H{?B<01RCTTY4f+s&onej$kKhZ57cf7R3Q{s#9w2~Glkvbb+-Aj{)Q_GI=^ z`ikB-M5|aX%!9*Oi-(K-_8{@$+{M zzspHX;dW+{d_L)Tb@c&}r#c+f7k+|xJBM*Qs9nkwt}lum&hhmd)aR}2_3AiEURka# z+_yNS@8Nby-n7TQYZ5VZThuTSIKUBw$+DRIk{3)E^o{!ck?r|gj_?$d$ zRIihPUHtLZzT~*@_q-hV5yuUmvsCf9cVktsr-|#^QfK>%fAbxFT+-R!wNZQi5>Mh% zfBoWDp81G8~#&h1Rpc{$z3 z_uNJh;#0-<@rXpY9JY`+Jp> zJGtkFw*Tuq9_c==R|t#e7NoCo2lyMr?@|*rf5(67AI9HHa@OT`QhN~h)uOVOG{yJs zc~i~n#UtBeAM?B^G}}8)6Q8+v-}+I1FPXvT9RYlPlEB~BrhbvTd4AeowKra+YoULB zPtH?Vo|j1<$zrxWzvH+LIyEPZUvw?^>$_0CJ$|w)brA1Y-;9ql;VSP#oC-mAI|wgj z_9>XZsa4he%Xpn%Y5*>Y`{k5Af^t0rb|wFWc$DyYU-E19aUr%b9*-VU`y=gZB0hQ_ zKTkCFh4@r(AFt4Ppx;Jmj|lz zWOO7SXR1%^td5WIhx@!JiG6BH6M#SXs9F!{BWa4~km)Pbc9@!V0;vG_o4Jtp%WCkX zS1T8Bx4Vq{s79x%$1#t2QpEk{Nl(z?`5D0P*Q4`sy9uw84Y5yDdKl-`^$WiMaf*D$ z^Ce>Qd~;&le`f~A6MueT)H@99uRq3l2q$GsT>ph}f2#C)*k3#sr2aYaJb>zT(prGW zHMAV?H#~mdvF`A3Eq)659|?fJal9XlJp^%ze9!SZdvx`|CH##a^^Zl><3a5tQ9-p+>ce&o=dP5R$CW&a9?P`<$hL=54C6MJ&VuhNYpQU zC$}qs=f?o9Q%P#p<5U0CMBbn3|0x+h3Fc{Yei$!fdw<6jvM>D;*dG)7hLmTx=L_|( z-|s#yg!3yC`+@z1cAsZ?D2QAPc@;afz4$anw|BfDGfLvUSQ&rkklLlRrt$e!(cC`< z7gpO}T3CI3NO}q@^E{0Y;`#_@TYzg$SC4yUV2Ak%k5B4rt|x!5+FsJO(k>G~K&m_e)=@w_ejQ#p5&dz=Utj&fXTclCG>K8gFK zm*?XCQ@dZ8*_p>H@B%MOp8U;VXL(VGPwE0abBt)DCyw3ljUeUz+)+|P4lf4T0SuY~g}!)F3t?pybK%Du_+q9N`d z{p#y4uKXs?$MD+jc6;e-{04k=+}F?xPwh3${wLNZJpUb!eK3fxqPhN|_WYxe?^$tO zLhU4Thw}N}xCQ!^?}qxs0lc01{arG380as0?AOu6?@A*hxP8H$`1oeu<>Rlj+s5~R zx^}V=Rt5IcRckYSwVam*8{{iYVZ7= z*qY<(c-|s@DeJ=_?u8NR_}9dK6|%oqIkJ#?+^AnwbDu`-b_RC&;Q(fJpYI{@;h9=sE2ycshJE%UrHovaQ zj|aZgTD+d{hIr3F^~srhUSzg_{Bw=~yYeD$0=N!1_@LTe;?>FU7Mi$-`)^%;zx6?% z*S&uEN@5>L&wf9<$0r$9kCP`a0%8V?n^EQQ%si={=Sg{gnsc|$uN^vEaeJOugsX^k z>{Q=h85-g*o~eEP;esct<0$QH)Bu;p_XrLAt}G_rqs6ZQy^dymSWtY&YS;MqWHK<$ zg*_my&gR08#nkrJ|K#}*nuX;s=O@2H+o+}9#263@PY37 zNN-X6o=fC$?ib;tEc#rhEc?lFdI)O=56odI!3Xx0gmJ;seZue1Ld7{4-)^YIJ%j930cuqU%G&j+%XWM*~se5Q6O za~A`z@eA-~eup?#alN0!>&lrn-k5$F%7A^lHe0Xz?ElB!o4`kQ zRQJMnj7`KEc>%;?++!P%4aPm=O=j&LsWlST(pGE6GD~i^q}FsZEvctln$b8A+5{72 z1DP#?B&5w2k-Q}00YO=5C%{vd7XbhEt9g^>H ze{-kQ|NFnEPMunA?RBY)N5*Y8{rB$pO+R^W@3Xwbr!{~1F74L;mVUq19dCutx#ib? zR`MHvDt~WU{hqNNnXXu$a+k*2Q}X>SYNxDUtHZteJ=x#J@3UK9ck9W|_v@~YKD6@I zXkJ$5-^p~bXzhR9{D`ze*FM+Ha5%GX(fV($X?dG(aoeByQEuC>y3<`0KlU~4PxH78 zXB6MY(<3q;+0S?Tz4$emPCCw)_8dE_!?XBgT@EdOUGk&k_kC=Cc8HQ=JN3O# z>(l(ogG+Z^G=5#a-yNP+Yo8}ukEO3kyBGdW{$_p~t)of&v->&oY`62LWIV)ondh-k z(e^GMl;4Z4U)1>4zwT_OcG@4x)?@2k4^2F_|GEs1?GOK6|KQI4wOym1*RAy6Y+qX#nnt!0vSJ&fYd^P?}^TvKx=hwcHe6Q<4mKRZa#U5~%KZ_CbX<1HsO}>}D zP3pPV?_x9?>)}iw6bBxwoFpu5NcggR}qV@e` zp6zbD*=--@Ez>wv?LTC`;pbgf5I(rGoUs?{@@w;5`?L4rg*(e-J@)Hv-{#ii+@DK3 zE**38cJpuTMjd}`J?{56Z`A(OX`blX6>i>c{&YM|>bo2N!9HKM=7raG*~gjviBtW8 zf3v&#I(NJ#UbnyS)JCM7=KOx`DBoxOY`6WF-07cr?U|jw!(Ff2`8msBw_wd{VEo~7 zS6{95+uUV7RLxp96s1oiVmxqbmvO`>d1F?8P3*C{JlUSyUwVm>&v^Q#ozu_Cx83D( z`Zsn?A1t5U#rM1A@blf=jq7x{7wmnvenY0S_~g!dt<%1nTfZdpL3v)vVSUDKl03!> z-B)-?iQ3ES%QyS9p^SPv@q#V@FBG zQ&&ZFDDV}I#ollCLD?PmX8JD~L$yGF52?U&VM%@167gSKak_ABD|*=>KW+n>!&iEq+4F2A>%o0!?g4LhY@e4A)#lJ4o{lYKG=eB?Ge|76qJF~xZ(<0Yu|E^p6U!AMUa>jn2f7d@v z`rqM>w+>pb!F=1@yjg}Xo0Rq$`=)$uzrWYtOLWfi_6MZB6A}Ho^?uTW>iyo6+~H&Y z%kR|BJK}EM)^E#j@q4?uvB$aJTYb5V|3z9~(Xi&jtX=Mo$4%>dw3{CMympE9ckD54 zxy-ZO_7_Th`T0u3cy?iz_9DN(o7?wncYI{?8sGYY+rGBkrZxV;&o`+5nSZbT%l_=b z@3mRw`udZkUVSgu`Jg>wT`J4j&D~yh>$eoKzH{+9xBV9Xx5U@qtbcc1FY(>c)Gk;da8^Me$H-()gD|psnh!^&4XZG`# z56tT<$mg|)^(@SfS@W&p|MuYO0ex?fcJJ8Oo1DJ)yUXc~Z%BEpukB{vv$K6|{=@xy z<-_jq?APCw`?Q?em)+$b%j^5Yo$b{2TRXqsWsRe+{?vohKTZ0wUhCFA%C&FkblF_i z`65g0L+01F^z(C{mFbtCucj$K(LQ#yJ{j(=Z_D5O-uf5hcboCOx}9Ipa%=C{n_bQk zfAI;@?u+|8S8eqcce-BuBI&codRA?h^OV^RZLiefJ2$4?=3RRWFTcN6cZ13|o4@&Y zGXByXI^No?dCB}<-{mr1WAAjQo30PL?Z|T2?fYf-`&*yW@3+%_C(LKJaG{K6#@XGV zdRQm#N5BsrX1DFqo#U^M>#3wi`II~S9dB~u8??{zs&(#L=aaR)&V5I_>HjI?ss2f~ zysfj6_fVN<KpqXniv1UgVT3&Ud!9E&W~li zn*YPC@3OT&%u;NB{;%Jz!^Qrv8>9YA{@wQTJEv#nvD@`MX&=UIx9exz{ue&Hzi@2b ztL0?>Udk)bIj-%V#BDwJclH(g3+HA;|4m|5>VNL7?)YPW*R1{P8DEI#r&@ZV)H6OR z<*$5B*R$52FL9R3ZsD_1PsXF%xV5g4d5fQRmn-qx-8jGZ!@3Kf(&4OI?XtG6y`?|) ze~tJnf3&l`n7>K;S{J^d?YAB=E}UJGdUSl#ZSU13x4&z&j-~C{I{kLg_zdgOLGu*X zXk29ZYAvV3>VIMWgLTtyamQns&MmBc$sMkmHBVx%{x3e?onJd1<<=ugZkE>DCTM>6 z(sepM`X12vr|o8G_dZ(xn)n;d+x`iuN5?MtY4v?t-Uf}AEqzM+lm42t&stgYRtT?s zTRu-bNB*|Mw@Uk2ZqawDY>hK5FKK^Qk4yb+IZawewmB^AI(GHW@7Z#8``x7Y+DNXdYklh za-QRUJxp|Idu~|cIGaCYzfF`L&BszYwe}B<;{ULC^9G$>S7@E=#uH>diIRUVq3yC} z?f=b~pL}p~&ShkN*r0V1ZTIb*&)WW2=C97H zWVukwx!;dHozmOCxyz@*DXC9Xc%$(8N3|W!Q9nZbC$&H6#?JOxq37+d(*75wNRM60 z-!kp*)c0%d@OEywan`^7Ew>%`dHPlE_xrvk@y65i@AbDyoaHoMB<;HVW&OMSYKb$S z-M)*Ye#>+6H}lpW*jWzq*j=M_2K;+Bci~rLxK@5g>(Mc(-S%h6=ex<{=Y2FUfq#26 zuVHOO%iFkqZ*m(np0V(II-S*=aJJv4-z$*2^)fAg`SDVp!WZOw9S^c!u3@b+we^hpz4!?C_pg4~ zjjs+#yR+Pm|K+wTKYy_9xm9hia}oQ^BqGj{DSybV=Wcow9{=Fpi;`QvOqTQOzboUP z-&=X2+uts0KX2x<+pyMeF>br<6^l`^*32w$pC!+0WDeqV2KvT(@1;tbG&OrrqVq(jNEwTE1PDtF}J;d-+Q`fA;lA zeuMhUHhx~}oBdarpIHvOg)4S`&OF;)e1;5fpD%xp{l(7dZ}~E*r!BwJTGzDExwAZe zf1B!8D}VUl!o_laRPN@b50BpU4QcO=J??v6Taod4ZkKbm&RP83?AS;9J?_Ti=ZkyX zr-Avqxoy_@bLCN)uR5*r{@kE0U$*`q?RFlQeD<&WIh|e;pOkjz=j^uavmV{K%Q*7l zkk+d?x3_e(_F<`if%nsUjh2(3_21s6I~?s*nJ*Vkxc%MuHJy%@tbN$n4xNwF^|!u= zeKKk{Xgyb`|0BN3IBegCwEisrhjkb3li^?dZ5__+Q*`)OULx~J`%^W(@NH?|#dm66 zfu7rX#qN>z-1>z6oqdrGPvbY;_HCp6IMR1&`5pg9>SOz}+wU#fU&ZES{hjT)(4+mW z-?Kme8!z5jF6*)WTFG0#ME+)8l)F48?aREy54rW-u4#Pr$?o^~eRel#UIYJL>e!op zW9Q3sQajJxo?*FB?z*+VY>dWRR=?oZW9$1mJ;iU+{%;VU<=4wnFUHwz`~KeM2QmLY z%T45Ter=<9|GW8{$hhOb>jiE+{%5j0XkPo^;*0faqy237H@jVbCH?Ps>)z7g+RHVs zFe3To<2oIzK2PH5y!<^jC4YB5My8+GE9G<6_n~rQAJ_gZkjrv6tlx}p{fE}4^Al1} ze*RFqahm`1P|Mx3JZoMdzt@PE-@?zE2OeJg#9lAcEBm`ww@&NMI)4;3yZOt{+lIBhRzJ3LdSO1h z3vb(ByzqOSJ^DMa{$2Tf;O8+~@6oa7e$G7GUEhVjYVV`?32EO=>%2Z&e))1~pNk;!9`Mp}Zj-Sov z>}-!EYd&p(&gWe^B*Rz#vOB&T*J^!g*Ghi*g)$zuEq#|>qTkyje>PsE`SDL`w=XH< zcY)Sx$B4J|S?M2#d#fbhV?4_3dWDp;S<~U{J0SIsdf&zyt5P06Z$B&XE}EawPW;3_ zNdL-zNp^jt49~i?9(bMR>$F+tFSYgW{2gEYfz)SfTmIg>O8Z;BZs+vF;bXVf=HeN?~CE_gLCdgJwD{$O%w)bHs(>idex z{2KAu4f*{;{-L;^8cVA;n9p+AWxPys*xe0h|JcRwqaCh=8||=E)$KtW-y)pl_uZ}S zz%Ju#7j}bi^(8ZYPikm*WKf0cD(@oiC%{j<(J#IbzXX2ZZR3vw3~v+nL1_1Nhix-^ z0S@M5Tf(dAT?{Yki{ULlRmU6pdkiqVP5JmY@*f8`^4sqU`2eZQIg)_IxIA@izI0cLIjDjb9BI-X@NJoB6c%c&(@J zXZl~78t(P`hei(_?xNh~d1#00;T^n9If&l~7~VDxS>MCk#Mxg=Z)pEI`HOOT0K?nG zM@+@nDBJT%-Vk7ToBXT1CwXbW@HTPZAD=Il=87|ZZgR4cuU2QLfZ;)UX1rRMpPDM= z6>8$MQ&ZLa9MKK_>71XdoFKZ+7yX0D0slyUkKYT~F*%CHLmf;zcRhmb%>EYUPvrg6 zxssOT`^Bn1S1Fz@=1Qfr{={tgY;GL1YJB#*Kn^lt+N3U5{mf`jx8I)`hSKfE>u=-; z^Fc^%rkb0WE6&dN6SoaQSJi!&$uN%WrR zog^v$LE)s|QhGK|KUwG#Cw}b0Ulrv; z0@zq?1o<7!s`H+fQnS0p2?dvsqrS`VjRsi*exH}UQ}R0__=EkUP}o4e zys#qVw>{l0ANeDhjF(MH{xW^{>-R`JZu^Vj%|P-&6Pk9=`VSvH6z@et1ojDWRUWqB ziVfv@wkq^rfP{$lX)H;+4j-mgyA7rWhevJ)vw6+toRE{S^;h}~4)^pbb-cvA?-cw6 zD*vUP>EQuQhY#jy!Ee9VrB8bJHV#)@@;fMAYWGTfiNY)W&7>fw9!Gn6_e=f;#h1nJ zAL<@f8PA2IO0iqd2>n-__Jpq&$iX1T?v(sKvS(ve;>&LR`-l3pA(~Cek2%vPe>EZA z6AMDmm@{57w~maG{JP|ik$q|h&I&nox1OUtM}~)0zB?rOS(1~;Nj&XLS5US?7RGd# zxLfj9$luz%67O`|VRWQ_=x7E6S@EcFCI8ktM7UNd9=$sy-bd*(_5q2n5x?;TiLXZ3 zXJo7wYODiZ_QIbQ{-!BjykinSM|QLHzdhskr@J8l+503vOZN2M^(rC1;noM_WO_zX z&Zi{55b19wHHiEJuNLw#Yhig(zhB}Tk^Ua*A4WL`e@4hjxZ@E%^dqUGAYa;HG)c`V zudyoSj5*Ue@Pm9L`Azb-+5Q@#&!*E3AcxAaMndw-&h$Jwpb8VTPhIlc$Zj%R$GZEH zBVZjUH$El#X{UXTjrI?w6kp0Yp1Cd4t!$LIw~NjWu=leqW|!rw(ZUi!O-hmQO3Uj}N*p7)!t zdBXvqsAjvWZ$pg~)91bSX`I_li?*KWWcMw}qbXJO0{+h=->BqV27jZR*ypvJUpS@l z#}MBBdh7eea*mCtlycx6&1Zj?NdMpaw8l|4l)w0MPf&V#TT3Fm*lt5k(Un2dp zACUMK#aHcqi5Doo8uz|Q$SD(^J@96MFO&RQQsPHh0CKDIF^}r3_7x!zj8>F9+RK_3Zhw7NlVF3=G5GY`vMF%g#l|A$} z;co&W6zys8GpW=qKGe#*?2_bn0$15Tw=CqONlr8Q4uP*xxEgm#JZ_guSP$$S7*1lV z)6@s?fnF{)yxN9UA0~ej2YyZX3&Vg)&)AJW6u>CX)5Pn*Rb=yA&* zzy^cE-=KnS$$^SBvRm}m71k)c)jq)QQ-Un{nbDC^mGxZs0JNAb96!ubPPeWDDkb5+ z`s9a1x;jVstNz447Wf9Gx2sYByo=>(`ycCc_^5YCJpOu(H@Chd+6o;p8m`z)cr?w*1qm=7~ah7gU3@N{?Q?*IKtK3lI2Vs zFf3=hH~ot6x7}54blvLVw7kP|l=MY4}bZlI86Zr4z{ys)1fDEBRR0 zL%Rw7NOGuWc+ejmIRy1>S#CG%?-h9kbJ0yQvbX-}*_xaxa#_8Ilv zZyb%Oa)I4^@3TC-j~vx^16;fl-#;hhY?HsSzx=$w`x3gGNqk=7o1{Cwur**8jjnfNbx@mG}ndH*|hjqxlPuNg1S zO;LO52(%1!Eo=yS2L=a+hg3gF^Hy1}>m+}hrzD;x{k_*pd;!9zz6-j($1OPgOsOmO zCdsdp{?7X0As9vc*>4K_)X85b|HkV*@6D25crnG-yCptGa$+Bp_)0?ahyPsHW1GLH z>#^)+yT2v$iIaVz@@W(v#>?cHTxH6in93>pgm``-KT#@ct3mk#1A#MhetE7kS)7{k z=lp_x67q}H;>^?}RH?Nb6~9NZb7nyszBxH|o2O^9L|rtnzn17$=>Efyvnk67O9G)IdA@|XWf>w)!uylfoDg7IRU^P!7ylnj$ zkCMM%oaM8>G39HkzmOg2dT{Z@_JQHw9p$h-<@Z-#Na1RQ9QzJYU6YTT5!%U;6w}>Hnkh_c2lCf$<9WwO?FIX?E#xh1z>` zzFVi?+vGM0XI}fwnxA;D<};6VsuBL9vfGdS<(SxSdU$yGVLfdoHxty-P}lwWE9L0A zybkgH-MWBf5-W||0wd* z)MsICZWb!(llaKyWBn8_#<@Pg_1XEsiG_vhCX1(23)nP+ zb_CBetWM-g?;{I+le zS;ilHxlx@f??FyzPvFmlFWBW+jfx%Lub!Qm@bTm2<2{w1n<)6$s&$u3ru@ppbeY2? z@i4pspPYB|XTk@9U&_16tGUVy%qq@n&jo)bR7l{JFk%E=opZ$3RJj5lDNYa}zdS!T z;m^-NpUBBPmRP&lXX;F)IG1Pp?9NB|g&Zp+{H=!mhInMj*#=uQ6 zMtVMN(t}{MKToeON`F&-uMIguAx>}HuIKNj$u~U+@nSVsnwg&_A5DC`l$$x}z$a$r zDx6VG{)tMi%mt{4muAo8TkTw|mf^!N=a645=O#EJO*!*rm`vZopPS89CyGS}Zu)E6 zhx<27`DYA6Sa`XR(;f(XvUs9M0T8%h2!X4Zx8*>c$WS!o>v{zR%Sb1%&cdHPov%#6 zTlmzSFMd>bs6Uh$<_F**($kK|HZqWnx7I%=)OWDeo*HjW&l9LV7fXiyp%4p;LmTJh zyzh7k?KWj*Q&YacV{dzk=m%bWuI|^(enjG39fW^E;!DI2{Z;j}AiVXrJypnu;|ElG z!N>Ik{%~(EOnHYTIW#K{<|o{EspR((Kd2`|Ib-D0#+NS>`~t80F!)CH@*XkuOfL=n z*O=O|AA7B)*IUN#qIH*aUfwG0Tj=|_Iauy9K0lZD%k!0dxPFK0?ZxVX;eiiJg>c=G z4`t6uKl~6H_L-ICPbhz8b_Nm!F17I?zB0GNl-Pj*|F+?g9-L*UQ(P#gSUqDFtP%Ob z_Xm2848V+wp8k+A5SZO`aI2N_qy+BJbn$uE4jXZWZ;(W zAy}H~kNP;dSDV56?eE;G>j$?EnCZ50rw(8J18!Wc|AN7$o{X(0r(0gvHie^lM)?4vRvJ`NaI<9(|y;q+E= zzEJzV?wupm}AN1HL~!JDG1SAAEnNRGc~4@}T*Hmj?MlWt2WH zHzuJXTxsF^KGf&n3vL%cgcm2RC-vt)O@yoQVwOKwoObA$_-n~8Q@NCV#ic^d0^wi> zXgbf%Ov378(-x}kglmjp9VxC$)w4!m-SvT2sPE3$4Z6Hyx7PP!A%BtN*PfLWxR=oS ze?6w_UG<@dT{XmfAzP`?X%-Z?l8# z=6(a#O@lpQIkss8&_m_F|9fg~mur3(?9Twzz`^90xyc6Ty5IZ@dX`Q?!`+TY-=C_wp7^7E zFx$7s&%i>lR1bZuz)G<{$cu1w+@kH1d(xD`dH%^Vh4;=iiPu9r==~7VM$>&LYh2-R3BJuWXv_5yfRN|c^r}mP9&_7Oius;LqgLN>_=f2xDKL{7` zv#*qLR!N`w9TH!IxWal!;};~}L3%bnFYz^!ll_6j8zcwX1;gF9_{o9(qeFwKAzgWZ zXTCo?1PkjOczLb>J+za41-coaV9Y`1oImF!9&=LIAraVNqLk0g%$NPCiMg;11@c)= zsaSHZc`L z0iT}faerdI;!o$Gi4kRo|1P*AzEp%caAk-1f{fj%sbdc@-<^K;uTPYoQMlV*oSr!g zO>t3K0!u{M0cso03Kq2QUP zeK)JcJM5|;>Jt~&ycz_<@99*r)bgc`FCf``NAqhx?+bsIxcq;+{%&%9T%__U`zf}f^xp6$^5khTN&qxya!cN)6P=%W!7aLng&vJ;I4 zmyO31iusrOD~dVT?y8(SePSGESvc@B4t(PDTy^qrwc5h3mP#&u8SqJm9K=sK@k)f8 zN`#zBl$@MfpGwZH5A22{$KSPmaF?VK^yl05LA=n4<5+3cA!mB_v_zCnQ5V;rRHz&JSY7C+M8IdfX>oczg*4FPtGzvH4in(>HN$b6rBMF!UeeA>?;J} z72nUpplL{CVKz?c0KZymD z7`ujyB6-3^)V9V|{RR5qf8;us2u^_DP$qOzNT4YjFcExYquf_KBbu zZU^^5`Wqd7e#pDXgHM(hf0wQ=GKKMVsL)~ihcA}j9GCL_V>)?cUODhee9iwi1gTC)Jea!AIhjT&v9_c@N zGzBZQgRTbUH}pS@^uWFY1O20;pbl(t(w`iHCyc{eAqaYLc&YgEnt^;RC*1?10xX31 z*zdRX`?_D0U6d1rb39^uc8$Wd7ds#y3TA5mrbkD5`g?m-TOu%XP;PViT*nO$;fj*q zXnUr26Uaqq7uuT|e7dClL8z+Z}J#(Dk^m$^~$qi`61#2)G1WJV3S;%-VR zX>ok9{%vF*#ve)HYJ03q&y06P;E4!1W5kE=TDc6L>*5@I+{$w>lCOJ=Y<~-a&$R+S zH$SI8@HT(R(&y2n|LW_c{#e#yd?o%ue+O6&WGjU)So*V^4U!Yqm(=(y50iS0_sj9h z#TUE%Ex%Oz8x>zaDm?p+r;2uE0Stv{F7}}p2)sskl%Cwsr2es>y&1)i!Z}{h#rUex zcj4OkYUSD@OhBHW%wMazl%5NR{jOnkt=Q%naBjEa^xnfI zp@*J%E$6z!W6;T<_KF^a{hKkvMCtisT(7(Tu^s+%>;O|xXJ=s2e+j#=pkpczQ;)F~ z@L$dT*qv;S$N9s@U<%TIJw5kpx1ik6s{0ntyXQrp zRplptU$THni1-1;nyV2{w6fsV&@LR8{1j&{cVp(Kb$^V{PlDU zFwS~D(egJ47j;0`{3k^6bqv`2ODz6k;%b%db?M5daq6t< zM>OP2l{oK`woau5&tGebFWtc0)w>pxY2iVvSs zVaOM18aPZ}h4n;JN_#WjHQpLtjq{S^ARjHvRydu@`MSi{%QOvtb$`C@g*W{z!nh)8 zq!kLotM;qGSz5}V7S8G$@)e)exA93*N8mVvn9N|~PC1z5IH8;RAdX{kc!fBOXuvoE zwCkZO+8h@sR!eZ4Na!z>4|>5I=4}`qG399f37G4GJ;#ClL;m$Pe||=Fd#ir(P@mH5 z%n2CqAdek#ta7QGgLP+TImv}`G|mQU!Rdj4&z2`<=Vw~-OPO%J#?s(d@?o|%?5UPx z1_g(uKbE1E{zhgL_JndjG=m`@mO4z~Tt01}P@j3|oX^3OPdzjf;xK5%iCM{)@dzIn zD;|N*gIPi!WAMu@$BN(C@mIni2xN>qP*uwg_+hi`05enb(@^&0VczOVBfJX7rJybx zXGS93mXAptd^OW2e2LYH(n!9KAHvXX$cL3ifqX8<6b>sg^#j4zD+^onJT35vv#`je zGOOBxIJN~NL$HV~l+$|*_Lc1)9#ZPt;eyhPaaFIN+y&O89BJ7ZOFxQV2Ona9>L*eT zd_7xmOu1knCk{S1aYzvkeQ4c;r4I$HMGgc&$4d)e1>cFz5riU z@^tfE;YB&E;YID$lq$Es4m(qfweS&F@+~_c?uswU0WES62g|wf>mzWSH=_K-RE7eA zk}piR&{JGES@y?gCMV_tI}5&%ek88!8RjpRQ-YSX%U>hBm@0SG2TE9$Blw0s5)b27 z;-UQ|9_Ay7hw%cDB-8|bR4Ac-R)Mpu{9tJth1cYp>0jWWCddJUV;cdc3|0Jb_<&7P zeOSep;2Y^*;Fv<$&LAvM)UXd?As*UC;-P&c9@+s@Yaj z;-Nkg593SXp`I$2n2M4<5(kCcc#yv=KISisFPv40@ing^Oxr=lm)TB4nB|+eN)On+ z;!Ncb_>Du2LI+U}t9GC%%R9Y1|pcij!lh9*ue)^D$-3%!1DJ z!1lLE*$Cs!u6FHh<}e9IwIWcy*4l z92%bu_V(7}Xu-H`rf+yeon)uq3;k8?pwes(_Go~dWc$0_5?;kumFEJyV98NI8J5;EWjZ}m^k~3-D2o(o#KUYNPY@$Sm(ep?!89qb2+Z- zhM7*+%+J7l;mOP4HFaGMJ1JD*C`TKQbxsH68~WP?g#(rk?C-VkH{$I-qvc193&3|) z&G(wqtH-e;PWc z$0O5Vy()h8BiAckqpSwwuOHR+Vi)G+boaq5Y(F`a>G%75lz|t-dnKPglIihJ!mQ803QwxMhL09vSiJaXd6r&g?Gy$KR;=B!!NHD!$q6 zo&Kc4+31IeSA!~ReT=H}z7CX{uR_Z;u> z;NorSgMVXv1HU_{Pc0~~!ZmrgO9HQ_!*g%pldf)44&pdQgSU<2m=WF*zsS1+FuWyx zu{whq%K;mI9$-2)6S z;`Pj*2+|M!Y=Qx?yyEj=VO<4m8^*Z{&d)aIML>T`F*laQ#}a>r*=&4Z)vm6y-=68oA>klZkwTHu{}9GU_Ama#yMUXk4jhj#clbQXm105 z*=|vI-QqWXz~R&nSU%&dKjR${e8$;YHa{w#vivAJupG8CsUL)QWmB)mwDUFNde(Uu zFO0+ILR~DMaV`gJJQl&navd+5Z`+^sw{cD<7i%$r9LD1jcp?JFz7V`vAC{BWa0}iS zfn(bRFI&!>hFkF0S~#aej$d2O&su!eb14E}jKJ#=_;Lik8iB7w;Ef1;Edt+&z&{p& zpR;hbTNGZS4950kemp`>BZ8lx3<>Rs*2N)s7@{42Nm)lezR=W>bdK;rh{ zaEZK+SAGOk4lkDjWS-D&-__-OOL_7gd0s;xhj0$Pjq~>?>bvt$;p{KRV}fjJvaZcI`=2`Y<=Diu4^Oy zp&N}Cc->sWS~nM^ry&P7+6&f|(0Y>=g-qP^*u-1_qZ# zsQoNel(QV>Z&81djkiNb2g+d_UAz{^U#M4rY}le*ZFdEml;qCBs6)tS`P&ilJ;?A{ zPn0tcQ_XREuM*5ts^m%_$@aGv5#Dx^!+iEPCgfLgGq6~7940Zs5U?7t*ZN~W9?V&U z)wOxGIy&^1<#a~LC;MnQfsK_7Tz2Rb{0eMnHJ^vcOECRfFXSeBT6i_E1M3qP;lhbs zMKwpiqPA^l<#$=}$Z`@9;p!9eK|%l2Ja{k#d(b%JH!b+Ugx;sQ{B*el9i;ez9WPnI zKarowS0DmPx#{uAoQvOp4tX;jvi|E4csU|m3lVsqh!?f7D~w9R94wetfg!f_uSLjN z6yeG*OytXRFg&1a=1LFgz~7@|V=%YB--m-{Gr{zkz+bGUV!qz6!pnF)LZ2}!-Y+IO zowObe_k*ItgVio!J}Ltwt@v7_)p5H1>@#j5YI!4y1J zmn}bjmz2+P)~)=`_=*)?#y5y>hU>Qe9$3?>L&p9xe>I3NUZ-iYLpw0P&9Xn^wIIA| zyaVD=eOmA%G33WXIasend#+jfbG)?EdOg;Y?cYhb`tIPcr&JTld80mn&nY4$PK(Px z2Z0;1*k2A;!_qUzcNWg;7MoUjVE(3MHxAdB87{6@2>pZlLzfw5))QT{XETV$fDhl< zP!RK3pG6~InEUJYeM|QX8ubm36B@|CX_Ql@E4D)nIu5wJ+C@Idamt5kNT|QzFW@1c z!^QEn6r@8{521QdD2Mr6ZfqIx=+bjycJ^curZkpjVd8(dl?B&xlzh|BDBmT=tY4Xi zV|} z49y?#+5Wg4FULF9-&jt)MUIH}7CBjx6NcBcLRg-#{Jt?=ehPkso}iYuN_JrTb9(R| z$My;8v1arJdLkdMF48k<{P)V^S9*9i>Gp2B(!={2PYnaNjPs%$@hX2*>%lJLON6t_ zIP=(LoX3yZ4c5)Ud?9l_PZXbV_K)4BceB`!dJGnrVZ2B28E5_2WxVjlC#(0_<#@sI zK}@&xpVsX{<~Q!ve0Diphpxw?W;3HO2Vw;6h~u-U7pFSof2s>{{AS{9^Re#; zZyU!l9&d?1$HP8 zrTmLMToZ@4jduWsw~gbPM7$+_k%wy`@iuY%+iY(x()c*q|1x-n_fGsJgMSdXc$<8b z^9;c7HgWvh^mo~i^DKCVx5-C2&jt){8-EU9cuV|ZFAf;qHhu^&yiFYIMK4Va_XhJp zd?3JuhY$+Go8-=VkQwh42h-laF{e zV0cTs-Ae(6w~5>Gm!W{cvI0-RJqj+~CLi%W!0@*5mjH&hjo$(o-Znk}7~T?pk~at# z-ZnlA7~Uq1f1CDcQ2K%WV@Fb>Fo}(qBUtr+d=JaFI20^gHkxu4o}_V@_fX~T2y?!K z!ppOzv(vMca-lc@;?$LR#(_W|1wa5%KBTMBo^awIr7FZ>0`*K4=1@Z`5jp}&xdmEJ zgbTaV!vV!@3)aVgKadIrD zqCiiyLlzQ-)-(9-o7FUBbF|MTa3g;ssLup^Q9ohx$1*wTvpPQi=KaeM9+e zP>`DO!gAs-lkG%~$5o>~Z^mOg$x-tI{nYU!Y=)g0?Hks+dFr%e^4B8dY+WPuVSfwo z@iX;ge4Fx-_P1qvW?)YaFJ@S6f0#e%3HD-4s94Zd|`jSm_F~ze;cCEPJy2z99YR`MP407I;_huik2(5Es*F1N|`^ zn9j$9e3aw159_l`^)cHH*+7n-_iIg$1w8{?BrKM50qL`8*@5l0W#Oz(!Lldg+ZG?c z%NX8xS*AnA6Thr+(leFL^h3v#S-vU#tzB}$^uThmG+&qGv_uStm+fD+^k*C^PC7p- ze_JBPma`DppXWczl&jJ|mZ(<5n7A1+0Uj}*neE&j=&Aj+XO!D|E?VJbyKT|DYxdWU z0G5OGE{w;7Sw29x?1*7Gb_B2-bWzTdWjExTImYI9P6`!k>I7PI6q z-a+%*136ZS!g4rY#B4sqS4%vCK2h<){;rsI0DhGHIleZi+-5y@vs>IuCm`QW&`J(0 zu7*w(VK@#imy>H&`eFUMO!-QVOz4JuF+rc@bNSOS?V$A$24z0me?3B3?1lcC201S<+NMhO?-~&x$_z>H&lKci?S!%En(UX_W`pC2&E6>M#2hlSwOI! zY@c(MeK;QL5#N!f#fRjr!d15F6^y4%d!n9}Jy{GN>=OY1x2cn379oj5d}dA>xj{|`nqT#WNRMFajA ztMOtvj3*Qt;ye#rRm2QF?|Z}ZuUHQAd7pn9_iEY$#(Dk>d0YEO`Xg{Y`)I0H;QV}Z z++WvqTKIpb`PZnP3a_QV^cvM8;li(1UUI)DyVt0m3Kw6uFqy~hHL3^0^SED<-D}he z1!$)&>3&FduTec1P_HGNT{~Z|QN5jUE)Tb?@`v#iDz8+zcjNW$a#G>$@{qqTV`h2F ze4|`teYpI@g(N|{4EffFocXM0)|S6Zd6eQC4xvC2c6zhZp{Sx!62 z;dHzHQ`oZ;UeJC?byE+3YdzghkUkxOKALX@H)!whxLeHPXO11gCKWczp~Bz?e4wfD z#_nSKgM6&l$!Z0*zcenRJ&?oSyEysF_Q7HV?HPNwme2T;2+z`ZG|P_)7u%uB3>WAb z6)sLEX_N1)FG0At{$oTyxDFyWFy99ih)kg#0>{ zOB`NKhhq_P)<{m+ACBYdt>dI9594|{_e`kc8)xbWy-v2~ydOA0yj12$T z;VP3IYr28-``Ihi@6n^eYhlDTXIkx_|5eSo_C#4?64lr^QEae zAJp3!CwhRhoLYn&uDjU&+H$ylj`exCUc>yt7xnsrn#Lbsy!}fWf57sW`B3z!i}|c) zRJb^vna}b`j934}#X)+*a&wU!(jL`~42Vj}brdU5R%R-n{Y2g5OMOeZqQ6v4WfYaCk$!G?6csf^x&a zC*e367hbBsRs>uDGWZAw{OEJ&qRx+_eYDihCwlKO)HRepk9#CJ_7PS4a|YvXAs=S+ z!nUau$aoV4bAQ6g33KPjkdOOS^65mTzxq&~R=b(II-2~cGVk;$^;i2hI`&a4R&lc* z4nU|6;IkF@P-&k{ocBt!<>S7Kd7Lf`4?;f9ZO83SZ8@-?C+sDsPwO%HdjCVs7C7x^ zsCP^ZcR^*&|+9}2f|*iJ&1 zxrV=x-*Z!~`5Masg{v~!DPM*c_;a&oa+OJZA(UU9J##1?l=C58$xr9tpg7w3sYSlp z(G2%JWBmg@>0{uh=4UAyB_DA1SjYjKzenMIO?+l2@7EN_$Il>(G36u9VhkKlTpJJg zoc`Ob^Tk4a6u%UfW9%>CL3!S~FCwNlE-U8MX~b$uiZVrceh&6%g`M9lJoL9%g@dBc z@WxvLFXK^o+M)ulLLr%V;K8nfX1s&^1+_jyy%5TQG~(oo&$VGsv0b-;S8;F0;QP+? zv@)$r)mobRK!U=27vvYV^9<(;OV1$vs~8CNSLxXi??L*s_$nTQjg><=*rFL%-y-xF z>zgVYADPBp+#7rbno<%Cn0 z{LJvNk#49q>g%ggK5npsb^XM%Zc{%NBY-ql;>G5 zQ+?R`uEgtvH|H-Ec1V+)*t4E4@G-_$B%UR__P)ymKStpS?FRKo==fv1-T7V3=l+~d z;>X^1P{>&&J#9Ih;9{S6Cd}JEU!@mpcQo$Q`%A@+KTFLairszu_Yh|{yKt3|UnBkF zcj@=MCta%SyZYPux9M*cjVb0s_4(jK1B^$@3D(%bf!?^oy>1Ix@&o(e z{=KyB(Z`M3xaDNxGjM!p3AQ7`XTA?#ni(kG6d4a2EzM~>S2_c08)3+XsY+EiuTz~Y z3Qck2G0K7Ug>$&gJ};WkA@ltcrQ-MmmY>Cw`O;YqukYi|huC)po$hK)!ZBQ!1#+Ov zKrPXtJs0tOLU@VhwwmMES<&%d7X)YAk%`+SjKQzwbayrB8OReVfKR?s=NR*}dvB#Q!yo_mO+m zm)*GCueJFYUCzAu27Ru5{2Cn(?7lfg__uU^iIaQXTiy7{_iB8b^k+BoakuByB~Z;1pfv%--vfOA1xfefc{(PV1lI!JsId_ z4r93ZRxM}ydwN|KyH~x}jr)E#ZUxuhBczz$9eutqrUks-{29{UvOlC-JhKs|Z@@;h za0Wd5f>E7ONT2+Dr_E@!7{L3nZ!h4(FU7CDEhEaw^--N38lRAOUrRX;@^ROAl7GcB zMwOiN;kPQEsl5HU4-a^Fzx(&~edHqp9^OJv*aVlvct_tmsP2jP4SIN=_nZ0-`Op}I z9v9|E$&Zo~#m9O$)>xp^8xKhES)twe^MW5WzvA70{IbA4sQWtEr~9uZo+dkY|AWNa zpa8}CKxhYSbr-1D*z>-A@5@!b*nGCmN9;m*8?2vAC;La(ZhHUBBe##HGPfnuxO1ky zYNvdW9yUl%>2I}c)Z43Pa%I@TZw3~r&&<(w?5L;2sfo(v&m+M*Oeb-ghbiRa?*F8Z zg$L>9@K8+y*S!gvE%@R=DCcz5d=TQrYOYi+zP57+O|@yMGC^jUJZ?h!k{P= z2;p!j*e749Kwm_03O0E-0X_J1^bCFPpqoi`?EB-B`k;3x4>4i2eDC_7pv!Ik4zYXH zhc(XSBfIaP*X0}Y*nRT_8D}{kl^>(>`_QX&z8Jefm(T3tJdNSxsH)ZI{hW1#eZBn^ z%HOpcHJ@E!|0y_w1y5>)7?`~GpHzOifa0<1Le8f+jt1LH;>j;iN7K?Fz47wvzU1+g z-*4pe^gkCUUYM^EWB1tD zp+mUo1I)+zWJ>T?DZaQILl?`RZECj~*e;z*p)ZZoc+dmBNx^SR7aihN! zJBMHg*%^HZj^fk!2yAUpz}-{;!z(x^g>heh!CLV{5q#9rC8sL_M=cFL?s(51M-$iM zIQ%&c_0+glrj?JTQCFb9=4)l(iG^!rOdNZWf>TBeet@fE5JEX2t_%^#4{@cF16MjZ zaHUg#V>g&fp8)4`c6j`Y`FLuJp?}Di^3B60On!jd;e~!}-5W3EhkPqs0bly7`g64) zjLaas2CmaTh0DOvV;3JicH!u8faA#AiWLsVO)Fbz^(ih z@Rhd?zVgOR?R43A*_E+H|9U8buhXyXvp~f+_ke-yzLtLh- z5SQsn<9s}q9WEB{z^!z}a9lOe`nlPebE|enDrRI?pH=!2mua z0UX>F$NQihz-M4k$A#nkAs0Ra8>GQ@?8Z??S`KKgz*2AklEn2nJJ_Kn@qkV^pUb1= zU{2z5aBu+GJO@YO@C(UsNnC|d9k#=`I^fO_#JD=(E*cL!V7@+=Cx8QggY$YoTYL)P zorl>0#TnRV4$kGF(Rwp}5wF6?4|KPx{K)*mJZ$v_`>35#;R@xb^JprQbJYoa;KIwT zcsU3C!4Ccuw94}{r(5Jql_nKz%SV3oOso8<8JP32(2B!}f;z~So>L1reW8^#MNn3sdpY(4zUs&r8-zrOv!Y9E47hY`jSMiHrPm8b5U22t&I39oG;up$p ze#wE4SK+i7hn)eRbm5iB^0YIZ&z4R(`Lm^h8?R_S?_2BrZ@Hhq7$|iSDn=LYYkLfS z<6akhHEF-wK+cAg!{geW*0{FlAAtUu;;ibP3EOL`y+6l?J!l>AhG&&Z&96gzZ6$l1D(`X!F^k7m>!phJE?tRWo5gOtDz zIClf4NWfM~MJO2NVD2V)pmAuyIdSMhws6jOyuPW83kyf$^1_{pD0S7|J(598-GUhBh@KA$Gn=r7obxJ`-SZIh2>W2;(hN{?v5#5 z`cJg`f15q`8(yn?NRJGU4x>R6pI;RAuaW(sUl-@`-iE8J`8+H=zC4qM(P^j|P8O%8 zg5ePl2R~x!zxf%gDszvc8c%_-(n-vHRllHP5y~0f#?mUv!txCccZ2hi0zMv{rAB7) zh47h=xOFBLzNGMxW3bG};)h&OfWk3ZQ11C>)TE&~L(f2lphI~M$LryCg~@^bqeC#@ zMi{~N(yA-?xgiPw1?@F?~)!#_0@ zKim`6KME_Lp=UcY>K_@n1tU%y2!Q11kz>8~gNeV;^3Mkv_8+d2zrXc3eU4cBTlKg$ zyZK8sUb{f+&+g(i8eiztk?Ed_#HNG~l z$5+@z6Sx9g_;t-+J*efg>%;I0&hmhozuF0zl8@&fPeOhJt5G6n{F+mrSN-Z7Pwb+< z$A&rR!kfv3vL`w|-G{_`zJxnOE9my>vc`0pxf9Hu9! zcv+)(|BEe+2jf3PK|iEmK)LHqQ;7K)?Ldp-0_h*(Ns_lyysrYUm!hEpYCHLBT(ZSxE)^_)rZUVd|L9iNWORLNl|}Wf{H3U^4@!& z=JUA8Hu3ZKOB^@vL;f=k==15Azd_+eefWI3;nD8oP4Us~6em z7&hdCtLiYvl`FCjmPcz)vDj149#v=e@huUcGZ}W)qXEmE4pE9;nl+Y z6n0nG?RV&Z##VY5-Zfe;X0Id5ewog%p$8l;=EJ91U5qpT0eZlA+gE5k+5?i$>&`Gw z;Kh7iPsjZ;jI$ig4*499fGbUz&p57`Gv%|tF%ral_7}e=crhNtqlN?Aqx0Pet}&l+ zT9y~A*Gqqm?5SS}_1ThQA!|F@?hVQ&?m* z1ziJbEmRKntR$S}Grz;aS$-7WAU@10JMHJji!rOdCz?z#Xo3)5HAkTR5R=U*M>|Wu zR4qWiazG9R;dCA7vDHnp$=UgFTC!({YuySLhxacmoWpD5oi7jKMdU}uBlF{vwFkC7 zS5iV@{M;4#T*wEk@`Q0xvnAe_;Cq1=%i(ani4sT&vWI>$PeQ zT+LW?;Hq`+z}2EU2d>uMgg8tmcdiRlxWjIMPaksFP2mpyRBqh4{!Za4OlY}KAB6`! z78V{X6tr;1dLooF87xqg{BQxGg}eMM&CXUF;e}FqmS;~2{VQMz7a#G^K0NPkI73bB zj7mVEK57|I$PdQ#6wcc-z`4_7qMpCT?FGp%@e84R9`Cc$C*#^{2VdFLfm`X5<>=lg z2j5Dc0bi$2woiBZm}wwG&e`&8xNhCT9d?7!Z|8b>g}eAFf_1Jo1VbpZ6w;AP4&7kq}e+7H1YA4ZnVd>7=4Qbhb}JkZDDvj>L15$p9z z3U|m68QYfAnomg%J+S$lu?<`qLR-zWTS;sfVe=i~5(WzT?Q#BRH_Sg(eQQ#_nK4ZH z3MUUt91{fVdFD`7%@^%Ba=B{CvTO4l_AHqjWC*^oVz>ow)o1pE^E(LH_fVY8W28gG zUFE#OUHpjjFVr{W<9-eB2_pj;`pf(hrcZ^l$IaNd_%1BbeA;GH;+xd}*{n|pevJC5 zf_PV*%H6}6Uae3I-Z!8ggnCYtD%Ekl=>$B9-Io{g<4*ah?!Nv3-TwxKKJDiw_SX&N z>wP@92#WoS9ADmqgC4ML&-Gj0$A;^%&DDa?C)O|dd~UnlPUQBrwnD4?i|GN(bHlS8 zt=%O;KG)~DddzwHL?iPb_HHIM&x+59gJ&&x`n4eY%b>eC-Cfd7U=9`dlY<+!jn0P-n~e=r`?$ z38_o&Odp;DC5|BlzS0Ng^Mw;_K^?$xe>eO{3GvKFa`1xoH#qk}yr9qd!UG;c9W`Iu z!IY!-wZL;f$BQsC?ku0Pq5Ij?xuUr_x(?SuW6kAxe?vpRzHO|aiGR2x); zkulIfFh2p$K0N`;NnzDZ-k+&XP8R`ZIq0ICvbA45CRfDI(R_R6Gv2gtOs>f98x7+T z^~C&xc!JKqU^&d+c&y~(d<*1ny-woHKWFgGbxAya&+=K%w51Q*ZP^O%C9J=74kP=! zP5y@IL>vny(@%KZTwrI`ryj&tkbZE_ao$c6(_0l58~AfD!4pbE9`5#PYwg}mU>AtSn6~eE$Q{tV} zPU*f|;#)Kh(sPf-d7NvT@bf<)@i@u(_=d(gz7m9AaG%6iNuQ5zNqmj)sRK=wUwB_H zJopK}BfS?&ypQDLc#xW>YefL$BU*0-`!eBKvmgVn5Qq7ivp5q{Um-p@>(9>5IdSNN zD-@^HGr@ER`Tm+~_w<_b!bz;S8-JZT{X@Hi@wx4yHb9R zJ7~Dv=6)Vnj;XG2*MLHC5~ges?9qBL=*WcS3%H#L9@_&UARHzv!xZOMyf_=6u*)C_ z!~B33@3YJ<>It)WcUX5OcU~d>8T$pqVf~sDpUTfpxz@G8lxtj~C_H$$$G=d|skzEo zOmnae7)Og5m&AS3X6E5^>HG<_avtaCD?UsiheMnvPQo+pQV#Gl@`3NqPQmUhE#*n` zgL0i+mePOh-+my*#X2az#LoYBftQ(oiNq6BE@gWp-of=lH9t@fLt zzmxnuc>V(l=kha7_`9#vIG0OZgl9)J&gJAH=~4!zVqL1=RP_KZso4De$w;v{CK{+1#=#7G3=Y01qiKj`tXvo>c&}rSSPF3#Vaih`Fu_&;a?qkp(>X; zkHu7dgNm-uM6NGD}V57`&@2z-UVFR|2tt3iI(TlD@*?0)## zlnPh&QM!ML-N0YkeSl{U(s-rW#8Q^ltt;5uGJi%q3*U2HBkwH z|Hl8%pwegQ_jG)*`#}4U!rQLadb0Z`F^zAW(DB0V_@8Q=-)Gm~aLc*0>6SzLa?qwp z*f8{!s<5xo%slMr2^Gf4@lx2&{E3QxIS|4_6rz#>|3e>NH=a6EZ8gGnyzQX<- zJ^utIh>YX2z;3GFX>howw^zMl^I^Wqd==hkY{>qBK3L?B^>&-D79yT$#i4dot)3Zg z;a5u~wNS*CQ?2Bnc7^>C3nIK}x4#gqs%ny3a$r+ECk|@PD<_^B~C&tb^#h6jneYeIiaYj}I*mkE54%Bx%M zeYwgnjVpA1VK=b<=-7~-N%nF9(SrLux8t|%^rw6!r#-3lXLmWL`_I>@|D4_Cs_gGw zqwkuRl>NQusQe84Rp~7`nxrk}B;K9sAJFNru_f0BZP?#U?l;zSh(}o1iaYa6!Um;& zDR-9Ix`|Is3A=4N^?^>iOd8GadH2fx-VRDX*~VLhoI2&l?5(oDw~yKv-hC3^a_XNN z9UDE8!J2}!1FW9X#ZoKI;pOzB?9kf{(`|MA=YF~0au=t6$xjU(*G-<-opSzdTWh}! z%yNhI2>qk#+avXay=8_+biS7I5m%Zv%OzpAGPl1Ze}vbIN%=70xIYcY5W-T9TW5rv zO-lcg-=Bf=Ott0iE(`v)lRtO_r|ZKS3NLZzoZ#1-cEj(5N+n)nRq_**9;80$;oB&_ z8rjoA{vyfu4xSM>9^9S3oy1RETT$pB3`QD1NgC?+|#L z%T-Gbl-p|Hq+`VKWt`8!VmH_~AlNVEdS&QXPL{(96fUe|V1M!@aASL6jrx@&dI zgTp;2KlV6EZ|YoN>;N_n;Ue8IycjOzcM3lE-H&HRg+~Kl1t-5_-yPm&xYYPa%jk$c z&;3cj#oOfL`RO=y4sR1@{n15z(t$o|TK+)t2%LdooQ#Bah9stLQx5IV*%AQcUkQA? zO+MmR0fx7Uw&xgpMKJ%O{?~wux5-ERxq#tqUQxFQ}GLmq5dp~<9+Gz5@-G@+27``(s>!^Zvy1ujU2uZ zPr?tpOSi)Q?eb}PI9~hRUyC3-}gfjUv}1i28NGPJt2Eg)+@Te z&MIEScX==cr7oov|q;FB&K+DA@4wwqjh zTn~aC+wCcA&_?0tfz4O#ba-InAV;;|ow$P!4aky9KHvox4xeERR*S#9agXgUv=g0t z)ewaM+kAyP^i()_?ckr7bIUm~=isY;iODl9a&R=q)n73UhCbtv1N|6hiViyft~RQ$ z^+dkQZrC3Zfm3-R(Q{;I7x+$pVf~RC&qer~i|WsDg%|cMnXaD1eiE5a ztEVbzTNfLz@B@nv2huqEVPHefa`kYzXv+b-T0IO~msoNjcAat{8#!_8Z*lcIO%_i( zam?-!d?&7wIZCqh1iVE1eTnpdc;3xF5rNMrL9OyMqCsxAI3f6EZ@QMhycCY;iuKKw0m zQ~~Gc_l5pHO@ws0yZTlSAq#i4@_@ilqsFmwf5atL?E@8n_FaH^GGo^+R= zh&$y#I+;{$jhi4GkAxfR)g6!JdbKRCpd6lbl*5?bsuB7?dEOE(EVo_XFD!>$IF`dM z9IIU}9FmU{2l-B1m)ju8wx=q$-FO}~ZRJC8>&7GaIIhuRAJ7NOc{h%NTK$EoO%b@8 zkLA2e4iv*q{ozzTCywR0OAeOjZX5-*>W}4l3y$SE_}XG;EYF=dl;=(yhHG3nl;=)4 zs+`9cEIpw(S7K}&%Xyc48dquw7nR#BxN6tnz>MWD;%6do=lBlrPr3MzVa6kHr+nZ$ z<$!@uOsk&ofpp2I;U@3-IX&Lgd4(RYVK->ECNr>2#c2QVPzIyj8b^Q~Rbc89wr72q z)m1LRv0u}$9hxylWsh6=MaaP*CviabiLYMG`A|5bl^8yz#?AS>B6gdz$3%O% z?i?RE-g}$cJp;yJr{#LInzKJ2#tU?C!|-A^#BHhMEpWaO_63>iL#w%|V4hpE@l!&d zb>}#d-dqXHCgtP06+RD$+Uc;LIQkqs`GW&`9IcSl@x^WsUuqoZw(bm%lX82Xr9gba zK2@#$DwRC%%-vdkXAh+ZauavnDZ*8=`V(&Ml6p#glEK1^R$O;jG}Ce%aGBzzd8foT zoc2rx0~?lnz_tAPMRGiG3yj~|AA;kFhcS9X`vl{Rhqa(nQclB}-cXJb6Us>^yKhMz z#f_dua3`DQhLqDu{W;A8a=fzcOrJQuspU7blE3cMr+XN>&QfELQM30-zDNB_(ryr4 zeI!37*Tpo+{>`++S4huBP2z1%`FKK@9#=|yK=RKy_3s&gkx49Oy!xRxiF6nPtTi4} zN0L2*nWOM5cA*@%T_rthr=*;&%barbMnAB9WHu?~v~$1QDT!~B{>{3?yPW-XFlgVO zQ~{IrhjHW{NJFUq0XdGmMf$h!;cSvyfbZobzv;9mj#G~y+iNaKej-9o+*%F!vAf?Q z?B8aW+bX|+{L##@H1ZG1@#{6W{=+b@2?l|0^J;fWe#6aAr)b~KX8o-~p9Shiwd?~& zmg$)b&Gw?;Z#&Bq7%m=6!Ca$Jh17nEx2Em7ds{Sos>@M_egx5!j=77 ziN~p2tsRi#?_=a|HupB6{|fONamn8x`Hif^<1b=cL^br}DWW<=`PDnD4xU za@;>_+egnUP~-kcx8y4vOPbgRq?~ikc-LppU^x)GPx1@ouXmxGCy=G|;3Xx#!TsC( zebjme1M`-ifRi2SQcl8cPn?IK3(!N;BEH(#ZaIm!lRnwIEu7=GA@L^Jr@1BZKBqqF z+#IdXK{@|n!5LqQuL3OX&=0dlk7G1?&6<>xcKQpG2h^!)7+;d#LE);MlKX(g2)F#j z@4MFjQ<6XC_80j&!Vbv!8#PWRIf=)d=|Rl{aoHhr+mV4J7PyIfrJPREzka{O7oB!i z`x{fd$nm2rg^R}lc|D8HbSesd{NIl)@M8=7*aAPcz>h8PV+;KM#R6}5y!ga7?$rG- zEy06{RI2_>4{Y9f_6uztg1<`p1KPax^b-Yd{i%9iPn*Z$SAJU07w6wCJj-8}$9!+~ zeBqxRj)3<+cjnpt)*h?pWAXdhEA_s6HgD-x8Q$g-BEoBhgLy39`_TUM^DKE>zq9pg zTKYwWqc-y3!omA%+WtoA7lilsAD-~WGBO;TUiPiu+Wz#*{;u?w_w%&CS3a=dw z<^|z6aDgaCBI}8d*dyvE%hhiq>J`Qx&k?6RA`e4c~ND`cgeqj+{WqIhe2l-JxNFa4`hzs4`P+xy{IkDXww>!wm+5b>?ei#J-LlKtFS+d!8<*jYlDF6RsP+ls}D zDi5|TUX(mrzpm%HC$DbZmr4G9A13KJ z_f(xzb?@6>YwI88r{b2z@f9O+7`OMT^ggHqpN1O%oVH!SxcTGK<4#2Kb({jeDBG=C zx7-fq>HE%byD)S!@F~}iPzQf68S=FtKMmIeT=DAU`>T)-<7(UU(y3C1hU)@cY+P-> zX%P4{Tzx?1r};7pe6jiQ_no1CmD6Ng4c7~}*tl9>4S-&49Uq3c8ejf&sUtQ&&F79! zNj`1AsRnU1z9GQH=BM?kJ45ED;d)R<Q0l>xT)qKWzuJvihnbH>xHv#!+ zam&CLt3&f8cZM8`O*xOWzQ=V)TXzx1$46f8 zuVzO_$FjIS7-2stp(*+OM&^h0Xi^;aYl(}k2llD=<+mC6V4Y+gSYPJHxQOdIC-D#G z2ak6T%KXq5C($GR+EdKEq%?;esm(3fEv?|v_F zv3jlf+qhoNU+sJ+=i5);E5U!GFFl`;e7rqET<3Y|IOcT^XVcpUe3lN&mm%QObQJ4} z4yzC9gv0rPzTo=D$F<&<|C7F8zf4dZ_Xmly`elU2Q6TlWoBrMEgVORBt*tm;Z28hW zKk*NJ@p{Lz>ELlzeRCJY)vZK0HNQt?eprtNjdzbooK=rl9gMT;F&e42aG_C;=VnJo zKgG5BW$?2}eym&Dj~KReTpqs8#Qbhj>c#rjE~0#%m$=ya4qcS&UkyH!@ZfqdMEq8L zbBm1q>=(lMdA%EFyKb6aV#NKgjEnvayodaIQQ~6#v-)L%_|^IAvgu`?thhbzO?0Vo z*OGD3mlln8FO#@fUveAE`wFnHa_>v>v-)cA$n^RmUkQ$x_awy--E{2ajDdy^MdC27#)mld`Y*)Q)+^-Gj`s_fgWh)f^`lB84&&yP`)S5u z{#Kt%kBfXA%6&_1$WL4E^H)f{8V=+3T$A2cIXG{j^=TL2wBySm$WOyze%kriu`QDK z^W%OAZqMD7(icrfY}`8VX+Af=7cFkzL-IPTHjm1EQip~cjEozr7jb+Xk3KgcKkc}? z1vt%@almzUrS~c3H+FP7u5^|3Ps^_ha9Vy7f7>kTyg&o^G#!PjWqum20yr(dUchO3 z(Lb%P5U0iMhqxLpmaiSjm%m2(r)@tv5f^zqRGa68whqgFZY``T=Ss>SNdJ@(>hPn*OKcCU*F=sulyn$7w0dJv(6{F4<>Q( zybq5bd?H)i!l2Z_`<=|^o(}UdZuHM_xLRc2SD%aHD?A&AbFU8f71pB-zD(S@qqu** zPRE)_{;0QbgX}A9 zyIO_!Z*c!1Uj_KI{Y2C;IW}iy-H@*z__X}G7D*jyTr#BE+9ugQrt7j8xAr;7r|D&X z`Dgp3pW(WaMp2h z^Ez1%-fyye=Jg(Nb&AV+wBwJSAsJWmWd!)N{;Sb-94l`5BQma5-xlPj^=Ymj_>|*{ zCdAdwCw3em_wTj*qWd29@3rH2#}(!N3tkV!brSisdN4m8CnMhk>QMTx^LXi>7Pkz~Eym7E zZGCA0pSE2X2b|U~xlhFDC;^VQAMC5!S=J4Ydpz#{vh6CKdrBd1F~+~dQb(N#y1JiDQWBJ2=J-(jnvzQ=Y=$%``~#T4OfnQex?e~ zlW01cz?aLXZ!de`c@3@qu&;P~gneIv=NvTLz&>%;)f#Z0jMguM5Ldg-J_&q$eURsa zdnDVsi@s?6HwpQ1T=cJUE6fjNJ?)Rg^#V?dI}A9j5AvUe{FLo}8~C*C`2aj0pv{k1 zpSh0K`rLamtj~(iL!ej9?>6a+Hs4BoKRzX@?I+fOPh0;60H^Vd08Z1<{;JfW^)uE( zo9AV?zg@%STS;8=`~lqepsfd(AM5R;IIa}l55sv`ru(kBzqI)=4tmwPy)th78*0jW zFdygP9?!O3wJ(%>vGvt_uG9H(&WC+Q|0;NX_o?*zRVLpY=Swf}u`d{RI1<)**Z^rZoOeB6yV=Ck^5kob5%qW9VKxRZoKpE-_OS8iv_ z^E5ONuS;5@+=R^IOlIG>D(; z%j0ls2wwX$wF-v&6J zT_i4czFGBfbe<4(`26n6)-N4jPWnLA`?~4ru+~Y=*V5af{7^6UeeNrUj@L^aShp@3 z?{<|qt8UHjq{qelSTF83O~JwWU2VT)l=8Lw1Rtvop5Tu%$GW_9wRi~y;0&Uy?x(H@?+gvJ^0_z7yjJ+Dcd?({(77*O~R?Z9FR>f z=ZiY9uX1!A#Hw3KIbXtYTt()Gb!*Ugcc8>sbz}b6^8%=Y$GZjD;#O}@?-$SaRJJ~- z6Q5e&gJgc_AJ%O^;X|DJzSP0n1+U{T*>v!@*m@w2$GZ*I6ZgSdebA?zzw&&4pBWvV z@7bB*!+O-eozz3^gXd-^?t~Th`PqrvL;E>6FVUCY@5(;4)@O^aF)aCdUr4`yw|=(7 zX>rFR_t)|VCg&}ie&FAI@% z8v-3AY+c^&jid6f@xD}P^O<^QA4tH4(Ns@+#rg1%z^kgo=MwZ4jt zI|y;LzMACY5hCXG9`oy8Bl%uSYaZok-Q_&B^C0~1{8PhKq5m{riiE>;5_Pm_UUFP* z9!)@8&A*Nx$n_w0zG?UCabEtX^4H13tY zX#Oz||70ClH~x42so@48u66yx;+q6MEiUu$PYqZ3A^2jPM`Awhx==sx@$laD+4ZTJ-ogJ+5BrlTuq1PH~bs^vDB;amB2sN>*H*e z@p$GZGOp(HAjH*hqmj7DNZiOzAwQ+BD&QY)7rZZZ|Exerx}w>*t_DS^x4_ z4@GZhB#!grpPG)`uj2B<>z7)ej>YB&^&O?}o1Lv8)<^34n5P)F?-QU~|5kGp?1zQHAN^C!ghbkJUTAS z=i{CbiR+2Pof3&VBNEpe#-Y!($7LUMZLrJAd5E|XSjVdyB{=WPS=r)Zzi4s$j!5Q_ zx{fc)7PtMR)H{0b&Z&Cyzlp>30j~bTbiScT9QvZoU&LuT5U1sbxZaU;9f<3=Kf(Dv zsAsDO^05xjw@;YQ(_QzclKJV@0Ua)#`J9bUtX3p=z)r-qMTXD7X z+2|khd0*Z$Gx>SG_lEgA?tPKCMi^)LQrI$mokU+o2}6-3bz*n#va`C6JM)|~PB@!+ zCMk|PMDpQrGWy5k+x77GgE7vkTkrqH`7%s6)t5tOM@RKTNnc@H^rdq=UB}qI^nT5Y z*Ae?4md|~}hjH0g*Cq90A9&m`5{Gf!BQy`I2962e6~>`2Jk08Y(Pz^A=4T|ga$#}fTm51-#@v*ZiZS9^c)Fy)7OeSSyD{II^L z7q{np9N)?36^@X6Rv)w}KhB5ybV^(TOt)W zmt(_vS)Y4%w)Kj~S^15&jk=vE^TWCo_&nM15@*$|aAW%Z5a;dA$;Q|7??i{C7w3m| z-fWn3;r#XaeKdUh>v1P%)4}7c^{V(#qSxb<>#%))j`L-VaH`%@r4H@_8#wEH#5noP;WfP_IJZ8t< ziH_Q)$@d#DKl)eBh#Nas>SbQHBwKwszviWq5A(~@`2%aa&pL{fAJ0GJ<9zXWl|OeM z%H}hVv$oTmAI8P}O8<=O7xs_&a3r=-9mCXbR@_n0QP<)|@-=8bn|&Ek`0~#s`mFqFkvQhD`l>II zZ*m*CebeeT^a0ri+I#bcBIB|SYyS3}Amj3T40*i!RJQebXo2L@>NZL1F4wn%&X3{z zC`=~xwQ!v8z*m#)@5JwuJdh9LmX){zJyJ(g!PVa$heJNCzPN7mU6Q_T;Ci6paDB=D zH+?<8d9Lx{Jg+HyIDa)<8`c9YF7k~jadAE9zbxH9To2l?U*x`&t?!##()Dj@#Qf9g zad|sk-moC{FR@QYUP|gT0NZKqb9ZmH{03;h*oxaj`==I;^Q&Hw=;XXmNAHoz{6HOu zV_z&B@4r~M2AvPI*1ra=LruERL))(#JdAW)Aoa3t_h`2FOiVtJeqI@UVSY=;q;)>= z37H?BhpW6S(dQnMIO{xI?u~{o?QDFpdfSvQ?uYSs_q2?QdOO!7y?>TCOE2?V^eceYbrNwyw0%Myh?`g^y&i}gAsq5~U#^ro zta|V`+`eJl=DJCK7#DFZ!m0gymCO%)&aFrDvQOe>N=Fy*TRIwqQ*~TDJNZpU=2uuh zy#%Dm$+D; z`Fx3X{-wBKqJz&X$l=WamqVSeR} zXx+F$;xIogF8k->@h`WA`55LtCvlkHIOq2niNpLn-{&K7Uz9kE+m$C@?vgk)?w2ER z-;g+rJIZle5~s%fb|mfx5{GdsuOz+Sl{k!>xex9O^ZB~{RN^qdHs|*viNpLn-vg1j zYWO`ip6?;ahxzqwO#b~=;?(>eo8JB@uWQ=*KetJe2hU5sF6niQN9Ok@i9@}0isK%W zIMkcDU;Z5C^E#f9ILxo(RaB3^N*w0r`L=(BI3KCvo{!{vN#Za+ANP|R2IIC^$G;_? zn%~F6d|ExYulRbI&+lW|__{Wg{m17MJzsyA&*RpNtjC8V`EH2BttaDR-Fjb5eYLj4 zVLddTSs&lm!hgGsvhj5;q&$dVa?3d@`v~LKHjBgI{b6IJ;P`zls3SH%_Lu8hCqI#|YYXY0cHbQH@lUnBa9^qBAMetz&LhaLvPBUaXyy`r~3S~%nyBT(s=iz#Hl{F!#LDiJV$O< z`TeopzrTg~Jnq>r4&(ATtDlGYejm6`2KmM>Hl7#ym&^}+p4@@@`8kPGeO^Dj?y|n- zozwe10&D*E@0jGP_SMT}eyF!inQ9(d2bWL)&6xhu`LqQt4bd^C(h9kKPzz24Bk|L?x{&sqNZ3p2GoBRLQ7awo`0cU*Xy~9n5d_OI94?`F#rfxBGhddS)WM&-6SMipKn+&4&^8h1a5!?=ZgNXJ_x4*9SioG;%;#(yJj;L{1e)mQzL2lgrRx_6sbU$oc#Kr2h@?&4r{1~vx&*XcwSNUMYucylVP)CE_)998;T&xbR zn|7c6DDiVY^L_eQx6&PPbt}9z!KuD{Q0hRv7?<5r`Q9Do8>W2RnG$FDH+HA&XYDwp z_=PxMI^Sma@-dko`qD?^-A5$O(qZ~X0A6oa{JHA)z4Lf?o{Wq670Zb}caFqa`Hkvp5e5B(da@$N$sm(@S*{Wf5?~I-s$HZ zJzq=eK)pkhkNc{`#p=a+__zzE$EU7C^TT{T?k6P<^?Drrl3(S6Rec_qPyKw8%kO0ip%%C_K@!y4t=KK&V5$;g8f&hkPn}h zIP5FWN55!&s^!Q1r)^jJDGy%9wf!~BgZl;Jb}o?h)$S{;0Z#3M$og`AT(`mRBza(d zd>)DQYV*y#UFxvr8^_mtsRCcD-eJ05-qO(<`Tof+dhZ?bO+bFDtG9fR^iS)99>8Vw zg?;Cr+Wt7|<@Z$PHkR-EVjj0`9BBJzmy(KAUvj5ph00`bAq05LZ~`gH_jY z%x@Lg%3rm9E*v83t6i_f>$+-vDKO99(Sy_HFW1d_AIdO44@bP*&tBhs+3J>u=h~QW zy8fXrV_)AX_5Q0qh^x&bWb&TGeoQGE9 z{v_LVze(b=;`R=t$Hn~e^!x(L=KEv$Z+CvS>w|-TPxr<1{Vtnc9%uDIZE+G;_4#YF z6L-vt`;lhQY2&){a5n!cYZ&Jp z=VZ%|b*cWnHq6K4-5bL=tXuDGhA(?(hn5by*%FiFx)R5cW@-%pjiz!;bFaYtpV8~WTk zvUBQjckP|&>n`RuL^#fe`S@@5lkogNzWTdleLL~UvE z9Im@LI&bOj4CBye=4W5{J`@e7J}=apG4AK%*3&`KW!0B;;C$oH-B+@$FO`$B&2!b4 zW!Zcg&KTG7C4X}Idf?oW~r`xN==k$u4Vsy=U%EiUt6zhHih z*SzMzisQX{|jX3MXK_;CHhxSSvR$JfvKb2lO5V*lk% zN%D4ol{l-fm>=uQpSw%Kd>;2;cpcaD#@5Zkjgo%!+2_}mI?z8YKlBB0y{8)evV)9k z)uW&IR2|PtzE~aTU!I<~k(~Um(@buzZ{Wm~yv0pSD*axi7y(sg;zUn!H)|VF~Zc4vwMs<7Ez;WP@ zhjFN5?89--i&rTRRc|R<+|rqee)O4TxSPX#9{1lc4)yXl>_7h8-I9%Ol60uP+!p5Z zabLE!cwYwg3+mweY1I3SUK>77*xyV2=VaU|{l^IohIL?ml`YbbkC@Kgk&UnR?(}}a zxct4tIM03DwZeLlkH;Y&;)-V_`C%U*u1Ywy?>CeAVIOcl?n`0+JZ{%;9}G}F?iDgF z_5tc(esvx_oNfQ5e0H3F92b4&&)tv0zMzg4#l?Ccj`^)VU>y2_d|k`p^p+GH$8lT8 zx?#VJ(s;MI#KqPZeMTLHbJFLf&u?8B7xU|-@opW7i_OpSd6@Vu9c@Ji>SbNn2mHBv zjnsj9J#P2#ysVv@`0BQne3ma`!|CfT>KG$_?0cWzKsdk70_~TqpDjP;x9V0uFK&Je z5Kh&xt;`SWF+t;9LE_M7&fDcB4*Ae$9*6x>u2X$Cl6)8!`ARp&oxdubPyCd?l=qr$ zmn|-yM_2F1qlwp`Ka?@zn9bVJ(6v|sSbLX4}B@WNBY9oL%ZlX<29BiaOwM;Tk&(x z<^PpVNahFsL_Vw=^LZV=4g2D8o#E|_6<51%+5){AuCRmbQ|rBqr^7Pj0a^}dld zfpFu$K$J~qxxjJj`2txJ`egu zeU1v|@8sWiO7)NV`1zyKrHP-GFPhJTG@g0K4oi<)xJ=fqxHuh$_2B0#to*dN6^P3^ zIA8bU)vK?jBY(Nn%Y9|((Dv8L^!^ggoA0MF`ILFYJp41ZueAJ_hx@9J^vCAMjKl`|^56AVm z-6C>u~jNT2r($MyMjM&jNUiJKRR zJ1`P=P$cfqFb?ZhZ6?0r^OxS2#bG{=dwaOAFz(O-8JFKT;`xq@jQfsATz43U`Q@HU z_9yZD0pbdi$#b&opZ4B7e$Qw1ifzU9F686)Fpr%Z#+6!e=firBOnm11{`r10@AGiB z`?Qdc-@oDczL$*;pG)BU&==;n>d~b4NvrQk_(3>7j^pl)#EnGaeiX)Odig#c%NNFR zJuJQ{?{E5fI6v>pFTyx2u2na@U)0CrUmgg@WtjVQB<{D7xCg^H)QdW%`273T<7+&V ztT$fo!`b+F9M*$BcaLV{L%rOmp6?go?KJv_`)k_sILy!c2Yn~Wx;$L zUQIsE+Z`YNUPjc>c|+oprK68$h}NZ%khgc)UAC=7&1a zKOSe*cZA|v`At~)y(^qw`NP!rM@yXLb7fhwZmad}k$mV&i{qXkaTu5Va>s>nn$Ony zQu;_-KX(yM)q9G}5A_bxcz2S-q2B7bv_0$%<52GajkEft&~Nnf8QJ1;eJr2*DXx{@ zu$A9AGC%Y=|557avm_3EM*m`U)QI2G!F(2Oi1@ItrkkJpSX@6B35RhxZ}%SQANpLU z@$N#2i}l&^WyH#_PsYXkI&PvqxI*Hr{P_Ei_`Cq0-a0Wv-tW5r}py)q<`r182fOY z#92Pa>R_Cuqk3~v4^_vfWqzmw{o}Zn&m$Dq%5TET@5ABz$^+DIH%Of2bG2d2qdO%Z z`qJXKw@VzxWxrg17&l#?OP@;gTRwLYPVIw_%luF;=7;Y))XqQG2WfwhjL_!!5Pa`p z^WW+3fowi3&qMKbUCfWq4`HABdVDkdzABIVP8f%A`FuOZMcn8=<@tMSJ8d0rl{(Y= z!0UK@w)0JxAHO$rkm9&F=5F`MoI{pZm12u2nMfQ6lKG&+mXRpT{kdIGjiP z-sRr!xRuvqw4W2C&mAK9aDBnP;yh3X;(Bf~`sJx?eLs4HQI8|SIyi4P5sn+{AL<>s zAz6oTo%C@h!*P+X@tJhJh{OGy*!ws5{UtuXBpH1{~9LDkA zZmn>AF>dFev3mC;?51@PzUqleB;mEC#J`zZl`Yz^ZB@+iNu{8 zuAArkd?eppk+?60aZ`MT^ZeR&zkIvwD-Bnn_x`dzzTb@hcDqIT@{O<#&-d*xZi-$S zsP@%;VLl)CN0GRnMB;uHi90>gztJ#XW?z1pkq`Q+>rcsjo4s$PK6-zoj^C_aT=jVR zPT9|08>HV)-3PepM(Ma-dfylK2jlo}HnAI0KRo_hXT-_C=|Kx6_Ez;(8rVtX{vc4vael`Ni(vGoR0| zJv;eT?~(rTemm+I0UYmVBhK{s&)Ia0&rR~f{auVZdXJoMd>=RBwEQOar1j);+4`?* zza&4t&yDXh!nnCFOP~3<7{qD$`97$H^YgehbK-tZYaVHFF~0`rsO_+G>hmO%fE(X5 zeSaf1F6*+k`-QJ0KI3tGcXxG3Wzqb(`*$C5_>%cu-3t$2Jb%&R?zsmnnZKy}pal!} zrvRw8LVVbN|KnS9)6)!yfWh?$;eeTP$zPO%tch5U?(W3eDmUJ&zd}#N)YPEaulKl@}uwQqj zySnJmC5L(*{^bLb5Bq>&tygRx>=(vW*N(%r4cz|(C(Qlx(&stHZRFzOcB~V|Vchny za$fTK%yHdU;`|#j;xb=l-E8^sIP81=eB9t;Tz$Q8T*l?skHZZ{;>sJu@r^~|dN+*Y z%WV{g>&(aDMhzVHm7AZw4zbVu8;9c}-{{xF^J8R_FdxTtUyJMK+NI=7F*xgEne ztjFMi;eIad6z1c4)aJzD+&AL0MqD5C>>bJ18HekS#JMNJ&pEJv?uBgEqb8O2 z$F8_uw&EQl*8j5LR&Whmb=F-g-d{3IKUMyhh3l~oWyj}TnWyuH?N;uu4mP(;J^sMs zibj1-I*thWd5tl8{x6H(SpQapiuPsQIA2&7`_l2@#Fy6f>AsZdJ*Rj)lSOYP9mj@` z_c?F3aab?oMqGHl;d;g6@OTh$T|Y?Q9u3lcG45kw9muD}jrDotPC6fPPdIKYALiHb zh4ky)EBIFY&+1d;%l|O(FB!f3|K}v<1^nNYZ0}LR`OAE~9#p!L^RvvK`$*FFjVpHu z&U5R&8|LHnVC3zIF4S8iy;ffh5f0}Y$8opG`r`4vyN`UmMdGyMc(;D|ywBua)K}jO z^Pyg>2fy!ubxf`io|lYsCuWRG1F>$NZ)rBZfiEWd)p~qE@?kxiBUFz&Bu=YG`R+AV z_9N$uIP|&nrSy4;xWZ49^PQ@W7vu7CcZYEpmvvx05Lft-Tn~6Z5pm3C&7%tNY2T;L zeEhSrX8L`C{lLfT3+6W*iE9H+dmm%|$I=%Khx0A}+Bu?++z-RsOVrT^aW%a|k+?Cy zsqgFiiPWp&;5z&8&WT>s!FA>JdG!8-A8{SuN}oqO-hF>|`hI})TK(MdQ|XH}KREA_ z($77>$Lllt(gd8=f2~NI)~6UZ_cN(i%dZ4DtzWt#ahP9hUrkUQdw)RN%cp0jUq(rX z)i32yW4-^+?Bv(`^Q3N8e*J_~w?`8)KisaiX}tTJ#97-*o)=broui2kHNVGYT+FYJ z#=AdCTx@>U_HvB)EgkL`hK^@teyF2Lq zFi1FczU8Ga=-(ubcN<6?`iJ@T{wm3j_3(WZh{Npy<9M9=XSRCqILp7@2eQ@8;>-U! zt{y{#<2+rvn0lPtNjR*V^3Gu)b6HXrQH+`7K=WH|f6cc(*~e_d-;O&+=u0 za2!W_&nNbuic@@He)lrzGtLi>dwC=-7sg@T#(yj4n{(;MTRso^Mca=pjY+i!RkM`-_*3$S50KZdzy zNWMz8`PTV6>C5W&RUhzGc1iDpA;78i_`S?e>z8Uf+0QYzzi|Ak@v-k* z-#p~&UKLr7E5p~Ba2|2o|NTs#=N%78Uo@Y40GEF{d9NVGEdx%i2l%JWj~4J*=aJaw z0jf9V_dh?9-$q~BRGz2VEV3S3gmDoA|k6~Z`xL^2h_n+`Q z^0v8#YMV)Z}0ORsFwXa?yby$33e>Cd$vT%N!k9&2t zxa~)hb(hEUx-rb3Z+d$Kxzta6ggzp2xd?h1ZQ~$E5)5pO44CypS#KSl;OS*TrqOI6VI} z{UadiKwoN)rO#iE<93~;{2n*rzCK&r;wufGcgx1d`YoSF6dmYuEMLbH>AoOeYhy$2 z8)il?=k4A&GkmCn`LR#=bGOI;-?*4x<4@`J@cHdEJNXsbM%=x##U0%wy$3WO z*vfC8Z285;?R?VkhyfE@@rCD%+JT&CA^=*xPecuA&ygUzbW^0qR%awo(|k! z!@lYwe$;`u2H|kOoprb)vgKF#3+eI%>E~7WpDi8zz^9#OEfCJq%W?Uqc0Wxo@u4s1 zU*}(?UOvCe{LbhDP*;8n@| zvifu!bWEw+yRyZ_x@q^duuh!k{JGmIV_X`Dd{~dJzbAFG)`MImu0c5T+3VO&>cI8h z)NWJKDjmEp8#92O% zZYSp@e{Uq~b6?5!d`j^-=^ww(1AW%&I|WCHSUy)NuH|!`aH`L5lm4O4BdqVO5@-2b z{>SS1;_I<-wz%kX$JOcA%a|X1=Fid|WrR|DMRU4s}v~Rz3O%r`Dq)ea3o>u@47IoK+7^FZxn?o%F9>ogn_ zIgVQp#$j9@hxI_*$iI?4uza2%oa*yIGC%aWOy?Ec+a(Tt=Dgi$VI1lh+As0h(!u=o z?{6*YfP9Rz{LB42&c71jRR0c@deJ}5$Gs!`J&FyA;|`I0s?WV)9QsnG^R}@*qkmq< zyR*gRama`HwO^F$TI}~xX~%D!|Ct`2bzEWj$KUg4>1AImKKEa#qjF5L4xxWVz^$%- zb>P$Dj;$~6k5c23VDx2lFIs1hnqFU_f9$I}H_Yd8?+oM6XM8Vvhw>hE=EwYyulZ6^ zUv+)?Yk1w@IBp|(9|f*MIY)Ks&Zd|7Egh?i5o-hu5uKqRsJ_^J!KkDVr z`DcTFS^hJ(^7rH^c8w4F-Ve`*pF{IF{$-ViRI{5R_V_{zyH)7y4UwC}!@5PlqXgDpuaw{&s;XlRUCfZ?KY<}I{$DOnEv}H@r z=wANY87Fj~aqL-Voq1k&@3OPHk2~|6GfqfWN#~~U!F|mW%6;qX8~S4Lm0y>f*W>Z- zz1jMz`5$AxeKS1YFu!tFIv?UVUsEpu5y#`*2f}(i?pxV(@HmW%I_jTEzpoT=qwA)x zyNH`4oVA`7)=S@haNh3QVZ9!Aao9i1uW(ZOI^_BGmG@7o>)$=${4j366?a(j;qiyh z@A_)<-Nr(~bv{J{Jgz^CekKHxq@ zKF$N{!JoVD%lvR2A>ZWj+17jOeu4hH^pE@A=lAJs^EcO%YAbP3Z~m1s zKaCIjC2Kt}ZYRaH`n2nm^!dj6-DPtAVtt2L-^CJV^=V&Zew+vPAL`AWp41I-Jl;Jc z`xNu@xG!eY!Q(J4<~Oo&(g#=%9`CM`ana|FO{kBqmN?Xbahp7j0%`A^X#tL(dqO^+ zum2@{{~G$@hkaP;K)tzFk>2Yi&eF^L*84X+?%d?Q&BC*Z4*uNzP4)}shrV=CzNi;* zo}Yfv>cKdRZqOJhUu*z31_bo8|p_7&rfF>VwN=epVk0 zoD+`g1|=WH?c=z&Nt_k8b*`}v{Ucjnu}@YXFwW}x;$}u4d?tKeet^ciyR-Si`B}$D z6T}~@mwB!A%Hr$kFnsx@)QkPnqVeu)5@+>G>7t}xSO@RF;QXDS_k&tGD!u8)Tgb=p z_<83t<*(r|ZqGUNob0GPUxL1H9Cxqu1#y#`(>(v4#996^ztva$TM$1D7=L~GaS!f? zY4^WyT=a!McR!UnP;cyeT(jU-#J1k!>hrr*=7&D>dsq2AB|NU(pS*Xq(3h;+*e}Do z8T*rK$mas5>xiLpfPf-WvSNuWx`Ijs{uX0I?ZJF{j_Px67Grmu!mwX<+Qf?pJ zP`GZWw|REldeC!kx-V1swl>zu4q0EUhd1h;unvz~Tk>JQV1C8*5*@fdRC*2d%gZGn z=7)ToN0Z)Hpgku%Nc{YKo`z#S%#S~Jt*|dzez^X5zHduD%Re56e6evgoV8!l-X^J! zx}I(z>t^Z57mPmLM)FyGP@wlhs&(5i8(;0#xOwS*n66{GK68E1XXLAIn;w_PyH{q@ z%j2xL6IR?!WL)fn@^(qyZexkF>Z|29kf;5eOTy==(Z43;f&GHG{tME#mx#-4pI#5d z^<9|ou^v9}$bY+^g}0X;HyVliWhAaUj6)r`AC}*3r%cxek*~5t;ve>(*Zcd`%a5P` z@O;N+cqFd*wq&V1vM-?x}IzDIG2UJ5X@ ztGo|X!&&PP=gU8}{k7iLC-vp$=!fZV9_KzC?q`qtY#grketEtK`;`f)3MJHPkD?xkm(bY^$&*(aWJ!kH^_)9PWJj~Koz zeH~)GZjWroZ^cqlH(WQmyAPZft z%oX3;x8moX%m3>;DtT`n|Mc)rOz(K6@4RhS9=FwBkk?l+?#Qu8T>goAYnRLV_WUS0 zp2@u-sT1-Q-nP}sxcn3OSQqwHclWW&mYucqxO0}B*nPr^``V8`cG-z1bf33$S4`d--7G8-n}>Up{AL{O%Rs*FCTM$hphEE_}iKdEI-J_S|!y?gI{AIB#+H z{H`S{xmM(oj$3k6b-u)5T-^WjeQ@CNFA1O5)z!V<`~w#(>|Qwckok+NbLY+PK4SUT zpf5OdA?ruJ${XeOh@bQCX1@8$8~uN5^A26OWbT56^A~A+?h0AA_O;1zyyyEL*TMVm zcX0Qii@KL*z5DLW=W#Ob6s*Usn3a`9hb~-j^xP%ObuOQ()$06(iT{QW%llD>EVr(E{{<_)jD5io^C>~}kMo|=SAuW(x4L)D?WQlNpS%3~ z=@%^Tjzg-;Cnxfa?V+qg%(wh|?Yrmgv(Jj}qfff!$a%}ZkG^}wd|zRr*RcY(cwYCy z<=+}VZ~o%Nhb~&&edxl2)jlZhnZ(8IAnS9V39knp_j!rK^K~BghVVM+aeGAKu8?uH z?V#H$%!l>(QSrF7sJ&8+)hsftH_jon(~wR{J{1 zcf|S9Sb)dT~|0G0BJhGV&(sm;2=XG}tehbv!BKt~TFaBp>Q%zL|79 zC2_HFxo-SE=~%t7IIg>UR_2E~G(POpu6;@G-z8tHUbSDIn_<3xNKn??uUnI`VHN9sicN>FUt>K&{&W^0*Q68{+)jIxF}0xgTTmv(|C+;q>xDpS|Av^!Tj$7WRwNTOpjPcjMW~Z#Xi)wvu1#$8>+_t7a#^+Ppab zxQhtz8KlB;66^Z}folxL)r= z;r$$sdpL~4xbE=u_uzWI|C4;Nb+ddKJ}_PHl>8_Wi!WbE=kq!q4eO}Uc=w3J%~W3v zS^52OcH$Nn7`{9%<6?d5G~PWXak0MO{Kfi?5WiL52}{Q<+17)hcO`vq#qD{!;oqNT z$Cq)6Yvq?aC_O*)dHA?Ey-bFd!6?PG^iEp&t(`5u+;i#AWubq)8Q-&G z>A>qV6Z4AVIMJ<_O$XPsC>p>rlcN<7tY#&(pjam7ERX0sEw=g@RthW<^*ADd4vuC-klr?^(Xt|m`k?lS z^yf%%ziHsl$$nF8+$^}5daw@8gZ&#J9mAv}OWYOrELs0s!MEanR==E-z}&=BiBD^; z;TkJHYV5Fbf3v!0@;%k81Mj~r-;~s2=&CJO;&FW`JfA)OXnu}_5DWTCazBUfZEB8zl!oR;*Q^v@C_Td;;WN>Y1}G( z!MOc=Kc~T0pzqBo+#>l+1hq!*s$A7zK#`83gU+-tq z^XpUMHr`9~GNXU}9ddt-b@2K;_#b(mphfHR#P!Mg?Df{e-?v!#d6M72ZE}9#d>h@E z^0`CqZy>IN-}_;#S6TW#X1?X`rTsl)-H6>@_SI>A5G_LMDpRh)Zz{uNBwxgw(>j}H}reM{md|TOL(4p+-|a; zt@AWFx;}&31*}_tjrvj3u~W9VoG!NIhsd~?pF58F_aKRj%@2J+|Ek2V=6Bfa#O>K5Ss%2x`N>m6ZVeBAvd4*Rch0{J{o;;{cb z-)FPEUo^jWxDQ-+I4=6kd06X4<;3)L1NnLhhdy&0cf8CG{Trt7?pTRK|Ni%W^rdGk zUDkcVdB>i0((*5oIJx`mr5Bvoz3kZIPCIdBNX(D(u=Fy{S`Qeq z^`bA+)^T!N-HL?6{F?jF{5Vc)H)ZfIX)Jw09OKwo-KN$T!SlQ`_tDSF?M9(M|kgjnyt zsuN%AdWAUl%k3-sz|=tl`Mn>bOA|j(N9U=@=eQmqj`OhUR(@-oe`6FE^1BSa55|cf_40W4P`3TV+!^VMNlapLi=7LMz2ZwcctE|0_f_;a@`+*ckqH(T7?QOR)t#>M=Gm!(((vMRx?$9~3&Jm&Z{&772tX-esykd3merG4;f%%Qm=eWLb9Jfr? z4c9e~n=f&=4q;p#XYIE$&eA(_?#%W<$9d^|oR7Om>P26AXuP{X;$nTV^l~1!Jwl&b zmX7y^^W!*fK_spoiMvGN&_5sd5Q#(o2J1Ax8etszGD_@*BG#eg0y8%_Gv!qa%*s(o;I*k_+#GmM*Vev=t&%FmB^LMqhnodOCRjAV>V1x4R}AU*{){$o_*ZivfgJa22oE#948H;l_V zaQ}}#ccas*hm~LHl5}5u-0S7_nVFiu%x~p4YUOv+^zuWWu^#!k>E{_ZZ}-*d#kKS@ zKjQdv_sMWvkNZX#hkAJ&#zkCpzjR*^SGz2|uV(r_H_qFAE37y6J~!qo?IZ8=#lGkJ z4jc73;yPmEBXmD-UveKg`cit)I8XhZuny$oe6eo)dHzy)e=_PozS5OR-9|1ctklKh z5!Z1=dVM*r`|ix@Xk^qeN;>M7COUXL>gX%QZTGu~54T6GcOqkc{e6jl#mkcXcs%CE z{8(SaO&a;tE(`Yo$8q;%t6S}=L`UiJLO@E9 z6^RZU@4g=Ph2y#(hjAEp;=s7$1?ES+Q}{^7=nctxyUUj+bw`{doYv3or(qpEl_YQX z%`k3CToPjG=(#4T$HbLMJ%$t=qpt`brxdOT_dVuUx;BYB(3iyJ@rdicXJ+fxBE4EY zni+LWl8(Wv5*;|+JuowMR6;L)qeXY-G%jKV;)${jq(3da)j@ zX40p~$8p?vw*1D459f#H`(>EV;~ov;P{-)PncXgoelYO`bzof17yXOH@p$*GZ08v& zA4<>9^NnTmuU1X`n<>5d>y7*_4bQjC{ymvZZ=aRl!`b+%ho$@H>rvcL9IxW>pvOIx zEiR9X?LTWh7`VZx+g;)OI3IU%_`Imc-5ut`KIq-S$nU}(qkL{g;tChV@wxLO^$tYh z`e%54d@dXpedhXD{WAICq#m*TXW=RzG3xtC>C2SsA2i;5T;g!Pq29(}#&-Gx+4$H$ zOK)etq4$e2F6u=cv2huP_2tjqm&5(yaW{tZ^SGA5cWJVIy01t+t8RUZ)9a@Bf_f1* z^3n8u_By^B)`5Hz#E08e&v%p5i}mgKSdx$XsKi;mOkN(hKhz?A%nx;NzLtNvo6`M5 zz7pXuF2`}VNWJJwgT}j?B@TV@d_Rylk7q~6IPt6b{XART+)&b|T)*1m$$M9@zJni) zTi1qeNuQUMkC89G$d(`HW%kvrarLbdPWA7}Z267dl-|$PkCWb~vhl_0ZQm{HHhS;Q zE00gHZn%F?erQe+{G7jf94&%`0@(JnN4~|>fB+SP+SIgFa zwQq*wy5qupKJF25xZ=K%I+n!oxkZt<6XI}%x5eex_trRE&kkW+-}=tZcZG44Q)#>ML^y7&FNmw$ zkNd)_Zk_d%)s@)da;fX7j&gY!lIG@Nzcbu3@+ zz3J;8#w~3g*H;z#J}S+Z+8UAT%fDsa&_CAaz9xO1?r~`DF6yIy$+#9@{pWG_dl!ae zpSn58_Sft9j?{sAu^t2TUR*z(_z>4p-m8W<=E1(=&)t8+-_z=G|H;o8K9{fB&RF>YNYF7mBMxL)F`elgLH{&mp%pwT~G?Ep?IU%Vm7bNpQiZ{f4@y{p*wJl>ri_Id0ZG`|c!)Y11q`uz2AM`T>g5BYc;`ci*q zlHc%W!g`zckdAw0TKykadE$-_T-$@HI0w1K-Du zacd*#J|nJ4K4G77KCTtHKlDP_XV3TbaKCt5E<7*)hl}LeLe8` z?Gp9{`TD<}^ey(E=X)_5ACI$ijMDdGU|h^EPx~L(FC*tC{Z=sgl=E>rhIM${u&ghx z2OjsUaD6@Qzu~yWZ_>K)Eg9EZH^#3{-@iitI1g*xV4PLA3Cb7i#^c@V!+Je#tFT^= zdqbG7bwSbxWup(!m+DVeZ=Lk{?G?@s;|`9-t&{!R81wRuY;ieXs}Bahoy5iYhB_t* zhkby!%6H=UMwEJR-frW_^?AL>zWQw>?tY2G^#Jv9zLw9m;q>};(&z4nGOo2A#K!F- zeylH#cWZ`y*7V}K;rU*bjj#IMbYGfBC724OvX+?QvIJ3w*K7fr8K-}3j;b@=?A z%2wYV;=}xyuV8#Hl%_+gTg$lqrtw+6jU=FTGtqddiitr z7g=BIQ`B4eL7XrBgwymkU^|F$+ce&75cY+2G%g6A-^d-EX*6oN$~szh8>~t{Ll9lgDow?o*7*{QR@DX7Zj0{yTSZ*gwW~UJ}M(+|iN5 z7al*fPNgr5!I`*gJIDq3!j?EEqhx@{Dd0aIT*MC_yUxx2b ze5rRQ^N8c1-p(IM|J-hg4#edNSF9y`tPgQbIxevKw2%0jk8HEjH?9-%;rUan??A@- zvhQt*%j2iS{ju}~k(X9Z$+Wof7vaVLl)CvFRQ6 zSo4Va5yzjqABFQny%Xd!_Mhk5Uh?5~+T%tf4!0l8pHP2n8^(FQd&4-?!Q=RScs;x> z^FMqq8(-h%;q9B-E*sy_BMBdWe-x*s>A?CTuKuWz-%c_=tQ+!8{xqo%_Ce)mRJR=^ zAJ!N7Sf8b1nD{X+k9TusCvNA@)AjneJIlD}UmuNkMTxU~X*`x*H}r2X636*kJ~IxF z12ArJ)bQnXQZM>~d{yGZ{08WA_gcwk`Nukt594KLT)Zg+`89auNc&+5~jcKSTx@otZ7aVIHX%NORi zaQzP${&mXy(7!f~cY8@3`p5aWO~U8-r|a|Jlj%MqU+q_kUdtEG*TRhvpSoRmtMmo^ zEB-pk$L%X|=pX8c&96@UYJTO}i92D%-CxE1AerkBTA`7w^qH|2Lsd_o=d|4a9e$Gfd(C%?|) zlIu*Cj`FyX-^;`Kc^%t^ap((=v+`pc|J1%Wcihsk{p{wKRfluQ^&a$P@R9U-AZ~Ij zsW1C7S*_;Ytzwzxdb+8-KxBGHR+F~6Qi(zjb2$GvuT&UaS+WYps=;ePS?mBTpHTR1(v zPZ7ubmVf!Sp<};n`DtM)BQsn z^To!UDcp#XALrv1WUB{{v*xcmb7uRr_2+CpV}6{sdo-Kg;x%#Wct>xX-qEKL9h?u} z*Mj{r2{?XE9dUU7MrD`e{v5DB84^rcO4Id859|Lr~$-oAO<8^bt^%j2+55jXUgL@)ZnqdjdySGT3 zwH^!}ki;FkIQ>3VH#Zv}*OBkHEj^QdJUv=S|9)5=@8(S}uH|$8-@`taKedLq{}Fv| z(|9+3dim8hP3{w9oj89xpGoqwbkqo^&hrJ+%Masnp6;M9pT`{%#-ZNk4oM%VaSzSL z$9eRfNB4`ql-_>>&n7G&?^-6;|m>x(td*}wn&Oz+d7BNP8r z9cN50KWl$z`1vHRrK3$aoWI!5`F|QZdZ(v@{p0;{{@a}u=JU8^VI1nsyjp_Mf#hrX1y>6Vhd#8+x>n`do{5yRfRp@hfjO2@5pRK;)d=bZ=yLZh_ z+|C!%_4>Fq8Q1c!{X+V6mp+Q)x+Nd_=i_b??o*H3Cd`NR?f7q^m&fCC9Rr^YKQF}N z-1>3(bqK z7{4Wqn-Z4>TK<(@GJH8z>P24~G~O+hIP`^ev~LdUU|cm4H*j9~d!f*meA!r^-z{~Z z-d;z?5obyq>czOM%c{pP@vGa_vu7u6=Njqj73b~FlX1}(kJ~-G9`sQhcaG$<{42gJ z?)a?=I6eo{&N-ABT4k#Fqmaw&_B$t&EqIhwGY-v^jbRduaNV6 z`0DiQJy;L*J?fN~6}OY(s{Vak`hx!Tao#scoaLWZU;e!P#qjnL>oI2O_(Zn+2L71T z!}5>wMI3+b_Rluo2G&mEs`a>8>cDz*y`OI|8C`1TF3DD7MUOVjCu=e!F5>5uR(F#rzBt2dT8^!u-MqI zyES9nNdJ1*HT*ju-1po^?lzep`rM{C?$Z)y`lsmdaX&LNeAowl>lwb>F5{x!F&gg% zCC=1q&9`UP64#kbKE*%OTVLPMdzaLKdXcZ=K{=0j9U7rH?oP=!Q##5Ur0c-^T7=_1 z;&lyi8Q}TWg#4*2h9fEOuf7m#^mnD{u$Ga=C-6zB2to+&= z#r0|9PC1V{k6ArmYWcXh{eO(RuZs0reZ@GwZpwda^|1H`=)Nz@XO1&dxcV#8=Ml$o zrEJe_j}Tw%d_x^R?(X5Z9(PT)?{naBRy|rz#P!R_?Q!c%?oV-igBkC?xB9PZleqbz z`NE&O8^S(&TxVq6zCAnJOU?uP3g>0<&vEq_D5al|MLv$p_W|TyOuvrJIP3aR=ceiN z664kg7dzjqxI>X~$CS9N&s{OS`dZgRtFMmprA|2X#pieB^zs|JD7l|zP`OWLg5p~9 zlJl_Eq4H+w^OwiFzOW9D`&}4^ebss@ZhlO@FMa*195vUwVm8?fdJp=_uC{UpT&cK9K-ce)%noetv(p{Cr-< zyzHa6)AgC-xDQM(Kg*ZmmWD6QY;lX(LmdC4wEq7UYeqi$NG#|E^9UYZtfK?Kr*qTHBcteb2Y0m-Dc2x$P2P z7~gS!`gypXZPWeZaqe?rU$DM2eci7_I?VM2&O7pT2(ROgY&sg?U+wW?@H!LDqba^n zB39iB+o#t9`6ekp91BfmqsULNnh5Z2*w8%=Ls znsrn93U!Q;4$epImmTH2tnH9KFFXDr>oLCRF00jlb&6}%V}Nit-&mI`XY;uUI<)iN zEy7v(jeaA2KNjoJv6J*!i`xWT{;_19d%gQfz1DT1uIFXlwD+dqI@!85y$?7Kt4~XG z{e$t7^!=^q%OK>(&j%o`5y{t}>p0ji$TtdnQ+%E$eYUQbRnC+9VSN0-`dvphzLxcV z)-AK~)pnNs$M?DU{9cod5Br7hhx2^fX5;Jsr|eVi1J5@n8y}Ce`gDp8rBB^1iGR2r za2&UDw*0EZhkfe#4#>ubI{1Dw?0e?tw z#eXIJg7rWhb&PkVuYdXX$a${i$1>{Q-#Yzz?Q1jEmk7;%W`DJ~Zwl|f zpf7_Tj=R3lN4}uX?1MWvtk>gC592UD9+x{#KCjE4yEA5(@5~wIqeR#D2|Jft`Frv` z<^JQlv(=5qS@Xl~mOejty!(obYwd3oUQFgC_Cb~6xO*g@wO!>rPzQhR4x3&*@c7sB z4TbabxXDOdD~!|n8TD$o*!95T>!-R|IM#3B#!Kmag*r;Rr{g$|`=;~{`)`!SyRSG@*y0rO*A%&)v>Twk>ahxI_daRtZuxG||0`^w{%h3nC^7xmR| zB_H;c=X;0bQ{#RslJ6YJhjGyt&I9`oas83^*D)W~gFkoQ3G2YPJdW>cY5qG|uMs!# z-}Lce__pH1iExTpj97{`44H{v=z9(Nvz$75Xn-2EWzpU0gyy*^-{%Zks{ zeWZUC!#|woKEL|(^27DT^Zg_23)X|jvEGpv()(b7^kO}buly$I3%_rPoosPO6dhVzE5Dw%8NM7IzVDy)x%IN?;Bi)dvAA40 zT?hJ7ip0gnE$^M|zceqE@BhQNgGyYEU-)zP>Wq46prvDAUXmZj;pd+CZ`T#>mnk}k57!~YO+ef!_eboQ zQ7_cDc4PQDgyly`E#=>VO#uH!#y`{IOuNxf4{W9Et z$TvuQ*ax1kmd(H3gW~#N7;su2a31J0>cIKSeSo;mgX8k+r~ItGuK}OBy^O4Hp7_*y zJP@ug`^7&S{LAv6sq59r;rjaFzY51ipLrbCjX&?dJ==R{s)vO8zH~=6z5(LXd>%3Q zSV!&i;kb-*C&c+YTo1o*j`^zRhjCf!F>dg2T>o>G+YM6t>et!&Wqe_{zV4OT_Hzc- zOurAs=l`lOpU0gZt{eJ1d3D_OvQka-V*jnRJn#x@2X2(x51$YI(h;enC!3DJcf?)) z;B;`Fqc1~;$#qv?O*pR4uQ%KW9#;tS zp)Y-F$NAT`bX*zE594CLbZxLpYQL~9tQ+!`K9Ihh;qmUmZ267Q{;5@8cVv2fF+a}3 z(otR~t{zp2Yvos0^5cBm@51l>n68eFuJm=o$8E@Z;C&fgOA{a5rfZA)f34%j%8luL zpy{yu<9x06R^-n~^2O~Xk9Vhqb$Hx)VI1n{`)IcP64dMC?v?HRSG~&lE6?|$+~39e zR*p{k!@VGJSYOZgzKp)SF8%v<(7%DT68}_R{u|B@`8Z!|o_Ai5-Y>}4`Hu8?gt$J! zsr~mdxn00|jL~@KBo6C=abxusk4e|TJlDFG*X7clT-Nk_;{Sv2UF&+ay@iH@deklQA@`{sRR9M z9!Gt3u*6yZ#p)d=e(WpMG3e6kfjIO}d#*P&zsB)K|D7c7V?_TjzvhOC4(tQY$1RaQ zBcI2;GrYf6IDzW6Nb+IbMoFJLLFzyp>fk(32jYe)53DbbcSnTtLp~m7#U0!zyFz!esE>>^z@w_H)XvVn?{7<9UqSCamR)A#>Pe5B>9Pbia5?g)p3%{59`L` z-FqYTo*2fpmr@^`Amd_vV|8da>$tn`l=S(5e62;)XJkbCrA<@MPYw|u`iy++r-iGY znw}qzciYa4f1d9&$%lO~LHW2-B+jZ^^E9eA1)6eQ=;Uy}Oz{u4Tg->J$t_lIo+BUo zgnh-IyY2oTd*1=xMwPXF0|ZPLU9?3&0Edu7?lM(LFmaX;v?-v_tQ05Ck|NSDU3Ak; zTgVrr|M}uP&Pd~P-}9dL zoO|caozcjfF4#_02N}>$)z72z6!o&JJ3r*Z7K(PX4lKKKz2z;kx$``y7kIO{=vP%& z+4;_OrJFZu7hB+rXT|$~w|G;)PnBPKT$Nof3jse>9Zv^%ad_;ES z{msHX()qa`-4KULmq^^Xo@H@RJmkTSb}* zwC>xs;_|u91%CCE|o-QfiLHSWUwnW5}-N#LJL7gdHGr`NdPx?`B@#^|T zJyr4gmx}RXKc{i%;!%DX$@jaoO8lZ9_C#^IG+p4_KM-Gfd`lG8e^okDU1Z~*?`ZLO ziN}59%~IZUNgprfS9*Uo8SnG%tGd|Tuf^|lcl|88Wtw$#enTgSI%D3bU5wbF&eX1j*vaaJ)|G6$>Lz&7Iyg~`L&h&c>}33snszh}94DzR zt?N1Gm)dm^zp^-}UzvXXlSEx)`E4b3x_;v`N*(8QCELRB6ADwNvu+%Tr}gGdB`1sV z>c%0<8|9~KC({}GsdOBF%3J?UK)iGuM?dUL_i=;PUmEaK^V9e#qRy&#kq^!{@ICvx zw|KL}uXH@H9Pk(Dm&S``G#}J1{)}GzwMp#I54+YqUdyh_-H!6Zb~qoe2OiWeFp?jq zX}wT8b{fwwtpoJKlJ5Mn+d=<-(cLc3FE~);19_%{oB7G!DuycBX<~g*SeYXPx_bp5LJJIy&-ZRqlQ* zyLY_hqeJ4C@o)^G4%{lqu?OA8&r6=ji1P`Kj{T3wSiYG>){y4*jtA+;ygST`FB7;{A!L z>nZKa`FKF%wfG(2P3P>n&UI?xz3(kvdR!=xtcxN(jf3jf(c;XH+94jTQ{2zSc+-WQ zr&oWOa_73I{33v-sz2nb(xpp+hwa%1?s>E9#(LBR8mjmqK8-iN6U?6H4L1$cG*3G2T|a{35>8?<9|YHFZv3;H`g1`5o?!Uw4(WE~o>W>J1OuQGT=zQWrYM zi|yHw1LHSzk;3oM1LL2KWs$%?+`Wu|Kz%*c!^e7 zK1RCY;2(#uAii|nVtz-tTCoJ?O>M{Xp|;~XtL?acYCEor+K%g@w&Qhwx~48_JFbh` zj_abfJ87zmtj> zu=J$V_Us)a4_vgA0xi1LsKd^N#Zf4uz)-QGQ z5zxd7Yuf3KLo&Zqm%#PT=Udbc>Cy8P+|M=?pL3#GkHvO)eL4j^WPa)TB(+Ok%jX@G zAGPZOJ9<8dd|1NU`daf1&g;t5FJ0fo`lEJDqxthZkdO5Hn9%^Xvd`_Xm3+QN45g^LeWll98&RPH!ApD=55?SJym|2RerA! z!KSk zwTs@YsHT?KC8yxFy)9jzA{Z!7Sib#M8-!5bd7qj=PB z3i#6FAhu_>h<<6jzFQ&Qn?yTRyogW7d&;l#2)#Ou0S{HY=vQUe0eDhf?iAyty3jau z{mSeT?NFx=Xx8anB0t@HsC4Q1r=nlpBl@MfgxjHB?iTG-{CXjNnh&aT=q?zSKuFbd zB~kCZZKu1=)Ncfy6Gr)2xEi%(&AI(P;+Ox+*J5@f~CC?9|@%GHq8z<9}I4GX3 zet~=R>YyI%q;>GEs0-B(`6PD{zkh++wSgb@jfkhxIdiA;dQL;b*fC=o>PH<`*Dz`7 zgfR_c4m~6?YGPf(s0jx)Ogem2q@j#6)74Lj7jnl#9T*e8x5iv&Kl3#HT>@3c>z1kf zx#zgm<(Fr7uU>xJJH&Cfb7g7ndT&F+w8e`T&Y8Ysabv^r(-zKeSTcXfqQ;pG3mX?L znY*~50pn>HJAT~gG0`ZOder2}6UU97GP$nduyK>djUG3C+~ld;(y|*}H+I~Fh6$q% zshboTHKxu;%!J9K#!aZ3h={OV>3+T{#T$R%==oIJtT6sIs8y>b(^~=tO6?r?QfBYgJ_C){S(QzZusfgpLf$`fb@k{w({HlD^ zKjIump?GcmjF;_aywIcl8*fWL<8}8lUg=|c@kSqZ9uIWuz?#-fnPklQYHJ(DA39+y z|8Gov-I#;19w}Z@lVAK|KF?9jU(k=L?!%Ak=_13!{jAAbKW{D4FV(N)iQ?j*c+q~w zYwu^gUJ0I+j}N`&1KX+UCH|zd&e)!PG%$X%D!-Y5@f&+e5%0(Del1-BTjlkh#g?nmo1{jBqOJho@6yz$GB=OU_}H>c`v(U+a|qj4Z#6<)gp z58JcV-r~h}D!<{ooyRq7&zQIG-NbgP>-N1bDDpeV-7orK*SlXIEHodXSDo`~`CZGM zU!i_GRDRbU7{8^jImb)mh~A^9mvsh)UzdcRm5;&wxc!!nVm}K7KvZbw!#sp9azug5P8c2a)-5$lxlYlZgg zd(loc&%roU`eju7ei#_P(GQ&a5%Oj~iGHar?a-e6DB7uX>G^^m7o_?4*&816Rq0&+ zFGaln75&n9+n_z`741~<>hjB~`28|4eq;Yu=<=KBm+I01?b)xQU4QAqK6K_s$5UOM zBNDvqhy1*RZBp2{tE#^)iC^T+d;{Y*{E@SMmfy`qzcjzC(4K83+R^-4crD)QpyeaQ z`QR4rehaOGXhxySR-#|3OFOh@TZ(p6mqPjVs`%|SFn;47D|GRTeyJ{b@sf3A*?k$= zU!9K&d3aE0s{R)GL=ngK?s2q0d$yfu*I)U?{-TP5tx&|Vv&c`G4{%(6w)lO9GM!cP zu;%p?{5}xpf4cgq{Q6gNzbgI0U?-h#?BT9oE3{|3iFW-JNAMHp@vqQ)1V7c&B?@*@ zU51PC(zF(o3+Y7KR3`Ax3`*Z+5RU9nq90!dTb)n-1?q}Z>7O#q5_xsNM z*Yf+hH^1R8c)ZxYWB4A9-|I&23&Q(fWV+Be5T6Zlzu!WJXSIjVK~lSxF7dt**?n^~ zj&{lS^7!F%Z8Q$*H~6KudQssqIA6th@%|U;H=*m7%!m9hIDd{W0@pQE`~qJ&$BTSf zM*JKf9mg%Z4czM>4u05&A|4&@+r~ow|Ii(e>KA>}xgSwGGmRJ9sdS0Hq*!(s z@fOdAROg*H5$^Y)`L+D^x*y+KUV-Dlmzr^WR#<;i)xE{ndcpgp^%hv>`&0` z`=iW`>KytG`U^D0<3}G7e-*avu=}NW^mys}Z>f+cgpuLl-*KD37sl4^*S0(NGGW`{ zX!jq@{ALF>zu3>?J)-XHSj~EdI0LG9e{_#GFK>WH>(u5Z_cCGI;i&Vj?r}6UOkXl* z?&3M~8)h^e8*iA`IB!wo;)eMPrq7>g{BP{D;oDy-{i3n0J2>)F*y-vbvqN~*=MrS& zc*&#U^GoQsww>|hg+Xf%V)2i8zgkUx&_CrD{lR&>N4)y4-0={X{pwy>NyMXdig=Od^zd4~(6jR$+rM^+<$8F5FZJyF&+FNBDC}rGxBM*5 z$HRN^^D@-AzDv(98={xD^v8O5O`qu5u@#zj>*(=oQ{YkkP^Z2vnP1)N?w8{Ayy?7t zVBv4zj)!)=pK9u|u^wLQXYP13j#4<^myJWrr{_1C_2!q3&n(NwXUdP-MZOTnakjm9 zesz-TU?h{*0a?R zU+{4)0e)CW#G}V)8V91N@GEn>%ghiJYK}bbtLMy7x>a~h}y*gPnC}l6US#< z=SLo_+FKo9JC!cJcSXN=K278B0Y6o|F|ecYA|JNDm|t2i9jL>8qFteNVENtGn||?e z&d+nBxK^e``9M3$kLr?@_{H{YmZ%HWIkW-vkC~z! z)eqNCljkkWt)He~Yx#i}lpp?G6-Ni~kk(6+J3n2&$cN1p@u)754MCT`igr{NUBA>W z3HZ`@=MRiu|3=PrYU#32^h!;$E06S@Z zn?-(9=QOluOGP_fomKn-n<(la=ITss-JID=)Wh6cKxMa z4DhA-EqC{eIvu9Z7l= zSw2d)5_OUJjSxF&K1dy4f1~+L5(v0VLzpHh5Ol_?)kOs;02B&=3B@6 zRRWrLySv*_olCY6^DDbQJ4ozs9i8GOBz9K3r+Pcj)6H+1_?5-cOYGVu*Bb+VQ5TsV z<%jiR#arqvA1UION$xYJe#2KguXAMyo-A*^ZN+$HcGRzI+-Toj#FNF*cC>h$PF1^) z<8;1Z>3py^ov|J5zqFpwj{42B+m6Re=Ox&ljW3L!%5SsE?}UNz+oSS(=)m~(uMq1> z_Pyp!+bi-Bapz~{?Jw?jd368{Re1~Upy1ayFn-%rerLP;wRC|O{8+``*pFL<>QcX> zLYF!2{0jA(Qu#f0VEl&uq=!#Cx1KzlnXFuY*~2y2u^RvV#}) z`st5)_6HR4E^+5)=VRxp8edvfevkL&H*$bN=M%i)VJxaRqB|?}J85A2rd57V85qCy zyC~v4ZD9PSRDMtQ=C@;vqF&DQhNoLEExRi8J8NM4vLOn;XAg|uW|iM_2F7oX%I~=Y zh4a1nO_TF2+4*W<53V1^C$ozlb%~zQ&-FKk zx=cy;p@UPj`$!&@BjLq)%`I8tAVcCm{j>&j&QQldE? z$gVH=7Hi&5Nc_si=V(xjL*_Rzh1Wej4$?Yp2Ru4&qIMm3>fvF3QLUo~%6J?qe)V9d z;uriz)J1lEL6=`jlV50>^Y}vb%WB4f{8YNc%6Yt07i`a-TSvIQPw!K(?5fsxwWD#+ z@t|pi^LT*xsyIq36mitJ^Fu%EP;)wT6R<2?WoSZuQ}J1g*VC@9=4
^;h7T(zUwuX^`O z>TDc0VW~&i80qhAx4C!foP73;g1ODgLGqs9-{=9sSjgX!n z3iV9?T~9B1sDJr%cJ=QkqaJlEoFnRafscfot?TvYn#V1i2_dI#-lneRRaWW6-9CQD zJWcg*(lPgae?6OL`On)x&yl_S+okq(l+MROJttV)BYA($^dAPh?qWHio;7eOJ^MZ? z7PrFnA;mTHa?k5g>jKjA6QQ2vNA&cvhxzN-5SCBrI+o>w>Zx=Kt7p4P?M%OXX7%&u zdZHe!D&#~xLU_a0BhFb^%bzo??!$g2jC=hIyFNh>X}_cZ$G&Y zongzDd%ypa>uDRmw|+?VXkOvCqjRA??x-B;uV-u2f82rcY2%EXK%B9VoarC@-*6@s z=OQ6FCkDl7S$9!X>%rC+&d>ApVCAFy^&IqiuqTA|ov*LsKI#wb#DLc)KPlwwuyxej z2OsR{y;T0;bBlT;ZI_-Aa+V5uoVm|A62kA9^7RJ%dW3YJ7jljqqjPc}>A_~zcQ@d3 z3q2<`)vq5W&MRl>reN=XmN(PWYcp=n;RyRn(sjT86zVy4tga{bIcG+=E=YRc@Ks^E z#J`Wgea<;9{5}GIznm%VuL(I5$Lo5wj?;b48F@lh-);A0knYRExEFt@b8#Q(!A=O{ z&fnW+()0C@dUAci2U`<BFZ@X7 z`!iu}yJ*OUM~JQP;D<$^rObtHQWTukRgU-19}9 zll$OgoFBfY-eN2X`&UK!^nAvrmBpHKaf5pvqru^`rw7(D(9;U^&FW_=UqCT_)?6U z^A&ca`$T*@{GfV%7E({HFY=e#pn4_)>IsgpdZK)Slb0XUc+=^3B@rst&A=;=9B$2#iC#dIE|+g4m-zaT#NSa*SZYHB@8VbXgY zV0>rV9+Y!U;CnA7?2bBgyjsZr^;|6A!kGBSi6&Sgb!|RTZXt}KdGLH7{&eT0Xgfx zCeHlX{&5#`E~mH4{Q6!~>n@_gcAl@hh$&v^!>xGTg=L)p^!!FZJ;4)J&#>h)CFG2j zDbDG4$&UWUKkf}xu5e!5O3NpX`({8+90zXr+>S2d-F{*}DQ9F+N@vr6oVnkUj^j#S zhPR)wrD@#ysj&Zqv@=fruvB;<7dz__@N1eJ}w zDGRehfxFz%Uih_`Ctl*V1knGVPa*}`)2dL*6y+)v0ksdSw9Bk2hr+}w^E z=E1O^H161cDBh)i>9&we8 zrngkj_8Rn@-Ooen*<{?{gSC}U%qMd_P4me+Qu(ybd-L{~`{0vWsh))t)%Vjw>KVU8 zF9)2@Rz9Vi*-eP^S3=Gxd#_Q$!r9th_MDWoo!_}vkL>gFg^zXpxX<;h8~RK9`fh8N z#;+wk&km_)>@uC3a}G++jym660_qu6>jCQ)PLrNEA8Gl_uTOdwgnD*v)35KNm;37( zvApjBoVM}_J$DVLC-exbCoiAU^`Gww*W1jr{*$c-1wZVVa9yRX9!;ut>9@kT^L8nB zrGMO|^@v|DO#S&$VcdEDo%_%c*3_Tpakp`%)VSclpqzgu9cya*0WNM$oY)Wb$QJje zihDU^+_Sa+o47;I?*-LU2@+OM9(S9b&W6-}{!pkVAIDWy{1HcPrQX}jN zz0=oHyy0^`_+yKc4)D1}`IN3x{g1Hy)>te!#3XKEwT^F*PZ{JTu08~o!g z{Z5lD?kN@b^Mss;d-^1rPaYZf=ak0X##v62o)-u?3zzHVvu)ul3(KdCv#IVMog(DK z{Uemmu^avMl-@tGaU#E`h3^x{?Wo@;kM5xRNDnr8jQ4yU>JjFbr0W&ea_hU~J2)SxcB<`_+LoJ%Hs5U z-#?quM?U$F$RGKHEY1tIsMgOT?$UPY$3i_DiZfOxUiiqL+r(CM9pT&I2jv_Qa`N@b z+(-VfBLiBeiu6tua&rB+kMv+odZK(v^(@>$arsF=&e7W`?sXM^aB*wm#C}0J#{zO9 zpRk+iCC?*7?;stKo~d2H?=}lgK2K}nJVwYl&N$nv>GR7rF8;eT z?l|sPVcc_nB|QtvQ~L=Y>2RBzKA3i?snR(ujGu$sfk0_c>?$1R1Bae9jq?lXG*%kn_h~}TuHUadXbX ziL$s$ubcCR3bj-7IMZP(e>m$=bRMkDUEwf$XRUY_hA~0n{(z*@sE3N zxZ@rqU6;N{ciiF3SH$~Rcz*Et_aC{B{kX-t^kP|Gzm0L6^gH!0_7b+QQ;j{Q$DR9} zFMra2#+!FjTuv8`H*>2{yEOU_;;l1o&KcXk37)W=7#D+6T94in zt_$MteT+V?mjm#_7NqNfEbnJPdKU`ybS~7#TaAuCXF|RA1Np#0&$-B>*xrtm$=i>g9tVDkz?zZoD)b66|#YF-2%j zncnyLls{+s{K2%JC?{tN%V$+_O+HP0@R1I;liLV6E$vd}ZA#~EVcdDUlu^8#4}SUI z{?Err>k-oXbwE9FTv$EPeo8sh+mfEY3CKC|EXBR@jDPu*#@+V*kjeF^{cH;39(iBC z9;Fp8^yRkm>0sgxJ<9?01W#B!5qCG+Ud~7l)-*rgZI&eKm&(uSapwNmpX2I_#45)Q zeWAE?Gxd*?_jvb{ZP(4>0u=Xqg>fHe&z+^(IydxyZSEyo|7q)gCN?0>N2Hva>0BKP zr}+7IOZ$oQzCu_&bL-IeKt`7&TY6sSMtZRAg0P*p^h1!|?}eNr|0J&R-qc@$k94@r zZ71WjwM)$D_m{2rww2GCI^S~w>Y03zbRB!aKkiaJrJUym zK7YZ-9b+$2`ME|I_mP+NxVMz9;O4geV`1Da^*wzoab7Ld6ZJjz z8pXT#l7HN#_1#vFO8ZegdQzxohrQ1#@v=W>$MT(J#NAdt6NeG!GeXYf4mwxU!WqAR zFmcCt^K~I7?uOxR8^-hbL~CXBhN#^H0Kh1U<*qd`;N-5a=!~ zpQX1+&o_m7R-V_}rTnY@agUrbnDU8s=^CM)XqTWz*mfysJD+@o+RvMWdbU|RUsvrY zxVarURi>xydQ?@MHw!sO|E-UYMql@j``Caui}TaG^esZpu~+o+8MVAWxh3SZweyJ6 zdcyLFb<<7td`H;#JR{%U{Acf-iP%EcG>+TC{W;~tt?xO>y{X5U`+9D65AD+EqbXj^q)PUgw)sP9tyW+(-|$^GD(M-O^t|de;f#USnL`M|!Ze<7DFw+qf9% zT_2Kj{1g5DG17z088~_SY2!?&^+h)X4(BW>%)_<^w`b%rj)( zA-<}Gvtqd45tj48fSkxDEGOcQ^`DqeN4lnV=@FMxGQTvbbVPdG$9Abj+->&}klw>W zJ^6WaAL;e&fZhv-^fnQ4^7mwieZM#24n3vU%}0ft6YBlro&Qihf{*j%HY;4uV2eBM zAN@_p$>SXM{?SZ&TCPX9-*KCe6XTA|Z>jxEDP6ga@CS9@5a~T8^+=M^*HBs#$2KN-dEXTTqE!L_dnBz`Tq{i@fY=Rhl%qE#o0A}oW&2>c{3m70oKMT ztw&k)9^JffT+H9Ul=w*J1|O{SJv`Fu`}@M@r1<+o3PjC*n(y`AAc(u1v(yvOe-pS^6|ou%tkpK%Y6tW%9C9l^nUZ08p1 zR4b<&?!OE5{4`+P!4Wp@(9_h;SARw4(^^|UujhIJ7_wfEMjeWKbcif`aC2+Z8=U;Q zY2s`PIl%{>&&w&j9yL@s|4)z8-hQIq=%^ty?~s^CoCt*XLp{~ z@tCJIeQ!7G?p}0gPSdX+68VbWE^#0HQVTt8<6@-u0@JfPi_U}nYK)Wn*bla2S?3Q< zTR$YG-eXo2_Lq1+B>PqG^8u&rJ!Yuy{5|BR`hKvg@7?(`zqmVGXYK<~+0+O6{So$a z?>+L}^2y_3ny-7&<&@0V@$$fZ&SCSVaYs5YvGR%S+-7E_I8Q1IpYI31x#nQT#Ypev zfSfokEGOC}sh+JLQ-9`_fSlwN zNQc|nhq8XMw4HxV$eFxSzhBIK&RI0PFFmZDlR{3eANM(@Nzb61V+T>Y@j*b&;tdq{ zj*36$gKy%*@2Ky#byn3es_$uE z4?9hddyCCGfDd*=U6nWR!F&boa!6s||dSd+ET2@atKTPW}$CO2S2lxK4f0wP!IJuAXU{j~)^ZD2gi+YruTc+o_ zLOn|j{k%sP)P3X+TmG}Zp5T;THw|BR$w?b+DW(2{~&qoioCG@WGB=I#|w?LvnI%@WGaZoYL#&Dnice zBBbZ!5!4TZ4=!%Ym&^2&a;_%itS+j@-Qhk19j|)dFUD?Ym!zDlhvb}z8vx4Y)c2;@ z=Dr)0Gb!Zc{iDocOy52M{gJWsm$3e`eTLqjH_a!n?T+Il^U0Hnt9T}*3!mYM-JtKE zKfE{I97@^V7sTIh4Zot^KVMPrxexsQdCNLLocL10@q2m+J*jymxG zr4tXyIl;KW2b;f7#wo4uOA9$uOX+%+m(+dm!KNM@Eax&IIXO4@VA})YEIvf%yKG3# z4$~KWur@u>E}=f+I8(cHw6I;m`{wZ;diY2`s14fAFDKMrevYgj**N1rqVt^=l5=bsUEi>rwstA`AaO1)pR!eR^O5CalL+>{k{zU4hHv;9<20x6Sn(YNN+)*p79l^9cm~GAL($LxWd1_qaH~) z7YfJ;p0J!j<+yBftC@2fS)%eSY;_p}r5WfHr8{e;zRIzzG|7 zT#th4xkOMs6)4wp^1obcRv{<xwdHT^kL-}8SD51&uYu0+=}(>njtdwR}qoll-nT#;YWI0-)VLq3TWDZj}T z{I8=ZpVIrV^9bY4zbjH+%U{o$@H->Y?>Njafvw%B{zO!a*s zAt(QCLx+9OgL5>6?>(q~qK~&toU5^Z$mEsY@hq)F+eg+V3!n4B&pjrq?^4dy8E3}A z368LwxV|Iqwsr~meQmbxU-o&1w$c&DaUa`ZTMgNI@5xVPaZfTmkq@_H>ruRuBV^(8 z{optLA&a||bB%zU;0Vjf<1U>KSyRZ_QaUC!AU)xOo7+fBrl<5d=n-MN)Kq-nDXvev z@VQN0;6Ls_J(B9VRzN+$6IM?icd4H1ht!kn3x3#{t=jS&N>Y3kI=ZY&{=*Mkqz)>te(96l z;+@^pKkm}i}MREChKs_7tsQFJ;4!{R1EuYeMelww-`DuFlQBLdS6@0LrB?sG2P7C$q{kX9G zWL`e`d-hE8idzWv9NAjeucP|)(2v{tzhw2@7Wc>!6qhXn>X}MX{7YNu+?-Q7?vUy^ zJ*1voU(Q)tT2?-#?dK*!J=-eo$!$qT_?!=ZL$xRHxy86cdY>yT)HAYxUf;*I@sE4$ zU0L~*>bYq^J)uijJ$Zf4eN8ql-b$!vbs=5PmWn^PxlJrLnDSYAn&Pr~NIh$;9B@uk z`Q&;=*?US&?dLW^JrmpO<&pcGb9{N3o>Is$$iclPxy1r**(C0pH(}nmrv6= zmhD|m$-1@Te!8B8jP7$zn~!$Mc0G!2M&j>dNK zkNcp$HvwHP4akY(#_kKp$@QFU>FJo-&wYjMd~07ly(II&51X3Dd%liy+P>4&RL^%@ zBCPKt8|cqjMt9McmCsyE3uc}K9^qh zUboU7qV{Q0SpZ>u9Z%QP&hPJXO4|88|L$}ieIFSIv}iwV?L3m*URXXOyXiV}AL+r? zR`kDaN;zXIQ#v~Y%oO^UR1@#?#;Q73qs7KPc|3TQV$>T#xn&$O#^B!{;{hsdqiXenIuzJ0xdVJ$c-1{bXle>L*++>?fCA(${;BXEb`^6h|}$Oqi;xs6Qok2~hU__yqz5~y#x?M{4a&KbkhAa|owLcfIY(*0oI8i)4if5_|E{hl_rV97Sl+)~ z3R;h{LeAKz&dGi7!Dd&H#a-Gi9W3OmGfwV<54JKOJ&Wpm_YiU-f7sCjb$ziNc2Moo zq~hE&Bxm${{+uacyJU-d`$Ot)?-i1B+`^gpK-QnPagMD<<@{Sh&d6N)dt`G5`RiF0 zepg-EE^RM-elv2g&c%I{%f4Mu_MB8~T{bU$4}CwZsw~nwM5t$tadIE&!NyjQwV!n% z=b=K*>>;|I+y@_QH6i1S9-zP&V4OkwAx8?!=ftgg`@wyFe(m?Y+a-*Pd(&_3LDKI%GFrt3LU)7ukp!A@-BuO~Qd{duIfx$t^aK3uPt z+(&w_?ic3t)-$6xN0mjQrnsBx(bX=eq#p6>2KTFTd2==tU)zh* zqg^s_UL)j0{Vp9zafc6mQgeHA2CeTV&TEC7(64p0YTwy?^Ok{gPUP@2#gP?&!};?{AI@?;G;6uwr9|!f5QvIX;c$@W?CIjk;dBp~s zzc6tg4Jnfy-E?MVkCm0v^ z!N)D;Y59FC=o$S$7Wa3B^NN)P^mZt@nC^4F{13h7KY97I#l7_-s*fiLT zHRd08)Ab1FgSf+oHMR41v+EJ|pUJB0Pxd6m$F4_(CB55E)AhZ_8K7TxkB}4NjB%{< zXPnigyg5z%x}cnmfSje%NKbG>_f~u`oTlsMy)I{vaq;Mnh?9>uBg=Smn#LVL%jbPU zJ<;Fnp#HG9k1XrW8MJ(w^t?Zyp6#D{>pA*0Z_YvK`9MHD$A0Er-<{>WIeqm+;hthm zdOk>ciu-j{)eq(Eb8>laPE)_mR6b3d4+Z2bo=$pl&Ya;r*@NPII3Q=@3~$a-BAA{S zckp#Vrt48tSU#~%Gr0#{*WsgR)z$mQ;oGb!?k3K^2|3X&wSMkhk0#W6**Ra(dSv4K zdqB>3$(u92ig(-x#ra4;&W3?=JPc=me#oOjPF&ANR67qJaqg_@t>>WnA&&**jQx`0 z&N*YN|93h65sPkHLQb?x`7^!idvr~2JqK0a zp9sh~{wr_J)LOwfG2Z0Y3qH?~P~R&V?_C(|^9;4O^!FY(6U?6yyY8R4V=MdX z3q27Zq+_x_6zW-3oJi;M>M5;974;tGy09Mc_uHiY<6n;w+xyp}pzA+>)YEguI#uY! z?c{G&d!&BgetQZ3IP>&^a-JaMto%;rDrqHE2DO zmQQ?#@uVK7y`AUfGwgR5+pExhI&kvw5x*Yg)%PM#7II>pZ|WS1fB6r3Ie^Ttrggvg zJt*fX0XdORSWa9wc{`teit3@Me4Z&RpB<%R@fx~r!Us3QaW((?A5_m%g?d(( zrRQZv{z&mIo$DX>+~%_T9n$jolYpGiFDxhG?yfuZ{0_LOzcl7@O4b3km5%KvDemyW zonrH}^)vMKv)B)om(Pk}{uKM4*3;8TbuXWO>uJX-6zAl5WZ_3{qH>6Q@=N=dOXO>6 z=kYtYKV_UP#liOjAGUv9PV|#`x~91QOc;00&wcPq?ZRqDTRlR07YgqmrLNZNH}{bq z?8sjF`Vf5AEWamhho1a9@+Ljca5*LQDDfwqll$P4TC|^h9+h7=OX~TxhOqxxd7j?O z(YTO!n~aN{$PW995+dOftszf(Og zH_0~s=3VdOhtvLud;SJ}+-Qn>Nf`II(h<6FAKRriXx#4&7iJ$;Kc9T z2EA@x-fKVY!S;o9esi z{$|^adywaPnuhy^xK2Gs<_He5hr}4AJl>q-x|! z$@QtfW#XJ5&i;Gy!NqO+TAd$0<{6L=jvGCd;_kCv(Q}^G#QBbpbL={ull$Q7+v>Dl zWb1i)PQS3H{(c7Bhvnm=>aWyu{cG#{KilhA54n@j{`0iS>vc}<_xaQxvCsVPf1)0B zR?*kDo9g@hy>#v4qZZ@jKIcsA>b-s*`+<{}bIv(-5S5<~dwSYACnCC@ojG(L`NP&e z^yWl;2PYr5a!#c8mXMRbUy=Jr57zX4MR4-_2rab^#x$>ZRwexJS|yhl+a7Ov%x|^YptO=TM5zdxHlye>25Bb_-ef_#OFl?xOti z)5+p@ZcTAFasFP&2|nca-{Kq}CLJUD>er)lgq(GyBRD5+*ZYm_hSG0qvZGu1>v{1) zYdh<>iPd&pvUh!jePCgC`w8y7(KX_|?Xbl~)^-+f2LRov-IGsnoYJ+2T-CLe-gdV? z^B3}Ao9^~*`h}a8>ZJqQUTke=L3exNR@xudS)8_iMWtW7TBZM&Bb^1@eDcQ~+RG2N zuC`~6-nF+Kw(V}uxM_eh{T7{{bK8-j8}g5sfU?jcI2R;K-7okO}mcelISP#(~JzUFT4#&L9< z$}8-5j$PAj$7Zy*#Txw{KW-QS|l zGEVnCiQjs~k$ZJc?sxMD@-Jxl+|Err?yO*qdz*1`KL}%YU&P(^{1MWv3g?&bz1_O{ z&TiQ6*dpIP=STW@&{RHW6TUyWv#>r-ncqtHkw0weeA#@RP0x&a4&|<1uioAd;p_Zc z_v_^qe6ZzzdvoG<=xO_oSnYXArz+&+-`g!d;LiyjlLe=3{ug5E#+z-{NJuD5BZ`$zE?b-i%^ zXhhwg;r-jm+q~y#OzUlMUmNM+q)hjG}~f z=nkHC!M`5@J$YPAdVUg8Pp&Wcq!xPexR|b+pSqlq@n-Z9D!2JKwWFhd_b$hMPT~D` ze!eEo&jNCS1KjXuvKCH$|0uTswQJ4OX}-I9hCc5dbH6v?&W7~Y&!?aC)@fYnnR}Fe zhmZT($fu$1qt`d`ZclTE(tV|%oQn{r^?nDqpc{N}PAWa5oG73CdSQzD{5?*4f2p(p z8^M?eUsz3Po zMvkO<-eLPM(TltNeF9a+$$jMCw`~9ZcJ&81`TCH8y02Lq(&wiR=pAQYAChV5dUBt0 zq||#H_;&ccxDUabVNK<8I>o&|Ki}RY7)OWPQIL@SJoau@Exy5xV^)&Iq=le9x#d&3-g{iS{!^{ZxWVIt}pkIkJJX$^J@Y11PAnm&uydXzwS5ay7Zfc z>!`<`qd2!z+~IRR_*ujAGWb2Hp38;QGi>=pKRKwLw*=G^dW6*z>- zSdWU&>-C%a$cNj+KlS7AyUQ63ay|Nskdx=fedI5-LF0a#Fz!vIOW_652fm4`YNUoDy&xV>`&c8%)hi~F)4mj?A4af zd5{qD8GVI*hmU?8@+p)kztpMpeheJ%{BpK#58g>-F%K4u^B&^dADsPk*&pD-X87Q2 z{gU{Moa(?CoJfgm{w#kzpQO0==a=-OXL!*L=~#P>Ec`z2uau7Okc}vRMhf&-Md^w1 zDSdCuy~6T2t~i@>QGXsj=YT(Xt=_N0`QUeqH~Dtc_5D7VbL#ygq{A)BZA9q_pYJF2 zG2WDN-Y?_?A2>cQC!bHYmCvUr?kQV6LU{xyeCSaLSUx!?(v7Kh3G;l|{&bJiJ`a|C zo$3#cgAZP8ms-p(l^^$>&*JI)UOiA}o2PZ&&^bFTS^7Lb_(ALYLlk%GI>4&pOsq!p z^ze}{w<+uONI#-^HnnFHYW}mXEcSYa;@-b6gYDdA-XuLsvyqPQQ9hB+h|16T4du(z zadxNcQP6SRaY8*)-`C?jaft47p2V@<-)X`)E-2@+!u2-obxF_iEW}rNOE0gSv;C?! zC-&p@y^|vSTk1YsGqwqFh2>1E=i^M*&8>T!^VNT@^wiIC zhF6{-9aHa+g%8f$5yV+jyb}w1>sdG4-?VXVL!2qw_n^TAa`<66=R-ouMh>O(GOhpI zw#PZIRnLynvGgy}6FzwR`Mg2-HNWqzXZ-tAK7(>@N1RqY!37!MgR=rXgq*l;^7~vS zJu}4VjJW{a`VJ0mN8TkJTOZK6Z}@ya`02xFfB4+;b}8`#(%&@iy+e<4{(ieuxX!!2 zw-x93P4qi_l+W=36;-tD}Nb7!HR;DVm;!*Ze?m3PtaZ<_i`yYx8i z_q9vAsr5kLCJP_jEu|;?&aQg?*bd9fXTIpIKlb0X$7z2*ZQ^~s{=$cz$S1One}2ff z`^;02f4dQ9zn>h78p`K8v^}>U>BPs~krQQnVB>m@oJ7Z);-00r_xs6>4|Ls-ZefzP z$JOufp(paGDBh;Z7sta^4D|@dn>cqTPHVdaF60LvoY4u=L&}MH2Bd>@P5q@kTu#Y6 z1J{}R$VY0yiT)vuGjZ-IjH&d% z10QimKKMOCv>b)_0yPU($yw>MCaNgjU$-kY|_i=h}Ork{NoRqRSp4WHVxMLre z(_H{ztw$(F6Kb3UA9^O$ct|?#!1ajt>rCqab3M*!)_z^|6TQ9SK6HY$U61%s3*&f20hzMfV1Tx9$WeZD>Ssje^bht2&= zUw4M>uu{(WJ5(Rv9_}7#Uw47^-pD8NnLlTIZ}0V=I3Ap~=TM4Eke+i3^^9Gm>shmK z#(pEy6Yu8*KQEt+cS+BG3H2P=UVk1o>v;E9kYDQ_8K+H8=S)gxk&t>iL;jpnJ^6Y< zu4nQ;r007=Jqxevaj#l9o2Ly%&xF!*(U5v(h6kgk?fH(0g{U5VAk=f@VqMQk3uh`P ztM9gT>FG6za~YwYt&(1kDqr!}Gkc#b?l#WGRg}(3LQeiZf%I4XIc@I~K>KOqtg81C zEGOjb9Ifj)Vc{ITcQAUQom(#8yf=;uJMTTy{Jfdk1U*N z#W@_3v-3GQc|RHVbxh;UXX*ZtwV#apMTk3m+&>!qHTCBQeg9}=gyO!MP|pf`-^ED8 zKkl~oUG%!W?nz6Z?|9DDQ}P^2n{ja;I&+KrzRivF`$5unDYHK5xrR{B6l<5pX7|@K z)9`PXFh1h^#ey}#Z`+8dH`~aR>B7eZ+B1b-%EFrmp8dm7ccy@5MQFJ-Ls3U?)!XAD8s?d|6MI_dhGoQUCKE z;dm3@6#_?6-S>dct?9c$xE=*vC-72FPy0BIuLI&f=QOPg!umSi&f|E~`jA(I^{6nn z9v}E<=aG-pBJR1D^mKXLkzPvpJZyC{y}ZTe(bGqIu-OZ#T*2oSoVIaX;wgHr;TyuZ zXExV4C#LH@=g2+j{oDk~Cpc~WPo%rKP|y4{T|e$4J=ok*bRB`uE#_&P?EZvlp7z`B zJeXuYnUA+j_Zv8m$q#yc-=xCvM3P*`pryzoVsoFttnH z>2ccI`P}@(nOcnOIO9hCeLL)5kHBf02Sa)XFwWLex^CDHoF*UJVbhz*<{3Ia*T=CY zJ+~CLOOXY1e(r-0w!W-PPg^@*dYand&4lfIduwXfi`$W{F>dg|Hq>+eD6{84XLN?(!1y}h8Gj;VZZ zEi9kag>-)I<9uK<%lUKSx|uym?0{% zK9v}8l@=#EY2l1-DJ!2+&O;byb7^m#z=`wVKDNV_XYr4FP(2T2oCzT(*RxpB>yb@Q zluw71dsF#5Mp!<1du3`Dpr_43PrlB?RNuD~*7x$FdU@bJ=Sr+3i@UV_JdDMi=La9x z_vn_?-tm4&?L0m1j<6phC4ndE)JS`h1;J+RjVs`w>D;)bF&qUh#U=W}LQq zgz_onJW|M6yo%cS$@Azw5`2`4!k=_KTi@|7pS(X`y?~B4eaGPkJ16X$Pa#4PPCt>mq^#teje>|O0Ms` zpPw}J`;ni`f)nis_BU}BLUM9$D|tcR6k!kKY1OkSLgY{FZMWR%rC{3^Nwf! zYx;KhXy=j7=q29QA>;>(xFa2GH^u!#Vca=C_mPj(q8}pdC!f^Q(>@PYXF7AA^Od*r zAICvY-d{55d3ION_r+uwJ4uF?xu0vslxJ^OHkZ1tB{3n;u??m_mhKi{#wWx zSy3;a+~>Tdxd+QRCgiL!PVRHg=8pdLJ*b|)5prf%()Hv%=SJMh|+51mT?dR`=oaNQ^@>y9`_c>>z?!PVw^%C<~wS!B5O3(^JY> z3djkLu$;Vn+SYp`zuyZvdEB{=^kB!P%k;Ee-y`aIgsp`4<3_)s-#;mBrTgH6?YueI zbr;(SIU~Cf*Vru7@9ZS~>rr(Dp`Mm?YsCdC>*U{7CKJxEd%l9V0 z$=7dj&g3mres&jfb}rQQOsuPO_xaQxtx=htw)$S$fZE}8g`DZF^>KF7!kNF@zkJT# zdpjUMJNH{m>U*nY_TAOvT+X<&QvbQ#_=vYoh4u99)fM#iwE4Vj{tIN7XW;3Y<{5tI za!T%ZaDMJ1f2pOXj~$1fuZi;{mvhM3t3SUqa=We*@@+7kNA}mt0rrzx)FZw=gx4da zcdoEsSKmO7dwzZ0M|!a7t^NBUh zUz``LseGRAa!T4Il%t8?sQS~<>rt6;BHxB;uiLEM4$AqbfSltSd2=Q&)AbxQ=LG>d za~peemag}{|6|gV-{-Qu&+5Wn`JC}StLC+OJfRET6E*g4)t^`Ix5E9ShSD?a`>bs5 zU%H5KmhbT9#QT<7>U~l0!I`_9;x2tp6xt(BriC=P^H*YpU}|d7lr`P44V} zJqpTM6>@fN)35v72On%?(tCV__7j}^J&C64`(LD-o9p^zzN!1*gH0VgSUoQla^~LC z_2fSIV9SQ@nQ}d)m@6s!MzKJ|xfyctx_+k|>{7#H_Br>$KIT0ZOD@+nv+!0*2gs(ecO^H&S? z9GOn#b1Y33KGzX`VMkfJWV_$dS(Vb+TeyxovV}e_Y%6YXaXWga|9l9_r&P~t0_q8# zuzI5X1gC8t4Ea@if7ts=$u0GEiTg+ow*IZb#C>EnN@pKo+}oGy*Y_6V1|Mv67w`TO zeutjY`v{Z07xUTmtVMOs!jig={QLGCZ#{Y3qa%7crt8u7g?c8o*5l6oKA-xdzM||o zXj^?py2lEyM@`1beWV9lo!whc{EoP{cF@}qlb**5IVbng(<^MF>x=whCt9-dDV?wT zgRos{Y^!s{nGZhL)RrzUt9_rV8S zKGdJnowtc}zjwy}ndX<4aCemSlVgmN`#e7K$l<#Y_YY}z4p5Jz{p34B>dE!x zoVCSe_cx{O(i1|?!ngG}Cvv*aIkQK5$DOzH((&e#LeAWd#Fe~>+NbCa{+!Wcyg6|` zy?I5C@@c9^SGd=sh%;@ddz|0<=c6wY*JxI8Dj)gQX7`>~tgG+ZxvA_v zth8Nf1l3ak_4Va|%9rXXjr+YJIm5;s?NV=9ipM#c?iVlZ?mP83!)zr9COmV?QAapX(^~P1hsScZHU76V5oR^u{iJ{m+rT^zz7kDIfOx z|Jpkbz&463?ypTkoB%7pEnlEepu6Gt;Gh;BkN-PC+DJM&jO&pX<;vUA^;?<{bh-e@)R+y9%Hot>Rs zK~K7V-lpe&n0hu$Q}aNvnToeaxKTdWqP=tb`InjXv*~bCPwG>?=*hhH&TU7pRLGf~ zW6tAH&bCS3oU|R$=dIb|{;G^S<2pk75lYX{9qM>Q+bQMr^AUG?T(h0WMVaII^pR%V zsZY6LNAbqp{I@7N#cNympa&NZ0py<@AZc%z(x&pbopv%KRG zSI_of1-;;7omEiIQorQ0PN3tTs{Z_q*)PS2ZKBSqrSrIMUoqa+k2mWl^^J`g z4vt5e4b1Vp?WC?{#<(wao z6CB`%Pi@`vy#AA`=Q|a0R;nlZrJ#BinVfi@P5l7Xj}&zLsgCdyr}6aUjzhjSyceiZ^+h$xZoe^%L81IlF$ZI6q}_(m2O%H0uG% zhxLm)mlJya%;bcg;HXqj)K4yFDysDSg2_pr_nG*6`MAgP<&T>s&Y#VE=y<;QW;Na( z%)D;cv5I-V724bMp)+h$=MNt?sGf%LxYK-|74^Xf8#~^6-9@EwcbMm!h&wncjeAhe z=x(aLe_NrR^||u>Cs$AIdE8~p`_4MgH0vkzp)+h<#5?ZzyworGTrbAn$y3nVi%|eq8IW4-p%4e_wl?*p{pT~vFo z3fM0d&sDtj+S)++>Uads>VTZ!s+1G`C*n@8$Jye(l;Gs7SHyZ>aQ1fHFE{QeZva!z zx+WFxc5UG!A8Om5VUFvV{pY}doZzXH6LIJ28K158cjGRF@4}MrbJyAb% zN15YTTm3vqWX$R3Yc(G@sE>564XWp$fO>+XQayvl9p%+9IaAYAoFf-13m^GV+otOk zO^46b6Wb3C$cgV&${AG8@Ep~Sh6Lnnyh!QUrga53wSA>0IF|{?37$$hgX$UiRgJS& zXL8c>_we-c{Sx>5J++0|FVXXN=<;v(jsN|ydBR0~NI1!(< znVhMa<~#%SksoY}&pg8l?h0OPy~x_`=bG-GZ>|{iJ3p$q)QofI=H_{6VzfFxs@*`@ zuJy~GFL94Y?H{T3xK2Pl^OICR(n`1&DWcxl^u%^t&e|1KI~va9q}R0)mznyad|1Eh zhFnhMw>guu$L}3oUY;{vR63v>YBBySTx<68w(;ksVjT--{Fx7Lss|i9VU0fHs1ZZ?K#gb zr+aMxgv#31GrS`>gFH{5?n1>$@4IyBy*X{q6IezrI~APSU(Nls>3KJ^enzi0^P|40 ziodst-h?~vJ&RdCJ2YqOok~ymR-(hr`bl-G(et$Q`?htz--x)&CuGTfLaw7OUTf-x ze44LO=}jjq&Kfc=l%C@q_jA$M3K&gQ$Fr~=N-_K-k)yM^H3&d?H; z@WHnA5ogN^s=e=5A!oy_roP~V?Q1>9F*$R$nOq^_gAcZIgT9UXu@!PsZt%f2kLGc5 zk4JxIa<<-X>Y4n9>4OipWL?}>e*1Co>X7( z!PYVL^gA9Qzk`^Z&K+i)6Is(oez3)rd3th>?}-XIDL43Fv#XTn#CSfjo_U^N8_yps zI63P>vRcpfLv+66_aec^wHPmP<9-NJPdYw|&nO>v?l^?5x3RVNU6`CL6U=c)mk(!K zsC?X^CwCn3S0*Rz*E4sP*E8+Y-cdhk+->zU#;l*6`uTdOf4zOq9yn=xw{h-KAt#;> z2=1U3ap#Vc$1>wi&)Zt=Dj)akFlPPq`MvV4Q`ETb9(Q8b|G1glNZvo_jmZf;JIAYd*SD6hpEf>e+F<*?-2~RM$INH&r&hiTCvn>`ze6bKT?7qTgMOJ!$eF z-`e|CdeaF=3Frz$S)@0sHG-a5uC&vtzOn>@Zd!+h7zryfxGMIKbv_B*oJFFy-T z{O&Baw{bQGIjZlKJw)Ki96V95)%5#P^FXhaolz!ab z0Z0Fd{6K5#=O+tJ&hd!y+jK{HeiodF6SlW;rYhv5+$e`@X*+8EQauOQ7Wb=}}PI2q!qJG|%uk*NBZxjDCefqu7#(mp=o?0O%<))m;KIWXl zmC{XRx2PxHnZ8cUlin4%gEDv)HEkvs|^h zkEiA+bDi6D%yCGkKEKO9rpBl6!G&_1Jym%PW0l3{)I!h14rW|zdQN5P8GTyi*P(68 zQ)d2@!_NmN&Rem)jWZpPv-ugt2X5pa)Pj?%=NXcdaUKUg@cg&+JhMX1-s*||lY8EA zmf+-^9~Ebt^|7A#&>6PPr(X)nd3J@IlpB1o;Z4i;pF!uB&T%;xop;!dhv<({@6k?i z-jSTC`XTQ8(!h64a<-c4IJtcza;0*~zUQV_Ic@u^bl9VdCyC#^s*+2@owLOE>dsly z{hssgNzU+Y>BU=)pCvyZCDOMN+v5AMX_3B?NSEEQ-0tiXHmDYFojLCIRZjD5tGW5Y zCf}N0HC$|ma@$gB`!q>E?qrpIn@Ep~{IGq~Y?WW~?fF%*T%<=QjdwXSB7Lw(l@O9= z!bvKh_eJ_PA|0I39pw6K$4Smt`N*)z?bka+ZIAkyn!}r?9pN62{Kp~bHnSa3Utk!o zcwPB%9XP{V^EhvFbNA=0{g=r}eFIWBi6eOPHhCuJKbV{a!byF~SwEepC-;7Y-DL%I z{Pj#dYwAgT%Go@%e82SkeH**&J+zr>*RbgaHg<+jT~z;T?>#}a3z;qoL3?SwU!~6z z>9Sq7ueQ3|9$;^KXk(*)NVlr~A(`9QZSUF0xTUQi(?<))nZeagoj+TSoobgh4o|#{cbb|=f)kJ zcLn4`IhAq-)f462&E#}mQaWa}g^zrwZ9KUA@rbJ@@|_is6W^Fn#dC7WeaRN6-`PhUlkYl-=KQ#6Hre8RjMc2k=rjJvu@T_KObiHOIS}@ zgY{eFITCqGzhrxkg#0~P_hh^qqkL=Qe1yqaywO~TL;b`o@BWiulw8C;{)t)7ZT)AQ z8TXDEs(shbRJQ3&Gyf8ReiJ{?yZ^*?h&%UrzmGEerMkCFF6yIvYVo|^+?D2aE3|j| zJB%HdsqMnk&Fvr4?H%WFv>f>Dgp>N%4%Tl!f^z;-b2f;QNO)a%?pFmiO8qXI1c)y%)iXvskd?3)-TEHD`{s%H_vkIz42XB zKkC=rLpZ~VGdx%IgV}G*`4QAlZruMAFz(Q+(zv6&%l_KyWz$n$KH}(^*Yy&4Q@=>{ z)Enk?yo+9OM`qoutsTjqN2qa@uaf&$F76HQtGE|;Q1?s0M-i=a$vC7|#XY9up3)ZE z+v=x{Qyz{4=NW#Sp$`;iVQ0k&ALYjMIu!U$o#M=EzN8mtY2!t2Y@D)scITw`eIf^p z7jWJMAD_pLBYM^=&Sw35s62U2l&yZ+=I7=1GDkVTTQ2U&50##EJ1RZlgERD3!l^&V zYQFZKoSyxsjZ;1zOmL>bnaY~yso=nKwoAH!x7_-PFL$%H=fX)o z@m#pHJP(k1w%4iSPPebRZ*kqMX`I>*_}H%N38H6%;*9I(gEf%fcXl~FuFKds#dG8g z&hQ1^oVY)%`FDyFJ~;DF63&?7v^~GhRzGd$M^Z;|+$_yAS*K~cSpHoZD<7z3V z-T~WroJ~&~r@SuKozr$dF6J%bTPi)_L(jxhM9;X=(>4zlR8Kiy(|sHgy3jlB^t_Pz zxn~Hc-hnP%FKZW?=Q~05T%K^|ES&WGfco*-gfpS^OlZF7vmWCm1f!d^9pB~Hi*tOZ z&*`Lo)6;}Av%Ki+?AHkRn3k-mEwqwVqvMTqll$ zp8dS-xH(J|RK-|#LGQ1nep8s}nN)Fa(ww=T_0w_a#aO{&<6KdE#u+csaR>FGE45|D zA)cJJkw@HZ z{k%L+>E3@Le`;yJPJOyPd|N*+`vUpGI8k|yW1C-koH=iU`5NTc+j$%Jc;um{tzVMQ zi4D>(fs^)2NT=4;FX4QXj=N}kk4#qc6>qtE`p<`SJYgPBBj2h1lybqZ(bp;9!{U5X zw%;JHu-;h4L5@FL$#XK07p_MYeo*tu@bP)qhot|+2NnxGx$|JJG4;&;+tic#6sO>$ zCzmsOvWk0qK+f84RJ_w)myf%R6Z;dC^Ywt7D5p|R)K73?{Ed8RJ3{)~OwNMVvC~oU zhmU-y4W)SVirjUoo4aEx|Ms5x){HatDQA-TTupAj^d?hJ^h-^hinr2!3H##~D>Q2S zUgej&NA(xBb$5xt{=(sGWm*<`{OctoZ3w8*PiPJU^|g(`FWerv1a|Geh1Ohg(&k6 z+B-d7*xLIv=I@#2e=s?zPmvndEI&W*K2Dx~N%*#LNSn|z?QHC;CyfvF)AyP6(*was zvT@q#=fB)`G}?EZjCu6bHcD6cC_H?BFiymsj$>_cKZe9e zXN8_oXG7oTv0z-27^jX$@WIs@P)}RjZJf^q=4lZ}Y7@Wc`uVG}@NqnH3aXqMU0&e@Z|?kf z_1u7rZdZphr z_3Zjh)ys~zR62ZcHodCKX?{uB#4E~TznqVho<)nEew_bd>Ip8C3!lxYzX(nokFcH; z`Pz<0FS(rlPLObS^IY$CpYfz$psCJ>j<$;%(xdOnLg!AoMx_D!RNGo((4hnxNpzYvpB%i zlltI*jeW?|({G*u`NiFVpnv~abC7v_>ZmKPXLfy_p4_;%yTJaObxWIiQXl&bo7DG@ zz^4|+BW`=2?`Gi7*-kjAPdQSD^5Ra%+qU|7EOVVzRDT3a#5dhHXp{*lUqNVnC-nlIH})*^DOl|9hwdw^^>mGvg!Gr`$hlynHp^BNqv+L zTXQ&1&l+;w!p8XplQS~JyBJA5FZ~X4yo7OF<1&i3jc|hx);6xg=ZL%C z_!FGPfSf3&Qcil@q}QEoaqn~s_OGAeWzD!#AN;T}X58s|7#ruiOg;0Ovtc>K3m;rP z>?yo<#N~W1ASZY#8CXsB5azz^Fnvi!Uv+L520aUGZU z1L~PvUh(C8IGsL39d>x5qIcW!)))T25s*ew9@uYIl1Gy zZ`^YIk4IVEA3;y*BOSKu*S?8+gRVax2aJ2yimHCbwFMWoeN{if*%6QvJe6|NxYO%p zw)XxBlQT11=@?r{S@__lwq^=1?p)3V0Xe}_DQ8eU8<$t-gP#WEjIN^e?9{q~n_8}( zt;~LDDzjgr=f&Y~6ffn2A6w0P98#&Cp9Rzt9F^)xIl1!;pEEf-biA9xN=NwMrnbOr zM_kS?0&;?qnHYpIklt+EH?KRnO0;upPDjP@a?9j{M>d zJv#&HiMUs)CyjfEtdp=EkG^7ZqF--0PtDiXty*5sMqRJ4U({k;SD0<)W8=Jzd0nRK zCo{ixAI{_`@BS0K;N;GG|Kfhpe_WUO+2l;GX8I@}w&n)j@!c=(c^#K;1IE3uy5g(V z7F^VFjY^1-6pMXaKW*)?RCJQlE0>zx8hKw0?509}Q;K&)nK3C-o_3c&GAu z%KJv;i{77Zn^(M3#J$?t(Rcl4aV2#>xyoJSzmCa`bgq^6yLr9vd<;C#1KW%cZ_?rq z_w^v1T6*1#`t|pc=W@^th%e@8-SzXdz1#F0DZbx*o;G=rw@$b(sdGD}D|}LX$<34d zUrQh8H^bdkfi%_buc|*P=}De9gKyH`Kc_kby-y1B-ZWpEo~sFv?s{fVH2X<#I+`E9 zuMWTTdB8Web-%WC>1&AmBhI3A>Ghj<#~t%k7%##HUg2G`J`o>SEXGUR^-DvU{ZhQv zc&$VS3oQda|0$Po*&h)p6Zw2`|;R5 zxAmX4aouQAc&V@n5Taow(-&?BBQiZSGtccvZWbcl#|-ROs77!<67uR^Reln%#{$aOvbX(KvQKl4biaR~Z(?(zL#=JCC8D>LrYr@I!N zQ+~bo^Ye$>AoWJv(U!u>Ypnh9GPQ=~sytw8& zHJ<;jT7vqI=To2R=j*xqC7x%njad(La>*3VFF&4#o;{B5mggR9;pV(;sb4A;MBaqz zO)lyu13updoY@0-{rr|LkAMBl5l-rp-STz8NzVsu^;7;voa6Y{&*bk+J*n>tMm7Lv z{b58;OWf<-@B7ESW?Pe!`UJz*MLXi&&-JQ%p!IJ@t%Q^M6f8Hp{P~f5{-j(_OJBC} z{PtqQ8fSIi`Q*fQrk>QN<@x#U@5gy;WP5(y@5QzuXN2$b>zwUP&K|x;ndOpfoVIcD zjv}*&Gt&2XlqHFrSKV*!rbknf0@7qB&lu`NEuEMmew@x}Cy@rS;Q~Go{<(Zvi=rJ1bqA zcQW+_2ds?~pWFIRTio{&Uko|^aj(~WD2Mt;=UQ&uq36PYdV-@;JrQ?Xd$%2r_7(+4 zoV9(AM@_q!ai%`_xfXijx*5J_Yex=qJuTL))$Xo%>vlD{QBKL;RDS#kPQUZbwtuL6 zR$y{=?PqdD4>bJ}pMF!T^QY-f&wq+({=so#UsCn2bw z0|M%a;w#k?ad-9f7>C&O+|Sjs)>qFq9dB?_AL(2RJ#jrB-?R0f1DSf_evZ25)cT9Y zv1UC$Ik3^2dHtu~{l&;{7?U%+r{ZcoMp^jChuY%pz zLw%%kt*yP==D`jS8K)gJw<({SZ7Zi?FEh^6w|&o+&aI!#y8hHK?JW^`pK=k!6z*cfa*E z$YcmJ?lt=;&Q@*VBOhubx0Y}3K{=NR$O)cGIlCW^kXLtWi~GT1qqMV{?{$Pk+>AT* zyO+gz&($-pwWJ?`v{XHov&r`gxn4hq!vK<*R3wa8aLf`uRciTrQxVrSb`P zDP6y@>52LYPQUXby5JS<&Yb7ampD#XI$L=kwY| z2dL}Chr1as`n~edQD%HmZp#5?I`vUby)MuBXZh>#+_+<&Arvs~?Rp-h(s>5#x4f@F zzUc3_+Q!L8h;79>meM+E_sbstbddQE>U(^}O~U;ou-Fd2D@5Z$L;Mwc5T` zTWtRq_f3`Wb%cWE#P_I=blB+GN_Y6w;&ppx+fbK@`xve$w*bw-HY2M{}fprq%CS#vWI{E0iJi z4fT`eW2>Jhx*-1bv++n%PwHcTV7c{^yN=~=ZpQxOqNqRGI*68a5^xMg!RlNjn zZ#fZnR%{%5@(mi@tg*!0BbsGmLde~voN z=CsB3De;C=KdH{tM}AxzRL_+H>RIBbP*2oPaB`pLzcQ1vOUFCYpyCd{#7*AB?%-YT z;Bu}KkP|qSat75iulF|`khA44O3&DF-u(jhgR3WZJijh;Jl{#Us1H8a)Sl(X^W6Fg zJx2u86C9Q5N#pJ}PHy-@oo8*xvsnxluq)@KnkfR8N$* zF_W{nwVGcjo}lz>KE8ZAO1;4Am*{;`w)5ikneC`v^I`v}k962hW;^nWJM!B!pq}_% zrFvEx_cfTDb$?TFZr8Ty#PV^E-OY2Yer*AnU6>?UpXVAFE=BoW& zDcopw-<9{da;2af@6Y;H-GpL@$_m!Rz=6dhYmgaLL3R+iiQ`^1|@A&T5j^dxF z>znH_^+Z1(nW*BOnovIO#ZUU?xCzen19C#QN;!kZ9p%+BIWZ0iPf|LzXVprq^$2fHe2%z>J}~#!Hm=)-$r+k#a#A1Vm+X-| zPVVzm>zSN6!b$xSpMI0m#}S$iAA0(=qxjdVAFgAzBlPn%rzl;MDN|pR56d0Tb2&E) z$O(>0IcYnJeafq!+cD$bs&xb>^^p#nOY-WcpPtBXbEcl9aq$!t@5HI)E+u|pS%FykIgoAr_URL{bn`sR3)`9;<9 zZ3F7re1_ufAl#Ib+m8JDd2ntQkP|$Wa?-f_aiYBKnVdMj*PX5OtUuGN2gnaLwvg8^ z`QF#_y=sqpFgYVlI^K7yaahrZvvV(Ad*_}X?Z|9LO=p?prQ%}Sl z9F@jBX#Ff!tNq;}AZPj9E;9 zl#lxmx!y+fiQM}UP7xV*UmwzVzIVNA)BQX+`s#iJny+nL(5ZwI9MqQh&r;VpOFrF@ z>6g~qd~D7$*f^(%e7oyuD<*t_sWbI$-?OEIlh#ig=V?sNyyonhtDa{B-^SsW4o-S} zw{f1%H0bw=iix}p$pBpQ{Tp8O9v-i7i8m{%H+%uPU_ou zZ0X>n_p{hI(@akKJ3iF6@z~OFUQE}K+UC8_a5Gx8-n;87@8^EiOjmKwe62o*Z{u(* zzsrX0!AbSBah^pukq@=4niJ{NM|#OJIdLBjzGve++udN1p4gt+#KmSiqCVZ8t>;H( zKX2nahso(Q>$u;b>xK4v@F9V#=Vs>q+c+;_a%Kq^^?_HiOiu3e70+XG#xF7VoBAa_ zykT?z6LTp3mgWTx#k`{SqJEFgfXZY#ZkVOwQP4inHlf z)sEl;tA}NBa@Va*V{&$CPVi74=_TvKDer&qdfASfcZ>55&iE7K#Pm*jJxhn#@3jwD z$8+U=+iz-}c~M)i;dn%UpU4*X>FyW(`}ybX-QR zo0j9tKlc@!^mmkOdS2}2>#t|?m8PE5r<~m5Cini$W+rF-RVF9(gL2a6NYpH?>UaKf zRiBg7l|{a-?)iIFR6Y;B+;gJByPNC5;AgHF<+h)~AXQG|KxON-k8)t66V>*JJN?}j zTih>oGw_dlQ;Vr5^}$iH%yvY755>lL8I!Z_YLk=tB|f}ia-zS(*KC}Z6VA|sCJ(;f zt~qPhRr3t+@j120pLz51^nBCCc?IFDy+v`*a?{r+{`5NPbNF;S_)Sbszj<2ZH^Y77 zUqA6Xz@fDjFMQ-ft?hS#u^rkG_x_Hn2xsIqB~c**I@va)xd)IjK)M(@aioKYufmGe$+V%NH<}&lVV~>Hd1po7n*q7#b4?fO2(mSeh;<~)HbIj*-l=fr1dEUXD zPrk#=!2kH}+-AnThhG9wZ(4lxME}X<9Lqd^&k|1R6HKRNLHW4jIVarbSzRz#mN3kb z^NZ!qH{<^>^^6|neZ2v^jW3t~9C~u+KlgOci~ZxCxm|I_URC4MF2W5y*y4WW^$g0n zS3pj1fEzxwh5dP)-1DP5-2(jejAhNZQ=f8naN7~{ddEyAXD8vLKIII3*SC7!#pG4I~pQE4m)3fO( zmCybG^=!Xe@iyIMa-)1$o1XX_oLoJhalh!_&(~?bmceR#2Os59o9^mcJ^vU`Pw-T# zC#|2{{_|df_K}{Y;#|MF`W!yEscj#}Ywujn`v@m34}NW{Ss$s7?O<#5I&JvW zqJGkKLALYv1DSCz5Kih-j_@zM`pMPvezySsc9gou)RX#@GtShL%b8@JcSPJ2q*QCA8d-Lr(gYS(Df$~uzu$6SGqRdXX*<+*v!v;TR$IkGxo2a zVa*2)>LVRC)5m%q98gbiRH|pC{rp32!Tx$SJYdF|`rwCc^U)LQ73p<7+q#Pj#rZpD z-37g#NPX~eE&6$Gzm#(`_SZ8}^O&h8^}z=l8O9rba`k-N&DcNgv45JJ z)CV7Ij;Sa2{QU{SSramOP;RH@%rvU=clh|6+9H$FFYYZmE=L87d*KbWA1#l2?+r^a+!T`rw0Y{3GwU$sI2}$>i+NoY|;4Ucv_#wKdFn8}4=OYz3Z^-r3d)Tf+&K92A0`yipf^&egyKnsr|I5^~vCZ@;r=K5`^O6cVDYqXN z{T!V1yu+sF<$|-y8C%jb^qjX&4bPhCd7>}n@biOmUO_l>Ois$}$3;KKag*+^?f8DB z;N;AIQhuB6l*i_SlkTsL^QsCtDYuQsmL9bKY!RHC@n_9EvwkL@H+{;Jjr48*d3A-H zl$&yP^)cr)OwLxKC-o_3el4D!e&_GVceeY+|GXpdf*EJ(BR|+I^L&$g+`N{lr}J-< zvxg5rZ9}7YdeU*7?L2Odo3Fo~S?#YX6F9e+WR~vXUj`we$=O&ZA?A6_wByGP0s?8vqN*%=G445e98yEgV~O_^T{tVIh$WG^`t)dU=s1gewczBo_m|xa z7ID)2;5WTy>PdZU2U}pqo!j1DaWnSktZO$psSiHb=oH?3GWS0HSDBpcgp>N5M?s)zfrk;&&E6(&FWg~By+~9*v&*imuuAXnX z8T;$mM!2XCKG+nqesc937f?@dKwtRO)=lBXojVTs!7adF&+vRR&eW%z^$U5N+~*qI z$6TMBC!Ex$oS_qV=kHuSi$u?+>%7My4eywGQlD~$598_SS3lcVRQvnqfb}z1RJle_NX0%kj^ zdC%mcKKNkMXP19I80Nj(UowB6%r@^mPv{wq40HURXVpqLQ%{=tgO6)5o=<+ri~IX- z#{T_h;(b$3>QlbD!+Gt!=I8R9iB(nonZm4}SdZM&p?P&ZrF`%kM)K+>w;lbJ$%%FZ zj!N4RZSUOQL;27x*gx*^56!q!AN;VLU-9DZr)O>@6_?`!>Y4dS@pchz@WFEXB`)U) z0Xe}@DQBf||JW_qKkl)Q&A3w^{IF?ed#BH_w;hkVn4F!2lltI;ZDNk=xc$;;%($ap z0*6y!zeMBC)$>QDp3zUtxKqExuivyY^-TU$zMqe*qT2iTfO^({s(3pHH|0#M%u|KWo~|@rDH9#=Z7S#aYm{?sJnH`N4+5<=atd zocy>MciTAmX~D@^$I`C3;?Jpk;e#uvMckeB&Hc62&(GZg{NtYf!px8Ql(UN&ckcDg zlLE#aJg5ioscrR%JM`q%&q)<>R$4!4zr>CEm#z^0aZh!cai>1jv#E(Uujr>|e1vL` zCkNEC?JLC_(U$VT_iOLmxPxWO*TmX#G>_?z;aG3Ij*xZ}@nU10xqlqX!&$9}`ce&d~Qa>sSe%=x8; zZ%zHE4?ftYbD851=JUbkGUFcl&g7&%_+UE{{B+$a z>iO>QOQn48{XE6cLiIey$g@?(_4radV(R&wTabVKOn$HQ?AlR{!{C=V$(t5t{p7Zz z@0px6KPb+I?Gz_`f>&}on4Et7QgU@wf6~nQiGHa#Lh-h0?h+Vz!|j*2{rpdE{{C@y zel*)rqRaFNrqg^e@A%H;{JBC-%1t@zkL2~A-1>PYGwxZfXZ$CnBYesSze(3C_|&4k zb2-ln$cgeQ<)q^fdVi4ZyyJT2IHXJK2u|uF9X82a_sgxHzq%Rwx1-F@X1k$2_+Zmx zDmxyf_3!1hkl)R@O2j?ltl%sw3MhBq8LsE2Mylfxd~mf`jz_J!yyTHR^r zxZl8xd&h64o}Is#K6qg>FCZ-_g+-^v#E8!L=Etq0(R^^3c0TxZks>VWMirt2kb zM{O28{n`<|57ee-hN)*=wfVb3^^WO7N7!~||4H}P#wl)&6EFXER3u!~2On(WhVsXE zH}2TDo3+LLnt<&ns{1F}j*?xKwIl9v^QH>pPU}H8Nz~i5%lAuY@7(7aRWakIqxxh@e|+N=jCA2z>Xc|F0&U7x%ZGwyAK zi~8V$ZLKiwHF~@fA>)<{MBGE-KiN-|i#x`N&DZF81~T80v&6k#m)H5L_c+<_Ii=X| zTbXeW*O+mpKJtUjF#CD#^KG7Eau!}O=ach<8+@=Glgsx@w)Sp2zE4xfclP;FON)v- z9p}W`z1zFrxQ_N4w)TD-Q_s*4Gw#%fjVp@yadX55{jgp2wF zu&s~V(R60q(QcBx$3%}tVcUwCO8ux64ai{eFyj+X8bNl%kX572T`2qDQUsI-h zd#Ar679XkNVQcRfi?}<^u)N>=Qur9v&hy&B$M1->>bOTnsPe+AdDjDHocTLqv_0C| z(H+d=X3H?M9mQ5KeX3{Ox{Tuy{gUu)dNwoL5&Dl-^!Ma<)f>O|*3Z^|qJGkPZqsu{ zg?dtbsWb^6J;BLc=Rbtmj-o4?ai%`yY`&rVd~(on$R*6Uqrc4R{vAH}YQFJ~yRH9( zo^+nd7WZYCdNvPNde*$6=9A%rliJ))jCSOfZGO|%jxG(TXNQhI)iV=NPaKbE{j_n; z6z!(7BKGhT2~tP z`fn?1N8EXvyO{lFVT7q?yIv7I6xTnJ=C-spZY~~#E;i14E99iy;De1`#_Q*~ z_jk;4I|%>lu*t1VJ)7S(pLY#D*ka22z8<PLO(2-~t0kCToQXxx$C8B9)RZIiQyj|{b~9mwP4&d;yNJv;Sxhs#; zuN_71QuTa2W;^PbY__BLIz(Rr+VC%4JL2j&oT+CQ;i5jlbRx@_pSQs{g!|mrm6@EG zbxr-KPdV#n@Q&|(&tpNpt1vlZ>zSO?M}DyJ-FWqr8~1aWoSlS|`rw0&pUJDA+~>ZI zU~;ysZ|X^X@WF<6=jqA4FLET4Gg@nMQXhP<%}maYjmjT4k>9FJ&JMy!edGsQWO8!b z`x;En<_%0esSiHbY>XFoZhK#o$yqmNG$H~=m6qB=VBa@T*;Dc>qa&q-to5|TuIH?al*mfo-w;ip+Pda@!Pf3sKJKgN4Y|k7_r>o5bIv=mpQ-CH;GjOzVWYFnaY+6n_5H>})$_E2j+fSB z>RH&t)RX$)gYCG_HGmw%@_IaDdEt#i-wUn>NDP!`J1stgFf^tnEF&jQxO~-1a`2sb}M6rk>PC z`LK0+^Wx5}pBpkc!<(C&)CV7Ifyv3OpBphb^MsT7;Dc@a15ZzG+&5-&Hf&+)Nqz9a z*6+jP^gDk?ew#2kLtC1h)JJ}>?OaZuc`)R+DU<IH`~PU<-#a^<;9^F*)hHH}$~> z8#$cE8Qz+AezX~rvu0~E?$ie#Y`(}lZiec4oLewCTL~xi!3W#H)RQ}2+LCZ~-eS(j zqTIwbrk>QtcChjHczSZ%`&NV#<@B)iCZ|Jv@`dCP-J!;jSs%{U z!_41p$^NR>3+w%HFI$m)ldkQ$_I2vIHv4|qrYfatk9hs)J?@C>`#b3Uur^NHb?xh! z>sYW3uoLSP$#ve^pS(G3>i}(>Ha%|$sAv3l-g@ROoPDL|jRE!S(wxv2RV?vyFg>HAAl+&LB$I1Po?uQIdH1CVFwRcPzHhUg+`nn#wCR~u z^|Le%X@A7L-iq=t?#OJbbcJ8~+``#c$IUwgC+Gfm^q-dxYGgjrTr>*~#bwa-A z{am)Vzvs>`g+!$;f8TEH&Sw3jzFTOwe>%@K=S#bN3Ju!9id-u9-}zngEO?0H)mh<^D|XDVvj@WcTk+PpU+x2ZT)=E z`uV=DpG`uTa`%H&Evu>!6{b$=KbcA!&*oDehGZscUBmr%4r;^Y`yleAF$Dh>b^6?y)fMD zuWjw<17_S2Z@aY%LfbwP+bt>?D-d9SLUzU$I+dzgAs zANvFAr+3hHbYH-BRJ=-^$I*7wP!p^j1&w>Zrb#`oXMH~#Jpb9Nw~oW+j(C3^`F?T-}WoeuRy;7{R;Fe(62zh0{sf~ zE6}e%zXJUV^efO83XB_{sFr`#UoD)v%Y;Prpo!{lfbe%dDN((&upbCJNZT512WvY- z+hw#}R@>#Y9jfg=CMBxn-@PZRKj)N0wfh%vCqn0ypNH_x?x%sC*U@`??>D{O1oOO} zZkH?^<0Lzep~=EuxKJiWd&^tBG>>;_wOwSoomWm}Bnu6Kw?U$jm*UOzmUkGFcelar zekGgjyzUc$)i`b>3lk7wMcM3_6Q^lk1f?+c2<%-h3zQEgXuhMjk5@wMoc z&s0aRvGeA8%lk5uca*9R`7*rnQdV(`+0~hCW?S{`>@DxQ%=%lawo6X3>nqn}6erHE z&QG@UM$YeL{TZ0D7b z(PvI@q92^lgBHhQj}Q8j`W5I`pkIN01^ypYKpr#YtN97Jo__J!&raUlk$;(#`pXL| z{}$-K$Ro>Dk2`g9C#r2y+l;n(Z6i}QcjRAG|GDtp{_!nm$WT>|wn=R>+UB+GbvZMp zs&ceVYMaqEuWfJ3iEev_TTW8jw6=L|i`w?KoXE+loT#=*Z8O^Dwe4*=>G2P^`;*Z& zudOpdrAJ_UTMsr`R>eo#q_!Dt^V;@$e;V&q`=f1MTW7pVkHGeJf369s{n0k5ZARO? zwtoAA{vfUUgT-Z0PNOboaoKKNgZnmjv|8`msBQKObNw&2Z#_z-$Cg*?beb*OVSC?x z=M7!ov`uQ8(KfHGUwnMa*;evG0UQTwB9QrnESd2M@L&KzBi zwn=R>+UB+GbvdW%81a_&;cv#7R7Z8O^Dwe4*==`jzwx@EM@YwPTw(j&0FJf5ac)a7WK z*Vg%)E(f-kT0aZBpBews~!P zUCta`ueD8To6$C}ZEwp-ub{`H+UB)&hUxJrtWQ0_IHBM6EAao40{KnGJMyon|1v`- zIMthucar)qBdq)@>c2?cct`#v^( z!pgsl{woSA{~}wczo@YCFRA}-5?1~>TdF^q|0wZ3t^YE@%D;E@Uvw++eesvne`#Um z-~X-GjFz*Vt)@Co*JBZPz6I8~=4@xUNUyu>z*%Q?vk{ptVCA)YnO^++3GU}nksj}s z9{XYqH@~DvUrD6Xe9|I)MUkHR>O}YZuyaNFRwDQI3l$G+{#w2L83(BCwRNtOJXKD7 zvf_Y^h;+##uMtSjYdwH@xb1) zj!YN(oz(lS?au4giv6f6@z$NQrmJgFq|5!zoUHa6cB%D5K7yF$lNRZ6zv=6Fcl#c$L_2^G-7~i-3iO6rU_9r6$C8-hEu%naef6O{F5?vvZ=iQ6U9UgPG%20a)B5#> zUO}wXTWX5qru=Sqy-VqOy$0%a=Y{=x2hkbZO1-6~?#~P9#O`{R()D^()a&H*e!Zb# z5G(bTn!1li@X))IuGib5UKcLz*E@*L*jDN-HFY0D;-PmbU9T5Ly^dbeM|yMDAp>{` zw^DDZsa%7MSNHy;l&;r1qh7aO+DCeG*HHs*3Aa*jsp+6@`_WzRQo3HRje6aDMIY(S zT?gKcZ%KYD^_H5t&*jrQBK2N+(wJ&FUzI;x%~!w?Z3I(pC!`cA`R(@ zYu0kV=bS#KTF#%K+^tcrPOp1feIGWe)8$xD=6}AP4->BY!uY!s2fe<()Q?=%NA;U~ z-vGdta4YM#)YN?}yxy1Y{YfcZ-=Bbfq_L%s^yc38u!QRje5tq8)P3H#hu)=h++U&V zb@A#x(i`~#=>Kyo^_H5-dp7XuUcXD}`u-5q>-e>Oq&N4z6TmIuR_ZM^#X2^*JKgmz zrR)1!P_OgX^^xA(`(~DKoq;d)mYT|YX7K8+cPU-ppVMdc8ijH1`@!~0xRrWKP37}f z@sfJe>kXOT`gs0Zs(?yObzjS?Gq{q9Zm#)u?bh#fruFs2f&+GFd zUFu!aq;!JK|7^KF|BL1NyhxWkIDaW!pBL$p2mGb$^CW$7U7ydt_m#Wu0q0ri>yLKp zZBeHe-cs>|b>0`-3*O|xDjjxhk=|YJ>@0PDmJ#W4|FGXE=Sh*isYrKnYCQz(zz@E1 zud63cQQwCxiuA!krS_*(xv(34D7UY2vOB8nVKX0@H0`2C-)1Xz#t5F)*M zJ*(H>d*0o?s^@x$gk?R1PN(~x73s3vt~=Cv2-xDm-s>T%5Aj|Pkre5YlfKfH^o&k- zJ7w`Dx*p>BZ#Hw+pJ1K>HvQdZqTVm62etR=btN)g8G?os*B@t`Q8PhT^#mh<@;mh*X;E(oAg>3m+KcR#;`-bs-z_3m*# zFVa2F=S8|aUyPm|QF>~dzteI)KhttPFVZCs^edgui}ddCFP+bm^u={PKO<++`w@%Y zGTlpWk?yItNcYrRqK!{r=?$BI&Z7787QIEfr`{snQ*V;K*z|6<=>3L8Z<+3; zw@CNYTcmsHEz&*p7U@#&=ChREu=zJFdcS4STcmsHEz&*pCh3b!?+%OJ3oLrebT7R{ zx~JYE-BWLo?y0v(mwM;)d@OAKQ;Xi8S@ag^o_dRPPrXU{;?ldv{K?<@_Zax z8Ik{zG#;E$bB_1@fJ4slz8_Ggd)04|?peP@x@Y|s>7Mmlq|5qUn5Oy@*!(hjdwM_M zvXaN+en64#S-(ZPXZrRm2wU_XY0+Dzd+9CGJ@pppo_dRPPrXID)Vt$yHBSqh zU)7@bY8Jgkx~JYE-BWLpzS#7xwdg(CqPI-<(p#i^>Mhbe^%m)#dW&?ackxVBzhUzm zTJ+w?qPIx*)LW!`>P^xYm)_6Td+Qz9)?4qWO!v?`Dbl_4PK$Iey)z=+OYaVmF7=L| ztMrC-w)fUMD$>3BlcY%Z(mO5Ez4XqI^u?w3jD)w|&LQ40Wxz73os%{P{}nl0DR0Z|5*?y(1#sOYf*i_tHB_(ifNB>Hmo9zung5;(BpLr{g*? zY+j}dy>Xow_I;7wU2j}3PQGMbx5f41Geo-A_2StgeJhbat`oy%UiQ9T{HaKH+ry6P zdU0Ia-g%u4onhY->D_gW zUZwUkdhypry=ikA-Rt~+66sP`%ws_BnIc{4+BjZ)A2xZ(*Wx~mDyM6Xx(*MU5$Uqu zz;$`pr$o9JPvla?gL0wwjw0QQ=OU3VdGd{l2R3@S%7@PXR3x^{|L$)Lz3b+y{VeKq z=nU)365EUKVZI9bjS}fz`<)i)vVLH{vHeXVUG6t@gZ)UP%l$5#uJ#+Y*!qp)>&uW{Cnm+^JW*bx%X~181zR=iohrFbtvFrJt7&_*NbjDH zv!=?YDAHv>BpU{pO1N$*k0s=?Hf;0>FbJgFCB^^y?eP6 z^!Aav=es%#5_w5IZF5IUn(!K7l%)9yYyifBzk-nAS#Ql)4(SMG0?~BBJp0MYLbU6=;`!iva zk4sLmUWnYM*(B0s{-I6P^HyLpPpJHx^mB<}^E#c*!^*ZN_m%td+m?R5xP30S-*yqb z!IE;EUtFBfVR8MA(2|mGzYgkn3LO?#eOprUg$_$f{asv~(4qMWRX_e$ZNCm?|Inb% zv;J2t>O)MQZ~w1ar~lQjK)(Y03iK<`uRy;7{R;Fe(62zh0*gg~+z`i^C?5D&BQ7qq z>IWikEYjplJPy)XOZ>@sZ}}X2y#~OY>!owD;^QUeRV^NJnU6Tm&4O6&-)`bh?ql09 z$2mb*`C487$@j;I53dn_M~L_93!Ro1R(`Ke{K@M(^0l2ZrFrmy`o{rI+3BTOU!CyV zgJ(XI7?XJS)^GG?&a(0%gLv&aY4@Yo7&LF4*KgYE?9hAD4^pX)v!)h!a?70b8QGPG zueH`$sfKGV5-a}IE3&e((;oZ%nkyWz=cC6ybmN;7$6t60KHo@A%8OTiqy1JHFy^5{ z_8s`vT~orh9ivhmXHy;Hr$2di!>=wXeEG*GZ-4sEr8l_-pKmDz5w9~Z89Aom^4R;w zt^WC#Wp*EVfJ$|otz?A|uYIS_nip!EdD~}=gAQD{;F*V2s^e@euFc5Tx_`d*rt7!5 zVY5HPj$L)F?`G&!$N8OnFt>Ppcc+1>ao79Ter-p5zP)@-^Fy?gJ0F}qxF z@1EEF=aF;IUT?}7o8j}_b^K<`m^|XPV2wTtGQn&^K5MEzz$_P6GiHDhC+{dmqd@63Mcq0;B?sdo=8H#D(e*r0s|jQMEd z7wR?#_k&6LVZ~E_IN{562Y$9-{4bCEb;yI4J&5n8^^QDx+Og|h`N&mc2j24i??-Jp zTwX46UrqYq(*M3{_1w_4-ui9tm3A7lvUAhE`1}I>W{>;dJ@Kox4*zi0oA;g-9rAGL z5y=*1)pbh{rutV^k=`^y~6GPyzL*Y=`El98K2*w>))g+ z_g#46+2_6f+#go{qEbFnw~ph9ej>JUOukz>Sa=2 zZvVuew>;^OU+g~{pWmnByJGU*Paa*l;j;_2KV@XqEyHEE;=bDT!yWab~Plbr{`>Rs`(Nws@lJ$c+E_pJHr4F~SKp!B(TR-}Ag(SFm(vz|FVJ>v9N zX5G8PQ?IL3@yx&x>fNu2mnR(ZmoYmG{ratQ-uUj+Gw}Jtx_`QVi#?7X_{qHUci8Xm zKW#nmsFFU9==jg-{2Q)7p~DI zW^~o-aoI_V*P##A+@DzWlGwB(8&(=Oe!V+Ys^dJNzklfb=G$J|d){hWk7|xjUO2GS z|2(ZXeCpxUjBl?$Z0Lq-T(`-pQ&Xk>?`h3{;EWr-jh(t+sci-xyUslyE{pElY18pt zdeuqy>UfSvP?f3Zh>Tk5_j`N(3^yK;b zx4f3ya{ZaR?)vViSH8Fe{4eM?Gw0m1*Wf>&Gxf8rM_;t_nAN_<=P!*`@8+DAzIO1J z)9-j{V#AcDhD?14pTDZ>_oJ(I-g3@f`yRPX-Iw|IMn3gw>GNIGyQMBZ<=JV2POG2y z@J_S$8ITr7DD`?xE(Q>SZUs@OT|Qe|MsKH~N9quUzi*q3yf3yx4HT zaZRZ9PKS=~X4}?Wz4tZy{q^5BZF|qqvz|Q$-(RqjdiTmlv-Vs2!lPRrUa-u4Rr&SL z!{=Y<_^kTtjq`rG=9T!y({}B8aM Date: Mon, 26 Nov 2018 14:11:28 -0800 Subject: [PATCH 22/31] Refactored the code to OOP, still needs debugging --- libraries/AP_IRLock/pixy_parser/a.out | Bin 8776 -> 30320 bytes libraries/AP_IRLock/pixy_parser/main.cpp | 29 ++++-- libraries/AP_IRLock/pixy_parser/makefile | 7 -- libraries/AP_IRLock/pixy_parser/pixy_parser | Bin 18256 -> 0 bytes .../AP_IRLock/pixy_parser/pixy_parser.cpp | 93 +++++++++--------- libraries/AP_IRLock/pixy_parser/pixy_parser.h | 40 +++++--- .../AP_IRLock/pixy_parser/pixy_parser.h.gch | Bin 3053776 -> 0 bytes 7 files changed, 96 insertions(+), 73 deletions(-) delete mode 100755 libraries/AP_IRLock/pixy_parser/makefile delete mode 100755 libraries/AP_IRLock/pixy_parser/pixy_parser mode change 100755 => 100644 libraries/AP_IRLock/pixy_parser/pixy_parser.cpp delete mode 100644 libraries/AP_IRLock/pixy_parser/pixy_parser.h.gch diff --git a/libraries/AP_IRLock/pixy_parser/a.out b/libraries/AP_IRLock/pixy_parser/a.out index af923f1458d7558a87b0dffb78fb95565b977a3d..6a4dd3bc153d1c7de0bd49da667bb95a2b995281 100755 GIT binary patch literal 30320 zcmeHwd3;pW+5f#W$;?0?2?;wY69qvr2?>F)1+ooHlt5%r+&X5NEShBEECF096{4mX z8(R0;ifi3orEjfL(F%wGv`cJVsI`6bwxB_5n^y6qZv4LAv)s%~lIo|Q_mAKE`EVik zIp^8VbDr~@bI)^U?w#vB%a+(o)6j?ASY)u)>6Dm4McCe?3IK)1Tw@r{XBej&4%8C_ zPSOh{0978xm1+%L3U3Fb++3SP#KTh*pN85(!bC+I4D6gNu^JkNTOcS$TU#4Ps>k#-?hQPD;gW1C{b>lDoSP#Tt{J$ImPd~fy7k?}O!X1xf z9pe@X*Hq7#!LgcS_hhAtK(l{!WmThJ z(gvsa>ejFKwfKXfKyzhdLwJL)btW6CtFHEi*iMe&ThqL*p}EGl(jSU6`AMvn2DC)N zAy@$es;~4_*I((Yt!!vCfUT~t3>q!LhURcB=+)~heYFkLezo6d@;5aFT49lodX(`^ zl?~0t(vlM2tgM+v$=bC=#bv&ntXam=Wo5-BzTB)ltCX8H8;-EypIw}7A|ey5_@tXm z{JR2B`?uoE4M|*i{){kKnFiDfClcwbOSw;4AnI#Ht=8b&hW|DkY^i4DVO z!{;R8(Cd(1KRQ)my;^THzCsmTGu=W?<8}RDw#0KS(DRLqJyCcqLws)(emD{8=!?Rm zBQ8{IHyc5M2Yo!(vS3M zxBXAvO^5m_Rxj&F96ri0yd5LIhe-2w6ubwn6JxR<^Kr`LQh_=jl{Mau#4X z!{G_&qK#E_apYwudTO&$CT|w{FMFB2>aRoPC^B};9xl|J^(ExJyT7!1+xxt`dl!4n zF7NAKhQ~wUfoW3V2r3*(-^PO7U^61w-c1GTSXx7SMtHXr+=E*0NOZZ^i&IzP-Kd*1 zXCn>!=w+xxf5?8>ky>!Dw95Of5ATAnYrI<$rcMW&x82j5v#YDE?#mM=VD#;T-j247 z1Q^*XjG~`WThR`lMe*lwAH??cCSy!6)~Q`>E!5uCb``+mU2Q>G3&~m-Af>A<0$_Hv zwMwuK!02jQ4^ZFLwn5ge23XnEc8#oE3oxat?K)ZeCcw?W^{ROJly5E3Gn6%x;*WG-=5m#*#dY=c9*9E@K(ru2XdW&TLHg2uFLa1 z$liv(+d;phq04h8;9Zcv8}OcKU7qg)-aE6)^8>&iLhe4uZG+tXka^(mU7iPfx;zgJ z>+(FD+U0pGJ#{;36`ES5KP3iLd8Sv1|F3(}ZyRU6M!lsqsv9GNjMaGPGizs>* z2;#at#2CXxqs{J=XN{C+ceQt6;%vr>E&{FhtVVs?8I>FX}~!*kp``i9`$CwM8UHE;URjXqJR zH|5!lvOL20983;5x@9j9%xbaM3j^2(?T@b8Ql9IU^$7SA@VBd|{kVvnTC1sh|B0qH zdHT$wcSzpC3c+!q#c?$_Iu9sc>E5+RdcYplLm`xJ33;eChT&_tK=cJY-E@3dt5bO5 z=ylSliV6wK(dsa7`v~@{C*`?9xS&rJRqu&a9Y@g+eeM&+?ZNg!y7$rJ!ZbT6=Z7L#MoAU1Hpg=8LeOIx497MYUbQ26K!aSVluA)l z4LaE1q(K|}!lg&@wPR=y-Wa)#t{O>^UZ8e}9by-vI>wrmwhvTWaIthjO558+brcMv z?2}4eO3IB)VS%1V^zA^`?(-Z12J4iAlug(5rL0?mB@KS^^jQn0xL$F-_IW$JoN5@% z%`T26*2UdDu3_D^*i)rE=jp9AJ%_jy*^d51+4zFsqA(-i#aNjSAoD@(0?#2a&ac7& zy(d1_c-?Ah+e*h)ezlWS}f)n{k1Y5#|? z8BZM#x7bAu*2hHJzjd4Z#ccL6O& znYG=bW<@qHPekvDVR|{1=^u(|ZwwRH%cywySTSJ-64l(kSf)?Fgx!q1NFa(n!37fF zV{8oo{(&6@L-TRd+t0Q)1%J8w@YlVe88U04xB)S$Ow=%-jZzUagFc-}CNzKBsu zNNHOcJto*Eq})^}G4%1zV?6UxtY`Ebp9ChGtRfX zvdFR6*Sngla7RJF;y?U1`t~6D0^c4S(zgc(`gT87583AZ(6PyLQ2N$PX}cB5qKBxX zLbcyNjn&qebM0GusKwh6#F~z3$G1fl*Ua``_ud4}Qd7UEj3_4}3M&AJ)-)_TK9u?rr-^*q!rxeg9xt`=`s=KPhehThWQp?|L`A zYP-5 zGgf&#?$zG1Rhc-TWDxb#W*Dp1RkpMYP$;ne8h5|KmHx__0c;vs8w@n5mX|aHLt%GS zW1#vOgZ%j6hM*paQE_EOD2t zD6d%NS?$R%miuAe)QGz&5cIpNHiZ2l8e1J`YH9R`{q9OP*oPa%%T|<}7bRtUwOlbx zA8u%Sm-(CP!u9S(nC}kPS2nwI@?v_UThtxOb%!=ISBKn{t++kR+tKbybT5Rv!R|!` zLRj{^qGA08=yop+`YUk*Tj~x3-Ttd0m5uC5&K&o;2DGdcp5v~rY^;tnR*KQD4pwL3 zFiKXIxR;?8it{psFq-$ zwV_5LL|m?}m&4$0XvRJ9Fbrx432t`31)Xg~XB$FRd|tpPz#VvZNxdJTQc~I22=*HH z^qKShO)bFZ%x{pP;?6}$yV*T!zK9#Xr#)b4aU@JB&zU$hCkixTCTjum^A#AP;`N#lyUMrD3j5H7AX5x;jl~D)IbiZ#-<7K?ZdU&Tkk~ zKqr6wkrO9c$eWzHBzgR~DM{;G8;!*i7o0t7%IQQ?z7&7k!H0dCbx@Xvd3D7yVTtqm zr>41$NzxvvpKW{>_Eg#N3C5l1Xi;+Njkc1J4(}$reT^NKOB)^n-!J|mZ<$#JdLigc9{TkkwCGbn{}l9NG4wu*UJ80Q z#_o|A`u!HY2J{Osray_HKV{K3gZ=^Nh46#bzI}mk0R8w7=*$j2O^Bu+OQ3>Mp!R~^ zhYPG9WurJb^*grWBCeJNOo>`PUy*Swo zKJXVOyTs>7BM?L5vAeM+BOYE6hrdbH^>^;XXMVup%Ov7>X1s(G zR9%0caFVL)djb-89f~e)QUT*q9T2%c z>dG8rjAXaYN{!K}zMrRa+)l-z?}OkYBXNvV@N(6##^0+JeE4uw9J>9}R9*Ao z7LDj1%oQkn)j-t8D}DH`kEm-qaXUcN#b=bzg|s||uGIgp0sX!5c!g)Gj?YnWiGmj> zSgT;Gg7NZSRoCAi)qMCO?R@w2HC4Dr9&zVq;XAdNx%m-M&G}}|+^m^-XGyei4n*WA zN*~{&T+O>lgB_CpVFa>d{9J|1TpikRLiYpD8!n8o4vbR59Z<|$G=nu{GhOB2vDuub zAz*9?&ZjWYHkb1;0@J}eDE1A|W}BJ`g*IDaF)H>0q)y8NCLtjaUpR(Dq8%;RM^ecx zVG!&)SnOai(dBU6O=;6{0rWXpcDT0T?0gs}7rtJNY56#G4$Fp;gfE6Ce8JD2lkC^m zz)?x|jkgJK<8V-u?CsM8xTQ#djtd01^-2N0vr&Mpj|*_yD+1i{djanLM1Xrnp$AF! z@0SShgK7b`Z5H6cI|O+60RbL)Mt~o^A;6;_3Gi4Nx{zdlV!8lNE*GHhHDTbfPtb=X z`zH+od3>_~|9o43Pwy7svmF9_{&xUl#AP@ooEQb+k)r3OnVevnKNVW`OPvR$vOh~@ zhoqLnQp@{NbuX2r)HJjj_BS7ZMhd3x)hCV$%83VyL9)5+KZ6%+sR?|(!j_QGz>#z% zOhDg&91SqaDBmFg&Y3kGnEB!4Lf zUGaNZb{TeB>R1wx{N-a18#GYzFK1EluVC55c={3r`&ckKD(*uOG0EGBqi=@!j;Zz| zKsj80!+8uXV(_I}Cs2j~F?QTa^v6+QBZr$DJb`#7!1xKTlDNi3Kn8}BWSE%4R{c3p z&frRY7*u0o36b^WWT+{mm&hyGM+Tlmj+;Z7bin35=k)k`Cw}NhryN)^^7H;tp%Z5@#iJn5si=cH}IlKBpAJciMv%Bqmz@QD7E zQknw<;+!m0lAQTsm37YLL`ZVZ6RWIqK7&2Uxlk;3&P8ICbry*>1OmdcrRo3Yd ztE_XWSY@4FvAjCZ70avhJh8kwmx<-oSuU1W=W?;UIxEET>O7yz>*QBqkUI;dgRWz1 za1BhW1H$!*Ff@%{kaK;;p>w6p#;CYH7sHt5CjJYS$EWqM{3Xlov`Xl4onU!-#zION zCMz>DUPFIfrl`!#IGYrks1#+ z;u>$>4Q-n;4zic0n2(`ybHFIdSEm2DZnWhGlw9?f`% zm6@WlJ>$Pw$u$}AJ2JjYN6iwp?aJ6gLuZ>$qn*9R>7!`EJ?`hhG2XR}olGkw_x&sy zX_wHB2iRR#+5&d>5e`o(Cefw9Ib3f-*%`d>)9fk5C=koh6xf$EHr<$d5&Cx~S9aH8 zllU`7(8NMnew0QPiSo2X;2Cxk+niR2CWqZDirkXsvI=gzK^U8s!>s#(gmA zK5(bifqTT1^H4O>T3DXSvMp^Q_(z<{aza`!m`6-w*NL^< zXlukd9Eb|zY#)F#fotQ4nID65#wDN{Gp2&yobeorwi#Pdw$F$FpJ1d>>4?nl2t_-o zXdxACPfKD01@{5JBQ2j+EF!);Eg$1GVsRlfA57cARtkylNqd5NidgQoe@y)JD)2bH zNL$XK2S!Y4hjz0O^-la{J`K%s@&Bn+qSpQk0`|Ls zS%0Gs=Kcds?gV8P{uWsrdr&g6{z!A?1!41k)Ystea*Kn0F|yBP6Z0PgAIC5hOEu1* z!#EHk%7+z&=9&!)Hy>g0K(xS+Gg6$hJiC(tI#2bIOn+0j+stZ#qZzE zd#}S*KbN1ho1-ai-}?5oxmmE$97~<{t$o+#UJHHZcrx0z_IxvU9jlYr5Bt{MYjcls zP%=6cbygzG;;}*k<1!HP8VvJPDRA&wWAHnhPoj7KOG!#1ofw;`Yyd`ODl9r&PS+2~Br}yn zmYuGLaZY?3CzYu@4U_sam0chpQ)xg~kg0HAoMgW-1wBEga*hDEED@mN5&>>)5#T#* z0&IO+fZJXb;Eo;v?*2@Gd&Xkuk*RnE_yM1ZOR{fk7vRC~3-Iud1bF0U0{rNA0zAsx zJIVgoI1DZ_l}rJiTqQtXw=nS7XXpbmm1coF-Y&pD-xc7~9}4iVNqu)EXQXm4*?gKsr(fvr|V;!MW*7y(56}^Q23Z#Or|oG z96W(I17JX=!f=udDpO&?!Qe_|kVa=J3^j$6nF{;Jz>`RwsqmR@#$mr*sT^r}`V&f4 zrb1UURK+e)ZWVQ=!fPqRSE*K+3VqFJPG!sD6qBhi!i9in%gR*P`W%wPiM^6^r)wdw zDpN^hIXY9}1c{f>nF?o3D*GAVGo7h$KFJOZmZ@-l#bhdU`EQ97#<7Iaq6<`}!tQb! z_S2>Es7!^^GoBossc_y3x|ONWExcQk%7#)!i72$pZFY2~!l@{^=p-vs;e6xtjGA*Q zQ(-W3#>xg&ra~m=Z@iT%Q~5o}oYw=$GE>P0ne)A$tTUAYP*QP)j-nt_5o@M%hFCM5 zSz?)U&SJnJQ(+iIXDVfs7TX78Dzi{QrXp5Z=UlPMI_HU1);V9Svd)EKxpOWOtE{t7 ztg_A$vC2A2#VYIch*j3PRIIX2uUKB4=ZfXkd7fBaoy)}X>MR$_t8=+nUY!+Ud3B!8 zK{6E%oz7ImFse+2Wu2+8tTPpstxSa#D^p>`%2ZgfG8I;=OobIIQ(?u* zRK5!ftxV-ERK7;0vJnctMyB#ZXtOevr%1J`aZXgGG8WhjO-ZFy(V5CCpv=WziN)~?l%g}0-=Kam z{`?jP{Suw2a17VSQjIg{Fb;%>a%3uu5)Oc_3l+ed~_vXWfd5xs&?rTc5c;?-Evj z&SA7|y*%$M)^<_Iwsmcuo3&Ti7u(ilv*(Q#`i(*f3_sHhq$3B|dE3?sWA=ZkPt(p- z95*SB_e3VJwbaO8pgu3t9F+g3q{=l61L}P^2Q-Ih>oLi3fo$t3S^Gx*w-j@9TaU}O>hn7lF}AHIr0k_s zpTnRuFZ~O;v_$#lC#qTVUSdZl$M|OLT=eBqH9&daqUk<4y7fj5r;U03JV0pFcsF5Tqmy4&r<@h=wtbYm1pR6*|7Dv@e%@&`xYc zoc8=16&r64@}RzKHBgvrT;t3c#^n$T;ctPSVhf7l<1hslQstMpy4?d9RNByWahUfK z`yl=bsKU0j-k5(GRc07JLH#5ASt=J*0?n2eRiVJubWyd&)S$qryvVOHwW?q&rgnbp zIu^OVPV-x>_K7WETWGuB1pzNFctyaq1-}xoqTp=-mlgB~SXgjGKnNyR~lkCZp zl1G_o&Qwfm+Y}=yX%SFZSjHOm+!&*%2eH$k^zTggE%!E8t9@k^Q1E%v>44{7o-rdS|X-rpo?eOVwyTT0o6rG z98f)kGp0ik?*yJ>^#K0PO{cdr)wlVdmtLuhEx?aIsMeKbOvAH z_&bWl2;}zLYa7qIjfm1TC;gEJiW*o_W=jetwQvGgj(;(%$*t)&Nb;epc65XI8{VAv%)D>md+|eI;yHdntq=X8|?Wy*yln))FhafWyUvq zr<_OgHN~AIC*%Tc2d-*aW=?u@a=)ocrXbPC5q2%=Z^bYc55kSf_9*US+KkmWo91W9 zBXKrSHdxP&go4?4?yoUY zzHGeuZ=m{o-ExdVd|v?%-DXv{w7^CqyrIP(%BrWa)%Ye2bn){RG=b+?Ya8l7!DbYM z8h|>G%lHW;=V-gR1`V zPJx)7@}NDi)}H1{vp2gI0(K&|FwI_W?u|?S&x}>Hcm6L8nckt<-KOin;r}@N_Tj^e zZz$h{p|Lw|-~c&X=>)C?>kcp8X`7ku8XZM@nf_k}riF)ukk z!}wwr31IN~n`?|FJnh{qFzfJ;zF**~`E;{S#A1_t0-kR&ZI0kQq3aD_ZDVB}UMgB0 z3Hqu7jgh8iV;$cnidKA0mBB0Vo>D_R+U^Sne4zl$;HuEf=6x40pJyqWh3_+Yps(Ds zYE{uvkFRXGeoo$~@mDu;rJCLxX>4o>2hTEs{_0jAwF;}yonSZsnjvh&lhjqzos$za zeR6We+fCU|ysE&{YJ~9409BLnjWr538ori5h&~EL!f;49u&!EoBvjcd9inX%k53!5 zje*LrQO!3TSk_-qw5+VuC!X9NU`k1zr>Ua8slKVn!24e7+~O2z4mH#@`|-p%w8(B? zMEJ-(e9iSTXAV8ek;1!MBQU)(gg3i3@>^h);Q;!MH@0Hv0tQC3r3l{rW>oJDD&n{Y z@g%#kuAwGeFLdF#{Tiu>%qyy{FsefS%3yUpdyhA~Vw~1Piqaeam?AoxlRFo$g%$5Y z@QEkc`4(DO7w_{Nsb9Jran=;5@f)*YGMG6^+W%I3h=<^XWioX7jl{4US49FGj}Qk0 z5eHw$7!|HyHP@Ge_tU~~UzBI*&?q9tlyBZ$;S-}NM5_V;xR24ClOui4Igni+X!2)Q zUKy&d+)#DJ%-r0Z>{5T|%5b11o6f2b*R19Kb+I++Y4QF55ukkCE}#3ygs5#sx2>yh zY?5&#q1J&h5JH@l|yydHWF^)@T|qXLk@ zDU47{NG+B?L@7d5Eh&8Sw!37;jGR3AJ#KeqQ#jJ>FR1flA#A8dm6NVOzSrBGS?A8I z74K-y#49So{_1cbmQ-Xv)Z!})4)?B`or#Em9OWEpXHiAu&JE9*oE1HRVL1woLMnJLDTvtF4|?t!_+x> zuo3eh67n<6E ztR&U-!8#$RUtQv_5iycugzFnHyW`p^$+Z@DhA7pp3j`s8iS<@rNB-_8o)b9fp41BwEI9IK_w1(Kwdv_};>J?Cs+ZyD`kT zc~JatLqAUvEn_#54EJ7JD$$b&jH2a$Kv-6+|ejew&QEu z`njEGqMc9s%p8n=f-!zjynYHPS_{WOjchk0>= z@%Iz)0=%DWGm?#6apTJy<-{Z8VvY=j*UxonVm=C{(eDSg$72cp%t8F$1U&WY=fud% zV*~z7yyZnd*CmiR-G#rw?7x2q{80Vm*k2gK)Zgr0%%^LxQR zdO*B=sPOUq;((Zg#M>BjKz)iMB=zYmflnTABfb>)RK#a|9G<86<3Cv`#(Lx)B%ZGU z|0rnE^ORph;lY;_o-T_q=SP%&eWyS_4fO=|;Qmtl^HzM{P#VTP{HD?Np3UDa2*hlkM5FM3A%e}Xy=52bz5BrdCD2z>SRyC4h{p%pUaFef^zZ}9`qbA_1!)Cp* z(N}|AW5`z-!OmR0P_8B`f6lx)gER5>J{o+L!C>VETm1nhYbx|>r5cR7ig@yX3NBDyy19oLO)~?Lwuc-`I4&cc7s$78? zqev~eC53g-zmXE#xJaxp5}|+(@7k+Dsugd}fSVDe7iI-W!?L4b9LeAu?P+X~q4#hCp*n#Rpo@-&jcjRcdJr8(Eyu zMiz=$b+~bpg}Vnh3vXrx17a3t`RmonQeOilx(4m|F(d!_YJW@EC+=iOWpdGxI&>Lr zRyH+M!%9x;EJUi2g$1t(ix_bJsz@C;E1T=EI;v_zb8SGEE32x4{#ISXuWR{r8Gegi zs{gGrci7kpV2>#eo!@E5FY!emQaM(3aqEwA%M4X0>E z1>@yQfyZkX1G;^kS8Ay3*J+>LFKM;QQNSnXmi;@FA`R!N4&!?z!cSUWU51SdfXAiK zlGk~vhWb4SU=c^W|Goh%-!Y)==a+AJXs9zIZNKKz@JjIVodvqC^Ii?bXK3J|{j^it zkD@sEOe~w!@;X1(@StSlhiT%_^1A<*12n{Ujbe`Y{y(PV_4w(0M8lDB0@`k^ROWg8<3H5z3u^v2bq4c3`d_!N z??Y%z?+ukU}X z&!o2gc$KyOx|aV41UaNAc#}!S}pQKSv=dq$by#FFjdLN zu^Gim{_;42meXi{|2Q5;+5<}dn7#lgfp}g%TON-i>z(CNV38iUA>`)`A^+woDR5WZ zgo$sx&+HDIw2=^%Aw3*z9h|YLd;#&MJ6{ z#>P-r1S49Ct+raNR;;aB+oozY7(0U6indl;wT%ikSgi5INqw;W{yX>I%uY5vwx{Rx z=FEQge|-1;bLZYWbN^hW)h^A?%M)BY;%q@u$tYV>p$vtmstTY&l#9{$JxxpzBO#BF zI@?}h1FUu#P)#!yD!m6tyz+co;l?S-kC7uJEKs(bFkWdHgMYxk$kDFJZwg&-Y`~*L$KCX3r6OB z6+DXbix!`9T&4OOZd}?_{EYk@<~GLa7L?6xjLd0_H77UE*<8M0&VsT)A|9A0@0;2u z-(@S-%AROgd8jDnNw`Qy_FXStaNn*OQyxe4Kubu}!a zc+a>hn1?Mlz%nt1bsu!oa_Ao(#{bS?^i9L)r$X%MKmkDF2zRK3GHp{~Cq$xe( zjR~!Z;tF#}h$eig5pKBDs1L;&5o36B$OxIy%`q^fP#yov`OwqM^WblUoPjj!NMp~&Jm4*m={c0(niPv+rH>GADqZrF z*l3!mMywGSn~N|fCLoYPk0|FQI%`ezQKBHjP2j)()X)6kfMsfo+b)+|qGUG{-DWoF@rThrVG?YiWrTh@d6xxvoq`Vh$eJ5mDO5d$X zy|6(~y{We!>R-90c1OV&gsblue-kMBjwNryD_y(|oR5m8R!h~r5Z3BD3hn^viw5-6 zVe@2!ej$knef;`#Z+)O>>NT?c^*t2zpo}JCDQV$QR=~o}6k%{QrN6eUsik{L2O1mwsZLOtUz1Pyd0c;0eQ)Fo! zd6u>f*EfZwUE5%3Dd2UhENwgR`stRo1Guxq(ry5Df_Ec$yE-lHCU9=X^)2XkAGWk_ z1NWS7X}18sGsDup3%qr%rQHVn9(dme?{?rFz#p7sX?KEq7p@<|es|2$?g9P?{Ck0W zzhY_k0e_5s?+5+_yq|*i0C*3A^U(X2_Oo6~dw8^^{oH41zgTK%zl2{Gc)x=F5!4^; zx3tH=`!#rvBi<*#>&CSYwkHv95AZ4U_Zy&vc%KIDN4y7s&w%$Vc+Y|NTX24d>v`x8 zg7*UOMeu$P`~!F|0sjcz%fMH_`xAJ7M*UTAUPGL(kFm7B^jg|q5oa&#Z@~6uv8BB= z!O{+acNp^9(Ekm*KHw4HJ4KfEckqwmdKdP8;JLg9?8kF?ANT>D%ZI>^N-XVTVRdY! z=Wcae3D|3OTqS40(;Y29S}^){S=Cb(W^GRarqh+5rPE!oz_fNCqR*csXNg(R*8#(U z9yx{DkNQ$uKT9PC+P8j|mz;O?)`4^y6Lc2Z=p2bQE`h7Qqxd4UhgGl@D$MmIB&DA2 zn*(E~-O%Gidx92r-(3iZW^T0*!3%=t*Q8z!t_@-EDP+$`-)ayO#APrYYO^(>}uwnAJD=w=VF3)l_Z4{QLwh?{u@Sd8%LeX;>K z88@^USPtw1w$Tlu(DxISyen3Tyv@G6Q^$=e?93bGBRzdHuS1)&$w8Ie{z6QLo&5KI zl1{HAU$1Yeck;PKV=pgk6X%?=_>B3}r;(cY7*5d-Ke`7l#Jw2T2k5VgZZ+ujZOgA3 zKhkq{K0=ahe;w-L7BgO zqj~*1MpSxdUSFVlOSX;Fz2)trmU}B&z2!k~Nzgm9((8vG{42eM^8G#nW496Q*iVES z`~MgIKH%>Ge*de-oOyS$Oy4S0#@Qgc)XQESPsAGa5`NHq{A@_@Mfzo^LHm&>ZE&hpP(TbFD$lm3N)`GJx-^A;wh zSbAk?d7z|hmaYB*4SO(q`CRXG_h3)t^KiD_BTOD}hk?G_c^*2{m_r4b`IoI9DR`b{ z>qiNGe%X3V0iNIvg9lj-o?i|%`W+*99%k#uX4Yf2ew;YS3&vsai1EUojdK3DvANPnM*sOQ4{(z}o1DRss3 zEcDdxR<-fUcPn(CDm}kXc;BV=a`jsTLmuYCXZ%8eAD3MIr^&#E&Z`pH&d~X=Ncx{J zWd5A1^!$F}KG(~3hR&Y^^ttjL*Fo>Yyz;r`)pYD5{v7k|M)*$vgVzi1-?u|Qje~ID z80aTroX=7(4*87(`(xBj{z-!OO{VNdzY}w;(*v>{_8P>Q(tmKh&sL_lhVj2d`VZY_ z(kdSJIE;mVuDlQ>*l66`>rq2HKFqgrHQzYWxzc~~ka1ot<6*Bs+$i;4(W~aC{C0!6 z1$zIWTc&os@?WXuKSWt>mHLcZrt;`8?L0G#{?IV(h;XZ!Fq8H5fv_0NgBfO%5vEL7 z0tu%`+}P9@uM0IA5i{PJFha@AA{=jOX^fiDNMPZDMU+*`;bb6b6*EGut)VSOwApOk zBI;X1O;IC~Y--v9ibFEsX=b@nYAX8Gh<=dV2n~`kdW^SHAj%M2CN3s<%znJOayroN5Yio=(!OB_< zts+Y(bAS~UGIyu4bVf81GDFBZo`-vg#F~v{B1)}NE|AlIih*n&<@hk_iMY{#d!uZn zBWdV%%g!$jTFbyf%9HOF!zr_ruDA?}%g#8$zb=vBdhTqen=SK|;Y3o7*S}A=+PO{g zrKy9?T)ED{$nD!7n#%o8(zV%via=sZlNqW5nyofAa4pu1+;EEsG{?zE@hWqF5ZARwvXEL9oxY-q`(ALfTZdGCQ)8L@cXE0Tn&*!uAp`$Y)^Ly0+ zk&(}paFInd$D-JP8lBmg&)@ls+z-dkevFrbPiH`uGv@(CSgCrV_{oRkS88zuDm13d z=W_!ipG&!a=5t)vD1N1Ckk1#48=RSK1HNFth4x?0_q>*B9{`Ep803E^xT{i zdG0w~D^&m8YT)QSGZz=f&-(|>Z;su`r%!w;qg_Vs*S69bAvb@tN)#SvM}= +#include +#include #include #include #include -#include - +#include +/* + pixy_buf_size = 17; + pixy_buf[17]= {}; + pixy_len = 0; + blob_buffer_write_idx = 0; + bytes_to_sof = 0; + bytes_to_block = 0; +*/ int main() { - pixy_parser pixy; + uint8_t tempArr = {}; +// pixy_parser pixyObj; + pixy_parser pixyObj(17, &tempArr, 0, 0, 0, 0); - uint8_t input_bytes[] = {0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x17, 0x01, 0x01, 0x00, 0x69, 0x00, 0x56, 0x00, 0x27, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x17, 0x01, 0xF1, 0xE0, 0x09, 0x10, 0x46, 0x00, 0x27, 0xE0, 0x00, 0xF0, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x00, 0x01, 0xF1, 0x0A, 0xE0, 0x10, 0x55, 0x00, 0x15, 0x11, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00}; //array of 15 bytes of SOF -// uint8_t input_bytes[] = {85, 170, 85, 170, 15, 1, 1, 0, 104, 0, 82, 0, 36, 0, 48, 0, 85, 170, 144, 1, 1, 0, 229, 0, 86, 0, 37, 0, 47, 0, 85, 170, 85, 170, 23, 1, 1, 0, 105, 0, 86, 0, 39, 0, 48, 0, 85, 170, 23, 1, 241, 224, 9, 16, 70, 0, 39, 224, 0, 240, 124 }; //array of 15 bytes of SOF + uint8_t input_bytes[] = {0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x17, 0x01, 0x01, 0x00, 0x69, 0x00, 0x56, 0x00, 0x27, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x17, 0x01, 0xF1, 0xE0, 0x09, 0x10, 0x46, 0x00, 0x27, 0xE0, 0x00, 0xF0, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x00, 0x01, 0xF1, 0x0A, 0xE0, 0x10, 0x55, 0x00, 0x15, 0x11, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00}; //array of 15 bytes of SOF +// uint8_t input_bytes[] = {85, 170, 85, 170, 15, 1, 1, 0, 104, 0, 82, 0, 36, 0, 48, 0, 85, 170, 144, 1, 1, 0, 229, 0, 86, 0, 37, 0, 47, 0, 85, 170, 85, 170, 23, 1, 1, 0, 105, 0, 86, 0, 39, 0, 48, 0, 85, 170, 23, 1, 241, 224, 9, 16, 70, 0, 39, 224, 0, 240, 124 }; //array of 15 bytes of SOF size_t size_input_bytes = sizeof(input_bytes)/sizeof(input_bytes[0]); for (size_t i=0; i<=size_input_bytes; i++) { printf("%u, ", (unsigned)input_bytes[i]); - } + } uint8_t input_bytes2[] = {}; for (size_t i=0; i<=size_input_bytes; i++) { // printf("Calling recv_byte_pixy : %d : %u\n", i, (unsigned)input_bytes[i]); printf("\nNEW BYTE IN:\n"); - pixy.recv_byte_pixy(input_bytes[i]); + pixyObj.recv_byte_pixy(input_bytes[i]); } return 0; -} \ No newline at end of file +} diff --git a/libraries/AP_IRLock/pixy_parser/makefile b/libraries/AP_IRLock/pixy_parser/makefile deleted file mode 100755 index 96a27f72d8..0000000000 --- a/libraries/AP_IRLock/pixy_parser/makefile +++ /dev/null @@ -1,7 +0,0 @@ - pixy_parser: pixy_parser.h pixy_parser.cpp main.cpp - - g++ -o pixy_parser main.cpp pixy_parser.cpp - - clean: - - rm pixy_parser \ No newline at end of file diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser b/libraries/AP_IRLock/pixy_parser/pixy_parser deleted file mode 100755 index 9756c81af436eefabfa34381356209af471b972a..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 18256 zcmeHPdwf*Yoj-RblT0#@33*@wC>I39YMwj}UVn zlh54W`906?{LbT^bMC#l#i(6o(KM!#m0iII>r54t3d!idLS_Ie*g}?$>r6I-kyr|+ z34VnD;EFUXO)F@ZbSog~Ewl(iGMpym6jUA(v`OB0VBJ(fRgf{A6G)GI-E}TU0d<~H zaEtU~7dgh0&aXr!y+@_qqf$@7A?cWcs(w^A`mK?6li^bEC@Dy?lle%`Zt)hj_yf@`g$&*t2D*=xxk4={CiG(wr*tYU$1%N+KW5(?(p5iX z|KT(PlG)=(2SL-vp*uhuPoDfAkABfv=vSVFz72F8zvQ$8gz@a(54xT#47>!tnd8tI z+M$8MzJRqwBVp!tha;YbP40%~P3}gIzlEp`&7Kfz3;6?)M(`W9c-)QtfTzWOlaICf zT3dtdK9I={>4qZiR*yfxuB@%8s&YurO|3vC3>m@BZ#h*^n4KfyL z{Hk%+nI;%}0en#9>q9376DX*iCa zVNw};O47*&)mx>5addM^0<$lUuEsv;{5*~xKR@=z(N&#E-qrQ4-L=hjqCjV^t$h*8 zNWZJ=r}iUkWd2M8#c2IxrM z0_c3?oW7Kk)&p7V>akr7=vp-F>OK)EKvgmbMO7wl7#V0Ra!$XE+uv}6YB7q#WC02G z%+Ka#F8Un$uEU>OUEM>j!-Gp)TFmwG=aGCEd^ukjoInQ8X0NmSb%?QOv8${6yOdi? z{!DOfE8hofa3ZQa=)xstdm6Y#?sSr4A0B~8)Q7}3oNR;y+paD zYA&shu7?M#Fn0%;1J(_TJ>?%vVC*1S8C>%D$Ov2*B7_&Wt)dP-425qH*xDiIfu;Sa z&I7~oc#8AD&*O26^FY7AqmWO*udlLuxI2cTwwp!0@)?TiGKRF%-x9JFbzI^WQ{wxO z*zvrom+tER+92xo_&L08T(;Siy&bY(-XoZ2ulRNdsESiKseWC<>FsH}{-@i8D|K}O zE+2GlOLuiopxO*N4^*JyLozGtOjKE2WErpN5clmP^ji_sQ=g)ys<56qjpw`T>ISbu zv=7oiGAl`q_rhdeK?rvDA0D25cyPM*T-V#$MbCBj-)Vc2Gi~1$GQ6N4m<4?u1;M~w zf_e5JbVDFM2uCaGsKE!H88_gU33KE5!^^+kEMF7lXPjN(>^_~zOY})}yupxcm>deb zt0(tom zryzT(@iOB$Z>4tfWD`8$qv+(z@Zuo9@f@WbujsSF=Kx7o3ZLKMJ`bk|pNA)MpXUpo zX@WI<#@xt#E*R_cyYS;(`1}q{#lq(^*;F&~`CXnfeSY70U@d;eJG_Br!4uK+zZyo< zA28lWb>4~OAl~1_dSP%ksJuF-Z3oFkvzJ$N58r9L=yh#NnLUSG$J||t(rn)r<(_?L z-46jV+%cWmyuiAjbM7}@Z>uBu%qacitkN&6@(?+`s(AJ11m;KZ}Un zM+ZAG*t?B4w;6A8J9|w#pZtZ}`E-)(k$*5bZxN@b{7sY4PlTh!0IEaXXCP~H5xUPl zXrjjqsHW)S1w3tP-A`Iw#(;MEg`XgpY;ZjYU0-|C>fE{(-5RQ>rJn`{WoLX$Zwk@;sZvrT4tBJ(3K|B|K5zRz=}*^jwza=Jy+ ze~kMHz(=@$0{j`bO#pGb6gQEhSh0!L+50iY4#NncKZTYW`~@m~x>=E4BT_E~rlhI~M~zn~yxWXdsE45a;gW07bKycs>9H;5PNrB82_ESyP5lz+cNwo}rw=2%DbB5W zd@ym_bl#CE=8?~ws>UDjoLOTEZd}#%Qz+?rA0jm z^e356?;6BFvJFvoTi!_mJ+>DJ@JRO|H~7X!aBiFJMNU0BI0usy##MYT-kfb>Sl-$O ze~BvW0BP9knkyy)5F;=n=Zdety8{(TnkiyN=h~R@^?fnpR=_U6+nh0Ds}?hE$L|gn zGwy7T8Qp+)t%@1j0Pmg^GkO5Gm&A;F0CzxdC-m;!5i`C4op0jzFQ9+xM9lbCz+KnG zjQarZpB*#44Y<2FX8arAccAwG^!5Ng2>8%BG2>zA{yTnq!GFXbGrkM>DD)o#+;?Hj z_#WWnDEA4#C!zNr(0dAcPebSXAH<9w48)8drpJu`%!(QNm&J?&kUI#yAA$Z1^1VYb z;}GlFo`b(f0Dp?|eg+tWzefRo4u78q{4eOe0KFHX_Y!n|f!{Ad z?}y&YfWLy?uK{0y-fsY3h2Cp`$DsE*^nQ!{8_;k6)(0>=d_rQN2?eZtUA+*Z}fPY52dLa&0B{ zdb1~|^Q~MV!PS-BpVf4KTzk<8zBfJmnRW15=(@JP7tu@KQ2Vdi?!VP`f4sE&Pn9FN zZ@RjUXs$)Si=Lvr>-8HdZ>Zc*d1Iyf$d1wd-iJphFxczz-7W30Xf9Ot1Nk$KNODW^)11MO?n_0(Mz_> zpRX4c>C1iLu&2qV*96*e;^UnmN=Ny=hG4*(pio&kuEOe-%k=7%%j;^5HO36K!Uy+e zNA=cV$fwtLM0{a#wjtQs*5Zr!bdL`43|3XUvii$$TI`GUs>t;Wru?n-1)3twdJEjw zBh8+GUOF$KHmXEbp)x((5oieOo^~91(Q%aSLG{8oN&o))S~=>mPTA0Cmg2edsFHo|YDfd-XXbi+!zapqDQ8i>{)VA*aHu z&t1&>kDGeKJelXc?V=1uG1U=NF<1z5*GC%{>x{;gtWQNn#XmGOGHBq8pDLHFF;?lu z^13zaVOyrZBTrTmbuv~M*XmX4*BE-uip7`<^%vzS2 zf0fg*+1|;POu6h!b7##YGU+eH?@q{JVP_`Ny#c?wP)|CGW|f&)w_B0L`s8U?9`@55M(MbmFbV`}KIfE=MVXod zrbzytb9J7h@kB}S&wM@-Bz%|b)Up`XM+YoO>RAXsW&zG`Mu0ygCK65sdCHeCPeKKx z8MaG4pHO3Gixg1vo~%AQN76f`BZ}TfV;@QR-N!M8=hGso^3RjFlEZY&>xX!963${d zzC+r>idONtCZ-{dM4PGDvzd*ue5?&)=qlC$NUxcgYU{_XG zFV^R*t;gCos$W_(x2UAB?9wPlOK&b+SX46aB0*-Cz@%t35mVZ4Q~I6ingTVi%@7m8 zvuoQC_LL69t{$236fK&46WA6@+6I(iNlBYSz@BzK0WGx^JnIcGZJAw2SBvdFqP$Hi z7tRAECB=rvozSrT02s(%+#R9pXC%`@S(`o8ejhQk)Ch=al(*hUm;5@q9tY7{P*2%1 zTvCoz;R=gS639yVD_pV1a7nfA0VVBqT+$ap=a}t`7vzkOK(Kw>iYv>Y?q~bt8@Spt z{+sfjQa&pq4H2<@M)~}V-%$Q@%Ig``Fkl;@{2WIHY}%McNQvWCTx}Xh7CJOU&t~CB zh2v|alEM*}BS5xn9I12U5t7Q0b&h(nX4iH@dZU9@8nz7WAt23;KM*oOBZu1@Pm{GQ zjzk=Dshn)>pTXJUm`KQEjiTJ?I6~IW(Q1I)>R5%VEnj;Ss$Gunk%4I%%@21vE+w7W z+U*e7;V33|3bma;b~zRhQpAxxj&eeZIr6AuDIp~sdCKu+LdvvW=p1zXh)mDrzV$g) z5of;kW6*xeCKQrC_ovf}E8n(E6Q}3WMC;f!7 zck=A@a67e|XP<#$+7xnRA~it~&}=s8LR2Ab>iIw>{fGq4BY{a55Oq3HbDn^Ow3N$0 z)iQ1YA(tO%=hB3z<$ePtS#pozYR$bFloU2`FC_1Q9IsXu%d13Q%O=fqYlW_Z%UIsS zM9iTur(4%4B8_h?m-N%E8x^q)wzWJV*{p~I8i&}6j+0@kBL>b~wko>`$ z(FOK`PZqiFQGqW5K8-H7(ERfriaqx`%}xz6<0^8(O~oFPs|UW&hYfA_G~7(i zMM8iKD2X9-b@P0y#l*#YNb@TT6oJV(Ic#FoLVQD zmq})xjl9_|bk~76^^a159wAW@Wj!b)t`TKDBCs2$o*AdCheTP;Q&VIMC6@KD(51T= zn^{kuuRVn94XAmxjEAbKwwtKuBZzB-&2@R(sN(BH3pQhps(^uW8=xoii{C(&`U>wk<;sFZvpfPv zbWwZ(nJc;jfqWj)l#U4iQ^hbYl#8YE)Jd{Dnk*?%Cn*#4+lUSBJs@cpEW%YS5coco zsJo|bmjx68r9`?H%6J3SCTX)Xa~#&pshN|s?6fSb9xbz&!*K;j7!Z@0HFL4!GDi&t zY>K4A8JiO#m~{vcEA0YCz^FTg!xp0EL>B?Uy7Bnc>95VB{WHaRIM`3eU)rAp781I=l$l{czk z$;WX-jwW0TWKxmm6lqHecwJEhMWQ1ATU7mZS#}z6rhsEdInW@^RKdXn z#N9_%KG!tr2=MTlM$faEF(K9I(h~e8RL_!eol%7Pi1;V?G&A0ClE3G}GI2#*nGP-wV$xRW1nGPZ{KMr3tH-}sZq;?lQ!>p5Y(LOAWVOU zdM#zSy<2*(lR}YH`wU36J^&#h!3C1pO`JWG+kG|l`Rnb?kDss{v*vNaMD48(9Ug?GIzK+7>d9YUY?{bvJk>yJQ?nDc-5XJC`AP zr*b8+-1VNYk0n^7GD_oA+ZkTWY|{CKc0$DF-U+{3S%WWt^KbVSmFZx3D-?&t!O@EN z0$vbXJWXNlE?zE`#dAhOG~{jwwnSS4;@wiy=eX|6+`$$vMJ?>(E|iII2_IH{c@ZBu z6i(JaPg_`VbFkG{?Aa7<_H@*LrKGH^w0Nm6yeSfFD~=mvjGjBto5Onb#TS>(6Z=uU zur(45_{y7n0bj`90Mrv|Xf7A;CF_MvdSN4fGqw;%=n-E-Bp50TM?#1Z;|JR~66a>a z?nuzh54Ksnue|E8xXBk1Lz>}HfLlEp@OfFY&)?J>5kZdz!v3a!4@dD7c*Ja3O|9W> zYl(^o3cI|QgsJH_`@NB7#(RREpvoVwkU!xdItc89J?%cx_SBT5yWCj4y7EfHU9&pymXkEiLfkBGbq4cvbCi|T~ z;1;!lGQH)yIT%8(fHR^R)D?J+yy4Fv+}v$0LQYWkmmv@nB?&gr!v{VX+^ymP6?3-* z5grlZFf-#I-d#?ZV9}M!_}k2~$F$*&d;XLuQwRXR@9M z4aOHAg{2E<7}D6KI5B8$K_y6M!8}Lh=zUOiUH2zMkqI2k5{>)m<^~P)zqSu_!GAHnFzWK?L788u6VPXKlpR2-VMi< zg_;%I2IKE}k2WPQ1;L${XsOxM&cpWQqn&-NS^ei?c_mheAN#=JWiS%sNMvJ7RWMw(# zIdMG8il;~Fd^nMwhwowZcoNTB*<|xPH=b#w(_4K!`FxPaqmSbx3|g5wwT`z=^r?vi ziCOtmqOmM1J9jJ*6f2`+y2OMf91c%D7)hjJfe(U(WwNJ|+L1QTMCb2B#wpE^bakGu zSeGKBvC%kCd6bsnr;QVTzKMqYPPqZ%!nkyB`LXS|3-s~)e}v2DvkDo1xnXBNkaTtU zBll>mPtrF^dFAIDlCF+`l>B>=u1F8^`czyyp z`JZej4fnZ3Pej3VMoIo8A0d^2K2!P@4}QtZ9ee*;A?+leo z)!jf}f?)~g_6FTeSkil1++M7*!){L$n+*Aakhkd41&bDpFGOFZ`Q4sS$kXA*<|Nd? z8bh8|pW7R4ZN=`y9f!Fg8A%Y0+aAC(_jR=k#ohvoO%tJYA&|1tvuxn5t1T@{Tyujm z&!mW50SuJJ8z76N3&$>KTjBAtRh7#Px3OZWo0gUdK4T5Nbp49TgVsuFg9!BLI5>;#h)n+I^w0KNv_r+~9?LEgn*kxwe)FE8^iPLbj+W2sA=F zp&}Zm5DM~cQRHiuBeU5HBMK9$Vu%V2l}8DlR(}J0qFz;m$g?6$53LyTp!w>fO_1~i znlP70)E{UJs=TMZKICgx7`{FBsXU?-Ke7EU^R%46RFAcYNNOLW;512BfMny-`9NrC zru5Z*M?pPa7L>dz$?PU%D5grkPX^e8Qc#tjT>smoewCC{`$Yw}#OYIA zlJ&QPMlq4g33Fem_Lo@sBqZscN$W-~USI7$72Ie_icFTo75pafc>Ol%h=R&rWk%r& z(!-~CeYGx9u%0$ZaY>b{NDm_uudm)`QcynEQsQIA&tp+Q09S zTV5px5uOyT;9HRdCH!_k3>ociAzfVOK~*HDsu{c z9!HB8U91Z%*{;%4vh;RMGL3j&(S<}yQiYRc3(lhd>Kvg@`@Hy+gfe>VB$-C?{j%aW zsDUMoB+JsPLPSfh=OywHClm0_s> diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp b/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp old mode 100755 new mode 100644 index 4a5e6b0614..b417661a46 --- a/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp +++ b/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp @@ -29,44 +29,39 @@ #include -enum message_validity_t { - MESSAGE_EMPTY, - MESSAGE_INVALID, - MESSAGE_INCOMPLETE, - MESSAGE_VALID_SOF, - MESSAGE_VALID_BLOCK -}; - - -pixy_parser::pixy_parser() { - PIXY_BUF_SIZE = 17; - pixy_buf[PIXY_BUF_SIZE]= {}; - pixy_len = 0; - blob_buffer_write_idx = 0; - bytes_to_sof = 0; - bytes_to_block = 0; +// Constructor - pixy_parser +pixy_parser::pixy_parser(size_t a, uint8_t b[17], size_t c, uint8_t d, size_t e, size_t f) { + pixy_buf_size = a; + pixy_buf[17]= {}; + pixy_len = c; + blob_buffer_write_idx = d; + bytes_to_sof = e; + bytes_to_block = f; } +// Destructor - pixy_parser pixy_parser::~pixy_parser() { } +// Method - empty_pixyBuf void pixy_parser::empty_pixyBuf() { for (size_t i=0; i= readbuf.count) { - return NULL; - } + return NULL; + } return &readbuf.blobs[i]; } -static enum message_validity_t check_pixy_message(size_t pixy_len) { +// Method - check_pixy_message +enum pixy_parser::message_validity_t pixy_parser::check_pixy_message(size_t pixy_len) { // printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); if (pixy_len == 0) { @@ -119,8 +117,8 @@ static enum message_validity_t check_pixy_message(size_t pixy_len) { if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { bytes_to_sof = 16 - pixy_len; if (bytes_to_sof == 0) { - printf("SOF COMPLETE!\n"); - } + printf("SOF COMPLETE!\n"); + } else { printf("Need %u more bytes to complete a SOF\n", (unsigned)bytes_to_sof); } @@ -128,28 +126,28 @@ static enum message_validity_t check_pixy_message(size_t pixy_len) { if (pixy_buf[2] != 0x55 && pixy_buf[3] != 0xAA) { bytes_to_block = 14 - pixy_len; if (bytes_to_block == 0) { - printf("BLOCK COMPLETE!\n"); - } + printf("BLOCK COMPLETE!\n"); + } else { printf("Need %u more bytes to complete a Block\n", (unsigned)bytes_to_sof); } } - if (pixy_len < 14) { // Looks for at least 14 bytes i.e. "sync+blob_data" = 2+12 bytes) + if (pixy_len < 14) { // Looks for at least 14 bytes i.e. "sync+blob_data" = 2+12 bytes) printf("Message Length less than 14.. Message Incomplete!\n"); - return MESSAGE_INCOMPLETE; + return MESSAGE_INCOMPLETE; } - if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { + if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { printf("2 syncs available and size >= 14..\n"); - if (pixy_len >= 16) { + if (pixy_len >= 16) { printf("PixyLen Greater than or equal to 16 with 2 syncs, calculating crc....\n"); /* check crc */ - uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 + uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 for (size_t i = 6; i <= 15; i+=2) { - uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; + uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; crc_calculated += word; } @@ -158,23 +156,23 @@ static enum message_validity_t check_pixy_message(size_t pixy_len) { if (crc_provided != crc_calculated) { printf("CRC Failed Message Invalid!\n"); return MESSAGE_INVALID; - } + } return MESSAGE_VALID_SOF; } else { - return MESSAGE_INCOMPLETE; + return MESSAGE_INCOMPLETE; } } else { printf("Only 1 SYNC available and size < 16, calculating CRC....\n"); - uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 + uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 for (size_t i = 4; i <= 13; i+=2) { - uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; + uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; crc_calculated += word; } uint16_t crc_provided; //Getting true crc by concatinating 4 & 5 message fields(original crc) into a single 16 bit - crc_provided = pixy_buf[2] | (uint16_t)pixy_buf[3]<<8; + crc_provided = pixy_buf[2] | (uint16_t)pixy_buf[3]<<8; printf("Crc calculated: %u Crc provided: %u\n", (unsigned)crc_calculated, (unsigned)crc_provided); if (crc_provided != crc_calculated) { @@ -185,6 +183,7 @@ static enum message_validity_t check_pixy_message(size_t pixy_len) { } } +// Method - recv_byte_pixy void pixy_parser::recv_byte_pixy(uint8_t byte) { // printf("INSIDE recv_byte_pixy:-\n"); // Read 2 bytes @@ -195,18 +194,18 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { printf("The byte inputted is: %u and pixylen is %u\n", byte, (unsigned)pixy_len); pixy_buf[pixy_len++] = byte; // Append byte to buffer - enum message_validity_t validity = check_pixy_message(pixy_len); // Call parser + enum message_validity_t validity = check_pixy_message(pixy_len); // Call parser printf("Validity Check Call: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); printf("Pixy Len: %u\n", (unsigned)pixy_len); - printf("Pixy_buf: "); + printf("Pixy_buf: "); for (size_t i=0; i<17; i++) { printf("%u, ", pixy_buf[i]); - } + } printf("\n"); if (validity == MESSAGE_VALID_SOF) { // pixy_frame_received(pixy_len, pixy_buf); - + if (!(writebuf.count >= 10)) { if (writebuf.count != 0) { swap_buffer(); //swap buffer @@ -238,7 +237,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { if (validity == MESSAGE_VALID_BLOCK) { ///-----------------------------how can I store the block inside a frame?----------------- if (!(writebuf.count >= 10)) { blob1.center_x = pixy_buf[6] | (uint16_t)pixy_buf[7]<<8; //Extract blob information - blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; + blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; blob1.width = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; blob1.height = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); @@ -261,6 +260,6 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { if (writebuf.count < 10 && writebuf.count != 0) { swap_buffer(); //swap buffer - } - } -} \ No newline at end of file + } + } +} diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.h b/libraries/AP_IRLock/pixy_parser/pixy_parser.h index 79ddb1e42a..2b34c34549 100644 --- a/libraries/AP_IRLock/pixy_parser/pixy_parser.h +++ b/libraries/AP_IRLock/pixy_parser/pixy_parser.h @@ -4,21 +4,31 @@ */ #pragma once + #include -#include +#include #include +#include +#include +#include +#include -#define PIXY_BUF_SIZE 17 - - +/* + pixy_buf_size = 17; + pixy_buf[17]= {}; + pixy_len = 0; + blob_buffer_write_idx = 0; + bytes_to_sof = 0; + bytes_to_block = 0; +} +*/ class pixy_parser { public: - pixy_parser(); + pixy_parser(size_t, uint8_t[], size_t, uint8_t, size_t, size_t); ~pixy_parser(); void empty_pixyBuf(void); void print_buffer(void); void swap_buffer(void); - void recv_byte_pixy(uint8_t byte); private: @@ -29,22 +39,30 @@ class pixy_parser { uint16_t height; } pixy_blob; - static struct blob_buffer { //Frame (full of blobs) + struct blob_buffer { //Frame (full of blobs) pixy_blob blobs[10]; size_t count; } blob_buffer[2]; + + enum message_validity_t { + MESSAGE_EMPTY, + MESSAGE_INVALID, + MESSAGE_INCOMPLETE, + MESSAGE_VALID_SOF, + MESSAGE_VALID_BLOCK + }; + bool write_buffer(const pixy_blob& blob1); - const pixy_blob* read_buffer(size_t i); + enum message_validity_t check_pixy_message(size_t pixy_len); - uint8_t pixy_buf[PIXY_BUF_SIZE]; + size_t pixy_buf_size; + uint8_t pixy_buf[17]; size_t pixy_len; uint8_t blob_buffer_write_idx; size_t bytes_to_sof; size_t bytes_to_block; - - }; diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.h.gch b/libraries/AP_IRLock/pixy_parser/pixy_parser.h.gch deleted file mode 100644 index d6ce4239147433410b7ffd6742b89f682f564ca9..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 3053776 zcmeFad0?c=RUg{6*&$|!7%&z~z!!5bYDuHTc+*I&8To1?SuNd}G0R6w-I98y)vf78 zi){=99y|zyK-dC-up|V+P9P8n#KwL&fQ@O-GFZi8bYyWEND}L%1-|*d^{<*bh)a2j! zJB{S|kq$renc{ecgEb#cLzlnLs9h~DKEAl%C}nsOH1e~Y-#fdfdxVq`?wO>K@C^6s zqB?5nOBeoWP<01F1S`(+WzTq*#52us?4?njQ9J4MJHzf#B}earz|Y2CQ8b&oMRR{| zXZu!B%*=ltM&wso=J6C^<-i%rlN9X57Ydjuy4=3Z!Xl8D9 zc6oN?L*exS;(f5Wy`yR@>n zyfnXfV}1#QxrG~x%bmyPmp7PqP5;)~TCv$!D{kCaDb{xG>~1yg&CGpR@Rp*ToD4fB zt#PO5kJ@Kll&?NNyYP_+W6QT(?BCyQpnQ}5sC&}yv}cY^TSLBxMMeE?zOu2iQEY7O ztnM$*B3yluNxX-6qLx@WYtKJ=Z02a@qdsb8i;ePL;*Tuu`bQ%G+ovelyth}M zY81`;+iTLmt9y-Nb$h*N-d)`->NEAH9d_;=2)i&--@yB|)j4|B8{0d3cU(Vh4`{&f1g3#$E#>jQvFGI2r*nbFA7AlDN_n?jhrAn|D@GfKBp*`Vu>{b_E0| z8c)INPGkS}&N_Uh7wE8JKRN97Tf^(3*By6;tseOT#|;}-!yo}Po_zs($@3%!%vh9r z^h>ajvIGpo#FYPBw1(YQ8{Kl;IXmxRunHeqnq7E4f@p??4{d-A;jO+)xgHfB2V3mL z8or4lyZ5_c-R+NAL1nX&DF(Lm{Kw~KmmXv7DPP#w+}_-0KgS^4+1|R(8p>oET_MRd zD~XxVx433tewF)z_bx>5knwtZwds2p+Ng{iN*r^Ek44(r@~5p)(d{4gChgAi!S)}U zDT;_x6hdTbt~|;ckdsj4`DHd`JQmB0&M)8KYu*iiMIoF@SzDQT@*e!+~_>Mu(G(gfym^H zI&rg#nG@H&dxQQ-Id!44zdJ&{EB*=$;{N1nrq05I*2aKLIPc>6#ti&FTq0QRu-`1| z%ZrQkVxGf*or2;^QB3+>q|0hl5rkRd3?yx(Vgd)}0Vf!S0#myuL!q&^d8e_x5B{@u z@7^qhiaMEI7&Rg_#4-ySxc(T~UOW>b0J3wyMo8+{3~V%Y{V^6^1BH$YfyVdT`XXPg z152l0UxuaQlBb|rRGdNAcPzC&&j!(mZoZRTJ^%5di08k@XX=l!Be79rKw(%!!om#5 zTJ;g%+}%M|IUSd5lfzH@V_+>IFE{3=a$l4*;l4~pE90Qa7p&fFY!$nEjg3t<#mnFu zT7m;7>L^dlE-%bsj4jPAEZ?{>i*C9wJG-=SV{RF8>&U6fB;0`zCo;*_ABk zk`6Kd#Qfr1eHN^1zFx;$A?7a5;lCxkcxfILdSh;JmctyJi$g)X6z113o>rb%k$;U9 zjMa}q5RNLHKgXxTPOCj?9e2EZ*X?&jx?7%IOxO>bGhsjTPe6pJuYjM{mzU=jmKGMl zg65VNW^b&_&o6=})mN4w$AID1*`}O9IUt;{sVsAITV_knku4kiWS$mp&w``Nnv%Yh16AK&oFP8Jc z&COf48qNJ;b!+q1HfN>aA0#Iy!-P6QQ&XmAMd|=-cY0i8cKavA(V#yX4<|?C!BC`F z^bfvEGoyTol^Ktjm%_i~W;*k@Wk&sprIn>cG|2qI@*?D&8%wjxb+Fr|g}HgiK@gE4 z2X$V63~k92r#*%O{IGQiW-vsSRG6;Mehglt^~EWWvUK1rvsZq6a=zxjEoN9NfGpN# znNv;ZxvqLJ7gv+v3*BIi*3YP75tB8$j>|=}z{-NmmKqVc-QC{{oMCZcCS?7o#I+^*JMNvqdA?sl|SEY)W@-v4oiD|uo>3eMz z6YNZ#2`i75cVD!6lTI=09CwDD{*f-N7VERjonv`a5J6-smndvB^-~$f&u#N_FAUky zuB@GP{t1+M8Crrx3gUCi%Qse*>+GEMW%OIjFNCMGqnZqE@L}*WJcY-fOVp8Z-6z`s~siXGP67I?Vd!#zqiDeRcZ2u~l-D z)>#`}s$RCV%pKc1#s2NR#_D>L?0^$X<=tN41^Ik_F=1+)rj|I|w0{flk)Kkk^cm6T z))sq$hIR}~)GVSiBAZe6k!w%%xLGtOtJL?!^PubUx;(9LnZd9QiUwL;1nbJnMbpHW z%W747X;}*29TpeTu12Awi(dY!&Jc6lXe^8e5(ukS%T{(8*V*QlSu$-imhQB3RUG#Q zEebF7#o2lKYE;e)t2Z}`ry6_B&7JL;`fOdee2_-imn@qq6UUp=f=76YrS->qHL6(}Xs_VZ4%B2RKVKNl}fp1wdfKX+Bm$zI~Sxw&3!K+m@-0s#9) z+)QRoNo7$fW4M9kQ_{8JoXEnuLU62(i3syv#4=!gi|Omw+H2g}#Oi3TT!eAVXj~_# zde%XPQC79DqjFLz>o3e$v8+*H;F_hUt$d#s{d$?Ryw;p;t%C%7baQ)ab6cdYlELCfV^!vk)Z=c; z7AcBSGA)J5(dhttE^+lSTVVp@Ldi~G)U&-4{#4V(LThIfNnkwg&S2@jRIjrmI+2OH zGjXos*HJzyhi)Xcr_u~lPvYk|6t8CZthH|;DLY40r5g#*BDz~i3 zm~^aQgrZ+G4{mZ>j(b=#hs{1A+B>&2VrWf|l};{Z^eb_f-(r8z-Y#s+YjoiV+?t?9E&)D&AM8LQomvc4yF~@!)>mdGYgIEED5!CjXUfjtixW#8DZ}uSWwgOKi$yV;&CEU}|Ez3r z`~!s6W<%x!JF7?x4a}44>#XdOJ2>@6xs;(EU-=GqTg#VLnRdBs*xg&bb!QceP)z6) zaT@pbw^#3AHCoP2GVaT_l=5z~ajV#9Do4~V7Bj85Im>R~OBts4dbI9jg13<1YA7dK z0ln2tsZRF9O1(a}vb?akfK>og&$CO=fMcr~n@#i3gs;>W>+?|e-T*@>D=gYf^+lPV zV|$kMDf$c3)xm7pwUn`;bhc9APc~yppPOug1m&$TSXWq`^8Kvqg5rT2nYyxESt^%~ zo&zjLqvRzaW2hy{4_f2d4aVggOVEbTEiQ7G13Qem!RUA6Lh-1iirdW(K|Z&*6Gzh{ zw-?7*PDiE8el|OJY)fUi}W)lYvfer1Y$Cx)|5{-Ln zjop1LoY6zdTJvfW->QpIjS9<-)VhnQ9usYCg_WdERqZQ^+NZy1%PoeFN1m(Gn6P;6 zszrTKE1O$uCFcaTjhN?HrhYRK2=)+~cn*Cq73OXS>NGzJ6|Cd~c6O0`o@m#^YX;*WzwJIu+ zMk!>S!-N8wa_Xk_rA##LmT{M)TP-HE5BX7ohAq1T`>4K^CHGr#?4aNr)j2ls;EX1i z!Y9?nNh|D&=A9Nj*mU3DJD^R zPhr-V+c>Dh5P(He?&zc|F+L-=LiQIaY#848_UfOBC6lELDe7F8=hxTCOVn3&f5sHf zbya0qA`5wiwd>Hft7_?8wwt$iutS>c;Xt*^La-(^sInX6NoyH)ilUmNw66J*R(I|C z^tVO8QOc$lRWDy#&d*X>-`{o4(@w@tBxUqd1G_Ybv(`cIPKFEXI4(}vY1l(qSdERc zh?Eciz_6i=D;cw^IK0KTHeao+?HF?umAl5wwZ7V^$DtZuy@&mPS!x`$BeOG>>zznf z__X#hw;oFvyiA(Xhu(p`ZBCkgDlDk-o2hdM>d0ijT6Rk*)}+qtWxKoa2OBC@M#;5I zS43Z>pEjebNWa2?%)l1Vij?ig-PQdy>?Aw|3kYmrmFrWymL;qR<>c6bYmh5gPUCs( z7MEFNU!uU76K#?@6}I*c*C{4VR+m>sK!4i1 zq+BO++R{XB-iL{wvhb<;FcwP36>`Y7_Ssupph%#VE@Hu?KklBvOl3H1U5}ucSzfBo zal$L7Vl&CaJd^2^dPY=Eq)|wPMQpIZ^v_yKvSzfip=NyJzN0cfn@Pn*8Hr`jriWIU zh)rb`l(NSzOu)h6GYdErCYE~QQkTjeF1pHqahOHCyA%dAPfvftk^NE|fNdn3^PQ`6 zir6&OEPI%2HKHf64#V&+GX$Q(j-bQD@swaquuMrp`v_msxjO2cQzm35pmvVjs%)F8 zlwO(Rgaf<-${!WY&BTPv`*xb2V-~a;TrZAW1chS>G>aIz!r8;rg|+>Sge`LBs<1^y zPNttVEHw_e7A93|R9F*=zr(RS&!rz*r&N)RVaO&BF7hOaUqp; z**ko%^?cYr528Ka-Azg#b5wpL6LPXveg`(=z*SfjSA%XpJ)YTL247{5stJoN%HIJK zEIC!6lO<{c%LU~UQ8%Wt9o@Jbu#QnWd&L{2z~$F|rYBSyve|e=vDVz5xlytq&wSBO zLm}0GnzN&J1Hbf$laGh>EJCtvW$6ya_;=}@yr9Z@b`y>7spuC@`!6gxs%JCS#ImU@ z1_!GMaoXYUTHi1C(3h*yCi;%SGY@=PR&YI_}~iNo+;W9eK8a z_Iy+%2U|K_&M#7OU^bJb(w1GZG8wHwX^-ldEGJh4FfUojs5a4`rVpNMo>Z`pwyQYb zY5mJ0ArX2)>vMxFEb+h;issJ2-Wpg1*^I_!)6krtIBK0^wJlaFY?w;#gb@afKxV2w z-ZW(X|NUzui+>;28p8^wd-M<-x;w6Y-1uw;M}x3qaaMbxn8jb6f8r3=9N|2F7Wi|6 zKa2cX;?FXFR`A1MbBr~|SaSjyYmTwz7>kI2ZYIF^jJ{HP;R|ao>h@uw({0ZT&T-NL zdnYfct=3l0&wE`}w2x}#>auq8U;|yRR?024wc6SXUQj~^+A8)NH~|Hxw*)F~HTIh| zoLQY8>+SVQ)o9OHNbd(SFb5dT}*xRXXY;FPI zhdNI7l$tC@aWH2a=5wwO;|$)$&TeB{{RhJu_IYZu4^qsblD(^5L%Y{*Z`NqNxk#IW z;^qdnt8EqBdp+y6>EbXH z*ZAzb-#V*pbq|L)*HXK4vsgP2bzSXFZK(1bwLfX{7~ncJqTpn(bNc{^++_#w&*uK>{z0>LcXJ~Ou({!bY@&zV+FspaaJct(c6Y_Oy}e(% zyS;OJb^8{dcUL!ogEt+BSGx-%hCAXo*xuh;T|-pX&Cc3taT~7f<|gY)9Xjeg*k51W zyA^rvugfkuy!YAX9FM5UURuEcAZNgkD4R=9sI&HZs&c>JJ2Q+Oz>B}m$V%mqq`GQXx?w$SzX)PX$FeC2E)rxQh!ih@XhriO!BDoo4|Vq*rwP|fo@)`J0gdC2;qPUA>3Ni zdukQMZ0;-Yi|iCdk)u{aOQ374u{g}@TDSL*s&D5SowqLg-hJIaf^&eAVVx^F`fVu8 z2JlA8s|OhPz9X#ooh>-`uz#655~z z8YX7Mb1uACor}&fKNlR{53ElEVLe`x!;73v#jLnM4ROOeG>3txdwOei$8P80YF2&9 zY8Gy~yIbHChdXV;_vof`y)NXnm2fmR=S9&bN0%Nv#RKW*d?Z_?2P|bcFF1WtbfO532-h-Ph|OS1C5K+c&SF`Gg(h4kU@~dFx!jnZzAQ$t z9Q!*GaaK`LI^?;iXjGN(FW2X^b<1GY9#E|99&p^EOi^WFd9fZh4f7N6YM=Ug4FP^AT2&k~sr zX5VE&DRM&`h=z5s0a@mLv3?&Vg^~s$!zSi%&nINraLd^`$5foVUR~R1Ze(atkCOA* z!sBqZOJ;f-z6m3M46Tv|I@J9;C@0o(FlFE0d@3rGzGZ)Pd#;iciIucK%mu85LtWfF zfD-Vj%_d|4NR{_(R`+R>fn7q%N5*fhvAJbmLz;b!H+m~MEh-(=o2gxpZdZ~7t(s)h zl2~mJMC?n}w>H*9GV!BGUfsC4x_+mb^a5lECkVFJU{Q~mISsvbdvmKo++5$gV*~1y z0X7fNc8I)dQr+HxVd#^UBzBs+5yRB%ZtpZB9vEnlek*D2qxbBfAFbl3PsX=-uxqId zjit=p3jHoP?>Z!H>#++Vw?f<7*^fB6W^o_KTx~$opgOdjsj+`=|7O#6zsB9212PXB z0k!G)4Sfm~kQ~r(lpz)%prmbg54!m64H0vV$FA*Zn5=ED+5m^Q!APrwTif2pF(LEv zjmGvkXVV2wO%D4Xq9lgYg?G~ZBF-4O_k^* z+W1(1Z|<`0O$xFuPh08s{oNhgBZOvOBt-k7P0UVDnU`QW!0m=S70ZWo3c%n;1YKO% zMg(iDa8se#ya}-R8SLu$4@y40YQ&_Ut9os9EXtSVHn~Tga0;w|Hla`5EA-!U6 zzw%ztD&e45;mOttzl6*!H&xg^#r0E0j!+RjlgeIWZx7;Y^}Wu+PSGlVCd&qyER~*n z!9G-&DZ512{hf+L0_wpU_X0!^T9;kNYQ%dRxXY)KTNOPaf!@UB9f%K68CJDWmvFkq z=EUwUbObiB`#8tDvzFl@Q1=v@ySVcp69a0)RZ$EjV}>!HpAgkbHd=GNI^{7^vyo4X z1No_qOf@qO{PHik&rVvE75E~lh+Kj4vj(FasCF$aDD=!Y?qn(^Bd~*185^Y8rUR`) zf>kaKjoQraZ`t8{AU7-7a0lB^X{}eHA7pFbsg1i$h|RW#KGn>VvsBgS*lgUzvbfUo z?*^4wQmc3Opy0I}E4zLZqOCAYchxywh}Dp&@5(9+O4`gaOsKYEgjh*6x0EV!YpL9# ziL^>r5n}Z{I~Bvsv^ztav#T~U$9~!v&wwyRiJ$F@}EjBVU zt`MuKW+y^kE0(DQp;nT}iK<0bR#j>xft)-ErhpDushg}siLh0XQi+)aGD0P;w8#}V zD(qI5-!(VISHxAiAY68<{_=}mMKz?tQ9MQjH6bvk7mK>s-&G` z7ob%~A&I%zRa!=#DViC9h6=1IUsP&EB!FVD!kS5|W|YKAra-LFpr~7QcLRWz$=2#7 zH(pB#MJ_rjv8>L(j-U;Xh}&yh2kVVu8;ZOFf`Z%63yHWxvlYFc7y&rTBeyFU;=s=M z7I(^I2d8{hso*qf-qIu0Pp0&YZgP7^j}t`iaFk**>OnqO0g)$K>ICvD4pyUTgIQ1m zdoh>qGV8kZwt-VGn&3P{t zyiCMXRWPm6_gDAw5e{OFgHI*2Ql&{L5N>TXqN?ze?3Tms-j3|VhXi+)URPP&kt1wOr zf%09r0u-HLd-Ij6+=77u75mcL&0=)}J1l>9u$v9+@kLc(I+j3o^wpb*n7@B-yJ)U% z#1S2ZeXe{hH{f)edmo8xHzHLcz1FxHC!(eqf#SKck|rcucDEa`#?OTV6Ol`9GvU<( zM<}8Vs}M_eS+iblQ=polXzsF6f}ZH@`}$qVY^c(3YAs*TGQiXvrh6Q|tRnbl-^q@R zb?sEYNK5AvLzHA&%G1q$p^&Mf#e5B(g-#mjuS-wdCWB4Fn8S!)WtUVpKe?U6oyfFl zyrq~}-dL~dt`}dh4lY|wXk+a*go`u8zbk zu?;4*7BLmlQTdfrwl++l(C%p-AjClkX*43$J(Jvy7j#0XOiZLY!;WI_t~8P<9}RSN z?o|5)n+rxa(W;DT;dV%Dblu-<#G;0JXsMx=+}UgL&RD}An&6Qs+%CUfd0`EMEf z9`422TW2MLrrU_pf$va@DN2KNw|jv-U0PLfyMj$XYbuB;bU`+9W;w9U;m+8dJF9GJ z2lk+SEFo&;=GK!=-3t8+{}+>va$+rx&j%xDzsF32Zgt^$j{b!@FIsX#QLWgVNB)Cd z(&o;_P1MZh&Xzv5^?_-IvkgkP3CRLNpLarothCK-++U#1?VUAr9d5}oFr}K^E$s9w z)Qb+(4Q=kgfB?x^;l!b|A259lvfaSo)9w@zcgmdma69|D zl^G`{Y8tE)l6+tc;%Yh6mxOeR$g+dsEw`zR#}oVuwj7jL1r#?SPjWAj$afH5y&$ms zKH06thI9@HTQI*0RBV2_O1ZOoi*p8&5*L1(*zW^`#4DGOc_4Zo@Jx6?@hDGrOzJAN zYhf%wXDJ?go40POtGTvGv#<^K4p{Bpy@^}XBou+%)D$6oLG#JY-Mh|7p-=+sZ=waz zlQ;ng;b0r(*=W#Kk-38IY=c2wesE`ZpIfk+0Lc5k+|Z>q_SXFSr2&GMTt_RLolFb- z7Fu2=8#>xy>*(PG*OTL{w7l5eaX>4Fb$GjSjB_lc+!{SzrtaV&*RSESc1@j`;l>7#>0+g2>0&|Y2YTI z=rrDV8LmESos2XHV}=Zr{EV?3L!)!p;kj|Ck{0fO)u<$1R;c6Qb(*H;u6)O3x2?rJ zrmHw>T_1LM#W+SauKd7F=aTwKXM7YKX%XOc8T>AfQqRDAk?jYQvvcxcID4%T?v24m z2{d))(EEtf+t5qkv)1roN2{>kp+E`=5aGu@+*~y3k|)l1o88+z44lNz?;w zw7I%b$yzAh$>Q=kirt|ubw<%x<964@qN{*ew025_!L%Y_CZX8nU;NP;&WMgN%v{D#@Zb(5#8nUGPKAg4n0RjSLn;GNGpl#qq)Ncl(+IET)C0L zl?b+a{mB_)wR-2L%tG@}hHdk(*XpyoG>`h@VUG^EwTOI#^T6M#?!y zI32J_Jz^(qPR?PePsf#uzXi)>n6zy*&Db~ zHL!gc+F*tV^2m0hhSelyZJ4UUoDj0;_FyR257dM+a!uprj2d)++$e>Cm$T1R9FV`5 z2LZhk;za4@83Hjm$Bcv70utSR&D#r?e$6$A2WS-7c+-A%n^%end?gUcv>x`)K%l(g z64ww;J%c$T#f*W?Da;3WmeVlGDc0fi^>*RjB~e%ns2!~j%p2U8gWje=Nf|_^j%YrG zJN|ryaD!?M60K~J=}y`f?9L<^?vbe-G!rF??Y9kqGcR=zB!|5)0@}z+a`87;YF>A! zdIcvjtF?a_T~_QE0qw4GGr@k83%KMd8jh=d--eMBbpo?!u}ILT5ZtmA_rQrRqE;OA zF*w`BUS~8pL)Uh&`C#h-XeYSAll?rV9`re#Dm|EfI|p9jU8;LS<9dQrLs*VD2O@Y^ z**!`MZA6iTAw-eTG7XAgD;GmdvXNDw{(oe2y}a$DZg@ir6_nG_tDkWe7k$m zxPsaCE1To_*5RlfT&NdE1K)G5li&gyaWt@3=W?ka#U8wI+NXdX?~bYpy=zX0*t>;< zgwv2fYPidaz;FV>+Cj+SY6()&pR|X$8rC3NPr~>L#aB;;6H0L@za-we}n{w4q;N|1eTEL0#D-(juVS@_2mv5k}CFbq8y{WhBNqELU-V~B>9b-MvklzlCBLxSt$b{>*&T&hggYnP-h zsj1t>fxPVDV0N`k==q2&se|j|^8jwyhALZy^*$C#y4O;0)21O`AyI{fCdtd>pu#QV zL#ejcc!f`zYm(SqhT~$zp1pI~l!Z+7pj+No^g!fN$!p5kI{vLcCpgeT&1eC5y*|%Z z`Wsl8Bxz-thyo**ut;fd6-HfBGQ{Ommc?s3TL*WxJz9r}1hxiotdN~e6nh%1;=xfb z2^b&pjtpHGNtQk(Az?9@2+D87!{*WBkfIVojs%t&aWD;CzE-^L+jx^lv{&cLDq**= ztk>}ZHtv0HHDGK^^L*G}%K)N>a;V$5I+IA5(IyU5;uA8_$l2W5#bJL2LEnu>I3UIs zcqNpU{N#XmYOr$Laj5x87E`JhNxAEV=5>-OsQ1e#a%{x!KI#V|u>Qx{OZT-10UW#% zP?4}qL)xZxH40P>Q@9|FRaO)(df9;bjaJ_fq~jByz|_Bsr5ndI1Mpfzw^NG#DfJW6 zWD41lJJG1r(eM&rcU6i4{Wwp;xha!9-yaTzi3_MOTx@s7 zo-5)UTHIoQNY%HP^F$1#yH{XR!N59?PpM`8_zp9`-;?@SgT548H0EM?30X-G+F~E2t}oA zJh#D8p-Gn=zT(ME>Re3-@?2<^sE!UkPRZ{QB~#pkPSkp{(~GXKaOZ5x5KWkDb8huz z5DX~+=XFWc?+UQWUZLYrx;KU_DBdYuI>y@k!5dKeK}-m7upt}wh&|w_OAykVsjH9c z6is(|96Xxf2A;~WD)X^#K#}W<#bG4L82ZiCy}eDGo_PD-xtI{vP)qq#>6eQm9b{T0 zw}rqGrFqvjo))d#=5dQSmjG&!qX9>d<-t)JRTQC0GOoH{oq#MmAOkD#0*IFsLhtg5 zabY9n4vwbHTR7ZyL`jg~&1K$oNr8tHg3wAf$O<_MmQvOLB*kVChYf zGm}Tz)u@Q0%~)#?6wOF)U!?-ESsmYY+eZcoz=nAcRs~UVR}!f*7@}}wwuwTRVEPuUaqL%g%pU5E+}_X zz)8&l)-SvqgNV6Z;{_lDyvxFYqQLgBh-y+Ry5KIiB#NRqJCx0fVw_NMPyVO_t#?eM z8a!z9ic`FbH(V8})GM*m>j?qc>!NkoEyk@Ac|Y!nIf0(3kSF#($hXCP*6EMEn;TF{ z#SWB)z&?q-N8u&zr^CB(5o$+*Mpz@9wU1k8xY5E@bRAv7&G- zPC^pJK$XZLS)p=hR)`BZBFCK%*^@ev-6-y{MLy7%+H84JlC6>$XDd+SYz1PRtw4;j z#XU`F0Id(%nHzR^;oK>2kS=p+ed3%|{h|z3JfnP8{G#ku{Nh}512M{GAzfIDP|doh z#91zBQC0&n%3`2JSqro%OMw<;1^ctDF1Fp|_P(+zrLox?Go(0=AsjD>3LUAWM!77B zQ8r6rlut+GmbUMjfs}bU`b_5KpjKZFV)f-9R$kt3Ro_lp_4P`v6kf=c3<$N71EE&3 zz+LmS_}DzBWaUPyRtag9mxEY&HE5L=gI0O%XmV)Z0aEqFLae-*)XJ+#th}4V%FC~+ zg$Akmav@e;PHN@lBvxKdV)XLvNH)jCu%IkFF2RXq}bn@<5DU9ca;u11)+jzpsO- z@|YiLEXzK^t#B5`*%1Gv^D8CFfD)p&Ds5ntsZt^lhHtmGa3=2<|?UCMoVIp(UPbc#m7|-C$w7uA98Ld zz<4B|%ZVhf5DZ2~iC7doYzLO<)A z9f2Wa$Y%o>4rb`*Q^K>WYarUjF@p(U&8%ze6%c`#hIa5}I?oSDx zP2HO-R?@$ilKYFP<-Hi?qsZmKW%IQT@lnU9* z9D_6oFMb#aXXgW_Neb~!PGBYmfkmx{@d|1_^8*c4)Xcytyw`{5C$mMF(Elj=0=GAR_Dgky?M!JdLIepB1$ zYy2o31cY%Zh~qqgBPOFka2mmk2MLiBTq%`QQv!QZl1e z0=te4VY0~}l~hv#+AvAPbOP{0G_nn0USs=#L`q(Bn6RxQz@#j|NpRCdfJt!MK*W^* zHo*jUx)vt!;hp+l#r^mQAN5FsU!8a3DuREv62K;yV9FhC2JR0afW)a;zoI`#r&pjT zcHU1W@o7nyo>S9yLGp>qoIEY@(sOF!E=WFciWAe)4t`UU)(|G;?pcfb3}Gx1C+$T- z(mq`Fb&qu)B97S`BnbiHPX8!nAtXr)B~5#fz8oP^|KW(b!I0Y?Fftemi$|nYBBgz} z_o^h3S5=aDRhq!7(&&T!gE&55QY_#kIzC7Pu7K5D66yS!N~a7dO-q9vtD#>gHzp6p zK2GKbPAQI>REQ@hQ%49amu8nW>H?<)&~zUqnT=%%%al?fs=|`sou;48O6Q5>bOe}G z32+kod^kv&gE)-S=F5Kt^M5nAuKeDF8kiSJb> zS;%*Y5F4te(ag6V5EgITnJgL?x!xsI;`WLQAqMlq3heL9*t?T7HlWO(7&P&SJK5eAY@{0JVLb z{Zw8-;42gQDh-}2evZ%5wGVL`d=N{_*hFZjsSnyo@WC+FeI1{RRv+SBoMF|+R4LKn z+c1ufd1N;UnjYaz0w(?JeT&4& zyayJWotR1LXa-g66g~4UsWAf$)MRN;QnO*v-7KSlRbqG4o<`4SWYj*%CO>NDGXwgR z@YxKh3M13LPT`Sh;frzm(Of2m(yOg?f$lliu2zQ76RoJ$sM53Pbo1{$2R$2pH08ac zDd~V-od_;4T;?(pgrirdLtNX#7`Yt5C?L~o5gzn>_{D{3G3b+xGnx_u^la%!&z53p z!_gyKQ{XuHDyK(2#WeG^HqDVA-W7hwMGxI7m>-M^Qo{R zEH$gClUT_&h}G^vVl`y8@~|q+ya~i={BA$}O;Y37vc6qjX&+{SJXM^#o$IB$G^!I|DHnGLz<{ zS50#;tdEUS9u8eC>&lF6(F5`V2DX^zci82}GqmZ7B(r#y70pgUv6-g6! zXtj;f$>kGl!gd=5&b1=x$re^fVl*uyRVFEkTu#aNB%eIUQzK+rtKCLDPKl5Wo)4Vt z-nydp^OcANZ?zIZ%w__1snx(2Cz%EYF`L50Nv0Se<^szywwkt*r$(rDAc>GIz4%l! zq~s}YI2mWN1oG4f*({xmr)BA6oXrx*xi_4lYhPC1pyYgnt4!bKBr_%bD>)dFOw#8F zKFJmsGf*ydQnQ)q_H(I|nhh?qNVNgLr7`Q|qfC0IlWK*6F@v0a2YmA3rv>k2gZHKd zpJezJvIBB1J5{L+yQ8^)qgMN{nh~L9gP%^0tKDV*#NyV z&!3M-ofiDjG@t5pfON8zN_zIKQ`62CGuy&Q`!bvMWj^0SIc$^;uMvpZ;)9+^o75@6 zGx;92^7#fmoA$JP=URCx%m-pVZyu%}xA`XsKq(sm%L16=5UCV%2T?j!Jd=~F-icmXjk4Jf8YyzP{aYb=Q zuA9#7KJk`f?^|764hOx{%1{TfI)mVr>s-iTCZshN(p-|7sSza?{Yt$K=~Jz((cxjP zm_n|WZ&Q&k}5LROdlWV4l!6KeCTx_lv5RryM;Xy%1nRpcuVg`e6?ElLeJ=E9KF&47o8*AH8CzO>WkF@96aX|Lk}6o zkza*xlzvrZdGK4Pa*@(6F-S_^xA1n-T+XLSE1cpYqq*k`)pJU2)N?ssHPj*%qvLKx zEzM+U5q&WwRq@N@RqQ@IkFMGeB;HjPhv}!SU7g5+#IgB=1V~u7 z9VKZ{28wM{7{-!^0#m28Ya-Rl>0^x8Q&bB3@2SN$0^JtP7J#~$lwO}+vVsI}+ z+dmo6^iUzCU4^8i{zyox&l)j|NT}wM)Lg;rA=mB*7iPq5NLWwp0~WV_pCwRc@syVqs4 ze_d94(`B`W^}`xTPA{v4ysVb;(w;f)jxPO2DxyMGNDpSCmpw?#p&ul+&=2Zyz{F1Z zL1Lu*Anqd%l4gF8v~e%xMjTQp;8 ztCS>?SVBhi(Gx;q8L6b?-5DE84OLA$wX*Els;bmXwQ8z$qveQmohfUkusy@>dqPM` zCX}QUJQwyi6fE9Vi47V=jF~V&jkSiH$#S zEU*xo3?(PO;BUOsclS>oB!_Y8m|QNAJ+xZRo1diZ8Z zB_K}2B`21!<&ZlvACr@_bC|87G&$v^8XZ!SNsxqO3Iri8Bw-~9Qet^g0>v^W3HCKc z#$=Gni&GgBLE`!ajAcx~cwsrU1!Vkv^{8 zIJ{0p)<8?j;sYkBaoLMYlH&FTsdb#nfqhR)6LbM>g5v>>eZ>L^qbt$IS89^LfZvwG zU12AKaeQ`baQFbnk3`mwGK(*XVYnriJK##j?l>NjN-$?)lo-F*Q4-SN{0MA49%1K> zWRr8`T3TFeg+9bLUP-$ETj6)^wC9f#ZRSklC{=aym4*3jwDTTU}lUluF{!5qlMi{a4BXRO3v+%4;j+MC)yTsZ1 zQ%KLw65=t%2iLH42AN%+og~&F4f9pnOAM45&M-q^4cvErjn=g!{jt4 z-ZxAa7NAs023nl%l=hCui7-C89$jRX1fHBO3Ov;;3q08_4AOfF%ryn(mIA`KXA{Rg z8#sYhi7;0EKvWY-Ng|zce>QUhd^~6wMd)~7)l1`nRT4qCtOly6lAr{Rnf7>y@1n-J zBu)xWLY(W#lqr?;>_8Qdyw4QwHJQe}#3P>+zG#UH`HWV4q94Yj_B$%0qw*foWPo8~ zl$V{k>CN9gsbg(2g>jLd&(KuHg#~ZA1W`i4t)(cJ5w%FieRahQN;)z?FoOaVJ0AQc zd+|&Cmw^MuCvwyT$&u=E;Q{P$G7Qf zjF?j1uj{|CevI{IxB*!r#MfLNVVNqQ^v0{r7rm9DpPeq<(WSdb`b~E3Zpq{j@Bo+X z$rl=M@76%h^h92`JbQqTTywD=QMIXjf&&hXlQEAQM`5t7n5DbsEhA6*qtouOw1^|R zkGqG|Dj6GajQV$B5k1B?F(L|?iX0?_mBS%E%po0YfD`;8bn^2G;VNSR{wiYvSsbdP zz}G4Ia)+_Q5z;eJq{F3+J?OW)8Zu>@w}j6N53}c7yU3= z!ew9j;e_y^B7Ye$J<&t^BV3t^H$h{8RsCQ{8RBTno0*T~>Siv7oQpTm2gIvw&kl>D z$q*l;r@}`AmGfGHlc?oP=flWw@L`amY?4#zIJ$x|5f>(5NsX-mC{VQiL6vK&FS^6A zZtUSx!FBQ!K3C+EK5*d^Ef+$(J}GeP6S;s?19+?IhmI;9S2D4%k=x{DZANbg_TpU8 zNYJmTgK#)uzi#8!99Ek;&)IJ6POpO-jZX^SGeGE`;l>h{4{m;q9nb!NSEfWahm#3# ze92?n5_JczD;0PlJqalJl1;lSNp`Wq8_T`gT*=_bUi*mM0}d!_$K3^Wk34bg9arj* zw(lU1Bkg|`m)uQ+L@+_&;%RYA&dPhfD}<6U$yk&wtgh~H(dT`nSdKClZo?k30_h%| z!w{bi`Rd29+}aJdt6S$PBGTsFc5AgcU&lZO9#xD}K+J`-rrRb+aODm*5IpUJf39PnA#89i?7>U+jjHzjtG)U|ZpxnX*`Mgh33^QV) z+&Mp-@G}C)Q|coNVUqA&gbRM+DoMc;t0|N|l@vtMiQhKqcOOkUg;VPf`6-AIJ1V<6 z`w?I7rYB+JQC4w9__1nuyo&7aIQGP{y;JXpY%n2Cp<%qivWteyluSfNfhgxFF#=*&H)8Zd>`VNvQKv)EROXFr!1~L9Up{x7y{{COX@Yk zm)RhdLaJdbAb;t#Liyf=Y`DNrF0)cPc0y&>1=LP|!nqhOFh&su;p}n7c5FyJ&*dU5 zc;TMyYe-J#r(KFiAdKWfD#0TRPe65Qu_F54(%bhi6g19`O0T zqk&sI$Wl|t;hQl|py9BT?L99dl>|9S6+zYnpcXWIa*@RN6A1t`JaBja1IZ=ESP*MK ztrd`=sPSRA?xim#S@#guMl3~AN7OVVuqtDMLI&rYN-5PwpGz2A_9Y)U;Z9)&4+`XX%Bz|4WKbwvd9L#%}`l{r4-0|xrYco0g{`jBV%y4F>a z<`9}{Xp>slPDnyZQjWs@gHEN$e`M_&bACnjZKu-@sCS2_x+ z*>k#~Ay)LR`_rlUhsr`7m*o4cB^B3qR%y`7Pkz|1Zicmyj04cJwQ zCFyFT3bE`m5YPO#7|C1!9gBAYH6K{Ix|J}IdyjkpMBeQ_n5(hLpkv9C3{QMsrA2jL z-_nS$>Yz{1H~nx8X8wnmFQjVxDnI?A3xpt_o=dP?qJrzlU9a*~jlMW_2BLE!bsT^D zCjH_KTCn_Z4MF(24M0cu1RUYxYH;g%3XbTDH-e&=*#3g@i8?>1USJZZHztn8pdX!j zC4j(V$o$yYV8zh)*m}1+u{Rc%_=KDfd@>dpRU-C|PBG_s9~hKG;lLvX52a=J3bYz5 z9YxP7G11P-^nK*fXw0ctJ>4s?_1|^#`Up&)Tm)h(LzO6Ehog(3venTw*8SX3g47$n z{#PZ+_y2NaD&#YCviS^|{60fo4rFAanvs|oWh5n+8A<46MiO$Fk%SyFayS_Dw1431 zddv|&yXJG5^(-?s#XDp$?;kRn_YN7(dxwmR9hKx5jp{R;5X+1ja>!sx4;f3zAwwxS zmk|-drP-sfs8fmrIdU!|2%gIb$hnMwoXH5xEi+X@YA!2E&*VisGMN#2CO1OQWJe@s zQ-16oWom`gOh!P?WCPSpCP2+(0ehs?HsDTcCKE!=Ucwko~N0COxH=-yiv(3H(xvMw=Q5#2*g-WU)?g`Jmv&0d zC91CR;Be5UT5JrVQk2_nm)H50TD53D*{wSmtK4M9UM@bM%@tcr1fOhO$-*Nnq01!< zNusV*hb)LDkf~*FT^&&YxDUZPmFKq9*93Ynu{oHOYfF5)=TyHAIf=JL`4L*`WF~IS zFV8r2Bo4i|CQJ8X(Z$Z~Snc&EN|D#Y3C*|hbh>bc!(!2Ry5%E1%NJ17Ch5@t+-HvN z9!^Z4_n>Z=UHuF*S6!uSo`ARv{#(u$2!Tx+eqq`fDn-Z{D1qX>L+G}1r24&kEZQ6N zAV~?|!SPQDwih_YfR9?ymF`MjU}O2P3w8RnCN@A%SM!_;=Tv&4)(93!PCsbA0eUfp zwoG&jS|b-@d`$~_0KA>;$xSg|OIXkQk5!Y*4Hy@~Z9TgkG|7Z0C!oh;2-oGDR?m5# zQrx*bb)SWoJy15oWu&sYbeoK##!#(=nm2Hr>Rj06fJQ|ywDjEl@ECdklJSr&%S+!y zFXcF<>k^j}mVxoFz|gUW&ke-DNd4epb!QBIC2oy2|3PL=Dj3>zcY^ywpMJ11AxEzs`r%-tS5eV+H*6^XI zx2VYml%nt#A^1QL)e%FDiWPm0ic+dw#f@V*H7Ff;^ zssqVuH^DCrW%*DVeuSRyaelX`yt}gFtt{#wYbo$>34s5dbyQ+<5#|A zssn?+r|`z_u|5z@x~?7^!{$c|(fJ`<{|q0*6)Gkq%;5uE5JCw_oOru@510GVdRASJ zr$Yd#Q3$~}ZuPHcgk^*0B6-~|VEEF_3H6~-~!3)yv6^P=vh6C3N=m%%{ zi{O+J`6KoSbchH>2L({tY>8DaHgKo~)-R`4DBNGeR%J?$DYCbjMlMMvw)2RiyDz%( zOSb+UCCNm09&vQ)L^_#F9jQQTqg_Lw?Q`zv$t-q+cE2 z>)ufwcJv0t@)QXgF7z##?A!y%y19=}MSKS=K59p@C9BtUKzcxJhzTvW{`+b>tLk+p zJgV>5i;~K+#fDaVU}iPb9>A0z>8fGv45S2{qVWiFc5rinU_wWgGQg4rmYmdp^XGy5 zAnWoOSNy_6Q+~l1y%W6;H8jA=pbx27x7@v5i!+AHg{%o|N*@JkzAWErbZ{xQM; z|4V;uyZOD1b#r@Rx#pfK@pv!<8CC@PQB(btX&YUweT_lHSLsu`B)-czuJH#~pkOQV z7(W+ zjL(VjL;VMTN>&Tmg!QYBh^+gLIJArH$C!+~yRT~EiMQbgzt~$m(%&d7h!pnei6_es zm*VKex?8I0BZ^IXIdp5cg42hb4R%geER7O7yl+EYD4S4_Az{$?J$lH5iCIWp0nU_yo$}dW(pR+t3b~&iMy|<{DJYY7}q7JLb4$8^jfqO7L zc0zUreF_CF<1NG^`*3Fnj%zpAvG|K*CsF1#prS8 zF7@GYPszN9=>)61BXU`FUBRx;xt#+8QF=Om$|@wHc<7#qhnjQ4hY}ASV!_9!GtGk& z0s($U@-sPvtrA^eF!}(y0lciKJ@^S$6s?{v{a`9xqq#I^iQrIEJWoDrJ?wBI30Q35 zR2_#Bx$e^oCdeRWM6p1Z+JFQX`heOsyGL7}8e5H=#gG|f zs>vz%;ZK$Xc*=?ZPZ=0^Qu&Gp#|$6CW10}*)9=oj)<2>8b~d&CsT8rSE$wQ%?!H6! zlrSpc!h*Js^WRF5C91QdMS9+z)?aeyo)VTEO>|GfR@H@8R0o<-94-j+s3(ZsQ&OP5 zO4L;@1z=u>q$Ei}R9S+Vf`}vjDJkfkckrPcDipo)t~>I^w%w7QaCA=z_51U*v`W`H_of+=EnJRMV@S)o{w@l(j9VZSV^Y2JX#22n(Kby9?aF`atrw)ML1> zYiAHR5e3$>1KK>E9r9VD0s@y%@PVr*R2{(wwFP`~+0Q3sN7yTmTDZuX0uKK8+J|lK z7~+X_M(n^~_B6c8`BJ7kd*}nov!pPXkTjI0Mtw8{C$fH#pZIeuPSl92PWME0;$k
IqLUv)bHh}-^)?Im!p0!NBu5EyTRm)GC4z~+@LE-VPq?o4(kbC`IDCVnxSaW~~-8U9RoRKQXuyOWtrc%li< z=Hv94oDLKIIDAQ|Y*r{i$D`zspqXEz%_Ko?_-XS*X$AGbnCz2DkMWsRHOpwf8f|u9 z2cj9j(RFJAM(T{SL#$>!^(W{Q()B~+_?R3YljCDX!gSr%)t1$Zdo}+-ve_^|tmX&| zDWIXm8!o9`!m^2&$kDJ&|L8u0jt=e9F!$?n{K4dUUQP`I8>$=wIaYI*6KW@d@Dcc1 zh5*apzD(WWp)w*f7tC-)z#&FTD=UdIGePqnW=5kjA`=#s5!%TRt{}b4a8ycyB+Cp( zWh6pd1A`>XOh;Xf#7EOYW=5p0M%)7>vJV88HO*`Dj0T-=^aq2{p!83eWM3n5f0<++ z>l?zIPAkb~nCQ^3oU~-0@(5iaQ6^U#L;i#Moo3ui_jA*ar1e;JJcrMoIWM$-(hQJ= z<&Z;E9;x4kWPd}7u#&cOa0NCr?sBIIp($P z@dao*kyE*>EJ(#O`z%>sN9`8xds`;kLwVn)=}%HWyRy_gckvcY1k z)k;&TC_bH6n#qyVZz2AW(NzC>NF85NpTPA0gSEA$KgR2BIb0=e+u@8}A!Qd(+G zfO$?&?%|rs2tV;dbDvn>VFq8Mr|0$bKarl(8=7^t@*JOCOlN`=^!&-}pfxn*l#!K$ zX1z2}W*-JUA<_L9)LxtOOxL2BsHnnxX%O?JbbB--$#Rq*+aBq9Dhbi{S-LI*bmm2o%n3w9 zG)rhE+Enk3UuC&Z({p!c;t)P)TyN$LH64Ab-^+S9+Vq&hlJcWjA%+k1jXUb2QJ*DNc>YhlY-yn{!g;xjD6iwPy6@j?Hlv z6%-dOD46EV56&}(#=jI^bseeNNA&}do~E0Ss@M5`eIDa}Zm#~6nnQhVJ{Z+Mre7R= zox!l(Wu24mztH@vopR8is(b(_{>(?H%f>5S6@wcA}S#*TQ&1arai(Oq}y+@TuQTf zRWvnNO1tQ5iJHDX&)4!PH7pHVYWZ(<4^NVLdzJNk`(_uIAS!El^Y58Dgb%$A^!%z` z(^0B>U4>i-H0?<{-0Pe&c`XN>H+i5!&o9k=Uh7xqgkk1A0L5uSZC^Eg&9A1Ta`7Ef z9&PS4ebY|TOotB>d4_at@OmS@M5y1#(@2I!#>5w8&vZEH^qYyN^03St`!I1t?XBr} z3Td4ZCU|7sQmDUOM*o!8FY&m^N27^4x*7N|jxwZ#HNRS}?@L|xG!S*&qsFUt^ZDqF z2h?vwQb_ ze|q0jcU>>0=R0?t?1xsp=0oLy!mD1>SAR?E11T>k(d$%3hitcfX3eJ)sn0#M^;Cb_ zero=dvR^MJaX-;^T=lsyh+fCCOS`{btG{2G?tK2(^pDVT{!XaJBj!apIg>>3*EPkX;i0brUW=h z`%_@Kxhp!3=0o?MX}oxBmKc}o_*}UV`Pd!{G-Z_~UuUvoO3S0|2X$S{&+YD;Su|xT zX?(t!1(V5>`qzGwj+=NL21lUxeOc8-{RmqA!0S7xe>9!@N5t98DGR65iWA3KFw5(k zHMyAkO=f6Jq$vY4f6miyG=DA&7tQ-mOg`v=Aa#*U|B6Vf@y!jJ$lWS(m-!sd3;$@G zQ^}^}=ZjI}BLC6TEVGcIye4ek*CFefX+EbmXk3iDb{;86d6{^meu43?QPHHJSvWyl z#(&U!11~2@*n!gJX*zN**C2*v`hXIy<UgQOu|v|S(0!ZxpuF0T()#44Z|a=c)ZM0euVSu#j;`-U@C0bS zgf~>sxK?T|z2$|b=0Y_8BK$Lr6q1Ywe%vplWMo{<@nL@7^b0wC8P*f! zL69N2qq``iNA%oZH2EfSeER+uT62Jz)?_Pu_wPls=M+w!J;Na`np{Nds(gzk^9nGp z&w%JH;`%_G!GG{PTRok=f%=sLxzjv}NxbD6S&u)EKXw03z4R5C6(Z`+{Yc(=r2Q(9 z`rAqMr*!uVDZIIrXn5@p8h5HX>aP7LjYra@`D#j?Ynb-8RIk+jDfLTv8GWMtR=rZw zRoP8?sA&v`Wdjbqc8QyH^Zq6N!@PHi{s{0Of_~IKOT)(k{m9*Hi6Cn%b};pd zS`_VXYQJCeXY>?6*4LmO*3Rf(D-oyE?i*zI8&^8UeHH3fO?;-xRKS^EX&L>J$5kt;t+0_vWnWQ zH!?Por!2HSLzaKi^BR6y;w0WDXFRRozXkhx3)p#9!K^6-^T;k?@$~i~k2`$m?Sbl% zdFvXlW1K=Ebe_N+rS=QPK{3`v9WSUq?Z0V1NpGb}4X^9V68j_(ug1gsH2H7y@)x4Y z3B4;HZg-WnKC7G{=8v>o9%M}YD^;He=g#M^L`F6&tOcwEtOcwEtOcwEtOcwEtOZud z0+X(N>;v|gzWR>ldDje{|MQK-TUQ-tenG+BzNrgoL?OSEmOL_r|LTkkH~wkd&QI{? zFPOYw;e2xMcz+wyWp24s^vB%(x*3-=-z{=OOBxSnoa_%peq@^wX2K*dUDDt1neEJY zGJTrJ58wXRt=WI^43RHxShNMpPNB$OroU$%xp(G^y#4hfk7aeo6p?Sud}0Tdy+tBV z-p{uy%e{Mxyr{4JXqNM5iG1k&SAEQK59C7%-*|%Myg8!pF4^Y-mh&4#K5Wc`&#~MC z`Q$yGx}N3kCeeRA^OCPw_RJM|tIsc9m*vGu0eR|h(SZ+K-q#RpXIjw zMIIIW_-`!tHHvJO*Wp<-yURWdOmdP;Z!yP?64uiEWN9hQxblt{`LSG@Tc_IFznK9`mH9o^nm+H~;Q8T% zY<6;_%C!ELULqxLs1^&TY%T(FO7d^kF{jA%AU9P`&L8jaNY>L1j+FR#hevY!EGLI2 znF933FAI-TWS+lFl#lfMd^=gD9UlF%Ol+pg$^K<$N0Q#`@JN!)PLCwn?6XLbsU=C3 zlk>+rK2p*%J3W&9^G=UcIVHT=@zJlBh3@A6^8Oe889CH1_xqO}9!avypC;^8X|@dX z>t)ABvdkAvl5AGSC(ACqEB=GcJZ-;!Ga-!q9{u^1eIWe>pnV^_u|lh3Qu;KJoRS~2 zpgdJib1O;dnH?Xga`O40@U#IUMNd0GQsk8SC==O9dYAopzC8K-v78*AtjmpE7RaSy zI6WoO{%v~JN$0ZcDHpjvep$D>GTnbE(sxeEoXFwZ(H~CIo1K;^GM&(VS#~@o%e-K> zU#9*OZ7rSp&gs{3{1r#L^GD0dD86Ig+51ndFFxL_mz|0I@yX7^emP{~$G*bE4F>lU zHJ5Y7=_AK*{Qd%W{IYRt{uc{AWPR5jqJQS0hi+s!9qsMZXHPzi<>IBHKY8Tl>$2>P zxZ|Vtn;xw8=Z~|OY!7O`Xv;#9UY^?~?$4yBTpzvl)IyHGDJtKfLU??U%Vd zOHPmbTf9Hd?BC;8XPIA8dt%zCJ-@6mD@3A4xXZ&=L-P5i>Yb8*(x=o1uI|a{lT3N; z&mV#Llxyh-l#Wk=tT?rqm%ecE^Gx9r@bT^aP|2QIrQPEvZ@9wevF z*MIW);hngtdTs%~d}{+UK5E7IuRs61Q!Y6??~qFgZwlD&pX*oh^=}@aC*_aKNA@Va z?(#o!`QjM=^@o=oxcxG>7b)qP9o;RHUfrIpC9c{&;eJWruZt zd8qwJsXuZKvmAL3n?ICg;yYo~b$fDpdCT4Tmj$c+@sW8bzKgGVHG};-2fF>sj!xO9 z!%wc|*B_qyhvm-ntR{1%^!g<{zGLU3eLQqGcm%OG+-Vk!t2d#VYpM7V@{D6kv4Eo{!x4Y@T#$S=oxT=0j=vCgz zC9At~N0)vlm&|(s_^19yiI|Xgamf>0@+8Rfw|Vt*{xf=!lqbtE&7sqImVEB^=7Qz| z*5~=9JXy|U7M)(`vm7&B<#eaZ=WJE(g}ivv(NrsGKI#!Uze8A{U-%xn#}Km|6TOpu zmVEc|qLcQoG9Ipy{P20=Fhh-_<4k^U9b?~C%*Uu+602(4!omv%1*Zt$*>W>i@7hc88>Q>|aiyy9nLC?@Uc!?Um)2>gsr}k@K@? z-_dE4&V63s)cvwFUy(D!5!yXsb81+ z)(WuL*(33#-+N^q%W2QAIQ}zxXWzv7jQOitALg)kC*!KkO#X|`ywJ?oHoYeC-+xf> z0i%CX;tPcu>sgMywc_-(JZfK+nf!Zi^TI2b?O#iLn_peC56f*INPN$JxPhtPPOr#W z&RkYg1NVO>e;S|re7fa<(tq^quQ%f8@;;aN52(Myv{#=0hee4U7SEJUG%ckX9 z06|-uCV#AP4{Mf+iI(p|I04g<0ba*T|@l)d{gF6qs>JN z#!4S!tS010{&s|=(oaLC)O&vx#pIOc#j^1%TS>K%B4IVnjT>qZ+CB1~+ zEB=Rvk3WjNw+~ryeiHr{q}G>#>O+=O%+Wa&FH8S#yHg)6V!1a>;@>QHh-vS7)?RUX z-z}fS7k)+JbL-u5ma{J>=X8{>xW1@=&A4!tYhEQ6;CBxs%%eKo*^rU8OzEat<C>s({vCT|ITF6jbw0Ixntv@%mgDE>9sl85q_n4hFs^K0zxk{9 z9O*xvu=|{K*r9N1&2PZyTX)(tCHz44(eww(&+_qSo34AdKlOZReoijEr;HP9-bT{T zdH?zrmV34pS>qopefGyc^{?@(Y%)RmvV(@b!TvnkuRMNtdV|UC^1J>2SiP3#vVYI{ zjPu`}_xmroY~vFZn4s<}%a2D4zPm@;BxEuguWYTOi@z96iwt zczS27Jiec+eEUqhD8TlP?=9(%d|^l?%WWH{*5_5Vm)6HMI1>7)tl`)EL&V%LGxm`5 zGSAuVQubG|r^p{3J#940O?$1}9(sN>{_kray1bu4^3~Y=gzp8%hTf#duA^= zGLz-BMN+<3i*~qxarsv@ zJ&pggGxuoY_*$-)@*Y<6=0_~&M^+xchClV}f8EXgJO3u(@BDb~43>MkMb65hfie9m z9v6A^`g zJ|BHoi|+5d=}+Y8GZ*BJ^-U|9VJy~t+vx!gpZ%=#=X}0}^qq*}Io^WVWA~7J7;D! z@TXh(y}c#}9*L-V-Vw+1Uws}q|GxR=1w^#1Ox|Zp`!=UdnMu3pW_c$sAb+0d^vP4E znok^=2uP-1zfA8B&Z7_PB6dojUU)%!GD}B}q{K~l^TH(xU_^?KzpunUk;mqYn=mdf zcl@{sB2Vo4vYY?PyF$lzGPZMHUs^v0x*k-&&3p6z$niBkD&@^`yevA+uKuk1`c&Dx z1u8K+Oz+2BufR-TXM8L9)A6R~R*Apy&QX_f{7vhu{QA=Pht$m5mHo%pU9tZeXH0m< z=(p4Sqkr#D9lvROY7dpoJ}0y3OJ1wh#6? z@5Vb!`yw3bzM9`#=AqeDL4I(m{06+@m}5UalGE$<^J-}F^8J^8v97}C)EeX zu)ghr)ayad?>Q%~-^KduYecW}!_g+0AKoOe)4HsWekJ-duGz=j|N1Ug|7JSG$)s5; zJ~3f>Ju>YCrq_*_&s-+ts(RX(N&EFw&--|JA0NM6g!fhkIT8BNerlEyo1Xb|s5MnS zd5J#hS@!A25mYV>_T-(b@}rOC(i^IMwEH?(&1GVH)04G?{kSs`rjJ+Y`KYg^4cg+> zL{LgEzNS6$Y7Pp|Zx{+CPGHp%{;pD3A16DI6X{cW_2u-1Q$4||*8o*ZYD@&kE`=A_ zt=9-uAAtw%3WWo8X3m1+;POOjLd*1>XFj<#&GSv4O<$j2Jza3Lx|6mga&@HjkSy^# z0mUVuFH4mzIr8_0h`|F#gx!}L;=hCnz;bj)i)lN?NZC83%U6C1xjfEttj;3StW z^OY>G3z{^jeDq{LXS_LeCPXP!{9r9UCPOY9RdRTV-(=1BH*!+>Ici$nTjPt!zT$*T z5%Cw@MqPO9#vHKsc)5QZ7`vNVX&MidOMAP{KEvN;IeV(K*D7}wta!dMf6Tu(VgJso z73&{Za--ZIFP8XYHyu*I-eZ@DtoIXb&$*k&`o>!%e;rHKS;}(HUqoJhcjbL7r$4Rt zzts6}_k8%zFZb^e=X|-#qq6&cspVCDzr6DDj9K)b>o^_fIVpeXE9)J>Vk_i<%B$(i zcjRVGUQj6g=jI#FyPm^0y}WXJYWTt8xB3;Izkd6rKJWhS`TuG4_ib|ZHGF;xm&*Co z=SO)Ti(Iz)2Y+RKN4i{(d_S!(p|8YL$Om@HX6*L{>)SUJeP_odW<2cQD8)a$CQrVo z=cDILbia+zEx=ST+AmKpE|E>sNgJuDbu!^W9e3vNq?haP;@fUw?iizW($@*79q4wSOP*hq>G8qzzwr zdIQC`Np9sM9KLwO4-0?)HUBZ^qjjW&r}{%H^0c?Y?P02YR30cl)IQPdhOR#P{^2!# zwGVyYs)l-Z^3fG4=Vwdb+mXxLIqQd&_lbuh&vN+i#DT)ExIXot-ye2;_n&_WujQL? z(b47seajTdk8|2*r*ru*)_dw$VoH*5t^!D(Ouo}-C9ICA9@4xB#xDg1i z@^+BlIeVtV$Ix@-P<HtMpMBwq^@S}X-(h{m z%}8(lf@#wVrpv>0a;NeI>v#zV&6Vp)r}f?2g<&IQ4Q&Dh z{z$*9ydkl|`Sb%XZsG9JZA5>3`=w{I?93H;{;OZTV&rm>|8!~LG?oi1MgDNuOfz#+P3W=nQDKelqlS%?48B!piXjIU6MU9nMz)?}6f<|nypd$)KuV};; z3o`a7qQM#q`mM6pX`E!d_xFAOe9t}41C#f>d#zp0KKtyl_S*5MJWcpxYkMi*!(*mD zI|+IJCmbHyt8?-az#>=qC;H{CbV|SWIr9f?y08$#$Nb26Z06?eh+EV6`5f){()yVH zWuBjWZqq$9{%Y-F{QcO!XnYnmf#08CM;3kGyeBcny)=oUZ~aM-*L=pDzDC4ozo}b zCH@oN_^gK&wm!*Pf54Yc(MJ{|4#m*B~g_B)=p>nYeE;@jp>W|(wXOTYK#uq z@`ATt#qi-M&VTvP-)}`6cK~DGtel#O;9O6f;t__O8FMfYT!L{f4==$*40T**!~AvE zv|lTi()-qQILAlxZ9HFiB7SJz9dySdDC+*1+b6LXZ1{wqchgU!>HF__M%wcNoI)%r zqgGPWlD{n``L2!34~u!WoAf=;Shr{M@_HA{rzYg$0W|75^qPIhzO4BT4*$a9Tb@A5 z)6RJDM{m?4?ojJJlxWW2h=@xctV1*;)Ar3b>t3ybLiYy@Wv8I%aX{=g!@*brcB z){o&01-iY1o}SYDYM-1=i}6qMdckK(!gR_m;G|?vc5))T6jaBU&(6(F5TdL`Q-&gaLSQ{hc5Aa9&s>VQC(Ed3VrBsH`$X5 zPdo=>gy%u!Z>)FZq-N*p%OAi)b`1!a9=rqx%+F75=s1mQ6kv-2!HNcXF$QG~s(y$% z;5mIW(voNjxckYc@4$4&mU8G@2#?X}5HO`zzoFtcVH#eWFvw%i4%JDiV+_^Ff-UP!TptY{v7tb(k17CTLxGB4rB=lc@yQM1 zA-I7#J}ZX!)D1m83pNxmZy5ai_T)(Vv^O3k&j(Ii_N65!`c64z5|tm=1NpKOlG4aL z2+9MoSO;Nx5ra7q)Kd?1kB_;aci$aqo(2v6PVoySL4t#!bLjunY>C?m$XH9yEFC7CnkdrwG)1RFpatoG5qLbW#w+&qbl%fclo3 zotBu(TT~!_*~!V7x!DPsG)n^Eb5paEVZJ6OA%!xu@wPk9$MnXIRq0L1%FazonJEgX zJn_(o?1b!@R9>8aZXKz-sXU-LAcIgTAE=@90QM@+oS8YkL?{GRA@Tf${1Q`rr*kPF zSGn1kEO#PAvGZ!`C4das<6v4v+mYeT`4|w;ppD*8?t}%xOv- z^iNHm25k$pD(R>I`b(KfIzo*0pV+@*3A_C#^Uy)p(?J{T6-pK7*LmGsqCnD0RPE33+3(;j$pV0{WJjb!fxt^q1k z6!`oqDr)D8{WPX$QT}4=GSj&hydGOsVPI?z4GUUWAIqn>z)$)-ND|ri&=?5rLLq|n z5g|@3@^kP=H)v7k70+J`IMeFT4%5Rvznh##WY_T)yCuL z@h|7?k9;VK`Bv?Inkq>h$ok8d$I*O?M}40z{-ka)hHtxs`Jaz=-HNz#1>@E)r(w0x z8eV67!Yk94BkoZ9Gbg ze5l<{_B{XDd>TGHd_XeaxIS??<==ZKKi}_WXHfm>9?IAr9%lk_XmrgDy3F^9zJkd| zJc;S_$FltMf8T!v;uhT=z#2cye^k^!e+=smUgyoaoW_4qYgv9?*Xxht{opvp3$8!; z9mFoRUhYq=`VMhe_g4ZRCS&;(o)`8Nr|Wm7o!D7R@*}x^-n+2xTErd7URp-hvH7(% zl`zNhLV6Uff4SCkeXTYx_JQ1))SQkhtC)gXuzu837E~6|vqC)f*nxihbuZ)e+t<&i zKXGmXd~tK=i?DIf)0G&$bziQ(dxg){2hyii;lan#9M z@i%@LzkeyXGYAK(coQz@Z{P`4U{cGN&jpj#6nXe~^U^&9u*cW<;Kf6ch*JI;z@9sQ z4mu2~tejT{I-x#Rk_i}nefMrpSFM`91?A(CIel!;OGn7yZS9-vUk}0Gz}d_nKCu|P z1zPD~e!q7&1%E>vogwn*rqnocY@zMouxroXLo>e?MY1?SRkcQhV7@A^K7ha&UrA8CXhq{KX48iWTH&i=nPx^x4CY+BdurgSr}6 zznwqm)5Z59A9$4crGpm!fml=aSoZMm?HckK(ylObuAbK5oWwvoU<pt(C>agzU?N~2mRw>X#Jpjh<7pn(qAt` zhi_&~4&7E}Z<~nW;u={#_JuR3euj$}L;5FRY_eVvfK!X%l_;#DuMFg)GGK~6!8-CMuWk4n8{TQd-`eml8~)CQyKH#34gX-nKicrmHvEeXciZsq zHvEST|7pW}Y*<0vKb(3^^!G*DE2;m|J_z1V34F2UPkQrR=WzdD_$b8-?r*~f*zf=w z9%#dZZ1_MMKFEd#E1a}+;?MYJe5B`gF&gJI+`|5YbiCGzW19shP>N!1Vt+MT7VkbE zZ*+Xl@00jDbSqx`8@hVTPa^3H+tO>~hk5NK$v@+0=>KwgB$0e{4bQ)f(HLt1E3VV| zWC|Z>l>9JGRsIxZzpJM9yN=POQTVt@?*9n(%whaz{W6;0>G-!iKMo&Oy!bB+=;cS# z6I!G4XE;Wq;jdPzmlxw!9iL6{m-bkG(}{O&=JF7Kr0y_352+u<^XKp$6@HAyGt+fD zq`Vl{hpjl~Ex{QSpSwWHgK?nLinTJqnH0WN&p+c-b$5uvqe!OSnUSo{Ssy{3%|?)cw}N`txNRrTjnX{@U6lz2}mCt%LDv^2l<1?1$ELgtJg7Fuxo5pmF!{0zAk5|4NasfS%kn$%h;UnqmiJ$uHnLncbPF4Rz zpTsY?C;5GUpLGbzN9Az(B83-T^#3wwB;_YK9b^g@*HsAhSXMJWTt z###S1RGC9H?Vl`{{O?Z;n~a_|8v{_G9?=FS-4b z^606)*?Hr6!63GxL?2H}dN%f5g`XYGwTJaD`sxGfs(CNAraw}AqR$?`VByCN|6>fs zSGSP$|GoWE_!7c+bP3~}XOH>@vHzmp<43)CiGHac-{1EqHGpj@KZ9>Low{nxm-Mbr z(kJ>v|D1^jyovF|HT*OA7bh%Vj^XRB=J2bBb+-}zip%%U<5GtsZd>us^htUmmA|C- zkVhtML;ZoT|5<&J`sTf{_w+=Hzo+uMvHk5`n4XwxS-;e;Xq$g2kx#zhIr?C?FR;#M z^%Vb<+osU_(sILpmVUdwNLbSM{ndYS*Zd}quX^~LTQPriLB`kLbt%2ioyy;qJU@{a z{7>Wir{Vvv`t0eG`qZ)h_UABv-4FC$zIJ(gdPHAO`LWB}!^``fQn8KtFYR|ar{~zg zs~^MkdTjpD{;B?+(r3?4Bz+Qo^c5wvKPBcKPVc4nJkp5i3n~2H#wYqkK2mz5{H9L3 z^#F|D+sx@1*mpl3dfx9`o;~RoeT}QH+JpK$s(x(!y>cyL*Ile{Qu}fm0JJIGlRkTX zFdSYzg%|$ke&0}sy{p`seo3Fm+x7p`^6E)m;V8V_{|*tth>G~LmXCE!i)Ur zS6o2tfADPn{%-zo%pwdQc#Y-3{)Z0w@PU~I-nYyDe~q*6|Bj~iy58+Q|B|1c(j(>5 z6CX+5&Kvsd_7joDgU;bGU3l5+Ph-}z>+rtk?f)+S;*YW8BbJ|c_iME7tF7nyJn^9V zVW>Yjy}EBJ-j6 zIJ^m$>|d&2sN-UVwdjNC{m|TCD>FpXp5AZh8l>t^VSU5a41XJOV#zKfCNyGm z7*9LPOX+CX#QB@>spn9Ve~Izm3vcHB_sfiLZ#tRAYk@Y#p{FL$dT!@mjKBC{{SuOY zp64IFDQvtDvG*0mSKl{00df4Bj6eJG2kJk!D}R zNBSBDGcLdAO8QUTQ6sRWZW$`BG%OT4#$igyBJ~cD(3H7S5<)6 z{cpxcoi%9$;*K{MPc43!s$%<_jI)lPM(tlz3_tH-D+W`0)Y!)O$)&tMwq+_~SJx(* zI&Mm3yz!fpGf{ukA^f}^{r+LfU+Y}vPi~z@_0Ofo$Ke0643@6xn}l+||FoUPU!})! z_&{MPv`FA0v$C+bx*GTM!)dW#tB7Io`YUsQ7k|6e{ffhsV~qBoXhE8l0~>T;J=4B_F52UI9p&q~ zIDFo!?mH2O)PCj%e)yZ(W9>KQCk(hbhl)pVqU`E)K=!J7o+<)*r1fp zXFP&;(_%1>ttg~gX{;xN)B@P8k1lRP`Iz@v{_o2+(ED8a0pkrPWl;T%{*ZCtuQBl$ zzI7y*Pt^~9UX9rQ5%WhOfa^8edfVGJ{DHz77T&ZT!#8}z^6yQZO!2p?{dTA$7jgkD1pz zi+t%Ye*XquxP$uRK^NoOuIt-{y#FD_qF?%tooB71{&L_1=4TA}{5}j{ca}B0w7(*M z5(a`x)<2rn`pT%n`9){A;DtNGH46Dr;NGyZYBBxI;d#EiQJ+uE!P{C_A?HudM{wOG z^Zm430roDkUNf7*#|@GBW~%O5qw=>uMk^$~RF`Mmt^EIw(Ta$#*XM7!DQNnP>%$nW zgm_oJq=#|4Ixk|3MxQ6m{h*|;l)`JJGXKl3YwSCskFo1*#=b;$$iYJJJxeT`KhIYk z$X~=?G=&#eaIzH-Hqc67j7HTN&M)Njp}jLWd|_vI5JtzkJq3F5EGq!_ouon8|CSUL zv%N2b7oH>(4=yXjpB4GTnp0E5FCf~Nkw+0-Kk@SmOX0jZil05^`c!(+Ke6l`#9K;# zRq;Y_gGd;RwZH?74;-ZwL;I}w>gpQmKI+(rUm14m`fH&_kuSvq;SJkvj<42NU0R7p zrP2lV=im|1>@Tyd+Lu3P4xABAJ}}8XG+wOxFg?Iy+Q9CN^#O)09r!I#*y6yD!jlt4 z;jJDHNk7A`)cdiBQe7JneZ8~Sq4pkCJq;cZy_VM+ROa6_k_2CPev zV7Mnhr{J-`DKJm;{LO9b!%bpPiuKwke_Bb zj}Q-`1mjOVeYpQJ3u9DqR8)e0o?^pasLz*?m6WX0x<4Z+U+5Us!0V?wEQ9@KssLFb zycb{_s~@)v>B*vlR-^<7o8njgs^mCD&FWoN)0BH*G%;886a7~i3h-$g)|i<8sp-=b zaR)c22l8t^o>7yhDft2WJ@Bt<*k4yeOIli0Spi)>YWS5uEWMbZ{1cLrvPC__H$8c# zjxhe*vnnwV8-0Ct@du7+Jhi69!psx_>l94{)k5};v9;c@V{goLB5dIj&+smh?_%GJ= z!Fa+{UZU@Kl>lfz!DTZz%Lb>kC?fngl_0x*`2JZ0Bs>j5KpwuQ`9($GVob#^{1_X) zNa4cG*&6=Sw(vg*&%Gwphv_%;?VX;2`SWOV7sn{_lP7Zof{#)d*5l^SD>Urmg+EiJ zXK(*;9A2J?9$wd1Qf<~K{1jXK$EXL0^#{zC^%O{WacE)i9HTwI5`Ns2<0!=#eor~^D~u}@x0HQ&AdH6^v_&UqCZYupUNKAZ^!37PA?y5VZeX5XprYqv0AD0bJ6^W! zO|YLNhaC+vt=ZfiA`cGYOY;?t*y6t(aGm)ElvgD<=!4c5Iu;-VJPfu9_5Rl|tuLvH z+pXps({koiqRGsvbT7 z4uGY(*2F(pNb&vs7gEz69k0SGe~SgsF5nRG(^*?+exp_A%c{x$A|?th?C-NbMjof` zI6UJPydSOnnIoTHU0BAWP)(b@Uow3vyf5(l815f4^QXe-ef-3t{*I6&~)rb?|RAKh&x3N1?7^F>br5 zg<>22-ILFtXyXh?kK$!N6P8o{e7!?tsNXpD6y*?~@w~Xo==#+ll}AS|eMk#WZ+-=M3zZ6{ zhgTtxhu1;pp*CQ3G+}xhbWBNwty=~2`4zBw<23w*(yTkAx2&382VGwLiHeG{YCa)A z(gzr;yB@yg-IxzSjppg#`c_s=ubR?V-o2)sIf z%NxiCd>p`3}YZ@!8sGh}}0k>+c#Cw;B1yTa5IXYlL0@ zyK`>{VEE=nBfPnW)NMMS<^mg>`=Ttek>1j4Qv1M zfLl>tdk_9%|NV8vqsRxIRP8^=o1eH{|C&=D`WwT$RvGCt*HC+SOpm#S_IdnY^zG<= zp5wcza(gD~i@DR#NA0nyaV2->pN)J-@q6o6?Y9d5?y9r)#qiO0IhXIaKy*6tt%^T( z-nglV{dYTux5sD41CKmE7v4Tlx z?5xio{7d#2|K`f!|1lGxO5vF=@kAY;M5trH>o>lxrTm zt^M(*kJcAjpJ4vF;dL~!jA~Wk=_p}Hgc4e^V$wG#SGPmzyKvHfqx7gv*m`>OEzdr< zV1qSzP(}%uuYe80hC^l3(Zv{z=JS%fBmFkH|AW~SB9TW?a+${WjJ@I<#K0^e+rLEt z$*V2lcu#m;Kb!}(pcdw1R0o%4U3@TLDk`I47h_|{##qlj__L7|u*Q-pU6O3BOzUSD}4_=DAcLc8wNq#ZUczqt6d=mbaZsYju z_6hfYaLI$n2j6F2)>B&4dW~Hl&Nt7&;f8vCbY7t}D5dU(S>CdaS5Vd}h&C4baOh4j(K41V8J z>wUEc^t%ny-87!-i}0V>)*rvJ;qPtuR~x2}KIoP4>=ZR$A^3PTUY}#@uk-vrIz;0h z{1}b*KX~tx^ScW$xmr+PkJ9%K!&G${)Gr-ZR?OA3A5uH$d#gRI+9!jD{l(axNcb{X z_N~)i$lG`X>W{gF>)Z6SALx4%tYJL*g>#l6U)qmxM$TKC5I23s>toL!dv*q5_kqkW zyZ5G%h+T&bbKHKa$e(DTkN+8m>;pM)=}7 z@LR84vUxqV@3G3BUfK7{a9n%T^;H?_YdW6G|6kuHQ-95?aeceyu~Dxe-`q#qD_FoS z3@jFVuCgi1?nK`Im$WCvvUFTw%5dE4(I_`lrEtSpO^69r_~bYw+0fgD&^5 zKB&1UJjTp7!G=!)EcQh6i|Rm+fy=3%_4A_-k3jvgr*eFs{dvxLh?~+mzRD>FB_VE~ z&U{hfotGl6OJ^MW>mM}U=)Qo%f3*7D8OX=0{qBEvzjGbprhMj?z4O{Th{G>%`Cgx} zlj5)2!uZ9C$y<=`x{UQtf1#Y}XX&fVzxV4(`tWxg!Fc;wXHfsU`*+4$w{NBXKwMv5 zPyYGFg-@cs80F9C_0!&?=a)K|`QjJ$(D7g4bpM<2F)x2X{h_X{j6dEr@dFIs`3B?Bne`_i z?oj?VL!*ZAM1}Had3Rs`aOCTbK}R3dACb0{$&r+oywl+&-*U819ALT4*&2qFMf|W zPT4p8{NS6^Kdjrvd{*)2&m&*o#?Nn`{ZIQDaou2kAHJ?XzY%eZvVY2*ci9lco+Fqa z@c8yC5WCJ~eC0=v(0q$Of${ETk5m2YOk*6%_S}o%+p`$g>|5B0IIPaE*Wwjqh&=2{W z418-C=Fj^&V`V>us_3fRaXfq_z+OxF_f~vfZi)|y`GUkSJ@3YEnD6KPr~~;Jb>7Fre;@e};x6T1{F7bDe;{rf$>C=&om!4K<|xLa zzIZDKanwM5KVQ0kL=9r?K*o*@)|Y;`Hb3 z8nO{_=|a}`%iQy>N8Gp%<5{z3?L-{z$9U9>Rbym; z;}NoI5Pw_Z(E8XDH=c(2Qfpa1$s6vSK_2|~Vs}wF5GMb+R5$^;V|?sl0ZK?gp)|X z-wpaJGl@w2y1Xx`Dt}I8MaulelqB@;2_C=n_DRZ1xv$6c@aR-2knyR^2vGT%Zc_Xv z7iToS&CUbw!)koY<9Xd-FT@W6=yTI@(!j+Tn>3or<8Hk%Ha#xSD8R*g*9x=M=q>qi12TYELuU)(a z^#|PY>h8T@egOUd!5COgqL}_94d9;*{7rx8b~5Nsq4t&e)ad zd-U&ySeBn5{y9+j7eb{dp>_@42RQzhT#a#jKJXt}X!wi+dG;4a-r_L*kR0&FPl4e- z@^5B}P_RTu{?pKRDkqP^n^%yLH!lz?EaDVCU^19MzSf4#4)2gRJG4V=c7TWTRp5?E zswepW&CE&DZ=yeA@_(#*5CmB$UfsM7c(_wo8ITDBcz+gF8Sbxv*G0KJ6_ghUUdQ-T z)mkD3umuPC0+{bMy>B9)%SkrYr&uH8F9*E+!U8l!hvfwr9PFtZgmd8qOEmGBS&87p zIG5fh3=gh{lRfDPiEx9$Pfg3@(ENNe5~igoae5wv$;OBIyi6$Z6!2FJX#jaVVGVsG z(|29r8QE!Yj2z|{csw2>2iz)S9E7v8Ef^h4qAuadIk|EWh~d+6=p~{%h`|AvMV|Z- zqLq}=pOT(1EeBk{V-?2mIn&cTGbnW&e|mC?UZ10$WIw=u^-J+(<|b!nCeXNr6=+zQR384|B?WmHy@Izt{u`r2-n@Xx zyrF@y?w%Fur}$s2r17VL$xkz-*L=hr@I^lGq=<3hh3SJ76k(6tf?=A@f^nH%g;!^A z(+!ko%nA(53J^nT$%;VqAy(=sep;V3=`Vok%3AQbixHqa@uu`p`-;loVq;rVc|dq{ zCkSq-^XEVTtHQ^krVGu5@C&cw%K18#eb!8@#$lC(-erjy*qe3^1QhN096Bp+87|K;$43+B-O_ytsIt@|RhH2g*YtvCg8!BJp721~wlY z9@57#P_Y6J0$>YQMxzE!uj0|O1MpOvbdx-o&odua2z=#2?r2 zlvXHE0@DZK7nbPmK^5j1CrUr?)sR50EgT+;8>$#38RZen8&C1q8s{}4ErCD)~9zd;jC2;{18!KE6uTU)b=1F5JZfE!kJs&ez+6 zeL$!5XD|r|ZCl{M-}WE5Kfn3$QkqX|JAlVKnBGMu2dZ{?OJ@i4JapOWOHg0yfh-T- zo#|+Qiudrc%L|tIN(wI@QwX2@cKu3}Yl$}LgCo1JZN}@rm#?!JebIs=SOEPq@Fg z{z9;~tlEp0{I&NxWGd?G9LoCC`2(;Z!~KgYvQ~zJl+Pxj{O?PUq>=K&Rx-${M^ui@Wu%AX8!J_y6#MVNQ!N(ds~I919I{qGmn z(I6M@^Y{v0W()+E#4qWG?=O5z3OSw(|ilKbNbW*1HA*|UBk`p?@Ld4!w-x+n=@or*`oDfJ%KM+> z^fau!uL-gDsehKf88DR2$VmfB556RQ_VSnb9*8=$2t&F)V*N|+yMpY01KSy&RbQ|j z`RMRJi(lds{Wp(3fd1_M;=hyss{gkaVEnPlpV7v-<6lPH`L$JFPwnZ6FF$=5hL782 z4R0@xp5#BAltJ>*s(&l_`=|11{7L88pbfuWzV7UsLYThh-<;DoE9LD1mRU z9;d!y+a{jxx9bz!Q+}==Je$@lqkndeuP1q_-@@;UiGoY;ehi^MlBn|PweV723AKBu z{nB3TJ^d11^hY(>Rz_=-Nk@AJ(oUTng6HkbK)p3bp+j+OT|HQ#{yBXRpACJHXvFPR2M zyyPkjZ6^RT*WA~hq0=YlKqjnk z_5`{_#iEb>Sr`U+d!0w;vmCDg@hJ@Z_-gVoemwrHO4I{}{Sl`5u#%cU4#w3yo6BGP z7c}es3uw3i8;8aJ02o=p)soNeCzKD&ZR7F0YCQ;Mk7)lsg~Ir0|2__@D(B#NF)$wS z!TI4eRdDPxgkk$HvHn5~d@<}u(B%QwR+!F@$g}RJhI7YiU=N#qz7CvsYu><%dwtCt za+JM*Y`5KOzbcF`tH2_t3ipfRDcCUIhBHC>iU;o3Gw&!Y$J~^;^d$~RKkV1n&Dr$* zJu!Z6Pj~+I`PG!QM#fd&w$l1<{7S|zpT496`Ls zP*@H|pR_oJ?&pV?Qan%0&{y@cs%2-UYc)x0K>~Q?;I*R$@^VY*x z9@{4p8n{ zc(g|>)aZXx0J2gvVTrE+EL5W*-s5x6p{Bj*Q`${i#=oPAIvM;Je@bEc>Z5;LY8lPnSU8Q%tiG0ITj2D&|bF+9~>?P~( zV_y8##5~A&>YDRuJmPIp^0ovlv`)`xAG9`8+Z=A?@Unjh_|f@%^(B{Kc+W>%UM3z+j$91k3*i7&SaN~WA+cZ$ z9_&-?7-k_&e2t9<|L<1$s_Fu*s1PQYYLqi5&{t%ICVgn%YSv#|hh8v@_+ZV*k{XY54`Y8JP+`a~sv6XU@-2V!`|m56y9sf$ z@~?&Ap~cnp5r!62Zj3*E2K9$EWp6xi=Q+otyr-`bUzI7om_0Dj3|EvoFBJ5tCX5q& z%Jjd^M7~S;`viLcX)!2EyAS;7a^$;TROtoYtl;9Mc_$zrA0_dt21^yl1Dnsd0{Mpi z%&)s<;SR*^WX3Pv=<1KSUD+E${1ycT|5`2r!9Wnmal+Z_)^y6n7cfr<_Oa#1i!ySq6qjj9a z<Sev)E|u3cs^jx&AtK1M<2j=UCuhH-=(8C{2$9-qV+D1vhQ47z5Hwp?;XV9 zk8S^s><^oUFmCymo6;LTl<^%8kNFbA`$x0B&)gHKzP25~{C#^msekKIc(6z#G#iMFS&a9 zkBCb*Gk$#5Ge;tB-NLxwoOsHAcqgZK);?E|e6yNwcz-fP1Xth(=70Qn7RA@}I?EqB zd&z3#Bu(?VtncC>*#sc9m@C_?Wk9g4-92|+*|LCMjWO3gF}WK=|`NZ`kOC*f7mR< z?xQ(;PD=W0#NjcFf19)CbHp9WzVo!y6`K)9k7s`H^rNVL#EfJ7{f<8_MZQz*cUib) zE`{$>{sVLFsr~}_xC=S_PorP?8F7cg)osHP5XUZMzPaMpI}x`lyz$1zC_kY~nZK!f zSy$OjHgX|9h()c`AWtaGk>JDMNb3c zAx}=F`G?ehF>bkV^1T?o>1xL3?QEv?zxZnzAN|5M*X$fe#VNPvGxEK|e2im0|tjH4cAOsGZv9u-Y$hNZSSXA>TBS!(ZO- zBI-}ow{!TXcOJF~`B?Ff8nnbmd$)8PhuEXOch^q3mgdi+_i*@kC$9Jo`RKzK zKl;$e^nSJ~od0ym66F0uncoz13e`97FvbpFDLs_=x)(BbAzwd<@qpKcPMe zVcfm$uB{k8+Rb?S-**%ub{)vygSY!!cR%9hB<2f;Zu%B+>NLiuoiUI4AAy57{IdOS zxfc2O>C9)(9QFj_hIGci-N5HFbYw8z{q_!8k7z!OOaI5vA)sqLq}n_sOj9^9(>ktsxR$|zhvr8YR|jDAr6lJf`cE2 zULmyKr7ZvIqdyEqTw2C>OJy|07p?s19`n;`?%%2X*Ei1IkL3OHIJ_^f0`~qE`Lc_v zYs-tlFX~Aer9Ci5rSImecB1}}itmDB4oyMaGGEF2%4_GF{PRNpvUYxvdH)Ic@3mmy zP5V`zJmwPm-f9&leWv{@wH5O!Di>Ag8&q($(j~?;kPdji>*}Dq7f!%bLI0*=u^txj z(AD?si@!~Gu>KRXf2I62u4YWmK*Sgr!jUma1-XhuF|DX9AG~i?*OXB$gL;kD8m0{~ z;3^I+2*K+xOoTyr=>MR9pz1Q!;i3IF;Bu{|jE4v?-v$L@+)(z=K8lRw(Xx_F*6=2r z-wbx_CVN=0P0B-iOm&OTQ`LQZVtJsYo3eI8d03!K^x^&)u;TY=(U+#aiE%Z(#r5f| z*(bUXht&Bdr;T`W0pd=zpXS1s(&&9{e22piJ$(n&hw!_Mzq)4&^?w@PW8Ajy@AN(I z=wSTguy5U{ukJ&}x20!1gt$$uXT3Li+r5b6mA=XS7IY!*Q2TW}uNKn$KI-R~J%|n>~C2I5_3?KC?wF(A>7`4SUQoOUwsVY+wMN$a^yX# zy;=FyIXQ@1a=83fdk*ptU(fie-^SdAxcO+7-|+b@F2unxjIY1CjLI+d7{*Iqe~J1Z z!R7q^?fxP}?Pt@m%rAN@gTBx1SjN|d&+b5doeHnHrhYl%#<9%by5^@x5yz|jO1US` zPDb2tJoBxG<(DFkQ~Q@r8$E;C({^z177h0&R=rL6am6wI*ROBNX6Zm;u^74kO5xeV|FIn;x^$%Or_s4bD5}Hr-rgM7UetF;{7~Ye~_`1;t4M5zj z@Un_yZbe-8D(m0z;)~Q@31)Hl>3KhnMZWo7j&IUcyx%d^!~EK;5ibxQz!aYHlXFJkYBM;thX<3Huh zom3xUA7uW5wO>z0zFpz>2By~|u3N|a^)>Zw#DRwxhYH5h{6W`QtZ()!lfOW|w1xSn zzj*0P#I3OH4(r$Bqj%qhIOiVE)yD@x+Ie|8?*5m1|L7=gpk|rMHiw_Oey^U%&L>Mrx1zE`GjG z#1+tdWfZvW$MSgSl~Sr-Eef|?9VkJ4q0_m%Zt`|ooYYdqW4dq zhT-GY{=KW#q*8lP`V)umyJF7}o>!alA74=3G7#4lk4r4sG>cdY_-hTvRZERyZ;*k12-tyfaS0Zj2#eB}r zenG_XYCNp%*xrJ;eJt}A9`qNDM?21BJkC9bzW1?H7+38coQmNaM>Br+_;l*eyWEU# z`Rp{Tc3L2T@l!K@rSDbDR2BZEtEheJRP%eZe-YM)>7@iYv=;^Advw==YBZR>Hd*7t z{4$x}>&q(;eo-kH;1*M0_zzs;fib!?5Bc)6m|kca+bWqCPFVXF)%Z#L@GAMh`NyX|1R zjhfZe%(nh0Qc_d3SU2`ZY_k1FUiWw7$;-wMwT@w1T~02Rx3L2qySOmFSx|<)2&KO( z{%~?rv$JLxw)0p?@n2v*IDagKO(ts1y`~h_uT3t;b;mmp7B6xhU1{>i1N+;m%D`0* z(-1$5FD6WyL?02j2lmAI;J9agvFc#LXr`tNTtchhn!esmtv2YdtpXGB8r`9?o?rCm z18)w@kD~W8)A~AWPb@0aZ@_s1W~im-`m&~;os^a>>67x{6G)8m%$b>SZgMv4k0JX` z=?()9n7rF-+5#K)*=~Tb0+^HIN()~&-48zYqeo0piFoRfng2&W{ZrSs#} zU?Bh;YD0zL{pY6O@`E5Fyfly;pCI5>_&Pm)){kk& zOTr7Eosfz4MN9&p0h@jDvW+`by}{avgyBENMtqEo^*sqM`X#&-LwI$Acw=~q`q92h zf1eblJ_DvfVg3CRUdm6fq*$<|Sg@p6@Tn(rf&jzoth>YG{MH&bn73g_zeo^YBuL83 zhGEN}WPrj$`N|E(u-#b&U<|2MHza(W1w-l;ww`u@^#%Ono9xZN-U@ApO!jEBd)kC) zceM#yf@@amBk(6{@%9e+wcQ~5Hp84sBWyZwf-q!XzAtkAg4}@lA+%u1G%$H5H{L(; zhmf3}oX9OE*~iUF&W2sRxmnO8=vY-?_`Vdup3LfbI!;N-p+<^6wc zud-bp@yY4%Wj2LROqb8kUg7tahxP!c$W(@{2-BOHl7wxN(hqidKJ*D~#Am%@Jv{-& zSxKDE=w$wlgn7TDSpQ-CXhEoN_XG?nG?iCUa$>qKH#x(TF8PNCkdcs>4co?(VCD$s z*GzZ<%){bBYneLzg8l8nQ4zXJ9X<_5?+$3VTM8{ECBK5p^XJl;KsttMjXh8u=fn2V z;)R;pUMt0m80=Ye2>nm%9jo_z@NZ7xb$0`Lc)26t1#|fs293(TQa5l!4CXetofVEG zs)O<&1EnfB1V>@q;LGRw^>k z4-O!u^+SDgCO{uW_gG+H4ukfWRmEgVqU0ewJTS4!L>|9j=$jF*fI84b-dDk7)e5}J zokHu8QOZ7og#P#6|4QJ0CGfuz_+JV9uLS;A0{<(4{~weYU9QlCo<<5LKQOU0=bCmBEeyf%D>GNj^ z=O)8UOmbpcW{Sz5yCgC?N$KBXl^5PE{J6P}@w@)5@_&sp9~AkG&U~xzBj!2kcmJmJ zXE^g(vP%DYXFg8&?aq9v@Pp<%#_tz?vNP`*qv9`j=9@)+l{4QV{J3(*_+2SV|3+s% zUie+ke5vpwDjfB<2*1>s4-3ED%3JFf_{f5RRIU%VP)W_<->%=)^BYv@7=O3uFL&l+ zr>XpJb>;)Y&ki{1Zxw!{mA9rpJ<*o|6TJ!3$d{Qp2ldBD{a)#)zg_h2vg+4$q^k6f zSl}q%HdN_fYUOR|1J8)LaN?uxjz(7>8mIJcx5`U^ZqYxe$}#@f7#06yEAJHlxf#i1 zQzE+Yw{)b6zuYP>VcepBl{4QZ>EG(iN1dqj?{VhaMgKL`j`{P5{D>MyK2Dwg>>hEe zBVRA_8P4);^8PP%=Cxs}e78IEp@UTZ2Gv^Px0b&rD<{nhRWu_Z9VWr0Z1J~I^p9I; zk(V&B$0+@?t-P)uoa(8gM>Dcu1tKexT>|Pnd5JtHFAdHn#VLBxE5B~hKVp$%{I0`Q z{xh6;kMK*K`BLH6JM&(blwX}={M{nI%9(E$`K``;^bsokdz^W<@Z%Oc#_tt=wlnY1 z-_P3}<%1%>(JF6!J~_GB$=TUi**<;#Ql3vxp3g3;yzs5Uk67XuzcyUuf2lJcBm8=2 zK2G@U&b(jvK^Hp4pL&#fzU!U&W|7}+^&OZctM zylaHi4`;qp%6HsSi~haShl^iE+8p?qIi@b$-aPp$=fy^OxbPcutSY~ak>WRPb~nk# zOa69Q4@+W+^@PjUKw1sBPV{egmTwe((6x@~YmbnB zZx+}bLSeWkU(3a>S;uD~(ZAHHUw^+m35nC8UkJ{Jr-3uwtZdsCutVgxTjllgk5%O} z$a#DiCF94*R(`Mea}&T-?OxSGbBTPpO&~66g{6 zRaSXPf80yGKfijB-__{&e42zWzuu8=5q`Zh-zNMnXFh6u@97JR{Kgv`LzWvQ zd74|~cUk2nfLHk0H#w%iIYRoHr>gv2<1F8KwBk29^9>UJpqm}zkC*w4RnB}zg!FkX zKZ4)?JvaC1OPRL5|Lqe0xLX|K?~0&5R^~5eJIiaMRQfbAUFonTAAghjU zk>75W$Fj$(LCSwyg!E-3z(6iHZ!q0Z*n-61o|G`5n^~X|vV(O4RgDQ%-3l);|ZFJV(DDm%c z=0n1dTV+YVCH|bm)Z`@J%(UcmF~5}TX&n;(Y^%Hk=n(zaIP+b??{ellq^c~{qR5PtUpfXhc-IPdqn>(XFmRDRX;MU<0IcRWxj&nr;NPZ zWG@|PWUQk zK3@3CoOv&p=i>YAzrmSzi~QZre88>bH#zfu(Z9`^k3UMuf9lMqO8h@K^K}w`-`5?> zw^ZUE;>-txALY!)$n)Ryj^p!9Rebo@4oALG_@N&<^3B2@>&%CQKdlE|<`KsWZvMCrZjkGvzK^Yn?|7N_H-$Ss?z6v%4=LVN zGK%V7IBG|qekLC5;}%yG`U)z+NEbc(fvubmc4zo-lQFn^(XU3YdOxd&TfQ$6pgmRb z6Gu4m&2K6G=p!w>iXXRh_-cy5)gMI;_MBpXtRir|t>o`H$|4_|&h@&hk@M#-9IfpO zGEzQuM>8LnrsNBcA$j2?{cY=ceBw_$R-+A-YJQ?g$+s8qekK2B$7=hT^lL*|zxL+7 z{C>ke;Ql7QU6p^_yYl>YSe{>p;#;5N{i@;a9hT=8II9o$3&0ISH0TYNhDl!fFP%zW z8*m`=b>Tkd_$7bwQoowQmiNP}+68wJm!JFDu%&*Ks&=8iOz|IC`7RZISom+Pe7EA= zbCvv`R$e=Y%P%PL5B$UuzofrTrNjN~r;hE9N9E7G;xkMB)c$~^v>X_fgH1DaZN*q! zl*4bS$PfJ7A}>Meg#6p`{jF6#Ugf_<#>W?ZLE~e4 z{cMu>&-~IcePJn|^lu!?CrXWsS$RoDG#pb( z?aP5bI?m6yg@4YO4+x+6lcRi>ieH=Yw&q3~I)CI5ex)<7 z%~kr>I`b`XY$@hn`%3GJ-w#c-|MPx{*6`mAXYAA0-%TNimH%}9_TKpo=k@DVe!~&_ z_R4R&uy@`wEUH)e8_w(BJO51Y{DvbA=v98(83P=7DW?{XJl{hcpPwIA%&2ttKa8gb zZR-PVF^YfLnGeE8o8^Z(%C`tV!F^=(f3;*OWM_z+Y8Kr;d z;f{Rw!HR#+nGZ?*UU`IL`8J%R%0GU%Bi}0gE6#ko@UuoZ%10lf(l_8p$MnZZ{-!(g z9V-3xEoWNv`-gM?$8{6;e}Y9*`W^(8O8P%izv8kvf5D`)Eb_vq3O_o*k*^cJILX3y zC35^)4bM*nlT-R0W{Teh+w1AMb#wnKSe()qx`cZA;)EZq)PHP3HJ`a&xH&=)C| z_=WFOTKCx7i z&c9t;KSTGwSN&-{qJz5bN{zn_zEj8>EG~7gzx`_&grM5z<-_6{!g=h zUs_cC_gt;&|5MibA5wgMgW_MY@}fWfJ#HV|mw6oX?~?pASjUedALvl>L$V#^JB7c& znQv45H}?@t`a0Yn>ENtpWWdSA(p%C*Q#u*MCl z|NHSzec)3K7e9Y_emDH#+`kj~D5+Vqq&{FYewH9&@c5r1{zCjul=fh)Dpa^eZ;RU z_)Sr~wwvcSv=?UeHMbAZBh>frXT`rctM36IC+#mOf&bh}Pw27p9KT=QVVsW8=<^-< zpiA*Z&U~uqUt{IjAAwr<;Dtpvd=pG84HGX)V$}Kkd_v27miArJ@2yh&Pku+fJy-FE zlsNJ((SMUO-zoBsS$TN=a27ip=qzhDYK~vhCBHFwD*iEZ9OI7@{uC>}mwtz}A&etc zZ5*#Vj9nu6q9OSmT#4F5!Q+@^<~WjFgvYQw~bvrT*?)=J@(d@Z&G>&DRUuDCHLR8S^QiyFaH8hm+gmSP(T>kYOM8jxXUqsLf4lym=zpE#7yX{ESwA=nB>nY0=nvn@`df~0)~_|F^uKM@ z9~{g6_rN(Pr~hK-^t(^nOzH2+an|n_{bTxD%BT5Q*8jJpU+MR!sQ15=pO5=B+xiF< zChUg1i{D2#V8{OB-M#begO&YX5Ard}KBg!A%@O#RhkK9T)zUj(AAxs2(!0Dj0^hQ_ zcllT~zg7R+ELFbN@t^xcmal*RJV!pDc=vPXTln@)e!kK7^7qGGF`L#GrGMOYEc0+O zJJlEW4!`E2XT?;goPij_%Ez{{SQk1IK}5(VUceX{shGrTY1O| zUBMsu`D+~wmgg%xxHqQsX?%Pa+_u)ARmGOa|+&G;n2#BQ$_XVnpYl|w;pHO~PRX&_x zxj0Y^j=4%Ib%xa${u`Zxpg$=*f}$FB891o``z>^q)ME(fUsqDk+F2aZr}LF~^ix4` zl@St>7LuQfvaT7>z}x(NDH zBgi*K;A0#W94JF^`8Hh2=d_wy!&n=ey8*`JlH!QS8ec4 z>5sdu_w+~C^)9bn+dJPO`{$uZoyI5b2>JsN__j4h{7&T)j36JB{x_u0NxnUTe0YHo zzf<{Yi+kteBJk~zo^OQmk6CBL@034(g!mgH@LIso@05RcRquQ#g8qgG_1_;Mf6Wp2 zt_bmW^(22L_ZwWZxc}*f`orTdw6cV8x#H`4;3*LN*HYU1`xm~wcfPv^-shX<^}?QI zPjWWwjDcQvI_^!2^D1}d61~w9p=@%@a@zw$=lgFWzgUQhtszn2wO7U3D9;M}|r z=5ed_gsDGTdytoKZ4t^(TjgASDt=muzv%Es;Oipr%@O#R zkDT)-@pttg&-o{x^F?KaU}6o2x5MdEdzF8}L+rNnCAH8|b^N%5!e>~1Q|Co9l&p*P;Ur%Yi#Cd+x|0L`0?m@qMl^Q>v zXw@J5CYHw4u((0`>wC~Yb-)(-e1y(*PJdAJpTzp5e0%y`q6qg1Dt{8Np7SSm0KzAp z`ZC4uUd{Qim+z?4m~WV&r;nOTng7;udEBpM>+=J|hkxbsJ|ueW3OXX9N~zH_9FFWcWz{!MU`Cn%(zlMApf3(h1 ziAny0cdGX3)c%woS%36AWRo}Qhecjw&*Z@oSy=`ny&7nw|Ne z@b^3OA>kij9@{UxWc^k9cq_GUv9r1TN&p^j*m?IooDO-ud)2=yto5gUw5|LG={&_R z<*zN^=dM-h&)>?g=X7fiJLgY(NbxPsd`P8Rd&HR!3;(GzudPw#{{{0`*~;g#vF%iT zjmvo5ccHy}DL1gby@AU&R_$hx@{Lm8zo3f8UjD*|6yKBnx*qfokni`soDaKx;a!Ti z*N=iY&R?6-Z+eCT{WR(~yTMc~~L>>Iiw z$a^Em$49WgDD8oV`I+>zsW2r&hNxi5=|k@@nZ7tFSoPc1gS-beV_-Y#Sz?`E>qD#P zhLZLO-rm#ajlc&Z z@LGiRnJ)3~*hBdRAL>1QF7eOTgM51g`OXM@Y6SZve+0fU0w0RNH$})_*fxJG^;haw zO9c7&2=-H+2z=)!y+5Ds2=a}~dzTNMXPrN{=P#`MQ@A0+IKOV^L+AG{9~j&F{HLc*lalOAk z-4W6s`&jSkZ;OzAcLe!B1im!_9~0p8h0b`luhaLvGlIPKc<=d(i@>Kw;KLD~kNbk& zpKo0R{jpc}p8ik-d3OYPZv?(8g8op1`saG0_w;u~kS~oOAB<4G?(*Ktzb%6P?g)JJ zlfCCJHUi%oq5NBp@BRG_M9|+5fe-hfAI|qo&&A_bQxkH0aC|{B41N+a?W@z8*4=}= zw9l;(;*X8sA6TpC{rPFW-ual;-k(ou1l}KkuZzGpN8m#d_>KsCu!r*df7rVc__&Fy zFPqEU<~9Vvl8|7a2~L1uZiU3bX%k{{fH}Q6oY;`V*l}WxgaHbe+vTduX>J3Bn%ga< z70?#9e6%h{F;J+10xlFVN5S0R(`rVe8O?e%GqTnT^6!^OtEV?J|M!3I&1f`|QvAXD zb~5qT@!P@e)0IKqn@PT6aDI{*_$z*F@b*<^kT++Lm!?@C?fP#9{oXqUZ(m;q{i5HA z^;7)8`;Id4SCU4bw7;@lTt1Oo8SLMbsr)SmFTXv5eoqE@TZZzjZJqj)dyC)SnfU$S z?JLb7ugD+t1fB;miNkTE-On_&B#-)7H8$8eMOIp+vn4VZ-Lw2|MJ#hmr)*6AHE$f((lS(pJb5o=aj>D z8w8Dm_B933x2I11&{8I938HU*7A;Ky#qcbwJBIo(0p8 z`~Dtyeq-f|Wia7Bf9dM^r#4ijUSzqrzPdWqD*9hvn&;Ep>EYCa$EnXs!9z5YX8_EU zvf%wL3!N9dIAy;|s_5P$)qe7mY>B+^S+RVy0S|x){>ahM2E3R-@JEi0Hg*t54fp71 zV}wvnj*d2V6w1lb(Z)_fIXODo7%7yKqod&oSI0 zjym@a(;g9#-E$%<@%^r7t@srn!NfVeN zdeY4=$pI=|Nt>sM9P%x|b#z5?!G zuUPF}T#RdR3-;rY$<`bL`h z`6~ANPw<>(?ULp5>BpZ|)K%BR2%rhcm50AIYIB@jKx zzxMi$D*L@jQ_JARK~pBrg#kQ#sb)^<6i(k?04}HvU%w_tZ;p>R_&xdn(67$PeJ6P2 zU;v-ku;68;_H|FonNGi%{G<>f+V*MZ{S%zNzX06Y7BYYG$rfqs*OKJI-#YF%h;zw48z3h50cNZ^GCG&>KgLtltuGb z&WHUa%Tv$)6a3IMG%kaWFD!))f<(7Be&PEo)$m~k{5U=~ySwRm3j6PqTQT-0ClquM z|K6IB)AlW{U$KC+kbc~S%4-{z)K|l!L-p0CKvzi0rSiHJ4Yf`7D*{poh@5N_r2Z?m zNmIY)yE4@c?(<2s{Kh)48?0}uUU|~8I>>5^NztioDJg&9wrR>=H6LEJu%xPPK746n zX*JJZ1<^kzoj$y2VL8rm3u{hhDu*96ME`-JH1$_its0~NMD#xyOh0}7twewC?bFv! zx)4G8OSi-R(ZK63JQa*qzhZGMEN@)g2;T~US6NiM<0r}weoY(apHvRSRr$}s-~U)# z4V^>k+aJsA4}j2*e_(m)s4a0$q;kST^Ru}9b9UhHr~keQ(Y3c`Io7`-xPBFRi5KWs z68#4x^e565)DitBS$%RwAHnw~E64T`f4`-aXv6$kCC0bah`{#o&|nzPVg1oU{Z%kH z=06`pD~G)zqCX|DzSq1)3DKVuT;F3}qnzl&bMnr3jr6Z6{}8p``}rHAjqr0taD9*Y zjU=gmZ}$5+m_K3twwGhM@B286ap6Z3DgP5;`96JO+;rtvd5s6(%D;vEK9Ez2Vf482ojLyS{44Rk>LwUvE?>gWzZ%oA|GpVezl!Z43ZBRM zp9Ix+l7l-x%(o94IK3Pj5F5ZEfgSpz3da-L^Njvj5SpDL61e;WHS z!4K~*bia?ZD}H~1qfhujL_UX=)BF!B)oV_!t0JF~Te@Pk-HW7^H`c+GF?=`YFlT(4 zTg&ly~Q;flIbz52$laQ%e; z2gauOC+{ypxcmy@pHH&o6Mhma$@t#UC;mg^HAH{TZcKa);OhfpPv`w@$>(-U-FYL| z2Nk$|y=Oc37m`~Q!<+2r`=2Y$#qGZZ%crn%mmhfb*W#tsP4G6Xs`;zt*Dl3#B%|!{ z+WaNe;~JMYHdHT4tb%t30C)H&Tr}ao63mYYzn%PEkdl;tFfzqo(Y4OD;E|nEzdMn$ z#p*`$7nq-KUuEzUc~6@6r!eT>Q`-{JSgD^h}cW2_8 z)Q<>14ZAb#YsJTn37DUC_Dnq)unxX{E5~`y*ayo;@0oi49g+7E{g1GG3Ma?@m0XDP z$CG=e@(1C+7xSOE9>?c%d#1j>M*Neszr)Qx<9zuCX7?5}!q7hTbPK%C?6hh+f0=-f z4cPIQc-omCN!~J!dH*0OA1%V|n=+m$pU90QmOmht7giJfy@dKL^;kZKmD~B3w0}`G za1W2?z@s`|5E`Y=Vhc-e~OP8t0hIP=)a+i?88IU(g)gx^ZszV;`a=L3@s6NUU( zD=_{~CW`Hg+nGFPZ)`EPf2ny4m%r6Msq#tw^5UOgzp{35?ZR3Zi@Nv;4;6K|{#*7D z)^FU5?fc}ucx3@wzi}&;KPQ$~xbZuQiC+uj>c;Q4Nj^CV_n*%EN*9(F-izb^IaW^E z--hj+oI?6_r+ov2-+i6uF_Y`;&*bNJ;y;h$_HV_?N%=)^!_1DeWWxdYkW)U)|2Yqo z!SqCR{mRr8Ap88;(X(bxwck+>3kNFZ&Yn7b+BCSoc*Nnjl&UHsPkombzRcjf2Yqim zzN|`}jK7%YyqkJfh5hEp$um+Vl>EcV%Y|n-_A#D1BxPTczq%iB+HDf~i;kT5XT^^l z{i0j2{yT@H>`(Mt?sN1jvHgwD9XZi2#&#*eTVsPmQ|%)8uLhTI{MoUuvD=|3`;+p^ zar=#@v3x&PUV+O^G~)UDcMfI7Hz%4Wd3 zzWuLnHxOy(e)bc;_8;rtUBth3n3|IEa`=3R;~#s7<&fSS`2k{iE0O(7W5x1z zB0oti?;!Hi#PUuezfdeMGI9Iw63Y{_u>3b-xkbwVi&$Pl^j{XsyNLd~VtEJV&wPBE zkiRw*pK-Pm|K|N-{XSx!C&c;%FFJX|e0C;dA0FQl zeEs3zgX<6S_$Pet0aiZGESpm?c}ki6jxP5V@F@$FkoLVHZeNnfKNibNeueSnAHm?K z?Mq#K!Sw7xxWHJx0Y{*l7=58&%Bb4#(jgVaBfmHX{iCp2Ie(LapUC-&lrxZ6F6o!o#*nu-1>R-e@0M&uLI$VvMS6U#e^e70ELP2>y2^5WO9{p-c@7W{ov z^K7x)Am5+5SuC$1-@m$_m2>v1Yg}Hp@Z_bd+292uwUGSq#B5=HEGP9p%a%{<+ddLs zpKg4F(Ep6*o$-tL#%%oLIXiwZiGA|f?{kszEmHmnary0}eV3=vC-Ns)IcJ}Rt5&Y8 zYnWJ9OX_v~|FE*dVcjv!z>{Yj4qdWm{wd|3_VkOrLZi;T0fh@H*qL0vv+Wnu->_(6 zgTH<@|Ie6um@~fR^_Ky|E9w_D5P~^*9oz(MY*2}%KvH>okD65%9k#1Tgc1dE;<$Z?O)fhbm{6^Qn*N7zjVE z<@Z!G@)DTrwXf@p_t$f__p#q^BNcScb@H3_U^RX|(ur@FwN3wWd7=#4!s~E;gnjS) z8#$%##=+%@8wQuR)H>HcCKTw*Upw=Ar2MuF@4qM|{XZy(+E+-v@A2#7gyV-|BLA~k z-i-4fI+gwY2Wel?Y>e+)vAmPy&&^H{)}JK$BgOI-A|Ef7cjES&%d6P(VIgPAKU(qk zM}D=y*gs_>XMUoH$Oo{zVv%9r*&x@SB}Crld|%KsY79Gf5jnx%cD{o@vFkFX{${M- zo5a_@+q2&vX~lADHJ0zs$~%jk_9vRK{1{G-_1orSc`YmNBJC&NKe>RF_mKMW^EJjV zSUJ3wF=anQ>i;z>FNB4xDf_OAzmKx#DXA6d#6BfhUiT|!ey#WJm4+R8L|%&Jg}-y= zzj_~KzrT`v8Lu<7Ncl}h1?aDvnx%v1^0B^!@%3JG1~b3ViRB6W{g2*jS$P+h8wp(g z)9m+Moc9YjA6B&Ia;8k4Q3el?loQ^`Hu15;fA3dkGW=KI<3@o~e&U6*VC9_sj&8^Q z3O{u0S9g|UpTt$%_hBA#nOej6*V!}=BXWBEg@yc^3)9>Ve$Sh>;fl;8F+mcPZy zO)M|G3CsV-$`O{MUt{@t=cf22^Gh9A-v1jc--ea^1C`dvt5bs$p?x@y8nxo@6BUy06P+rScg(>&ULckyi2j{ox&4??q1}{Ui{-^c z|IcE136Z}fmX{Lw7h<_d@moA~=uT||DgSl&OuX}_^r zEHC~H%byaxgiS>Io`kN46C6VtSme&#a9%6YjkslzIcaiq}SS;@(`p1gp z9Yp^mvAj9M``Ic+;p>A-5OaOt@;epx6UQCo43AU26p_OE2Xg)XG<*F^&Zr>Q#|Ksj z%P%1H|3oZrItaJ#II+BEeJtO&QdoY?!B~E>SUy1J-)88q7~#F63bV>M|M_`p3T`7 zZA18Zo6#p{we9KjKgscZ!v4pY>3k0)Ir6>K`aiz^FuriEPm|-*$Y*2yLs)s$^jUyl z#mTks_0kpY>LBto3LN5zkvb{k8b`Jd$Yeq&eACF7qO z+^-s?Sbk!E>WO+HFX_bk19ge(*6f|7Ji*wtWil zHu)_~D8L_SUklc6#oOd&pD^+^e7v2=N3!x1KTE6UFK?`~A2~}6Q&+-5xl|$WUl-OZ zB=s+6^}DgWpnz7WdWe~jfvisgl*{Kv&|b2}%#dhh#E7+==Eoc!AR zxLDpp} z=E(;$<+oz|9SO${=IIBg<~N9clKR{6dFF^infVWT{~Y$<`5m%8uo15hOeZJH2YESJ zf9L3X*LSe%-{4oOX;h!cm#tV;O&7?emE!{ZTA)h`hZ_9)c>NfsPgj+(`ow6 zFj1HKbNWYr`Sue~bbVhsIcXx5r`EqX>x*g@tS0q}<#hd#Sib0#LG@vM$l&s{`VFVl z!}^}8<@IUw>-iJ7_Q62Ap#hfXxC_wya_59J<=g9vm;!ixyne@BKa@u9KH$#Fp?%P} ziRt8Z;GN4FPF~=ykn!uUtXniOt^HE#qZWDBN4f6@an?UU{r2*uLG9x`K~#UkAoUab zEW!rn^~w6HG;(|WPU;E%hQ+l_b`hL@9W2mkpwVop;XIQ^Df3WuR%NP0b@%l!0d1D&+Quq3v!-w^k zR^#-WMt?~LefoGkSN^j34JShvwdj;aTmdJy^LOeI>s5G-Y+5;9fSFcadP=Qbg+Pwi zcc#Q?<@+>bSpSKa@TM!jRJ=Zvt}o4?KVeeZ_S*xvRfCkDl4o9@>U7~;`{4~f@Nn|d z`AgtUV5tSHgUC|_aPrhU!n_3xCbtWqa_8H1RjX@P!i!$)mmH-$gvwKH!L6S4>Zjy2 z)${9^CAOSCyr6GkeQh0m!5@|5^|{;`R1RjfUn~Sq@K)EtQ|3PZh4(k59?pkXbu`lN zr}OJ~*9ARTzl*gESnFrMO^g27*XH*6UV4Tj>)!-lU+uJjxxONr1)E~|t73U6S^s;& zBB6c_kv}GucM$nZcKtA^zil$E|KP>K@;ixqnONRU(a=KFfYNWE$FiM%eu`kMZwgRf7oyLs^Tw~r(Kb&AkG+cMPOmqA{_egBaEzFJ4R z?=!(GHtbnTl*WDqSYB}}i;w@lVhQ*CM^b+w)^E+AU!F#v@RQ6SZ_e<2!|n|7^4nQ_ zr2VA+x(weRG}3$@F!g)!u2~~T0-(t{|MxWG=GJHR; zYX{u^gPVl@)tlk_g8dolFUatHz^)APX0pELl2e84Gc$ZYusF^8^@)9q4Brn-W{`Jg zC_ho_+}|^yLVFBA{DaN^bB>t-AcW!1EKbIU48#dw<-kJ~q{L0Erh5w8CPv3!8E|DKgX{a&(u^O;7W zJh?qC{~NKqoyZ?sCDiXB^7qB^R+67yUCrpT_JO61sZV53_vhua%Vy7>1z$Me%x5(1 zNccIODW9B|+y&cr*%^$SD<9%_&fLj!kD4}zHX&6+3(-Ge4Wm!WH^}|*OT_ZZk+^-= zpDEODCh}**a{HkfyPq~+5wG9vCHHrJ!rs3@Qyo2neBboAgPHq_r2WO@{?CX*nD%uh z9Q}$b@%ZQDLsIvz$o(JZ`{c`4z-#%c>*(uas#cy_=gvXcb+nQDLmPAVhurrkRKk}l zj;NYj1}~t7S1gluk!>5fzxCdsO#6tuleGWQDMEQSksmmfk-PlUCx?CSZm{dw~+F`nklv)`}{M0`kIsu?{_5nkFx8_ zU3{ret4y6W?=X12%z1@SO4*h3_I01IcIqfFaeTZtONg(Z_}^Dzc_E3fjVl;^w|=`@ zo-w0r27KFOPT6dGiFoSfcpAzP$1(Uw`H1L0c08l+)G}9uD)#_=w7PkRKQbMspqFs+RpP=6%|#fC$MHto?GrY z!!tndBKCXiM5g_u30(x=GgXY7soyg`AbMn5OxEXrBi8q<|HmT?qUmgVN&P1zh4t@W z>OMcf=#%z&w8nJwU;JZgGFC2~I<6!ag3GJl( zWny`P%r9Nf$_YN_`Gv`I?QfjIx7W%lr^A9e&tCzVU;BpDC#RH>`L9dF^K+G?{qKwA zt)%>&#PfGuM81ZV_d)~g{E{TkS8vEZzf9VP2>w@DeIl^h&9Bg|?`8y3dKR4@Wc#qmtSli@LP3_i9 z!R_0$mWdy7UMrCwES7f>`7*J*;A3a}*L%@g;rcl%&GjLvzc=0d4L+eI-S>;I96gN3 zpYYr1;Mn=YlFq^99p?-#@5&%Y_2TPif)D+E@bW9}8eHCK4K6nx7t7)KS^E9PROS+X z9??jScl3LodRgcnO+@~pSWa-p+t>oJ1!4=t7KkknTOhVTY=PJUu?1oa#1@Dx@O`vE zo`JMrWnW*b`FO5Hy$olrCY$<5y>igZ)3kuJ{`(uI<~vEFvu{7r618pIel@!ht=N9V z5^CGnerk3jTCx3zCDgXD{nYG6v|{@aOQ>yQ`>ENDXvOv;mQdTq_EWPP(TeRyETOiI z?WblpqLuse7l=Sn+Uom{ZvDFYO0Zp}nE%-Rt}`g?#Qu}({-Z#;M@651PhkqX`t>7) zTB%Chf9TpT*Y&9{sO-i5tINNN)u~Qw|JeT28|3$5|IzcGy&4NVu!s-w>zElXujKmL$PwXRO~@$0tVg`%{hZ-1p~ zT_t_{BeyJ-9ew=Su3rT;)zQaK%Tn3X=U=5(s-uq|(ZUq=^y^os)T0vH-(w7gU48zL zLakIKuAkaMWiPfLQZbvWll%5_p(yR><5#NIRm%PPk&8uTM<0K#*Pre7tFT6O^v56B z#;;p{uIp1SRrd7bSEW{}6W32|p|Tg-PsM6fC$=B8h00!RKNYJ{o!EZV7AkwO{Zy<* zbz=KbTd3^C_EWJM)rsv#ZK1Lk+fT)6R429{wS~%FY(EvNQ5}8zAzGNip8ougLZu!R zef*xn6n6FTBZXS2O7`*7wy5l7-+oA?*{+U$``x0HcJ%8Nr z*3!41Zv9%#*L-`n{r+v;_Geo^wx5m#vLC-Xtsf5ltJ{8EeWX=D_Tyix`61*#-THOy zpX>GOwqI92+xFLOf422=-G13_{|~)>UH^^kr(;3={#&Q^FvefH_3P>*tpfDN&${*N z>TAIdVf>Zt_UqQKs~_86#{${Ue>$xn4*65pe|7bB?We1++x~3p>*Ckd*TtXh`m^2s zY~#=M`gPkM>+4uRfBdUcyWM~4{psuLm7u3R9Pnq`{&D>}7Kr^%$9i%6#r~u1KkMq0 z5ZhnJdU5>5{uBF;js;@>(Xn2ffAWkCl?>R1#u$a5sqcSCseYoA`}GqfYFmB$YV{H= z{rV9pN@<(@`m^1BC9}Co*|(qD6s4WqzyG8J+f~Xwe&n`AWk=utRBEL<*{>hb#whIR zw?EtUD}eT>L1?&C)c9@!uI_+@Kk&)2UXu?0&0%KiE!0duG4 zK7Pa@lKZKTU#>p>Z2kHXU!>IU+^=5>uJ7dB$B%rNWDe-#m#NKvu73TE9gOe{6T9HpQm3x5*Hls zXzte^5NMjyavwiRgDlu#ef&n2*S};Nf41w7?H|n3#b@Qd|BG=2JsRKt32G_vc_H|Z zxZr?C~qBLje*Po`~fQRGyQ9w(H zPs@J)q1%34eX(7F9@Y21TyK9+ONr0Z_djvDL664u2ep*=yzJW#i5nL1X!hG5u%T&A z({DdYQ*yAw`uQ(dJ?YNU$Dgj`V8^qM9|db@nzOQRzcdXCcsRCyKtrWDO`m_1rsQCU zbHDyzIMbaK`)@kS1UsJl{)2)6O>>q${xk&#Jgi?o3Rsi)wA`;>j4SBTIDZ7Sl=!^d z_a7t%7VxM({(u#wIZeNQl&0ihhjYLFU^vsA72{85nPA7WZ$A{Qp=r+2Z-1JC10L3| z9|f#Qd|K|;FUA%0Xzt@jL7@uI)5k9?Ht@lC{1(_$!V_cr3C$AtpuYd3z;%gE%zpji z7JMpdtl*efTX15ULwRZ5fcL*N=ktg4{a=jWGrpoUzrU~bf1U;}e>fd~{CVkqi>;sT zZ2xh6edI4x;)p)~5|s%~)yFR=RN_!vzl5;_r^faZ7)9bxY(FGnE&r+d_RDtteoQh) z^zqBo=0Ep)(0}MY|E#O;H>$*un12al2~LgeCoqb{q3qjFqOpQgzX$nCfGYSQef%hR zWr8!a?>|5E_Uq!;)fYI0#G%-KvTc9e`g2`h!dV5U>gQiUp%RDm>qio``A^l4U)}n3 z_5GM+j_Bi;sm*_G?$?j}pd^my`@ckGf>U$9ek4E@{7~-uUvR9VGxhmLqGAId)3^T* zz5c+a7M`eYe_^qK561NeHkI(i*nUE@1U{&5KNPqw(TV!?i%JcCOuv2DnO_$4Y6oSOamk)Tz<59#xl?fQdb6`h%V{GwI`KbHIL4~|uIX71xhB3OZs>EjPv zmGH#u*Dq{V;Dg!E-+`MdJW;>>NLX&rgK_=2ZojzwL493xo__wzw*5t@f*;ezAG|Kn znc2@jNYt#r$CSUHetB5mPgnbXd&SwL{_NoIZ_IA}9cPgG15+(LQI-GhHQB8nok{A? z4*zxMgj4^ahLLX*)Ba7dQE2bH_Dt$`=hfS!ekX6vbB^0G_(Nz{=l5C8Ha&mI)cKkI z)6btMQx${C)3-k%);nNB#vYODbFGrD-_&fsuD)*jZ`EwSuD)*j+cn!CSf6Vs_p{?% zl0VY*e+f=Q{8QThPT5p1esuNgHS5>a=gcT=zxy=(C$N5!YpM9Bbo<}dY`;%mZv>qF z`887vm^+$YpF1(l&s^6}1Iws8$QeH*raIen=Skzgd;>0jNb;|%|32@(>5v6GF4=lt zp?OAu?^uunEtin|ucqH|sh)oKWqSG@4SM?BD~Wy(Yo$L&pTG2F2a&|}2eDH6b7K3Y zw@na9Y`-8@N`FrF?T6AgE`TK4?GMmI=9JRQ*zriV+aK4@&?EgLwx6`g7=_q=j5(x# z#P*Xm8KV%}k1>bzkJx_FCSw$0`!VK_{*itAA?Y@I74+{vc}tVu*RLPRSL)Hw=TEnO zU40K2h28AiUl+fwzJk#_DzW`M#!%SJzWo#$?NQNhzo#&TUH$x}P^m{nA3ySxCcmqX zU$=f;eR<4Yjoi1t7mfUW%s-Mhnny$5e>{aL?CRH#6l$d^vH$4WFWdT*OO?Is`(JE7 z72b$W_T!hdL~X0zezkguR`&g$v_x$iw;!n)4r}S#Ppf)(`+c_CpX>GKy8Yw!>sUZP zespR#;`r4wUz)Ff1TQrEmF6`h&=_9IcV0v`*Z{hIIp&U*U;+e&m|2=)^d8~B)h z{zQT65}lZR{GwI`KbHILN5R1g&eZoGL7@_d^y^0wwfRrg=U=yeU41_$nIp0NWBbea z3x96xKf3;tZGE0mx!?Ny%hku9tzSRli2+8|QDoO=OPf+YiZ9 z=Q}t1_4}G6bwEFUkyL&B$@=!=OO*Sa`}mO@VD9Yf+dpnUM~T!=egBoJ&UbR`KR%O4 z9niNQlB$nCS>Jzj>(|xi5y}0I?VoM?%kjmZt?$2liE_W=`sM7!pB>wew}{;DT+d&7 zH8#}mRl9uQ(#A#Ado`6#s+zRVxTUqr8=J;0S>CwUg4&f0d#$Xgub#hXTtm(L`szjF zR-Rf{-7vm}SSg6Ut+7|b%KFBIE2~!4E~{QOf2mu5zW*W86s2vh^QUh=C9}Co`u1~+ zQrgLW{YuStm9pP{F3W}uV1(Q+14jas%^9HziRC!TKfJ=N>bZq-+oA~;aE$*{aV$358hvt>-clM{YVQy z?)$$M{1D!MmFxD8?Wbdb?DxMqt+(Hwr}r1@$M(~)Kop+u|JZ&y7Kr^v$9nPjDfXY(e{?Jm`;U(G;`|f)PwYQB7Kr^v$9i%8 ziTx+`9~}$C{-a~PIRC`{6Z?;j1!Divv0j{i^!*2E5um^RNVk5i=7(_q;D_G+A3FZn z|8y*%pFebJxBCxW|JBux+plAR-0%N%(8vC(AHT8vbu19uU&nfJ{Kozh`;U$V^!*3v zR6h*X@5SxcAy9YxxM9G`zk@%~sk!gJy8frDFS2UzWBT?FUYF?1+^-*rU*@<>34Ad2e_i|Q>IbGuc%nXk!eRp-jN=~#ww36_+_zt@;}@|K z{Fr|H#r6wsZU342_D^>Omhe|5IHDiFfvs4#oD9FqYud*nR?| zNF0joCt)nXsj>Y8Mv*ua+fTw+f>UGr35+6fD7K%3u>_~a_7fOI;!y6}4@sc)pQ?ZT z=`T~}Nbc86MuU(#UQ>Djj*;#ws4GxlFy`^njxKRdR6Y=7P-WPWGgf3nS=jJ5pd>gVrl z*;-BFPrBr)S@OYlNHFA11CJ@@e=4w2kXef)Cu@n^^RgSUv>Z+-rdT!q}(xnDmANb+ay<42N++0*s$ zv*pSD(yt%MR>_>7{rtr=NBT$h?I+!2Mj`j@j~G0%KXRWxS;Xx5xsM;QfFytE+_Gi#YyjHpTD^M(xiD5V*iQ# z$KwvtyRrYo{v+))9);L{V*l~DgY<6fKe7KvJB>#n_Mg~)JnkU9oBRGF4Vh8M{`DWz z9O)nW{7F~IDCpadDNg!F_VFX>HhUGaZ$EEqMy8U$9pKX0z{&m~0TfeS;+Yp zETDh=ugjmVz7G1>fA!<{hi?CDsUZP|LfEq&tJ#(kNro-0NXr1(_n)}^It1$T7u#RY{<`+l)z@kL_hI~@Yd>9mUHj|S zpX>VBwqLgE*X2*Q{krE9O(ewPy!uPRkUTEaoH=noPuQ$YSZt66?6j(=hocbjGYtv_J? zAEx+M1OLV@;qY%vi6;NQsLTHY6#qXw{LAKlo_{pV`LFyl=D(BTZvy^1LgL?yi2oi% z{tIuy`Tr4$|3$n1e|i_C{MY;*oBxg5oN`ILH^0v22P35TZ&J+vJ=@{&|8FS%Q-Oc9 z$&O0+2~M&_5%K?$F8_~G{5`;%>9df6-2u|KC#lrvd*x zA@OfT#Q)2>{QsKbf62qYZ2tH0&&9vXJK4!H|LuRl`Tutm|LMSg=eUsi|EbaR|F0;Reg@8tM5Zg-QA@KRx(m^B<4j;{1QO;dih9 zpQQL-1^ngz=HfIU|L6lY{!Nbminq9OL*oB5`S?%q@8bU>#s3=M_q8)1{s9iZ#o-?+ z{z%0e|J&oSz2dzu;s}?+&M2!h7-^P9Bo~pRVZt zF8(fx|8>CcYiB_GeIK&%k2w6q4(@ii;D3tZf5U@c*8h3@<}k0^`0M_|l^YWOXDIr=i~nhg|KEV$*Uo_W`qZTv8ys&fCQyKY-X4{`X>d#rziHUG6n(f?iif2H`}0sOvp z2K4{dQ&{}QozeKeHvVTQ{yqlu2kRBBBZ6C7ou;TyB334SR3=aSE6#x5x-`CE7_^m@( zeCAzFxjw%q2SSQ}ZT!zs{2zGm%lbc$-x%iji|@w%{{qGTA>gm*XL%%aWt#shp3LeY z9{)$IT+VArEBsp|o&O#Gck#bS@%ICMgKsCUG82B($o7B6-O>2JHvWH5{2zJn%lbc$ z-{Se_sS7FoRq?lv#`phvDE^NDe}^Lf<*Qi!tqS)3Px9lT@&B_F{olp^GR6N1;PAFB9Q z#oxOK`~Pbc{{Z0c;{7xr|DC6@{2Q~`{FnIO(D?s3ivI87@1^*^0Q|mo2E<=^8jBxs z_=k#rZT$bD_`mevm-T-hzd3C2JI}wk>tCOs_}9SthvtyhKcI-#KfEfx{vkE;bk~2r zN%5}*{JkOJw<5y-nj(I8{o}tW{xbo8%Vy!Me=*9~{5Mqb|1U-S?)tyCD1HR^`$EER zMufjt5x=|s?QM$xEWmGW9uEH~BK)r_;&<17y+iSz4ftC_!f!={{|!a_ZvOA1_|F0S zB@;(6_pwOaW}5#X=egTy(Zv6oium39_aBP?r+~jdB>v5a@c&y8znlNwrTEVU{N;rq z#eYQj-%`Y1_c4C{;XR7~Jiy-;5`HTp{NE|!Z~ZHt|NSq;e?H(J2noM&cr@{EjB+zh zpdIr3w~POMioY4~S8NfE|CK0mXj-;BOBJKZ@x2_k3OaA5#1m0)Au5aQH_N z@xP8P{(g%8B0K)~4X6LNBEr9}G=As)PvS(J|Jyf8jd${Z`pxoT{^vVxo(5-?Oyi&8 z(~FpK6S`>~=6Bm6+EChw|A_K`u^s=D!r|X2k0$@Gr^tVC z4W9pdo#Our=6|~RdAfl7m!Hnge_7o85BiMrtC0Brsr3AxGymg`e?Fo3F9H55L&|?< zMEtL>%m1eo|JT63kEekA7oNfLZ_bIv|5f=%&*S+2AH{zu@ZS*<|0p8`R&Z>(YC zA94Jb4shj$l>g6_zW>kV|1T*17T`Y_692~ZX!75Ny8M4h@qY*W`*;e-e-p>QF*h3g zs{Fh8|0|0BXTX1FNc@`-@xPHS{{s}iu`cCbHvjYdTU`8OH=>&?$G=s8*FSwj@m~)7 z*K8e5{znnfz<=LIYU^K$*0TBE$%te`8NMNPXY6P3&+33@lOLE?}Zfq+WhBH{8s}1b=!m!|HhA_>Hjv> z<^Nmi|Lb`8m(Bk?|0q}ZUx)I474Y8`68~mI{BNene}5w$|L0Tu>jM96pQz>k$}`#g zZ_H!;zyFJ&8ULTJoB!9N_^$^36WfLp|5ilv|C{Ubzdpsk9`NtuDPaCDzlY@?ar_Te z{@3Pz1B(CWHvb2XV&<($yEDyylk>S1zcI!C3*f&y zB>s(`u>Bv&3+^@~{9EeszX`=(0Q~!S3dnyC$G>@0H2Ago-<0CN2KX=DE}Z_~jEMiO zbot+i;@{B2zij^J`8RTf|II1>Yk~isgTm?m&5NDuDmUKwosi;xYeoLu=YKY%_%{On zE51_8{}orW`5$roxAWzOg#QA?`@in|&lVK_bvFMY#lLY~H2iNP%|HJB2burcisHW> z@HZEQlmAde`EOfY{99A}HvsEa(j@!tmc%SVJ1|2IZ6{u!x@e@BY{ zcECRn7XFC%-&q&`P89zgfIoR?IQ&}?;fK!^N&S)azwY>dB*otj_&Yf#?o z@&6L=HysuZ|5il!$4KLMp8s&?f3~FfH-`Bi-#iV@u9@cl3+`j*e+)C4{3k#E!{INa z_&4$3m!1FQ@mt*dm#>q`+WZ&Bza_r^vn$2FDd4aCT5bNX@I;RPqgnn7zTwIZ3IB!C z_kTG2V=4a40Kc!D0sY^)pT&6q{p9bW=XBq3?h{Ip_Eh`V}{a+U;`oD{RcZz=t!0&5kK>SS)vi@&WvhhDu{A=Sc zruet?;FtA(9>2x$Kiu%QkHq-;?6s#)Dth|9SjqnB(sojs1Td#lJ1!x8`$x z8j%0GM_B%iW7z!Hw2&(|B>%reG5@>x_oDc>1N^>r2E^ZTJBuH2_=n2>wegRq_=`OF zW&NMWZw_<(?)6^@#lJn^@2=$hG$8*yoh<*xWY+(S7jfl=TgL=I|fO;vXvim&ecD{~t~9-vjd>#Zx$*0^;}Kn-vZIvC{J&9R7VM{(Av`Pe}O9 zi16Oi@%iO zzYp-YP74RW!M*?97iJ;#e|zZS-=E^YAMlqS9u9spBK&*m;y-}me*o}Tl!t@gsE(%p z`;jjG11bIo0lzUl9QR13@ORA!2ftY#4gV8#@tYL?uK|De%y94_twRK7{&i6;4hgK4t^97{(W@uPoemK3;26O!f!={e_v_* z-2MLv6#od%{EzJXA3y(NMKu2>KmWts|Ja-2-x2U5ex43rxMW)Y(fJ#8{>$X%znZJL zxC-g|=Q73lKllF6G>U&G!0&5kK>U@DviL0yKQ4xDh70~OihraBzpVfB_|Y)O@8177 zoZ{aZ@Ru&;{4^l{#dop%8^^Kze;;3NNc^|x-v60S@h1Skublz$xBiyJk2w6)@$uep z!Cy}C@8ZEP>;F7{bC~0AGVuM+A5;9J0DtQeHUDq9KUDs&jsGVU|E?bVvi{HGH-x_s>aGb#QtfWM-a^V5L* z_x+3IAMyB4;>r!l|1X~)dRoipZSH{t{{FR#e-_0*7VsN<6|Bs;fcLV-O|1X>W`2OGG$3MIQ zLW+OY{@?ZgITZgmkN?Z!=l$Ot=Kf#43HJY^DgNJs|Ci4W$N$ZU{J&Ju|BVeX{-Y@V z@xZ^eR1JT{+id=`IR1;4api{O|5qvYf8E#O?>`+&@ms+EKuG*s4bkMk{dM_2j^f`7 z`1kRI^H!$oAM+iSf3qqY{HpxB-~T(F;(r|YZ=b{YX+ZpZdPfn({{g!EA4Bn%c=(si z|2+RjuJC^%#s38GZ_Evce=8#X4^-qIZH4py2^9YX;J=H{(*gaz^b0or(K&4VH!bJv z8dCnhT6+H9x&CqEKS}XF3H%q#gxvE&!heu1|MMySiNL>)r-1ke z`dI#ri26TO{>!((-#=ME@&5t%?+l55)EEu_hwAcQMe*K-x+>r9$&lSi2F8_-u z{yzc#MMtaQck?>lu_DUi zAJ4zJIvV_k>GEGq@lW#bFPr~){t*}dynVu&|5WAQjsKG<{x0CZ_?U3w->8j-|0#<6 zyW{^_ihn=gzlYD$0pq`)i+^J!i@&#yvujBCzg2Pk@5cX9ivQ2Re@{sKqb3&rQ2GB< zUH+F*{H4IZkEekAcm9{n|A^y%sPL=u@5cXfivKUbKML#l*NEc3Oqc(YDgOOE{LAKl zo_}+g^WVG$p8u$$_@4&;n~&x4R6zgd{ToHZ|1?GZ6We0^D=7X0fd9@_YWTa~XXD@E z_;0P}$_*+1|3Y#6-?RAMjs#9M?`o{ta&ai}#PP#y^Kk^N*kZe`1U?KedwL ze+KZI$A^R8ipc-V74aABi1}}%`2Py{TSLNcoD@y}KV1=j#m*T2DvJMafWQ2NaQHVP z!vAAM{3dz-(Q1mn8}JW=gdatO|0jz0dv?S8H&Oh52mI|PhQq%V5&jv9`1{EEuTv@h zX90g@RXF&KlcS0MnTq%ecfkCgM)5xf_&Y+vZ$^aw2u1uor(^u5Q~b{Z{v`jNKE?hY zMTCErBL40*82=d*{|kU0U9yw#zE!6C|NQvIiU@y&BL1#3G5$3a|33hK&u>GD|E1By z|B;ILUH@N8@xKW8dmjr2zZnt!*^2mG|38!B?*aU!zY7OHiU|K4Mf}!T*#8m5{}SNu z3kkm!5&pS~_}%gESrq@vcKmN0PX05NMHBz?bn%}}@xKE2`+pyf|C;H)3zmhLEB>%rw(f?ii7gGF_0l%-E0r8h_!s0j2ji&$8#(x3Df0zfqtpD@)EslR| zM!Lx||8D<(5yd|R@E0iF|0&#*<=^1eztpVe;wmKk*D3nHi~kaee=6YjwKJgqcX0SE z4nHLx?+q9H7gPLY9{jTY&*MkK7k|p~on-#=Qi^{X;4f<8{4^l{K7P6NA6gjsIs9|8&6LbZSWce=6Jm_ngL+ zn~r~odo|0cuM{&y4p*9%+wU*cWo zUlO+VKMVBEhHWqYXS@gc_P-(e8!G(P{127zCl-A8{lI@yzZ(9V`@bLfclk&S|EQ0? zANcb=QNy4A$@c^QS&I12{+{4}{8KglpZN6q!T%PYtKr}B^X~=z-uYiB;Wrn2@%_Mm zlOq0`qs5=V@4s{3f6>2D>Us+{>K_%um4*4azh&bu3I8EPz3y` zn%(jL<#hc26VLcx`}%K~j{nK`kKFs8Kc)Czh5MfaA>IE(5#9f-RJ{M``u~j-|3TnN zK0n3omFfDgXg${dja^v(_jzfS{eOV0|Gkppp8@{gdpdWW9uPl|&*J>Q=yZ1ei;s_V^MB}Lx%p33|1W$I`~R)f|NjO4U$K2i>z|gZ z;rH1o!+~QJ{lDot{Qj?-DgHyCu5!ixub0dJCg=aH+i`XcDgUjfIR0_-e;dVrgvbA7 zbn>i=&3zk}lM1^@4OBAonhMD+cy<8=MMo#HU{a^= zmz@9eJPsHC{}shQ8~lHOAEyMw&%-nL>tDqARY>@6(jEUiK=J?E&i^C0>oisTE24@2 zDqa7-m*SsdW5xb2oBw$KH;1|ZyW^jS9Q;#1-!5+s_`iYuRCoMiJ*^o3lJh^>{{JxL z|1I$U#Gkl0RrG%|BL7b+`hR~CU;jKv@lOS;m5TYluz=0~7U%y3{J1it{I@}g^!Kk) zHM{da_f!0HJ^n8n|JY63jmhVKSAus!!msWBzoz)#2LJC4$^TJA{y$&Q|0_Pi{{I^X z|BrUMCBF=)A$}^G|C%}fH!fAof2DHQf7<@vN%@}#{@>ahPX4nv|L+*0@z2e=a{P|K_f6{NJdHX8gZU(f{in!S_EOqxcU85)0o~ zyZ&jK#EyRu=l_NLyh2F*e}V4&&!ZIo(H{Sojep+%4aNCSUpW~LX#4*Y6#sv~|4aWI zj{lnx`Trta|9_I=FSq@l_fu^DO!GfY8?ydyd>u{xSM~pz@p%0AIK^KH{*PM1;U97S z-}MStZb+5d0F z{ohj#{;5xm%sU4BpZKZn_{aF0TKuEDF;dSzYWsf|<^MhK|Ng&laT+lH@%&m5`Tt@? z|997a{)yuMF@UfX^Z&q+Z2mX7{9p7(&aNT(|Ava=A2uXS_7pPpodBKyq>-&zT5N0$$4hTK>R0D@wn_Uq zoM%5DVju5ayDTNY5RUH)$4bxJIaLnX8VA_t=lRMR1;;DA<(%v2AvnGb9Pg=j>LuGY ze7v{8sgGmAi{u2E2FaJmV|0htQFHhrIGWmaNg3bRHm;Zf@9WMF*FBJcAkpC0^ z3@850HEjGh@#Thu|5n}c|KBM7_aXmP{9icuQAF!MYb5iZ&;S2S@z3!1zij`{`#&0{ z{y$Xt-@5NhrRN_L_kS7b^N+xPD)MT`_0Mw-|1&q(CGU8Me-fwK*FSf#@gF$<6^xO( z{*jIUq2j-Hn{i70|1R5(i?sjujsKpf@&5tjzwVK0^S?a5W<=w^TIu{(xRKpfcmDfX zihm{?Z&JMfTR4a9|BY|h>;Gc@zFJ8A-$s(xe?#W~XMLrV|ID+$%1-_x^PkU9{!j4a zKiU3|_kYBVe|ULV*T1s)&lmqMQT!i5{8v5`&iKcQX#8`MZv4MY@gD&s`Qj84mudWO zjAG*-aq&M?{12P>e_S#CpU6)97w?Ymf4oTfKM~@;o4-y8%0Ex=T6X+{UghE{r2K!I z?)A^B6n{U&f5Bh5b}HgW5%vEk>&E{J6#p#1O5$HS|8wzg{=nkjJo?~#mHE#$(2I8d z)9HCDufX?zdL91D_S-zK3gVx{sqXcU)y0ng`1Fvr|9@9*{fl<|zfS%CBZ&WGNbzq) z6#q*V&(0m(G8j zgPUCc$BA((d`G1ZX#4+L6#vKI|Al`Gr~fnR+5X=LEF}Jy>H7cM6#tRXNS~kLhG!c8 z){JKT-}qKB|M?6x_yJY_@7fcO|Nc$!&jZ zDW7Z?z;W+=!GfPTdKMhF%g={@-usU5Q|m8*d!DYF@c8dthyUA_B=QzO{F6A<9se2K ziu|uXMr!_BJO1CJ{{Jb&e^ED=r?9m%<$s^dT(R< zKg7kq$*-#lDgSRGIsUun$u#l*$29Q|$L;tpneN0T*_wY!6aR4Bj{l`D{= za9kMwaC}JPpY;FlQ2rNs;$JrZ^Zsvf{XZ{Hd;RA-aqt7$@&6&k|38TTroV?1|0tsP zuhWhHeu{rCnA#Vo*!-FDU;D0H{6{qYm5u*Po)^b|@*m>(KM#)E@!yQ&pKOyaisS!Y zIBv&(@A1xffo$7e6371&aNHaJ%`2RBL5Y`-&EE>@<@^5yaJ&M_C&xSR`x|KA}w{vWdYfBWvGbpJas zX|L?w|NeyX{~6@J?vV1I6;b{>MK}Nbm*SrXQ9|;cZ2!mSKXaJoKZyVJ?PSpV59j@l zt)-(=n+ ze=IKk2l#SB>i;%{u*{`DK7SbI7LhhTLE@i`e?F%CFZRU0Z2sp#nB4e>mxty5+VTH2 z#XkV?-@dDJ-O9H&)A*l1-;5~!8+7CU8;bvE0O5;M3@j6VYYZ3v-24Y`pRo9sjsFDh z|BacrAO6z8Uu)GEJ3;?nagbd9kJ9x27T5oiatkkH`~RY=o&G;LANT*~W$6FT3#b3@ zy#?R@_=@ts1meH7H=O>@;^IHKW*2tc5>ozem%RS*_5Uy&w8wAuAnFT<|I+8f!H*(} z|CPG&{{`j05^O-?UpD{q@o#*`j(?$O_AeykKaMi(_+OXC|CbQ|eIdoa6;b>*O2x&GCT{{rg&UqSqvFND+o8y7}{ zf0b_hZ%FYU3ncpD6cd|i{9n8qJN`F}b(wtN^N%dWzpot;9~gH1{|1!*lkDsN%hd8e zZ$|Tc*8kgH=i(|P{_oTs|8GL^e+}{9A5#3A5yk&%-S}UR;y(^ZB=Iks|M~d0xc;B_ zkFc))Rr`N*1MdGfa`0Ddz1$cL{eO`u*Z;S{0!-2TzsdFgq}=|C+5W%a=Z=2i0(||S zq5n7a`~TGQk8NXcJ2s{K9}gsTC_ev{Sf3sLnOy!)p1|dmkm7%H`SBl%e=Car1im51d2g^K>~;@_6yPXc~lJ27#Y{J&&(7QdMn&G=6n|27o=d=GwE|L5@= z!yJG4Se*a2qxcs9ev9|hfcy_6S^m*AEdO=DeeCp{v9d)#emh<&Vcw!_hkLwxR#B7Tnya|7yKhA{v{s#vi|SGpFdpj zJL^B(_n+)U@z((UlIOVVbj(;L|L<7B@^5nZoB47>;(se?|L5@UO!3zOR$n^<;;;A- zi{Ik#<6`J0%lKPv9_w7U-mqC}d+s03$p3m1=>K1I@}KtopSleGPc6ajjo4LqJ;r>@EW2KX=P35S346h;2ksSTt_ z_;>sN1m*u^D4|91{$KKOHvWxuSo{TJxp75E@xQfV{wur(^FJE%KX*<3cffyLNc>xh z{G*|d|CHt3``?>;_=ov#-#j(;s!aVK?|fE7_rJ8~zY8h;Z(#nru9)*vMf@nD`R^v_ z`ERHHcjJFoihn6!^~GsG{N^||{!K3adH)D&{#!Nvjry@pKRd?3KlWUBVcDke{MSn% z<^Os%|M~D|=|BRne|6)3V-NqH_?PYfc{nIn;(s@a|67Rvfq$rt|9SjYMDc&BZv2m; z_?H0)692ON`{F;M`G3{;?|XQx6aTwA_{UzgCO;qIzdNM(w^ZYQ#~~m8r~3cmYw`U5 zSP%aY{}pe9pk9cj?~$-jm}04&uLfk8t{b<0AI{Kc64M>irXj=i}ev`hOpr zS&sky8^=21|9u_&x9_?(e*=jBl2=0N|5s+ne?EiY1ILdU>iPea<=y^&qKAKo{|C0ZFLlTNQz-uRpiQM=J^vR`{3FHqch`TJ z6#q)#x}6`V2jsuvR&M;y=l>EeuZG0`c8cTwil?yumpS;Ge|l#A_7ML){o%yFu}ZD~ zMQ+s=6~Wnqvw)gAvEir;@j`Ev6g^6~Gie{rAx*=*xf{F|0>&ZIRDA|KcD~1i2PqU z|NR5|{}B%U=5J_?rN$FHQsE@4lUj|A_ckj(^hs zAMN08z7pl{2Jv6|aX8mM#zPtWAKTTp85eQ<&+_o^iGSJgACJT0@;@&R>-tAE{@X4X z>%{*t6#qsL{~c38n*WF>{?FBo|JfA(sX!8me_8(d_(u`(uMq#Kkw@DDnEy%-e(?Y1 z8R6uA#O1%{vxnyW-}fqxe@idL_)nntH?}RaLpb=Yi2VONMgMo#KOIZ)p9b&?C#vCZ zxr$x?VC>D#f7I~hro7OX6{QbsFF*ce{lCh=KlSIE=bdKzKlW4Y`Ttuo^ndB_zbDuK zsrr9g7xw=o<$n`sQ)^h)f0ruam-K-1CH;S>zJF#N`FY;WeVZG`f1H1lVQc@p3IFSb zt^F_YuJbPmTl-&P_UCzL!?qXyGu{Jz``-}#CGh$eH~$|``9Iy`|FZp`uesMo!@sKk z_x~CD|3Zp?Q}F-Jso{)&%!vHISkgKGAB$=DN4;|WpDO?E_^*cYzd5w2V1(NEhsTE^ivJ50`FG>Ln&MyU z;a@iY^ZX+&{(1X^b^WW#zdQapiQ>0c1|&n`--?L;ixl}UC(r-XQv7EE|0Vz7@-!wc z)BJzo9_;wvyq=B!UcTHk@$d7K3eK(DD=6_dE{AUCI zeKXbYw~lA?Ke~a@!+@5X;U#lJPQsq1Pr{Jei#5%GVSBL6j);qiZi zgTL&N&GXK&`NurT=Kr2U+5C?bum6$c{Ff^KZv3yL{BHyNm(K|2`rl|_{h#-bu*SbF ziu}9re+tF_QxE^L`Jd$(Oo^r*Pum_*pdk zU#-Z$8~|4V^^lU3LM6x}`6>Hp56_%8zgH$LF{set(TcB7kF z|L@?-4JrRWsM!Cx{{K^oe+m|MC8BaqAy>{|IaR ztL^{iIryio-X!m0@PFc`y8XYUI{trEuK(Be|MMyTBfLh^qrBLDw|qW`<^zc`oT zUjt5R@#{3P<7UeLMO(7Zzgk@WFWQ^yS3}BwJ1DOIbo2i?6#pe2|Cfz_KE6%W^`Cq} z8GdW~|AiF)&cI1xB*#-g{(a57obCU7@{styM%Vu@qWITBBYl1v5Pvy$|J#aa{fnyq zC+{8WjDIem_%8+jPktEA_{ZY>zp$SxHzfWaQXK!d^M996{0V4N#|`25zZsGLU#si? z%@qHc9{-okf4u*jx#ItqIrz(#Y?*f%_&@Pe-SLmXjsJt@KlHxb_(#?M-TBWJ%Kt9l z|H&J}@qZMN|6ix*|L*hOms0!)NUGz^8f2~{r^ge|12QU=cfVvKgq5C zFck0q@qU!)w}Stt=D+$M9P5mKE~of^2L7M8S&jda{n+(S#%-+sTSGMdd027$d7sqFZtqKuvYH5BoqH{`}Ys{Ze;|NjN$e^>CyrjV|G&4~Q}Mn(U3=l_3B z@t*_!pV&t&|MhLnj(;rf{l`swxgo{>j`HIlHveBm@n7Nbf7$rw{U34pf2i`Gvj1N& z*6IJQqxi=FC&fFf@z3Kk-;E~!x9R%-^%Vb40ff&_F|bVI|1Oiwf2QjFZ{Cm@eyjR_ zX(#6YT8jTl@c+7xxOtj@_*x@Km6yLiQSnkQsif`hUe$c>HshgMZo`TjsTb{}Vrz9shJLV*MW}&i|ti%S}^8ecu{onom$DI`a1>kEfe^-nD&PnX}$Kclgq9Gdpj8q)| zxcUDMivJfL|Cfz_pZ|0D-xtQiCI8<`@$U(3YC0jL`Twif{%@%8->&QbzoPgrghu-O z6gNE6_^0(@Hvd_i{|^;@RsVOte|QhYe+~FQ`b2H~)3-4j|L9JZ{~o^Fko^DG6XaIX z!ut1A&2Ij`kK+FkNP0uc|7Jw~e}}IB|B~Xr$m9RA`H%O1bJ+U7^ZY~kSbY6|KgEAB z;P2u4setisbh7bpa_fIeCUO00NdCXGbpOZUf0*LG1hD$r84!Q-R1SYc*MHjhAENj# z_28HFe;&WZ@sG_&H(BPt?cCj*>)%Hx{>z|s&AgxD7H8`J5|6U{8wat^e^TIhFC_fC zDEfcvZaDsbP4Txt(|Q&0x8Bb7e}>}qkIzmS4vbR7Zx& zA7lAP5yk&#Mf`mP|DzQD<$$$C5q||Y|6@hO|E`Mon@-r>iT~eH{8s?}K1KWq&i~Db z?thO_#P2@;@)*T`CEzzp)%?Gl8~<7y{#L%+kn-Pdy7+%b@m~e_eeHx}_Fty>Pj15I zKa0En>y+a8f4Jc9r1-Cf<`Mj|{XdW29On4l_0PYj_(LgVG;zp;A;-X!q*-`)Q23CjO9P)f<>&i5br z0yD*b$G9CFdtyb4g(`8VeO4-WqGcReeA9Pr=ziIb;f?|<<2LW=ww zdqu;)i~mp9|L2~SUjq2cKMe=JrHa2~sPQ}VfA0GC2dV#$gFY$obU5?hD5CklcIo*) z$Nx(=!Poy!JNU=!bbJ1Bz<lT z|M76Fi1@!#n*V~-`sdaSG5>Ek_%~d3TmI3&e}A(x|1X>W%=6jnfAat}{*8$Eci(^V z7s~%$z<*yz{2N!Z_dj_5kh^Q)({>NsCCxt<|9^Jy|7h9m`6mGXE#HI`|BqzA?;_xK z4vr}P$@;JVqx_cu|K_N0;@|u*1AeG0jK8}T`7gK{$Ny6f{--}ZJO3cye;}m(-?&UI z{?Xpi@bC8jf2I6S08ToN4~hSX;{TV5{3r7<|Iax1-}>+E`BlKb`E5AyZ**qx|1{2z zqKf~nvCj2MH|2jK@ZWhtIQ*lC_`gSyfAk3E|L>Up8F%C_1pbpVoa;Z?{-3AQROH_{ zWN71msJ{P~`29Od-~U6P7wz}|oa-NV{PQgJ|GmNgtrJ7?|EDsmfH~%5U{D%&e<$qAReL}*2+XT%2ibSMhX0oT!}wpN{Feg%J@doK z|HfZ3_&?MY#@_?F{J-Yl|K&Hgo9#Q%ee{FfKt@lUUV|LyB;&7TAOC%$y>>yG~n#raPZ5&x}wWBjjE z{tp2DTaw}AfAeY9|6TtkJ0ZpYL(=>^*S|e~!~Xv!#eblUe_=TOZ$*UvVMYAKf5-U$ zP4OQD_{~M(;5Yv-8vY-V#_!z!aMwTlk>bA=eABm10sCvF`+td(+3SBRqV=z;>mLe7 zuk-LPyZ(vi z-{hWuB5BXvro-=^5Nt=4fA{&X4iA10|FZab{;i1ctMc!z|9hL_zaC6p{IXj9tGk+B+>FI3$@V^fI z-wojZ#7|}Wzs_0~zsdQ3Q2eM_uK$zu{{&wD>GI!4`M(hwN%)t||2+Rl5x>t)84jrO z@8-Y%c<_7pm&NbnKO+BE<==h(=lc|Y8`!$y0JZ+Fq=a4ni#Yu4e7PaT|DMwQpY!~y z%l`)+{J?+PWX0>>E!qCh{3V_zA^-iyfT@a(N0zY^L}(?qTEKxQESum3+A& z#s80_^S_h-T>d}x;0OLI71#fjZ^PoZIQ#|ty0Vb)|5oz)2k!r-)_=SC|8t7}R^Zyl zQ$YS(?q%^C_p;&YxDm< z%KvR1{$=wY&p+b)pAwJvvdq65|DSpAd-#{d&+~6aCg=KpUU{4YTMzXSLuJjv$&%I#VF7I*zif#bb& z_%D#l|JwY2Mfq=srV;*S^B>Q@G0gdQ^Z(Z#{2u;g@%#9X2)`=-?)yK#qxkOx{*!#3 z#_pOa|Dy;0pS<$`tE1@t@Z=g5J9g|>V+^rkG>U!g*s){B7O`W;nzducPOPY(iXA&@ zV%8GHjxA!xl7z&D`+?fy@W|FAjp=j9B6KX?!L@1T7;A%EL(YX4__Dt`k#uhJ6#vxdii zr2pBF|6X8?c}mD%a-zx~5dUH|xUj@;>RPYE|Im|e|8F>6<@XHvea-%# z+W!#re_zDEZvUhHeM5c>NV2c={qy;cy#M3u$bUcl$$Q~sHMIL5;V(h{2Y@xUoeBA?P9ph#MCBK&!Np+VpA-2XjPUE`pYjL9KZ1*|W*R>q z|K#~kb0PmjuxSC!so2~?`Oi*N^B)lZWgC;avczAZoqxhV5AwGGYiv6c^0QOa{QEDt z$$x78xsm_j2)}OrDZlsVVCCoiPv(DKuF9C`ftmU{1g8jbiJ1HzovHn3IF`a z|0uA=wlg7r`SL2i=ji&+)co@y|6>t;-TYI2Hpuzq`5y})|Kq^l`8Da&3H`Sa{{i9e znnKoVDgUDk^Dp@qME)m$HMX4z`O8*N^B*|6{xLOwDe^xV;n&SS<@W|TzkK~`A>?ld z{^~PGP80g?CjLEo{o9#jy_WL7mSO%S|02l$RF0KyXF~qEE7kdr_o|!mKQ;ft$p3VN zUpN1hKcN1_^C%ZH%|AK*l|ladBF8^;`RVZw=4k)N^!SH7{yPWq-w*tqhVOqV!hWtP5Gt&CDH%G5q{nJr~Co&AC|pb z&Sd|Re;MR|1o$fruYav2$3MJjYX9${>$SxHT-y9E$NBGs{67l(;dbigzk?kAW2XKu z(aXOnzx2N>`hP6KubY3$?-Tzr_u&^a*}vq^BLCyS-)wmOb9;l@|5%Tj|Efcav;X&e z+WfD;`Nu*2p8)=FJ9YEld8*1E82a}$^KZ&8{V$LHpN#P9=AZI=#D5rjxwMr3)cnJc zza9AdXimij7kd4tVwgJr2`K+z#mWB*Y4bmv^Irz}e+u}S*iPO2x0B-^KINC<#TWhg zzf`aPoAS&2uZaGij_~W|pYpTmYX777w(fte&(H7w(HY+VVhW!Bv=KPzHSGVCFL>Pz zf4lbmFF1eC+9UY=h|1Cb#=zfVSpSsYd&3R?Q-=H<@2fuZH}a1An_E{=gCcvxfZg{*S98{}#YscetJWd!26lPc-D0 z@Bgv}@^1d zH{_S&-zem-0{-%&?C^W=0Jgd-Ox+!uP{vkb4~FfL+J$k$*f~eg%(L!{fQ@CUQUTy~o#AJNJ5Q zQFyFrB41Cq^x^S^;qita`Qza-fXCN`wS? z^WU}6|F+=2;%H0xf7ea^Cu#Z*`Q`Y(4)SjY{N0xL14sNX8S=~Ve_iC?9{8J%vE=_f zH~wGN4a?kTb_V~fg=OxOy}Uki`~D~V$W!}} z5q$su6Mp<>>KXTBj)43B*3D+;{_mdQ{onnf-~XNPug~+}v-G{0qkzA9cRTO@;~Vm` zP4$j{>JA3b|MK_0kmr9ciuL~ttgQS*v->{!1IZ|I6Ls z`+si0`KNtyZ{}F=Up|MO{0D~q{i6Hl=fBJ2-z!D@!}0Gn)8k)95&vaFd4Ca-YY!#4 zvgH3o?bko}{73HpRU-cmuua~vcE-QJ(fHS)IsV1!e?#OS53XW$D*P2X{@Y9ZGe^h& zQ`i4SoPYWm_hpWU`fr@mPW`i|3(SA|X@34@#qR&S{^j|P8*~1%;q|}qQ2$|_>c0M$ zy;^wl*8FZcg9!Tj$C_1|l${=N4L__x&mUP)X3iy{AnNd4=+{z>cK zf6WcQLH+0FKl1&LHs$;)t#*IrM5zDD58}udvkrMyH+s zZ^`+meR6;16sZ3mOZ6YDP+E;!h{{_dA`9G=u zQu?}@CI6GO@BhN*|MK|X*2rHC+thlTS^nwsr z_Z^-8k-Gl3;r!Fjcp!5c)PL_>cE*3-aQtUmx~YFT|KFDLp9J&&iBSJxo$Aj2+pbaP z|30aIS|9zM|Mrg_ziIu;zXkFKk^0x2|IzwqgS`G5 zR~W&MPwl|@dzOAMa~9Np^*na!KQOKTt@QFAtE&PJgvWp6{C}&6|49Ao`lt2JX1E#u zOzU6H|93+EU7-GJPq0(}-Un{@-_Wjqa{rUln`eW&Q8W`Dc9cVCEdC|I!*eum7-T3i$7*PW>v!^}l1pKh%Ff=jjRkmz+TS z->dHb)YJ2-Ect)QaQ-ik|LuzWyTUe=o@l5314s4$X4?AS4f&r3*ReWH=)d7wb^ga3 zo&RZC|2-4M`#wl(gY%EM`4sj%)PGo~y7T|C z>s0^V0|okDfA!y_$Dg|X_r(0~2HO-^s(-J`kiVaCp}&XUN?ZTc$p1p5{&nYnwElfE z{>QezKmV~G9QXl)`p+N#uMA)R-;48){`8^D1yKJr^V*sJ`-b(;w$sc1z|T(nyRrHI zE)oBc`q%YO>pyTb|2M7wt`Xw;r+turcgSS@NtVWcNA=&Cw*G67|3!#P=~y%VPBQ=V z$@pJK*K4W%*VUi@=j*>?#0b9szaQrxab{cQBB=k``RvqxU|9ct(d(a_|Fd_*Kh%HL z@cjRt6V>^@_l-LKb<*`(^8d2o`9GzL3I7Km{~oYSt;cZxv~w2P|D`|geW>!&@ArHB zGxmc6Kk#i2q3a>-vw?KN?TTjGD$u>R%w|A!#|%K#D3dAa~AH2zoYwFK{{;S)iw|E%}P^J@} z{yPlk|IIH6|3@PKUa(F6DI})}^B=}OTn3Kn|FUfO7n3dF$JOh9jzazpSVgQ(#cB)H zfBDJk{vUI6{jYxgi|e0;3;#!R{uL%Xnz;|^zss=xgZI?@2N$caedexsyqMhA@v^^j{m;q{6BU5AB*|lJJ*wzGdus0`t?3m`yc(jt^NPY zv#~V~_yGL4TK{#({|fwOSpT~7KU)7j8UJG&WvTz`*FQP_bwq?el7C%(ntzXsf5qZY zo&OV%e;;sC(O_x(bCmxpAkaD=@Z8I0uNn4#>Hj?Be;ZuKJSFtsOXk16qwC*N`#(Rz z5B_7G67pBwtorx9cQgM>?f)F)e<$K!xBpT9Y*z7qZiGMLUzeZyXM^0oJpOe7^1loI zE6yc-I${26_aU$UlIvd@>3S{ozYWv&{|h7h;GY>@|66yE%I_2ZCG@&NOZ=}J_J8UB zV&s1h@ME45`e&!B`#;Rl`Om5SUlQR5|1nPq`P*($`#<}^P5)2rzY+Q0kNDT^f7HKE z>R&vKxUiJ})c!Au@JIaX@>Bl-sec3)Us>We^)Kgtmm>dU*tBlir^V(Ln*aBb`u9ow zH=Reu6-)dZrS1QhMfkygJMGg6`5VWo{m&=$Uq`Piv&8>~e*e$^<@TNt{QRds=gKc< zTsk@P+WheTXD9L3zk{jb`yqb`%Xn}z@_*n%JT&0K->$&%Z|~oK-GA84`42MxP3Zpv z*rZra#by@DfBPB4zoYYiQ|JH62tVXMmeYj%Wi9IX=k>Z7{|xec8bcb^g!D`G4N| z#ToxLPCNcx6X6H{Wro*3_WGp%k@~Nu*Hu~a|EB)gNJuZ!?U{Oj^l z{{g9g1Q%af;@9`j@Bb*z|2`G@_k(R}I+gTkvAKo%KjjM?o&R%Xmj2~|{|`T&?|<_3 z|8dCw3H)j^9jC89sgc8az^1NE=e_q=8&+QR@$bY%v^^cVgtMecB zlj^^9S@OJE;_pm5|G5kK4}@*1x|?_s;VLx#(+mcV@_#J^TIU0PT+RR8$lnbsise+S zybymAIsVHW@u$vzYlI*2AIoV%{<;oz{^OJUi`C#_u;l+9bAUwNOa z^-sTV>-xv*vavM}_yGL4n*aYG{}=F^Vg7Z;f0}=v^#9mKS@NGc|93|CBl*|mr}_70 zmHgk2{0D=R>Q+nr-%nwiFVFwE7x}-06?I-@R{!4F>iF-I{@-{BS+Ax1 zZ<==gb6I-+z&e|BmWEb^afY@I(G%IZepl^@N&#|KS4Xf6V0k zmz0g*$9Wz>{zGA#O76AP{~hIj90XeD1Abi1{{zVXHLNJizwY=?^Ur3L{684skK|vM zpXQ(a?56*j_J5iG$B};wqDx4=7>La{-2KU zL;e}fX+r+CXH@=x=3lHwE(S~fpF#dQ*rxjX?d0G4(oO%rDJ!4RL|?@6{{-?+gEfTt z*B$?9{(aK_V;g75f9m`{8R3uQUzeZe-=9_T|19z!o^$dk8K;D}Lj8~W4IJhF<}Cfo z1OGpq|H#+B#v^|Z{Aw$mr-;=R;%_9c|M;~3H2{YX57TMAmDG|J}6npXZSO2-v2E2gr6NOXbRA(Ne! z^3T3@!+&d52uiq!<$ogb&&aJqHjf3mik}n{J)I+ zN5M9AJ!q-_JIa4cHulU8_&_-Sk*|MELjG^yH){<0f9GU!{SO)c+UR;M`QJi&{=?7z zmB&9`MgF5gNJ zUq}99z<*h{o&6u*k^kGXF~tKu5cA)G{NKTEhW>T?KlLAw`j2hYV5$E%k^flOChuWO z^*_~3{oj#|J+lKo5c<#FEbf2&2J(LozgcpT8GqZyiz(-g2af80tF-;U6Zz}Gf3GF~ zo+JPNG4$UN`hOewe*pjOSDN*|>}Trh|DL1%x3#u^e&$`x5+itC-$DN4z<U*O1pm7)LYD+T|1$bUTeuYS~ye>Tlc|IcLg z&Lj={f8WG%p8xle|3~oOZs@=3b5j3(Zuqw`^v{+Y!TBd6{|Vr~>r1o#2Tz^y;r;H0 zpJkOlTkt=j|FT;}{y#wepWwGkFE-16Z@22-cjSLtL;uxF3IAQleVNj^zsMTkq0oOtm*D>x`G0}mt23 z>fe$7$%g*BLjRv4|9`=MVCcW?lO>hD;XCrbqqcv3{I6r75qx_;L;h31f87&y{IfsZ z)c;)C{`vW@EyGvl{GTKLui(Gz5;OkVY3lr+k^I-w^}=&)<6|d7|Gkrh|8C@OfNd&! z(u|+7_>TO~ouz+y;Qzyq=g)tZ{=Y!}-{4ncp2X@3jsLZs>iEyDb94T?ssFk~h5s*+ z|5WhbVaY#RYN*l=V^%EXe;yF3^8r7u`hN@g`(Q<(f8FE1)W1*aKemmQ_)Y!$>k0o~ zBmZfzO%3gK>figHoBls92-W$3AJ6;m-A&AYzC!-rVMX4jX8bjutK+{%`d=?yuO&!Du2q1pE?K}`JWGj>U_YDtNy1U{~xfTm?yFFLjAw)b@lZ>=7`_a zf3UIe--G;Tfd4K_{=L84)c^b-RObVJJnvt=|K&@_{|%h~(M`|O6Du#|zwCL{zemo0 zs(gvmm8JTBPy75o!v78Oe+&Gv?M%qu`GU$H9OA}*YW`P{|GNmk?)Xpned0fs(V6VO zd$Jh+zD54;fxqlmv*W*AlZb!9-&3Ugzi*g-$^Sj_{{Z~4?M#^e;4O9j@BQi~|Ec-E zL;l_fzi$31Kbuwfe?a~pf!}+X^y!5D%X`%Qe{WHB|F4;@*HZmYPMiN9k^d*)k8NjC z{N|+FUbF2;BQ#P?DZeksg8fF*-iet((?Zo`F{oemJYN2SNbjKe~$P+ z)aEbE&;R|`MgD(9{@;MV;&-$8Pxf8azwapjAEo904f*?kztNE2|3UR1IO6{}Eq@>K z{|@|>f0+4inM}sN#og5ZC))gc|F3IpasJEi$o~iMSHEIb|81qJf8SC4f2zsf^3?(? z_Zf)KX|T+F4w=F~4}@jzvqgM%!!q}|+Eo5Iqz8TuK5NCN56j$Vc5Kg(+hNJ3^UqCT znfts=e0IY!_nDo+KWkx``}E=W&VgmO_+;O}@8>>?^bubFP`Sua{cry1qnQWi zgX13y@%*=3yMl83egT%ruz}wHiROPof&HKU_;xS$`#V!@%FP zuo-{Z2WtI$ru=&po1Yy2oWl7*E&CHb!{eX2^Iv-WGa$#mW4bNv|L7n832-A36Tt_Zb;iE#-e_?bm-u{{IpA z-|z9vGm!u0Ma=piebxih{O{!^|JnJ){0B}SE`^QH^}n;gN%zylQ$qig-}}43_-Dy~ zX_o%wf&ULbuI7IT^8W?D8q29zU7`Fpy`zqQzN7j#%|F{h^uG+}A2#9f%tXk4@BViB zKYO--|Nb=X<0k)oTMGW!(EnJ-WaTq<@*gkhUw|DRZ3{Es~$;(>$Q zH&0B>%eeADVwQtK@%ik^f7d%uLVCf0nS* z{{z$fAMGapvj3N%{|g}hZI<%SGH&vJreXf&{qGh-{@Ee_HHQ7aW*PPT4@T<0jjq?y z{AV}A`A^F}qW>?+`M+MeJ@YN(zidf6`DcOQ{J-8!{$>AP3jJRQPHF>7{ohgk&q|yB zrICLQ$bT%SFeK(a3eEpIe^lo`0m(mKOXS~~od2c+ME;lI{8P4X&-6n6>n-KqH_iWX zZt^ehf3+<7Zv-c$&)La8o6SxCza$&URDv(V{{7MA{P@@M=>H?8Apa#_ znALwnR-ONNWc;h8>$TMXcQ>5>)a@qnKaBHl{YHD{H^_h2(suICo->>O_$Ro@zr6qD zis=7ha8m!gng3Yp9qOk4UuxL@W&VdF|6Gv&SWX34q4`hc&+7cgb5#EZ`OjBg^OEJf z{zoAHCGedNOaA>?#s3P(KX=5x?)Xpr2c-YS>SN~hzx-dWJ6!a?k;s23e5Yn{-v8+K z7Ro>Uc{aP7`rmg{>@N@aKvtapR9P$d|Cm!A|N0ZI|7bG2{-yM5QvZ&wfB8)F`j3#m z>+6+x{jZAt{|Ef7rq{m^e%}%Q=cfGO^*^g2|6joG{b`o}@+qqSz!879A-~N3>d5~$ z@HZRsHxPbS=BEC?Fyxo{UjzC70sdY?{$9fGIpY7)lt0XW1@g1mp>@7$HvjXclKeZm z{_QJ6ewqI@k$(vA*BJ8G5q>t#P5!?&P_{-5tC|5FV4gBfD{ zTMPMT1OC4Mnf3pQg;oB*5&u+8{$gGK8EpEC(eG1e>ndu{Z{a=gZ#4tf9dOH^BjW&SIXe@@`9{>!ZY^$>pF5&sNBewqLEkiP`@14I9{)7AV3j`+VZ8Ad_HRPB1-vIgN2L7@)%=%xjh&ulJbL;LtY;ok`P=LP=Qc5?iJ{4Kwb z`ge5vGd2Ip$Uk3%U-$SY<@W|Te{1;q*T%>{Kk(PloF??&FE{+w>|pPGL&~{Y%TrYW`V?>c68%`QOVh|B`YHUB>G-$2)EiGOdy z{7e3AkiQK0W7{co725wP`$Nrtu>4T|`f5zPUH_^1tB`+*2)}OrDL3S{Ye;>pAOaASVe<|RPZD+##*ZisG-=D{ge|>&_{9hjb z+YtHZf#W~*hR1(eW~lt0qvK!S8y^3W{!14f2Ce^+{QZw=J`%5g?1=pH zg8vRf|K2yM|9~9-%f3nailzGh!O*{)|LuVM%Ygrisbo77)_=nqYX4*Ns`cMU*K3J? zU+w;Gpw|8M??f8G8^{riske`^0bq5tI~{&o4Of1lKUvGT9)pCA7(zfrvZ z&o0Qn0Qhg9eL89Wzg7FcKTMtfchdD*s{dZY{xA1`c18Xy`0u8DIw61g+G_p#r2Z?X zk#WTm|9;y2pZhNzCj9Tg`M><%Bbie0A9~X5|G{^v|6qK9>p%MApQ3mDM{56jqW|T= zf6P-t{}t;H|MR=)|EB(B{qKhS3r76w_CM;ME#-zkwg26be}#yDU4H7H4O;*F{x`K- ziuqp+@-GDb%ikh>Dq;TX>ecr@^&R>DQM>>1{a?BNw-@pc1OH95PbcIrtyJruU9aZ9 zhpxB3{wMxk(#8JT{h#w!e-PT`|I%jsv78imz?5Ge|2P2oSAzU|J%;^%ed51Vfa~z z9}_#%>YwlbR!tN8zlWm#GVouy1>7Mewy}lJ|7>no=f9pK|Nk}gFOPp5g8U=Fe=qIR z;<+eP|Fwsz`S(fvS4}5%Wyyc7cK=^wo*a^V|L4Pye+ls4XjuPM$Ef^l88`L+Yg+$x z$iFi9k9kVy-y`!se<3&grvB?b7xjNQ@-GSgn`So~{~PL6|DGfNzv=tWS6=B6V*bAh z@?QquX|r_y1JBXV#UCiqTZi9c|}Z<_zwBSrlm zi~LstfB6`*{zv_Kj?RBI$bbI)hxWC_`~TG=|5d=>A?|-jc?#vfy+ZB(0pX9WH=jcK zSM>jXU3#uO1$oY@4^;+UTRGVL%|Fy2@e@k zOZ;QB`T6S~H6j1W$UhFY$y?42KO^V=#nx+y|1d-T-U*`qPeJ}0V4JG4X8biwegE5l zT>lqauOM z{!?tdmiUh_ek_$3N-u4>o9ze~|unB=Ro>$3MI|%;x|8c=h|2+-)Z-#BES%GY)nAjAW|5gqs{g327wq8s8M~%|klg^6y zf9L9A{67NuSB3ny(BrfT`J3tM9}BC;|N7{9E%6_yef*c?{|w|`8uA~@X+r+WXVv@% zB>!SHxUj^ppZ}8lUzYvzEd*HEdL0`zw*fWkL`55miR9)?Efpf9!cG@W4fe`R_ek?Ek@= zUWfc^;)WdA=9`In32U$_2g z{yozF$!5SrBld{V1E%>8>O}tGP2WQQx4||w)SK=9(2WmB{$uO4#DB5j{72>=-t;Tv zuYml=aw@ueB9)_@OWMgNoehd2EV z`PYo(U$_6!{QHjP|N8kC=fAaz{KK1`g#61x{u{P7^WQ<||I4|l|3A~_AKvsM#**|MyA$eUks!dM)LDeZ%}$9xeRCn;wPyqagonbe@v1{{{P~_3xAZU-B)PS6Sje zxMIL^k9`x)?#v(mYraSD!%06O{|dSOKi|LdmBKb-Uv@~;K?kL5IB{@agJ$A9*s8~>^E4=4SE{KFvs zore9t;yE?{o}>Q%SK9o;Nk1X~osh{+!~8ds{Cnj3zu0;$<$r^;`G=D}L;kfR`PZHQ z(EJB44DS3l-6#70HORjrB}dy_WJ{X_)`|Cj~#8^cM1uhWyvkc}l|m?;o%F_elS5r|Y%Ee@I1aiZkE? z;rvJL|H4U6A^&j5zi*iT?3pTm;HdxqlQ#cw(o@KPH#n&%H_Ja;Ma{oQu78QG*OLDY z)8-#edJ6g1f&9mEnlS(MH_7@czp;P4izB?*GC`Pa*$GkpC{j{8yf(=AUKV z^na#({EzSduw%shA5MA-`CB2A-ic=WKMi-Q`~k^-Y`vE9zh2t>!%43p|GJU<>&|~@ z{sXfA8;hfdve{~>Af4<|i@{P%#9Zo~dxw<_uX zuu>V)n<9{ou{V$;FwZwmDMXa(0d?1|v z$o#{Lo*{oZ@WpZ}R#xcsuiC}b`u9ox zW7}kj-!%Vn{}&E=hx{XR`QOHD{@eC~di*DFl>gaM=AXeq&yfESaMEKb|DL1sUsC5E zPI?OY*N^01cm6~3?+x<&%lqHKL64AsWypV{Vg5@i)a&2aZR+?}tok3Spa1;pAKuMk z{tr97A^)S0|K>9+^?zsik3F*kK5*0;>kSz_ma)<`IcK=cuDRZjMaB+cou3^0(7Eva zaOve9hc!ZJu-xO_pYiV>4Udn8$J$C($UlGK(pxL{^Fv^;O8HKsoQ_XF{G*Yo`M!)3R4y!&$gc({aBB>KpT@vn5O@V^rGzx7}3nLp=) z@n2m36&wFqMr-`{o-1(w&;GXdB)#+B`ddwZkB9t?z2$jt?0(Ka^`@sXe*u4wC4S$K z-#^(6f5T1U_&2=h5!U|(5b}~$%;vu>Wd84yhhYJ4> zaQ>d{pUw=KAKw2}T>q3d|AC=@c1p4R^W#6g;qfon=?(p_0^?uhwr2CcvPtUv&s*Nj z_&2-Z_$TxKAo6br`H$sP#Hi5xzhQB8{?A6Z;Wy2HTb;=NL!5v1PoK`r2Kg@)=l`b7 zKYQM+|N9M&^WTR4SB3mHKWEne+LuxN`;PKIhkpL^omb9(VW%fo|KIHUOlEfQ-*GJG zPwU?^^v_OpVHms|M~g9y#5Ie`h@%&L;v&l zH|ziH^!z6>{#P78)@y0}Kdj>4$NByq&4%;e@c#FYasH{FJd>F-mw$2oYufz#hWYo4 zo_~J*WA~Th`me{)|LTzc9>e_iEvxpwfcC!^Nnf?(za(w`pFsXiApfzPiXasl|C`DP zzoXYbQ|JFl&OdGG@tL_G|5E4b@>&u zZ^ZmpMDnlgpX8qn^8Cx|Kb}JVO(Fk{be@v1{`<)JuK~$_Wo>chKXr!lpQd_|{|TJG z=acc71t9wNj|LpT*|EFB#51&W5v^4)S$UpzfO=ABq;QU`NJt0$? z>;K~XkF@#s4f8LbpCWyc75hIj|IeZSQIP*wPQ`W<%6~n{KU>?4|J3;(kNlfQ@~=Do z(fqT)oB#a&KRcqF_qi81|MW{IWEO_}SB~U;DsBD))BJzoX8t4d|1A1nE0TX*|1|#r z>Ho2Ew$%Sj^DnRedmj0>fc*E+c}l|iuO;Wd`Xv8-UlnKn|8V{JPyU&g_y2nl`PT;j zy>y&T$WQ%xj{4u+hU35V-+}yFg8!JOg#4xC{2w;bP5;;RPd&N*f9(7@Z$YPFne_lcVqapt-+mm^!*t$aFKZWoe<$s>E`JaURTSfA(+y80)1JeKK^JDA&7rOZe z|1iqKasC^G|8{=-=gX^K%q#)l3E%%U#?MOs_52TScYgj0%aTkrSkI)?@E5( z!AJKng6Wl z|ML3RH#z^8!zN{x98Jk(r2lt)!~1{RRcimQ9mo5Br|AFetbzM~OX~j5 zU;pU|?|=CY`mcoicXp8d6cOA)^PlSV)&B31{MYPA>dI37=QqrMZ`l9eMgDCd|5XQ( z?M%qub*`F!Hpxx>AEljtKK@laQqJcQlaYU0;O{f!Z#rM)_lFN9^AyqnE%`r2o1f(W zW#nHU@*n0jHvcPd{Z9+YzfbZ{=*3=0>{0CpO!MCr`u_m=w*&v(my`2U#TFH+|EddB z|AC|af2_8Do`3IJG5&ps{M!S6^}%NKU)iYgvz6V{f4w1p({+OXBjn!!_{--1_x+hd z{#!0m`8`Md?>IyL%IgLH$H>1U@V6TJ@7qcp|9nUOkJsks{ZGFC`zOf16Y#S`%<|tk zL-ilLm{IzFSr3_4SnB^Lrse+>`KxpJr`wsZ|J84;`e&=SssGgcZy^895q{nAkMakO z@^8v7-~anFL;QQhe;Zw|rTm{{n19LNjr_X;e{4Gw=D)IvC~!u&T8es;Z^{r?6-{*Ffk|1{*^8~E!C z`75?l{RfWnf2uY=J^q2`KW_lXKicSVx`h7AHc2`k$`<+{wSW z&yEUl{);rmzi1m@t{k@vzg=>b`gqUDyiTgbedNNQYuu5~AN)tj&+o(^?|52_JK`7G zPUGt-8?Qdzc@}>>Adh#A<&S5{dfHFtkN0gO>RPP7>`eZ6xP4jC|E2%$(7zY)uiO8r z|A5qg`1j>TI_%DQZTFV z`F861mtMm!7Ijnq;h#&o%!>R=|G%LB&A@-mlUQ*f|JjYy@h>3$W7}sb|N8z({(naP z%_ID}{wcpdc=_|syuAN=L<~%YSO!Dtls`a1Ug*>m8_!rXdf4uYln}0YJfYl$x$7%Xh7UHKrAO64L zd+tBBUQ7Jp-$}a6QvbiB|1H6P%#&DgA^slXKOp{N+h>X2z(2qKD;)oSL;kHI{JQ;* z^816AKmW}CTmIox2v+g4-Te27{uf)XCI7Kp6?h;k^4~CdIG^YLiT<|+{|&THiS-rA zf9=NV_|Mi;`(GzruOkAJcCTH=pAuLT~+iZd_&t^dKPAgtwh zyZx_5@W<9W)A;%EuZjo7>tAfHd>_mm|JoMv@9%0>|K*#g{VyQ-uh@;O*Ao9C7W*HZ z3IaF4BikwRRH**NkHr=(!hdYNmiS|Tu)qV5?)>~mzW&{V{cj%#L16g$r%zu0WUHy; zUu?51@t>ys`X|qS^IYP1+iX1lv(0yBW;@7#nA6zne+BOU+(Gj1J!y9SlfS{h*MHFG zQ9u9W_5azi{`Up{WrvyNKfAqJ|NcvE{GV>R+D! zFem!oFXw+Ra-OaTT%rEgO#FL}>i-OF|2+R}esTPF4&>hf{P(?K#^2<{CBp2 zoBCfYt^awD{{ZkG^OTUkb_dme;Hdsh{WrZolJEb|i~Ku*|87J7{-!Fw|EnASi>LKJ z1?PXY5&yd5ANB7KTL1j`Z&M)r&yW7A!GERU@&8WZ-*Z&|WrqIc`JeM4|AFAYI%{_R zE89`cKU-bRe`k^U|5=9pUta%Tiu^l+|0YBK^_!{uKJj0y*MF8s>wiJyKM4HCJSFV^ z4aC3yn(AMy1{apb|J42$LjGOAf6P-t{?g4=|K5gf_*45|0QnD&_}A_K)W1jSAH|EW z28;g^Mhj#vyI&Fr}n=n@{fu5*X@7Qe?aQLSp6@x|HY7hkBEO=e(FCU^P3t(0?cK?>X{+c3S_-B7Y6|k9kVyzn%CGh=1ul{9-2i zm-oL~4*3rU{}o4&c}hb5`kmGM`;Ppdqv=0<`e)X1=HLI2*T08isWB+{G<8z z2YLSG{m+(1{v#m&9Y34B{!_Y(ntxW|X8b!(Gyhp}|HIB3NAly}@A2cmUmiRuvz)>G z57{37zQ5>grt&w;;P*dlx>mjaVVAi7p?@fU+%Itd!|csz?|;klFW>(#i~je9{5PLs z*8hT9;(ue6zp8<(*HZsq+Hm}r_kUXv`HzJBcN_NqMv{O3U6nu9Z!PhkubKbYb~t`u zu=Ia<|GN?B|0wX^bR@~Cczz1L{y$WG{~O;?|GPlbe^&HA`ToblIscb;Ov3;#~e;w0#|6|vy{jd54-ajkGi1QJ~4t)NPZ>j&u`~QtZ|3`!W9z*}$ZfgGv9QnUc z)4$_#kNvs9QvdS)hpV9fW59pcf6eAUHP5T(KLnHA^#4Xp|6%=CU0=@UKP!v+pY5g0 zaD(~}`l)|!bCtiYhu437vs(WhqW-%@{rd&#zuQv%w}$WkwHo?A7W_B zo%4S=?Bz_kLH%d<{P+EzfYg8cG+zJRPa!{r8#m|3>P6e>eUA zGEM(s{Wpyk=l_r5{F`;Xk=YLFziUC>|6<3#`g#8!zn}W|wov)ort;}Q2(`eq^*DMU!MOp8vUOD{;Q5Q>;KhjsrBzW@_)Ief5+t>`*VY({^jfc>!SY? z!GG%?X7%4e{0ENwU!mzA>OVj7__vGt-3Zn@B;ad*((L-j zrnS}jXDhlH|CY|AtuqyMh1G2kiJ~Tbb2AJJ*eW+5a~}|EGZelAFx@w-W#CfCBuM z=Koiv^?w`s-_v6M_X_#nw4Ww@o*V!2{m(W*{|(^3*3f@;9a8_qe>+{TCI45a^)LE$ zuK(`^{%h0re~&+(zM+5LwSRac(o%>bsAs3bKQT`triEVr35frI_>ZN1=K0TG|0wgn z6!M=I;g9YA6}bO1<@X0IKY9IoCFI`+UjL50PMy$yDcS$`$?M<6@~`{)cWgTxKM>o0 zaQ^<+#Q!k#zi-69ZvLr%Z;<-WGB!tE`3~ZE>q2wn`(O2m$1o@b*5UE_U;O?LFwj7M zp#EwP{rBU){!Z%rCtPps<>K#(-1*n@-wzHFk2elH{?}e$=lBl`U;o(>{qG0<`{;Qp zVmk}<|F#3k>%YW*>#1a3X{rA&qj~;|z?o?anjhx8{>A-2L;u^L|NX&#%u_=DUBth) ziJJe|6F!stLv`oJ|E5Rz{(tv{y#BVYKY_uaP}Xr-fAydF*Z2RGTvw3%llqrGH|D%6L_y1YZ|6A$>|IVEMjxEm390dMDPx1Nhz~f&p@$Ws6 z;r+G04eZbVXg&Va{&(U0i-Z5;z<+gM$A4hz|7tz{{+{0c9uNJ?`riTT|KNy!-SMCL zXI_E)_vgRA4e#gi)c$wl{Bwc-6Tv@w&W?Y!O9B3Vc-S>X_n&{}<^6AVMgNC@|IT&! z>z{PYr`urv6R+%lTgo=l>4s|1|Jl^1L1YzG?m6?b!eB=>M>Y zf8Ft)`VUC`$KpPd>tFicm-BxP{?7#er7zg=ADH@YEw+Dt{HrTG|92nsUkCo{$@_(c z-U{{qK2rZassF5aKeKRs{3wL{pYazf8210tVI%qe$=;lQN0|RX6j=9-cKow%4EukR zWB&)B|HHw5%#$!v$ba*pYXA4i^=~o3mg+yX|60z!8Tj8H{P)~s$-n9T-<6L2?}z@6 zi1^p-|I|MlJIY z-$47c__KxTKelz``j^=EE!F=p?f%clKY9Jbp~!y}@Ry7C*QDE9h`*y!J^#rk{61Z; zCH@uD@{d9Oqk%uRoeBL{A4d8=x&DDZpSH&T)cgk{|1lAM-Tp`U*&yea=l>pt{Kw|% ze^1{3sINl#uUTKszxR*2|L50`^;*jRaKrpd{=<>KKIflqXTtnfZ9w>sQu*ogX)FJx z{PO(YBar`i;BOS~|4O&FkbnPhQvZa%o37WA|CJ2=OMV#i!}A|c0RGr^CiQ=W%Fm8= z<3Bb3pZNYKCr0>n`(G8|4~T!7CtLY9Mj{HMeDy>&N}oF?>Nxvo0@W3{UPfUeh4{;z@4l65|^ z;`|TE4=;L$`9A~rW7{cKUTFT;NceriAKS*k!oLObpBdrT%|GS$206dH|Jg~%e-`kU z-C~yia&r75ApF@|$$BmMzt%ASk{@355A#13_+#6dF#m01NdG@jt^Z=>KQ;f!$nQt^ zb@Na8*&yea*MBu2|JlG_{}ee+kgWX+r<4^!VR!b^o`#r8xcn zdc*unet6M8%>VhoAKT7^{PpDcpYJIDsrk=9ez>$u^6TcG@_U1vUylE0A^(Lr{%6ek zf9Zzm{68T4ev$IuY?yz^?<0RB@W-|@Vg4Hlzjv^k{-2tEEb?Cz;n&SS!14fXBGeFBmWuTKjtZ6{!8ms{{eaZL#zfDGueN`8lwN5hy0g;|E39M(>YpCG8{m@sDee{~GY$@*mQt68bNzQvI_LZstEX8~T^$KVOaf=YjvSMl=4F zab)}_^`E_ntk+WiUtPQZ^ZI8`3;)+4|Fz)1&(MGSSk=GpsQzzB>;HP>KOg+ZJSEJ( zcZ2FbApVP0|N8#<@xQKB#r(e+`L6^2)pwGdCgiVLjlBOE@!v||C^D&5&XwICCq=#jcWh*93B5L^<+-~VJY&Y!#g{XTI2`w~m{zYh%Wf6vZek|_3%&kP z+pN|=KW%Iqrp&_@=;!@UyZd?n zQ=jm+PT}u=8r;N>yTIEHr1X*ME-x z^ho`u<@XHveMkIV;r-8ruN=QWp#Oy9|MA?vZ^+MXapPa|KZO3z9nilXe_+ags~i4? zuSES%LH-MXzkVt|{t?T6SwjA>_O>;vf4`;Z{Q3QVdHm-V&Yv4ZZj9{z>hAy3{ojBb z{|TQKxwN$Zqrd;lkAKMhzdMot64?KX?Wc(iF0}t&e~G&P7dSfpVX*&~_wTPJUjMlR z`ESaF;4ZSCnvlPTod4n-rsltfuGfXx? z=)aAe{}K@YVl}v!$^Pa2PaZ}7%fNpRJx-I5zw%~s{O@=*|K4S!t}OAdsek-Ot^Y@m z|CWe<-TYJk{;cBvN#wsA{Kq^c^xt$j>Hp;T9|m81HPig_{?`zm|Mdj&-wOWQXrE5V z->}=_%KkE|Q}bUe{@V@vzpVeqk^hQ_f8G33{~oFTV)5(OKld-s|9TqvTfl$G-K0+? z^k2D*dR)SDTK~@=|5XwHy8WN}_h%LV0rKAg{$rjJ=D(wn^uNR1jQ^(o z<@G-kk^gG&-+UZ7PbDFL#WgB_aJBmW7p+$mC;w|{_kU9V?a2S1h=1MuQ~!aZ{-4_a z3&?*B_>Xx?=)a~#?f>2hZt`#HU*7-cdE~zn{MXSwoshq2Z?*q>r2adnk@Lzd&42DP z?EkXBlYhS|4lED^;+Uz+pz!3`hOAm?~eG_%|G?;&no_3LH_H(f6P-t|IN3l{hyua zrvIDzm-oNwK>k+n9~k!kuKm>h&yG;}%kC*o{_i&I|FZsHM*ilAf8G33{{g9gY<%LY znOy(U|Le$q5BQIHN|^sLa{SXL{)@$L>R+D!{2KC)1OGj=PbcKByj`t-kJP{SVsY|6 z+OYpi|F0tdy%GPq`KSK9S;hZb$bSR)k9kVyzl-<}i2q{c-_(ES>f-g^HzD=4ex&+`hN%g-w*y{p2XS;o&Qiyj(>Vbs^fobqb!Yorv7FAJCXl^2)}Osqx@`; z^Y3H-rXX8t?Jsr~~;{vR~tm-+u3`P*~( z|HRCH^9?FLJHt)?f5?zu=D!>Hp920?L;l(uResMAf15Txzy4KT{~)ec$zA_)k&WwL z9_G)dw`~Fcn}#C`S>Cqdzm7lTry~FLB3~E&GAs6f*)XyHKNa`?ABX+_@;lA;|9h@d z=l{VfZu;N)hWr1r|9ye^e;V>%d9GRi>-${IzfbaC^C{^omgc_?r_KMDoIjWUOKn{L zB=YZ@=KuDh=Rg0<*H01GKg~e?D+av&X{gryAA&;sXZKU9cNCkS&;R7{|2HuIH%5;C z>dyb^@n3)N9{gm%fr_{{^9)HH%-pG z0r~GcX}SFTGnlI0A7FtJrZ@f-%D*2=1b<+o;hOW`e%8~^!%*G%>%ZjnFW;d5Tfu+T zBr;DE>nYU#dS6uMe*y8|Lf304|LYp|zxE#C_eaiu=>wB9o#4M~6z7lmXH3gK+g|Pe z{pg52>_4JA{>4@?-~%!L-=qH)@E`Le)>g=W&*SR&=bc=Df3W!fne$&VVRGgj@ZY$W z9si!Gf7kW@E&9JL;$OG_Q~zvM@&8}WfAJfWGw*@_ZcF}sL;vhiH}x;Cf9pm6w}bya z+NTrNe@Bmc{;x-_f2)3pj4PJvztXV(mxbf|Z=(Lco1FOo{5P#_r~U&||BpHL{|oxR z1N_H4CG_9>q}u-jNA+*&zx7*nes|ewA7nlP|JCc-@y|9>um2fvP>z1{amW6DLjV7X z_}A_K)W1K-{mc2^cbtF5rIRx~;J;QJ|1h5aT{UNZ{_gEiVE*GprQ_GWBmeUHmtWEU zo#4Nf_Gz(ch30?duc-5Xc1i($OZ|U6!~QS*|Bn7=fdBCR&uRVphW^H|KagZWB;O`1cm(j;)x{--?jh$ zq5r$VfA-R4{`L4nq57|UL-p@F^1ne^|9_$XAHaWj{4=e8uh974kAL>03_?PT|a5{J?)F8a{$?gIEHbZ{@S#|!)8r+P38>QtRg8cUa ze@TZ~|F55@@_UZ>H%`l+LH_%Izt)hSJ*V>fj`%mx=I7TxRD}0G-JjS0+kO9x_2Hhx zWiRsAe_F2P_azR8rv+FhlPi+g{d>b7pvzqgLJ=)d)SGX9a{AEmF5y0SF?_0swu%K2Xa|L21L>?Aw>JyZYp7TZ7X|K-EQ{{QTp z|J?Z=%{&19Lr=Q-Z+~8`e{ZP*`R~vFu6q2b{m;Sq9|!;NR^Y7Dl7HXOzwgMutp7fo z|2!D+uY3H1`VSoS|J43Vxc|GsKfDzx>-dKEDc$^s?K@lsrvC5K%YXRyk}k81_kaHe z(f{Y<{JHtxL*Tz|YqRs;TDsK!@13gFe?ZsUU;QTq5kI$S+WtQ`=N||D;jN%q_se$r zKif^^Pm1N=Uu^%p|NAS7{yz`r|9X>0Gi~5M^rV~r;6=6nGvYtS-;aM^v;U{|KQHIM z_vCXKycIfY{N7Ied#3&$aO6L%|GBXKACCCf?f=xjZ|FaklL8N<_CG)8Z@u7L25$w) zdOGaXzi;aQ!D9P|0S`V}7ZUw{KJ@=cuK&|{x_JHz9sjETSndDpk^=p&pZYJLJNE6( z()NF7hq>b)_danhgSWzE-Ya(ev)v2u$4K}C{zJv~&-Z^Drme*H{}x35kLK#%(0|KI zYXA3$|DFaiudw8Q^HDi_$v?8<`UkoHzmTZ^m(FF);J?|Df6vr^n;ZZ2yNL0BVa`A4 z#j`Vyf&b8x?)dM$tomn96nOo&KmTj$@tgW*$MgJ`{mPH?3?F`KrfXi9|8?@?|GNCK z1Rgb%*H`QtGxvco|FZrU!1{kY;$L_Cr~Z9X|1s+R{KtN9;0JX5FDq8pbm6ePpNjMO zvi1VL>=VoKM*jamENd>}|L+yc)?WVq#*6tfdkJ5*i)BYM|9^*AfAyvO|2<;qU&jC6 zb~#^mU%{89SMsHI6<>D!$d|R___9wdn{MF$FTas51F@{RiT}S>EE{j;{|}$Vta$&c z+AT%@Uljd60shNgCCBN+FBTgAJ3dv%|G<&|EwsmfzW-CzD&{{+ApeuVUvJ1?_L<7h zE}d=Q`nQz-Ew%ai`QO2C{`zm<<2DL?-^ZT|~Q$G@la`hS?~q)V9H z<>$Z6_Xz(>qW^aA-(l##o%r`0`QOUWe{H#V{eLOWKVy?0@-w5-Yxq1Zt$(&hf&BL) z%zwtQ|E1CYQ@Q%DBJzhZqomU6`227>i<>x{`37$UjO{{T={V-cl`Gm_$PLqa>D%gQ2sLu z)W0Qu)9atxMvDHo9QQx{fFBsV6voP~wbTE6!~FY2&p+S)m;OIS|KlV6b?5)oe?YE( zkG1=m=Rco+dH;{)vHm9je;d6{KVkm;H`M)KkL17PGtyTq@js$}{lCh;BJw{A{ITs! z$e(>v|LiQa|JOE>^;*jR zqlWpH{3DS6IpB|NXTto~zNO~hC;Y|Ae`@}fkpKAzzi$31zcLQP8Tez{nUKGo@H5{{{!{a> ziu@fBe%<_2{($%|R{fju%kh78RCggAVUgh^3 z`QI+B|53>QX2id4{||_NZ;<Z)5ZB8>mmO{@ZV+Vznl8MM1B3M;tkSQEX{v+Nb7%n zHsJibTij^69P zsr^@?|FfgYB{`KFIe?(l{`VsOb^9On?++pi{L->q&xlx)c>+(_3w|;8~;uH%lCiX z4E?_k{>#54IZasq?WF$MxhlU;*K2A1`?P-lSL=Th&}+=Q~Tcv z`6q+_n5TsPYd%o>A3IGQ|BJ=1@1I})*Bie7)t1Qr68LYTeL5k3<4-ETcZHh&V)0iS z_J3LbTOj`j5&ydRr~W-s|Hb0h_s`G&uh>SM|F{kEzYP9+4E=Wz|Gp#tI~)3!$N#I4 zzYF|#ePnk3w``Z1f1miT_==1xmipf_`u#uum*w?8+aZ4k`1jr-+nKQbX}$wT{&z|1 ze|zNr5d6nHCFJk^PJR8Co#&?i8TikS|NcW_|7Qo}e+B$E8~QI9uD<@~U+!l7+jW#) zA!Wt>pRE6Fk^iHJf8G91{RgD}X?^f69D7vz0aO1qO!WVqkpETi-)rc<_h+^Lu_iVD zJ@kFm^tAQ+yzFLJ|8oCtN96w){5R4*E&g($>mM6GRQWwp|J`)GmiWi(_y2tTOa5Ju z{}bSkZD&IM>W@_Zfbhoz4i^4uWJztxR|K7){e|ElF z|K1d`UQ7Nb80KH{?~eSR1AlBg6Xw62@cV?nSou%QzZ>#*NBDK~Px-w;&M(LRJ&^wk z;BTfmP3XV%6E*(<;jfxnocup)n19J%gZy6te{4Gw@>hMT@_QGk^=i`M-+r z>*k;Gvq8=;$N#;M|7+lHp*cM)69R+cs^TXEbQn1eau7W=9WM6Ww&^|;_5x}kB3Wk(fO`X@2ahidkA=S%{MiWpFWU4?JG+ zDBq57*$t29{%*MbDsf*@b_xHx)u$Yt|9jywD;^KGGvtF+C?8pR{OdsU|4r_XQBUHx z3myOP{#NUso$luNpRWIqUmpM38Tnt!z5YRuQzhhY`bFjU$?-3-8eCYK|Ck>ClJ#GU z{NG0W>-InD-=p=9MQ#iAzncH5^&b%b&F7KzTH@b5?eXu! zkpFw|AM=!y{~wi~T|~xzu^zdw#Gl%K9rC{k{$rjJ^0yNI{*`XVztsK@MgAWm{&o9b z4e=k4`j_6rF9wVMG06W`#J?^-_0O(!lYdkHa{upeh-VQeQx@nzW*|Q{$uF>803E&{I?kTul!B*?>q9pXIlS9BL7bj|GNE;`uA^e)Bp7S z^D{4G{nsP^JK(?1(0@3rh0DN^{~AO8a{hlT^8XC}YiXZOSpPkw{sZE_ovzo?`2V7I z|L6YY`LD+#|GPQ=dzp=Yq4#j@@ZV1lfi#UmTYIj{?|+V`;PqYo7VrS$p0Jok9kVS-;z=LKfB3I|1Ik{g3lE&n51EaX#lC`o^7^Pk=w%PTl(- zu*C@flZNkqsQLa^`uzOF1lVz`9DTG|J=XiZ$$pjfj_pL;+Zbw zzod-tU$6E*DJ=YAu<&1m{N2FcINZ#?PxyVpU%3)luO_Zh(Node5m@yWh{-_Ly(=_4!VKRt7Z z{l81l|CivuhvrmlN1^&}UP7(^faJe_GJolED|7!>A%73>w;A&H5q>sK?SJj76vzJwhW;i0)yO{`_+#6d(0}u? zs(+8>AID-5{>J49Kk;8j*K3LYL__}#;qlKik^j%g z@lV~?Kj`sKZ_pn9>@>Vgr&ZOa5QhKK@Vm zuSfpBfIqgK3Hh_LtNHf{zgP_}1`Gdn$p3eQUpN1h-y7uo>}iqzX5{||_#0_X6Z&s| zSiS#OK=`}qdM)|yFwDQ?zXADk7dghZGa-NN93=m@sP&J*7heq){&C1ZB*L$of6DI- za(+4f-H7}d;IG_}^y!5D%jZ=62ju+kCc0ir{$DZ7zvRCe`DX+E*mfr5?g%5#@$YR!>dI37Up36X{JQz4{Qe;4m*f9!$X^2d%`~S8{b%P^{j(Oe z|Mk-KTJryzVg4om9mqcy@W-|@A%8RB_X$4+Uwk!K_-{x4xg-3#`KSEeAm?uyxiUZg z^&jM)2l(s%A^Wij{a5d<{$4=%t2Qo9|9{;u|MK|HwaEVs9RGVGF09{-d6??nFjBK~#zU(Ek)>i8G4Xo)|y|9g=CJMbU#l+b_83aWqK(eZCn z|J51s`uBav|2^rt|Lp$a_}5Q-JK@k5TLALk zLdU6u{4Mhm{@dN;{|&?OPx`+f{r>>|W1bT7SFWh?d&Iw34K6Ize`^2tB7bSbzi$7d z{sTw-FSY*%k-r!G`)iPKDxv@0d)4zF0@DAw=z1;rKgF>AD_35b&wn34{sqB*^(JQg zb@QqD56Jwdm9Ezk|C?#+zYY0+1phHl3H^Kbss6ot-SofI{vSsEg}{HzQ$qgoHHd#l z{omAo%WPu&e+2n|0{<-^l5sjAe>e4ipX$H6g4C6z{5NRU|NOv{`=nmY{$-nOSNAvH`D*1m5`G1D|$8suU z6gvO2b}hC3eMkLIH~(;TPyYJvo`b~sFOMSsBDsWmq)rp^mn^LEvpdxKuc7O;RR3?8 zj(;nPdVdo6e*yoMYnt<gZ6-K-@-y7uqtA>jC&ojvXEBJ37 zWmf-Qo9ds{s{X6iBI~u3|I-ZXzhaE&|4$?T;^4oH_UVNAFS%dk4~YMgO^d_dY1sdz z{|U(d8~BfTO32^5uG;?s(*LpXiLVBW|7VfE4E)DDCFE}-^B?a&>iAzQepCOIC8GW( zB7YzF@1u2^kiWK4_0R5C`CHd6PX15Vu77^ywYFUFufX}I{qrN66J~~98^8aH_VvF+ zaIlBUPrlvnfBgw7CfX0{cLfE$5zc>P{~M3~mx$zFcl@LIXR}KFpF{rNA^)+Qis!S? z{!bUlzen;P(_*RrndYCZBJ%&d$o~RAvAH4t&6e`d_B6{sd)7_<8x9xae}Mj%g#6di zaXO*@ve9b)^GW{O>3S{se_Mb2&;R9?Z3X{}$o~iAzh*S)(+T-w`6lCk?K)(=miW)m z@BjJz|LRpm{wIn2FZUCh7rxW(Lx%*IwEf>R&Huz==bvByAo)8u|MWF}V)Fxk)x&ni zKi`nwFFt=hd2;-Jh4cTg(@*&$LoJs014Dimxbfe+y2$^loPXZ7pV&g+zxok7{#lJ# z|My+*b{Q3GX87cDr z2Irsg*3WDy;I9?$%aykO2ZsFY`J(&J^Vh5__}}FG-~8}1TMqckp0MMe?PXT~>_s>H zt>OIlEzUo!^cOY^_`7bfH2xd%`;*-8x2z`ocXIxY>@REt@Ymb&zrs+n{n(e?@Mm`r z{BMi;_kLlk0)K}ke&5u8ha3L-^#uPrg1`C~RssCkC+*aKV9Nh$(fNTA&hroFKkst> zh3kJ|qu@IYmiXD;hW+n#H~g(0_uqXgzYoZkce5cI0e|DmminI|zh7kjocriUDV%VS z+utknQ6heBAvi=hl+7W391a=C57>Rqf6#Ln;I@+g`oY(t{`9=?lP@g7R?YpwB12{y zlKa2S53rlhzdZi&63>5bE0zM7*l`N+#|s_*Dp^N8{=x1nkbg`2|N6&22>%PnzjTCO z_xLB}56JPKn8TUGAKQ-qXAgw=uRl^8|M~#^F9ZHdHzUWX66U|2y#D1m%Ky8X$N&DH z>5k!s{)3~0|BulBvf#hY(0^&E+W&k<{@*k7U;orFKJM+K-nSz5goy`&NBR5Wb-x48 zVC09Y&;IxO#YTQ4(UQzb|G+T+ZRGW@z)}9+ z*UW#&-yZURj{I5RFWcO#|2LBQXLq@o|4cUIFR2&)yODo+;IB92_itCvfAKa|&;N;) zn5Fs82ipAn^^frV&wG1#AI$Zi+)GJyPc5zVw{W`)&42wNi>tr4wCca(X|i5R{6n<) z`TV!$IN|>b^uGf5&u(Fs|B4ON@y~OV{|~kKRsZZuFzft)A3i*eD|4v47nvmbWo7DelZumb+>tFEY>VIwc4E^iw|55*Jko&JbLHM77 z{#OM54TkmK+^YKb9rgc@4gJgaKlvK@M}vQVyjlL6N&Wl8f5il{UQ6|#(dOsfg|R=|*b*_Z{{BPqg`Y|Cj!IkbfQUAM*r{j>-PVce^UPCW`Bw%1O@{u}P{0 zme^zeKX*Gj&&{(JZ+CWXa{hn$e9j5uWpBUteV%7#=XUqNe;YkdU(vr!u7BzJn%q}I zQ~f(B^!fjM{&PR){~7rwfPbr6E&p5Yll|MoztyiW^S=dA{r`gee}aFXCq@74b~E)a zvi~0BUo-8WdJ4!N-&H>TWjCAQSM}dm!`J_QMgG6Qf8AuY_~&nvXe{Et_PfI5|H)DF zzZ3b_%JLs}{zv^gB>%-5J2kL;SZ_6^8#5#rzlk z|3dzW;NRydAb;y_a{agFn3?}Z_Ww8X$H2eOQ$T(%@4eP0_226kt)}>o?EeqsUpvcx z*!u7Df1jE0U)6u@q!>{I`k!&a24#sww`v6zjk6zZmi_2L3DNk^KzFPv0+ghne_4HLCx9 z$iHsdKlK!lzkPSvzhkKWhxhLu|F)jT z!`6SFf0F;c{OG&ofuLzitl_|EJ6GUwJioUp4vvB7FVN_^&;m`yYh-1HgYu(SOq>GQVZ0{+}Jy z|6t^w4E}wd0{U+w{;m7XjDL~+FOK{J!GF`4Bu)eJ*IKfF+mQcrqWUjI{;DkhVe3Ej z&x+i?sDHbaiuwO)a1hY7&^`YlH2>dZ{bQ(^_}^2p{;?)r|AwIdQiy-+EVcOWA@T1R zivM#JwJ!>wjg)KM3N#TQUBfsWQK1X#RhmV*FQc#^Zk}mw)=eSZo@^ zf9rF4;@?q>e|u%a@xL_sUmxP%7pDQo{~j9uWd6%HgN>&7uX6k!$Mb&~Kinep%Z@bRB{=Tpb?{9o4PpLwgtq0+w*$jpY4{1A0xr&Z*jQAZ~6rV z|8SSTadJs)I`EghpoiZoUVfm2Jg?^UuiWK7Kfyo3<)8O# zNo*_NZ-2$TzB%&!zZCgxL;Q6caR1Bm{GYd2Y!>j>zo-`fsqN+ZXRF@-Y1Od)%hKT- z_$SWupYi+OuoYbXX~X-)YJk7vB{hEE4(zU2|6UHu?|bEc?C|lg$oXgYi){z|oiFR* zw^aE@8Rj49^3VFEUu*~9Z+t}$zpcn`oAU1+|E}cnS6|jYwj=OYb?D)D6#4%#cs2Y_ zFaB%1dqaV<+VtaE{zyTae#F0Y9|>sF4-5Y8G-y-& z!4|>arym9SiSzIO6zks==zl2qZ&mc4m`>u~kpGKA`v39Gv24;Q@aAr^s(bz)Z&{o>uRT@fw+!)Ls>mEh|r)# z@yNc*eI1MU``*uh9dTa&n;vrSd(Mt573aTP3{JZ0)bhXePx<^8r&O;0zU^xAzfVa2 z9>19XR$}}w3-ND1t9JfF;~Y8uEkp5tc}V_I>*kLCr!xKi_@6t;jsK<_-1o(6=dPDK zFYL)~oOkkg_1YHb&y^RcD);#`&PPwlofi)Dr{_iV`6=Gt-sy`ejFxo&UQ? z_55FN{!=qR9RI8c{;f;Y{99|w{MKDEzi(or>GwIQTDr zP0fEd@$VS&e?wINnTDS{!!q+R?&a`y5#uJQ2w_>^mVR|5lQWtD46DZx!pmnE&sH z{1xE8?7w6`1J=J*lK+;W^}pMr`rirpXMlg7r=a}%%l>UL{`1XX)5reB{C{WUUmg5A zivH`*k@?v@X2!oeqWa$f`M1pSAGZFtQvW3XQ9S>xkNu1J|1QYC2KcYPLM{KhsQ>-s z`EQ~4?^N_JzW=Qj`L_c9rN61w|Lz0i_;-l^<^t9KZpHd9=Ks4P|2Xg;zf#SA;#`^E zGL-+VQT^|Z{4>G7&l3;aeDnXd*@XWgGxbl^znK5;f&Amaf5(Sv{yV9EL;3%|sQ!0F z{;jk8hpqqAKPz(oV*bAu@=r+nSIqyK^W^xq4dwq`ivGp-KkSM8v%tUeyITG4sFV2} zvi{p$p!)xvV*MBM|GklaP4Hi#djE6c-!bI>?x_CvLH=#Pzt2;^`d?EnuYWj(@?X`z znE&sK{A+=KThYIDz8wGTUNht0JyHE9kiRC&f7tp@{o6(EU(EmaNB&Ci-|&dq_@5&F zZA0V#y^8+D_kZk%{M&;6nxE9x|2q#N@&B+K|JB!$_f^yJ-}j33U(Ek!Bmczo_^;@{ zqexK)|Em7Q{QqF&UkChmD*A6G{%u44+Z6qa`+pyV z{5ydEB(2i{JA!|or-1%j4wd7tG}UL!te<-+$IQo}d3&kNi7>|Hi-7)_)og zm-!t-{(n@g|6=}s6!K37|4oYilf=I>rJs9$DPQ5|9h%0!hZX%-dj5|_{#x)~GhZ$K z<4M^+d&Erq|D@<&%>R!;{wna_rRcx>e!~Bv8U9B?`**+pt-F@r|8umT+xwei1abNT#to6LWGxSI0+XT|sz z$3Mp*{}hP-jxE*r>qz|DhT{KG#rW^qmB)XB%Rg`6px9v${}u1(iGSYpb5#}wnga!(%rC%F9Q&K?vy0^+~%T|M#7p2@@COZ>Cf&BT9Q4d*}E<=_9= zL9wHOKlyqJRV&LG|@xWj6p&oummH$mM{1wM=|F+9tH+yjG zB;aQs>EUP3D#riYX85c6@%ulY>hd3W)8N=Cz@JFz;kQ-CzfLp!_2+W`XS@6}-X0R0 z5ByaNH1VtYUtpMjj>|uN;F7T$fWLd89)3rae__G-Gb3;H+GE}0^V2#1aZAQ-2L5E1 z9)6bZ^S@rkKid$0TN97}GhF^HZdx*S8}QeBp@-j6EUNLs`+Q1nc)}5|0lZq>HAXe2FL%59;c_@EcnTH{&yoe{&(o{zq=XyucqVQu*d%e zyZ`CaYbo9TGXBh3eRBUx;r~eVzk8Pdu%G`?|Mvei|2tNy`QNFsPyCDPKhHt`dw~C1 z#r&_BFR%YOWc|C9ZdX(O_k>*kdvQ)>=KEjDCc5|Y_gedm%FOq_q*GuHd_O=1zkhi$ z-4A`j? zXKwY}s6{&wO{>Axk7b1TmUH|&2t^dcjA)o&d{?h9U^ZCcGA?shk;{Q#x z_+RC%zKMU~{}S{MUs=X{o&wgt)OBS1Gj#r2(fHqgZMFJ$z}kIM|AhaG(Lda>UHA`M z|9t*Q{_`-xM$`CLH2yzV^uM5Q{EOqC%g{gEvV|pRoer4)_Vsf9vw8CIe;eJdCjY+` zOZ|U(9ku*_W}QCCf8qZM^beP8F`uV^{#$G1>mRMh%*=m_#{VVjs`yG4^YnoE-&j&Eo$qTC|8;b` zn(F`WA?yFs&rHg!TeNNKu77y#P0vCnV&esA3+{;<0}u0y$r^Ystm|624v z8~pn`@mI>X{?T;<8UGzK^*^-#Pjmaf<1^QP{6RPVz4o>Rx&0@)a{IS4{eJ(qLw_#+ zi7#{ew|RfT{a=Ir;g)T}f7tp@{W~Q8eF57?`R~QQxc5<-pLZbt;lQ67 ztoHd=VxT<#vk8CvroxQ>e}#^J!rzMg^}z4j&w%mYk|6p2xtaKn%zr2HACbi$HvTEU zL;Ul%5gSeQPnBQX|L}jveGuf2>sN)x`g|V*CsKyOIAW;P>rk zK>n&*3I75!@gJH0F62Kti$84qQ+~%#{;TqfrkKz>#y^E-s!w{LyM&z4N@OXub8^@e6 ze6rb7CCkD8>3F%9^&eJNl0FIUZ}`b(N$s$zwC*kb-&1n^Yx;VH%=0?VcdxsjI>>!y zeY5-b_51Sc@lX2a^Pf}mU@cm_NctBmy>u1$$LIfE^nYBI|FHQ_{o6(BpUi*mNB#!j zulYe523|;^4guMR0VC&!gtCZG1 z;{&StWc^Fr|LYO-zajW%_qm^o(s<36|1E8D{yT>JKOWM5oUeb0`(HhV{2Kv(w_^Oq zACURkGiK`F6CwGx89v25|Nmt-&&zn57%?St{(m|DJlkvSbUy?`=aDWP2nWqJGuboocq`1fQ;|Anf5$xEjw)xQ+{U0XB z68^3);=e1!?|<_qp8qhVKV1JY%RT=|E>`)ke@(70uYa?j&BXtbA^m&tFXq2bWBgBr z_^)|Vt^OxS{97Gn_@4>M|Hb%CGUI>GFn689Yppdm$$9Y^nd7d*MH(R_kH$SYep~rp+Bd8=+EhY%U=9Le@_2f_2M7; z3+Z3X|DQ+yn}Pq@r_}PFJtU8R)~janzdfY?LXCfHz$m5hF9CmNa{Mb4zx~c8O8gG| zok{*UpZ|&DpBFLyH;4F7Db~Ll690~&_{|#OL03-Dk1wA%Pr{;)j$Ifned5Yqp&&$r8* zhu^ZRyUyvg@dewl)#3V&#*5r_F0b7O`qS5cv~TY|-)leP{jG!e^&-5r7jDPKX3bmM ze?K_0ZkB}p$yxo@itaj>1N{}y@6CU0e&3B0^pDGWzBm7kcWuYkfc>G*ho=VmiSzm| zj(=W9|I@*LLeYO6@o&9uCjVay>Az6pe`@}IYWaWNetnYv;`rxH^j{7B+Z6q$h=2Bm z8UHU8iGSyl*-HN7pU&k?X&0$p6bl;y*RNPRYM@U0t8} z7xVvj(Epa;zfRG=P5iSr&E)?pA^o2*?6l1Kmv`N#*Y2}iy5B#}e+vES^(=3l%Ul1l zho2_h=PGsGA(?T0KJ=%r^Yi8jUdzf)O5(4T&O(+%$T6nSl+!5^OFjsIf){~r3^3j8~Y{yT_&+mQc`kp2a~H~;+r z`DX%u`Lk;EFaD@p|JYk*;{R1eelh?15c#(T{(43JX2Ne9;(tw%U(A0#LjGC6A8%Ll zU-p>n-+J4O|JN1y#rU5>{%wH2L6N_a@H>Y1-%#Wi9zf+Ol@%TSS{vCk7@_DuVFME#of7guvcNF>S-sS!m zApefQ->Ar+ApDLY{&yAmyDs71|FRJIcLM&DB7Z00x85`3|2;*1QUAM;e`nyY-bStd z*E}!Bzhj91eO3PVc>I5X{I$UEw5ip`CQF^54rxsA=iJ@ z((P(G|FuN%`WM0fHS(Vb{J#C<6QO+bpZYsV{2RLdBQpQP$bV86f7t6^D8F6g{Nnn@ zZ;=0F;BTdI8qj~u2lD-|S(lvur3*-2X^Q{FLdO579mcU5IA5QxXFiqb_n)`dxZ}9Y zdSmrT?*4o2GdsEcrIqe@>9x+z<1*`_o&0l5ukC{V^txy%Kkv+Iy!Ixe#=N}nI+{q3#pd5B)i^@#@dR=)nV8~vXG{(YVT`mcLe&VQTu7dznn z(ntP%{NEzKoy8wE|0%y!wEXV%Z{qtOzDNF3fxnIBX+Zy_@5%lh!e6$qF!|pvWd6tb z=l_ELN8~>Z_`~`>A+t{ z<20cE9^&67{0`l&Cjb2v<6rRqg8XLyzi&SS^4GsF=Rf<>O#DaY{~7t=D;orV*!ZXX z4)HJY-utDG{fqmb_aHyqvW(Si?tcHBx0_y@Z~kBQf$ZNR{_DF6Q~w7j#=qeI4fz{^ z-?yLq4ampeNcbJX@4b(r)#N`i|F6h@W)^?g_^14Kk@Gui^Yx$Kk^d~Mn@(0|2; za{RMJa{a5hkgO|e@;^{9{u6P|{}uA@2J1gvitAtYi!#4sX#FP@di}?p|0dq&>z{ui z|L(wVy-4a*K>rf15-~Ylf#Q%vZzjyu% zTOxD4eR@4$PvEcV?;g*4n!Gk&{dZoHv+`NjD!G34J1_*)eD6EDmBjv@Zf z6#2#ZFD1yI0RGkiYW_P3zm+oM|8qrtasJC<$iFx6mkw0puX%;|H^dKL9~J5+POty! zhy42hf14tIH{rKFHsgPxBEP8r{gHoP;IAuH^B;eO)PF<#U5fnnJN)zS0m#1}@Rtu# z<8SMbmR;Jnx^Al)%6d-{|EA)lf@r){fqKjMb2ODt$!_v@qaGx$G=cp|L7+E9m3y0 zx2ws2sp9&V;4ee|^MK#Cp8?~)?jt$>of-YeeTqp26bt`QuZ* z$nozG{zkf8P5u{GjDNvD0{Jfke&2oul-=$3l;y7`OA^NIg3AR{8N5by!>wD zHSy#BM)&w*J{HJK1^8Lzp{9FF9y#8$y|5aa+x}qunmk6K#?kigr?(xZrF8|ikhsT}+ z|JL_<{97-m`M1CO=kI@s8YVvfBhmkV!N1Q_K>rn=%JrXpn}@&e{DWl%-*eCXui^4< zK6};J@WtWy_g6jsZ8(`+{+=HGM&@gl;OAxJd!FL|kJJ2L0sUW*^@F09(vu=6**Zg&1=Ko7Zt^cE4{@d?gCAK8^k87I$IdCzp()d5fu>aN3e-ixrJO%V` z6aO~x?<;qj>c6Ug<{kg7hZq~i%ClUe=hX#pF95(`9Bu@ zUz_DWZ2hPHtz!4@&Hu-9|Ff5meF*-$bshh|DAzw<{P)sf8}i?N7q9>0(Eoh!-%aau z!2ECfUcUa_A^xksDNOwzs#yPfZsFtqnlAt83zv_50{*Li&@=u!s{Vg5lmEj1TIl~e z@bB{!(7&@l9{;WH^2EQU`XAYUrOSWr&MU?ifPeOrCjU<>*8g7(`=5aRug~%yw*FK9 ztZ4n0W+Jcq5nlhkDb0-2>FZzKhW}H!i`w~bJWWJn4>J@0;spc#66a?gG~dqa-`cMK z8MPy0iy;16yWKh+dH(ZK9{yhT*Z$2+{FmRu{ZGXBzX9UEYNnh2bocVDf3*#gzyHoA z@t-Wv_*bSl{t5q+T>j~eBV*m*zf9BmCwp1VKl{V5|Mk%Sjo{zsi3dVH|FwU~;~)Dz z55K1IPt||@e4hW4UH&a9R*L-y{_B6xl>e&!nVI8Xk^k$U|C_S>haLZ@e~08httYz9 z|5Ejzyp{W}aQUabJu0>`tbf!lrf2@c@_ql0?+tM~Y(wi`b@%f6Uxof#z<&>|(*g6p z`ENP@Et3B&-xlWhXQ|Nj-#z{p{2L*|5y~+P7Uz{-qZS@Q*nE{JVB0KmTP2 z`ac-1f2kUxHvjJ=*S}cLghWNi%P&Iz*P1(O=i2nyg{@PV}{%?l- zhXa32nHql^;b)(lng9Q&$j?S`{>_oU9{6j2R?GjEw`Bj8A^x8f`5WHi@&5;||IFwQ z*S~D%j(?%Y|BdD2e`|^v|H~-y*M7+Pr=kBNz<=8>YX0lrmi^oP`u+3gUz*0hpB4Gp zN1T5;@*kOw|E1LOzp7K_cMS3WqR3yq7(f538u^a`{>0L1{H=ta^*7_cN0DEQ|1*&P zXy9-7O)dV}JFg}j!n zx`@Hs#k~87d*6Q;hyG#E@BO{kTF{?fawB{d@e4b9nsELjDHeZ&&0mUqOz4%Mkyciu|ox@%isI$bUTW$A_u;ZzKG+A^yJ< z`71W&<9`kE{|ERx6!}{w%ky8y5dYsH`BPTz`p2f`u76{pKV65sy63g=O>@^j3;Kt_ z^S!#~wF&6YRsU@0&sG2Kfd2IBrp|KfpV!)(=dOQA-k-nzx$D1e_woGS2>suh{$u|6 zFZ?F`5uR1IB;LVluz=qn!VRivP&`J0gE;7Ju0Ir~Ir)`42jO{aAWjX{&VSIbNG; zT0gcdeE)gJ`|fdp*Rl(sAD%Df`5(Ife+}r*Y-iA_nRT8v-X=ehk}3!4b^6X)}P z@%>*rqyPVb{{+obzSVs7zq+3s|ISkK{J)KES5y68Rx$qt|E|b?7x4S`Ga!Fif0^H2 zTITo3DHi@(hWz&cf7$nBoC@f_=UI9E%OU)Abi11T4^xbP z!M_Lc-wXV{{S3&T93aQPGu6!JzmfTONB;Y=_`}9OD?(vV9|LuwV_XB_9 z-tO@htylT#e`=uY-y-}@f#QF;(D6_B6Ug5N{J#AR82>G$GQUIk>HDec_$M;|UdaDI z7Ju0Ir~G!&^1Ji@?l%7U*WSqgAn=#-^FOJteDU8rNcPW`mGi%2J~^(^RR4#Ej(@_x zFY-SG{J#AR82@F1WqzCR)Av(X{HyYd&%d@s{u5yRuVOj1_0QTBWq!7rnd3jUj_;lQ z$BsCk|BLwF2l*e)@*g(;seh};{a23V>%aRW|B2wgQ_+71^*>O~f1eah`5#mCU+vYu z{gD3=@ZYeHTKspC{C9}|ihap;HSw1#*1wL`x&PV7e-ij_98UI=i_2I4>qpA@ZyEAm z64iel@;?gxeVzjH*RCXg{$UL>6aT9I>&J8d2O|H;;NMwH?fl;^;@>vpf3c|k4?zCM zviygw|I|M#a{rwha{mV-|0&?Vsa!4p6D!I2?-=smPtm{iAfNvpg!~Tp@1%7)VE(r+ zF7w-K%k!Vc{mA>Oss4{ptpD~#-2b7-Z-f7i{%ZN(N&K@?Gxe{3RR4z||Ks4_=P96n zYYExEV<`Vs{l{b6|KZ4gD){eG%>SB|Wq!+${{d0`AAsr$IA7OZw4Dp^>1Kk|L*#i`23?D`JV*;Rr{;)mkyERpDicXzb3j} zP5jF%*8djo{O6;Pe-8MsUS5sgip%`Aq5Ln6>i=lue+vBjJOzyZ7UJJF^!cx<|C$t^ z{~Uw-r-OfMklOg)M*KU5{11xi|48JATeb-QVe3EjZ;|}R!pDE>NNU%HB%|7?(4{|d!FIJAFq{>!n*50`8*>j1U-SG}anZxjFBbi11Tub^1}d%XNV z9{J~j|C$xl_-*3fGUR{psQ&+h{Lg}apQnKJzl->1!_CCMs{f8se*WhP$UhJKvlZ3+ z_YnWKA^%H6_1}Q}?OFcA)_>~XA^BgZ`lsq&%>Pe9{zmZMs_4IdRk{8-hWrmv^e^WB zCnEoI;6FKAE&dya%KR3||C&0oT}}0WMaB9ruKzv-`OgIZr6b9H2CaX@KO1bO{w*2R zzm5FQgMXi=fc!OOvVVv8FI4`k`WM%~pNjlvf&Vr||5c-8erpXg$NxhW{fq10=OF*t zz+bnLTKuY1msaE#mr>*wi^lue-ZFE%~j)X9xMB2OPHyD<%;~G{-1;V7X!aFPmRBNjjzmg)qsQ(ut|9^qM{9Hx;)5!UchT?x^MSijVcQW$7khT63cKw&G|JX&o z{v)n`I}Q0?1b%j)n*XMyt6@muBP~pE5^UzzZ&`90)F3q z2INm}D#yP~_zUGfGXGV`|8^FC*!ZXXR+00I`Oh`T-wFKoVQTT;eujMf=MetN!^w6v z#s4bd<3IDt)=^{KeBHq1e|qfb*edY-H;uZ!|M|5%_1~8eZihXTpO@Rq|Bu=o=hr_A z|JS1bcfh~T6Mw;c$3L~3ll)&nu7AG$?qmPuZT$Xk^IiTec3v$u8vJ+t;okov>i6HV z*VX*9GQ<9p=>Od;|6%JN^=}oq|Jp~m|LeK`n^udB1^?Ecdi*=8{+BAa|4in!Jj(fR zbor;x8xtD`{3%WK&w4{K{+BkxpL96?O)mey<}tAez+a^){~bksdl@tQRZnyN7MH*J zrZKTf;BOzGC;qKB75y)3hQIv<&VMuKzkf_@9pG=)mH(>z!wSw1-|`4?-jAREeT&OK z`N`+iLu5IWztR|7|Y+w8>** zQ-D9IiQiV_w+-=&_`luduRm^VYy;r$EY;+{Q_=r$!~XAZ`De}>8`}u@dvy6%$0)2O@P1VZ%zK+QS)yXowb&ZzgCxj|KSy}sleZ&iQiV_XCut|kDuti z-n6zgV$*@YYOp5%?<)E?%+K!P@n1SFHUs!unR`FysK>vyB0pQc(EiE&FRyd?)Ayf# z4~~CRbe)PXT;yB-u;-EWFLM0bR9~3&uT{gZe`V%>;{3OZkpBue|D*9zwe#N`i>&_` zI{zac`uq>#{~qLjAN>0~1@vFFh0JfQXlDIO)xS9Z?_T7;68u-3PvSHnfBhU1|Azdp z64n0=$p1l>|FG*{)ITe7|Kj||`;q@D@L$=a=D+b*^7+@2hT>n*zxe#?KIH!p{98w; z@h5MW!Y z`R9ZGmW$Q=caYEj9Yg-dM)m(F@_(A;KWzP{{w$BCa{pTd=f7#|Hb_OY2?2i z{I^|7_LJ+%xBeAxl=<0EdHgGs|J9@Ve+KzK2md}#0r?YK$?PW#PZIyOA^+nP{fqM- z+mU}E_%AzFjlb(Tx&GP2zeBgHss4{qtp8&E{{r&g1pYfNSL3faOXhbB`5zzE|BJ}q z1^#`W0@nY!t>ya1RyI@rRsDwnKIIsP5uzfk$F z>R-(NUq}91!GH5rBu)eJHU|EnzjVe3EjZx^|LG5>!P`ELXN)mN+e z?;`#kL;fd*_D`<=eFOQw2LBDTP6v(u3+4LntS_(sRvb^>S55W5Lb3jf`TyI^E*zZEybuj*fX{`D5}f1AZ0w*FCmR^l%%yppY^Z)LI_^-cOZT^#-Df_n##s9jB@h{fD-$no3;6HJJ8h__Sa{fESf8~D) zQ~y?1tbbzu`#$owg8$NM$$kdRf2&F6XG@#O|4C8(e}Meofq$Q;fc)*-lK5ZU48N*> zG5`G#`Tqz0%jT>3ucY&TL;UMS_5U97f1l+)Z2hPHEkpdO{>A(^h5UDc|MKh9{M*F8 zwT7AapRDL#tbc!m{6B#I6s^-i^FJZyKO_82Cy@75)BJZ0#riMizn>ug-Qd4n(SHwF z|8WREe;cvU#9tNF|EI|RBl!1u3h2L%-2aS?GZX)+{>A$DXUKmK_>W&t;xr(C*EVwe zTZZ_jMD_nM^8b|OKWzP{{%u3?AKpK?{^N7x{~7qL6V?1D-<9WoHu2w0x2q}t$0^o7 zG5`G(kALoi__uFRHe+@ADKe|9ke4^WQeauj*gSf4@Nf z`@w(ZjcWcYE|%lpnkTP+;lRg#(-i+3M)kiC`Fpbbhpm6qKPz(oV*a}b`P;yM)lF*t zyNQ1`!A$;d6xu(_L|)BQe*N>^F8}Gx<6<-6`q$E!p6g%PdwJsDmk@4;ZRq+}vHtTV z`u`Q;KY5ax|JD!X{C7zF*PKkYt117-D~^9+{{J=dKLGJ>wUGVfp7Ndl*t8v~|Ayj! zW5xJq7LWgLT>fc2<6^TQ{@XOgzpWVmYy~sde~bA47XAMQ@$ZY%fc_Kv$^IQf{#D~& z9RGA9|AP?!?eD6^e|@K%|7=Y&^?#G_@t?W=y|J3d|939`+}iQ68i@b05>560eZ~4; z@c4JfzpCk+|3}W>Ha@l;@H?9LZAE^zVxjZj{rtD~HJ88X_EDM7f3~ig5Zej(o5yRq z|HlW4{tfZ>yutnd?E0ToHzBqw@V76fC;n|!{*}!57x#bq#pSOnUo*Bl@Hh0+!_Pic z^UvaD_{IIddR+dkYS)bI3H%+J_-#dg+YrC-|EtS?P~)1h1n^h%*W~{rMgOZ5+P}O0 zQPIlp|5u0WKS%V3^`BaI{11ElTfKoi|FNd!;ny_(Uv2GP4y1bNj`RB;H^*H5#im_n04 ze`_r>>tB)i`yu~dS^Qz+pYl7zKN{n|^_hQi{{H~v{~P#AZ4##e{r7w<$G=1TmtREA ztJTE6X6X1Q{H4gBF2cV349MU73E{6a6aSI<2O@tgi$84qQ+}(+`NjA*2>DBZzoXn8 zmubG{tAACW%Koj1vj3W|NM31*|Fsn3U+^!E{EGplUpT3{&D!i{Z zbVp?V!N}h)i$84qQ+|i|_ks1Xe=+}A0{Qy`e+!LMzT^4gKXo-Z{-^%GE=>GaD#pLy zUlRET06(Mq8IZr~Kso;HbAneXH>Yw@vZ>%8Pc&^m{G4{EW=H6&xC7*1r^m~8rwT;j}37%cS@2}>y&VONlpuh5NcR#!~1^wCUW!2yCdz`O-it~Smq5ns~e}|&~+V|!9ZyWNzX-NMEwSx!nU&=jt zZR)vnT!07a|M|2ZCe}s0_cadvx%^nrpN{Y<}P_D`Jq7w7*DNB@t4|BCn3>Yww0?4KDr{@pCB|4!F`8~5+E zsdswu|86h-p+Bd8=+EgN`g8ivY(Iy8zJ1T9@XxpJdG}iOUO4~a{MQla|1t32sp@}U zGXFQ^fAg^ZyIlWeFSv2;wW%+9@&9En{-Hmof9TKYANq6p&ul-3f4+U6f4+UsyVtTs z;rxs9KUYBi4*0M9KrR2uTdG}hjxcj=^^S%Ad z9{bb3$NBg#=Km|B|0lqI)rV^NUqe3svd_%(`M;*)zv*H9m%IMUUvxRWHZ`Ib|I7E{ zANq6phyI-Yp+Bep%=UBm=iB#u3jcijo_DWhD}?he=Krgp|0ltJ#}Kvk|4Q=tmqph< zX&`FyUmezeh3mhb`}f+^>b>}1qZj|spVL3|=kyQ#IsIq0pTj@jzRy43zUSR**|>22 z#r%I1`hN=iH!0?S-2w9a&oShGMp*wlfbNYw=oc=T0&*7hM-{+ri-}COZY^!ko#r%IP`hN!eTOX;7|7GO!U&oOD zt-|`Rb^TZU;?DoPHnmGH{&(%gKlJDH5B)j)Lw`>HneFHB&$sXM&$sV+_gc1FIR9e) zzdHJV7W_9W`tO)6*MG~<`v1(3{?D#+{WtLZ_uBYDx&2$|ewe#>9=v&V0{V0Lx1m3m z|0MM1@}J6V-|wFt>~7zCU2pyuhyL{TJ?~y?@qX|5-hR?)SDeoO$D#jr@ZYWIzm?{{ zA^%&4^nXyJ>%W8h_uAB%x&5=Va{G@%e=h$P^yl)Qfc{+mlbP-N{X2a7o=?wzif`ZZ z?zQafkoo@+KhJmq`hO1mSEtnKzeCP{u?&6wIV+_9v)Ww$6)(G-UdtZL?LVIG&yoKY z^yl)Qfc{+mZRpSC-^py>??1)2PyMrpa_4`X_j}LJm;Yk^zZUv`9{eX2{U<+@*Z&+t z{Hb{)p+Bd8=+EgN`g8ivY(Iy8zJ1T9m;daAUi|ZZ@A>)s zi~0XV^#20*?@{#MO3weW)-!YdLrqBk-uNfZ|C=*7bNxaL94`UqKeTy+i{QWJV>N#J_~FuZOO7G_ZKL{M2Kk3%`44;k3-!+o@vHh5^Z!Z6 z{}TAOmsDH-Ya-`AIfmAMw^Q^l*1sns|I5J7K2eMR$_4WHXHPa$|F&1;7w3PTj`eRS z#DCqliu{Mj_0KWHzm8)46YJkq=>HY)U#sZ9)OT@*lSTRTBSJ z(fW6<|Eig_hC5!ZkNh3rzg5wHijMz={O_pfKVHfCry&1Q;J>_EE&uBm%Jt78{PlFZ znm+$oH+23J{~IFztKdKJsTzOXX(a!rn92X0qWa$m`IiR&K2IlU2{D-ao)W1XW-;JWI|Mpq_6aND5e_%+Ty|Er(K>;E+59}fQG-;p>C$Y1`Y z9RC*K@1Wb&6#wgmum73*zX<=;$p1F@_jwA)-$eM?hI0P<)M(<5?0*LGmxF(wr-1x5 zhs*WfGQ=O*|CY$#3I02oTKuP||Fh)tUpr`B(d7T@sQEt~`A1~=4_p7Ke~09Mq2fQX z|Cz}D4*2(Z3K;+PBDwxKhT=cGe|P?qn9t`wTOt4Q;NSjUE&gi>zfJfne<0h{6#tVI z>%a9GAOB|||GVJ7Vj&u4u~tZx!>u?OI;{w?+Pu;J=a9>7e|Z$nnnze~NBb6MvOr z{TKdsK>iQFzt2-Ze%q4y9m3BygN-Ks$o_Xk{*}PL&r?AD6p4Sfi5&k3&VSRyAKt$^ z{>2CL_}>ZnKLr0Nnx_HzTh1W)Px!08C`|r$N6r83k$>eZ|6%Jt^=})B|H%Gpk^dv` z@ADMUzdeoQKk;9v_*eB`dL57dosmBd{+oUzaT<`HeJOwbX%qe~x?N5AKP7bick@3v zpO62$B7X|}chNiz$lp0#_HS8o{jlrR{{S%PXYOzxpMup34fvD zKeGSbk^f`x@ADLpzj2<-?-=5b?0*;JUp32r*!oZXGei8U{u{b^{o51yKLP*EG*1Ki z@7a>%|5Q2uo#hI%{{OvV{?{cr{~pLc3jA9?kvbKSzq?xIXN13*ZdX(NTVJvM3;zk^ z{}lZDJO$)$oGJ5Lj{NyI-wZaI_#^w@8~I0rf1js-{1uI){t^EO&VSRyAKCvt$p0Dm z?^ewJ?yY72Y*RV^s~3^H(!~Em)coHI`B%&GAGZEe|MtJd|9;5-Ir#T^3K;(_XUXwz z6aR&Ze^vj^HN5`si~M82f6Yo{oC?U_{^WAf`92om?=DdN-$1ecC%56Be;G?13S7O0M(tpE`FP3w3IMwp`Prj#2_4Q;r>?=k~^T^!K%I>wY|B?6iI4Dj(sWZj- zTao{yf8;+s6u;FkPyYADe^sIR-Sux#{}0CaAD5N?VaI=(|BS@HPmHGcSIvJh|2-V} z#{+*49jEw?=ez!)r@wsu7n>&gulc1gt8y|JW9?e;@R~gTx2gZ0!sP$PA@kq!FZdgfzY_Qv z-OqsW-*z5}|1HhLe`NmSkbhzpf7tk^{0{X`6F^h`N9I2s`PT;iT1EfKD`o!{@!v|f ztBHS;sPTUS@~;E@zWods|M4c7-y!@|zpmrI$o&67{&lnX!^S`5w~L%#od13z@=pT( z#IK}I2lU^*vwZx=wvy{#*>7aKn&RJ5jDNv@GV-qn{J#AR$lrN^9RD`qFI4!Mg^R=afAie+kK`rtI_OYVQUYJo6@2|;XF30U@!wm=YW%#k-u{2YesBIK{GW>c zr+|N-C;oc*=D&3p$@y>1%){Tu{yRo;|EIb9V{cxpk?|j&!TB4x|L6LZT%8{Of70XMQT4yNVgF~M|F6Nn z&r`tsuOP=imZ9|zRsZZ1{`uBf-2dwRORfd~O`7~$yDH}Y8fN^Le!}DbZ1n#P_^+pV z8qj|kJ^mw~|HnrbCjWaB^S@?0&VP=}zuFi5OKt%F$zL?(zpDRnhW($5{=WtPK2HJt zmkySX|Jd|A@vo`=tNQPp#{Hk?@^7)mfRdZRe@l-Z|JH7K`1$)v8+&}A{kzA%)iwP5 z$MeyDH~4QkR_*-HL`wer!y^7GRw_*X|Eik*v$_8!m;dR@2bA0n{%e2LG5yvo`;_%KL5A< z;pm*7KlbwU(A{x<|F4R7IsZlI|9kM?N%NGyLcaB%HA`1g4V=)dJ+`S_3RnJ4}=<-e+bk^h&v{0ko( zSn>e)FaJZ2e@D^3J<+iL%h3Oi;6Fw4G@$?bFXZ}f6aP)|!sP$&iuqr01h0S1F8{oW z(vnBPf5V@8{9B~{@wYL5vyNf^m!tomz`xH^K>rPkWdCe0Gx@LTKYkSV|6lIEuC(My z@NfU6$G@ZMf07yh%)9^T73lwG@Nca`@-(3Ty8p@b-zNU6S0&rkRR8}_%>S-~x&JG< z|CZ8{cJSY+$-hPFU;e~*pJ7in?EfnC{|or{c?#&i_HKFopC!!XzpDSz-7{wx31l>e&!rxe=1d;Y8a4d=fG{r7B(F5_Z>AXkg8wGu z-vs!5`x%hG{aQKx9m0>|`ESL-esI=TL{ zS#tfW__Hwazqw-k3;tV>e^cQ1?Poy#%IoC#w+Vlt;y*I~&B(u57Ju0Ir~Fot^Nad- zEAnp+{5Fl#fd1>ZlkflN5PoMonOAD6f72A>U+~|K{L_Hnx1Ry|%Wjb4-`Ymb|3bxo zWd7Tbe~T>su<=j%S&{RL`gaHNPY3>v8RR%Mp#RFFmZNzmslPQ~Xa?jDNv@H}Y=<{J#AR$j@$)kAED(Unu{o{9^s@I^_Qy)_;8KGy(Y= z?;-iWkD2^eUH=jO??V2WS^mT3KlN`Ht$+9YujJ8V-1AKCMgBj)e_}NVB-_=*Umd#s5&!oi|DWLB z=P4k6&AoE|Tl>oVd^6Z+;*adV4f$t*f1js-{PA04|2FZD;QTjD{E_`1GB{HQ;L=9+ zSC;><^^f|upU89nCr$j3{ojZFx5@G!mY@2!{w@9=K>okMe;uvU0pq`$K~ir%dCIwfK|B6^*`eH|3T!h0sq$4WIqG)H{K%GKZp45rrXsN|1+Z2|3{FY4TR6X zsHcGZP4^N0{mj(=$o?Ni{%yg(&r?ADid$uVYdbUik^Mh}{IM+mVe23DZ~a^RKaBj_ zW%&=wPyMrhi~q-vzXbgE*kqkHVEi{cB+q}W{pI*?s33J!Q~ir6)_<}7}Np!mOEsAoA|HUhHO_8|CUkf|C7kS82I;j3drAcKdFBQ$o~0eu+hXH+5c0>zXSO9 zc?!s1cbm-5wl~8c+5h9n-!IF5*!oBPJ0$;6JpZj&{6B&GJ7)P0%TN6~B>xM=AKCxY z$lo9QSFBFzRKWOm+T{3mNd8x@LAI;Oe~DuK7xVvTkbfue-*E3rIj_IUcl}f4?J~bb z^1rsGF#KCZt^dy<{{Zms^Aym3;sKf8nQf;2MfU$Z^6w1(eVzjHcM$&$@n5L?kL>?h z_1D{{JHK?*jfywR)949mu~c`1g4V$e*}Vj(?l@FBE@d|1Tl`;4J@P>mT*+ko+$ce`NnJBmZt${=@Q9 z|JJ|7|EtKqIQVZGr&j;0hvfKoNd8;n$#yl>zkZ7KUwr=i8uITB{>!!_`x!9*D_RLZ z@gIMktgC6_-#Tjje-rta0RKKu0r}gg|AWlb|H%H|LjFC#zt2-Z{v`2l?P!KSvj5kS ze@K@9u=S7nxBe~u-$4F7v;2qUr~X-y`>$A!-~aAype<$@)L>AK!s&R}=p%#riM&zlZ!o!N1Q_K>q4S zi2p-m|9mspXyT9T|9#|7r1PJ83d+Ao_Rn@Q!ynoIJIG&_R)94pCJFf;NRyd zAb-QxvVVv8FI4_V_Wu#`FO%gzZ2hDD9Yg1TM)sdV{{6E2hvldK?SG5^PmzCF@LyU< z>Qun^PdzW^KRZm$|2Dc^P2>MS#riMS|35?i{lR}#o7(tS{*9dfjC}t~<4)v#)x=*D zwf-+e{$b$X=P987mKTWs!)5=4s(+FFcOm});NRydAb;W|ncpV<3&kJV|L4fRT$cZ^ z^^f|uN&Xj#KeGP?$Ui&Fe^`F%-zswdr33l(Utb{qaPVI?k<_Vx@t-2~&nEd_N4Kk~ z{*@}$e=-0668Y=W^?zqI{;sdc=fC9pf4b;)HSuq&SpS9puaUnT{QEow^xsMAU%i?7 zAKCvm$bTUC_jwA)-~F;&|5?88e<>FKi;#armjAHzkNRi-7XM!%|3O*)!}3%AHp%}& zjen8z|6Al=9{iWDtycfyF;f4Ikn_KtZdX(M4^piE;{JDcEh(;ld=&imbh-Rt{r5~+ zK{{{LxmxBgl>fs+*MIl=H*x&ajs6b?{^nXW|D7eWf1A|5CVE_@$^Ukt`Q7WE#rXFF z@~;5#?~Bub^*{9rssBfs@vj>H!v9ame+c;Zc?!ti(INBO`M&?CSp0v7{3~Yp51aqg zzfJ02q4Gbh|5W87wk+&S{MEznoO24cY$Ei-zbh}=Dbw$@W1&A?V!M`h>w?$D*IvZn za$%OfZalr6)OCks{?3B_VbJIOz1Jq7KmEF_?Xb-Ayw-;PLFwn;?e=@^9nhbC-O97v z*Y#R^U3dF6#~qs4j@Kr6e+m3edVd=K;;#e$&i?VP{}u87J^DX1EB?d!r}5AJE%E;| z@{ff0?^s8z{&)N+uYcL3{#C3?wyP=s2P=;M;{2~)kpD37pWKD)Cl8){*MHRgD35=P zeE(C+u4KEK__vQb{{4>pD}jHXr-1xruaWwHl$r4_tp9I6{+3OG`cU?=`#GQ2vd_MS z`WN%nt$4a0-h;$0ZoTx{&7i*q`n~#B`?kA12l{i>zZCQ@lYTEr{af|(^mby*t6No< zx^ZGde|kHhWzze{=@Q9|2Cf|8kT#{#zCNw_Q!@binxc@f~fZ z{x!yZul$c4KL3BC|0BRZ+f9wXlhl9f1ew2;Zda549YT+PWtms*dW?VnMF}4Nj{^T? z*QoK+H{CYm|I9dj<$wNna#Wn99}a(XL7RT8vYPui725Q};SV+jUH~4m_+x5CoTVR0 z{&1kpJU*z6eFDE*tGka=p-n$N=8yOqah850_#+8z`VsrEHueOx@p10Mf;Rmq)Q>Oz z7eoI?Lj3#UlA`9YgVdR-C@_ zKmXg_@S|AzIJfKQBQnR2UVAh2r{{$o^WE?N@!Hfz@O;>$H_x+0D7uRRU=v*SE@lN;wL=ugL|7q?zsta4H+HUxUh&vw_5 zyw-;P>^QI4#Eo+Y`Uk`Fy}X#p^J1}+-RFD#ja%}(fd1_K@;LqxI_rOW@h?9A9f1Ci zhWPJ1ZKSl0@BL}M`rrBoIsQ3O_Mh0D%qukc-%)Y?BjSHB@{fV|cQnPnV<`TQi+hHG zwaHJ1vh>5@kA={tAF2OIHvNe2^=WKAwCoG_ zF%{bM<68bmL7RTWzjPl7XwwfH{_ZqrQ~bde!QZDJ1^V&D{}Sl`7>Ivgobvt17yqSi z%JUza#J>-xkK@1kHD3RRApcm1|MDcs(}4Vx&pKAl|9ZMzP5cdU`pWuYmY(r*X=|DPR86sIy7@$FC)Mr78Z8kJDHF z=YM|7ClS{p6d=$6xvv`TS#~od0!nyPEiSQXK#5ujch{8RTCb{5Mcf z0r}~>ZapdA|G9&1R}=q6tI}8g=YJQf{>AtDTygyWyie+%i2r5Le*?t7FHQscZ+=T2 z|Jg}${QInE@~;~IR>d0bJbxJSuL1F2F<&kJDW5~?pG~)`iGSme@gHaI`7b>u^88P_ z>%V8V4=Q~Hv?thxSek?;S`^_*ON_6CLh{^Nq> z|KE!F4}aGe^BWpOyb%=RY+69Ygb<@cGX&nP*Sp_dh5{{&A51oitB*kmeiz zeX)F;nfiBk-1o}=*a1%;oPI*nsXYHjxcp~T3@&*a^1q4c$$v*N|Jla>()|Buf!g>F zf7ciJFFyYtj`9B=$p7*^)yBW}m^}VlWc*L1$ma^0#=o6I&wt(gZ=T7oe_0Xv$3y-% zUZ=)Slg=`f|Mx&bhxvi0XY$`ZgXjN9p8t)5OWue4Z;t87e=Cuv{`Ioc_9p+*{9kLK zTK>b|nazLKf5SZPe--Y(YjDZO;J>;=kAFwi|J1_z_u{|n4nF>ma{0#&TB2k@dj6}4 z-`ZO-{x>zl-}DaWAMNs2Z@EOtBH(BJH2GKM-`os;=N&x$S9AH>Z(gFL8~7{u=Rc8; zf5`XW^-}J9-S!q{_?>$={}`A5i@`%megghhUH(=1tIhDYJjnUSy8H`khm`yZ{H6W% z#6Kh7f8`V1ONYIs8UBuUIe&%A|7`P+l0Shzp^4vC&7b{~9j;>NhW0(jWNC2Iz@@Ta|y78UCt8oPQkWA2GCK5b)P& z;%E83|D+fHti}v~`*)mwyvx7knL|s40Dt*FP5u@6?QPBQH+OOV37r4ep(RTJf4wGt zM!x@~H{HJe?alC~MsWT$IsbuWCBuNfT@$~p$ZzjZXnyzlSF!%Fvdf=7kLd(h|M0C- za6$Rj|0+7=^$&-vfA~E2@%l&UdE9>-`6s~oM@rNBhiz#66CmE^`0fk8uAJk$+9_Uv<5n^)H)z{_B&XDgN(M^xyFuKmM&m{*%Ced@nWr zM1MK|?RcK!e@*$w3u8jYtS$zF}J>;(h z|8=$Ga|-_EhV{=H%<#7XP?#Ujf9rL;{!d2!Q^3ESP^*7ErLup^kpEp3{fqfe74lC6 z|4o|4Kg*E+2NeA$=5zm3klzOXor?Zzn0)^moA|drA$g@~{M#+6|Mii7ZSdcv$-iyL z|ASHeZ-D%#f`6YUUR?6kzw(&upRHo1{;B#G^WP1Te;x2|-Jn+gXbpBonc;sps{gf- z|FkUsVUK^Pe~08heSh3h*w-7nBeMUEk$+wAUwxw<|Lklt{vT2F-*zpp{~ICy9Pppo zTaCZ8gyjDzGJn%PWV@Q`|L%(QU*x}q{FA_c&+dBW|CS;DPet`V75PsG|2|JVBlFe& z7UJI~{(XsEEdDn|{`J!SHRZo!$p6z({cnQ&XJq*gTmPwltH}L3JM-he&5?gH_;0z1 z)Tw~+?~Ctq{PZNzj+Km5~;^HL({o)<}3;)xRe;)YvdE#5mSO2T}$^I?d48N-X zhM9c*w;K7Ufd5)e{v9}(KG!;;kfbU8Uyh3{2KvS4e;V>PX88|W|EYgg8--!=ox+{oll=_JPqNQ8fNEzXtg?g7|OK75|3n-)oBTFRp*w2Kmnc|0z07aU=Q0 zzq$c(d|PDwyQzcZm8S7;uh8-DW}f)`YkTD182p#rLiRHtKMh>l(DCoGjsg&rlNl_|Je!o&jVHD9{>Pu?^WR;N ze=7K|*X93QnV*+YY&7w|9o7G?$lnD1eV+Ip=Ntd4OJ)By@sHsAH%ddc z6#TdA^1qrH|D93&*CPJ~S^mS;f9l^Va{nU#_dx#5z<>NUwfaZn+cK2@?81nzVqJOdevk&rL0{&~?P~%Symg~Pw{FlB-wyUZB z@1t1%J6GWT_ecKe;NRBe-_ZQ;gQ)%wK>ka?zt0no=zR6xT3q(ePB&BkRsDDW!Trxh z{%Y`FRj2s*pU8av%Xwz_KaA>sKjgnG%YWGVPyIV2|LNPK>+=s)|5c3N|MEcOp8@_W z?;v%G?|8oWr+k(n{~sy(7wbQD$lnb9n+K@Hf9Vo({@Y~zzw9mYzG|xf`zqFd;s0Rd z-xB<{9i!*`SI3b5R8;?mAphmy-{&b{{C80QhU$NK|L*r+Rb0XA|Dnjg75J|xlkfZL z<#pKnXXl%#|FB#Y>c>0(N#y@Q$p7Cg|6%Jt^=}oqfBV1O|KZ3#6a3qn{M%#9_=m&Q zP(Pl3vHo)y@?Qb|9a^XP*7L=G{SdkSJH&syvoQ64ztHucod0kn@?Q!3zWofy-$nSX zGtBsp%wLcES7q^s&40?zikx2@{~m?>R|9_sjnjbsD`(5+|Ja1zey1?;zrSMq3;tt} z{~F-;?Poy#>N=U9%{3GMk@=5C{$v(^*!ZXX4)M?5Mr<_Ae^vR#_e%5Fv{v-3Bg#0&W@rR9n%I^^W{B6WWQ~gurZ}sB; z6y(1J_-j8RaT?Hn%UW{$Tf~29ifmUC|AC?7-@X5R&2N1DV=b5e$)2T4hQs|Y8%p)u z|CG(n6aN?q@^3p8`u>+LfBoW||1_6>)auKWi~#-)RsNM^|F$B(9iBf_B*poa7iB-W z{PCOI_0DOxZe3Cf{4LWo`L9#-zjLAeyX!w9|4+sIzZLS|m!|>qzq(TP?~weLgB<=9 z%9`)5MTbKEXI?q+EPtO*clozCcvi_?;6E{4kAGXyzrBlL|2F!+Ez5t{@sIkqi`GAn z|91X9&vp5yfA{w(dxQU)-PHVByUFp-4phs3yKHpM^#>8~5r6Tmf1iQ=ZwLQvbe!g| zmv8-}Y9ir3Q|7PxxG>}YL7~Tg;=j@5UkUv03;x;eYW~?d%SqmBMgMFm!~V}i|960Y zpQnKSJBfdr`1ggaruwhyzw~>a|7W@UUv>X|$^qcNeRp^LFYNcfbQAyVAUXbh{JnJ8 zrv1-D|958j4_p7Kf2(NyyYt_kqxk)QmK&VO+Z%T{zT{o-U-hbD{u7_}A&UN&Hk1G2 z^N+L9e=GPe|Af?O&XuqJC)bwizeD`D)9q@?|ARxY`Q$YW9>&X7?EA#O8vHzxXx&J1Y|Ji>3DM^9SWD|JGG``1{y@;&Sf)QkVa%i%%%|5&XAl^6#knA8y$HMd%-H z*&_Uht^d?ND{}ueS8@N%F8`UIolx=%`0rfOJ^wrG@t>E!UTYnmC;q)BlGYw!#=p4# z|7GYOZrQ*pKPPpX?_a+8f7c|r{##>Y{uJG=ru;utvHmBo=KlZd^3U1t#F8HHU-q`9 z@n6wD2?y=}^w$4`|0~e{{ovo{DWLz>^<@8!q5N0%FOL7ObosA8{lt>rz<-@4|5m*m z|3O9C%Nx%B%h7*ZmjAHzpZd3p*1x;{EAD@P74km-{8b;TUH{WCS&n~pwd}unA*rjH z>fd3Z>mT7yBL9QH@7vFS`Cnc|_>Y(QeevIS{FzrSFXiX|9D)2>r>}ooO3(E#mZ9rk z;BwtiKT!WO{AGhV|9s@11^kVg_-#Y{aJgcrACJFoRet`%b;!RB@TWBKJBIl0ROA=_ zuSfnG;ICR*PyDkcGx^`D$S?fgfc)D6f0rhH%Mkzn6#1){;`x6g@^1(H)-rnh+lKh> zQsnO(&iQXb{_TOkTNA%yi2rUy{_>HWzXkbs0RH5%di=8s%;f()iu@w}Z$|zdfxkx+ zzh#L3UPXQp|FzZLm+2L2XJ{Ei|2_bc*?_`ePLYk|LZ zIX(W_g=YM>De{Z>za9B^0sdA^{FWj92Nd~*|2vR>SKvP?CE2bf|MiOg1^>Os?*Koe`x(%G z#fCCJOPcW?ng7Qjne!iG!1;IkNi(%@rR9n%5N7rzo>r? zApg_AU-uP>(}4aPKbG%*Vv)~(9J*ai{*P3Qf5HC{@;?LozWofypZtXIUu&lRN9KPJ z`Jc_=4;%lKpA|X3sDBS5e>?Ekf2|h(>}1)$P59&AknL)U|DzP+U+_PQ{LcZuZ$AUZ zfA?N;{kKW}du3m=#lrsx@;{%&A2$9ezeD^BZts`Auh);}Ic{yl-eyqe@G2Mf#3E;3X9A64WR{+~epy@0>I zS&x6q5dULQ`JY7oMB4udJ?nptq4hr}D*sc+zjxZdCVtzH|Hl>i#pgdyBmX|Y->!+@ zF~t8wRQ_j>e_!B_FRv&5*~Mn+-;+`KpGE%tfWJc%zh#L3si^$z$iF}E+bihtZ&jG_ z|Fj~%82_I`{sVx&Qxm^!$p15n{9^on9{Fbjf8~mL{5yvDpH<`+_5TIruLJ%@P5kT< zGx6W9$S>mmMdUva_-kHPJO7!^|7}D0|C}Pfi2s+6{~+LRn4xF>ZyEah^La&n5&thE z|G~hY(iH!;q4pvg+f9zccd>qB~UWq1} zIl2siET)-$6oViT)?ke2N3{qL*2V+@2F|95>NQnKCQ#_QkEP2T^p zu1xNK9skqT)l9noam4iB|4QEfsPy#z5E}o|%o_h+X#PJnqvQWVU# z@Z|V=+W70ohne;Mx1T!x-TU8jJ^eqF#=mh#ZJthJ|9kcCg5><~RX&sE|I;%%{y|Uw zpNftD^xpr}$KUytkAL_6|3Xjy52NvKTYl#3|IRNo{?APR_$T+jmwNhNr2bcDQva>h zewq1Sng0GKkAFM&^#2)}|4pwY_c2+weck`9zMuU5$GPg4>Hm>G@%Y!h|GnJP|Iupy z`~A$B|K2Y&|DT=F@qe+W|CQMIPw)PxkH7URAOF^M@ci2=J^dd;0JNQC6*x@1&jhl zfnTu#xxMRCf3NT>Zn9~bQNSo*6fg=H1&jhl0i%FXz$h?{3Y0FVXS7qerK{5M;`8aa zpTQ3^{HKI8(CnzdjR)0kMD4Djbn;lb-?<&n51a7CDQ|yr$gK(&>k_^iu{(Ac6X9b0 z$WKkTpI~wJ6DU9AyEK;hVy&B0+#Y_{7Klr@;!At#_T>1k#?RTz_rR}3`(5w@jo*NN zh2Yoyb@!{YRkvu%5Pm-eN9#mvK=_h`x2(y2#9Bv_|JZTfUxmw8BV74uUWeZ=F4k*d ze#aP&EA~pl3&fY>eEZ{E&pL+VTCL0%YZJaI@!S2;QGdj4O}L6%S(odJb&ut^#Wipo zhV=+napib!pN03~6R!F@Hzjp`bWv&T=r|t`J}}0YQ>DT7R@Og@(;ny6*ICaTi93m)$b1E{oV%NdLAEF#coZwIxe;B%g2AQBR^4ija6-8Ti8+gpEsI0Za}y?U!b2JMaNa|HopE3BfN)i-^;l5nc`c$_%?9qR}1(K z;ql{SFpiJsF5#*@!fzPM{;wc>p{SKq82^0kT5|tF!5xcO(fN=~xcE`{VSnL%xrEQ3 z;^!*(QRflr)AT#|`GWm0+Vg*x@CC?^v{UYP_=GFn^iL4sI!gB=GH~n5bbV~XRloF) zOL%I(2v_<@zg+3pSLuF+6TWa-`w5Th+}z0egc*LUu5|x)2CnyKPRj>tkB-)V@wh{y z^GLBF@WRo&{>9d=Gdi(;8piYA2X+aM=0_XO!(n~G=b~|ybzVFU>zQyFS9SjEa|M-U$0 zFQmT#;c5L1f#nv4R)Q>;t4=%e_R-B|xC2v_=u|L*hu4cNcp#y1CLFu&UZm-dTpdOVY71-y61MeDzMC+iq~#?}We>t5`` zgsbtE<8$F(c68kH-W!*gui;grqW$Cw!q*|btOK!~gbyOTZ8FyvYjuvZ)OEXq_K39! zUxIL%zhbu_T=|jn3b8)nYJQZl4~Y#UKRxsNB;233KHz@IylMQH_cfbv^OJ7NO!UO z5ndoavad}%hxHD@mv%~fRF}-hC}0#Y3K#{90+|Zb&L183dzJrKmyY)$YQWqX{xn*z z>^EAx8u;nb@Lm-)VDp8huif8Ir++P+$r=TI4GQ>gFA|;q%YCGWN8&yl@b>NadfmB( z&*$GKT%E7h-OA_3Vr$-AB=!EyaKhE~tvdfypKw{e&h!aa=hgZrBz*4Z>^WJo)_W>$ zjpZV)*qY8oto|u{m+-XvVP1qMeXHD+gvYOATMxr~e?CZW=U~Fq?pIwwc)Y*4t+>Bo zh9CRG^!~bpr?vki!c{xve7=0b@1lJxBs@(|>%SRzZwU-C2P)vNXeZYHfw*5C0GI2- z`n`A`=pnDit-UIy>;c4sNSuMSt;|Nb%|8Ei=@9)I5dHvg~r~7dUPuuT&!qeLSAmM52 z-(Dl#zmtLYR=^;0q5{Ev$4Bemn#A}0#D>7-zMt6I`;U*-zub2c>k_Wkv+NggKglOt z&11Q5CN>~^Ug8J$a9pvU!hh*3zE36AeUSageLt}t;VQ1&kCg8Vec*E6Pi#QAy1yvx zl>2{SXIX=3-DE$;` z6CT&u+~20bG@qZWK=5?N`UfuSUTp0%8S8=Y_`H<$;}f2`{s~WA|L|Wuo7cZs_qmMq zPk8G32QKSgY(RMG`j7mltpDdT`b&7~`X@Yf{S%(L{^6(B`hOu~{SzM7*{uJcJoQaQ zrN9OBds6y7z1Q!51=oK6yA9!ksG9sUyME`+cr|aq{=M-N%2z)7ldfuG%BN`xR?ll8z51ygsEpKH=)R zL-vv8!F=5jz>oayS1g4zAESWfy}oU<{ynTiu|9B_Pe-4_zi)3RT&=?#ezz|+{P(u0 zzyG)2ApbNg<-A|)7KE$cpU8Q83+C$sgsbanIbMsk|HFP{y^3`r+_I$IVqL=1)|*GT zT5r-0u>s+A6jxvWb)o7nsjwxUH-NR@WIwWA#X7)6H(CF#hRZ%;rl3*4DDd+s;5<-c z<$gZ*)9rcUM2Fwhq&A(IW(6EDi}&+3Z1Rlb<^m>qU6a{d50I z{=LAJgvYPLoeB7RBBQH(|6KdtaRtKF^8)hwmVy7~I0qB1?mILc%Js$89A1sS|1TWP z@x;1>t9FW?)*twL#*+w7YfnhHx-THt?ehIa%@N!lxlbT=JHl0a+{3s%VuK^AmU>^1 z_>t>>>!@nx@h9?>NGjCjZh-dH&}u!lSsGA}*|ZQZ@0sR(+XuzLM}XzJFFVdVZGC`x=Ahvzb2$wywna zCfJFvU9k2v`qkq$pk1x7E^G&E8Ft_tI=;GICZDc={cz3nt^X<0$=AX<(^=n@_C3OJ zL&?Lhhwt}%*Z?+^@BJR+dN!;B>%w}lK5PixdVX6BqSzGfc<95mH@@6YRgPSs)d znX#s&GgAQv&g6Gs#_~Qer|B>==alg^`zYX`sdL)-uIX>`I%oEov8JUnQvnCg=G60E z({J7fX6BqSzGfc<95hwFw>Fl)ubc?oMUo^#Nj{~=tSmr#G_ zr~COI!qxL0@|=X&nk_S){~(E8Itk*58YIhxD)qRp8FA7TS)J(OL$s; zeZu2^Ur3(+2?ISnSF8)X?MTMOdJ3l=iS7={uOVEGx4);&&kMqye5}H2EE#99 z)^Y!-QF^Jr52e=mI`a2t36GEK2Eg42r}u(A$j@Vm^?-+GF)sER!sGLx^FzISC8iBwB9CMy;n=x*|<5cTlWO^lYfZgiuDOs@ADOXwX+Vg)t;c-7j(l19TfFD`+Vy&_Nsi~#b=>2sFkNau+J^Dqs z8W(B5tbc;c=eMZ99vScd6I`2@TN19;x%}O4u>s*~-pG6Z#9G6W@5Af<``?5sKl1)S zv0fAN<-LDmuOwWpXPL+H9zknQjw|o|6KfN$-Xkb~_gn1NgsZsn{y?$rpE$1m{x6U4 z_&y@<5%dXH{gr*8`|p1fuHGXk>qpjq&0a%mS0Ge$5!+0-+8=wpM{sX$kAD0Q2v2KI zNVsZ`tb4K6K8(wI|HRtBrJeHkzsZI9%s~n`=&SiYjE{eFst$9|ls8>93K#{90!9H+ zpyrVwwdy|K#GUNuI#R4l_-bS6eJtAf{}wM1pUzk1?|z7V2)Mg8zb99$^YW0|`1^3= z{QqRam7m;W%ol5Q45?j%+9l`xVu!xR{JK21Q|xx{Gv0at|2;CXVds$Oy~A?eFLuEX zhSdI%{4YdF-FL{n&d2?mKV(1Qm+VKZ`{j^Ybw5nb^Ebr(h^q+yV+?N^%zm7&IIf&m z%lZF)gsbZg(M4=XxH@mwb+)=#H~sv7OTy!E+ZN%tA>r!2iJbR~o$G6kEBcD{2v>2X zopS!~&bw9AU%}=2|4PDDTzOx!x(TN4JJ|DW6~&eJ_=t4~m%lHrbZ*D}4wrBhS9oGQ z!sGKKe1q?+JV)u{Rvk(hhs2~u+IF<*YE%BPq^Yw!n_r0FOc3&f2pl% z=OZ0NAGv?@F5zlE>v4mnIj*{HRUdi(Pbc9juDm~6tks|6%5|>zw}H$3MzIdzaoyza zL0q{?Qa2y-#9o!#BkdQyL-_pE9`P&oK*Ci!<@#J~Ffi#y#_Mgu5CQ^EWR2v^tF`X|ir?{3KRS>7il_Bz7Vys9HdYJS?-2mFn= zopK+z+Y+w!rCy(*Th*>keq_9w@%M~|5U%D!!w5TCCt|IwSvTE}O}O+|m35%M4&h5u zzA|q2=vm)7?ZDRGnQilE-cKj)!}*RTwoSXT4L4># zt+?-B+z$A@Tu*OX{U9#)_hu{Q6L;Z!v&*(xVB3gxxM*M37{-gO?7!|bww*=P8_m`_ zf^GfLY&(u&TR5Bfl@`vsN3!)$-h342+fh&2S4MwZ@P4^2w97#|1GKvh`O=@*PaX92 z?_`}OKE!{=(8m5y!ueML{kIS2_Bo^2hC8yKhJ!iZf$<42E*9F=j^kZD^e_LJ>$Nm< zy{YMb^#Unr$=uHDVnU zu)a#;Ic^K)frW8wg3V!`RS<6==0j@@$89={{a1!@z5(;Fb+Z9{p1&@5>#_AVVq4mn zZ6|EqPVA@Q32sky6E1JxnenbaaK7&KWh1}VW}FW;XIpgG+Jo6vV68p5zPAPA6F*-e zs^5Wp^IlvYz;+H{p0gF(;@(`|IF$1~ti2D~g?!^YtiOK<$%x#B+?x_X=X)0^Wk_R0fY~t8q#jDr@WZn{w-cgZ@*9YlH^DKgoLZO z>iY%tnM>YF|MG~$?^uIzxL-iH@+0kZ_vCgugs0t~yy8FHo=LdxAl3>wZWJ{3zx4@M z{cUUH>jJUCTj~6_2v>YvXXkBhr}V21{c?fFLPr05>wnx%8CS7xwP(B(abftmjc_%- z?YMpwYk!vB&MgQ}Yo|}R(o_Eggs16w)sGxE!2KJs?=7-l)E@a>N^F?hFB)In|H6yz zXQ}U@`k|n7suf-T+V+0Y@2_?KeuT^SKB}zwcg(j|NcTU0aMfSYQLIOJT7T_)dfX9& z%l9uTZny}?4GCBCR{zwl%W?Jj;1Zr1*GZ4NAK~%-7SZ33@H9Wx;Qdm^>&l&YT%`YE ztwK8AAzaq*_T(58PMuA_W0_wQ=-BcRZFv#2on2J26$S7bGFbWt2i~_Tz z0$KO}gCZaIEBCOi8=X84XwdR{=bQT|*ZF$BJcIRhf76>UewXa;^wyu<`2)wy+5Mm0 z$8Sd4@6X}$e@68)^^F3vg92H{|4C;3&kn<9+GrFo3K#{90!D$Kq(Ij3e_$#7`p?P0 ze^PK$$tYkHFbWt2i~>f1S)zcmX-o9`KY4D|zL$SbHj41H-~YMW6Q6z`qkbWyes33^ z$b64*_4~hW{HjsW^QsRL9{o;Bo=<}vvIFCjF5}>DHs?K4{PIa5FXcGe!uux#P9vPJ#Q@YTk!m_ zSfB8;{sx4{`zz1?hrkn!r;L9_vi+jZTbFSA<@cLnM_kHy^LQS2u_56~WqCeZtbJLs zzuoWuBs{JCF5&U^i#{IVYF;fsNzIe%@H@hHZi3F*JoIno_9$QKvkRU}e~WN6pQYVm z-CJ7d-3au1(=mHQ^Ioh^_&kKG-)pLmJpcb7;p%yBHE-3Yt&!)+;9FbhcYtcPB|ldZ zo)*_G^E{OKDg7NmxSEHuF53IE|B&!S3D@}p{*mtACtSV%LfUyUbPEYr^HB6T82VVZ z@wiCbx_{z#tAqea=qolLd|=!G{v8sY_IpkL-j?Y1d@`TJ z?)N13SAM@K_UhLem;Fer`){5PdT5{U0<~U#k6V8+?;CFeSHFK%^KFvHI=FA7x6}TJ z+o}71=)3fGuC&lG(R`5hi46(wQM1RJz3?%qzt?mKSL;Y0FPHGN@$v|l@lySg`Q}Id zd*aEz9wc0iqpW|ic0cwnF)qgZaS2cRU8zTS+IsilN7mOr;3ptFb)FEOHczJfE?rM| zxpclyc-rqo1Hx6G^z{`27hQ}s3K#{90!9I&fKk9GFsl^s5O_}ed$*>)d_8D%FgoOB z)#hX38U>63vs3{O(dX3n-kW~&@z3ZmXX`LaHz5<;C}0$rB?@?mTD+h4KVyv!>Uz-3 zgE?y+%#zK=1T_j61!k!N>USSgd;d=bzxOZUeE==6&1duT0bL6(#qa$_FPhsJFTgfz zjl9?)$>$1+XL7y?R>bI-fO^eIzLYoh?-PxJ4u&-Geir@I}9 z+xZjgJE%ACC)S_t_L>St0i%FXz$h?VDexn;mR{*;S>MdV$MM>E*)9OP7;NMG5$+we za%6Kyv-M$v7S0!rVH?60kLA2|9NQACeLV2lN-fh^qkvJsC}0#Y3j9VC7(O!f{r@)b z!qNOZlUPUL)OG#+|1NO-c{q>o_;VZb9($kg=-ChL?*)W}&reTJ={Vpkh6GJ2j# zp5OBEzI1m#_9M@)$ov1VAbcV6(|Y)!(eqehYeupkd0wXl?-h3lSM3p8-v93rzJO|v z_IHp2!lUO@^!7(M>7%vZ+MjjPXN^sGnm!KUY0r^(ge!fdo$~(w#|T%?dntX?r!blC zUt0&TA9?Oi>|nx`KKdshJpTM*r@ZeSessRw%=(DFV(rnakN*CDC&G0vmgNGM=d;9m zgs17_6Rz~}#_;%x4GCBJ=%3Zb^ys6WTgqR>`nZR)ADw>%;R~nuv5!dVQ-wYb;i^6I z+@DyFa5aDQPe8buKl1+n!{oWT2-n$^Ka%H<=y@XeHsNXdIE1VAh>l`C!qfD5jPUsU zaiEWNH2YEOOMT?|zrlp3>2n3)%8$&?5>?Dmy%2sPC-MKar0XB2n134ui~>K80%~2S z{r$h@XVdR{S1w4$f1cJEuSNl*fKk9GU=%P4{2U5|w^XC+|Binj7F{QMm+lwYd2X#n z@Bi`fchbd%gsbZocTeVvwaNQC*F_XLTxZs&GN+}0mB&H%zw+e5f&kG!`b#QTe` zAY8Razn=eyaMhl6v`4IWXEpkJgyQF~c%M%|c>KCLw;ZmE2v>3S`wQ0n)#yDf`u&t` z2v_fc$)C?Ui1h>RZ^yYjeqtXaJgvX>1Iczue_g`W_)7cb{XeG@uKFu~|4{5z4|01- z_&fAs?T5Hu9VhWT5$h7J{MY}T@9&5`iE!0UiQCx5{R`noaC!faH6=s0XR6WrYQ(Qt zhj0~F?jOnfe-0o#tzRcs()(pSo17=IZXCjuf4S}#>k>XM^-Ik|^^y1gcoCoUe1P>4 zdnMs%<7GX^al7u~c`SAX!qxl~edK*CqX<|1l64}s=7p-YRtn!GTzL_{Vtv9@zx3<> z2MJFbFZ)Gqr{b&oEb=}v2ROlrj|*J2Uw!2LKb$lFHwqX9eoh6{_y2V&z@!EFd;h2F z*uDU}GJo%Htq!|3?0T>p!v36%G`@`jMggOMQNSo*6qur<%Am81Xvlwr~@BT}uFXi={ak=E%!JCBN{nu%KXSnW%Bwy-@?ZWd1lGkkq+O6Z$ zn)mvM- zo_DqS&4}05M_lpKK8-x#>$W_D^}A-UemH~m2hQN}CpUxjn`W@S(?|W*KFZs0+%Nyc z`SsCuLuVRp6!_T`2)zn!23sG$ zi|s-_E6~6h{QXmw-){VHZck+l+6CKzzfa&G-!&TThxK3!ur_QJ^(Ml0$1(pf3K#{9 z0!9I&z;952tmA*~M?P+5b-5Gg0a@kwbEaNDtDc2=6XiL83}VYq^$&k;AN3piD9>ot zYy;Q#(Z5n3`p-5UH4QZi7zK<1MuAiXvX1{veH{N&of*(5U=%P47zK<1MuFKvfvn?y zD~|t@%z40UF^;B@MggOMQNSo*6qp_b)bT&<`Tu&n|E7ZDe>1SZQm+r^)XN8ka%cl&sMo>9*zU=%P47zK<1MuFK^fvn?y zQ>|R*&%S*#EjJ1n1&jhl0i%FXAYFm1|`oG`kb|ERquuqK8S3? zzkVO_#XcC}HCE|!#>H-No8s4419xTrVgumqH`n8N)E;YaNCz#Dew z_K02R5$3n-#QhTMKg#1(+KJ2ec5pl6GEQPW!sFvohjH03V_ce_h5v_n z+)J?6KF7E|?pHj|xQw4z>jfT184s}o2v<7G_=)uhSK}z-@^|QYHTa$AuUO|r9!GC2 z)<>*Mc-lC6gsX8>Nsapi_zlrfI`zsY|5M|m8@Zuu7D?%s@x zeH*xs_K0=gPOg`WL^s0KJnRBr?0|O|x7XtKi+z~zw0*{Vm-Uo&)G>y~^AW<8|JGA^ zpAj3p$McGYAn|#N@U(g5ywCHhGH&;1e-PVDxZ=ycAlB>T{wADL#wR>&UIm1!In}V! zp^<;FA>lG!%2%0^IzBXHjMo95aDOKa;r@=eF{xHf5Z;>jPZ%U z#a;=#xrzOY9q{?E+8S$7t8xbPfxU)s<=@(q{fiy<1>-U=#l8hx##^lWCG+e4$>S*Y z8sL=?jEi-@8df_G=_K=^c-$e8uBQ>M^w;;FQ@YR|95*{*?XQ#im$2_`oT2}zHBG7W z)2VHW*1NPv=I2R-D}6*?vGdHucyUkGS?v43o1mxInt7Nn`?%PV!0Z0R`imVnFY_yZ zV*g^@`I@5RCP|d|oJ4rqx(EqZ`|XloKXou4XXmbCzU;GNeZtjoQ~w0u%kffdNVr-T zy*~4&`>_d^w)CoF0Hc6Wz$jo8Fbe$I6j-#`T7s@80W)T4IT2Ya_x{9fb#b@$VV@rPz=3cLMypN%%s<7rbFC`x(46`w_fr z5k3$02#=2UT7R7tnyHPXk9NN65w3L8KYoPw^jGu=GVqY_G<~cAJ^H8^7olGc;Yyzt zTtA2%Pq^q4wF!Uk#a@~Hi2m2W&v3$(KKkbY!j&JZCpEvOc;W zkML+-9nRMwd00QfQ}hAujbXmnknmJ}*6Yzn&4=rxJ%lTL^v`(0;r_0J}O3?=(8dF>4(6FNqYuo=tH>DNAx@qd_Tfd^Z_n9iVX=*)n|(y zeN>a~koFKR>r3G$10PR#T%U=j^7^v3Vm~q;?gxK3;c4?HAYA#85y(NG5Pqb;r%QWw z&d`VO)b$nNbe*its{pv_Q~VPWo~q9-+^;xS{o5ftb^Z_@*T;Vb`s|+WXE@;tcdO77 zB_KSmPrc}q;l~-Cp%3Ay`b2n7Jo#6Ufro^r>N6s}Uk>4^`Vb!1r$gq?{^@>(6P~8e z1B5F-YQCwD4SlS?r2BD3XXrzCsy-3UzT^K7GVqY_RDH%|w1@CieF%^1)3_G@9^XDP z-Oq5sQ}rP{uFpWx=csf)&bSPH2v5}~!sE*Dzk>`sBs^80lQP;vc&a{x$Mvbo{5dt< z&v3$1^&vd2kM}zqzfMc{V`tz_2Hsm4gBS&j0!9I&fKg!9D`2Au)hqb8r_RHFq>r_b z`WA!EZz-vBtKywFF4DiFahFK?(+5j z5S52sPkCLue1lD+_DlVnr~!%kLpF`-cb?x#zxT?X>>q#cin?#rQxgAP|GlH~pxC2-|5&+m;@**e5A|2p z>N`K|6V=bh^igdP|IU5;M&)sRlm^}9_q&mQslObRCF-v;JgOg@)6>4?f2WzoM^xLPB`9w`;LPn|D_9h{I3x6Z#{NsqW&MX`r)_5s9f|PNab<;!@W+3{I|r` zk7}dzKb(AGRNfwouQZl&zc?=PFZGwEvUq*_8ZMXkA5(cezSVSkRA2TVwRYqCqt$#m zA(mDBxMzP^jq(!Ts;7;SKCLnRSC5w;cxL2Z>Z`F$)PL+uRh>4d9(~uOtoZjnzCKZZ z0F}k-d&}RTYFi!W_S9dS^4;~v-jJxTv`f@Ko9kPxJ@xbP`neku^;gmB7j7hk_TSk4 zv>xTV<9jzpNmvnqu&m7$G3(( znW(>%RzLjk>8M=VujWp?{ow+Y$bUIDKR1r~4{vxeI(|v{pQtPYQn#2 zTf+aFUq$6IKh)fbk54%6d*#Ne{HL!$h(4WjyfY<_PQufN6~QMo(5N1vhb^1b(r+AsB&qF{;oXY3i( zFT~bwW4!*EdnM}k*Xp~2?}*B!{c8N;?RSUY#s2@@vwv(y92r0NlYd6#@%>}_c=;Ch zM*a(^ua3Wo`d8i?)sL?qb;K0^;iDai`nFa--1?QMetC3{e(L^Bcm2-S6ZO^j#N&ru zuSfO0Sp8jM^_@$?M13{4;`N;~-sJix_r%{VUVotvqVh^?e0PtRpYdT-9zXxuBUT>X z_unYK)K|yuczt)*AEI&(@sFYMczo*sE*Jgj_fd)VTN4&n)7P@k=xM*&14KXT^kt*+ zFt$JK6)&&*9sRzkr@lx3PShXxyQqGBY<}(&uYY~A{z-cMySaXIZ2hP+j_&qtvRoqm z$$I^5my6tg%Y{;~T0 zkj)bHFV*V%FKiywFUF2f2gK{&F*qtO#m?`V=N4$P; z&CsY^;{Tq?ZZK##v_ zW8^=$ey;BQxfu7~*_dd*I{qixU$;$E-`lsgyZ)GX{a3b0)K~jQyuQ89PTYR1pGT-X zK7Z_g?-cp3#?Bv(jQO_@*@fF5D?ch$Zq=yY57O}sob0KDPdjifAoj{;@5I{{Kkj@%~#6ak=b&e_asIT_tczt)-E2DCWzY%$h$9Mm5AN!xsv;UqJ^Y2dhqkvJsC}0#Y3K#{90!9I& zfKk9GU=%P47zK<1MggOMQNSo*6fg=H1&jhl0i%FXz$jo8FbWt2i~>dhqkvJsC}0#Y z3K#{90!9I&fKk9GU=%P47zK<1MggOMQNSo*6fg=H1&jhl0i%FXz$jo8FbWt2i~>dh zqkvJsC}0#Y3K#{90!9I&fKk9GU=%P47zK<1MggOMQNSo*6fg=H1&jhl0i%FXz$jo8 zFbWt2i~>dhqkvJsC}0#Y3K#{90!9I&fKk9GU=%P47zK<1MggV3B1>7h6eT8p-ai#j zp&IBXC{Ta+l99dxe`Kq>D1D!f>%3{rx1B$8{Y`6J!<#)7D46*&dk&mw_0OU}e)7!S zKi%;&*Wb+QbjPo>UDMmY=GkQba%$7hzoxgpzczm5%=G!)Fq@3a^y)dO-*0mqr&otx z8^1J@_w8R>|7O?r&j%YnpvzW@-6r_EY%5%>SQre0*~}{yF8H?R+;h z&zkktHhSuDD`uX~c5^AM!G6Yl+%&Gii~_m>`A4U|Pw4#V&3FAm-{-XK#r-J$TJCF1 zq>2m0#b;*AI0+^L-Zov6|WH`@!}ZJm2p8?zb^Ne(Jn3^^5}3qCo3R zy00@4-;YmA%s8hylfO5Q`<@m5?$oXi2KI4WEzTtU`|4{m_S3o}%)U4^tvc_SHht{J zXYhFX#0=J-S|@(NvaXt6$NkSHbG-irN8N<_xfN)!ejV%T=kDjU`mdZfZTs@H`kPt2 zi8J~9rDG=hn_2xdetsJYgtOUwfWB1sr|~?jYX^g59ka&&x zyq4+w{gpeDz6Wup^ZU5cuWY{7|H|5vHNFOC1^iije4Sb2P?^o{dj!9+^UrA=$CCEk zp8FH;mrrXv!<#)72({~!+-$Z_<+XV|X&UdR&#KYtI4k{pZC15sdgC_Er1P)ojjQvW zX}k{C>&>iutM{1d_{goOz^Gef3Q?? zULza(gm{PGS7zPHehH7fbJ z9h3O>g&L2Ny>lUn?@c(R(ADrW2&ZJ9qv4kjPAT-0xV82!H7a@Qk&S)adv~i*$$ntB z1nxh%Ta8NYvq{|jh%idlCrRA@j`)Ww#KF8y>)C7-|@H_mr}6XaY?-2S>*q$8f$S%v5))o+2o(nb7v><G)?7Klkn$kCM}NcM`vna7y9CBvsIe#o>yeFpoa!evDg|GBlEh12)Hsyf^S?;q z#qVnzO70QgC-C6KEoxPA-q@lx=H7Ci-nCXG@8w++xOdmET9vE^D8)X0`>@^f^REJa zHQ6{{;TKc7hElxbCd%JP>1GYTf%4Y_kNZ*hL`t_%iu<`0c$sXRukh63;Z zM);W;e|ySrM`;HQ-x2suWaDx7p#1KXhEa-_>_+)rfyem@--S{Wr8s|2;C~_;=PP_? zN_$a?myDqNa7z1WxJ&tcfyezQ{Lhp|Qi}W8ANXI$#`y~0htdI*;w1&jD}B=NZ3%DI z_^VQW6-om&d^O;!la0q+m-2Z^>rslAtV8*=fyem@UyIWEl;ZpifDa-Y=PP_oN*hv& zmuyD)O)33R!~a0}O@PP!D12i|n^TJWaexmd8|N#$fzlR~;w5WPUg?vDuT1!s8o!qE zHI(Mk@VSA{LpC0FA<8dEX<V@=BjH+#-B=jsNd&ejNKc zr8g+W{rm@bNH!k#eagQ_sgqK?icf<9vm`Md>3-@siId z|0$)IKzUdk(d((td_S^rzQX@RX(Xk1$qtlP`lR7o6TZL3Uy1T7Qd(KVR{_2%*?8QwDZdt_ zbtuJ4)};Izz~g*{uTCjXDb8OP_ZkMk8i52Xbu#rX>XUzlv1ukg7k^`jIoS(5TgP+CgE7pMGUz~g=tz9^-o zDaHNN1Mg2Z&R2Mj(lV6dC38_;>5zthPx!JLKXg8{JWAFUlwu!eOUhGnha~ZUc#5y^ z`27KIE5`kyN&X3+(6uS0v6N!&ErlOP=@d%wl4B`<4DdK#;VqO-r4;8MMtPMErxfQO zO8G-F@KJ;xMJZmx{quIUM+1-h@fxSp21BRRTH8#ijrZ5Ra7wK^VM=XCHjW1yK3r=J zdbrlv=-~t&9!2<(57)X!YxrG+-%0pClejnkBefQ#P}$hWUVw3L!AEN2?e_*fN^u{p z4U~<4He}r0=+Oi}eEq3fmy-3yQ;Bx^tJA$DO4b^c1a7Tasr3l+$j03}gektl<2tx& zRcb@Re6n%eUz_+Ut&{WdhqkvJsC}0#Y3K#{90!9I& zfKk9GU=%P47zK<1MggOMQNSo*6fg=H1&jhl0i%FXz$jo8FbWt2i~_$l1xjm9+xx@w zms*Lx`;ohX^TpSacty+W{jJ`SYs{lEeqW{+7#~)7h3*NBh=cTfTtt5c-AMyl}or z`ghMx=A|8C{Y$vqrq?*cb(eD8Rxp2pPm}y2`fqQI_M)O!VqOvbC?KBrEn(hBUbp3w zxPJBgWIW-8E$Mi55VynM5W1b16phn&wbBv z{m0o>F^=M=cv-Stf{P8^WO+%Ohr+XuXI^1hj$i3W)+@h?Jm#0wtE|QR>Iqz)m;K=(xzw|cOO|)z_($*rm;000mJdtk2ODtwqNaZ^knwK62XKAwm2^MCt5&$Yh;>~0 zFXw&qvp6BWz9-{``CaNt=LHus?&|H!@GI@g_tW|#1)6m*Uo?2Sv(Dwo_6O*{ILd4L zkl?y47TJ&2!0q?Z@BB?k|5C4rbyeZbqa7i$YDL_zUH`9?CFq2-fAL$E zdA9=di~ZR;9mzPt*KKY+=I38yzK`(|UUf3#!7|DA_|RW?Wo;kIp*>QbWvf{4;aMD~ z1YHYgmwPee9{g9e_7%0bc{%UEx(_uSLYzP3vA^W{I4_WP+yCQsNZ!Zs%fa#5$MILn zbz8!?7O=1Qnr1@Kw_NU{|APNiTgG}Uq5oCv;~{X} zudD6HPCK{9zLTxa&uPa$DbH#9g*T1!N$PjojQz9p5x1wPjYAH{X{m2x{!}mz1rNq^ z{qPF5m6zGNn4f`+!_quXHje9gZ9a;>g0`Ll?620P>{obM)?19@_*f4P+Ed6l4%s;W zuyFpK<<~u$;}uXI$bHGRC3$Ap0w#-1d_GrGAL>P|1reB7Rw$*JaGBP}{$xUjCExI3CuIpRrFB z7D@KY9+1pCzfa~RUIoXe{E_K#OY|DF9FfZt+2*TBUWoID5{^Gb%wI=aKi-nb_<5YS zNjs+1+Sqr5?_+*RKJO;mXJOt-x!5YM(tKj^>%UD<9r-bv%0?xmxeVp&+aD1z1`?C0}XxAr#=ldt; zyWkeqad-X{%rBWABa%9G^R$1sn%*{aw6)`-`|{NNh3h8US<;S!T39Q{IG?THc%R3< zC-s6-di((UoR9spbOG}mnNQ-N4;$k6TEKNp3G2so)8lr#dx6W#INx-%^A+J$FrTXQ z+DEkyTH3x^!Tc#_)Gr;w^{U$bTE+RF#3`X4-FbbUpuoL{{S~zP12)Fl{}k;6Kc`*q ziT^BX%f5p4IIteZwSs*-hxJ>e*JmnS3Ru5Im-8iU9y&Na1vvke_>OkG4-e=1dHAm) zeq|c>xj;KUNt_Dyxd7Kwwssy+k^5;%+%O0s_y98cZHxZKl@`yu9I5%V>`_)2qqjFX4<2wu35{Z%ku!!FKO5hqv~ z?Z`M^5Cy`jpR2mW!K$cAiy{;|K@= zj>Cl?xqcD*t<=|TY3bxR=;cM|YH9md8P_Ly948C1Uuq5t-*Y?c=hFKl^a}JWVO%TP zdKI3BVSkc1 zF4k>XyN)Sn^U}jStBhtpRUEg)&$Qa=Ke)bsYu2;qJGsO9IQ9Iv}IJyl`FVL>TT^u(H zxK7OJ#}VAO$>I1Ver?R_@~O}f-+P2uFBbN%oOYeyjc2~^v9gt;V;DXcd&eN|8@~y>Xowg8ExH%&`Ij$>)EfX zeP1BuA=Y!Coo5uFV;<{7_^uC~1<-8ns${v1{UML@fFkxGty)hO>nx9Pkb<&yo)Ki6 z$CX@;U&20+L;oC%i;eYAI6m3V0?tb$p3}IYI(CP_K zw?#QG!tp78G3(%Byee)|7Z2w-;-`T5BYF1(<~ykGVjnHycxk=L<(@Vlr2e$pV8!Hq zBlSYWakPC~%EcD3e-&_iu71w#%E|eN5Mcw%H&;9F@UX8{pXK`g7`9T~?xP*T%d#b{ zpTX_yzl7sR3Fo~z>Q}+M7G6m^f68Os=CB{RxPBMDSYKQJxzCbusu{;8sqbj(GlzaxwBuw| zI}S;G3+EYSv@ehQZ{6kEKZ=OwFOxpcHM&*A@u?RMU2N>jdU;OTf#aStjrYeroNwv= zvhszDaj|jy_qF465&LGKt*0#iI-Wm-$G4afw~Xs=y`DXd`=(y6JelK#+IkOgzEH(+ z(D{UU141LwX$~JpoO)H z@MojG8^DhcvEO?*KM`2BHqK)N5AI|?<>Qk60?ezbc3v*^rq_D<{c3IB>C2xZ_j_=@ z<$ufVEkWP>63Ow%Lx%#^oA*8Q^K!m~fHsaldC>vaaaC>p6>+{J?JP}Zf9~^1-O8H& zIn0X?wvusO=WF#Oj)&ulMf6I*WK{#8-0 zqFrB<<-83QN*V1Ef1Y-pDtHdZG0BT9pg&c)zQH`o!;g=4*`t%=kh?FL52fAO@ulo0 zc@kHwb32!paQ{VcSLPp%Uj^-YQh1?uo>)1H{Z;hy7mQC4>$`;c;N3Iz_Eoj>Z;9)E zmtL<3{k#jg+{U_)dSVMWzPl5d=OSOlI;~--TaR@PKfnp)VH`!kIh-6;syZ9d12fz3!^Qzi-xYsjYlzwXCE&d7^ zSL>K$yb$xTa(EJ#dI9z~AMFetWnQjda=$BR$8D*vTMxRGaUNNEp8b`+W*Y=(2XLuh z#5$9_h2vH}V;|3d$$rW!B-`0tKjR-Z?z`u(|2jpqCxb6=cqH?3+Ih8<>$ZS>st6q` zUvT{@bOTY7=(OSyydurl^HOFJG^^!)}E%i4Li_!Dd6`_%x)S;57I zSdWqy>q2KwYey*eV-8NXzkvPE_LF$t<9r_XWBgZ<$9xT5N%AGW*ox*)@Br)G&sf(5 z?f7A1zB~Wpcs}M+ad94(YQ}wr9QIL(TgCn+c}qLb$#t;*k{nlHbGM`4av$ed&U@p~ z9@uWb+COqQo@%gF(C!OMx%V0Sm3)>hXy^YyhMu8zzaz_^;6-ge72LUd>g}p(`(_o# zA*t`-{KdufY8m@i0p|nGVmzKXIX+;2E@50;tp5`B7YF-m8S_Ho6wjM_JB8PmEo7|E zvOYf#<#^SM>!B*X|E^|S7kDn$FJ#;=&taaIu%GGe&T02)ia3tsuwJ|QH*%b^oL_-g zKz!kq9${XwkM%A5Ube#ZyKz^`cNgFvm~Xaze9_LwTxmCS4z%&{ui~ChGQNj( zXUq95_O~L=*DLsbSeof!A1U3-eoETDD!fqkq1TvK!11MweI|$V!4l3(q@K5M^7vB4 z`IeMB*mrUmkNh&sw>3Y)&*3=aYvWhC2s+659O71R{L4eX@Dk?vF53Y8DZ!ts>Fc1M zmbU(b%TfPn#FYlZI@+zF}L0p28Db z($3#(oM%Y6Bj+_4z zTbN(b`YZLbY~Uv2ROI{_6&$%gpW(oR4yAk8Pgz?Bc^t3ZgOhQ3x%-;SL;Mb{ApODq zQT~j}1FVxg)~AR2Gro3y<6wW%<9JvXMcL1^_Uil){VU&{-hL1BH!t%6`+nsg%&%g9 zEa7-vzi^7nD-rc)-B5?c$467^$nJc{C%6j3xszH^S%ME{^(@; znifR++Lwy_eGT5k!;`#r`1^S2`iR$+!K;ARuZ?+MW$-${JM?|#eVM@v!8>c!{!!d7 zGI*WBJAiqgXYf=vbL8o)>zMah2CpjqR$V5F`zd(3elGOe{%YoZlELeOzfqqvubRQL zR^;}bG54}j+?T;?JN9=`ySdd=^vHrye$*YyMZA~5tGhKhU+UoR6)IQ67r}EiUJkrB zzu`U!-(a;U z?vCK;aqE`maoZXGb^uS0+k$np2YB0O_zOh8_g0VMZkNI91n;_Q*Nk}Uf!C`a9nf!y zwIbfS8UCv9w*i$aVjeubA6?*W4Bpb<^@`iT`Ykk`<1PiBuAfEIN$pqt;crRs^tg54 zEf3yzKk)IWSKLhycZ0Q~{(cLd9=9I;exPzi{02Nd?m&$1T!{N-R@_Yy_iBzCX2i7- z_ie=ePgY#;I>CDcyk7nN3gf%MI#GWg22byA9{$?lZwh#Ne;dGi3cMS^>lOD*^mhu! zy#YKuZp)TDzBj|)_2B7oJ*;^g1aFy<9QO$DdbRI7nSbj>?K>Piy?q7vI|^~ffTy>w3B2RL+Y`KAaW6pJ z7dUPcczWDc=)4#F4FgY)+X($!@csy1uefc9J953Kzng)l$1S2C4*YEjo*uV^_H6~; zis1E%dlBNk!*K_Ir^jtU+?C;P1@QE^F8aGVcs6*ILz45rgTM8bSU>9TeBkwJ-z8|@ z6z0tfp5DG9;?9q_^MI$fuMKhgf%nn(8T;R5h&z6RsD1whPmk-v-^Wz0h#!Kd$DIh? zXW%^xUa$W89Cyvr2Ssr!;OTKa^!IuAdj>o`ZW(bqz`F~)UU9EOfA82ZihCz`dfZmT zodkb(fTzcugt-3#?_%(J#l0T=9kNjr_agB0xE1)j6#gy*PmkLH-j(2a;Pr}oBjS$d zxMRW7Pgp;yyWr<1PlC9=D9~SQ7pg1y7G_ zBknTbb$yqyzdX%4-}Lh4QGdSzPmkLGf8S8KB7O;;9@hcyNASJ?uQHCW2jxCPBY5Y% z%5h%@ua_Ft{YUEV<4SHaWU7l8LRc&~t`pC7nr-#zbh+yJ~@?RyUE zXbqZ(^tm5Ay?xE__aNfl2cF)(B6yF2_b=gfB#&Ed6ic0FfAChL3Txe)!RtVOKNz!3 z#G9POL);H)w~cuBWbi`aJxCXP^tn5O*VvESx7x`&M7&Ah4Xm@HcFQ~n(Y|et+AZS! z6TH#_NnRCkZ#JGvfMGru5t9H1>BJc+P^!xYjDn zyYY19mBDMggy(ZD`A{Dh_wkh~CJ;UdO!a!OO3eoPV7dH|0mgy%xOsD_9p9kGfZRJd_{B zy9PXc9yrpzyEyLE;B{&3YXtA+e=_e1@br1mfVj$!itA^@ElAu)*x%*gOEqEQ>+(I0dp>x%T(W%@-40dj=*IV%Hy*tF$I1EJjD9FTD(<=9HP)~{ zSx448>`(boymP?Q+t(uceaUf4;00RyJkjqf=A8vzmln4=f#WJaD(;yXaa$$syt^x! zbq09$SIPd?i7xXo@9z@#>*W2;68tGY%HQ8I;`$PIDfTxGyh+Qje)Fr!^r>F8Y&0G> zEzLYH!(R^V+h!H!jRh~TlI@!)`mM^m6T#ERw+x>0quOyic>4Id7+>W_@s0yeAK!Xu z--aCbSn%o><^Ia?!v^oBjhJ@~c>4O7g!U;vD(+F@Pus6bJMsEZeiZLW@bvZtG9E)Y z?h)X%Ywc?X@0P8ZHyS*Bzbax~DnBZ2F(Yn8;_kuz4g;^WWKx%b(B+0<%sT`;eZQ(; zJd__5cT`5)P~!fD{T&Qm+fvE6t&YX>?*Qf<1fD)$I^j?GQE{8W)8|Ww_9;J#cK~?$ zcvPi*M{(T0h`*(i?dt-sd^Gb$3Qs$p=i9g+%8!b>Uq)PORpxDT8v7doUY8cP4!nPy z&b;B^>AK`GZpx2}yDxaUF3!6gSNT!AKZB?1l9Tpb%W?MsuXXO^InFTye+`fk6T6X zlphs$bMW-@x@Mg3DnE+%NAPrATHtS+_c-om;B_p{{grX^z`N~z=4}F=e%$g9SNTzK zH_nLLDsh(@rf60Jc&$q$c1GNZ5_b>ww-$KrB1v7Eu-H?=w&NQE^wuh+CHNc!d4g z5?8zaodn+Pk1}sL@bvlDj`^qjsJOq&h#N@Up-qZrEd!pepAY?R+?sj)GyJuSzoVG9 zG?pZ`AVa{bZFTLL`qmgIGO7y5Bi|2?DjEe>Ai8g?|_WZ!66l>Pnp&-+BY#lUMC zl$f4O_oiE{j-4!Dv-k0F%{`{@E zeP2_#B7Om$e!s4Se*6I5>)`dePuRh6KMD_s;=Tr+9(UkCj{64uy$YTlH-OG>gZBV< zz2d$q{cVoo2H@#&8xZ#)_`4rGJ+1>@J9zhjr_X~5^n2o!L!-F=0#Ba@6QQ5-qlour z@La@w`Ze}989Y617kD>*SB&D`li|;zpMj`-Qu$HDyTO~ZVRD|~B1Hjq5Xy zZc9d=+@#ebf7hHaI?5lG!K+*g-kHqXHiK6<1-wg{w{iy0nF!v^%(F6h!Kuu9_+QL> z?HgVndOyn7!{1ZPyDNid-w58nnRiYGFMm3C|Hr&hS-i`@`<{7QXYec!yoJX^IuFR; zm2LuWIp%%;b$WlTTfke3dEbCnx+b~*6{~zazxMdUqqtvX@G7T+cM0=8&*1su?_TEp z7rcC%9nB-TpVM+H-_NPr^vEb~XNJE?@b?LoE8>4L{54z+f7`Ra*E9T8;O|}ddp^To z(>3t7H~Xt(`0IqfSK#l_41a<2cNF`ZlHt#4Wu2dbzsVW?>dI)}@$7F>mcLKf-vjV> zYlgpq_&bCB-IU?49{%oxzpFC*c`_cCus=V;UmpIhhrbCK{@SE{H?hC*8U7mK?^5{t zdzQcJpx?dhuQkJ8aV^&G9QYfX;jj1)_9b;|sEo&6Ov{I$T} zG4OXt2CoF(wZA_qT5kts@ai%DuHA`w!@<+n?Gp0_pGN%-bG3y&u+X7`NA%w@rq>4*1)J%2i+|!(XHL`-uH* zmf^1oe?#GKQ}Fcjmx(w|U$^G*QGeG3&$^HIQ~DWF^a=jM$L(#8JSobroe{VBQ=ZQo zBkqbB{`~vd|F);HKRd%;3FEN_{4JT`Z(;y{=d-`XGW>aH-*WIbUxvS?2jK4-_BVHi zzc%<=1pdCp^98zo)pw!ao$T*R@bu$l8UAYE@4p%T+y~LVhuL3ehQD_B`;5xf!2LVJ zU-Luo_aggyHN#*1x;(z`!rwC){@SO&-@EMZ$qava_;V(pg zAA`T!GyHjvpndb49L?u)hQBWOn+$)~WcbTJ3V%zozbiBR!=uL-^GUf*p17+Oo#$;k==5mZP6kiE?hdeTta;3t5zhm!>297!b493S z*?(nS*4*Uc2sshF;urkfPAzz)x%qjbo92BoLQVkBUOD-EPum*YzV?2d5$|~L{NE>e zA^New`X5BRvP19+=G^S_996nOeR z)V$PEk-t?|{50Ynp273L`^);wD`xQ8gm*jh4$0t^!MpY$<{gy5EB%MZ?b_#=cOZCe zt0i^rKz~1co@1P?;Oj#9WwlR@VCn2NuKVn9XhY{1oO7d@YexdPP<^Ps2@YXYq^zmnHRzYC-M32 zc@vU6J#Hv*FPb{fMt`r~WZpzv-Cq$p54mCLyu1zl?wN0@{&G7o@9GbjH#kF=Ds=hF zrgf1&;py$mqaPzTW8NP#{MGfxe4d=->HZqvZ^*sO+XVhPi##54V?4sT+Gw8M@B#BS zmbeu=!lOnLw*k5+KdS16!qe{O*l6D>OU)lu6`tNc2mV%CntAJI_-lZ_c@ItUbbkXe z9&;bYynKeg(zU#f9(kI1Yh~~Xi2F$Y1)_eep22Gd@4Xi0t(w7Wll6N8^Hu_{@dO?Z zIp6T$uX*x+GX_AKb&eV!H&cgj=DTQI|4yXg02lBfGC zqkU7pXI@=~zcS`u>nil(5c&vD_vd21Oj(P0^JVDLgnm4BT9VhxA9zEyqX+KkBmQ(= zfPTDl3G?PgT>bnYgf2s$VBTCA?Q^mJUH>Kh!AtrGPmfzffA#18^?A^a_Q~`A@}24=OG9EE~@%PMqCeZZ@8X$pM$5b%NCn;QGQh1 z&%kRtKH0vB7`MmwpcgsEczXM)=*KC?GVjw2e`WD^T9T*x^K5S4kQ>aT*h?>w=>RC%rF$CP^pOqExKzbUJ)G*w=k=yEZ= zz=u8`Ll=EMJInAse(g8R`)>xX3A}lip%+!rM|iq^^+R|(=3bV0of-a$@HcdmBv1Ee z!{3lUFz?+Ae?I&@avbyC%HV}^p8fYEPmengaaTHndH>1qHwkh7a&eNU`zv8xj=Y3< zuV?tHh%S@q#bERip6)L%y4=gWS2Fx{O8XX~7uwNBc)GtfY2U(A=lS5ha~bnq%7|+% z%kyg9z1EE4J`bLLobHn2;IOqK-gDsT`+Xz&``GEsdnUtQJ>s@bVBV7%?aRH1^Uh`0 zj^aL+!OKfO_D=G2{R%r`-tWV_M>701ioY|M_b_<+^STA}cgz9nMD3dbo_>F=32{Gs ziFpr!H*vlJiR*j~y z>Cg(^B76Taf+m5d-=AzbwA?P?U{FHM*BK;V_iNx zn0a@A7xvS}7wy~Nb>`hJ{_aX1r`s_PzBqVD)V|xm>sT@AFTi+w`R!H_?;jcdLh!y= zqY&}hz-v90W#CrK8?*xR&I3=^IS<|vYcua$@X8k@?-MqlA4hD# zymP<{R@8X#r~Ih?mcZ+3OY$7}>%SxWI~zQ`zm4$s;Zw{zD}z_JJNI|>ADDM$1}_KR zhd1vV>32p3&sqUG-+Xz*`+Ej2?|}C`^Zo{2!>IUczWD=#N7n`HUzI% zT#Vc1;0*$=^|j=mXdK}-ZJ3n{cu-c{g$J0 zHE#XE)B7aJ$QOQeDt^9|8d+Ozs&fZGyV4`<6%h{>{9%GTPS&UEZZ~rQe(2>FsNV&L4u;4qmTu8-TcL zy&tvjQSfwK3W)nS{5=Am9=D9~cm}+i!Rrlm)=>h zufg`GHd_8pM4Z%HMZNz)zC7Zj-XzYWs}MHn$s18y(G zNk44#W1rdWU99Nn0$%TGI<5W^|J3ujNkQuTOM)JzV7WM zy04ptqh14X(!LPJWo5)Ihq%&Z+`a)-?$%Je!Psh zUgP#(wC{Aly@WVvUlRFVMZGT~PTH43+#86q5hwFLjkw8c&TQFtH{yEPw_c!?&(lW( zZZhJeeOWx7-h+B4Ax_$tLA?(m?k>d1ymxROO}-oSUWT|{_FawfdlGP$B2L<8k8Hkg5yEcP-Ss8K5Ax_ToCi*dX zr{7xs4nbTm`<8<1tLftaHy7fheI?A70O}o#xL)?{0`|?1xNl}^j?eF4p56_5ry)-2 z4WPf@&Tj9{)2|UH^#)My4~T0ZP99&%=*Q&Ivs!VPia0sXEgX;c_Xpf-i0c)<4{&_5 zfO{2j(vK4IRcE(%`|%3mq#tF(y^Xm05Z6oZC#bgqdhbP?)LTJ+A3(l)5GVBpF@BFA zu7o&wT(gny?$Lj=;x`F#^8H6)2Y7yP>+fByM{|Ue&v%2HLB8Dl2jK3|@RgA7`7v{} z_-;mA_#Sx9HKaSJv;P&(hIKcu#{hQ~;(}$s(K_zPG`OBIx8pczUmW8yd@Y@PSM!cbq>bQ0^Bhg z`$9Ls{fK!d$4UEA6u(J;J6dC3itPIZa4C&_VY06YxP3MDS>Iy(W^tUfFGKeI0l2Xm z`?6%;o^!VHZzql3@(j>xCjhs-hOdtKeD0lq+f2ika)2*)7vMJ4@P!Y@{F@56bu@hD zO)zeD18{32PF|PTm{*fF7}WB24aCX!?8W2YdHb{t0k=BhlE3rk{8c<|bn|r2)720s zuXAdMn{*}cnHs$n(t8!)Mr!od(2s7OZoR`1*Xwvi=Y8o%9mltur`wO;5hwkKk{{;*-}i`< zel&MNKXQO`5GSvP3gpK_fSZoEUVfYc<1x=8fcpk<(hmd2qnoGOj|SqTA0^7GslfLU z;-nwRJ7``4?nA`M>z4-R^W??nYK?CVang^j6`4ZX*&#PmAZy&_T zd@=u|@deyo8ov4w$afy#cGU1?XVGyDaNBA4!erkIfQxGQVkaY?4Y<*Wljr?<&v^@Q z8zWA}*}&uEv|j$4CB1)=IM^}hKQ5r{RZjXbM^wd+5gtl=uP7IPTLD`>uU4{ zV{l*5&C|`d7UJai#wdR00pAG3$?>g@$Mb#;a4R8Bp7%qjchW`Z3Rv zfSV6-(vJw{K{rpgA9Ev4`jH_&#sJ@+KfrZ_^dmY4`Vj-%ABdCZ{Vx2zZ1M!a{fap0 zN7t!%zB~zVO~gq*0?60R)9uGkh?9QUbl$%W_@*IF`r(it7T~@{oILNFmBd2 zlYT_$`sIDVeStXXM;Q6KdAj}h6milIi^gNYDIC(9zR(HeFW^qq@EOGS5a7}pzEm3d%78mc!xtgGp$oM9O=|e6#1{bE z{)m(3!5HS%t0MuoAL8VBD}={`SFZ%z-WvPrbUb($a64-3%ToMmfZG9a@;qaZ-l4-< z{%)($8>hI80o*8!UYqhX2DnWSC(jEe>V0hj;5O9g%}_o+1h~~SdK=_#8E~s2P9Dd@ zq<1RdOpV?w`8zV$ipx?Oz3~Z{S0><=M4UYC#xW0G+Y@k$YxL&H-zxz(k4CRG9`zOg zH#g#X9VgM>DK7wSh(@o4dbggnP|IJ!$>&^AJpXR_JKzRs_zD!i4Hj-qTS z@O=Ep-AA=>ZzE1V9}mr5xZC~SzBaqP`}qGB;^g!3)L_7Ugt(^=mtPtDTe!RP?0=aT zS8VaU_@7N%dM9ge;q4K3GvKb);F3Ea?tZ}KG`ReZhfa>)Hb1 zNBL5~vb7)J4nv&GgVe5YKAJxF4lTYE;^ca71J|=2``eB!+@Xl;wcdL!7~g3d?$p8^ ztkE0X4fL+|dZLBf196dU!4HZ{9pe)D9&lSCE;$x(3t{|>@hi3B)XmdfwHe~%^-C1> z?tr+B5tkG1Kk_&)cSPLkhzsq^?Mst=bL`dfV=2T*`|1~fece3W_Jt59?MtA2!x6U- z;-r1q3*r63N{H)1TxLtSzoNLLF9f|CEeQ5abMSd0#&7nr1NfJO<7qcfcg0l1N&6f; zPX02xy&Lx_;-q~Qj9(LRb;5~tEk(@dRqg@%K0%zEM;7A#J><|9}tq!>6wj39I3gX;SI{UvY@=ba9 z=oa4x$X612^N1UT-#HL2@G3m#>ES~^P98h1#rM93uZnS*ygdO#!SOBJ8;ElXeB5ft_ehcBl9&f%UmbDdqQ|xPUPr$Cm7K4ExCirqt0FEUacJK| z@#9;3QxI1bemIDGunM@>5Z4fV4(csuPiXPIin!QS+`cB_9;*ZH6~skFT)Kuro<3Zi z(BgX;aZSmG_B|fXv~VvWP9Dbt$T#hJz`cMtc|7P!z;XPm5hu3zp4H$&h&vLMcmdl;P%tt z!mGn~PtR|CYRiwkHMk_=zS;|Lam2~|Gv0%IX^aKj4jR4$`FkGVw$h=&S?32 zgW#j%ZuCdYzrldJPQw?N1^#}u0pKPIKFXIOj&CCZxQjJ>DH@OQfICCO7og{?#{up% z4PO}Jck2s)%OFnfx8&e;`+YXY$>$6fULS1vGT@Ha=#A01{Rp^m8okE3a6j|rOpcR! z%c%F@UjTQcMz4Y6@%;ERTjP5O;wrd)ZT4kV>t7u8esUb(4$|-?$&W#2wfOec@MVc_ zFyO{&__8>@L&gAZPsGXl^8(`TirmoByPJkDgZ7QM7I3>FPF~klF@AS60TO%Nx~zv*Y;ddPg0``ug zPcj8?8*22%F<(Zkc2mpWbu|9g(cg7e2b_sGvjpcyI&K7;aNKxzO^%cH8MIHwI)GbA zV_ya1a_iB6TS0@X{|k@1CBQ9?I2pgtuXtR$2XKpM_)3_6Bj&rg6_>d+d^Yl#LBI{s z@TCs{`$pUaxLM!v^D4#9oCWrolK|I5oIJ0laNN!vc1z2?pES4{#&7F1;C|5HGKYeF zw@v}v3=Phq@i1;}>HPw6GR~1dzz=JAj+1%N6@Wawc}2i|s?nRJJUs<)?`ZTkP_KC^ z$4R{b)I0oiz`d!_8#o%zZ!-XAYxKtOcX}EQ;GWa)*_2oN+}4WUBN{$?N0?XUzJPm3 z!)KsCbR{-2e8ouyQ@FVvb$4R~j z@qGcfaT>l{1CQeu-r2H`aFVZS;Bow7z#WNv@^}!(aXUABSBviejoy3!{aB0Rq}~|$ zu@2z&(D2!-!n&ovXB;Q_;>b7n3&3rs;fu`!_QlSe)bfLHk}rXLTb>QLsD{tN--$9; zo800foaBq(`DpkWfLl+)*EJv5XHMrh$(Ka?hJWXdOCj#r?AI;#iGW*F*f$I=JG<%=;eC(!;XN%r z!b!duj>i`t11=!==)NL~??cUT_qOC*a~+S*xBkg-(!SY` z>)`ro(0whvKWX?%7{4Jwj+1-^eC~brB7plr!&jj5;PxEXix0=+<~ZPHX!vZ(t5-Nq z@)gm(o2!7EuHh?@ebYHk@|DRx2XJ3&`08ZeCil1EOgPDB6JHc?UupQ7#5e4L7T9~Lz8vvA2Dq&>eCFlI_c-7-*YKGbzeAQUxBMNg!PP0B z4*=XI8eEk4CIW6l4X%lNU)2G(z6O_~yjuF$F(h!kGA}nOQSc9{%-vV;O5leg1^JOJY>1YT6}*^hwBn~y-~(- zJ9iw%N&5PXNZ&QX-eqFLd#cLe4iptKCdey?)*I9-a%Yf0OmD~Z|MTK|2X!!XIgxO3#k1UeDuM4%IaP6Rp;=tQ6sfldTE5$Hsq6M;?yIuYnZpc8>k1UeDuM4%IaP6Rp; z=tQ6sfldTE5$Hsq6M;?yIuYnZpc8>k1UeDuM4%IaP6Rp;=tQ6sfldTE5$Hsq6M;?y zIuYnZpc8>k1UeDuM4%IaP6Rp;=tQ6sfldTE5$Hsq6M;?yIuYnZpc8>k1UeDuM4%Ia zP6Rp;=tQ6sfldTE5$Hsq6M;?yIuYnZpc8>k1UeDuM4%IaP6Rp;=tQ6sfldVee~du# z0r>q6@~w6W{O&E4Nv76--*-tq2ftHNIRkK^GeKsSV}_7ks8+7G$=qw5!3uy6fzd{mzvX|#UdiOR;F z>Nrrlm#l6AzYpz&%gzgWvZDZ>UzOY8)qkMc3y<-*MivHpqEWRUsi!zzXGh{Q_c&Vb z@b=PTJg=(_UZatxA_}4>qB)si8nPC{Ez+!emNWX z+5Vc+}w`b6wqsa3icPysh*_$7;i7^4fZzf;Pr$jS>1kM#yS5f z=qbDcvg9+5>!0)dtj@*DfgHr8a6a(nzu@iUM_`zH{0P^sG}7+zBR-?d^M>jNT87pJ zKciQw^NRF2r@*+z?@*6#a|-l#_E5)@ct|E*2YhBGk4NMyu*Z2HctTroyW;;=>nC24 z^`jtu$wU91aV$Op_En~Fe+!Scr>}ZLdwBAXq`5D~aefiU{dwHd`+=VDe!QM|qCctQ zTD;ZWzU1TJe{&8suKX3Zi}aDq{J`)3tgFDj=9k>g#^Jn7{dF>Y8R)gYRof-|#dq?D zqkh#feB7y?WM~k#x6$Q3pDSmBy_t_eCgoCmt9Sr$LSs2^Dulmj91}7j-%f(O^WkDcxR6Dva_%4 z@t4*9{ZnM zH+E6$HMRkN%p?8TPkQ{y!kucpe)|(Hf!FofwfJ#@+DXR#1b;&J^W%Z}Z})z-xK2#{ z(4O6?7r8#Nhh+K`(4X1_?4x>;UFX{LCq5$ZQzH#K%Fl%W~-rf4s7vESLW49+$x9?)f13WZ4n-W5u!D&-Bs|XX6ZBFL|OnsK-O% z!uvy98tZ^xwP!hR{&^@H?}2piI@x+2`XyiHc*!5%m&c>NB+oyIr*h>dK3?^hd)%p? zUl~mTUna%%`0YPjGFH=7$GrPEttHe{ejQrt?xc{jSVO-;9`HOP}@xXdDBbsJc-}P+nY;*{ecGOE#C~d#7!KZ#{0qAa@?-qEgVO7IV*Ess_&~z zb#XoM&-nAH(vRFJi_2$k|=TB*As87wWwyQQ(-7kLy$HxsQ=Nf=_c89Vv zP2E2{iuX@`!Q-3$3d+%OF#dLtAK#19IX<|6dOV6l+^^RuetBDMC$;OO`4rb1*`C|k zNI@Ps#{hp+tY@jN%=0^X7~rj=czksFgS)Hkj()^>Ym<4I_!>+4i%+b<{i6N_kN0ha z^DC2sK~Ho?wY@r?;!f@1B~SVybsQy5S9XH#aST2K{3(>g6Z#RxJM#MheEn+ocEU+nEWq(G`yLx8rsO?{wEw zljoHW-SJ+2HRe>uxq|CA1M~6oO;$WN@#6PtkDmtm6Q^@KGQaY;)ED*Vr?~*n!>H5V zc#yr;s^E8KCGJ19d&%^#+}<)iFDre??bGqpaQ(5az1{lqX6||`U-IiF;;$X%FMgSO zfj{DNopfx1IXY)wCG z&l!Av%Kl#E(m2pxJlUPc#&wWhe16+=&vAW)xxtRW+iHKE2FH`0;z&MUs6H?q@R@DZ z{Rk&z7VigRH^6vS@H>RY4{Dy&mVDk6H1~s~r~Dq|OBm-r)u*#+erhKfKLYG(EXMJP zw|LxQ_&lQdJH$1yH*Y6CFB#v8>(SvIydO&$Fdp`y>bx#*5B3vJW(B|p45%+0$@>LX zQIBus7{D2;LwhXCd5Pb4`1zRX2Ub%e4brtE0j!++GsNEjN^P+jAKfluWeWX)>{4|U1c}n_9O^l-r zddfSi^VgZ=&ko{EFV6j-`rvJ9p6XaNp8Dxz`8sZId>M6oyIL9aD4FqHE-=W_xWo)!gLf$HBf!Js)(uUiHSJ-2cok;73xtHw^p&dTZ}<{i(;*b_el#uX!=>Wmo2Y zc-b}3?TtO#)1SOm?N=hl{SU3j<5xYmy>TBXKbvE@T{_;%5 zcIt0FsOC+dr{lXEr z;P-j~To0DP@7?m#;CvB24E(imy|m6Q>s!DV>AQ{wKi`z*<#8jP;34YqrFN3Z72R?1 z&D8uAaU5xU(B6C{{Ujrss`XI2lvRB0+kB|K`D=gDo*t=JSI%$9^DX_fd%hA+tg4QG zdQE?JMh=9yH(zZp4n;$)m+b1VY+S?Rq2tT!5BAr_sQt}+1ND)Kz-No&cVmp&?*_(2 z>NWBDqKWfKwpZ_0+aYmOPHNVt1;ly;!s}!zrJg^*)716p!+3pSq&nWte2|A}+=oW$ z4}H&%C$c>+)_2QxDp&D25tY4U0qr7OL+lHXN~--Kd~6)|pXvjTsPm!Z@mzrVle8`b zp29tR9v5zGFF%N{ztVYw+tFV>>K~g4ytcT0r}k_V+M8c<{nd#3`JDPonO_mcHNCaJ z<4;Abb4?t>$2~P3%DG#C*QoRH$>BQu&;go!dQ5Fc2%oc%{ps(x|4ngUOgJgigMq({ z*WlV` zdzKR7L!a|;ApY>K?tTz1ir=kJnPhrX&KqA=?N4oO7|#@5ms|K=ig=`~tPk_VS)KDI z8p!jgT94!je2sbJvCoF=*Vl4Id?%SWUyRq0JRchs?niW9-rlwy!`thh_t=kv^d~lI zkC*!CWORnVyrce!iy%&+C)E9FZ}9VRJYd@ug;}d8plZ8vHdE2AM@k?cqhB zJ|n(ksGSFP*0G)NUNR`&a|goi@wQgxdE>>O9}52Feueqqg-_u7SHe~BxjB`+WGRC4 zPV=5j*S~=4S9R^tx!|}E8ld;Sf#V@h^1r#q#mK^Vq{V&^f%U+i;-1jIhWGEy$?o|@ z{u%rD!-epB)gpe+8efYaSBOu_!WKOL>nmWt<=yob@qJjGcfg!48R;&~C@)cyV?pm`ri z`jWU#uZqtvsQ#apwSszH_SKH^Njz@mPdskKTbUDZfi>D2C+e@0(FN7|ba<*SuG6=E z)Za@Mzv6y|MZU#%=lbJQIX+h7?W8ZVGT`jx)aSwM^6Gl(|98p4Tkd+T*SJ3pt}i2d zG8^+es)TsidXM*~e(lQoO>i8I+>FOlB#7R^%aXU?(N6fR=DDPKG>=c?0`RXsH`f~; z$8p5lu1tq{K6&*Ip5NYaA#SPh>HGM&>GTH0`lJkgCukp|?jLD$oqbfSuWD+(%PKDe z@eUlz$ARq5hY$i_mYiG-19hj0oda##m_gzrFmKEDd7EqtfzA1#`f|db0E*d z(DI-^j_WlFxPB()VHfH5E0YJq_~(CB=RxixZWr+ukLC4=J=AfIm;A-Syou*`Hm>F) z{gGQZp6Ye7ngM&OJ8@ns!R-sJz}rpDe)6OzyfNUNK~}^_$3}yk3Zq1OmBg_m-9R*uJ3MF@^`g8lHXb$cpQ8lXltIwP`~UE7}pQMk2v5znG&QztV$zd~|k3e&WxybU0aGs`GfIaX(2L zzi%ge9^W4)Ug7rS)`$M_@w}e;#qc|@u7&yW*ueXl`U~oQ)ZedcpnVb_9K!vh_WHZ( zcvHKVtcmNB{Ml+fUOckhz2SC@8miF~H^xL9Xg^!RQyxee$u&v&<% z_?>G3pAYi5Pvb z<3~Is?cwh2g!{iHYxsV;zjj6Dg?Q!e=5fp8_!ZXjH;%^fd|YDqK1JH+Tmrb-2^=qR z<_0{UsJ$eTP^W&1KxgRthaQ8>*k!5>Fu1B_O%lCudNso0S z#W~!^Gam4#-}Jb?D&C{klimyXvzqn9TK_~tNPLHE-J*_r@E2}JVh}G2+OG0M;0f%h zjze^Db$)gI+PC`^(x1fp=j?*$$6jiG2%pE_d!TZ2dv`qHNTwf#dEj)Z;}O~i_^P}3 zSS6g7fF@QuC#8T~=W@pZCP8lS$lvy0(!z z4|M$os=n#*{dc>1N-OaA#Bg7n2JT-V`O5F8^E@WLr>A~_Q+XZ*{>AkX&Pzsy`8#jw zc#^xQ?bhMjtq+Uu!rJXG@%apoTfE8hysUXX6O6ctmBqf5p_Mp3{W*+FWEakxKN{+DVn6T*?)MhEO+B6#{+>;G8+Ci& z0bXz6etPA7d3^-;BdgcBT{14RT)_R+WPN5Ch<9c@_+NaOkCTD>@ukH5X9?G(R5bgy zN9=@Z%XV2V4RIfb;26-G!FW|`{_K!?yvntM)OLh%A4#wNUhP5rJ)-8b z5FZ=go9X&lxSvP$FFqc@d3ibejym2pt~1J9&&OM*uPOFt$6@RVM<)%R_n*meU}p}$lhyInai5Wpn1@k(U!K{W$3w?M z^|d`XK2+o7-~;M$i)o&Zl*IeUQke5OMK~@6PvH5H)ckG~+1Xzi+DM%TetFCHtK;Ce zfBq642iecktP4-?tj^2GqF_(`^7j0y9m(yeX`Z)A`$D_%e(^W`#iJWm(9F zfXDaQgts)`D>Yu{b`m}>?%TTF@@GHwCt2H@pYL-!L%BMd>#b|nkEb{1*9F8Yr6JZ6 z%62Lj!+ai5y-tQS`J}@qzX$)4_&tcx$L}DEAE@(Kr&m{R-3#N^SV-hOez%gvbpTbL zzyFl42_BtdQQw@%$6GZ2PjQ-io|P7X_@?lEeRa?F#`Av^@xMaXs{IPz5BhRTf~-{l z7k?b=44>uGFRrdDsQEoW0qZGR6LB2HzW9+1-TklNet*G^Q!bYf9@#z$#QD%_Kru<7v0B8^7pqK#r3H{&F{wq=HlZR6Z`8} z8}j%Rrt)&v*1W&8H?+vW`kTV%Bc#W~eZTB;AYZEDcWDUMcp2J5VqJAn^IVnswJW3e zJLi7;W!4|q_=NGfVBvK4d8V_khR?mJy*LzjlDIxRjQ2O0-`vNY`X_(m^T`bG{E4pM zk0&*X>v?tUe(NiDf}MqN?)FMP^E9>n5=Z5R zcpgsmk!4{#(s;jWY0hhbpLyPvMVa_W+D(q9dXlBv!QWI&?ROEsyEE`TN)=^oa~PlO zvhMu#%iQOG{}AGw9jVU$l=!{*hS+bO zcrDF$kJL^wgU=!9>d(CF)xUZ#_>q~!?XHRMnJePHGtuQwPwsFSkHFoaC)f1XkL(WO z?@mzJOXj=4k8~Fthr;6bNOk?IwtHSSPvzri{ienn7*Cy^uKhTV7N==wuBy)O`YY~n zb(V$p0Isi-^fB5$<^Z){gs*%7_BS-&i4rb~_k+gCYQEBZ;74;awLiq8lh$+G-%5}l z*Uc$BpLINb>+J=&K3%_n_`W7x<;R`OHr!4fPZRgu$<5>LM*{B$B~Nlo9#{J(us>M= zzQzOUagjW_a?{}aT`!2Tt|Qi$KXv!ZqkFIB$hPh2Pp%LCm$%{bF}IQWJxB9Nj*|v7 zCPI697RdNP!k%NfzcwD9h$mw5{0fWj3RC!=iSUh$!OpCB50?2C_?7m!A0!@+n zTo+qwg8k*I`j*B??xAKAAO1c z-!8|*I;?@Rr@SLS&Pd+)J20-YzNh>L?_U!8P4?i#AIWRf`DmKje7m^W#(wlzC5l&N*v}sK2{3aOX9w_vAa6{(%!&b?)-$0 zZx7>^8VT_(Xx1lM8GqwTynU7RJGmb7dR`{p1U?6)azXPxpz$d`-Vt6Wqj*1<6Z_j{ zHP4N$72)_-enV|1>8a<`cBGH>H=e{pvNpn9AK?;P4eaqb{5JO^bR6d|;_vj4ev;Oe z(65pPyCXOcLN9VZYNH??&Br(|@%WX7$9K{?p8Wj&=8dj@yY;aH`S{mv^yhcv2;Q&y zgZuSDstNPk#NRO~i2ac(Yq{$+aDOS|GCp4EH+Vjf{~2759r{XbS8;y#^E~nBWb_Yi zZ*4U`ZixkX*}~(TSMUS zVEj@%FD=2xGimej@N0J&-{<$4B-r?#1VyZ2!B;LGeDiT|JpEATEKAxZi$x zieem_$NGyG@n>J=dSi3Ck5g?<^>K{&yktRqhZJo>epJLhU0I*kyOnqNxCaj8d7b-= z`zP&73cPHma!qqzk{+s#S78x;Ja437T!I6%o|NpW4(0w+y_BZMIuMDca#8cW5Va4K zOuYheOx?)yw}kt2kRC(+e#;y@&V(!D^YW_1BcS;>=(Cnkk00^Grn?{C>(4>|m{=EI z{|ov#$6(cEv+U;hUB8*RQHr2bMCt_FLv$3fhRA@08=zNeS{sT>pQ zg%hLH_7lFCd6{q|&0W>wO6^`Ufa~Z8*W6jHFZ#Co_)>qJOwR}7)0_!$Y?}P| zQ`G!!TzYRfE`@PFQUYv`&pgu&K5kLk$*$J)?QcR^ON|vJLmKKCi|rfiSLdACh#|}0sT3T_uj;3{i3#u z+6(gc!}kIH#I1OI+YRgu>3$DQ>{CU&B=eempwpJWyda+NWA1(sF01)H0BR>$xR3MM zI{&DHkRf~yXIFuuBUh} zFB2}fs{3_p=})zv)Zedc;&(dMfB1OG{*?tlpM~!~9I-AxhTpSAD*onQGV88S>X+r( zzahVyn&VpHJ~-ag${?+mxxVsF>i9)hf%?jM>UOdtyDmSTrE~6h>Q{MJJ>Dhp{Yhpw z;EychK96I2Kzr~B&~F}~<|q9m^J95DsNTkX!l>*e!+74Uy#?bQo=@=R)p1Fj?d})p zjaU8Qa(Ep|{d&pO)pqp4X)2t{{pB@v4}axv9BQxeJZjwK&tK9bW%iD~^>^ZY+{$h4 ztB?@;ky-dWx%!Mc4)K$@-_DL|9Ql_x*x&eBecUIbOV}UA@5oC#yW2(fmG|fIi}-vm zn%J20=N92{A%2|*{0cL7qjPYfrD_vsd>wuYz;A>nT6&?oSoJ zPpd7!^%=iIzxw%n-c*)y*C+j;a!#|Zxq;v35KhX-9blJrAlOle@VtT@=GXPh zeg^nDejnZ#p|(TU->W|Sx!N8liTUC4xijghAIS5`IggK9bUn2`>hD)pu2u7-mjiwI z-8}NuLs3|>ZXr5^$3KDB$5Ff=j4dwa^XA-+^zGd4*zugt!z^uc5Z4boBh`F`hq+!! z6gi&TDck#7jxI0af`q|@+TP&4YP?@Nj9>fL->;r_alx59&gsv%o#orqf8> z-rRQX@hPv){mJ5eujG~Gpjc-w+hsZO1s+$P;r2;f5cf%?`W#-5P&t}+_rE0Wi=C4= zK6?=4cQvH8BPZ71k>1GRJWf>KUs>P3z4;y%--RW&SNoC0=ScyN@0rQ|jM$f`u(^BQ zP(Qyi7gpOT`ljQMTp1}Eh_Y=UT&*M;d>Gtv{rdh`q8s$DdW%*sx z_v-Uo>`SmGzp{HC*2MelEbezeVMuHCqoQ__#=lX|qoCK&>}Ob^{TDR%gDH=FsDrD) zxF$9CQ)G{ng)WF|w8!Cln( zl%es$-y8Art6_8fUU+IxO;hJzP4hb@iCKK!*3RJemtN<7XKv?Z((CNN`%yi~$k*-p z)9{I}czlOL`bpZy^Ya+hldONIjvuv4+5C(1<>qM5&#q(K<3{>&@B70MUMCY*gMX#H zfiLwsAOGB@-2dp8P>$ky5FM|qH%{X`vi+YbM^@wGLwXBGsPmZGb+URR@TKtgX6z@q zpSe}l`a*4fAF0zX>mzUa%eT@u+^*zhF#g5wx&76NcpN+n+8ZcIZ$YyTh}w(iw3nxe zW4T?#Lo)Q8dwUY!&qwinx^uKY{nZONE;WLe%R~LemF$!!vkxQcw<yI!uwHu^ij~C+*xf0;YeB=sClUUe@lkH zRmV9~85nz`d-Hrt-tRA7x_C4fb+;?NvU>b=eAN};Jxinn#~%lO-#)tru5-clP_lm- z_bD%nbe;Q$Y-=n#Ysv(~2up??eOX5DO^evA+_1DSd zcYrSr=Kb;q@$*L(_oL7F{7zq|&k)~NI4AHp$$kcom#pu4k;l7NyQU&3_T@0%2K{9* zUYhP*<~#28Qa|%g^?iHbIrTVFKPj_fe`DGHca`Jw`18}R{z%e&9;X*Z z$1%L0F1LAJF>oKH0zQYV59RTcb|vO+Z+v8bzvUEu|C2hx-*_}G>DzoOegxxIUy#ou zI}d(VHSYy=egv;q=RpInGj;tMxUWL?1m54A3jUYcyw0g;>>&N+Z@3<+Cu!34ELHSV zX2o~L)s=X>b@b+N7>C;Y?VX3Jzx6F2$d1eyJ`W1=e()Y>FVD$w5&UkEc%&?9zN?Zr zT{#fq`gAy1A6*mjsQfaIOYC2~O#SkBUqWRsS$Iu7p6Oj7&zj=9IWNAytKFI(?5W^B zsLec|2j(W+kLcVG?_i4K$iDPe98dNCS7q@`VeiT?uX5sd+NAwCTt8kD>-kIP@O+GT z{BDZm^(q(fcYI>2^Y}*(hP*XS75*S$;XSCYAI975!#EG=Z@$lQRNqVD@5)epazpNa z8Ozy8YCY+V0bdRK)JKYhv^Doh`I#`!GYhHp3!0u{?GJzF*{(bN;gXU5`PZDgfBkzL z6Muv>-=9}L;o~T}^(uz0;Kxk^*L@Xn-+tMl`WoOXx42(FRjUx+n&$qo@ifGxayr*< zmEC!zJ(aQQ_@`b$bQiYhqdAsT}_p`ce7+sw`{=KM0pt%$?7;n~xjyYgbn13fdX4IqqUQcc zjUKpK2frT);`?}FE{X3%sJ_3_I**T|D1L9W{zhhR|(O+DgB|u-==l=Y~J;ZS#!OJ1>yW#fU zyj>Ts#KQdeRK|V!LaPkS@vnBankOW$(}aPI1dn3??aFH2zlrYp;=B--q~?1YYZtY> z));lYUXi*bfO?zac&JAAzqZ=uc`W^ndj2Ga!@MZp&gX|Qo#WGS_q>aEtShOUFfehZ z$c299_QfA@w~zX@Er)Qs8#B0G$rsoRuagdiJh$=pHY%Fme=mvoF8K=L`mDT{KR>hL zz9ak~^fN+WUv>$!Q!4!bq?}B{I0ZE8^vXHN_w)e&J}ZT<_zu5br~1E37IxtCm-JLV z<@NQ?{N)ezj~xvCLk^z@)K1ct`y&0R)|353T~9nDoihLz#P>^7pPuY)M(o|| z5B5tSL!bDwgY=TDW_djAKh^pO?^ot81iNbQasJeBsMqlXX7cvTRXjchUiUaF!11VY zG4R(<;yB_j;Pp~$MSh;9c9JRlomDFLk_U6Us68b1*|x4%+d+7H8(~M0<5Tz@YG5sa zBLX2)_`X(D_Y|F*gxx;(@#rD&_@gSmkBA?|^DtKv`Zatu?YEE57i_%WCwOEj_q;6h z^LJxRpYyo#GS6qSuU%Qk^B46?ug0%$sh(s3-#buQCyfJnJ`pasxqJL-x2XHoZ-;() z@qVSc4a6Zi2OigcQ1ctx`paXoQzt9;x#v;F1bb?q^8CxJ4Ejrh-R-b3{?@+ zLRs(b|N8~7wLHb=u{C$(gT)=BT#mA-K^*zReV1MCOo{wc*2TS@% z#&DnL_=|wA?+kh~;&~n6y=3hNb^K(%NSWtlXd1*Tw}QX^l5fDuTk&`kZ%A`L7+wyP>tudiz*lCt&j($9Szla)$Empu z94`~U^6R3?iBK>5o7;lFv8SOud=9s({4w`0i~E&I9$9YQ&Us`zl?$5piqxLMef26R zsoox<9;Y1c6Kwe0*FU_tKRZcpBLw*1oILK-PO`BLv{$C9?JOM!Jh34#PYc@u-uZ@) zTkuO>CVrBQ=hXbvo)h;oRPR@s)489c3cN$k*JL{_-Gz&#TQj;kZ-2gWDB;QmvoV^;Ozgt|wuEy>+pl zMC1c^Kl0cfe}K=^<^+HFQNs5nef5L-WuNEzseYhkW?>$;{_@v;bB{0a*CqijH_IQM z`VEw{Jl1J7Zh-MluIGN8oAcU_YZZ0A$A?4QQ=7T-OMk81fiLzIKVC?jEH^dy@UuMr z&CB|hcln9DUvojVU-|w0%_C`lVr|YZ+q;_T_A0(NFvagtQvbvNuWv~j>hUIhB;#kh zkDvXp+8^p)JsI>QHNSIfK7->rnvX+%2lafn=5p6ZdJD_K_(gvc*}t#l)FglY6Th(q#5MJn`#6>#0^Y(Vd>n|UzcP9>pTGU(OKHBJ?Zu1xgw=Kt zd4NEBRC{)X@cbS7vAur1?DAP*;(cZfe}A|BfqGs9kLLN9T}th5SUew%J^|w%d&AwI zz+iQI^J8w0xwJaZ@^^82YNOSB@k^k8d;!i&;R@WtdAd#kp8Qpuuegf95dq5N&w#IC zoC2Gu_2qZ+H{bGibNxbHPqDHAAE%xM{G*QR!DT&_>v( zxZht>|Ju9i@pTph|BHAZ7R2{awL#q9{FXePR>)u6NPk~t4dWDF(Oq9~Q8@l(@qJ?j z%R0SDvCh1{k^Av8Df1VJ8z-pas?(eDu&Y-;d|%Y7-e-k52J$M3<1D-7H-T|BH^=kH zC@en#GPWs51NYI1;B%qWZNO`dhW4%~N}-_X@Vrhv;U2Hjy6)pZ^r<`C^MP<)GI}Am zkMO4E_eX01cfAF9-9m(Yl+`VHTno7FBC`{(?<0Lrx7Zf$e)Ry`{3E|U@P@^Hkh#eo z`c{K+$-k-|9|!kcE=M6>3a@j%zbjjECB<~-J`5W)b z7{KL6xcgDU@3y60E6(-Gb}EN(|IlKa_k&%U`@z_$d^{67s`Jha^5avw=r1m0cOHMw z&%Bh!C-E>ZM^5JU*oXUz3+W-5(A-B;d-_Mvn_CF{ZDiE`)ZYMm(#Ju2=mu_&J&4DJ z_{|g4eAF&wW=Y^NG`~+I@l?+33HB86elKvV+Me>sd|a)WU|(_#s1Lr#+lfDMD)%>q zzdu3kB=d)>^-{Z(Ma^?9iKBA;P@X4L?~b!+$h zEdQpyzYJvhmUrc05Qh~0ZWGy66Z`2iAN-PMUZ>Sa=uXc^RL##Vw&6DnK05 zD2dMy>%^&^WJaumq56T6hWH(zrqAC!isJl^i|-&4xX#5n1pLiE)3>;K`B%dCfnGRj zkB{JaO!e)`UN6B{E<2Vr*1Nmd&`)}F5-E#Tgz}LJQ{lMqH z=2qMv9dCY7=qK9?n)`o=>uWi=g8Okq$D8-Lo=VsM@2Zbp3;9?;8CnR&CI2`cCmJvw z)*z@SI~v$d<-c3ja6jnSZeUN~O+KHEonc%m_xc+jQ#^04tO5OkXS6pzb2HWF4ZraS zz0Lio&f)L5P-3b-KgkZuXb&G=kmGZExyL1W1#d4t#^+~g4)D|5o!66nBx84}=YI|F z8{)YBJpG_M5Ak`)_zbl^>K8o{><+EN^Pk$=l@;+FiDB@#g+{9V3U9;ng!D%6y+uvL z)maozmUcGiW~C&WM9(nzRYK+{U)Bm z<={`~ba$MM?Xi==9{X~@XEA@Q*TLUp&Yg$!I=Fuam31Rs;s7B6t;4T=4PEsx)mBRfbYo(29G`cL(J zmEj>g-nDPJzmm7KF~l$YC&WD`p3_QvPx-%GPfxwiKhpTTu(1Z{&EWT<&8xuPz~kzy6sI)cKb3_%2N9ui$qT}{7JjcIs{34w%>!{N zY~Vf*ycC$4_tyDg>hpGOP4&DgF3QI(c|GK3rVLVNN9iKY7g&k=6FNnmuek-(_DMa) zGhBcDC9Y56+b-k#-{eH@e_HI{K)jVrz`rV*8vk>eght7s*ilyw|K{PUw~iL-T3%f znstJybJh8k5c}hH1^Dr^EY?XR-c_Gp$*zHt&MFY6ux4GmPEQ@jyM*tX3qHT&)A3P# z;(nfQx%GJ5gSa09;iZh>ciuI8zhpfDe3dQvxEOQc{Cb+}lYD;5@dG)(u3vU8z*!}A zeinUxKULkB>non?&yR*?U4YJBuX^Kp@FRbld%ng`J;?h}ef3c8f9*~+ zj_@QCFSz4!t8=>owmY79Nha`pZ24Ywzr6UpL>uqVW8(Ua`25QH`s(qodR+eze{)AZ z&!T6l?I(QwV2D%W5#FyJhVzk`;Bjnd_D3K-DbsoNc}?Pa%6LCW<(g*yDf2wwb$;M> z_w)<#<8tOG@FVMSKS=#a+M4TTYVVPQ)OPf=d;F1Hh{xFj-qT#3uFjVpK%0Lg`gvd5 zrn(+@{d9gD2+e_c6N9)ogVgaUZ>)}c=pr?~M`4?PWbk|SDjp|g_xe0I4&pnCC_Yci zjpY8x{<^Y*_Z9V5)$=%ZW_!H3%K`5^(_X)V=KD{b-Mab`?pLd8r~2B9{J4>vU+q8P zb+VX&e(^_n|HyB=Ec;vQa{aR1Z#i}=+S zyzr^1{Toj&ermUV;Pb5TBlw?NlgFR%QihjPpHB?U?;AxPf6f_}ft@@ZgVdG&bIHQ#4v=Hd3})P%3%GO9=QsVop$WY)9M}Q|L_G5_c>@VN)52@`Wzmo6qam|F?@zhUBBlY);qxk^X6Cdh+ z{5O2gKWX=&$Jqtk z=X2@{fB8rH{7UN&e|Z$feJhf<-c0g`ukgns`%&3`gZpnC0p-R)Jnn=~z09vW!b7?K z%w>?rP4V6%^eX2oitk#9za+k+D~;swcMj$}(O0&vN3vWDNyW%0X;u;#ie z_$}9GJEr*2h6SD&x5wg){i^ETZ`y z!0h7jB)uf#7jqt}uZjI}%lMo!_8cF7!b_Q2jmM!b_60UyR_jgT`fAB1%f`wO*EHS_ z%62LjSLE>z(f+Cg(8%=FV85{j_d~*Kxc<|)25^CcxnG4#__)dbx^lgN<0iguDXa#3 z!F8eC9?JbAzR-SZz14skPyI-SJ@%h#EDHRwSKZ@7d|opA9Jed_0x!${!B?O?KfQ1I zW54^$DkmU^Dq`29^ViS76uZF)G*6XGLTob29CxaQAlz0}^W%y_K3 z^2?XT@4oW$s>iV`=1KlQ_c%+v&Ov~$reXYZVjr*KOwen+rPeR`s9buxJv{Z(N%Oxj zJ~fp2)qp>DHPlxyFJj;Dag1EU%aXr|_{^OC@;~#rdwio}pOO^*ju7b$UFUDU5WZcR z8wL4Z!u>_4f8HYwg!7V3ai8IZr}pF)V3++l=F{dp4(Z3#@pmqT@pC3~Jn>3dNvL@w z&Z}H;;Jzn6m|vI3ez7&$%k$v;5QmV)U&*g4I}bxVA~*2kn>mg9UpwDDZlN7HUZ?MW zyFNJ|_mk{NPvG-AF7~}8oRI!f zjj!CtC5GQ~G;iQ>p#GlHQuAkUe+1j-x}LIlp6jJIitkkk=M49kM}#L?TUc#BwP%y= z?L9c$?|{njls|hiVqGrvuj~SP50y zOv@v{UTaYvkMj8T=0!k*kG4CzjR3fjXiLEy=If%J}?Bz`TodtL>wXY4QCb)sw93#N%2T?w+4nT(3p_|0$We z6UN6Lpzi{u-64;45fUH%i=U@uyDZ!Id`#AxBY7Ukc3nBVDP9j;0`n=eD9CW$eSX!k zy>^H?Z>q~eoHL6<9!ElIzM{BZi)`$k_f5oSn_zb+%6YSgxyKFT(8_4C_aecN9gy!f1w`aBU?N6nwd@2`sD`D<-oz^9IGZ#=#1Yqvf0yT9Xk_6)V( zq_22t|Hd!)I>aG}-$xiVt}k#Mlp|ul*&H5+GI)JP_Lv2A9+&O|p5$KY@oG%-7mxY@ z+`bwf-$}ntMqXFjrNdKwb~|;yvSxqaxW~S0xgXmbuiBN|U$QGTFN|AsTXj4MC#56s zwZ*tS)nV=Ng*H{khxFE`aQmCzyPtQdAIXHHo~LCz|3&dRZdAO-i{W?j#AAx@L*f&; zUDm!l4&{`)U&PyAnV!buZQ{NOb-WKK9jmq@c)GgY%bw(`+|SU0JPxro_fd;(#Q9R! zbG~|&+Zn*;T(-~m70r8j{~rIAQ|Cqe3w3=@Km4Q8)bI*mGRSd3TyIf2lItn8c^wyd zhxae%c^*`s=5Z8eb>+qLd1|ko#mA$D-rHo`lC-ulwq52?=( z$CncB*H{?B<01RCTTY4f+s&onej$kKhZ57cf7R3Q{s#9w2~Glkvbb+-Aj{)Q_GI=^ z`ikB-M5|aX%!9*Oi-(K-_8{@$+{M zzspHX;dW+{d_L)Tb@c&}r#c+f7k+|xJBM*Qs9nkwt}lum&hhmd)aR}2_3AiEURka# z+_yNS@8Nby-n7TQYZ5VZThuTSIKUBw$+DRIk{3)E^o{!ck?r|gj_?$d$ zRIihPUHtLZzT~*@_q-hV5yuUmvsCf9cVktsr-|#^QfK>%fAbxFT+-R!wNZQi5>Mh% zfBoWDp81G8~#&h1Rpc{$z3 z_uNJh;#0-<@rXpY9JY`+Jp> zJGtkFw*Tuq9_c==R|t#e7NoCo2lyMr?@|*rf5(67AI9HHa@OT`QhN~h)uOVOG{yJs zc~i~n#UtBeAM?B^G}}8)6Q8+v-}+I1FPXvT9RYlPlEB~BrhbvTd4AeowKra+YoULB zPtH?Vo|j1<$zrxWzvH+LIyEPZUvw?^>$_0CJ$|w)brA1Y-;9ql;VSP#oC-mAI|wgj z_9>XZsa4he%Xpn%Y5*>Y`{k5Af^t0rb|wFWc$DyYU-E19aUr%b9*-VU`y=gZB0hQ_ zKTkCFh4@r(AFt4Ppx;Jmj|lz zWOO7SXR1%^td5WIhx@!JiG6BH6M#SXs9F!{BWa4~km)Pbc9@!V0;vG_o4Jtp%WCkX zS1T8Bx4Vq{s79x%$1#t2QpEk{Nl(z?`5D0P*Q4`sy9uw84Y5yDdKl-`^$WiMaf*D$ z^Ce>Qd~;&le`f~A6MueT)H@99uRq3l2q$GsT>ph}f2#C)*k3#sr2aYaJb>zT(prGW zHMAV?H#~mdvF`A3Eq)659|?fJal9XlJp^%ze9!SZdvx`|CH##a^^Zl><3a5tQ9-p+>ce&o=dP5R$CW&a9?P`<$hL=54C6MJ&VuhNYpQU zC$}qs=f?o9Q%P#p<5U0CMBbn3|0x+h3Fc{Yei$!fdw<6jvM>D;*dG)7hLmTx=L_|( z-|s#yg!3yC`+@z1cAsZ?D2QAPc@;afz4$anw|BfDGfLvUSQ&rkklLlRrt$e!(cC`< z7gpO}T3CI3NO}q@^E{0Y;`#_@TYzg$SC4yUV2Ak%k5B4rt|x!5+FsJO(k>G~K&m_e)=@w_ejQ#p5&dz=Utj&fXTclCG>K8gFK zm*?XCQ@dZ8*_p>H@B%MOp8U;VXL(VGPwE0abBt)DCyw3ljUeUz+)+|P4lf4T0SuY~g}!)F3t?pybK%Du_+q9N`d z{p#y4uKXs?$MD+jc6;e-{04k=+}F?xPwh3${wLNZJpUb!eK3fxqPhN|_WYxe?^$tO zLhU4Thw}N}xCQ!^?}qxs0lc01{arG380as0?AOu6?@A*hxP8H$`1oeu<>Rlj+s5~R zx^}V=Rt5IcRckYSwVam*8{{iYVZ7= z*qY<(c-|s@DeJ=_?u8NR_}9dK6|%oqIkJ#?+^AnwbDu`-b_RC&;Q(fJpYI{@;h9=sE2ycshJE%UrHovaQ zj|aZgTD+d{hIr3F^~srhUSzg_{Bw=~yYeD$0=N!1_@LTe;?>FU7Mi$-`)^%;zx6?% z*S&uEN@5>L&wf9<$0r$9kCP`a0%8V?n^EQQ%si={=Sg{gnsc|$uN^vEaeJOugsX^k z>{Q=h85-g*o~eEP;esct<0$QH)Bu;p_XrLAt}G_rqs6ZQy^dymSWtY&YS;MqWHK<$ zg*_my&gR08#nkrJ|K#}*nuX;s=O@2H+o+}9#263@PY37 zNN-X6o=fC$?ib;tEc#rhEc?lFdI)O=56odI!3Xx0gmJ;seZue1Ld7{4-)^YIJ%j930cuqU%G&j+%XWM*~se5Q6O za~A`z@eA-~eup?#alN0!>&lrn-k5$F%7A^lHe0Xz?ElB!o4`kQ zRQJMnj7`KEc>%;?++!P%4aPm=O=j&LsWlST(pGE6GD~i^q}FsZEvctln$b8A+5{72 z1DP#?B&5w2k-Q}00YO=5C%{vd7XbhEt9g^>H ze{-kQ|NFnEPMunA?RBY)N5*Y8{rB$pO+R^W@3Xwbr!{~1F74L;mVUq19dCutx#ib? zR`MHvDt~WU{hqNNnXXu$a+k*2Q}X>SYNxDUtHZteJ=x#J@3UK9ck9W|_v@~YKD6@I zXkJ$5-^p~bXzhR9{D`ze*FM+Ha5%GX(fV($X?dG(aoeByQEuC>y3<`0KlU~4PxH78 zXB6MY(<3q;+0S?Tz4$emPCCw)_8dE_!?XBgT@EdOUGk&k_kC=Cc8HQ=JN3O# z>(l(ogG+Z^G=5#a-yNP+Yo8}ukEO3kyBGdW{$_p~t)of&v->&oY`62LWIV)ondh-k z(e^GMl;4Z4U)1>4zwT_OcG@4x)?@2k4^2F_|GEs1?GOK6|KQI4wOym1*RAy6Y+qX#nnt!0vSJ&fYd^P?}^TvKx=hwcHe6Q<4mKRZa#U5~%KZ_CbX<1HsO}>}D zP3pPV?_x9?>)}iw6bBxwoFpu5NcggR}qV@e` zp6zbD*=--@Ez>wv?LTC`;pbgf5I(rGoUs?{@@w;5`?L4rg*(e-J@)Hv-{#ii+@DK3 zE**38cJpuTMjd}`J?{56Z`A(OX`blX6>i>c{&YM|>bo2N!9HKM=7raG*~gjviBtW8 zf3v&#I(NJ#UbnyS)JCM7=KOx`DBoxOY`6WF-07cr?U|jw!(Ff2`8msBw_wd{VEo~7 zS6{95+uUV7RLxp96s1oiVmxqbmvO`>d1F?8P3*C{JlUSyUwVm>&v^Q#ozu_Cx83D( z`Zsn?A1t5U#rM1A@blf=jq7x{7wmnvenY0S_~g!dt<%1nTfZdpL3v)vVSUDKl03!> z-B)-?iQ3ES%QyS9p^SPv@q#V@FBG zQ&&ZFDDV}I#ollCLD?PmX8JD~L$yGF52?U&VM%@167gSKak_ABD|*=>KW+n>!&iEq+4F2A>%o0!?g4LhY@e4A)#lJ4o{lYKG=eB?Ge|76qJF~xZ(<0Yu|E^p6U!AMUa>jn2f7d@v z`rqM>w+>pb!F=1@yjg}Xo0Rq$`=)$uzrWYtOLWfi_6MZB6A}Ho^?uTW>iyo6+~H&Y z%kR|BJK}EM)^E#j@q4?uvB$aJTYb5V|3z9~(Xi&jtX=Mo$4%>dw3{CMympE9ckD54 zxy-ZO_7_Th`T0u3cy?iz_9DN(o7?wncYI{?8sGYY+rGBkrZxV;&o`+5nSZbT%l_=b z@3mRw`udZkUVSgu`Jg>wT`J4j&D~yh>$eoKzH{+9xBV9Xx5U@qtbcc1FY(>c)Gk;da8^Me$H-()gD|psnh!^&4XZG`# z56tT<$mg|)^(@SfS@W&p|MuYO0ex?fcJJ8Oo1DJ)yUXc~Z%BEpukB{vv$K6|{=@xy z<-_jq?APCw`?Q?em)+$b%j^5Yo$b{2TRXqsWsRe+{?vohKTZ0wUhCFA%C&FkblF_i z`65g0L+01F^z(C{mFbtCucj$K(LQ#yJ{j(=Z_D5O-uf5hcboCOx}9Ipa%=C{n_bQk zfAI;@?u+|8S8eqcce-BuBI&codRA?h^OV^RZLiefJ2$4?=3RRWFTcN6cZ13|o4@&Y zGXByXI^No?dCB}<-{mr1WAAjQo30PL?Z|T2?fYf-`&*yW@3+%_C(LKJaG{K6#@XGV zdRQm#N5BsrX1DFqo#U^M>#3wi`II~S9dB~u8??{zs&(#L=aaR)&V5I_>HjI?ss2f~ zysfj6_fVN<KpqXniv1UgVT3&Ud!9E&W~li zn*YPC@3OT&%u;NB{;%Jz!^Qrv8>9YA{@wQTJEv#nvD@`MX&=UIx9exz{ue&Hzi@2b ztL0?>Udk)bIj-%V#BDwJclH(g3+HA;|4m|5>VNL7?)YPW*R1{P8DEI#r&@ZV)H6OR z<*$5B*R$52FL9R3ZsD_1PsXF%xV5g4d5fQRmn-qx-8jGZ!@3Kf(&4OI?XtG6y`?|) ze~tJnf3&l`n7>K;S{J^d?YAB=E}UJGdUSl#ZSU13x4&z&j-~C{I{kLg_zdgOLGu*X zXk29ZYAvV3>VIMWgLTtyamQns&MmBc$sMkmHBVx%{x3e?onJd1<<=ugZkE>DCTM>6 z(sepM`X12vr|o8G_dZ(xn)n;d+x`iuN5?MtY4v?t-Uf}AEqzM+lm42t&stgYRtT?s zTRu-bNB*|Mw@Uk2ZqawDY>hK5FKK^Qk4yb+IZawewmB^AI(GHW@7Z#8``x7Y+DNXdYklh za-QRUJxp|Idu~|cIGaCYzfF`L&BszYwe}B<;{ULC^9G$>S7@E=#uH>diIRUVq3yC} z?f=b~pL}p~&ShkN*r0V1ZTIb*&)WW2=C97H zWVukwx!;dHozmOCxyz@*DXC9Xc%$(8N3|W!Q9nZbC$&H6#?JOxq37+d(*75wNRM60 z-!kp*)c0%d@OEywan`^7Ew>%`dHPlE_xrvk@y65i@AbDyoaHoMB<;HVW&OMSYKb$S z-M)*Ye#>+6H}lpW*jWzq*j=M_2K;+Bci~rLxK@5g>(Mc(-S%h6=ex<{=Y2FUfq#26 zuVHOO%iFkqZ*m(np0V(II-S*=aJJv4-z$*2^)fAg`SDVp!WZOw9S^c!u3@b+we^hpz4!?C_pg4~ zjjs+#yR+Pm|K+wTKYy_9xm9hia}oQ^BqGj{DSybV=Wcow9{=Fpi;`QvOqTQOzboUP z-&=X2+uts0KX2x<+pyMeF>br<6^l`^*32w$pC!+0WDeqV2KvT(@1;tbG&OrrqVq(jNEwTE1PDtF}J;d-+Q`fA;lA zeuMhUHhx~}oBdarpIHvOg)4S`&OF;)e1;5fpD%xp{l(7dZ}~E*r!BwJTGzDExwAZe zf1B!8D}VUl!o_laRPN@b50BpU4QcO=J??v6Taod4ZkKbm&RP83?AS;9J?_Ti=ZkyX zr-Avqxoy_@bLCN)uR5*r{@kE0U$*`q?RFlQeD<&WIh|e;pOkjz=j^uavmV{K%Q*7l zkk+d?x3_e(_F<`if%nsUjh2(3_21s6I~?s*nJ*Vkxc%MuHJy%@tbN$n4xNwF^|!u= zeKKk{Xgyb`|0BN3IBegCwEisrhjkb3li^?dZ5__+Q*`)OULx~J`%^W(@NH?|#dm66 zfu7rX#qN>z-1>z6oqdrGPvbY;_HCp6IMR1&`5pg9>SOz}+wU#fU&ZES{hjT)(4+mW z-?Kme8!z5jF6*)WTFG0#ME+)8l)F48?aREy54rW-u4#Pr$?o^~eRel#UIYJL>e!op zW9Q3sQajJxo?*FB?z*+VY>dWRR=?oZW9$1mJ;iU+{%;VU<=4wnFUHwz`~KeM2QmLY z%T45Ter=<9|GW8{$hhOb>jiE+{%5j0XkPo^;*0faqy237H@jVbCH?Ps>)z7g+RHVs zFe3To<2oIzK2PH5y!<^jC4YB5My8+GE9G<6_n~rQAJ_gZkjrv6tlx}p{fE}4^Al1} ze*RFqahm`1P|Mx3JZoMdzt@PE-@?zE2OeJg#9lAcEBm`ww@&NMI)4;3yZOt{+lIBhRzJ3LdSO1h z3vb(ByzqOSJ^DMa{$2Tf;O8+~@6oa7e$G7GUEhVjYVV`?32EO=>%2Z&e))1~pNk;!9`Mp}Zj-Sov z>}-!EYd&p(&gWe^B*Rz#vOB&T*J^!g*Ghi*g)$zuEq#|>qTkyje>PsE`SDL`w=XH< zcY)Sx$B4J|S?M2#d#fbhV?4_3dWDp;S<~U{J0SIsdf&zyt5P06Z$B&XE}EawPW;3_ zNdL-zNp^jt49~i?9(bMR>$F+tFSYgW{2gEYfz)SfTmIg>O8Z;BZs+vF;bXVf=HeN?~CE_gLCdgJwD{$O%w)bHs(>idex z{2KAu4f*{;{-L;^8cVA;n9p+AWxPys*xe0h|JcRwqaCh=8||=E)$KtW-y)pl_uZ}S zz%Ju#7j}bi^(8ZYPikm*WKf0cD(@oiC%{j<(J#IbzXX2ZZR3vw3~v+nL1_1Nhix-^ z0S@M5Tf(dAT?{Yki{ULlRmU6pdkiqVP5JmY@*f8`^4sqU`2eZQIg)_IxIA@izI0cLIjDjb9BI-X@NJoB6c%c&(@J zXZl~78t(P`hei(_?xNh~d1#00;T^n9If&l~7~VDxS>MCk#Mxg=Z)pEI`HOOT0K?nG zM@+@nDBJT%-Vk7ToBXT1CwXbW@HTPZAD=Il=87|ZZgR4cuU2QLfZ;)UX1rRMpPDM= z6>8$MQ&ZLa9MKK_>71XdoFKZ+7yX0D0slyUkKYT~F*%CHLmf;zcRhmb%>EYUPvrg6 zxssOT`^Bn1S1Fz@=1Qfr{={tgY;GL1YJB#*Kn^lt+N3U5{mf`jx8I)`hSKfE>u=-; z^Fc^%rkb0WE6&dN6SoaQSJi!&$uN%WrR zog^v$LE)s|QhGK|KUwG#Cw}b0Ulrv; z0@zq?1o<7!s`H+fQnS0p2?dvsqrS`VjRsi*exH}UQ}R0__=EkUP}o4e zys#qVw>{l0ANeDhjF(MH{xW^{>-R`JZu^Vj%|P-&6Pk9=`VSvH6z@et1ojDWRUWqB ziVfv@wkq^rfP{$lX)H;+4j-mgyA7rWhevJ)vw6+toRE{S^;h}~4)^pbb-cvA?-cw6 zD*vUP>EQuQhY#jy!Ee9VrB8bJHV#)@@;fMAYWGTfiNY)W&7>fw9!Gn6_e=f;#h1nJ zAL<@f8PA2IO0iqd2>n-__Jpq&$iX1T?v(sKvS(ve;>&LR`-l3pA(~Cek2%vPe>EZA z6AMDmm@{57w~maG{JP|ik$q|h&I&nox1OUtM}~)0zB?rOS(1~;Nj&XLS5US?7RGd# zxLfj9$luz%67O`|VRWQ_=x7E6S@EcFCI8ktM7UNd9=$sy-bd*(_5q2n5x?;TiLXZ3 zXJo7wYODiZ_QIbQ{-!BjykinSM|QLHzdhskr@J8l+503vOZN2M^(rC1;noM_WO_zX z&Zi{55b19wHHiEJuNLw#Yhig(zhB}Tk^Ua*A4WL`e@4hjxZ@E%^dqUGAYa;HG)c`V zudyoSj5*Ue@Pm9L`Azb-+5Q@#&!*E3AcxAaMndw-&h$Jwpb8VTPhIlc$Zj%R$GZEH zBVZjUH$El#X{UXTjrI?w6kp0Yp1Cd4t!$LIw~NjWu=leqW|!rw(ZUi!O-hmQO3Uj}N*p7)!t zdBXvqsAjvWZ$pg~)91bSX`I_li?*KWWcMw}qbXJO0{+h=->BqV27jZR*ypvJUpS@l z#}MBBdh7eea*mCtlycx6&1Zj?NdMpaw8l|4l)w0MPf&V#TT3Fm*lt5k(Un2dp zACUMK#aHcqi5Doo8uz|Q$SD(^J@96MFO&RQQsPHh0CKDIF^}r3_7x!zj8>F9+RK_3Zhw7NlVF3=G5GY`vMF%g#l|A$} z;co&W6zys8GpW=qKGe#*?2_bn0$15Tw=CqONlr8Q4uP*xxEgm#JZ_guSP$$S7*1lV z)6@s?fnF{)yxN9UA0~ej2YyZX3&Vg)&)AJW6u>CX)5Pn*Rb=yA&* zzy^cE-=KnS$$^SBvRm}m71k)c)jq)QQ-Un{nbDC^mGxZs0JNAb96!ubPPeWDDkb5+ z`s9a1x;jVstNz447Wf9Gx2sYByo=>(`ycCc_^5YCJpOu(H@Chd+6o;p8m`z)cr?w*1qm=7~ah7gU3@N{?Q?*IKtK3lI2Vs zFf3=hH~ot6x7}54blvLVw7kP|l=MY4}bZlI86Zr4z{ys)1fDEBRR0 zL%Rw7NOGuWc+ejmIRy1>S#CG%?-h9kbJ0yQvbX-}*_xaxa#_8Ilv zZyb%Oa)I4^@3TC-j~vx^16;fl-#;hhY?HsSzx=$w`x3gGNqk=7o1{Cwur**8jjnfNbx@mG}ndH*|hjqxlPuNg1S zO;LO52(%1!Eo=yS2L=a+hg3gF^Hy1}>m+}hrzD;x{k_*pd;!9zz6-j($1OPgOsOmO zCdsdp{?7X0As9vc*>4K_)X85b|HkV*@6D25crnG-yCptGa$+Bp_)0?ahyPsHW1GLH z>#^)+yT2v$iIaVz@@W(v#>?cHTxH6in93>pgm``-KT#@ct3mk#1A#MhetE7kS)7{k z=lp_x67q}H;>^?}RH?Nb6~9NZb7nyszBxH|o2O^9L|rtnzn17$=>Efyvnk67O9G)IdA@|XWf>w)!uylfoDg7IRU^P!7ylnj$ zkCMM%oaM8>G39HkzmOg2dT{Z@_JQHw9p$h-<@Z-#Na1RQ9QzJYU6YTT5!%U;6w}>Hnkh_c2lCf$<9WwO?FIX?E#xh1z>` zzFVi?+vGM0XI}fwnxA;D<};6VsuBL9vfGdS<(SxSdU$yGVLfdoHxty-P}lwWE9L0A zybkgH-MWBf5-W||0wd* z)MsICZWb!(llaKyWBn8_#<@Pg_1XEsiG_vhCX1(23)nP+ zb_CBetWM-g?;{I+le zS;ilHxlx@f??FyzPvFmlFWBW+jfx%Lub!Qm@bTm2<2{w1n<)6$s&$u3ru@ppbeY2? z@i4pspPYB|XTk@9U&_16tGUVy%qq@n&jo)bR7l{JFk%E=opZ$3RJj5lDNYa}zdS!T z;m^-NpUBBPmRP&lXX;F)IG1Pp?9NB|g&Zp+{H=!mhInMj*#=uQ6 zMtVMN(t}{MKToeON`F&-uMIguAx>}HuIKNj$u~U+@nSVsnwg&_A5DC`l$$x}z$a$r zDx6VG{)tMi%mt{4muAo8TkTw|mf^!N=a645=O#EJO*!*rm`vZopPS89CyGS}Zu)E6 zhx<27`DYA6Sa`XR(;f(XvUs9M0T8%h2!X4Zx8*>c$WS!o>v{zR%Sb1%&cdHPov%#6 zTlmzSFMd>bs6Uh$<_F**($kK|HZqWnx7I%=)OWDeo*HjW&l9LV7fXiyp%4p;LmTJh zyzh7k?KWj*Q&YacV{dzk=m%bWuI|^(enjG39fW^E;!DI2{Z;j}AiVXrJypnu;|ElG z!N>Ik{%~(EOnHYTIW#K{<|o{EspR((Kd2`|Ib-D0#+NS>`~t80F!)CH@*XkuOfL=n z*O=O|AA7B)*IUN#qIH*aUfwG0Tj=|_Iauy9K0lZD%k!0dxPFK0?ZxVX;eiiJg>c=G z4`t6uKl~6H_L-ICPbhz8b_Nm!F17I?zB0GNl-Pj*|F+?g9-L*UQ(P#gSUqDFtP%Ob z_Xm2848V+wp8k+A5SZO`aI2N_qy+BJbn$uE4jXZWZ;(W zAy}H~kNP;dSDV56?eE;G>j$?EnCZ50rw(8J18!Wc|AN7$o{X(0r(0gvHie^lM)?4vRvJ`NaI<9(|y;q+E= zzEJzV?wupm}AN1HL~!JDG1SAAEnNRGc~4@}T*Hmj?MlWt2WH zHzuJXTxsF^KGf&n3vL%cgcm2RC-vt)O@yoQVwOKwoObA$_-n~8Q@NCV#ic^d0^wi> zXgbf%Ov378(-x}kglmjp9VxC$)w4!m-SvT2sPE3$4Z6Hyx7PP!A%BtN*PfLWxR=oS ze?6w_UG<@dT{XmfAzP`?X%-Z?l8# z=6(a#O@lpQIkss8&_m_F|9fg~mur3(?9Twzz`^90xyc6Ty5IZ@dX`Q?!`+TY-=C_wp7^7E zFx$7s&%i>lR1bZuz)G<{$cu1w+@kH1d(xD`dH%^Vh4;=iiPu9r==~7VM$>&LYh2-R3BJuWXv_5yfRN|c^r}mP9&_7Oius;LqgLN>_=f2xDKL{7` zv#*qLR!N`w9TH!IxWal!;};~}L3%bnFYz^!ll_6j8zcwX1;gF9_{o9(qeFwKAzgWZ zXTCo?1PkjOczLb>J+za41-coaV9Y`1oImF!9&=LIAraVNqLk0g%$NPCiMg;11@c)= zsaSHZc`L z0iT}faerdI;!o$Gi4kRo|1P*AzEp%caAk-1f{fj%sbdc@-<^K;uTPYoQMlV*oSr!g zO>t3K0!u{M0cso03Kq2QUP zeK)JcJM5|;>Jt~&ycz_<@99*r)bgc`FCf``NAqhx?+bsIxcq;+{%&%9T%__U`zf}f^xp6$^5khTN&qxya!cN)6P=%W!7aLng&vJ;I4 zmyO31iusrOD~dVT?y8(SePSGESvc@B4t(PDTy^qrwc5h3mP#&u8SqJm9K=sK@k)f8 zN`#zBl$@MfpGwZH5A22{$KSPmaF?VK^yl05LA=n4<5+3cA!mB_v_zCnQ5V;rRHz&JSY7C+M8IdfX>oczg*4FPtGzvH4in(>HN$b6rBMF!UeeA>?;J} z72nUpplL{CVKz?c0KZymD z7`ujyB6-3^)V9V|{RR5qf8;us2u^_DP$qOzNT4YjFcExYquf_KBbu zZU^^5`Wqd7e#pDXgHM(hf0wQ=GKKMVsL)~ihcA}j9GCL_V>)?cUODhee9iwi1gTC)Jea!AIhjT&v9_c@N zGzBZQgRTbUH}pS@^uWFY1O20;pbl(t(w`iHCyc{eAqaYLc&YgEnt^;RC*1?10xX31 z*zdRX`?_D0U6d1rb39^uc8$Wd7ds#y3TA5mrbkD5`g?m-TOu%XP;PViT*nO$;fj*q zXnUr26Uaqq7uuT|e7dClL8z+Z}J#(Dk^m$^~$qi`61#2)G1WJV3S;%-VR zX>ok9{%vF*#ve)HYJ03q&y06P;E4!1W5kE=TDc6L>*5@I+{$w>lCOJ=Y<~-a&$R+S zH$SI8@HT(R(&y2n|LW_c{#e#yd?o%ue+O6&WGjU)So*V^4U!Yqm(=(y50iS0_sj9h z#TUE%Ex%Oz8x>zaDm?p+r;2uE0Stv{F7}}p2)sskl%Cwsr2es>y&1)i!Z}{h#rUex zcj4OkYUSD@OhBHW%wMazl%5NR{jOnkt=Q%naBjEa^xnfI zp@*J%E$6z!W6;T<_KF^a{hKkvMCtisT(7(Tu^s+%>;O|xXJ=s2e+j#=pkpczQ;)F~ z@L$dT*qv;S$N9s@U<%TIJw5kpx1ik6s{0ntyXQrp zRplptU$THni1-1;nyV2{w6fsV&@LR8{1j&{cVp(Kb$^V{PlDU zFwS~D(egJ47j;0`{3k^6bqv`2ODz6k;%b%db?M5daq6t< zM>OP2l{oK`woau5&tGebFWtc0)w>pxY2iVvSs zVaOM18aPZ}h4n;JN_#WjHQpLtjq{S^ARjHvRydu@`MSi{%QOvtb$`C@g*W{z!nh)8 zq!kLotM;qGSz5}V7S8G$@)e)exA93*N8mVvn9N|~PC1z5IH8;RAdX{kc!fBOXuvoE zwCkZO+8h@sR!eZ4Na!z>4|>5I=4}`qG399f37G4GJ;#ClL;m$Pe||=Fd#ir(P@mH5 z%n2CqAdek#ta7QGgLP+TImv}`G|mQU!Rdj4&z2`<=Vw~-OPO%J#?s(d@?o|%?5UPx z1_g(uKbE1E{zhgL_JndjG=m`@mO4z~Tt01}P@j3|oX^3OPdzjf;xK5%iCM{)@dzIn zD;|N*gIPi!WAMu@$BN(C@mIni2xN>qP*uwg_+hi`05enb(@^&0VczOVBfJX7rJybx zXGS93mXAptd^OW2e2LYH(n!9KAHvXX$cL3ifqX8<6b>sg^#j4zD+^onJT35vv#`je zGOOBxIJN~NL$HV~l+$|*_Lc1)9#ZPt;eyhPaaFIN+y&O89BJ7ZOFxQV2Ona9>L*eT zd_7xmOu1knCk{S1aYzvkeQ4c;r4I$HMGgc&$4d)e1>cFz5riU z@^tfE;YB&E;YID$lq$Es4m(qfweS&F@+~_c?uswU0WES62g|wf>mzWSH=_K-RE7eA zk}piR&{JGES@y?gCMV_tI}5&%ek88!8RjpRQ-YSX%U>hBm@0SG2TE9$Blw0s5)b27 z;-UQ|9_Ay7hw%cDB-8|bR4Ac-R)Mpu{9tJth1cYp>0jWWCddJUV;cdc3|0Jb_<&7P zeOSep;2Y^*;Fv<$&LAvM)UXd?As*UC;-P&c9@+s@Yaj z;-Nkg593SXp`I$2n2M4<5(kCcc#yv=KISisFPv40@ing^Oxr=lm)TB4nB|+eN)On+ z;!Ncb_>Du2LI+U}t9GC%%R9Y1|pcij!lh9*ue)^D$-3%!1DJ z!1lLE*$Cs!u6FHh<}e9IwIWcy*4l z92%bu_V(7}Xu-H`rf+yeon)uq3;k8?pwes(_Go~dWc$0_5?;kumFEJyV98NI8J5;EWjZ}m^k~3-D2o(o#KUYNPY@$Sm(ep?!89qb2+Z- zhM7*+%+J7l;mOP4HFaGMJ1JD*C`TKQbxsH68~WP?g#(rk?C-VkH{$I-qvc193&3|) z&G(wqtH-e;PWc z$0O5Vy()h8BiAckqpSwwuOHR+Vi)G+boaq5Y(F`a>G%75lz|t-dnKPglIihJ!mQ803QwxMhL09vSiJaXd6r&g?Gy$KR;=B!!NHD!$q6 zo&Kc4+31IeSA!~ReT=H}z7CX{uR_Z;u> z;NorSgMVXv1HU_{Pc0~~!ZmrgO9HQ_!*g%pldf)44&pdQgSU<2m=WF*zsS1+FuWyx zu{whq%K;mI9$-2)6S z;`Pj*2+|M!Y=Qx?yyEj=VO<4m8^*Z{&d)aIML>T`F*laQ#}a>r*=&4Z)vm6y-=68oA>klZkwTHu{}9GU_Ama#yMUXk4jhj#clbQXm105 z*=|vI-QqWXz~R&nSU%&dKjR${e8$;YHa{w#vivAJupG8CsUL)QWmB)mwDUFNde(Uu zFO0+ILR~DMaV`gJJQl&navd+5Z`+^sw{cD<7i%$r9LD1jcp?JFz7V`vAC{BWa0}iS zfn(bRFI&!>hFkF0S~#aej$d2O&su!eb14E}jKJ#=_;Lik8iB7w;Ef1;Edt+&z&{p& zpR;hbTNGZS4950kemp`>BZ8lx3<>Rs*2N)s7@{42Nm)lezR=W>bdK;rh{ zaEZK+SAGOk4lkDjWS-D&-__-OOL_7gd0s;xhj0$Pjq~>?>bvt$;p{KRV}fjJvaZcI`=2`Y<=Diu4^Oy zp&N}Cc->sWS~nM^ry&P7+6&f|(0Y>=g-qP^*u-1_qZ# zsQoNel(QV>Z&81djkiNb2g+d_UAz{^U#M4rY}le*ZFdEml;qCBs6)tS`P&ilJ;?A{ zPn0tcQ_XREuM*5ts^m%_$@aGv5#Dx^!+iEPCgfLgGq6~7940Zs5U?7t*ZN~W9?V&U z)wOxGIy&^1<#a~LC;MnQfsK_7Tz2Rb{0eMnHJ^vcOECRfFXSeBT6i_E1M3qP;lhbs zMKwpiqPA^l<#$=}$Z`@9;p!9eK|%l2Ja{k#d(b%JH!b+Ugx;sQ{B*el9i;ez9WPnI zKarowS0DmPx#{uAoQvOp4tX;jvi|E4csU|m3lVsqh!?f7D~w9R94wetfg!f_uSLjN z6yeG*OytXRFg&1a=1LFgz~7@|V=%YB--m-{Gr{zkz+bGUV!qz6!pnF)LZ2}!-Y+IO zowObe_k*ItgVio!J}Ltwt@v7_)p5H1>@#j5YI!4y1J zmn}bjmz2+P)~)=`_=*)?#y5y>hU>Qe9$3?>L&p9xe>I3NUZ-iYLpw0P&9Xn^wIIA| zyaVD=eOmA%G33WXIasend#+jfbG)?EdOg;Y?cYhb`tIPcr&JTld80mn&nY4$PK(Px z2Z0;1*k2A;!_qUzcNWg;7MoUjVE(3MHxAdB87{6@2>pZlLzfw5))QT{XETV$fDhl< zP!RK3pG6~InEUJYeM|QX8ubm36B@|CX_Ql@E4D)nIu5wJ+C@Idamt5kNT|QzFW@1c z!^QEn6r@8{521QdD2Mr6ZfqIx=+bjycJ^curZkpjVd8(dl?B&xlzh|BDBmT=tY4Xi zV|} z49y?#+5Wg4FULF9-&jt)MUIH}7CBjx6NcBcLRg-#{Jt?=ehPkso}iYuN_JrTb9(R| z$My;8v1arJdLkdMF48k<{P)V^S9*9i>Gp2B(!={2PYnaNjPs%$@hX2*>%lJLON6t_ zIP=(LoX3yZ4c5)Ud?9l_PZXbV_K)4BceB`!dJGnrVZ2B28E5_2WxVjlC#(0_<#@sI zK}@&xpVsX{<~Q!ve0Diphpxw?W;3HO2Vw;6h~u-U7pFSof2s>{{AS{9^Re#; zZyU!l9&d?1$HP8 zrTmLMToZ@4jduWsw~gbPM7$+_k%wy`@iuY%+iY(x()c*q|1x-n_fGsJgMSdXc$<8b z^9;c7HgWvh^mo~i^DKCVx5-C2&jt){8-EU9cuV|ZFAf;qHhu^&yiFYIMK4Va_XhJp zd?3JuhY$+Go8-=VkQwh42h-laF{e zV0cTs-Ae(6w~5>Gm!W{cvI0-RJqj+~CLi%W!0@*5mjH&hjo$(o-Znk}7~T?pk~at# z-ZnlA7~Uq1f1CDcQ2K%WV@Fb>Fo}(qBUtr+d=JaFI20^gHkxu4o}_V@_fX~T2y?!K z!ppOzv(vMca-lc@;?$LR#(_W|1wa5%KBTMBo^awIr7FZ>0`*K4=1@Z`5jp}&xdmEJ zgbTaV!vV!@3)aVgKadIrD zqCiiyLlzQ-)-(9-o7FUBbF|MTa3g;ssLup^Q9ohx$1*wTvpPQi=KaeM9+e zP>`DO!gAs-lkG%~$5o>~Z^mOg$x-tI{nYU!Y=)g0?Hks+dFr%e^4B8dY+WPuVSfwo z@iX;ge4Fx-_P1qvW?)YaFJ@S6f0#e%3HD-4s94Zd|`jSm_F~ze;cCEPJy2z99YR`MP407I;_huik2(5Es*F1N|`^ zn9j$9e3aw159_l`^)cHH*+7n-_iIg$1w8{?BrKM50qL`8*@5l0W#Oz(!Lldg+ZG?c z%NX8xS*AnA6Thr+(leFL^h3v#S-vU#tzB}$^uThmG+&qGv_uStm+fD+^k*C^PC7p- ze_JBPma`DppXWczl&jJ|mZ(<5n7A1+0Uj}*neE&j=&Aj+XO!D|E?VJbyKT|DYxdWU z0G5OGE{w;7Sw29x?1*7Gb_B2-bWzTdWjExTImYI9P6`!k>I7PI6q z-a+%*136ZS!g4rY#B4sqS4%vCK2h<){;rsI0DhGHIleZi+-5y@vs>IuCm`QW&`J(0 zu7*w(VK@#imy>H&`eFUMO!-QVOz4JuF+rc@bNSOS?V$A$24z0me?3B3?1lcC201S<+NMhO?-~&x$_z>H&lKci?S!%En(UX_W`pC2&E6>M#2hlSwOI! zY@c(MeK;QL5#N!f#fRjr!d15F6^y4%d!n9}Jy{GN>=OY1x2cn379oj5d}dA>xj{|`nqT#WNRMFajA ztMOtvj3*Qt;ye#rRm2QF?|Z}ZuUHQAd7pn9_iEY$#(Dk>d0YEO`Xg{Y`)I0H;QV}Z z++WvqTKIpb`PZnP3a_QV^cvM8;li(1UUI)DyVt0m3Kw6uFqy~hHL3^0^SED<-D}he z1!$)&>3&FduTec1P_HGNT{~Z|QN5jUE)Tb?@`v#iDz8+zcjNW$a#G>$@{qqTV`h2F ze4|`teYpI@g(N|{4EffFocXM0)|S6Zd6eQC4xvC2c6zhZp{Sx!62 z;dHzHQ`oZ;UeJC?byE+3YdzghkUkxOKALX@H)!whxLeHPXO11gCKWczp~Bz?e4wfD z#_nSKgM6&l$!Z0*zcenRJ&?oSyEysF_Q7HV?HPNwme2T;2+z`ZG|P_)7u%uB3>WAb z6)sLEX_N1)FG0At{$oTyxDFyWFy99ih)kg#0>{ zOB`NKhhq_P)<{m+ACBYdt>dI9594|{_e`kc8)xbWy-v2~ydOA0yj12$T z;VP3IYr28-``Ihi@6n^eYhlDTXIkx_|5eSo_C#4?64lr^QEae zAJp3!CwhRhoLYn&uDjU&+H$ylj`exCUc>yt7xnsrn#Lbsy!}fWf57sW`B3z!i}|c) zRJb^vna}b`j934}#X)+*a&wU!(jL`~42Vj}brdU5R%R-n{Y2g5OMOeZqQ6v4WfYaCk$!G?6csf^x&a zC*e367hbBsRs>uDGWZAw{OEJ&qRx+_eYDihCwlKO)HRepk9#CJ_7PS4a|YvXAs=S+ z!nUau$aoV4bAQ6g33KPjkdOOS^65mTzxq&~R=b(II-2~cGVk;$^;i2hI`&a4R&lc* z4nU|6;IkF@P-&k{ocBt!<>S7Kd7Lf`4?;f9ZO83SZ8@-?C+sDsPwO%HdjCVs7C7x^ zsCP^ZcR^*&|+9}2f|*iJ&1 zxrV=x-*Z!~`5Masg{v~!DPM*c_;a&oa+OJZA(UU9J##1?l=C58$xr9tpg7w3sYSlp z(G2%JWBmg@>0{uh=4UAyB_DA1SjYjKzenMIO?+l2@7EN_$Il>(G36u9VhkKlTpJJg zoc`Ob^Tk4a6u%UfW9%>CL3!S~FCwNlE-U8MX~b$uiZVrceh&6%g`M9lJoL9%g@dBc z@WxvLFXK^o+M)ulLLr%V;K8nfX1s&^1+_jyy%5TQG~(oo&$VGsv0b-;S8;F0;QP+? zv@)$r)mobRK!U=27vvYV^9<(;OV1$vs~8CNSLxXi??L*s_$nTQjg><=*rFL%-y-xF z>zgVYADPBp+#7rbno<%Cn0 z{LJvNk#49q>g%ggK5npsb^XM%Zc{%NBY-ql;>G5 zQ+?R`uEgtvH|H-Ec1V+)*t4E4@G-_$B%UR__P)ymKStpS?FRKo==fv1-T7V3=l+~d z;>X^1P{>&&J#9Ih;9{S6Cd}JEU!@mpcQo$Q`%A@+KTFLairszu_Yh|{yKt3|UnBkF zcj@=MCta%SyZYPux9M*cjVb0s_4(jK1B^$@3D(%bf!?^oy>1Ix@&o(e z{=KyB(Z`M3xaDNxGjM!p3AQ7`XTA?#ni(kG6d4a2EzM~>S2_c08)3+XsY+EiuTz~Y z3Qck2G0K7Ug>$&gJ};WkA@ltcrQ-MmmY>Cw`O;YqukYi|huC)po$hK)!ZBQ!1#+Ov zKrPXtJs0tOLU@VhwwmMES<&%d7X)YAk%`+SjKQzwbayrB8OReVfKR?s=NR*}dvB#Q!yo_mO+m zm)*GCueJFYUCzAu27Ru5{2Cn(?7lfg__uU^iIaQXTiy7{_iB8b^k+BoakuByB~Z;1pfv%--vfOA1xfefc{(PV1lI!JsId_ z4r93ZRxM}ydwN|KyH~x}jr)E#ZUxuhBczz$9eutqrUks-{29{UvOlC-JhKs|Z@@;h za0Wd5f>E7ONT2+Dr_E@!7{L3nZ!h4(FU7CDEhEaw^--N38lRAOUrRX;@^ROAl7GcB zMwOiN;kPQEsl5HU4-a^Fzx(&~edHqp9^OJv*aVlvct_tmsP2jP4SIN=_nZ0-`Op}I z9v9|E$&Zo~#m9O$)>xp^8xKhES)twe^MW5WzvA70{IbA4sQWtEr~9uZo+dkY|AWNa zpa8}CKxhYSbr-1D*z>-A@5@!b*nGCmN9;m*8?2vAC;La(ZhHUBBe##HGPfnuxO1ky zYNvdW9yUl%>2I}c)Z43Pa%I@TZw3~r&&<(w?5L;2sfo(v&m+M*Oeb-ghbiRa?*F8Z zg$L>9@K8+y*S!gvE%@R=DCcz5d=TQrYOYi+zP57+O|@yMGC^jUJZ?h!k{P= z2;p!j*e749Kwm_03O0E-0X_J1^bCFPpqoi`?EB-B`k;3x4>4i2eDC_7pv!Ik4zYXH zhc(XSBfIaP*X0}Y*nRT_8D}{kl^>(>`_QX&z8Jefm(T3tJdNSxsH)ZI{hW1#eZBn^ z%HOpcHJ@E!|0y_w1y5>)7?`~GpHzOifa0<1Le8f+jt1LH;>j;iN7K?Fz47wvzU1+g z-*4pe^gkCUUYM^EWB1tD zp+mUo1I)+zWJ>T?DZaQILl?`RZECj~*e;z*p)ZZoc+dmBNx^SR7aihN! zJBMHg*%^HZj^fk!2yAUpz}-{;!z(x^g>heh!CLV{5q#9rC8sL_M=cFL?s(51M-$iM zIQ%&c_0+glrj?JTQCFb9=4)l(iG^!rOdNZWf>TBeet@fE5JEX2t_%^#4{@cF16MjZ zaHUg#V>g&fp8)4`c6j`Y`FLuJp?}Di^3B60On!jd;e~!}-5W3EhkPqs0bly7`g64) zjLaas2CmaTh0DOvV;3JicH!u8faA#AiWLsVO)Fbz^(ih z@Rhd?zVgOR?R43A*_E+H|9U8buhXyXvp~f+_ke-yzLtLh- z5SQsn<9s}q9WEB{z^!z}a9lOe`nlPebE|enDrRI?pH=!2mua z0UX>F$NQihz-M4k$A#nkAs0Ra8>GQ@?8Z??S`KKgz*2AklEn2nJJ_Kn@qkV^pUb1= zU{2z5aBu+GJO@YO@C(UsNnC|d9k#=`I^fO_#JD=(E*cL!V7@+=Cx8QggY$YoTYL)P zorl>0#TnRV4$kGF(Rwp}5wF6?4|KPx{K)*mJZ$v_`>35#;R@xb^JprQbJYoa;KIwT zcsU3C!4Ccuw94}{r(5Jql_nKz%SV3oOso8<8JP32(2B!}f;z~So>L1reW8^#MNn3sdpY(4zUs&r8-zrOv!Y9E47hY`jSMiHrPm8b5U22t&I39oG;up$p ze#wE4SK+i7hn)eRbm5iB^0YIZ&z4R(`Lm^h8?R_S?_2BrZ@Hhq7$|iSDn=LYYkLfS z<6akhHEF-wK+cAg!{geW*0{FlAAtUu;;ibP3EOL`y+6l?J!l>AhG&&Z&96gzZ6$l1D(`X!F^k7m>!phJE?tRWo5gOtDz zIClf4NWfM~MJO2NVD2V)pmAuyIdSMhws6jOyuPW83kyf$^1_{pD0S7|J(598-GUhBh@KA$Gn=r7obxJ`-SZIh2>W2;(hN{?v5#5 z`cJg`f15q`8(yn?NRJGU4x>R6pI;RAuaW(sUl-@`-iE8J`8+H=zC4qM(P^j|P8O%8 zg5ePl2R~x!zxf%gDszvc8c%_-(n-vHRllHP5y~0f#?mUv!txCccZ2hi0zMv{rAB7) zh47h=xOFBLzNGMxW3bG};)h&OfWk3ZQ11C>)TE&~L(f2lphI~M$LryCg~@^bqeC#@ zMi{~N(yA-?xgiPw1?@F?~)!#_0@ zKim`6KME_Lp=UcY>K_@n1tU%y2!Q11kz>8~gNeV;^3Mkv_8+d2zrXc3eU4cBTlKg$ zyZK8sUb{f+&+g(i8eiztk?Ed_#HNG~l z$5+@z6Sx9g_;t-+J*efg>%;I0&hmhozuF0zl8@&fPeOhJt5G6n{F+mrSN-Z7Pwb+< z$A&rR!kfv3vL`w|-G{_`zJxnOE9my>vc`0pxf9Hu9! zcv+)(|BEe+2jf3PK|iEmK)LHqQ;7K)?Ldp-0_h*(Ns_lyysrYUm!hEpYCHLBT(ZSxE)^_)rZUVd|L9iNWORLNl|}Wf{H3U^4@!& z=JUA8Hu3ZKOB^@vL;f=k==15Azd_+eefWI3;nD8oP4Us~6em z7&hdCtLiYvl`FCjmPcz)vDj149#v=e@huUcGZ}W)qXEmE4pE9;nl+Y z6n0nG?RV&Z##VY5-Zfe;X0Id5ewog%p$8l;=EJ91U5qpT0eZlA+gE5k+5?i$>&`Gw z;Kh7iPsjZ;jI$ig4*499fGbUz&p57`Gv%|tF%ral_7}e=crhNtqlN?Aqx0Pet}&l+ zT9y~A*Gqqm?5SS}_1ThQA!|F@?hVQ&?m* z1ziJbEmRKntR$S}Grz;aS$-7WAU@10JMHJji!rOdCz?z#Xo3)5HAkTR5R=U*M>|Wu zR4qWiazG9R;dCA7vDHnp$=UgFTC!({YuySLhxacmoWpD5oi7jKMdU}uBlF{vwFkC7 zS5iV@{M;4#T*wEk@`Q0xvnAe_;Cq1=%i(ani4sT&vWI>$PeQ zT+LW?;Hq`+z}2EU2d>uMgg8tmcdiRlxWjIMPaksFP2mpyRBqh4{!Za4OlY}KAB6`! z78V{X6tr;1dLooF87xqg{BQxGg}eMM&CXUF;e}FqmS;~2{VQMz7a#G^K0NPkI73bB zj7mVEK57|I$PdQ#6wcc-z`4_7qMpCT?FGp%@e84R9`Cc$C*#^{2VdFLfm`X5<>=lg z2j5Dc0bi$2woiBZm}wwG&e`&8xNhCT9d?7!Z|8b>g}eAFf_1Jo1VbpZ6w;AP4&7kq}e+7H1YA4ZnVd>7=4Qbhb}JkZDDvj>L15$p9z z3U|m68QYfAnomg%J+S$lu?<`qLR-zWTS;sfVe=i~5(WzT?Q#BRH_Sg(eQQ#_nK4ZH z3MUUt91{fVdFD`7%@^%Ba=B{CvTO4l_AHqjWC*^oVz>ow)o1pE^E(LH_fVY8W28gG zUFE#OUHpjjFVr{W<9-eB2_pj;`pf(hrcZ^l$IaNd_%1BbeA;GH;+xd}*{n|pevJC5 zf_PV*%H6}6Uae3I-Z!8ggnCYtD%Ekl=>$B9-Io{g<4*ah?!Nv3-TwxKKJDiw_SX&N z>wP@92#WoS9ADmqgC4ML&-Gj0$A;^%&DDa?C)O|dd~UnlPUQBrwnD4?i|GN(bHlS8 zt=%O;KG)~DddzwHL?iPb_HHIM&x+59gJ&&x`n4eY%b>eC-Cfd7U=9`dlY<+!jn0P-n~e=r`?$ z38_o&Odp;DC5|BlzS0Ng^Mw;_K^?$xe>eO{3GvKFa`1xoH#qk}yr9qd!UG;c9W`Iu z!IY!-wZL;f$BQsC?ku0Pq5Ij?xuUr_x(?SuW6kAxe?vpRzHO|aiGR2x); zkulIfFh2p$K0N`;NnzDZ-k+&XP8R`ZIq0ICvbA45CRfDI(R_R6Gv2gtOs>f98x7+T z^~C&xc!JKqU^&d+c&y~(d<*1ny-woHKWFgGbxAya&+=K%w51Q*ZP^O%C9J=74kP=! zP5y@IL>vny(@%KZTwrI`ryj&tkbZE_ao$c6(_0l58~AfD!4pbE9`5#PYwg}mU>AtSn6~eE$Q{tV} zPU*f|;#)Kh(sPf-d7NvT@bf<)@i@u(_=d(gz7m9AaG%6iNuQ5zNqmj)sRK=wUwB_H zJopK}BfS?&ypQDLc#xW>YefL$BU*0-`!eBKvmgVn5Qq7ivp5q{Um-p@>(9>5IdSNN zD-@^HGr@ER`Tm+~_w<_b!bz;S8-JZT{X@Hi@wx4yHb9R zJ7~Dv=6)Vnj;XG2*MLHC5~ges?9qBL=*WcS3%H#L9@_&UARHzv!xZOMyf_=6u*)C_ z!~B33@3YJ<>It)WcUX5OcU~d>8T$pqVf~sDpUTfpxz@G8lxtj~C_H$$$G=d|skzEo zOmnae7)Og5m&AS3X6E5^>HG<_avtaCD?UsiheMnvPQo+pQV#Gl@`3NqPQmUhE#*n` zgL0i+mePOh-+my*#X2az#LoYBftQ(oiNq6BE@gWp-of=lH9t@fLt zzmxnuc>V(l=kha7_`9#vIG0OZgl9)J&gJAH=~4!zVqL1=RP_KZso4De$w;v{CK{+1#=#7G3=Y01qiKj`tXvo>c&}rSSPF3#Vaih`Fu_&;a?qkp(>X; zkHu7dgNm-uM6NGD}V57`&@2z-UVFR|2tt3iI(TlD@*?0)## zlnPh&QM!ML-N0YkeSl{U(s-rW#8Q^ltt;5uGJi%q3*U2HBkwH z|Hl8%pwegQ_jG)*`#}4U!rQLadb0Z`F^zAW(DB0V_@8Q=-)Gm~aLc*0>6SzLa?qwp z*f8{!s<5xo%slMr2^Gf4@lx2&{E3QxIS|4_6rz#>|3e>NH=a6EZ8gGnyzQX<- zJ^utIh>YX2z;3GFX>howw^zMl^I^Wqd==hkY{>qBK3L?B^>&-D79yT$#i4dot)3Zg z;a5u~wNS*CQ?2Bnc7^>C3nIK}x4#gqs%ny3a$r+ECk|@PD<_^B~C&tb^#h6jneYeIiaYj}I*mkE54%Bx%M zeYwgnjVpA1VK=b<=-7~-N%nF9(SrLux8t|%^rw6!r#-3lXLmWL`_I>@|D4_Cs_gGw zqwkuRl>NQusQe84Rp~7`nxrk}B;K9sAJFNru_f0BZP?#U?l;zSh(}o1iaYa6!Um;& zDR-9Ix`|Is3A=4N^?^>iOd8GadH2fx-VRDX*~VLhoI2&l?5(oDw~yKv-hC3^a_XNN z9UDE8!J2}!1FW9X#ZoKI;pOzB?9kf{(`|MA=YF~0au=t6$xjU(*G-<-opSzdTWh}! z%yNhI2>qk#+avXay=8_+biS7I5m%Zv%OzpAGPl1Ze}vbIN%=70xIYcY5W-T9TW5rv zO-lcg-=Bf=Ott0iE(`v)lRtO_r|ZKS3NLZzoZ#1-cEj(5N+n)nRq_**9;80$;oB&_ z8rjoA{vyfu4xSM>9^9S3oy1RETT$pB3`QD1NgC?+|#L z%T-Gbl-p|Hq+`VKWt`8!VmH_~AlNVEdS&QXPL{(96fUe|V1M!@aASL6jrx@&dI zgTp;2KlV6EZ|YoN>;N_n;Ue8IycjOzcM3lE-H&HRg+~Kl1t-5_-yPm&xYYPa%jk$c z&;3cj#oOfL`RO=y4sR1@{n15z(t$o|TK+)t2%LdooQ#Bah9stLQx5IV*%AQcUkQA? zO+MmR0fx7Uw&xgpMKJ%O{?~wux5-ERxq#tqUQxFQ}GLmq5dp~<9+Gz5@-G@+27``(s>!^Zvy1ujU2uZ zPr?tpOSi)Q?eb}PI9~hRUyC3-}gfjUv}1i28NGPJt2Eg)+@Te z&MIEScX==cr7oov|q;FB&K+DA@4wwqjh zTn~aC+wCcA&_?0tfz4O#ba-InAV;;|ow$P!4aky9KHvox4xeERR*S#9agXgUv=g0t z)ewaM+kAyP^i()_?ckr7bIUm~=isY;iODl9a&R=q)n73UhCbtv1N|6hiViyft~RQ$ z^+dkQZrC3Zfm3-R(Q{;I7x+$pVf~RC&qer~i|WsDg%|cMnXaD1eiE5a ztEVbzTNfLz@B@nv2huqEVPHefa`kYzXv+b-T0IO~msoNjcAat{8#!_8Z*lcIO%_i( zam?-!d?&7wIZCqh1iVE1eTnpdc;3xF5rNMrL9OyMqCsxAI3f6EZ@QMhycCY;iuKKw0m zQ~~Gc_l5pHO@ws0yZTlSAq#i4@_@ilqsFmwf5atL?E@8n_FaH^GGo^+R= zh&$y#I+;{$jhi4GkAxfR)g6!JdbKRCpd6lbl*5?bsuB7?dEOE(EVo_XFD!>$IF`dM z9IIU}9FmU{2l-B1m)ju8wx=q$-FO}~ZRJC8>&7GaIIhuRAJ7NOc{h%NTK$EoO%b@8 zkLA2e4iv*q{ozzTCywR0OAeOjZX5-*>W}4l3y$SE_}XG;EYF=dl;=(yhHG3nl;=)4 zs+`9cEIpw(S7K}&%Xyc48dquw7nR#BxN6tnz>MWD;%6do=lBlrPr3MzVa6kHr+nZ$ z<$!@uOsk&ofpp2I;U@3-IX&Lgd4(RYVK->ECNr>2#c2QVPzIyj8b^Q~Rbc89wr72q z)m1LRv0u}$9hxylWsh6=MaaP*CviabiLYMG`A|5bl^8yz#?AS>B6gdz$3%O% z?i?RE-g}$cJp;yJr{#LInzKJ2#tU?C!|-A^#BHhMEpWaO_63>iL#w%|V4hpE@l!&d zb>}#d-dqXHCgtP06+RD$+Uc;LIQkqs`GW&`9IcSl@x^WsUuqoZw(bm%lX82Xr9gba zK2@#$DwRC%%-vdkXAh+ZauavnDZ*8=`V(&Ml6p#glEK1^R$O;jG}Ce%aGBzzd8foT zoc2rx0~?lnz_tAPMRGiG3yj~|AA;kFhcS9X`vl{Rhqa(nQclB}-cXJb6Us>^yKhMz z#f_dua3`DQhLqDu{W;A8a=fzcOrJQuspU7blE3cMr+XN>&QfELQM30-zDNB_(ryr4 zeI!37*Tpo+{>`++S4huBP2z1%`FKK@9#=|yK=RKy_3s&gkx49Oy!xRxiF6nPtTi4} zN0L2*nWOM5cA*@%T_rthr=*;&%barbMnAB9WHu?~v~$1QDT!~B{>{3?yPW-XFlgVO zQ~{IrhjHW{NJFUq0XdGmMf$h!;cSvyfbZobzv;9mj#G~y+iNaKej-9o+*%F!vAf?Q z?B8aW+bX|+{L##@H1ZG1@#{6W{=+b@2?l|0^J;fWe#6aAr)b~KX8o-~p9Shiwd?~& zmg$)b&Gw?;Z#&Bq7%m=6!Ca$Jh17nEx2Em7ds{Sos>@M_egx5!j=77 ziN~p2tsRi#?_=a|HupB6{|fONamn8x`Hif^<1b=cL^br}DWW<=`PDnD4xU za@;>_+egnUP~-kcx8y4vOPbgRq?~ikc-LppU^x)GPx1@ouXmxGCy=G|;3Xx#!TsC( zebjme1M`-ifRi2SQcl8cPn?IK3(!N;BEH(#ZaIm!lRnwIEu7=GA@L^Jr@1BZKBqqF z+#IdXK{@|n!5LqQuL3OX&=0dlk7G1?&6<>xcKQpG2h^!)7+;d#LE);MlKX(g2)F#j z@4MFjQ<6XC_80j&!Vbv!8#PWRIf=)d=|Rl{aoHhr+mV4J7PyIfrJPREzka{O7oB!i z`x{fd$nm2rg^R}lc|D8HbSesd{NIl)@M8=7*aAPcz>h8PV+;KM#R6}5y!ga7?$rG- zEy06{RI2_>4{Y9f_6uztg1<`p1KPax^b-Yd{i%9iPn*Z$SAJU07w6wCJj-8}$9!+~ zeBqxRj)3<+cjnpt)*h?pWAXdhEA_s6HgD-x8Q$g-BEoBhgLy39`_TUM^DKE>zq9pg zTKYwWqc-y3!omA%+WtoA7lilsAD-~WGBO;TUiPiu+Wz#*{;u?w_w%&CS3a=dw z<^|z6aDgaCBI}8d*dyvE%hhiq>J`Qx&k?6RA`e4c~ND`cgeqj+{WqIhe2l-JxNFa4`hzs4`P+xy{IkDXww>!wm+5b>?ei#J-LlKtFS+d!8<*jYlDF6RsP+ls}D zDi5|TUX(mrzpm%HC$DbZmr4G9A13KJ z_f(xzb?@6>YwI88r{b2z@f9O+7`OMT^ggHqpN1O%oVH!SxcTGK<4#2Kb({jeDBG=C zx7-fq>HE%byD)S!@F~}iPzQf68S=FtKMmIeT=DAU`>T)-<7(UU(y3C1hU)@cY+P-> zX%P4{Tzx?1r};7pe6jiQ_no1CmD6Ng4c7~}*tl9>4S-&49Uq3c8ejf&sUtQ&&F79! zNj`1AsRnU1z9GQH=BM?kJ45ED;d)R<Q0l>xT)qKWzuJvihnbH>xHv#!+ zam&CLt3&f8cZM8`O*xOWzQ=V)TXzx1$46f8 zuVzO_$FjIS7-2stp(*+OM&^h0Xi^;aYl(}k2llD=<+mC6V4Y+gSYPJHxQOdIC-D#G z2ak6T%KXq5C($GR+EdKEq%?;esm(3fEv?|v_F zv3jlf+qhoNU+sJ+=i5);E5U!GFFl`;e7rqET<3Y|IOcT^XVcpUe3lN&mm%QObQJ4} z4yzC9gv0rPzTo=D$F<&<|C7F8zf4dZ_Xmly`elU2Q6TlWoBrMEgVORBt*tm;Z28hW zKk*NJ@p{Lz>ELlzeRCJY)vZK0HNQt?eprtNjdzbooK=rl9gMT;F&e42aG_C;=VnJo zKgG5BW$?2}eym&Dj~KReTpqs8#Qbhj>c#rjE~0#%m$=ya4qcS&UkyH!@ZfqdMEq8L zbBm1q>=(lMdA%EFyKb6aV#NKgjEnvayodaIQQ~6#v-)L%_|^IAvgu`?thhbzO?0Vo z*OGD3mlln8FO#@fUveAE`wFnHa_>v>v-)cA$n^RmUkQ$x_awy--E{2ajDdy^MdC27#)mld`Y*)Q)+^-Gj`s_fgWh)f^`lB84&&yP`)S5u z{#Kt%kBfXA%6&_1$WL4E^H)f{8V=+3T$A2cIXG{j^=TL2wBySm$WOyze%kriu`QDK z^W%OAZqMD7(icrfY}`8VX+Af=7cFkzL-IPTHjm1EQip~cjEozr7jb+Xk3KgcKkc}? z1vt%@almzUrS~c3H+FP7u5^|3Ps^_ha9Vy7f7>kTyg&o^G#!PjWqum20yr(dUchO3 z(Lb%P5U0iMhqxLpmaiSjm%m2(r)@tv5f^zqRGa68whqgFZY``T=Ss>SNdJ@(>hPn*OKcCU*F=sulyn$7w0dJv(6{F4<>Q( zybq5bd?H)i!l2Z_`<=|^o(}UdZuHM_xLRc2SD%aHD?A&AbFU8f71pB-zD(S@qqu** zPRE)_{;0QbgX}A9 zyIO_!Z*c!1Uj_KI{Y2C;IW}iy-H@*z__X}G7D*jyTr#BE+9ugQrt7j8xAr;7r|D&X z`Dgp3pW(WaMp2h z^Ez1%-fyye=Jg(Nb&AV+wBwJSAsJWmWd!)N{;Sb-94l`5BQma5-xlPj^=Ymj_>|*{ zCdAdwCw3em_wTj*qWd29@3rH2#}(!N3tkV!brSisdN4m8CnMhk>QMTx^LXi>7Pkz~Eym7E zZGCA0pSE2X2b|U~xlhFDC;^VQAMC5!S=J4Ydpz#{vh6CKdrBd1F~+~dQb(N#y1JiDQWBJ2=J-(jnvzQ=Y=$%``~#T4OfnQex?e~ zlW01cz?aLXZ!de`c@3@qu&;P~gneIv=NvTLz&>%;)f#Z0jMguM5Ldg-J_&q$eURsa zdnDVsi@s?6HwpQ1T=cJUE6fjNJ?)Rg^#V?dI}A9j5AvUe{FLo}8~C*C`2aj0pv{k1 zpSh0K`rLamtj~(iL!ej9?>6a+Hs4BoKRzX@?I+fOPh0;60H^Vd08Z1<{;JfW^)uE( zo9AV?zg@%STS;8=`~lqepsfd(AM5R;IIa}l55sv`ru(kBzqI)=4tmwPy)th78*0jW zFdygP9?!O3wJ(%>vGvt_uG9H(&WC+Q|0;NX_o?*zRVLpY=Swf}u`d{RI1<)**Z^rZoOeB6yV=Ck^5kob5%qW9VKxRZoKpE-_OS8iv_ z^E5ONuS;5@+=R^IOlIG>D(; z%j0ls2wwX$wF-v&6J zT_i4czFGBfbe<4(`26n6)-N4jPWnLA`?~4ru+~Y=*V5af{7^6UeeNrUj@L^aShp@3 z?{<|qt8UHjq{qelSTF83O~JwWU2VT)l=8Lw1Rtvop5Tu%$GW_9wRi~y;0&Uy?x(H@?+gvJ^0_z7yjJ+Dcd?({(77*O~R?Z9FR>f z=ZiY9uX1!A#Hw3KIbXtYTt()Gb!*Ugcc8>sbz}b6^8%=Y$GZjD;#O}@?-$SaRJJ~- z6Q5e&gJgc_AJ%O^;X|DJzSP0n1+U{T*>v!@*m@w2$GZ*I6ZgSdebA?zzw&&4pBWvV z@7bB*!+O-eozz3^gXd-^?t~Th`PqrvL;E>6FVUCY@5(;4)@O^aF)aCdUr4`yw|=(7 zX>rFR_t)|VCg&}ie&FAI@% z8v-3AY+c^&jid6f@xD}P^O<^QA4tH4(Ns@+#rg1%z^kgo=MwZ4jt zI|y;LzMACY5hCXG9`oy8Bl%uSYaZok-Q_&B^C0~1{8PhKq5m{riiE>;5_Pm_UUFP* z9!)@8&A*Nx$n_w0zG?UCabEtX^4H13tY zX#Oz||70ClH~x42so@48u66yx;+q6MEiUu$PYqZ3A^2jPM`Awhx==sx@$laD+4ZTJ-ogJ+5BrlTuq1PH~bs^vDB;amB2sN>*H*e z@p$GZGOp(HAjH*hqmj7DNZiOzAwQ+BD&QY)7rZZZ|Exerx}w>*t_DS^x4_ z4@GZhB#!grpPG)`uj2B<>z7)ej>YB&^&O?}o1Lv8)<^34n5P)F?-QU~|5kGp?1zQHAN^C!ghbkJUTAS z=i{CbiR+2Pof3&VBNEpe#-Y!($7LUMZLrJAd5E|XSjVdyB{=WPS=r)Zzi4s$j!5Q_ zx{fc)7PtMR)H{0b&Z&Cyzlp>30j~bTbiScT9QvZoU&LuT5U1sbxZaU;9f<3=Kf(Dv zsAsDO^05xjw@;YQ(_QzclKJV@0Ua)#`J9bUtX3p=z)r-qMTXD7X z+2|khd0*Z$Gx>SG_lEgA?tPKCMi^)LQrI$mokU+o2}6-3bz*n#va`C6JM)|~PB@!+ zCMk|PMDpQrGWy5k+x77GgE7vkTkrqH`7%s6)t5tOM@RKTNnc@H^rdq=UB}qI^nT5Y z*Ae?4md|~}hjH0g*Cq90A9&m`5{Gf!BQy`I2962e6~>`2Jk08Y(Pz^A=4T|ga$#}fTm51-#@v*ZiZS9^c)Fy)7OeSSyD{II^L z7q{np9N)?36^@X6Rv)w}KhB5ybV^(TOt)W zmt(_vS)Y4%w)Kj~S^15&jk=vE^TWCo_&nM15@*$|aAW%Z5a;dA$;Q|7??i{C7w3m| z-fWn3;r#XaeKdUh>v1P%)4}7c^{V(#qSxb<>#%))j`L-VaH`%@r4H@_8#wEH#5noP;WfP_IJZ8t< ziH_Q)$@d#DKl)eBh#Nas>SbQHBwKwszviWq5A(~@`2%aa&pL{fAJ0GJ<9zXWl|OeM z%H}hVv$oTmAI8P}O8<=O7xs_&a3r=-9mCXbR@_n0QP<)|@-=8bn|&Ek`0~#s`mFqFkvQhD`l>II zZ*m*CebeeT^a0ri+I#bcBIB|SYyS3}Amj3T40*i!RJQebXo2L@>NZL1F4wn%&X3{z zC`=~xwQ!v8z*m#)@5JwuJdh9LmX){zJyJ(g!PVa$heJNCzPN7mU6Q_T;Ci6paDB=D zH+?<8d9Lx{Jg+HyIDa)<8`c9YF7k~jadAE9zbxH9To2l?U*x`&t?!##()Dj@#Qf9g zad|sk-moC{FR@QYUP|gT0NZKqb9ZmH{03;h*oxaj`==I;^Q&Hw=;XXmNAHoz{6HOu zV_z&B@4r~M2AvPI*1ra=LruERL))(#JdAW)Aoa3t_h`2FOiVtJeqI@UVSY=;q;)>= z37H?BhpW6S(dQnMIO{xI?u~{o?QDFpdfSvQ?uYSs_q2?QdOO!7y?>TCOE2?V^eceYbrNwyw0%Myh?`g^y&i}gAsq5~U#^ro zta|V`+`eJl=DJCK7#DFZ!m0gymCO%)&aFrDvQOe>N=Fy*TRIwqQ*~TDJNZpU=2uuh zy#%Dm$+D; z`Fx3X{-wBKqJz&X$l=WamqVSeR} zXx+F$;xIogF8k->@h`WA`55LtCvlkHIOq2niNpLn-{&K7Uz9kE+m$C@?vgk)?w2ER z-;g+rJIZle5~s%fb|mfx5{GdsuOz+Sl{k!>xex9O^ZB~{RN^qdHs|*viNpLn-vg1j zYWO`ip6?;ahxzqwO#b~=;?(>eo8JB@uWQ=*KetJe2hU5sF6niQN9Ok@i9@}0isK%W zIMkcDU;Z5C^E#f9ILxo(RaB3^N*w0r`L=(BI3KCvo{!{vN#Za+ANP|R2IIC^$G;_? zn%~F6d|ExYulRbI&+lW|__{Wg{m17MJzsyA&*RpNtjC8V`EH2BttaDR-Fjb5eYLj4 zVLddTSs&lm!hgGsvhj5;q&$dVa?3d@`v~LKHjBgI{b6IJ;P`zls3SH%_Lu8hCqI#|YYXY0cHbQH@lUnBa9^qBAMetz&LhaLvPBUaXyy`r~3S~%nyBT(s=iz#Hl{F!#LDiJV$O< z`TeopzrTg~Jnq>r4&(ATtDlGYejm6`2KmM>Hl7#ym&^}+p4@@@`8kPGeO^Dj?y|n- zozwe10&D*E@0jGP_SMT}eyF!inQ9(d2bWL)&6xhu`LqQt4bd^C(h9kKPzz24Bk|L?x{&sqNZ3p2GoBRLQ7awo`0cU*Xy~9n5d_OI94?`F#rfxBGhddS)WM&-6SMipKn+&4&^8h1a5!?=ZgNXJ_x4*9SioG;%;#(yJj;L{1e)mQzL2lgrRx_6sbU$oc#Kr2h@?&4r{1~vx&*XcwSNUMYucylVP)CE_)998;T&xbR zn|7c6DDiVY^L_eQx6&PPbt}9z!KuD{Q0hRv7?<5r`Q9Do8>W2RnG$FDH+HA&XYDwp z_=PxMI^Sma@-dko`qD?^-A5$O(qZ~X0A6oa{JHA)z4Lf?o{Wq670Zb}caFqa`Hkvp5e5B(da@$N$sm(@S*{Wf5?~I-s$HZ zJzq=eK)pkhkNc{`#p=a+__zzE$EU7C^TT{T?k6P<^?Drrl3(S6Rec_qPyKw8%kO0ip%%C_K@!y4t=KK&V5$;g8f&hkPn}h zIP5FWN55!&s^!Q1r)^jJDGy%9wf!~BgZl;Jb}o?h)$S{;0Z#3M$og`AT(`mRBza(d zd>)DQYV*y#UFxvr8^_mtsRCcD-eJ05-qO(<`Tof+dhZ?bO+bFDtG9fR^iS)99>8Vw zg?;Cr+Wt7|<@Z$PHkR-EVjj0`9BBJzmy(KAUvj5ph00`bAq05LZ~`gH_jY z%x@Lg%3rm9E*v83t6i_f>$+-vDKO99(Sy_HFW1d_AIdO44@bP*&tBhs+3J>u=h~QW zy8fXrV_)AX_5Q0qh^x&bWb&TGeoQGE9 z{v_LVze(b=;`R=t$Hn~e^!x(L=KEv$Z+CvS>w|-TPxr<1{Vtnc9%uDIZE+G;_4#YF z6L-vt`;lhQY2&){a5n!cYZ&Jp z=VZ%|b*cWnHq6K4-5bL=tXuDGhA(?(hn5by*%FiFx)R5cW@-%pjiz!;bFaYtpV8~WTk zvUBQjckP|&>n`RuL^#fe`S@@5lkogNzWTdleLL~UvE z9Im@LI&bOj4CBye=4W5{J`@e7J}=apG4AK%*3&`KW!0B;;C$oH-B+@$FO`$B&2!b4 zW!Zcg&KTG7C4X}Idf?oW~r`xN==k$u4Vsy=U%EiUt6zhHih z*SzMzisQX{|jX3MXK_;CHhxSSvR$JfvKb2lO5V*lk% zN%D4ol{l-fm>=uQpSw%Kd>;2;cpcaD#@5Zkjgo%!+2_}mI?z8YKlBB0y{8)evV)9k z)uW&IR2|PtzE~aTU!I<~k(~Um(@buzZ{Wm~yv0pSD*axi7y(sg;zUn!H)|VF~Zc4vwMs<7Ez;WP@ zhjFN5?89--i&rTRRc|R<+|rqee)O4TxSPX#9{1lc4)yXl>_7h8-I9%Ol60uP+!p5Z zabLE!cwYwg3+mweY1I3SUK>77*xyV2=VaU|{l^IohIL?ml`YbbkC@Kgk&UnR?(}}a zxct4tIM03DwZeLlkH;Y&;)-V_`C%U*u1Ywy?>CeAVIOcl?n`0+JZ{%;9}G}F?iDgF z_5tc(esvx_oNfQ5e0H3F92b4&&)tv0zMzg4#l?Ccj`^)VU>y2_d|k`p^p+GH$8lT8 zx?#VJ(s;MI#KqPZeMTLHbJFLf&u?8B7xU|-@opW7i_OpSd6@Vu9c@Ji>SbNn2mHBv zjnsj9J#P2#ysVv@`0BQne3ma`!|CfT>KG$_?0cWzKsdk70_~TqpDjP;x9V0uFK&Je z5Kh&xt;`SWF+t;9LE_M7&fDcB4*Ae$9*6x>u2X$Cl6)8!`ARp&oxdubPyCd?l=qr$ zmn|-yM_2F1qlwp`Ka?@zn9bVJ(6v|sSbLX4}B@WNBY9oL%ZlX<29BiaOwM;Tk&(x z<^PpVNahFsL_Vw=^LZV=4g2D8o#E|_6<51%+5){AuCRmbQ|rBqr^7Pj0a^}dld zfpFu$K$J~qxxjJj`2txJ`egu zeU1v|@8sWiO7)NV`1zyKrHP-GFPhJTG@g0K4oi<)xJ=fqxHuh$_2B0#to*dN6^P3^ zIA8bU)vK?jBY(Nn%Y9|((Dv8L^!^ggoA0MF`ILFYJp41ZueAJ_hx@9J^vCAMjKl`|^56AVm z-6C>u~jNT2r($MyMjM&jNUiJKRR zJ1`P=P$cfqFb?ZhZ6?0r^OxS2#bG{=dwaOAFz(O-8JFKT;`xq@jQfsATz43U`Q@HU z_9yZD0pbdi$#b&opZ4B7e$Qw1ifzU9F686)Fpr%Z#+6!e=firBOnm11{`r10@AGiB z`?Qdc-@oDczL$*;pG)BU&==;n>d~b4NvrQk_(3>7j^pl)#EnGaeiX)Odig#c%NNFR zJuJQ{?{E5fI6v>pFTyx2u2na@U)0CrUmgg@WtjVQB<{D7xCg^H)QdW%`273T<7+&V ztT$fo!`b+F9M*$BcaLV{L%rOmp6?go?KJv_`)k_sILy!c2Yn~Wx;$L zUQIsE+Z`YNUPjc>c|+oprK68$h}NZ%khgc)UAC=7&1a zKOSe*cZA|v`At~)y(^qw`NP!rM@yXLb7fhwZmad}k$mV&i{qXkaTu5Va>s>nn$Ony zQu;_-KX(yM)q9G}5A_bxcz2S-q2B7bv_0$%<52GajkEft&~Nnf8QJ1;eJr2*DXx{@ zu$A9AGC%Y=|557avm_3EM*m`U)QI2G!F(2Oi1@ItrkkJpSX@6B35RhxZ}%SQANpLU z@$N#2i}l&^WyH#_PsYXkI&PvqxI*Hr{P_Ei_`Cq0-a0Wv-tW5r}py)q<`r182fOY z#92Pa>R_Cuqk3~v4^_vfWqzmw{o}Zn&m$Dq%5TET@5ABz$^+DIH%Of2bG2d2qdO%Z z`qJXKw@VzxWxrg17&l#?OP@;gTRwLYPVIw_%luF;=7;Y))XqQG2WfwhjL_!!5Pa`p z^WW+3fowi3&qMKbUCfWq4`HABdVDkdzABIVP8f%A`FuOZMcn8=<@tMSJ8d0rl{(Y= z!0UK@w)0JxAHO$rkm9&F=5F`MoI{pZm12u2nMfQ6lKG&+mXRpT{kdIGjiP z-sRr!xRuvqw4W2C&mAK9aDBnP;yh3X;(Bf~`sJx?eLs4HQI8|SIyi4P5sn+{AL<>s zAz6oTo%C@h!*P+X@tJhJh{OGy*!ws5{UtuXBpH1{~9LDkA zZmn>AF>dFev3mC;?51@PzUqleB;mEC#J`zZl`Yz^ZB@+iNu{8 zuAArkd?eppk+?60aZ`MT^ZeR&zkIvwD-Bnn_x`dzzTb@hcDqIT@{O<#&-d*xZi-$S zsP@%;VLl)CN0GRnMB;uHi90>gztJ#XW?z1pkq`Q+>rcsjo4s$PK6-zoj^C_aT=jVR zPT9|08>HV)-3PepM(Ma-dfylK2jlo}HnAI0KRo_hXT-_C=|Kx6_Ez;(8rVtX{vc4vael`Ni(vGoR0| zJv;eT?~(rTemm+I0UYmVBhK{s&)Ia0&rR~f{auVZdXJoMd>=RBwEQOar1j);+4`?* zza&4t&yDXh!nnCFOP~3<7{qD$`97$H^YgehbK-tZYaVHFF~0`rsO_+G>hmO%fE(X5 zeSaf1F6*+k`-QJ0KI3tGcXxG3Wzqb(`*$C5_>%cu-3t$2Jb%&R?zsmnnZKy}pal!} zrvRw8LVVbN|KnS9)6)!yfWh?$;eeTP$zPO%tch5U?(W3eDmUJ&zd}#N)YPEaulKl@}uwQqj zySnJmC5L(*{^bLb5Bq>&tygRx>=(vW*N(%r4cz|(C(Qlx(&stHZRFzOcB~V|Vchny za$fTK%yHdU;`|#j;xb=l-E8^sIP81=eB9t;Tz$Q8T*l?skHZZ{;>sJu@r^~|dN+*Y z%WV{g>&(aDMhzVHm7AZw4zbVu8;9c}-{{xF^J8R_FdxTtUyJMK+NI=7F*xgEne ztjFMi;eIad6z1c4)aJzD+&AL0MqD5C>>bJ18HekS#JMNJ&pEJv?uBgEqb8O2 z$F8_uw&EQl*8j5LR&Whmb=F-g-d{3IKUMyhh3l~oWyj}TnWyuH?N;uu4mP(;J^sMs zibj1-I*thWd5tl8{x6H(SpQapiuPsQIA2&7`_l2@#Fy6f>AsZdJ*Rj)lSOYP9mj@` z_c?F3aab?oMqGHl;d;g6@OTh$T|Y?Q9u3lcG45kw9muD}jrDotPC6fPPdIKYALiHb zh4ky)EBIFY&+1d;%l|O(FB!f3|K}v<1^nNYZ0}LR`OAE~9#p!L^RvvK`$*FFjVpHu z&U5R&8|LHnVC3zIF4S8iy;ffh5f0}Y$8opG`r`4vyN`UmMdGyMc(;D|ywBua)K}jO z^Pyg>2fy!ubxf`io|lYsCuWRG1F>$NZ)rBZfiEWd)p~qE@?kxiBUFz&Bu=YG`R+AV z_9N$uIP|&nrSy4;xWZ49^PQ@W7vu7CcZYEpmvvx05Lft-Tn~6Z5pm3C&7%tNY2T;L zeEhSrX8L`C{lLfT3+6W*iE9H+dmm%|$I=%Khx0A}+Bu?++z-RsOVrT^aW%a|k+?Cy zsqgFiiPWp&;5z&8&WT>s!FA>JdG!8-A8{SuN}oqO-hF>|`hI})TK(MdQ|XH}KREA_ z($77>$Lllt(gd8=f2~NI)~6UZ_cN(i%dZ4DtzWt#ahP9hUrkUQdw)RN%cp0jUq(rX z)i32yW4-^+?Bv(`^Q3N8e*J_~w?`8)KisaiX}tTJ#97-*o)=broui2kHNVGYT+FYJ z#=AdCTx@>U_HvB)EgkL`hK^@teyF2Lq zFi1FczU8Ga=-(ubcN<6?`iJ@T{wm3j_3(WZh{Npy<9M9=XSRCqILp7@2eQ@8;>-U! zt{y{#<2+rvn0lPtNjR*V^3Gu)b6HXrQH+`7K=WH|f6cc(*~e_d-;O&+=u0 za2!W_&nNbuic@@He)lrzGtLi>dwC=-7sg@T#(yj4n{(;MTRso^Mca=pjY+i!RkM`-_*3$S50KZdzy zNWMz8`PTV6>C5W&RUhzGc1iDpA;78i_`S?e>z8Uf+0QYzzi|Ak@v-k* z-#p~&UKLr7E5p~Ba2|2o|NTs#=N%78Uo@Y40GEF{d9NVGEdx%i2l%JWj~4J*=aJaw z0jf9V_dh?9-$q~BRGz2VEV3S3gmDoA|k6~Z`xL^2h_n+`Q z^0v8#YMV)Z}0ORsFwXa?yby$33e>Cd$vT%N!k9&2t zxa~)hb(hEUx-rb3Z+d$Kxzta6ggzp2xd?h1ZQ~$E5)5pO44CypS#KSl;OS*TrqOI6VI} z{UadiKwoN)rO#iE<93~;{2n*rzCK&r;wufGcgx1d`YoSF6dmYuEMLbH>AoOeYhy$2 z8)il?=k4A&GkmCn`LR#=bGOI;-?*4x<4@`J@cHdEJNXsbM%=x##U0%wy$3WO z*vfC8Z285;?R?VkhyfE@@rCD%+JT&CA^=*xPecuA&ygUzbW^0qR%awo(|k! z!@lYwe$;`u2H|kOoprb)vgKF#3+eI%>E~7WpDi8zz^9#OEfCJq%W?Uqc0Wxo@u4s1 zU*}(?UOvCe{LbhDP*;8n@| zvifu!bWEw+yRyZ_x@q^duuh!k{JGmIV_X`Dd{~dJzbAFG)`MImu0c5T+3VO&>cI8h z)NWJKDjmEp8#92O% zZYSp@e{Uq~b6?5!d`j^-=^ww(1AW%&I|WCHSUy)NuH|!`aH`L5lm4O4BdqVO5@-2b z{>SS1;_I<-wz%kX$JOcA%a|X1=Fid|WrR|DMRU4s}v~Rz3O%r`Dq)ea3o>u@47IoK+7^FZxn?o%F9>ogn_ zIgVQp#$j9@hxI_*$iI?4uza2%oa*yIGC%aWOy?Ec+a(Tt=Dgi$VI1lh+As0h(!u=o z?{6*YfP9Rz{LB42&c71jRR0c@deJ}5$Gs!`J&FyA;|`I0s?WV)9QsnG^R}@*qkmq< zyR*gRama`HwO^F$TI}~xX~%D!|Ct`2bzEWj$KUg4>1AImKKEa#qjF5L4xxWVz^$%- zb>P$Dj;$~6k5c23VDx2lFIs1hnqFU_f9$I}H_Yd8?+oM6XM8Vvhw>hE=EwYyulZ6^ zUv+)?Yk1w@IBp|(9|f*MIY)Ks&Zd|7Egh?i5o-hu5uKqRsJ_^J!KkDVr z`DcTFS^hJ(^7rH^c8w4F-Ve`*pF{IF{$-ViRI{5R_V_{zyH)7y4UwC}!@5PlqXgDpuaw{&s;XlRUCfZ?KY<}I{$DOnEv}H@r z=wANY87Fj~aqL-Voq1k&@3OPHk2~|6GfqfWN#~~U!F|mW%6;qX8~S4Lm0y>f*W>Z- zz1jMz`5$AxeKS1YFu!tFIv?UVUsEpu5y#`*2f}(i?pxV(@HmW%I_jTEzpoT=qwA)x zyNH`4oVA`7)=S@haNh3QVZ9!Aao9i1uW(ZOI^_BGmG@7o>)$=${4j366?a(j;qiyh z@A_)<-Nr(~bv{J{Jgz^CekKHxq@ zKF$N{!JoVD%lvR2A>ZWj+17jOeu4hH^pE@A=lAJs^EcO%YAbP3Z~m1s zKaCIjC2Kt}ZYRaH`n2nm^!dj6-DPtAVtt2L-^CJV^=V&Zew+vPAL`AWp41I-Jl;Jc z`xNu@xG!eY!Q(J4<~Oo&(g#=%9`CM`ana|FO{kBqmN?Xbahp7j0%`A^X#tL(dqO^+ zum2@{{~G$@hkaP;K)tzFk>2Yi&eF^L*84X+?%d?Q&BC*Z4*uNzP4)}shrV=CzNi;* zo}Yfv>cKdRZqOJhUu*z31_bo8|p_7&rfF>VwN=epVk0 zoD+`g1|=WH?c=z&Nt_k8b*`}v{Ucjnu}@YXFwW}x;$}u4d?tKeet^ciyR-Si`B}$D z6T}~@mwB!A%Hr$kFnsx@)QkPnqVeu)5@+>G>7t}xSO@RF;QXDS_k&tGD!u8)Tgb=p z_<83t<*(r|ZqGUNob0GPUxL1H9Cxqu1#y#`(>(v4#996^ztva$TM$1D7=L~GaS!f? zY4^WyT=a!McR!UnP;cyeT(jU-#J1k!>hrr*=7&D>dsq2AB|NU(pS*Xq(3h;+*e}Do z8T*rK$mas5>xiLpfPf-WvSNuWx`Ijs{uX0I?ZJF{j_Px67Grmu!mwX<+Qf?pJ zP`GZWw|REldeC!kx-V1swl>zu4q0EUhd1h;unvz~Tk>JQV1C8*5*@fdRC*2d%gZGn z=7)ToN0Z)Hpgku%Nc{YKo`z#S%#S~Jt*|dzez^X5zHduD%Re56e6evgoV8!l-X^J! zx}I(z>t^Z57mPmLM)FyGP@wlhs&(5i8(;0#xOwS*n66{GK68E1XXLAIn;w_PyH{q@ z%j2xL6IR?!WL)fn@^(qyZexkF>Z|29kf;5eOTy==(Z43;f&GHG{tME#mx#-4pI#5d z^<9|ou^v9}$bY+^g}0X;HyVliWhAaUj6)r`AC}*3r%cxek*~5t;ve>(*Zcd`%a5P` z@O;N+cqFd*wq&V1vM-?x}IzDIG2UJ5X@ ztGo|X!&&PP=gU8}{k7iLC-vp$=!fZV9_KzC?q`qtY#grketEtK`;`f)3MJHPkD?xkm(bY^$&*(aWJ!kH^_)9PWJj~Koz zeH~)GZjWroZ^cqlH(WQmyAPZft z%oX3;x8moX%m3>;DtT`n|Mc)rOz(K6@4RhS9=FwBkk?l+?#Qu8T>goAYnRLV_WUS0 zp2@u-sT1-Q-nP}sxcn3OSQqwHclWW&mYucqxO0}B*nPr^``V8`cG-z1bf33$S4`d--7G8-n}>Up{AL{O%Rs*FCTM$hphEE_}iKdEI-J_S|!y?gI{AIB#+H z{H`S{xmM(oj$3k6b-u)5T-^WjeQ@CNFA1O5)z!V<`~w#(>|Qwckok+NbLY+PK4SUT zpf5OdA?ruJ${XeOh@bQCX1@8$8~uN5^A26OWbT56^A~A+?h0AA_O;1zyyyEL*TMVm zcX0Qii@KL*z5DLW=W#Ob6s*Usn3a`9hb~-j^xP%ObuOQ()$06(iT{QW%llD>EVr(E{{<_)jD5io^C>~}kMo|=SAuW(x4L)D?WQlNpS%3~ z=@%^Tjzg-;Cnxfa?V+qg%(wh|?Yrmgv(Jj}qfff!$a%}ZkG^}wd|zRr*RcY(cwYCy z<=+}VZ~o%Nhb~&&edxl2)jlZhnZ(8IAnS9V39knp_j!rK^K~BghVVM+aeGAKu8?uH z?V#H$%!l>(QSrF7sJ&8+)hsftH_jon(~wR{J{1 zcf|S9Sb)dT~|0G0BJhGV&(sm;2=XG}tehbv!BKt~TFaBp>Q%zL|79 zC2_HFxo-SE=~%t7IIg>UR_2E~G(POpu6;@G-z8tHUbSDIn_<3xNKn??uUnI`VHN9sicN>FUt>K&{&W^0*Q68{+)jIxF}0xgTTmv(|C+;q>xDpS|Av^!Tj$7WRwNTOpjPcjMW~Z#Xi)wvu1#$8>+_t7a#^+Ppab zxQhtz8KlB;66^Z}folxL)r= z;r$$sdpL~4xbE=u_uzWI|C4;Nb+ddKJ}_PHl>8_Wi!WbE=kq!q4eO}Uc=w3J%~W3v zS^52OcH$Nn7`{9%<6?d5G~PWXak0MO{Kfi?5WiL52}{Q<+17)hcO`vq#qD{!;oqNT z$Cq)6Yvq?aC_O*)dHA?Ey-bFd!6?PG^iEp&t(`5u+;i#AWubq)8Q-&G z>A>qV6Z4AVIMJ<_O$XPsC>p>rlcN<7tY#&(pjam7ERX0sEw=g@RthW<^*ADd4vuC-klr?^(Xt|m`k?lS z^yf%%ziHsl$$nF8+$^}5daw@8gZ&#J9mAv}OWYOrELs0s!MEanR==E-z}&=BiBD^; z;TkJHYV5Fbf3v!0@;%k81Mj~r-;~s2=&CJO;&FW`JfA)OXnu}_5DWTCazBUfZEB8zl!oR;*Q^v@C_Td;;WN>Y1}G( z!MOc=Kc~T0pzqBo+#>l+1hq!*s$A7zK#`83gU+-tq z^XpUMHr`9~GNXU}9ddt-b@2K;_#b(mphfHR#P!Mg?Df{e-?v!#d6M72ZE}9#d>h@E z^0`CqZy>IN-}_;#S6TW#X1?X`rTsl)-H6>@_SI>A5G_LMDpRh)Zz{uNBwxgw(>j}H}reM{md|TOL(4p+-|a; zt@AWFx;}&31*}_tjrvj3u~W9VoG!NIhsd~?pF58F_aKRj%@2J+|Ek2V=6Bfa#O>K5Ss%2x`N>m6ZVeBAvd4*Rch0{J{o;;{cb z-)FPEUo^jWxDQ-+I4=6kd06X4<;3)L1NnLhhdy&0cf8CG{Trt7?pTRK|Ni%W^rdGk zUDkcVdB>i0((*5oIJx`mr5Bvoz3kZIPCIdBNX(D(u=Fy{S`Qeq z^`bA+)^T!N-HL?6{F?jF{5Vc)H)ZfIX)Jw09OKwo-KN$T!SlQ`_tDSF?M9(M|kgjnyt zsuN%AdWAUl%k3-sz|=tl`Mn>bOA|j(N9U=@=eQmqj`OhUR(@-oe`6FE^1BSa55|cf_40W4P`3TV+!^VMNlapLi=7LMz2ZwcctE|0_f_;a@`+*ckqH(T7?QOR)t#>M=Gm!(((vMRx?$9~3&Jm&Z{&772tX-esykd3merG4;f%%Qm=eWLb9Jfr? z4c9e~n=f&=4q;p#XYIE$&eA(_?#%W<$9d^|oR7Om>P26AXuP{X;$nTV^l~1!Jwl&b zmX7y^^W!*fK_spoiMvGN&_5sd5Q#(o2J1Ax8etszGD_@*BG#eg0y8%_Gv!qa%*s(o;I*k_+#GmM*Vev=t&%FmB^LMqhnodOCRjAV>V1x4R}AU*{){$o_*ZivfgJa22oE#948H;l_V zaQ}}#ccas*hm~LHl5}5u-0S7_nVFiu%x~p4YUOv+^zuWWu^#!k>E{_ZZ}-*d#kKS@ zKjQdv_sMWvkNZX#hkAJ&#zkCpzjR*^SGz2|uV(r_H_qFAE37y6J~!qo?IZ8=#lGkJ z4jc73;yPmEBXmD-UveKg`cit)I8XhZuny$oe6eo)dHzy)e=_PozS5OR-9|1ctklKh z5!Z1=dVM*r`|ix@Xk^qeN;>M7COUXL>gX%QZTGu~54T6GcOqkc{e6jl#mkcXcs%CE z{8(SaO&a;tE(`Yo$8q;%t6S}=L`UiJLO@E9 z6^RZU@4g=Ph2y#(hjAEp;=s7$1?ES+Q}{^7=nctxyUUj+bw`{doYv3or(qpEl_YQX z%`k3CToPjG=(#4T$HbLMJ%$t=qpt`brxdOT_dVuUx;BYB(3iyJ@rdicXJ+fxBE4EY zni+LWl8(Wv5*;|+JuowMR6;L)qeXY-G%jKV;)${jq(3da)j@ zX40p~$8p?vw*1D459f#H`(>EV;~ov;P{-)PncXgoelYO`bzof17yXOH@p$*GZ08v& zA4<>9^NnTmuU1X`n<>5d>y7*_4bQjC{ymvZZ=aRl!`b+%ho$@H>rvcL9IxW>pvOIx zEiR9X?LTWh7`VZx+g;)OI3IU%_`Imc-5ut`KIq-S$nU}(qkL{g;tChV@wxLO^$tYh z`e%54d@dXpedhXD{WAICq#m*TXW=RzG3xtC>C2SsA2i;5T;g!Pq29(}#&-Gx+4$H$ zOK)etq4$e2F6u=cv2huP_2tjqm&5(yaW{tZ^SGA5cWJVIy01t+t8RUZ)9a@Bf_f1* z^3n8u_By^B)`5Hz#E08e&v%p5i}mgKSdx$XsKi;mOkN(hKhz?A%nx;NzLtNvo6`M5 zz7pXuF2`}VNWJJwgT}j?B@TV@d_Rylk7q~6IPt6b{XART+)&b|T)*1m$$M9@zJni) zTi1qeNuQUMkC89G$d(`HW%kvrarLbdPWA7}Z267dl-|$PkCWb~vhl_0ZQm{HHhS;Q zE00gHZn%F?erQe+{G7jf94&%`0@(JnN4~|>fB+SP+SIgFa zwQq*wy5qupKJF25xZ=K%I+n!oxkZt<6XI}%x5eex_trRE&kkW+-}=tZcZG44Q)#>ML^y7&FNmw$ zkNd)_Zk_d%)s@)da;fX7j&gY!lIG@Nzcbu3@+ zz3J;8#w~3g*H;z#J}S+Z+8UAT%fDsa&_CAaz9xO1?r~`DF6yIy$+#9@{pWG_dl!ae zpSn58_Sft9j?{sAu^t2TUR*z(_z>4p-m8W<=E1(=&)t8+-_z=G|H;o8K9{fB&RF>YNYF7mBMxL)F`elgLH{&mp%pwT~G?Ep?IU%Vm7bNpQiZ{f4@y{p*wJl>ri_Id0ZG`|c!)Y11q`uz2AM`T>g5BYc;`ci*q zlHc%W!g`zckdAw0TKykadE$-_T-$@HI0w1K-Du zacd*#J|nJ4K4G77KCTtHKlDP_XV3TbaKCt5E<7*)hl}LeLe8` z?Gp9{`TD<}^ey(E=X)_5ACI$ijMDdGU|h^EPx~L(FC*tC{Z=sgl=E>rhIM${u&ghx z2OjsUaD6@Qzu~yWZ_>K)Eg9EZH^#3{-@iitI1g*xV4PLA3Cb7i#^c@V!+Je#tFT^= zdqbG7bwSbxWup(!m+DVeZ=Lk{?G?@s;|`9-t&{!R81wRuY;ieXs}Bahoy5iYhB_t* zhkby!%6H=UMwEJR-frW_^?AL>zWQw>?tY2G^#Jv9zLw9m;q>};(&z4nGOo2A#K!F- zeylH#cWZ`y*7V}K;rU*bjj#IMbYGfBC724OvX+?QvIJ3w*K7fr8K-}3j;b@=?A z%2wYV;=}xyuV8#Hl%_+gTg$lqrtw+6jU=FTGtqddiitr z7g=BIQ`B4eL7XrBgwymkU^|F$+ce&75cY+2G%g6A-^d-EX*6oN$~szh8>~t{Ll9lgDow?o*7*{QR@DX7Zj0{yTSZ*gwW~UJ}M(+|iN5 z7al*fPNgr5!I`*gJIDq3!j?EEqhx@{Dd0aIT*MC_yUxx2b ze5rRQ^N8c1-p(IM|J-hg4#edNSF9y`tPgQbIxevKw2%0jk8HEjH?9-%;rUan??A@- zvhQt*%j2iS{ju}~k(X9Z$+Wof7vaVLl)CvFRQ6 zSo4Va5yzjqABFQny%Xd!_Mhk5Uh?5~+T%tf4!0l8pHP2n8^(FQd&4-?!Q=RScs;x> z^FMqq8(-h%;q9B-E*sy_BMBdWe-x*s>A?CTuKuWz-%c_=tQ+!8{xqo%_Ce)mRJR=^ zAJ!N7Sf8b1nD{X+k9TusCvNA@)AjneJIlD}UmuNkMTxU~X*`x*H}r2X636*kJ~IxF z12ArJ)bQnXQZM>~d{yGZ{08WA_gcwk`Nukt594KLT)Zg+`89auNc&+5~jcKSTx@otZ7aVIHX%NORi zaQzP${&mXy(7!f~cY8@3`p5aWO~U8-r|a|Jlj%MqU+q_kUdtEG*TRhvpSoRmtMmo^ zEB-pk$L%X|=pX8c&96@UYJTO}i92D%-CxE1AerkBTA`7w^qH|2Lsd_o=d|4a9e$Gfd(C%?|) zlIu*Cj`FyX-^;`Kc^%t^ap((=v+`pc|J1%Wcihsk{p{wKRfluQ^&a$P@R9U-AZ~Ij zsW1C7S*_;Ytzwzxdb+8-KxBGHR+F~6Qi(zjb2$GvuT&UaS+WYps=;ePS?mBTpHTR1(v zPZ7ubmVf!Sp<};n`DtM)BQsn z^To!UDcp#XALrv1WUB{{v*xcmb7uRr_2+CpV}6{sdo-Kg;x%#Wct>xX-qEKL9h?u} z*Mj{r2{?XE9dUU7MrD`e{v5DB84^rcO4Id859|Lr~$-oAO<8^bt^%j2+55jXUgL@)ZnqdjdySGT3 zwH^!}ki;FkIQ>3VH#Zv}*OBkHEj^QdJUv=S|9)5=@8(S}uH|$8-@`taKedLq{}Fv| z(|9+3dim8hP3{w9oj89xpGoqwbkqo^&hrJ+%Masnp6;M9pT`{%#-ZNk4oM%VaSzSL z$9eRfNB4`ql-_>>&n7G&?^-6;|m>x(td*}wn&Oz+d7BNP8r z9cN50KWl$z`1vHRrK3$aoWI!5`F|QZdZ(v@{p0;{{@a}u=JU8^VI1nsyjp_Mf#hrX1y>6Vhd#8+x>n`do{5yRfRp@hfjO2@5pRK;)d=bZ=yLZh_ z+|C!%_4>Fq8Q1c!{X+V6mp+Q)x+Nd_=i_b??o*H3Cd`NR?f7q^m&fCC9Rr^YKQF}N z-1>3(bqK z7{4Wqn-Z4>TK<(@GJH8z>P24~G~O+hIP`^ev~LdUU|cm4H*j9~d!f*meA!r^-z{~Z z-d;z?5obyq>czOM%c{pP@vGa_vu7u6=Njqj73b~FlX1}(kJ~-G9`sQhcaG$<{42gJ z?)a?=I6eo{&N-ABT4k#Fqmaw&_B$t&EqIhwGY-v^jbRduaNV6 z`0DiQJy;L*J?fN~6}OY(s{Vak`hx!Tao#scoaLWZU;e!P#qjnL>oI2O_(Zn+2L71T z!}5>wMI3+b_Rluo2G&mEs`a>8>cDz*y`OI|8C`1TF3DD7MUOVjCu=e!F5>5uR(F#rzBt2dT8^!u-MqI zyES9nNdJ1*HT*ju-1po^?lzep`rM{C?$Z)y`lsmdaX&LNeAowl>lwb>F5{x!F&gg% zCC=1q&9`UP64#kbKE*%OTVLPMdzaLKdXcZ=K{=0j9U7rH?oP=!Q##5Ur0c-^T7=_1 z;&lyi8Q}TWg#4*2h9fEOuf7m#^mnD{u$Ga=C-6zB2to+&= z#r0|9PC1V{k6ArmYWcXh{eO(RuZs0reZ@GwZpwda^|1H`=)Nz@XO1&dxcV#8=Ml$o zrEJe_j}Tw%d_x^R?(X5Z9(PT)?{naBRy|rz#P!R_?Q!c%?oV-igBkC?xB9PZleqbz z`NE&O8^S(&TxVq6zCAnJOU?uP3g>0<&vEq_D5al|MLv$p_W|TyOuvrJIP3aR=ceiN z664kg7dzjqxI>X~$CS9N&s{OS`dZgRtFMmprA|2X#pieB^zs|JD7l|zP`OWLg5p~9 zlJl_Eq4H+w^OwiFzOW9D`&}4^ebss@ZhlO@FMa*195vUwVm8?fdJp=_uC{UpT&cK9K-ce)%noetv(p{Cr-< zyzHa6)AgC-xDQM(Kg*ZmmWD6QY;lX(LmdC4wEq7UYeqi$NG#|E^9UYZtfK?Kr*qTHBcteb2Y0m-Dc2x$P2P z7~gS!`gypXZPWeZaqe?rU$DM2eci7_I?VM2&O7pT2(ROgY&sg?U+wW?@H!LDqba^n zB39iB+o#t9`6ekp91BfmqsULNnh5Z2*w8%=Ls znsrn93U!Q;4$epImmTH2tnH9KFFXDr>oLCRF00jlb&6}%V}Nit-&mI`XY;uUI<)iN zEy7v(jeaA2KNjoJv6J*!i`xWT{;_19d%gQfz1DT1uIFXlwD+dqI@!85y$?7Kt4~XG z{e$t7^!=^q%OK>(&j%o`5y{t}>p0ji$TtdnQ+%E$eYUQbRnC+9VSN0-`dvphzLxcV z)-AK~)pnNs$M?DU{9cod5Br7hhx2^fX5;Jsr|eVi1J5@n8y}Ce`gDp8rBB^1iGR2r za2&UDw*0EZhkfe#4#>ubI{1Dw?0e?tw z#eXIJg7rWhb&PkVuYdXX$a${i$1>{Q-#Yzz?Q1jEmk7;%W`DJ~Zwl|f zpf7_Tj=R3lN4}uX?1MWvtk>gC592UD9+x{#KCjE4yEA5(@5~wIqeR#D2|Jft`Frv` z<^JQlv(=5qS@Xl~mOejty!(obYwd3oUQFgC_Cb~6xO*g@wO!>rPzQhR4x3&*@c7sB z4TbabxXDOdD~!|n8TD$o*!95T>!-R|IM#3B#!Kmag*r;Rr{g$|`=;~{`)`!SyRSG@*y0rO*A%&)v>Twk>ahxI_daRtZuxG||0`^w{%h3nC^7xmR| zB_H;c=X;0bQ{#RslJ6YJhjGyt&I9`oas83^*D)W~gFkoQ3G2YPJdW>cY5qG|uMs!# z-}Lce__pH1iExTpj97{`44H{v=z9(Nvz$75Xn-2EWzpU0gyy*^-{%Zks{ zeWZUC!#|woKEL|(^27DT^Zg_23)X|jvEGpv()(b7^kO}buly$I3%_rPoosPO6dhVzE5Dw%8NM7IzVDy)x%IN?;Bi)dvAA40 zT?hJ7ip0gnE$^M|zceqE@BhQNgGyYEU-)zP>Wq46prvDAUXmZj;pd+CZ`T#>mnk}k57!~YO+ef!_eboQ zQ7_cDc4PQDgyly`E#=>VO#uH!#y`{IOuNxf4{W9Et z$TvuQ*ax1kmd(H3gW~#N7;su2a31J0>cIKSeSo;mgX8k+r~ItGuK}OBy^O4Hp7_*y zJP@ug`^7&S{LAv6sq59r;rjaFzY51ipLrbCjX&?dJ==R{s)vO8zH~=6z5(LXd>%3Q zSV!&i;kb-*C&c+YTo1o*j`^zRhjCf!F>dg2T>o>G+YM6t>et!&Wqe_{zV4OT_Hzc- zOurAs=l`lOpU0gZt{eJ1d3D_OvQka-V*jnRJn#x@2X2(x51$YI(h;enC!3DJcf?)) z;B;`Fqc1~;$#qv?O*pR4uQ%KW9#;tS zp)Y-F$NAT`bX*zE594CLbZxLpYQL~9tQ+!`K9Ihh;qmUmZ267Q{;5@8cVv2fF+a}3 z(otR~t{zp2Yvos0^5cBm@51l>n68eFuJm=o$8E@Z;C&fgOA{a5rfZA)f34%j%8luL zpy{yu<9x06R^-n~^2O~Xk9Vhqb$Hx)VI1n{`)IcP64dMC?v?HRSG~&lE6?|$+~39e zR*p{k!@VGJSYOZgzKp)SF8%v<(7%DT68}_R{u|B@`8Z!|o_Ai5-Y>}4`Hu8?gt$J! zsr~mdxn00|jL~@KBo6C=abxusk4e|TJlDFG*X7clT-Nk_;{Sv2UF&+ay@iH@deklQA@`{sRR9M z9!Gt3u*6yZ#p)d=e(WpMG3e6kfjIO}d#*P&zsB)K|D7c7V?_TjzvhOC4(tQY$1RaQ zBcI2;GrYf6IDzW6Nb+IbMoFJLLFzyp>fk(32jYe)53DbbcSnTtLp~m7#U0!zyFz!esE>>^z@w_H)XvVn?{7<9UqSCamR)A#>Pe5B>9Pbia5?g)p3%{59`L` z-FqYTo*2fpmr@^`Amd_vV|8da>$tn`l=S(5e62;)XJkbCrA<@MPYw|u`iy++r-iGY znw}qzciYa4f1d9&$%lO~LHW2-B+jZ^^E9eA1)6eQ=;Uy}Oz{u4Tg->J$t_lIo+BUo zgnh-IyY2oTd*1=xMwPXF0|ZPLU9?3&0Edu7?lM(LFmaX;v?-v_tQ05Ck|NSDU3Ak; zTgVrr|M}uP&Pd~P-}9dL zoO|caozcjfF4#_02N}>$)z72z6!o&JJ3r*Z7K(PX4lKKKz2z;kx$``y7kIO{=vP%& z+4;_OrJFZu7hB+rXT|$~w|G;)PnBPKT$Nof3jse>9Zv^%ad_;ES z{msHX()qa`-4KULmq^^Xo@H@RJmkTSb}* zwC>xs;_|u91%CCE|o-QfiLHSWUwnW5}-N#LJL7gdHGr`NdPx?`B@#^|T zJyr4gmx}RXKc{i%;!%DX$@jaoO8lZ9_C#^IG+p4_KM-Gfd`lG8e^okDU1Z~*?`ZLO ziN}59%~IZUNgprfS9*Uo8SnG%tGd|Tuf^|lcl|88Wtw$#enTgSI%D3bU5wbF&eX1j*vaaJ)|G6$>Lz&7Iyg~`L&h&c>}33snszh}94DzR zt?N1Gm)dm^zp^-}UzvXXlSEx)`E4b3x_;v`N*(8QCELRB6ADwNvu+%Tr}gGdB`1sV z>c%0<8|9~KC({}GsdOBF%3J?UK)iGuM?dUL_i=;PUmEaK^V9e#qRy&#kq^!{@ICvx zw|KL}uXH@H9Pk(Dm&S``G#}J1{)}GzwMp#I54+YqUdyh_-H!6Zb~qoe2OiWeFp?jq zX}wT8b{fwwtpoJKlJ5Mn+d=<-(cLc3FE~);19_%{oB7G!DuycBX<~g*SeYXPx_bp5LJJIy&-ZRqlQ* zyLY_hqeJ4C@o)^G4%{lqu?OA8&r6=ji1P`Kj{T3wSiYG>){y4*jtA+;ygST`FB7;{A!L z>nZKa`FKF%wfG(2P3P>n&UI?xz3(kvdR!=xtcxN(jf3jf(c;XH+94jTQ{2zSc+-WQ zr&oWOa_73I{33v-sz2nb(xpp+hwa%1?s>E9#(LBR8mjmqK8-iN6U?6H4L1$cG*3G2T|a{35>8?<9|YHFZv3;H`g1`5o?!Uw4(WE~o>W>J1OuQGT=zQWrYM zi|yHw1LHSzk;3oM1LL2KWs$%?+`Wu|Kz%*c!^e7 zK1RCY;2(#uAii|nVtz-tTCoJ?O>M{Xp|;~XtL?acYCEor+K%g@w&Qhwx~48_JFbh` zj_abfJ87zmtj> zu=J$V_Us)a4_vgA0xi1LsKd^N#Zf4uz)-QGQ z5zxd7Yuf3KLo&Zqm%#PT=Udbc>Cy8P+|M=?pL3#GkHvO)eL4j^WPa)TB(+Ok%jX@G zAGPZOJ9<8dd|1NU`daf1&g;t5FJ0fo`lEJDqxthZkdO5Hn9%^Xvd`_Xm3+QN45g^LeWll98&RPH!ApD=55?SJym|2RerA! z!KSk zwTs@YsHT?KC8yxFy)9jzA{Z!7Sib#M8-!5bd7qj=PB z3i#6FAhu_>h<<6jzFQ&Qn?yTRyogW7d&;l#2)#Ou0S{HY=vQUe0eDhf?iAyty3jau z{mSeT?NFx=Xx8anB0t@HsC4Q1r=nlpBl@MfgxjHB?iTG-{CXjNnh&aT=q?zSKuFbd zB~kCZZKu1=)Ncfy6Gr)2xEi%(&AI(P;+Ox+*J5@f~CC?9|@%GHq8z<9}I4GX3 zet~=R>YyI%q;>GEs0-B(`6PD{zkh++wSgb@jfkhxIdiA;dQL;b*fC=o>PH<`*Dz`7 zgfR_c4m~6?YGPf(s0jx)Ogem2q@j#6)74Lj7jnl#9T*e8x5iv&Kl3#HT>@3c>z1kf zx#zgm<(Fr7uU>xJJH&Cfb7g7ndT&F+w8e`T&Y8Ysabv^r(-zKeSTcXfqQ;pG3mX?L znY*~50pn>HJAT~gG0`ZOder2}6UU97GP$nduyK>djUG3C+~ld;(y|*}H+I~Fh6$q% zshboTHKxu;%!J9K#!aZ3h={OV>3+T{#T$R%==oIJtT6sIs8y>b(^~=tO6?r?QfBYgJ_C){S(QzZusfgpLf$`fb@k{w({HlD^ zKjIump?GcmjF;_aywIcl8*fWL<8}8lUg=|c@kSqZ9uIWuz?#-fnPklQYHJ(DA39+y z|8Gov-I#;19w}Z@lVAK|KF?9jU(k=L?!%Ak=_13!{jAAbKW{D4FV(N)iQ?j*c+q~w zYwu^gUJ0I+j}N`&1KX+UCH|zd&e)!PG%$X%D!-Y5@f&+e5%0(Del1-BTjlkh#g?nmo1{jBqOJho@6yz$GB=OU_}H>c`v(U+a|qj4Z#6<)gp z58JcV-r~h}D!<{ooyRq7&zQIG-NbgP>-N1bDDpeV-7orK*SlXIEHodXSDo`~`CZGM zU!i_GRDRbU7{8^jImb)mh~A^9mvsh)UzdcRm5;&wxc!!nVm}K7KvZbw!#sp9azug5P8c2a)-5$lxlYlZgg zd(loc&%roU`eju7ei#_P(GQ&a5%Oj~iGHar?a-e6DB7uX>G^^m7o_?4*&816Rq0&+ zFGaln75&n9+n_z`741~<>hjB~`28|4eq;Yu=<=KBm+I01?b)xQU4QAqK6K_s$5UOM zBNDvqhy1*RZBp2{tE#^)iC^T+d;{Y*{E@SMmfy`qzcjzC(4K83+R^-4crD)QpyeaQ z`QR4rehaOGXhxySR-#|3OFOh@TZ(p6mqPjVs`%|SFn;47D|GRTeyJ{b@sf3A*?k$= zU!9K&d3aE0s{R)GL=ngK?s2q0d$yfu*I)U?{-TP5tx&|Vv&c`G4{%(6w)lO9GM!cP zu;%p?{5}xpf4cgq{Q6gNzbgI0U?-h#?BT9oE3{|3iFW-JNAMHp@vqQ)1V7c&B?@*@ zU51PC(zF(o3+Y7KR3`Ax3`*Z+5RU9nq90!dTb)n-1?q}Z>7O#q5_xsNM z*Yf+hH^1R8c)ZxYWB4A9-|I&23&Q(fWV+Be5T6Zlzu!WJXSIjVK~lSxF7dt**?n^~ zj&{lS^7!F%Z8Q$*H~6KudQssqIA6th@%|U;H=*m7%!m9hIDd{W0@pQE`~qJ&$BTSf zM*JKf9mg%Z4czM>4u05&A|4&@+r~ow|Ii(e>KA>}xgSwGGmRJ9sdS0Hq*!(s z@fOdAROg*H5$^Y)`L+D^x*y+KUV-Dlmzr^WR#<;i)xE{ndcpgp^%hv>`&0` z`=iW`>KytG`U^D0<3}G7e-*avu=}NW^mys}Z>f+cgpuLl-*KD37sl4^*S0(NGGW`{ zX!jq@{ALF>zu3>?J)-XHSj~EdI0LG9e{_#GFK>WH>(u5Z_cCGI;i&Vj?r}6UOkXl* z?&3M~8)h^e8*iA`IB!wo;)eMPrq7>g{BP{D;oDy-{i3n0J2>)F*y-vbvqN~*=MrS& zc*&#U^GoQsww>|hg+Xf%V)2i8zgkUx&_CrD{lR&>N4)y4-0={X{pwy>NyMXdig=Od^zd4~(6jR$+rM^+<$8F5FZJyF&+FNBDC}rGxBM*5 z$HRN^^D@-AzDv(98={xD^v8O5O`qu5u@#zj>*(=oQ{YkkP^Z2vnP1)N?w8{Ayy?7t zVBv4zj)!)=pK9u|u^wLQXYP13j#4<^myJWrr{_1C_2!q3&n(NwXUdP-MZOTnakjm9 zesz-TU?h{*0a?R zU+{4)0e)CW#G}V)8V91N@GEn>%ghiJYK}bbtLMy7x>a~h}y*gPnC}l6US#< z=SLo_+FKo9JC!cJcSXN=K278B0Y6o|F|ecYA|JNDm|t2i9jL>8qFteNVENtGn||?e z&d+nBxK^e``9M3$kLr?@_{H{YmZ%HWIkW-vkC~z! z)eqNCljkkWt)He~Yx#i}lpp?G6-Ni~kk(6+J3n2&$cN1p@u)754MCT`igr{NUBA>W z3HZ`@=MRiu|3=PrYU#32^h!;$E06S@Z zn?-(9=QOluOGP_fomKn-n<(la=ITss-JID=)Wh6cKxMa z4DhA-EqC{eIvu9Z7l= zSw2d)5_OUJjSxF&K1dy4f1~+L5(v0VLzpHh5Ol_?)kOs;02B&=3B@6 zRRWrLySv*_olCY6^DDbQJ4ozs9i8GOBz9K3r+Pcj)6H+1_?5-cOYGVu*Bb+VQ5TsV z<%jiR#arqvA1UION$xYJe#2KguXAMyo-A*^ZN+$HcGRzI+-Toj#FNF*cC>h$PF1^) z<8;1Z>3py^ov|J5zqFpwj{42B+m6Re=Ox&ljW3L!%5SsE?}UNz+oSS(=)m~(uMq1> z_Pyp!+bi-Bapz~{?Jw?jd368{Re1~Upy1ayFn-%rerLP;wRC|O{8+``*pFL<>QcX> zLYF!2{0jA(Qu#f0VEl&uq=!#Cx1KzlnXFuY*~2y2u^RvV#}) z`st5)_6HR4E^+5)=VRxp8edvfevkL&H*$bN=M%i)VJxaRqB|?}J85A2rd57V85qCy zyC~v4ZD9PSRDMtQ=C@;vqF&DQhNoLEExRi8J8NM4vLOn;XAg|uW|iM_2F7oX%I~=Y zh4a1nO_TF2+4*W<53V1^C$ozlb%~zQ&-FKk zx=cy;p@UPj`$!&@BjLq)%`I8tAVcCm{j>&j&QQldE? z$gVH=7Hi&5Nc_si=V(xjL*_Rzh1Wej4$?Yp2Ru4&qIMm3>fvF3QLUo~%6J?qe)V9d z;uriz)J1lEL6=`jlV50>^Y}vb%WB4f{8YNc%6Yt07i`a-TSvIQPw!K(?5fsxwWD#+ z@t|pi^LT*xsyIq36mitJ^Fu%EP;)wT6R<2?WoSZuQ}J1g*VC@9=4
^;h7T(zUwuX^`O z>TDc0VW~&i80qhAx4C!foP73;g1ODgLGqs9-{=9sSjgX!n z3iV9?T~9B1sDJr%cJ=QkqaJlEoFnRafscfot?TvYn#V1i2_dI#-lneRRaWW6-9CQD zJWcg*(lPgae?6OL`On)x&yl_S+okq(l+MROJttV)BYA($^dAPh?qWHio;7eOJ^MZ? z7PrFnA;mTHa?k5g>jKjA6QQ2vNA&cvhxzN-5SCBrI+o>w>Zx=Kt7p4P?M%OXX7%&u zdZHe!D&#~xLU_a0BhFb^%bzo??!$g2jC=hIyFNh>X}_cZ$G&Y zongzDd%ypa>uDRmw|+?VXkOvCqjRA??x-B;uV-u2f82rcY2%EXK%B9VoarC@-*6@s z=OQ6FCkDl7S$9!X>%rC+&d>ApVCAFy^&IqiuqTA|ov*LsKI#wb#DLc)KPlwwuyxej z2OsR{y;T0;bBlT;ZI_-Aa+V5uoVm|A62kA9^7RJ%dW3YJ7jljqqjPc}>A_~zcQ@d3 z3q2<`)vq5W&MRl>reN=XmN(PWYcp=n;RyRn(sjT86zVy4tga{bIcG+=E=YRc@Ks^E z#J`Wgea<;9{5}GIznm%VuL(I5$Lo5wj?;b48F@lh-);A0knYRExEFt@b8#Q(!A=O{ z&fnW+()0C@dUAci2U`<BFZ@X7 z`!iu}yJ*OUM~JQP;D<$^rObtHQWTukRgU-19}9 zll$OgoFBfY-eN2X`&UK!^nAvrmBpHKaf5pvqru^`rw7(D(9;U^&FW_=UqCT_)?6U z^A&ca`$T*@{GfV%7E({HFY=e#pn4_)>IsgpdZK)Slb0XUc+=^3B@rst&A=;=9B$2#iC#dIE|+g4m-zaT#NSa*SZYHB@8VbXgY zV0>rV9+Y!U;CnA7?2bBgyjsZr^;|6A!kGBSi6&Sgb!|RTZXt}KdGLH7{&eT0Xgfx zCeHlX{&5#`E~mH4{Q6!~>n@_gcAl@hh$&v^!>xGTg=L)p^!!FZJ;4)J&#>h)CFG2j zDbDG4$&UWUKkf}xu5e!5O3NpX`({8+90zXr+>S2d-F{*}DQ9F+N@vr6oVnkUj^j#S zhPR)wrD@#ysj&Zqv@=fruvB;<7dz__@N1eJ}w zDGRehfxFz%Uih_`Ctl*V1knGVPa*}`)2dL*6y+)v0ksdSw9Bk2hr+}w^E z=E1O^H161cDBh)i>9&we8 zrngkj_8Rn@-Ooen*<{?{gSC}U%qMd_P4me+Qu(ybd-L{~`{0vWsh))t)%Vjw>KVU8 zF9)2@Rz9Vi*-eP^S3=Gxd#_Q$!r9th_MDWoo!_}vkL>gFg^zXpxX<;h8~RK9`fh8N z#;+wk&km_)>@uC3a}G++jym660_qu6>jCQ)PLrNEA8Gl_uTOdwgnD*v)35KNm;37( zvApjBoVM}_J$DVLC-exbCoiAU^`Gww*W1jr{*$c-1wZVVa9yRX9!;ut>9@kT^L8nB zrGMO|^@v|DO#S&$VcdEDo%_%c*3_Tpakp`%)VSclpqzgu9cya*0WNM$oY)Wb$QJje zihDU^+_Sa+o47;I?*-LU2@+OM9(S9b&W6-}{!pkVAIDWy{1HcPrQX}jN zz0=oHyy0^`_+yKc4)D1}`IN3x{g1Hy)>te!#3XKEwT^F*PZ{JTu08~o!g z{Z5lD?kN@b^Mss;d-^1rPaYZf=ak0X##v62o)-u?3zzHVvu)ul3(KdCv#IVMog(DK z{Uemmu^avMl-@tGaU#E`h3^x{?Wo@;kM5xRNDnr8jQ4yU>JjFbr0W&ea_hU~J2)SxcB<`_+LoJ%Hs5U z-#?quM?U$F$RGKHEY1tIsMgOT?$UPY$3i_DiZfOxUiiqL+r(CM9pT&I2jv_Qa`N@b z+(-VfBLiBeiu6tua&rB+kMv+odZK(v^(@>$arsF=&e7W`?sXM^aB*wm#C}0J#{zO9 zpRk+iCC?*7?;stKo~d2H?=}lgK2K}nJVwYl&N$nv>GR7rF8;eT z?l|sPVcc_nB|QtvQ~L=Y>2RBzKA3i?snR(ujGu$sfk0_c>?$1R1Bae9jq?lXG*%kn_h~}TuHUadXbX ziL$s$ubcCR3bj-7IMZP(e>m$=bRMkDUEwf$XRUY_hA~0n{(z*@sE3N zxZ@rqU6;N{ciiF3SH$~Rcz*Et_aC{B{kX-t^kP|Gzm0L6^gH!0_7b+QQ;j{Q$DR9} zFMra2#+!FjTuv8`H*>2{yEOU_;;l1o&KcXk37)W=7#D+6T94in zt_$MteT+V?mjm#_7NqNfEbnJPdKU`ybS~7#TaAuCXF|RA1Np#0&$-B>*xrtm$=i>g9tVDkz?zZoD)b66|#YF-2%j zncnyLls{+s{K2%JC?{tN%V$+_O+HP0@R1I;liLV6E$vd}ZA#~EVcdDUlu^8#4}SUI z{?Err>k-oXbwE9FTv$EPeo8sh+mfEY3CKC|EXBR@jDPu*#@+V*kjeF^{cH;39(iBC z9;Fp8^yRkm>0sgxJ<9?01W#B!5qCG+Ud~7l)-*rgZI&eKm&(uSapwNmpX2I_#45)Q zeWAE?Gxd*?_jvb{ZP(4>0u=Xqg>fHe&z+^(IydxyZSEyo|7q)gCN?0>N2Hva>0BKP zr}+7IOZ$oQzCu_&bL-IeKt`7&TY6sSMtZRAg0P*p^h1!|?}eNr|0J&R-qc@$k94@r zZ71WjwM)$D_m{2rww2GCI^S~w>Y03zbRB!aKkiaJrJUym zK7YZ-9b+$2`ME|I_mP+NxVMz9;O4geV`1Da^*wzoab7Ld6ZJjz z8pXT#l7HN#_1#vFO8ZegdQzxohrQ1#@v=W>$MT(J#NAdt6NeG!GeXYf4mwxU!WqAR zFmcCt^K~I7?uOxR8^-hbL~CXBhN#^H0Kh1U<*qd`;N-5a=!~ zpQX1+&o_m7R-V_}rTnY@agUrbnDU8s=^CM)XqTWz*mfysJD+@o+RvMWdbU|RUsvrY zxVarURi>xydQ?@MHw!sO|E-UYMql@j``Caui}TaG^esZpu~+o+8MVAWxh3SZweyJ6 zdcyLFb<<7td`H;#JR{%U{Acf-iP%EcG>+TC{W;~tt?xO>y{X5U`+9D65AD+EqbXj^q)PUgw)sP9tyW+(-|$^GD(M-O^t|de;f#USnL`M|!Ze<7DFw+qf9% zT_2Kj{1g5DG17z088~_SY2!?&^+h)X4(BW>%)_<^w`b%rj)( zA-<}Gvtqd45tj48fSkxDEGOcQ^`DqeN4lnV=@FMxGQTvbbVPdG$9Abj+->&}klw>W zJ^6WaAL;e&fZhv-^fnQ4^7mwieZM#24n3vU%}0ft6YBlro&Qihf{*j%HY;4uV2eBM zAN@_p$>SXM{?SZ&TCPX9-*KCe6XTA|Z>jxEDP6ga@CS9@5a~T8^+=M^*HBs#$2KN-dEXTTqE!L_dnBz`Tq{i@fY=Rhl%qE#o0A}oW&2>c{3m70oKMT ztw&k)9^JffT+H9Ul=w*J1|O{SJv`Fu`}@M@r1<+o3PjC*n(y`AAc(u1v(yvOe-pS^6|ou%tkpK%Y6tW%9C9l^nUZ08p1 zR4b<&?!OE5{4`+P!4Wp@(9_h;SARw4(^^|UujhIJ7_wfEMjeWKbcif`aC2+Z8=U;Q zY2s`PIl%{>&&w&j9yL@s|4)z8-hQIq=%^ty?~s^CoCt*XLp{~ z@tCJIeQ!7G?p}0gPSdX+68VbWE^#0HQVTt8<6@-u0@JfPi_U}nYK)Wn*bla2S?3Q< zTR$YG-eXo2_Lq1+B>PqG^8u&rJ!Yuy{5|BR`hKvg@7?(`zqmVGXYK<~+0+O6{So$a z?>+L}^2y_3ny-7&<&@0V@$$fZ&SCSVaYs5YvGR%S+-7E_I8Q1IpYI31x#nQT#Ypev zfSfokEGOC}sh+JLQ-9`_fSlwN zNQc|nhq8XMw4HxV$eFxSzhBIK&RI0PFFmZDlR{3eANM(@Nzb61V+T>Y@j*b&;tdq{ zj*36$gKy%*@2Ky#byn3es_$uE z4?9hddyCCGfDd*=U6nWR!F&boa!6s||dSd+ET2@atKTPW}$CO2S2lxK4f0wP!IJuAXU{j~)^ZD2gi+YruTc+o_ zLOn|j{k%sP)P3X+TmG}Zp5T;THw|BR$w?b+DW(2{~&qoioCG@WGB=I#|w?LvnI%@WGaZoYL#&Dnice zBBbZ!5!4TZ4=!%Ym&^2&a;_%itS+j@-Qhk19j|)dFUD?Ym!zDlhvb}z8vx4Y)c2;@ z=Dr)0Gb!Zc{iDocOy52M{gJWsm$3e`eTLqjH_a!n?T+Il^U0Hnt9T}*3!mYM-JtKE zKfE{I97@^V7sTIh4Zot^KVMPrxexsQdCNLLocL10@q2m+J*jymxG zr4tXyIl;KW2b;f7#wo4uOA9$uOX+%+m(+dm!KNM@Eax&IIXO4@VA})YEIvf%yKG3# z4$~KWur@u>E}=f+I8(cHw6I;m`{wZ;diY2`s14fAFDKMrevYgj**N1rqVt^=l5=bsUEi>rwstA`AaO1)pR!eR^O5CalL+>{k{zU4hHv;9<20x6Sn(YNN+)*p79l^9cm~GAL($LxWd1_qaH~) z7YfJ;p0J!j<+yBftC@2fS)%eSY;_p}r5WfHr8{e;zRIzzG|7 zT#th4xkOMs6)4wp^1obcRv{<xwdHT^kL-}8SD51&uYu0+=}(>njtdwR}qoll-nT#;YWI0-)VLq3TWDZj}T z{I8=ZpVIrV^9bY4zbjH+%U{o$@H->Y?>Njafvw%B{zO!a*s zAt(QCLx+9OgL5>6?>(q~qK~&toU5^Z$mEsY@hq)F+eg+V3!n4B&pjrq?^4dy8E3}A z368LwxV|Iqwsr~meQmbxU-o&1w$c&DaUa`ZTMgNI@5xVPaZfTmkq@_H>ruRuBV^(8 z{optLA&a||bB%zU;0Vjf<1U>KSyRZ_QaUC!AU)xOo7+fBrl<5d=n-MN)Kq-nDXvev z@VQN0;6Ls_J(B9VRzN+$6IM?icd4H1ht!kn3x3#{t=jS&N>Y3kI=ZY&{=*Mkqz)>te(96l z;+@^pKkm}i}MREChKs_7tsQFJ;4!{R1EuYeMelww-`DuFlQBLdS6@0LrB?sG2P7C$q{kX9G zWL`e`d-hE8idzWv9NAjeucP|)(2v{tzhw2@7Wc>!6qhXn>X}MX{7YNu+?-Q7?vUy^ zJ*1voU(Q)tT2?-#?dK*!J=-eo$!$qT_?!=ZL$xRHxy86cdY>yT)HAYxUf;*I@sE4$ zU0L~*>bYq^J)uijJ$Zf4eN8ql-b$!vbs=5PmWn^PxlJrLnDSYAn&Pr~NIh$;9B@uk z`Q&;=*?US&?dLW^JrmpO<&pcGb9{N3o>Is$$iclPxy1r**(C0pH(}nmrv6= zmhD|m$-1@Te!8B8jP7$zn~!$Mc0G!2M&j>dNK zkNcp$HvwHP4akY(#_kKp$@QFU>FJo-&wYjMd~07ly(II&51X3Dd%liy+P>4&RL^%@ zBCPKt8|cqjMt9McmCsyE3uc}K9^qh zUboU7qV{Q0SpZ>u9Z%QP&hPJXO4|88|L$}ieIFSIv}iwV?L3m*URXXOyXiV}AL+r? zR`kDaN;zXIQ#v~Y%oO^UR1@#?#;Q73qs7KPc|3TQV$>T#xn&$O#^B!{;{hsdqiXenIuzJ0xdVJ$c-1{bXle>L*++>?fCA(${;BXEb`^6h|}$Oqi;xs6Qok2~hU__yqz5~y#x?M{4a&KbkhAa|owLcfIY(*0oI8i)4if5_|E{hl_rV97Sl+)~ z3R;h{LeAKz&dGi7!Dd&H#a-Gi9W3OmGfwV<54JKOJ&Wpm_YiU-f7sCjb$ziNc2Moo zq~hE&Bxm${{+uacyJU-d`$Ot)?-i1B+`^gpK-QnPagMD<<@{Sh&d6N)dt`G5`RiF0 zepg-EE^RM-elv2g&c%I{%f4Mu_MB8~T{bU$4}CwZsw~nwM5t$tadIE&!NyjQwV!n% z=b=K*>>;|I+y@_QH6i1S9-zP&V4OkwAx8?!=ftgg`@wyFe(m?Y+a-*Pd(&_3LDKI%GFrt3LU)7ukp!A@-BuO~Qd{duIfx$t^aK3uPt z+(&w_?ic3t)-$6xN0mjQrnsBx(bX=eq#p6>2KTFTd2==tU)zh* zqg^s_UL)j0{Vp9zafc6mQgeHA2CeTV&TEC7(64p0YTwy?^Ok{gPUP@2#gP?&!};?{AI@?;G;6uwr9|!f5QvIX;c$@W?CIjk;dBp~s zzc6tg4Jnfy-E?MVkCm0v^ z!N)D;Y59FC=o$S$7Wa3B^NN)P^mZt@nC^4F{13h7KY97I#l7_-s*fiLT zHRd08)Ab1FgSf+oHMR41v+EJ|pUJB0Pxd6m$F4_(CB55E)AhZ_8K7TxkB}4NjB%{< zXPnigyg5z%x}cnmfSje%NKbG>_f~u`oTlsMy)I{vaq;Mnh?9>uBg=Smn#LVL%jbPU zJ<;Fnp#HG9k1XrW8MJ(w^t?Zyp6#D{>pA*0Z_YvK`9MHD$A0Er-<{>WIeqm+;hthm zdOk>ciu-j{)eq(Eb8>laPE)_mR6b3d4+Z2bo=$pl&Ya;r*@NPII3Q=@3~$a-BAA{S zckp#Vrt48tSU#~%Gr0#{*WsgR)z$mQ;oGb!?k3K^2|3X&wSMkhk0#W6**Ra(dSv4K zdqB>3$(u92ig(-x#ra4;&W3?=JPc=me#oOjPF&ANR67qJaqg_@t>>WnA&&**jQx`0 z&N*YN|93h65sPkHLQb?x`7^!idvr~2JqK0a zp9sh~{wr_J)LOwfG2Z0Y3qH?~P~R&V?_C(|^9;4O^!FY(6U?6yyY8R4V=MdX z3q27Zq+_x_6zW-3oJi;M>M5;974;tGy09Mc_uHiY<6n;w+xyp}pzA+>)YEguI#uY! z?c{G&d!&BgetQZ3IP>&^a-JaMto%;rDrqHE2DO zmQQ?#@uVK7y`AUfGwgR5+pExhI&kvw5x*Yg)%PM#7II>pZ|WS1fB6r3Ie^Ttrggvg zJt*fX0XdORSWa9wc{`teit3@Me4Z&RpB<%R@fx~r!Us3QaW((?A5_m%g?d(( zrRQZv{z&mIo$DX>+~%_T9n$jolYpGiFDxhG?yfuZ{0_LOzcl7@O4b3km5%KvDemyW zonrH}^)vMKv)B)om(Pk}{uKM4*3;8TbuXWO>uJX-6zAl5WZ_3{qH>6Q@=N=dOXO>6 z=kYtYKV_UP#liOjAGUv9PV|#`x~91QOc;00&wcPq?ZRqDTRlR07YgqmrLNZNH}{bq z?8sjF`Vf5AEWamhho1a9@+Ljca5*LQDDfwqll$P4TC|^h9+h7=OX~TxhOqxxd7j?O z(YTO!n~aN{$PW995+dOftszf(Og zH_0~s=3VdOhtvLud;SJ}+-Qn>Nf`II(h<6FAKRriXx#4&7iJ$;Kc9T z2EA@x-fKVY!S;o9esi z{$|^adywaPnuhy^xK2Gs<_He5hr}4AJl>q-x|! z$@QtfW#XJ5&i;Gy!NqO+TAd$0<{6L=jvGCd;_kCv(Q}^G#QBbpbL={ull$Q7+v>Dl zWb1i)PQS3H{(c7Bhvnm=>aWyu{cG#{KilhA54n@j{`0iS>vc}<_xaQxvCsVPf1)0B zR?*kDo9g@hy>#v4qZZ@jKIcsA>b-s*`+<{}bIv(-5S5<~dwSYACnCC@ojG(L`NP&e z^yWl;2PYr5a!#c8mXMRbUy=Jr57zX4MR4-_2rab^#x$>ZRwexJS|yhl+a7Ov%x|^YptO=TM5zdxHlye>25Bb_-ef_#OFl?xOti z)5+p@ZcTAFasFP&2|nca-{Kq}CLJUD>er)lgq(GyBRD5+*ZYm_hSG0qvZGu1>v{1) zYdh<>iPd&pvUh!jePCgC`w8y7(KX_|?Xbl~)^-+f2LRov-IGsnoYJ+2T-CLe-gdV? z^B3}Ao9^~*`h}a8>ZJqQUTke=L3exNR@xudS)8_iMWtW7TBZM&Bb^1@eDcQ~+RG2N zuC`~6-nF+Kw(V}uxM_eh{T7{{bK8-j8}g5sfU?jcI2R;K-7okO}mcelISP#(~JzUFT4#&L9< z$}8-5j$PAj$7Zy*#Txw{KW-QS|l zGEVnCiQjs~k$ZJc?sxMD@-Jxl+|Err?yO*qdz*1`KL}%YU&P(^{1MWv3g?&bz1_O{ z&TiQ6*dpIP=STW@&{RHW6TUyWv#>r-ncqtHkw0weeA#@RP0x&a4&|<1uioAd;p_Zc z_v_^qe6ZzzdvoG<=xO_oSnYXArz+&+-`g!d;LiyjlLe=3{ug5E#+z-{NJuD5BZ`$zE?b-i%^ zXhhwg;r-jm+q~y#OzUlMUmNM+q)hjG}~f z=nkHC!M`5@J$YPAdVUg8Pp&Wcq!xPexR|b+pSqlq@n-Z9D!2JKwWFhd_b$hMPT~D` ze!eEo&jNCS1KjXuvKCH$|0uTswQJ4OX}-I9hCc5dbH6v?&W7~Y&!?aC)@fYnnR}Fe zhmZT($fu$1qt`d`ZclTE(tV|%oQn{r^?nDqpc{N}PAWa5oG73CdSQzD{5?*4f2p(p z8^M?eUsz3Po zMvkO<-eLPM(TltNeF9a+$$jMCw`~9ZcJ&81`TCH8y02Lq(&wiR=pAQYAChV5dUBt0 zq||#H_;&ccxDUabVNK<8I>o&|Ki}RY7)OWPQIL@SJoau@Exy5xV^)&Iq=le9x#d&3-g{iS{!^{ZxWVIt}pkIkJJX$^J@Y11PAnm&uydXzwS5ay7Zfc z>!`<`qd2!z+~IRR_*ujAGWb2Hp38;QGi>=pKRKwLw*=G^dW6*z>- zSdWU&>-C%a$cNj+KlS7AyUQ63ay|Nskdx=fedI5-LF0a#Fz!vIOW_652fm4`YNUoDy&xV>`&c8%)hi~F)4mj?A4af zd5{qD8GVI*hmU?8@+p)kztpMpeheJ%{BpK#58g>-F%K4u^B&^dADsPk*&pD-X87Q2 z{gU{Moa(?CoJfgm{w#kzpQO0==a=-OXL!*L=~#P>Ec`z2uau7Okc}vRMhf&-Md^w1 zDSdCuy~6T2t~i@>QGXsj=YT(Xt=_N0`QUeqH~Dtc_5D7VbL#ygq{A)BZA9q_pYJF2 zG2WDN-Y?_?A2>cQC!bHYmCvUr?kQV6LU{xyeCSaLSUx!?(v7Kh3G;l|{&bJiJ`a|C zo$3#cgAZP8ms-p(l^^$>&*JI)UOiA}o2PZ&&^bFTS^7Lb_(ALYLlk%GI>4&pOsq!p z^ze}{w<+uONI#-^HnnFHYW}mXEcSYa;@-b6gYDdA-XuLsvyqPQQ9hB+h|16T4du(z zadxNcQP6SRaY8*)-`C?jaft47p2V@<-)X`)E-2@+!u2-obxF_iEW}rNOE0gSv;C?! zC-&p@y^|vSTk1YsGqwqFh2>1E=i^M*&8>T!^VNT@^wiIC zhF6{-9aHa+g%8f$5yV+jyb}w1>sdG4-?VXVL!2qw_n^TAa`<66=R-ouMh>O(GOhpI zw#PZIRnLynvGgy}6FzwR`Mg2-HNWqzXZ-tAK7(>@N1RqY!37!MgR=rXgq*l;^7~vS zJu}4VjJW{a`VJ0mN8TkJTOZK6Z}@ya`02xFfB4+;b}8`#(%&@iy+e<4{(ieuxX!!2 zw-x93P4qi_l+W=36;-tD}Nb7!HR;DVm;!*Ze?m3PtaZ<_i`yYx8i z_q9vAsr5kLCJP_jEu|;?&aQg?*bd9fXTIpIKlb0X$7z2*ZQ^~s{=$cz$S1One}2ff z`^;02f4dQ9zn>h78p`K8v^}>U>BPs~krQQnVB>m@oJ7Z);-00r_xs6>4|Ls-ZefzP z$JOufp(paGDBh;Z7sta^4D|@dn>cqTPHVdaF60LvoY4u=L&}MH2Bd>@P5q@kTu#Y6 z1J{}R$VY0yiT)vuGjZ-IjH&d% z10QimKKMOCv>b)_0yPU($yw>MCaNgjU$-kY|_i=h}Ork{NoRqRSp4WHVxMLre z(_H{ztw$(F6Kb3UA9^O$ct|?#!1ajt>rCqab3M*!)_z^|6TQ9SK6HY$U61%s3*&f20hzMfV1Tx9$WeZD>Ssje^bht2&= zUw4M>uu{(WJ5(Rv9_}7#Uw47^-pD8NnLlTIZ}0V=I3Ap~=TM4Eke+i3^^9Gm>shmK z#(pEy6Yu8*KQEt+cS+BG3H2P=UVk1o>v;E9kYDQ_8K+H8=S)gxk&t>iL;jpnJ^6Y< zu4nQ;r007=Jqxevaj#l9o2Ly%&xF!*(U5v(h6kgk?fH(0g{U5VAk=f@VqMQk3uh`P ztM9gT>FG6za~YwYt&(1kDqr!}Gkc#b?l#WGRg}(3LQeiZf%I4XIc@I~K>KOqtg81C zEGOjb9Ifj)Vc{ITcQAUQom(#8yf=;uJMTTy{Jfdk1U*N z#W@_3v-3GQc|RHVbxh;UXX*ZtwV#apMTk3m+&>!qHTCBQeg9}=gyO!MP|pf`-^ED8 zKkl~oUG%!W?nz6Z?|9DDQ}P^2n{ja;I&+KrzRivF`$5unDYHK5xrR{B6l<5pX7|@K z)9`PXFh1h^#ey}#Z`+8dH`~aR>B7eZ+B1b-%EFrmp8dm7ccy@5MQFJ-Ls3U?)!XAD8s?d|6MI_dhGoQUCKE z;dm3@6#_?6-S>dct?9c$xE=*vC-72FPy0BIuLI&f=QOPg!umSi&f|E~`jA(I^{6nn z9v}E<=aG-pBJR1D^mKXLkzPvpJZyC{y}ZTe(bGqIu-OZ#T*2oSoVIaX;wgHr;TyuZ zXExV4C#LH@=g2+j{oDk~Cpc~WPo%rKP|y4{T|e$4J=ok*bRB`uE#_&P?EZvlp7z`B zJeXuYnUA+j_Zv8m$q#yc-=xCvM3P*`pryzoVsoFttnH z>2ccI`P}@(nOcnOIO9hCeLL)5kHBf02Sa)XFwWLex^CDHoF*UJVbhz*<{3Ia*T=CY zJ+~CLOOXY1e(r-0w!W-PPg^@*dYand&4lfIduwXfi`$W{F>dg|Hq>+eD6{84XLN?(!1y}h8Gj;VZZ zEi9kag>-)I<9uK<%lUKSx|uym?0{% zK9v}8l@=#EY2l1-DJ!2+&O;byb7^m#z=`wVKDNV_XYr4FP(2T2oCzT(*RxpB>yb@Q zluw71dsF#5Mp!<1du3`Dpr_43PrlB?RNuD~*7x$FdU@bJ=Sr+3i@UV_JdDMi=La9x z_vn_?-tm4&?L0m1j<6phC4ndE)JS`h1;J+RjVs`w>D;)bF&qUh#U=W}LQq zgz_onJW|M6yo%cS$@Azw5`2`4!k=_KTi@|7pS(X`y?~B4eaGPkJ16X$Pa#4PPCt>mq^#teje>|O0Ms` zpPw}J`;ni`f)nis_BU}BLUM9$D|tcR6k!kKY1OkSLgY{FZMWR%rC{3^Nwf! zYx;KhXy=j7=q29QA>;>(xFa2GH^u!#Vca=C_mPj(q8}pdC!f^Q(>@PYXF7AA^Od*r zAICvY-d{55d3ION_r+uwJ4uF?xu0vslxJ^OHkZ1tB{3n;u??m_mhKi{#wWx zSy3;a+~>Tdxd+QRCgiL!PVRHg=8pdLJ*b|)5prf%()Hv%=SJMh|+51mT?dR`=oaNQ^@>y9`_c>>z?!PVw^%C<~wS!B5O3(^JY> z3djkLu$;Vn+SYp`zuyZvdEB{=^kB!P%k;Ee-y`aIgsp`4<3_)s-#;mBrTgH6?YueI zbr;(SIU~Cf*Vru7@9ZS~>rr(Dp`Mm?YsCdC>*U{7CKJxEd%l9V0 z$=7dj&g3mres&jfb}rQQOsuPO_xaQxtx=htw)$S$fZE}8g`DZF^>KF7!kNF@zkJT# zdpjUMJNH{m>U*nY_TAOvT+X<&QvbQ#_=vYoh4u99)fM#iwE4Vj{tIN7XW;3Y<{5tI za!T%ZaDMJ1f2pOXj~$1fuZi;{mvhM3t3SUqa=We*@@+7kNA}mt0rrzx)FZw=gx4da zcdoEsSKmO7dwzZ0M|!a7t^NBUh zUz``LseGRAa!T4Il%t8?sQS~<>rt6;BHxB;uiLEM4$AqbfSltSd2=Q&)AbxQ=LG>d za~peemag}{|6|gV-{-Qu&+5Wn`JC}StLC+OJfRET6E*g4)t^`Ix5E9ShSD?a`>bs5 zU%H5KmhbT9#QT<7>U~l0!I`_9;x2tp6xt(BriC=P^H*YpU}|d7lr`P44V} zJqpTM6>@fN)35v72On%?(tCV__7j}^J&C64`(LD-o9p^zzN!1*gH0VgSUoQla^~LC z_2fSIV9SQ@nQ}d)m@6s!MzKJ|xfyctx_+k|>{7#H_Br>$KIT0ZOD@+nv+!0*2gs(ecO^H&S? z9GOn#b1Y33KGzX`VMkfJWV_$dS(Vb+TeyxovV}e_Y%6YXaXWga|9l9_r&P~t0_q8# zuzI5X1gC8t4Ea@if7ts=$u0GEiTg+ow*IZb#C>EnN@pKo+}oGy*Y_6V1|Mv67w`TO zeutjY`v{Z07xUTmtVMOs!jig={QLGCZ#{Y3qa%7crt8u7g?c8o*5l6oKA-xdzM||o zXj^?py2lEyM@`1beWV9lo!whc{EoP{cF@}qlb**5IVbng(<^MF>x=whCt9-dDV?wT zgRos{Y^!s{nGZhL)RrzUt9_rV8S zKGdJnowtc}zjwy}ndX<4aCemSlVgmN`#e7K$l<#Y_YY}z4p5Jz{p34B>dE!x zoVCSe_cx{O(i1|?!ngG}Cvv*aIkQK5$DOzH((&e#LeAWd#Fe~>+NbCa{+!Wcyg6|` zy?I5C@@c9^SGd=sh%;@ddz|0<=c6wY*JxI8Dj)gQX7`>~tgG+ZxvA_v zth8Nf1l3ak_4Va|%9rXXjr+YJIm5;s?NV=9ipM#c?iVlZ?mP83!)zr9COmV?QAapX(^~P1hsScZHU76V5oR^u{iJ{m+rT^zz7kDIfOx z|Jpkbz&463?ypTkoB%7pEnlEepu6Gt;Gh;BkN-PC+DJM&jO&pX<;vUA^;?<{bh-e@)R+y9%Hot>Rs zK~K7V-lpe&n0hu$Q}aNvnToeaxKTdWqP=tb`InjXv*~bCPwG>?=*hhH&TU7pRLGf~ zW6tAH&bCS3oU|R$=dIb|{;G^S<2pk75lYX{9qM>Q+bQMr^AUG?T(h0WMVaII^pR%V zsZY6LNAbqp{I@7N#cNympa&NZ0py<@AZc%z(x&pbopv%KRG zSI_of1-;;7omEiIQorQ0PN3tTs{Z_q*)PS2ZKBSqrSrIMUoqa+k2mWl^^J`g z4vt5e4b1Vp?WC?{#<(wao z6CB`%Pi@`vy#AA`=Q|a0R;nlZrJ#BinVfi@P5l7Xj}&zLsgCdyr}6aUjzhjSyceiZ^+h$xZoe^%L81IlF$ZI6q}_(m2O%H0uG% zhxLm)mlJya%;bcg;HXqj)K4yFDysDSg2_pr_nG*6`MAgP<&T>s&Y#VE=y<;QW;Na( z%)D;cv5I-V724bMp)+h$=MNt?sGf%LxYK-|74^Xf8#~^6-9@EwcbMm!h&wncjeAhe z=x(aLe_NrR^||u>Cs$AIdE8~p`_4MgH0vkzp)+h<#5?ZzyworGTrbAn$y3nVi%|eq8IW4-p%4e_wl?*p{pT~vFo z3fM0d&sDtj+S)++>Uads>VTZ!s+1G`C*n@8$Jye(l;Gs7SHyZ>aQ1fHFE{QeZva!z zx+WFxc5UG!A8Om5VUFvV{pY}doZzXH6LIJ28K158cjGRF@4}MrbJyAb% zN15YTTm3vqWX$R3Yc(G@sE>564XWp$fO>+XQayvl9p%+9IaAYAoFf-13m^GV+otOk zO^46b6Wb3C$cgV&${AG8@Ep~Sh6Lnnyh!QUrga53wSA>0IF|{?37$$hgX$UiRgJS& zXL8c>_we-c{Sx>5J++0|FVXXN=<;v(jsN|ydBR0~NI1!(< znVhMa<~#%SksoY}&pg8l?h0OPy~x_`=bG-GZ>|{iJ3p$q)QofI=H_{6VzfFxs@*`@ zuJy~GFL94Y?H{T3xK2Pl^OICR(n`1&DWcxl^u%^t&e|1KI~va9q}R0)mznyad|1Eh zhFnhMw>guu$L}3oUY;{vR63v>YBBySTx<68w(;ksVjT--{Fx7Lss|i9VU0fHs1ZZ?K#gb zr+aMxgv#31GrS`>gFH{5?n1>$@4IyBy*X{q6IezrI~APSU(Nls>3KJ^enzi0^P|40 ziodst-h?~vJ&RdCJ2YqOok~ymR-(hr`bl-G(et$Q`?htz--x)&CuGTfLaw7OUTf-x ze44LO=}jjq&Kfc=l%C@q_jA$M3K&gQ$Fr~=N-_K-k)yM^H3&d?H; z@WHnA5ogN^s=e=5A!oy_roP~V?Q1>9F*$R$nOq^_gAcZIgT9UXu@!PsZt%f2kLGc5 zk4JxIa<<-X>Y4n9>4OipWL?}>e*1Co>X7( z!PYVL^gA9Qzk`^Z&K+i)6Is(oez3)rd3th>?}-XIDL43Fv#XTn#CSfjo_U^N8_yps zI63P>vRcpfLv+66_aec^wHPmP<9-NJPdYw|&nO>v?l^?5x3RVNU6`CL6U=c)mk(!K zsC?X^CwCn3S0*Rz*E4sP*E8+Y-cdhk+->zU#;l*6`uTdOf4zOq9yn=xw{h-KAt#;> z2=1U3ap#Vc$1>wi&)Zt=Dj)akFlPPq`MvV4Q`ETb9(Q8b|G1glNZvo_jmZf;JIAYd*SD6hpEf>e+F<*?-2~RM$INH&r&hiTCvn>`ze6bKT?7qTgMOJ!$eF z-`e|CdeaF=3Frz$S)@0sHG-a5uC&vtzOn>@Zd!+h7zryfxGMIKbv_B*oJFFy-T z{O&Baw{bQGIjZlKJw)Ki96V95)%5#P^FXhaolz!ab z0Z0Fd{6K5#=O+tJ&hd!y+jK{HeiodF6SlW;rYhv5+$e`@X*+8EQauOQ7Wb=}}PI2q!qJG|%uk*NBZxjDCefqu7#(mp=o?0O%<))m;KIWXl zmC{XRx2PxHnZ8cUlin4%gEDv)HEkvs|^h zkEiA+bDi6D%yCGkKEKO9rpBl6!G&_1Jym%PW0l3{)I!h14rW|zdQN5P8GTyi*P(68 zQ)d2@!_NmN&Rem)jWZpPv-ugt2X5pa)Pj?%=NXcdaUKUg@cg&+JhMX1-s*||lY8EA zmf+-^9~Ebt^|7A#&>6PPr(X)nd3J@IlpB1o;Z4i;pF!uB&T%;xop;!dhv<({@6k?i z-jSTC`XTQ8(!h64a<-c4IJtcza;0*~zUQV_Ic@u^bl9VdCyC#^s*+2@owLOE>dsly z{hssgNzU+Y>BU=)pCvyZCDOMN+v5AMX_3B?NSEEQ-0tiXHmDYFojLCIRZjD5tGW5Y zCf}N0HC$|ma@$gB`!q>E?qrpIn@Ep~{IGq~Y?WW~?fF%*T%<=QjdwXSB7Lw(l@O9= z!bvKh_eJ_PA|0I39pw6K$4Smt`N*)z?bka+ZIAkyn!}r?9pN62{Kp~bHnSa3Utk!o zcwPB%9XP{V^EhvFbNA=0{g=r}eFIWBi6eOPHhCuJKbV{a!byF~SwEepC-;7Y-DL%I z{Pj#dYwAgT%Go@%e82SkeH**&J+zr>*RbgaHg<+jT~z;T?>#}a3z;qoL3?SwU!~6z z>9Sq7ueQ3|9$;^KXk(*)NVlr~A(`9QZSUF0xTUQi(?<))nZeagoj+TSoobgh4o|#{cbb|=f)kJ zcLn4`IhAq-)f462&E#}mQaWa}g^zrwZ9KUA@rbJ@@|_is6W^Fn#dC7WeaRN6-`PhUlkYl-=KQ#6Hre8RjMc2k=rjJvu@T_KObiHOIS}@ zgY{eFITCqGzhrxkg#0~P_hh^qqkL=Qe1yqaywO~TL;b`o@BWiulw8C;{)t)7ZT)AQ z8TXDEs(shbRJQ3&Gyf8ReiJ{?yZ^*?h&%UrzmGEerMkCFF6yIvYVo|^+?D2aE3|j| zJB%HdsqMnk&Fvr4?H%WFv>f>Dgp>N%4%Tl!f^z;-b2f;QNO)a%?pFmiO8qXI1c)y%)iXvskd?3)-TEHD`{s%H_vkIz42XB zKkC=rLpZ~VGdx%IgV}G*`4QAlZruMAFz(Q+(zv6&%l_KyWz$n$KH}(^*Yy&4Q@=>{ z)Enk?yo+9OM`qoutsTjqN2qa@uaf&$F76HQtGE|;Q1?s0M-i=a$vC7|#XY9up3)ZE z+v=x{Qyz{4=NW#Sp$`;iVQ0k&ALYjMIu!U$o#M=EzN8mtY2!t2Y@D)scITw`eIf^p z7jWJMAD_pLBYM^=&Sw35s62U2l&yZ+=I7=1GDkVTTQ2U&50##EJ1RZlgERD3!l^&V zYQFZKoSyxsjZ;1zOmL>bnaY~yso=nKwoAH!x7_-PFL$%H=fX)o z@m#pHJP(k1w%4iSPPebRZ*kqMX`I>*_}H%N38H6%;*9I(gEf%fcXl~FuFKds#dG8g z&hQ1^oVY)%`FDyFJ~;DF63&?7v^~GhRzGd$M^Z;|+$_yAS*K~cSpHoZD<7z3V z-T~WroJ~&~r@SuKozr$dF6J%bTPi)_L(jxhM9;X=(>4zlR8Kiy(|sHgy3jlB^t_Pz zxn~Hc-hnP%FKZW?=Q~05T%K^|ES&WGfco*-gfpS^OlZF7vmWCm1f!d^9pB~Hi*tOZ z&*`Lo)6;}Av%Ki+?AHkRn3k-mEwqwVqvMTqll$ zp8dS-xH(J|RK-|#LGQ1nep8s}nN)Fa(ww=T_0w_a#aO{&<6KdE#u+csaR>FGE45|D zA)cJJkw@HZ z{k%L+>E3@Le`;yJPJOyPd|N*+`vUpGI8k|yW1C-koH=iU`5NTc+j$%Jc;um{tzVMQ zi4D>(fs^)2NT=4;FX4QXj=N}kk4#qc6>qtE`p<`SJYgPBBj2h1lybqZ(bp;9!{U5X zw%;JHu-;h4L5@FL$#XK07p_MYeo*tu@bP)qhot|+2NnxGx$|JJG4;&;+tic#6sO>$ zCzmsOvWk0qK+f84RJ_w)myf%R6Z;dC^Ywt7D5p|R)K73?{Ed8RJ3{)~OwNMVvC~oU zhmU-y4W)SVirjUoo4aEx|Ms5x){HatDQA-TTupAj^d?hJ^h-^hinr2!3H##~D>Q2S zUgej&NA(xBb$5xt{=(sGWm*<`{OctoZ3w8*PiPJU^|g(`FWerv1a|Geh1Ohg(&k6 z+B-d7*xLIv=I@#2e=s?zPmvndEI&W*K2Dx~N%*#LNSn|z?QHC;CyfvF)AyP6(*was zvT@q#=fB)`G}?EZjCu6bHcD6cC_H?BFiymsj$>_cKZe9e zXN8_oXG7oTv0z-27^jX$@WIs@P)}RjZJf^q=4lZ}Y7@Wc`uVG}@NqnH3aXqMU0&e@Z|?kf z_1u7rZdZphr z_3Zjh)ys~zR62ZcHodCKX?{uB#4E~TznqVho<)nEew_bd>Ip8C3!lxYzX(nokFcH; z`Pz<0FS(rlPLObS^IY$CpYfz$psCJ>j<$;%(xdOnLg!AoMx_D!RNGo((4hnxNpzYvpB%i zlltI*jeW?|({G*u`NiFVpnv~abC7v_>ZmKPXLfy_p4_;%yTJaObxWIiQXl&bo7DG@ zz^4|+BW`=2?`Gi7*-kjAPdQSD^5Ra%+qU|7EOVVzRDT3a#5dhHXp{*lUqNVnC-nlIH})*^DOl|9hwdw^^>mGvg!Gr`$hlynHp^BNqv+L zTXQ&1&l+;w!p8XplQS~JyBJA5FZ~X4yo7OF<1&i3jc|hx);6xg=ZL%C z_!FGPfSf3&Qcil@q}QEoaqn~s_OGAeWzD!#AN;T}X58s|7#ruiOg;0Ovtc>K3m;rP z>?yo<#N~W1ASZY#8CXsB5azz^Fnvi!Uv+L520aUGZU z1L~PvUh(C8IGsL39d>x5qIcW!)))T25s*ew9@uYIl1Gy zZ`^YIk4IVEA3;y*BOSKu*S?8+gRVax2aJ2yimHCbwFMWoeN{if*%6QvJe6|NxYO%p zw)XxBlQT11=@?r{S@__lwq^=1?p)3V0Xe}_DQ8eU8<$t-gP#WEjIN^e?9{q~n_8}( zt;~LDDzjgr=f&Y~6ffn2A6w0P98#&Cp9Rzt9F^)xIl1!;pEEf-biA9xN=NwMrnbOr zM_kS?0&;?qnHYpIklt+EH?KRnO0;upPDjP@a?9j{M>d zJv#&HiMUs)CyjfEtdp=EkG^7ZqF--0PtDiXty*5sMqRJ4U({k;SD0<)W8=Jzd0nRK zCo{ixAI{_`@BS0K;N;GG|Kfhpe_WUO+2l;GX8I@}w&n)j@!c=(c^#K;1IE3uy5g(V z7F^VFjY^1-6pMXaKW*)?RCJQlE0>zx8hKw0?509}Q;K&)nK3C-o_3c&GAu z%KJv;i{77Zn^(M3#J$?t(Rcl4aV2#>xyoJSzmCa`bgq^6yLr9vd<;C#1KW%cZ_?rq z_w^v1T6*1#`t|pc=W@^th%e@8-SzXdz1#F0DZbx*o;G=rw@$b(sdGD}D|}LX$<34d zUrQh8H^bdkfi%_buc|*P=}De9gKyH`Kc_kby-y1B-ZWpEo~sFv?s{fVH2X<#I+`E9 zuMWTTdB8Web-%WC>1&AmBhI3A>Ghj<#~t%k7%##HUg2G`J`o>SEXGUR^-DvU{ZhQv zc&$VS3oQda|0$Po*&h)p6Zw2`|;R5 zxAmX4aouQAc&V@n5Taow(-&?BBQiZSGtccvZWbcl#|-ROs77!<67uR^Reln%#{$aOvbX(KvQKl4biaR~Z(?(zL#=JCC8D>LrYr@I!N zQ+~bo^Ye$>AoWJv(U!u>Ypnh9GPQ=~sytw8& zHJ<;jT7vqI=To2R=j*xqC7x%njad(La>*3VFF&4#o;{B5mggR9;pV(;sb4A;MBaqz zO)lyu13updoY@0-{rr|LkAMBl5l-rp-STz8NzVsu^;7;voa6Y{&*bk+J*n>tMm7Lv z{b58;OWf<-@B7ESW?Pe!`UJz*MLXi&&-JQ%p!IJ@t%Q^M6f8Hp{P~f5{-j(_OJBC} z{PtqQ8fSIi`Q*fQrk>QN<@x#U@5gy;WP5(y@5QzuXN2$b>zwUP&K|x;ndOpfoVIcD zjv}*&Gt&2XlqHFrSKV*!rbknf0@7qB&lu`NEuEMmew@x}Cy@rS;Q~Go{<(Zvi=rJ1bqA zcQW+_2ds?~pWFIRTio{&Uko|^aj(~WD2Mt;=UQ&uq36PYdV-@;JrQ?Xd$%2r_7(+4 zoV9(AM@_q!ai%`_xfXijx*5J_Yex=qJuTL))$Xo%>vlD{QBKL;RDS#kPQUZbwtuL6 zR$y{=?PqdD4>bJ}pMF!T^QY-f&wq+({=so#UsCn2bw z0|M%a;w#k?ad-9f7>C&O+|Sjs)>qFq9dB?_AL(2RJ#jrB-?R0f1DSf_evZ25)cT9Y zv1UC$Ik3^2dHtu~{l&;{7?U%+r{ZcoMp^jChuY%pz zLw%%kt*yP==D`jS8K)gJw<({SZ7Zi?FEh^6w|&o+&aI!#y8hHK?JW^`pK=k!6z*cfa*E z$YcmJ?lt=;&Q@*VBOhubx0Y}3K{=NR$O)cGIlCW^kXLtWi~GT1qqMV{?{$Pk+>AT* zyO+gz&($-pwWJ?`v{XHov&r`gxn4hq!vK<*R3wa8aLf`uRciTrQxVrSb`P zDP6y@>52LYPQUXby5JS<&Yb7ampD#XI$L=kwY| z2dL}Chr1as`n~edQD%HmZp#5?I`vUby)MuBXZh>#+_+<&Arvs~?Rp-h(s>5#x4f@F zzUc3_+Q!L8h;79>meM+E_sbstbddQE>U(^}O~U;ou-Fd2D@5Z$L;Mwc5T` zTWtRq_f3`Wb%cWE#P_I=blB+GN_Y6w;&ppx+fbK@`xve$w*bw-HY2M{}fprq%CS#vWI{E0iJi z4fT`eW2>Jhx*-1bv++n%PwHcTV7c{^yN=~=ZpQxOqNqRGI*68a5^xMg!RlNjn zZ#fZnR%{%5@(mi@tg*!0BbsGmLde~voN z=CsB3De;C=KdH{tM}AxzRL_+H>RIBbP*2oPaB`pLzcQ1vOUFCYpyCd{#7*AB?%-YT z;Bu}KkP|qSat75iulF|`khA44O3&DF-u(jhgR3WZJijh;Jl{#Us1H8a)Sl(X^W6Fg zJx2u86C9Q5N#pJ}PHy-@oo8*xvsnxluq)@KnkfR8N$* zF_W{nwVGcjo}lz>KE8ZAO1;4Am*{;`w)5ikneC`v^I`v}k962hW;^nWJM!B!pq}_% zrFvEx_cfTDb$?TFZr8Ty#PV^E-OY2Yer*AnU6>?UpXVAFE=BoW& zDcopw-<9{da;2af@6Y;H-GpL@$_m!Rz=6dhYmgaLL3R+iiQ`^1|@A&T5j^dxF z>znH_^+Z1(nW*BOnovIO#ZUU?xCzen19C#QN;!kZ9p%+BIWZ0iPf|LzXVprq^$2fHe2%z>J}~#!Hm=)-$r+k#a#A1Vm+X-| zPVVzm>zSN6!b$xSpMI0m#}S$iAA0(=qxjdVAFgAzBlPn%rzl;MDN|pR56d0Tb2&E) z$O(>0IcYnJeafq!+cD$bs&xb>^^p#nOY-WcpPtBXbEcl9aq$!t@5HI)E+u|pS%FykIgoAr_URL{bn`sR3)`9;<9 zZ3F7re1_ufAl#Ib+m8JDd2ntQkP|$Wa?-f_aiYBKnVdMj*PX5OtUuGN2gnaLwvg8^ z`QF#_y=sqpFgYVlI^K7yaahrZvvV(Ad*_}X?Z|9LO=p?prQ%}Sl z9F@jBX#Ff!tNq;}AZPj9E;9 zl#lxmx!y+fiQM}UP7xV*UmwzVzIVNA)BQX+`s#iJny+nL(5ZwI9MqQh&r;VpOFrF@ z>6g~qd~D7$*f^(%e7oyuD<*t_sWbI$-?OEIlh#ig=V?sNyyonhtDa{B-^SsW4o-S} zw{f1%H0bw=iix}p$pBpQ{Tp8O9v-i7i8m{%H+%uPU_ou zZ0X>n_p{hI(@akKJ3iF6@z~OFUQE}K+UC8_a5Gx8-n;87@8^EiOjmKwe62o*Z{u(* zzsrX0!AbSBah^pukq@=4niJ{NM|#OJIdLBjzGve++udN1p4gt+#KmSiqCVZ8t>;H( zKX2nahso(Q>$u;b>xK4v@F9V#=Vs>q+c+;_a%Kq^^?_HiOiu3e70+XG#xF7VoBAa_ zykT?z6LTp3mgWTx#k`{SqJEFgfXZY#ZkVOwQP4inHlf z)sEl;tA}NBa@Va*V{&$CPVi74=_TvKDer&qdfASfcZ>55&iE7K#Pm*jJxhn#@3jwD z$8+U=+iz-}c~M)i;dn%UpU4*X>FyW(`}ybX-QR zo0j9tKlc@!^mmkOdS2}2>#t|?m8PE5r<~m5Cini$W+rF-RVF9(gL2a6NYpH?>UaKf zRiBg7l|{a-?)iIFR6Y;B+;gJByPNC5;AgHF<+h)~AXQG|KxON-k8)t66V>*JJN?}j zTih>oGw_dlQ;Vr5^}$iH%yvY755>lL8I!Z_YLk=tB|f}ia-zS(*KC}Z6VA|sCJ(;f zt~qPhRr3t+@j120pLz51^nBCCc?IFDy+v`*a?{r+{`5NPbNF;S_)Sbszj<2ZH^Y77 zUqA6Xz@fDjFMQ-ft?hS#u^rkG_x_Hn2xsIqB~c**I@va)xd)IjK)M(@aioKYufmGe$+V%NH<}&lVV~>Hd1po7n*q7#b4?fO2(mSeh;<~)HbIj*-l=fr1dEUXD zPrk#=!2kH}+-AnThhG9wZ(4lxME}X<9Lqd^&k|1R6HKRNLHW4jIVarbSzRz#mN3kb z^NZ!qH{<^>^^6|neZ2v^jW3t~9C~u+KlgOci~ZxCxm|I_URC4MF2W5y*y4WW^$g0n zS3pj1fEzxwh5dP)-1DP5-2(jejAhNZQ=f8naN7~{ddEyAXD8vLKIII3*SC7!#pG4I~pQE4m)3fO( zmCybG^=!Xe@iyIMa-)1$o1XX_oLoJhalh!_&(~?bmceR#2Os59o9^mcJ^vU`Pw-T# zC#|2{{_|df_K}{Y;#|MF`W!yEscj#}Ywujn`v@m34}NW{Ss$s7?O<#5I&JvW zqJGkKLALYv1DSCz5Kih-j_@zM`pMPvezySsc9gou)RX#@GtShL%b8@JcSPJ2q*QCA8d-Lr(gYS(Df$~uzu$6SGqRdXX*<+*v!v;TR$IkGxo2a zVa*2)>LVRC)5m%q98gbiRH|pC{rp32!Tx$SJYdF|`rwCc^U)LQ73p<7+q#Pj#rZpD z-37g#NPX~eE&6$Gzm#(`_SZ8}^O&h8^}z=l8O9rba`k-N&DcNgv45JJ z)CV7Ij;Sa2{QU{SSramOP;RH@%rvU=clh|6+9H$FFYYZmE=L87d*KbWA1#l2?+r^a+!T`rw0Y{3GwU$sI2}$>i+NoY|;4Ucv_#wKdFn8}4=OYz3Z^-r3d)Tf+&K92A0`yipf^&egyKnsr|I5^~vCZ@;r=K5`^O6cVDYqXN z{T!V1yu+sF<$|-y8C%jb^qjX&4bPhCd7>}n@biOmUO_l>Ois$}$3;KKag*+^?f8DB z;N;AIQhuB6l*i_SlkTsL^QsCtDYuQsmL9bKY!RHC@n_9EvwkL@H+{;Jjr48*d3A-H zl$&yP^)cr)OwLxKC-o_3el4D!e&_GVceeY+|GXpdf*EJ(BR|+I^L&$g+`N{lr}J-< zvxg5rZ9}7YdeU*7?L2Odo3Fo~S?#YX6F9e+WR~vXUj`we$=O&ZA?A6_wByGP0s?8vqN*%=G445e98yEgV~O_^T{tVIh$WG^`t)dU=s1gewczBo_m|xa z7ID)2;5WTy>PdZU2U}pqo!j1DaWnSktZO$psSiHb=oH?3GWS0HSDBpcgp>N5M?s)zfrk;&&E6(&FWg~By+~9*v&*imuuAXnX z8T;$mM!2XCKG+nqesc937f?@dKwtRO)=lBXojVTs!7adF&+vRR&eW%z^$U5N+~*qI z$6TMBC!Ex$oS_qV=kHuSi$u?+>%7My4eywGQlD~$598_SS3lcVRQvnqfb}z1RJle_NX0%kj^ zdC%mcKKNkMXP19I80Nj(UowB6%r@^mPv{wq40HURXVpqLQ%{=tgO6)5o=<+ri~IX- z#{T_h;(b$3>QlbD!+Gt!=I8R9iB(nonZm4}SdZM&p?P&ZrF`%kM)K+>w;lbJ$%%FZ zj!N4RZSUOQL;27x*gx*^56!q!AN;VLU-9DZr)O>@6_?`!>Y4dS@pchz@WFEXB`)U) z0Xe}@DQBf||JW_qKkl)Q&A3w^{IF?ed#BH_w;hkVn4F!2lltI;ZDNk=xc$;;%($ap z0*6y!zeMBC)$>QDp3zUtxKqExuivyY^-TU$zMqe*qT2iTfO^({s(3pHH|0#M%u|KWo~|@rDH9#=Z7S#aYm{?sJnH`N4+5<=atd zocy>MciTAmX~D@^$I`C3;?Jpk;e#uvMckeB&Hc62&(GZg{NtYf!px8Ql(UN&ckcDg zlLE#aJg5ioscrR%JM`q%&q)<>R$4!4zr>CEm#z^0aZh!cai>1jv#E(Uujr>|e1vL` zCkNEC?JLC_(U$VT_iOLmxPxWO*TmX#G>_?z;aG3Ij*xZ}@nU10xqlqX!&$9}`ce&d~Qa>sSe%=x8; zZ%zHE4?ftYbD851=JUbkGUFcl&g7&%_+UE{{B+$a z>iO>QOQn48{XE6cLiIey$g@?(_4radV(R&wTabVKOn$HQ?AlR{!{C=V$(t5t{p7Zz z@0px6KPb+I?Gz_`f>&}on4Et7QgU@wf6~nQiGHa#Lh-h0?h+Vz!|j*2{rpdE{{C@y zel*)rqRaFNrqg^e@A%H;{JBC-%1t@zkL2~A-1>PYGwxZfXZ$CnBYesSze(3C_|&4k zb2-ln$cgeQ<)q^fdVi4ZyyJT2IHXJK2u|uF9X82a_sgxHzq%Rwx1-F@X1k$2_+Zmx zDmxyf_3!1hkl)R@O2j?ltl%sw3MhBq8LsE2Mylfxd~mf`jz_J!yyTHR^r zxZl8xd&h64o}Is#K6qg>FCZ-_g+-^v#E8!L=Etq0(R^^3c0TxZks>VWMirt2kb zM{O28{n`<|57ee-hN)*=wfVb3^^WO7N7!~||4H}P#wl)&6EFXER3u!~2On(WhVsXE zH}2TDo3+LLnt<&ns{1F}j*?xKwIl9v^QH>pPU}H8Nz~i5%lAuY@7(7aRWakIqxxh@e|+N=jCA2z>Xc|F0&U7x%ZGwyAK zi~8V$ZLKiwHF~@fA>)<{MBGE-KiN-|i#x`N&DZF81~T80v&6k#m)H5L_c+<_Ii=X| zTbXeW*O+mpKJtUjF#CD#^KG7Eau!}O=ach<8+@=Glgsx@w)Sp2zE4xfclP;FON)v- z9p}W`z1zFrxQ_N4w)TD-Q_s*4Gw#%fjVp@yadX55{jgp2wF zu&s~V(R60q(QcBx$3%}tVcUwCO8ux64ai{eFyj+X8bNl%kX572T`2qDQUsI-h zd#Ar679XkNVQcRfi?}<^u)N>=Qur9v&hy&B$M1->>bOTnsPe+AdDjDHocTLqv_0C| z(H+d=X3H?M9mQ5KeX3{Ox{Tuy{gUu)dNwoL5&Dl-^!Ma<)f>O|*3Z^|qJGkPZqsu{ zg?dtbsWb^6J;BLc=Rbtmj-o4?ai%`yY`&rVd~(on$R*6Uqrc4R{vAH}YQFJ~yRH9( zo^+nd7WZYCdNvPNde*$6=9A%rliJ))jCSOfZGO|%jxG(TXNQhI)iV=NPaKbE{j_n; z6z!(7BKGhT2~tP z`fn?1N8EXvyO{lFVT7q?yIv7I6xTnJ=C-spZY~~#E;i14E99iy;De1`#_Q*~ z_jk;4I|%>lu*t1VJ)7S(pLY#D*ka22z8<PLO(2-~t0kCToQXxx$C8B9)RZIiQyj|{b~9mwP4&d;yNJv;Sxhs#; zuN_71QuTa2W;^PbY__BLIz(Rr+VC%4JL2j&oT+CQ;i5jlbRx@_pSQs{g!|mrm6@EG zbxr-KPdV#n@Q&|(&tpNpt1vlZ>zSO?M}DyJ-FWqr8~1aWoSlS|`rw0&pUJDA+~>ZI zU~;ysZ|X^X@WF<6=jqA4FLET4Gg@nMQXhP<%}maYjmjT4k>9FJ&JMy!edGsQWO8!b z`x;En<_%0esSiHbY>XFoZhK#o$yqmNG$H~=m6qB=VBa@T*;Dc>qa&q-to5|TuIH?al*mfo-w;ip+Pda@!Pf3sKJKgN4Y|k7_r>o5bIv=mpQ-CH;GjOzVWYFnaY+6n_5H>})$_E2j+fSB z>RH&t)RX$)gYCG_HGmw%@_IaDdEt#i-wUn>NDP!`J1stgFf^tnEF&jQxO~-1a`2sb}M6rk>PC z`LK0+^Wx5}pBpkc!<(C&)CV7Ifyv3OpBphb^MsT7;Dc@a15ZzG+&5-&Hf&+)Nqz9a z*6+jP^gDk?ew#2kLtC1h)JJ}>?OaZuc`)R+DU<IH`~PU<-#a^<;9^F*)hHH}$~> z8#$cE8Qz+AezX~rvu0~E?$ie#Y`(}lZiec4oLewCTL~xi!3W#H)RQ}2+LCZ~-eS(j zqTIwbrk>QtcChjHczSZ%`&NV#<@B)iCZ|Jv@`dCP-J!;jSs%{U z!_41p$^NR>3+w%HFI$m)ldkQ$_I2vIHv4|qrYfatk9hs)J?@C>`#b3Uur^NHb?xh! z>sYW3uoLSP$#ve^pS(G3>i}(>Ha%|$sAv3l-g@ROoPDL|jRE!S(wxv2RV?vyFg>HAAl+&LB$I1Po?uQIdH1CVFwRcPzHhUg+`nn#wCR~u z^|Le%X@A7L-iq=t?#OJbbcJ8~+``#c$IUwgC+Gfm^q-dxYGgjrTr>*~#bwa-A z{am)Vzvs>`g+!$;f8TEH&Sw3jzFTOwe>%@K=S#bN3Ju!9id-u9-}zngEO?0H)mh<^D|XDVvj@WcTk+PpU+x2ZT)=E z`uV=DpG`uTa`%H&Evu>!6{b$=KbcA!&*oDehGZscUBmr%4r;^Y`yleAF$Dh>b^6?y)fMD zuWjw<17_S2Z@aY%LfbwP+bt>?D-d9SLUzU$I+dzgAs zANvFAr+3hHbYH-BRJ=-^$I*7wP!p^j1&w>Zrb#`oXMH~#Jpb9Nw~oW+j(C3^`F?T-}WoeuRy;7{R;Fe(62zh0{sf~ zE6}e%zXJUV^efO83XB_{sFr`#UoD)v%Y;Prpo!{lfbe%dDN((&upbCJNZT512WvY- z+hw#}R@>#Y9jfg=CMBxn-@PZRKj)N0wfh%vCqn0ypNH_x?x%sC*U@`??>D{O1oOO} zZkH?^<0Lzep~=EuxKJiWd&^tBG>>;_wOwSoomWm}Bnu6Kw?U$jm*UOzmUkGFcelar zekGgjyzUc$)i`b>3lk7wMcM3_6Q^lk1f?+c2<%-h3zQEgXuhMjk5@wMoc z&s0aRvGeA8%lk5uca*9R`7*rnQdV(`+0~hCW?S{`>@DxQ%=%lawo6X3>nqn}6erHE z&QG@UM$YeL{TZ0D7b z(PvI@q92^lgBHhQj}Q8j`W5I`pkIN01^ypYKpr#YtN97Jo__J!&raUlk$;(#`pXL| z{}$-K$Ro>Dk2`g9C#r2y+l;n(Z6i}QcjRAG|GDtp{_!nm$WT>|wn=R>+UB+GbvZMp zs&ceVYMaqEuWfJ3iEev_TTW8jw6=L|i`w?KoXE+loT#=*Z8O^Dwe4*=>G2P^`;*Z& zudOpdrAJ_UTMsr`R>eo#q_!Dt^V;@$e;V&q`=f1MTW7pVkHGeJf369s{n0k5ZARO? zwtoAA{vfUUgT-Z0PNOboaoKKNgZnmjv|8`msBQKObNw&2Z#_z-$Cg*?beb*OVSC?x z=M7!ov`uQ8(KfHGUwnMa*;evG0UQTwB9QrnESd2M@L&KzBi zwn=R>+UB+GbvdW%81a_&;cv#7R7Z8O^Dwe4*==`jzwx@EM@YwPTw(j&0FJf5ac)a7WK z*Vg%)E(f-kT0aZBpBews~!P zUCta`ueD8To6$C}ZEwp-ub{`H+UB)&hUxJrtWQ0_IHBM6EAao40{KnGJMyon|1v`- zIMthucar)qBdq)@>c2?cct`#v^( z!pgsl{woSA{~}wczo@YCFRA}-5?1~>TdF^q|0wZ3t^YE@%D;E@Uvw++eesvne`#Um z-~X-GjFz*Vt)@Co*JBZPz6I8~=4@xUNUyu>z*%Q?vk{ptVCA)YnO^++3GU}nksj}s z9{XYqH@~DvUrD6Xe9|I)MUkHR>O}YZuyaNFRwDQI3l$G+{#w2L83(BCwRNtOJXKD7 zvf_Y^h;+##uMtSjYdwH@xb1) zj!YN(oz(lS?au4giv6f6@z$NQrmJgFq|5!zoUHa6cB%D5K7yF$lNRZ6zv=6Fcl#c$L_2^G-7~i-3iO6rU_9r6$C8-hEu%naef6O{F5?vvZ=iQ6U9UgPG%20a)B5#> zUO}wXTWX5qru=Sqy-VqOy$0%a=Y{=x2hkbZO1-6~?#~P9#O`{R()D^()a&H*e!Zb# z5G(bTn!1li@X))IuGib5UKcLz*E@*L*jDN-HFY0D;-PmbU9T5Ly^dbeM|yMDAp>{` zw^DDZsa%7MSNHy;l&;r1qh7aO+DCeG*HHs*3Aa*jsp+6@`_WzRQo3HRje6aDMIY(S zT?gKcZ%KYD^_H5t&*jrQBK2N+(wJ&FUzI;x%~!w?Z3I(pC!`cA`R(@ zYu0kV=bS#KTF#%K+^tcrPOp1feIGWe)8$xD=6}AP4->BY!uY!s2fe<()Q?=%NA;U~ z-vGdta4YM#)YN?}yxy1Y{YfcZ-=Bbfq_L%s^yc38u!QRje5tq8)P3H#hu)=h++U&V zb@A#x(i`~#=>Kyo^_H5-dp7XuUcXD}`u-5q>-e>Oq&N4z6TmIuR_ZM^#X2^*JKgmz zrR)1!P_OgX^^xA(`(~DKoq;d)mYT|YX7K8+cPU-ppVMdc8ijH1`@!~0xRrWKP37}f z@sfJe>kXOT`gs0Zs(?yObzjS?Gq{q9Zm#)u?bh#fruFs2f&+GFd zUFu!aq;!JK|7^KF|BL1NyhxWkIDaW!pBL$p2mGb$^CW$7U7ydt_m#Wu0q0ri>yLKp zZBeHe-cs>|b>0`-3*O|xDjjxhk=|YJ>@0PDmJ#W4|FGXE=Sh*isYrKnYCQz(zz@E1 zud63cQQwCxiuA!krS_*(xv(34D7UY2vOB8nVKX0@H0`2C-)1Xz#t5F)*M zJ*(H>d*0o?s^@x$gk?R1PN(~x73s3vt~=Cv2-xDm-s>T%5Aj|Pkre5YlfKfH^o&k- zJ7w`Dx*p>BZ#Hw+pJ1K>HvQdZqTVm62etR=btN)g8G?os*B@t`Q8PhT^#mh<@;mh*X;E(oAg>3m+KcR#;`-bs-z_3m*# zFVa2F=S8|aUyPm|QF>~dzteI)KhttPFVZCs^edgui}ddCFP+bm^u={PKO<++`w@%Y zGTlpWk?yItNcYrRqK!{r=?$BI&Z7787QIEfr`{snQ*V;K*z|6<=>3L8Z<+3; zw@CNYTcmsHEz&*p7U@#&=ChREu=zJFdcS4STcmsHEz&*pCh3b!?+%OJ3oLrebT7R{ zx~JYE-BWLo?y0v(mwM;)d@OAKQ;Xi8S@ag^o_dRPPrXU{;?ldv{K?<@_Zax z8Ik{zG#;E$bB_1@fJ4slz8_Ggd)04|?peP@x@Y|s>7Mmlq|5qUn5Oy@*!(hjdwM_M zvXaN+en64#S-(ZPXZrRm2wU_XY0+Dzd+9CGJ@pppo_dRPPrXID)Vt$yHBSqh zU)7@bY8Jgkx~JYE-BWLpzS#7xwdg(CqPI-<(p#i^>Mhbe^%m)#dW&?ackxVBzhUzm zTJ+w?qPIx*)LW!`>P^xYm)_6Td+Qz9)?4qWO!v?`Dbl_4PK$Iey)z=+OYaVmF7=L| ztMrC-w)fUMD$>3BlcY%Z(mO5Ez4XqI^u?w3jD)w|&LQ40Wxz73os%{P{}nl0DR0Z|5*?y(1#sOYf*i_tHB_(ifNB>Hmo9zung5;(BpLr{g*? zY+j}dy>Xow_I;7wU2j}3PQGMbx5f41Geo-A_2StgeJhbat`oy%UiQ9T{HaKH+ry6P zdU0Ia-g%u4onhY->D_gW zUZwUkdhypry=ikA-Rt~+66sP`%ws_BnIc{4+BjZ)A2xZ(*Wx~mDyM6Xx(*MU5$Uqu zz;$`pr$o9JPvla?gL0wwjw0QQ=OU3VdGd{l2R3@S%7@PXR3x^{|L$)Lz3b+y{VeKq z=nU)365EUKVZI9bjS}fz`<)i)vVLH{vHeXVUG6t@gZ)UP%l$5#uJ#+Y*!qp)>&uW{Cnm+^JW*bx%X~181zR=iohrFbtvFrJt7&_*NbjDH zv!=?YDAHv>BpU{pO1N$*k0s=?Hf;0>FbJgFCB^^y?eP6 z^!Aav=es%#5_w5IZF5IUn(!K7l%)9yYyifBzk-nAS#Ql)4(SMG0?~BBJp0MYLbU6=;`!iva zk4sLmUWnYM*(B0s{-I6P^HyLpPpJHx^mB<}^E#c*!^*ZN_m%td+m?R5xP30S-*yqb z!IE;EUtFBfVR8MA(2|mGzYgkn3LO?#eOprUg$_$f{asv~(4qMWRX_e$ZNCm?|Inb% zv;J2t>O)MQZ~w1ar~lQjK)(Y03iK<`uRy;7{R;Fe(62zh0*gg~+z`i^C?5D&BQ7qq z>IWikEYjplJPy)XOZ>@sZ}}X2y#~OY>!owD;^QUeRV^NJnU6Tm&4O6&-)`bh?ql09 z$2mb*`C487$@j;I53dn_M~L_93!Ro1R(`Ke{K@M(^0l2ZrFrmy`o{rI+3BTOU!CyV zgJ(XI7?XJS)^GG?&a(0%gLv&aY4@Yo7&LF4*KgYE?9hAD4^pX)v!)h!a?70b8QGPG zueH`$sfKGV5-a}IE3&e((;oZ%nkyWz=cC6ybmN;7$6t60KHo@A%8OTiqy1JHFy^5{ z_8s`vT~orh9ivhmXHy;Hr$2di!>=wXeEG*GZ-4sEr8l_-pKmDz5w9~Z89Aom^4R;w zt^WC#Wp*EVfJ$|otz?A|uYIS_nip!EdD~}=gAQD{;F*V2s^e@euFc5Tx_`d*rt7!5 zVY5HPj$L)F?`G&!$N8OnFt>Ppcc+1>ao79Ter-p5zP)@-^Fy?gJ0F}qxF z@1EEF=aF;IUT?}7o8j}_b^K<`m^|XPV2wTtGQn&^K5MEzz$_P6GiHDhC+{dmqd@63Mcq0;B?sdo=8H#D(e*r0s|jQMEd z7wR?#_k&6LVZ~E_IN{562Y$9-{4bCEb;yI4J&5n8^^QDx+Og|h`N&mc2j24i??-Jp zTwX46UrqYq(*M3{_1w_4-ui9tm3A7lvUAhE`1}I>W{>;dJ@Kox4*zi0oA;g-9rAGL z5y=*1)pbh{rutV^k=`^y~6GPyzL*Y=`El98K2*w>))g+ z_g#46+2_6f+#go{qEbFnw~ph9ej>JUOukz>Sa=2 zZvVuew>;^OU+g~{pWmnByJGU*Paa*l;j;_2KV@XqEyHEE;=bDT!yWab~Plbr{`>Rs`(Nws@lJ$c+E_pJHr4F~SKp!B(TR-}Ag(SFm(vz|FVJ>v9N zX5G8PQ?IL3@yx&x>fNu2mnR(ZmoYmG{ratQ-uUj+Gw}Jtx_`QVi#?7X_{qHUci8Xm zKW#nmsFFU9==jg-{2Q)7p~DI zW^~o-aoI_V*P##A+@DzWlGwB(8&(=Oe!V+Ys^dJNzklfb=G$J|d){hWk7|xjUO2GS z|2(ZXeCpxUjBl?$Z0Lq-T(`-pQ&Xk>?`h3{;EWr-jh(t+sci-xyUslyE{pElY18pt zdeuqy>UfSvP?f3Zh>Tk5_j`N(3^yK;b zx4f3ya{ZaR?)vViSH8Fe{4eM?Gw0m1*Wf>&Gxf8rM_;t_nAN_<=P!*`@8+DAzIO1J z)9-j{V#AcDhD?14pTDZ>_oJ(I-g3@f`yRPX-Iw|IMn3gw>GNIGyQMBZ<=JV2POG2y z@J_S$8ITr7DD`?xE(Q>SZUs@OT|Qe|MsKH~N9quUzi*q3yf3yx4HT zaZRZ9PKS=~X4}?Wz4tZy{q^5BZF|qqvz|Q$-(RqjdiTmlv-Vs2!lPRrUa-u4Rr&SL z!{=Y<_^kTtjq`rG=9T!y({}B8aM Date: Mon, 26 Nov 2018 14:41:28 -0800 Subject: [PATCH 23/31] pixy_parser: fix misc errors --- libraries/AP_IRLock/pixy_parser/main.cpp | 5 +- .../AP_IRLock/pixy_parser/pixy_parser.cpp | 93 ++++++++++--------- libraries/AP_IRLock/pixy_parser/pixy_parser.h | 7 +- 3 files changed, 54 insertions(+), 51 deletions(-) diff --git a/libraries/AP_IRLock/pixy_parser/main.cpp b/libraries/AP_IRLock/pixy_parser/main.cpp index 5cdf348744..2d78f670df 100644 --- a/libraries/AP_IRLock/pixy_parser/main.cpp +++ b/libraries/AP_IRLock/pixy_parser/main.cpp @@ -17,9 +17,7 @@ bytes_to_block = 0; */ int main() { - uint8_t tempArr = {}; -// pixy_parser pixyObj; - pixy_parser pixyObj(17, &tempArr, 0, 0, 0, 0); + pixy_parser pixyObj; uint8_t input_bytes[] = {0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x17, 0x01, 0x01, 0x00, 0x69, 0x00, 0x56, 0x00, 0x27, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x17, 0x01, 0xF1, 0xE0, 0x09, 0x10, 0x46, 0x00, 0x27, 0xE0, 0x00, 0xF0, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x00, 0x01, 0xF1, 0x0A, 0xE0, 0x10, 0x55, 0x00, 0x15, 0x11, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00}; //array of 15 bytes of SOF // uint8_t input_bytes[] = {85, 170, 85, 170, 15, 1, 1, 0, 104, 0, 82, 0, 36, 0, 48, 0, 85, 170, 144, 1, 1, 0, 229, 0, 86, 0, 37, 0, 47, 0, 85, 170, 85, 170, 23, 1, 1, 0, 105, 0, 86, 0, 39, 0, 48, 0, 85, 170, 23, 1, 241, 224, 9, 16, 70, 0, 39, 224, 0, 240, 124 }; //array of 15 bytes of SOF @@ -30,7 +28,6 @@ int main() { printf("%u, ", (unsigned)input_bytes[i]); } - uint8_t input_bytes2[] = {}; for (size_t i=0; i<=size_input_bytes; i++) { // printf("Calling recv_byte_pixy : %d : %u\n", i, (unsigned)input_bytes[i]); printf("\nNEW BYTE IN:\n"); diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp b/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp index b417661a46..01612f529d 100644 --- a/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp +++ b/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp @@ -18,6 +18,12 @@ * * */ +#ifdef PIXY_PARSER_USE_ASSERT +#define PIXY_PARSER_ASSERT(x) {assert(x);} +#else +#define PIXY_PARSER_ASSERT(x) {} +#endif + #include "pixy_parser.h" #include @@ -27,16 +33,16 @@ #include #include #include +#include // Constructor - pixy_parser -pixy_parser::pixy_parser(size_t a, uint8_t b[17], size_t c, uint8_t d, size_t e, size_t f) { - pixy_buf_size = a; - pixy_buf[17]= {}; - pixy_len = c; - blob_buffer_write_idx = d; - bytes_to_sof = e; - bytes_to_block = f; +pixy_parser::pixy_parser() { + pixy_len = 0; + blob_buffer_write_idx = 0; + bytes_to_sof = 0; + bytes_to_block = 0; + blob_buffer[blob_buffer_write_idx].count = 0; } // Destructor - pixy_parser @@ -48,6 +54,11 @@ void pixy_parser::empty_pixyBuf() { pixy_buf[i] = 0; } pixy_len = 0; + + printf("\n--------------------------AFTER EMPTY: "); + for (size_t i=0; i= 10) { return false; } - writebuf.blobs[writebuf.count] = blob1; - printf("SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); + writebuf.blobs[writebuf.count] = received_blob; + printf("SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); writebuf.count++; print_buffer(); return true; @@ -187,70 +198,64 @@ enum pixy_parser::message_validity_t pixy_parser::check_pixy_message(size_t pixy void pixy_parser::recv_byte_pixy(uint8_t byte) { // printf("INSIDE recv_byte_pixy:-\n"); // Read 2 bytes - pixy_blob blob1; //%%%%%%%%%%%%%%%%%%%%$$$$$$$$$$$$$$$$$$$$$$$$-------------- should I put struct as prefix or not?-------------------------%%%%%%%%%$$$$$$$$$ + //%%%%%%%%%%%%%%%%%%%%$$$$$$$$$$$$$$$$$$$$$$$$-------------- should I put struct as prefix or not?-------------------------%%%%%%%%%$$$$$$$$$ struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; printf("The byte inputted is: %u and pixylen is %u\n", byte, (unsigned)pixy_len); + + PIXY_PARSER_ASSERT(pixy_len < PIXY_PARSER_PIXY_BUF_SIZE); + if (pixy_len >= PIXY_PARSER_PIXY_BUF_SIZE) { + // This should never happen. + empty_pixyBuf(); + } + pixy_buf[pixy_len++] = byte; // Append byte to buffer enum message_validity_t validity = check_pixy_message(pixy_len); // Call parser printf("Validity Check Call: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); printf("Pixy Len: %u\n", (unsigned)pixy_len); printf("Pixy_buf: "); - for (size_t i=0; i<17; i++) { + for (size_t i=0; i= 10)) { + pixy_blob received_blob; + received_blob.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; //Extract blob information + received_blob.center_y = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; + received_blob.width = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; + received_blob.height = pixy_buf[14] | (uint16_t)pixy_buf[15]<<8; + if (writebuf.count != 0) { swap_buffer(); //swap buffer - blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; //Extract blob information - blob1.center_y = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; - blob1.width = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; - blob1.height = pixy_buf[14] | (uint16_t)pixy_buf[15]<<8; - writebuf.count = 0; //Turn the count to 0 - printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); - - write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) - empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' + printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); + write_buffer(received_blob); //Writing inside the buffer(the count increment happens inside the write_buffer()) } else { - write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) - empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' - - printf("\n--------------------------AFTER EMPTY: "); - for (int i=0; i= 10)) { - blob1.center_x = pixy_buf[6] | (uint16_t)pixy_buf[7]<<8; //Extract blob information - blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; - blob1.width = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; - blob1.height = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; - printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); - - write_buffer(blob1); //Writing inside the buffer - empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' - - printf("\n------------------------------AFTER EMPTY: "); - for (int i=0; i #include +#define PIXY_PARSER_PIXY_BUF_SIZE 17 + /* pixy_buf_size = 17; pixy_buf[17]= {}; @@ -24,7 +26,7 @@ */ class pixy_parser { public: - pixy_parser(size_t, uint8_t[], size_t, uint8_t, size_t, size_t); + pixy_parser(); ~pixy_parser(); void empty_pixyBuf(void); void print_buffer(void); @@ -57,8 +59,7 @@ class pixy_parser { const pixy_blob* read_buffer(size_t i); enum message_validity_t check_pixy_message(size_t pixy_len); - size_t pixy_buf_size; - uint8_t pixy_buf[17]; + uint8_t pixy_buf[PIXY_PARSER_PIXY_BUF_SIZE]; size_t pixy_len; uint8_t blob_buffer_write_idx; size_t bytes_to_sof; From d43345328473aaf338699b16845b65f56764834d Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Wed, 28 Nov 2018 18:24:53 -0800 Subject: [PATCH 24/31] Integrated pixy_paser with the firmware, still doubt the integrity of the output vals(x,y,w,h) --- libraries/AP_IRLock/AP_IRLock_I2C.cpp | 164 ++--------- libraries/AP_IRLock/AP_IRLock_I2C.h | 20 +- .../{pixy_parser => }/pixy_parser.cpp | 10 +- .../AP_IRLock/{pixy_parser => }/pixy_parser.h | 21 +- libraries/AP_IRLock/pixy_parser/a.out | Bin 30320 -> 0 bytes libraries/AP_IRLock/pixy_parser/main.cpp | 37 --- libraries/AP_IRLock/pixy_parser_old_working.c | 274 ------------------ 7 files changed, 55 insertions(+), 471 deletions(-) rename libraries/AP_IRLock/{pixy_parser => }/pixy_parser.cpp (97%) rename libraries/AP_IRLock/{pixy_parser => }/pixy_parser.h (95%) delete mode 100755 libraries/AP_IRLock/pixy_parser/a.out delete mode 100644 libraries/AP_IRLock/pixy_parser/main.cpp delete mode 100644 libraries/AP_IRLock/pixy_parser_old_working.c diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.cpp b/libraries/AP_IRLock/AP_IRLock_I2C.cpp index c320a40c44..8e89667117 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.cpp +++ b/libraries/AP_IRLock/AP_IRLock_I2C.cpp @@ -3,12 +3,10 @@ it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. - This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. - You should have received a copy of the GNU General Public License along with this program. If not, see . */ @@ -28,9 +26,9 @@ extern const AP_HAL::HAL& hal; -#define IRLOCK_I2C_ADDRESS 0x54 +#define IRLOCK_I2C_ADDRESS 0x54 -#define IRLOCK_SYNC 0xAA55AA55 +#define IRLOCK_SYNC 0xAA55AA55 #define IRLOCK_SYNC1 0xAA55 @@ -56,88 +54,6 @@ void AP_IRLock_I2C::init(int8_t bus) { synchronise with frame start. We expect 0xAA55AA55 at the start of a frame */ -bool AP_IRLock_I2C::sync_frame_start(void) { - printf("\nSYNC-FRAME-START():- "); - - uint32_t sync_word; - if (!dev->transfer(nullptr, 0, (uint8_t *)&sync_word, 4)) { - return false; - } - - // record sensor successfully responded to I2C request - _last_read_ms = AP_HAL::millis(); - - printf("\nSYNC_WORD BEFORE: 0x%04x", sync_word); - - uint8_t count=40; - - int temp=0; - while (temp < 9 && sync_word != IRLOCK_SYNC && sync_word != 0) { - temp ++; -// printf("\nTemp: %u\n", temp); - } - - while (count-- && sync_word != IRLOCK_SYNC) {// && sync_word != 0) { -// printf("\nWhile Count:\n"); - - uint8_t sync_byte; - if (!dev->transfer(nullptr, 0, &sync_byte, 1)) { - return false; - } - if (sync_byte == 0) { - break; - } - sync_word = (sync_word>>8) | (uint32_t(sync_byte)<<24); - - printf("\nSYNC_WORD: 0x%04x", sync_word); -// hal.console->printf("\nSYNC_WORD: 0x%04x \n", sync_word); - } - - printf("\nSYNC_WORD AFTER: 0x%04x", sync_word); - - return sync_word == IRLOCK_SYNC; -} - - -bool AP_IRLock_I2C::sync_frame_once(void) { - printf("\n\nSYNC-FRAME-ONCE():-"); - - uint32_t sync_word; - if (!dev->transfer(nullptr, 0, (uint8_t *)&sync_word, 4)) { //I think this conditional makes sure if the I/P byte length is atleast 4 bytes - printf("\n1st condition FAIL, frame END"); - return false; - } - - // record sensor successfully responded to I2C request - _last_read_ms = AP_HAL::millis(); - - printf("\nSYNC_WORD BEFORE: 0x%04x", sync_word); - -// uint8_t count=40; - uint8_t count = 0; - while (sync_word != IRLOCK_SYNC) {// && sync_word != 0) { - count +=1; -// printf("\nWhile Count:%u\n", count); - - uint8_t sync_byte; - if (!dev->transfer(nullptr, 0, &sync_byte, 1)) { - return false; - } - if (sync_byte == 0) { - break; - } - sync_word = (sync_word>>8) | (uint32_t(sync_byte)<<24); - - printf("\nSYNC_WORD PROCESSED: 0x%04x ", sync_word); -// hal.console->printf("\nSYNC_WORD: 0x%04x \n", sync_word); - } - - printf("\nSYNC_WORD AFTER: 0x%04x ", sync_word); - printf("\nSYNC-FRAME-END!"); - - return sync_word == IRLOCK_SYNC; - -} @@ -153,50 +69,45 @@ void AP_IRLock_I2C::pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, fl 4.79331390531725e-6f*((pix_y - 100.0f)*(pix_y - 100.0f)) - 1.0f); } -/* - read a frame from sensor -*/ -bool AP_IRLock_I2C::read_block(struct frame &irframe) { - if (!dev->transfer(nullptr, 0, (uint8_t*)&irframe, sizeof(irframe))) { - return false; - } - // record sensor successfully responded to I2C request - _last_read_ms = AP_HAL::millis(); - - printf("\nBLOCK:- \nCRC: 0x%04x - SIGN: 0x%04x - X: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x", irframe.checksum, irframe.signature, irframe.pixel_x, irframe.pixel_y, irframe.pixel_size_x, irframe.pixel_size_y); - - /* check crc */ - uint32_t crc = irframe.signature + irframe.pixel_x + irframe.pixel_y + irframe.pixel_size_x + irframe.pixel_size_y; - if (crc != irframe.checksum) { - printf("\nBAD CRC 0x%04x 0x%04x", crc, irframe.checksum); - return false; - } - printf("\nGOOD CRC 0x%04x 0x%04x", crc, irframe.checksum); - return true; -} void AP_IRLock_I2C::read_frames(void) { uint8_t buf[142]; - dev->transfer(nullptr, 0, buf, 142); - // printf("\nSTART: \n"); + dev->transfer(nullptr, 0, buf, 16); + const pixy_parser::pixy_blob* temp; - - if (!sync_frame_once()) { //It just sync's the frame - return; + for (size_t i=0; i<16; i++) { + pixyObj.recv_byte_pixy(buf[i]); + temp = pixyObj.read_buffer(i); + printf("\n\n\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); } + + printf("\n&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&------------------OUT"); + printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); + + +// pixyObj.pixy_blob* temp = pixyObj.read_buffer(i); + + + + + + // printf("\nSTART: \n"); +// if (!sync_frame_once()) { //It just sync's the frame +// return; +// } - struct frame irframe; +// struct frame irframe; - if (!read_block(irframe)) { // Try reading blobs until I get a sync (Nope! does not work!) - return; - } +// if (!read_block(irframe)) { // Try reading blobs until I get a sync (Nope! does not work!) +// return; +// } - int16_t corner1_pix_x = irframe.pixel_x - irframe.pixel_size_x/2; - int16_t corner1_pix_y = irframe.pixel_y - irframe.pixel_size_y/2; - int16_t corner2_pix_x = irframe.pixel_x + irframe.pixel_size_x/2; - int16_t corner2_pix_y = irframe.pixel_y + irframe.pixel_size_y/2; + int16_t corner1_pix_x = temp->center_x - temp->width/2; + int16_t corner1_pix_y = temp->center_y - temp->height/2; + int16_t corner2_pix_x = temp->center_x + temp->width/2; + int16_t corner2_pix_y = temp->center_y + temp->height/2; float corner1_pos_x, corner1_pos_y, corner2_pos_x, corner2_pos_y; pixel_to_1M_plane(corner1_pix_x, corner1_pix_y, corner1_pos_x, corner1_pos_y); @@ -212,16 +123,6 @@ void AP_IRLock_I2C::read_frames(void) { sem->give(); } -#if 0 - // debugging - static uint32_t lastt; - if (_target_info.timestamp - lastt > 2000) { - lastt = _target_info.timestamp; - printf("pos_x:%.5f pos_y:%.5f size_x:%.6f size_y:%.5f\n", - _target_info.pos_x, _target_info.pos_y, - _target_info.size_x, _target_info.size_y); - } -#endif } // retrieve latest sensor data - returns true if new data is available @@ -240,5 +141,4 @@ bool AP_IRLock_I2C::update() { } // return true if new data found return new_data; -} - \ No newline at end of file +} \ No newline at end of file diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.h b/libraries/AP_IRLock/AP_IRLock_I2C.h index beee279b2f..bccb507dca 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.h +++ b/libraries/AP_IRLock/AP_IRLock_I2C.h @@ -5,6 +5,7 @@ #pragma once #include "IRLock.h" +#include "pixy_parser.h" class AP_IRLock_I2C : public IRLock { @@ -15,27 +16,14 @@ class AP_IRLock_I2C : public IRLock // retrieve latest sensor data - returns true if new data is available bool update() override; + pixy_parser pixyObj; + private: AP_HAL::OwnPtr dev; - struct PACKED frame { - uint16_t checksum; - uint16_t signature; - uint16_t pixel_x; - uint16_t pixel_y; - uint16_t pixel_size_x; - uint16_t pixel_size_y; - }; - - bool timer(void); - - bool sync_frame_start(void); - bool sync_frame_once(void); - bool read_block(struct frame &irframe); void read_frames(void); - void pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, float &ret_y); AP_HAL::Semaphore *sem; uint32_t _last_read_ms; -}; +}; \ No newline at end of file diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp b/libraries/AP_IRLock/pixy_parser.cpp similarity index 97% rename from libraries/AP_IRLock/pixy_parser/pixy_parser.cpp rename to libraries/AP_IRLock/pixy_parser.cpp index 01612f529d..e528668623 100644 --- a/libraries/AP_IRLock/pixy_parser/pixy_parser.cpp +++ b/libraries/AP_IRLock/pixy_parser.cpp @@ -1,3 +1,4 @@ + /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by @@ -111,7 +112,7 @@ const pixy_parser::pixy_blob* pixy_parser::read_buffer(size_t i) { } // Method - check_pixy_message -enum pixy_parser::message_validity_t pixy_parser::check_pixy_message(size_t pixy_len) { +enum pixy_parser::message_validity_t pixy_parser::check_pixy_message() { // printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); if (pixy_len == 0) { @@ -202,6 +203,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; + printf("The byte inputted is: %u and pixylen is %u\n", byte, (unsigned)pixy_len); PIXY_PARSER_ASSERT(pixy_len < PIXY_PARSER_PIXY_BUF_SIZE); @@ -212,7 +214,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { pixy_buf[pixy_len++] = byte; // Append byte to buffer - enum message_validity_t validity = check_pixy_message(pixy_len); // Call parser + enum message_validity_t validity = check_pixy_message(); // Call parser printf("Validity Check Call: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); printf("Pixy Len: %u\n", (unsigned)pixy_len); printf("Pixy_buf: "); @@ -248,7 +250,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { if (!(writebuf.count >= 10)) { pixy_blob received_blob; received_blob.center_x = pixy_buf[6] | (uint16_t)pixy_buf[7]<<8; //Extract blob information - received_blob.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; + received_blob.center_y = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; received_blob.width = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; received_blob.height = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); @@ -261,7 +263,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { if (validity == MESSAGE_INVALID) { // If message invalid, wait and read 2 bytes pixy_len--; ///----------------------------------------QUES---------------------------------------------- memmove(pixy_buf, pixy_buf+1, pixy_len); // This discards the first block of the pixy_buf and makes pixy_buf have everything except the fisrt block value - validity = check_pixy_message(pixy_len); + validity = check_pixy_message(); if (writebuf.count < 10 && writebuf.count != 0) { swap_buffer(); //swap buffer diff --git a/libraries/AP_IRLock/pixy_parser/pixy_parser.h b/libraries/AP_IRLock/pixy_parser.h similarity index 95% rename from libraries/AP_IRLock/pixy_parser/pixy_parser.h rename to libraries/AP_IRLock/pixy_parser.h index 7375aab1d5..46412bd98a 100644 --- a/libraries/AP_IRLock/pixy_parser/pixy_parser.h +++ b/libraries/AP_IRLock/pixy_parser.h @@ -1,3 +1,4 @@ + /* * pixy_parser.h * @@ -26,20 +27,25 @@ */ class pixy_parser { public: + + typedef struct { + uint16_t center_x; + uint16_t center_y; + uint16_t width; + uint16_t height; + } pixy_blob; + pixy_parser(); ~pixy_parser(); void empty_pixyBuf(void); void print_buffer(void); void swap_buffer(void); void recv_byte_pixy(uint8_t byte); + const pixy_blob* read_buffer(size_t i); + + private: - typedef struct { - uint16_t center_x; - uint16_t center_y; - uint16_t width; - uint16_t height; - } pixy_blob; struct blob_buffer { //Frame (full of blobs) pixy_blob blobs[10]; @@ -56,8 +62,7 @@ class pixy_parser { }; bool write_buffer(const pixy_blob& blob1); - const pixy_blob* read_buffer(size_t i); - enum message_validity_t check_pixy_message(size_t pixy_len); + enum message_validity_t check_pixy_message(); uint8_t pixy_buf[PIXY_PARSER_PIXY_BUF_SIZE]; size_t pixy_len; diff --git a/libraries/AP_IRLock/pixy_parser/a.out b/libraries/AP_IRLock/pixy_parser/a.out deleted file mode 100755 index 6a4dd3bc153d1c7de0bd49da667bb95a2b995281..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 30320 zcmeHwd3;pW+5f#W$;?0?2?;wY69qvr2?>F)1+ooHlt5%r+&X5NEShBEECF096{4mX z8(R0;ifi3orEjfL(F%wGv`cJVsI`6bwxB_5n^y6qZv4LAv)s%~lIo|Q_mAKE`EVik zIp^8VbDr~@bI)^U?w#vB%a+(o)6j?ASY)u)>6Dm4McCe?3IK)1Tw@r{XBej&4%8C_ zPSOh{0978xm1+%L3U3Fb++3SP#KTh*pN85(!bC+I4D6gNu^JkNTOcS$TU#4Ps>k#-?hQPD;gW1C{b>lDoSP#Tt{J$ImPd~fy7k?}O!X1xf z9pe@X*Hq7#!LgcS_hhAtK(l{!WmThJ z(gvsa>ejFKwfKXfKyzhdLwJL)btW6CtFHEi*iMe&ThqL*p}EGl(jSU6`AMvn2DC)N zAy@$es;~4_*I((Yt!!vCfUT~t3>q!LhURcB=+)~heYFkLezo6d@;5aFT49lodX(`^ zl?~0t(vlM2tgM+v$=bC=#bv&ntXam=Wo5-BzTB)ltCX8H8;-EypIw}7A|ey5_@tXm z{JR2B`?uoE4M|*i{){kKnFiDfClcwbOSw;4AnI#Ht=8b&hW|DkY^i4DVO z!{;R8(Cd(1KRQ)my;^THzCsmTGu=W?<8}RDw#0KS(DRLqJyCcqLws)(emD{8=!?Rm zBQ8{IHyc5M2Yo!(vS3M zxBXAvO^5m_Rxj&F96ri0yd5LIhe-2w6ubwn6JxR<^Kr`LQh_=jl{Mau#4X z!{G_&qK#E_apYwudTO&$CT|w{FMFB2>aRoPC^B};9xl|J^(ExJyT7!1+xxt`dl!4n zF7NAKhQ~wUfoW3V2r3*(-^PO7U^61w-c1GTSXx7SMtHXr+=E*0NOZZ^i&IzP-Kd*1 zXCn>!=w+xxf5?8>ky>!Dw95Of5ATAnYrI<$rcMW&x82j5v#YDE?#mM=VD#;T-j247 z1Q^*XjG~`WThR`lMe*lwAH??cCSy!6)~Q`>E!5uCb``+mU2Q>G3&~m-Af>A<0$_Hv zwMwuK!02jQ4^ZFLwn5ge23XnEc8#oE3oxat?K)ZeCcw?W^{ROJly5E3Gn6%x;*WG-=5m#*#dY=c9*9E@K(ru2XdW&TLHg2uFLa1 z$liv(+d;phq04h8;9Zcv8}OcKU7qg)-aE6)^8>&iLhe4uZG+tXka^(mU7iPfx;zgJ z>+(FD+U0pGJ#{;36`ES5KP3iLd8Sv1|F3(}ZyRU6M!lsqsv9GNjMaGPGizs>* z2;#at#2CXxqs{J=XN{C+ceQt6;%vr>E&{FhtVVs?8I>FX}~!*kp``i9`$CwM8UHE;URjXqJR zH|5!lvOL20983;5x@9j9%xbaM3j^2(?T@b8Ql9IU^$7SA@VBd|{kVvnTC1sh|B0qH zdHT$wcSzpC3c+!q#c?$_Iu9sc>E5+RdcYplLm`xJ33;eChT&_tK=cJY-E@3dt5bO5 z=ylSliV6wK(dsa7`v~@{C*`?9xS&rJRqu&a9Y@g+eeM&+?ZNg!y7$rJ!ZbT6=Z7L#MoAU1Hpg=8LeOIx497MYUbQ26K!aSVluA)l z4LaE1q(K|}!lg&@wPR=y-Wa)#t{O>^UZ8e}9by-vI>wrmwhvTWaIthjO558+brcMv z?2}4eO3IB)VS%1V^zA^`?(-Z12J4iAlug(5rL0?mB@KS^^jQn0xL$F-_IW$JoN5@% z%`T26*2UdDu3_D^*i)rE=jp9AJ%_jy*^d51+4zFsqA(-i#aNjSAoD@(0?#2a&ac7& zy(d1_c-?Ah+e*h)ezlWS}f)n{k1Y5#|? z8BZM#x7bAu*2hHJzjd4Z#ccL6O& znYG=bW<@qHPekvDVR|{1=^u(|ZwwRH%cywySTSJ-64l(kSf)?Fgx!q1NFa(n!37fF zV{8oo{(&6@L-TRd+t0Q)1%J8w@YlVe88U04xB)S$Ow=%-jZzUagFc-}CNzKBsu zNNHOcJto*Eq})^}G4%1zV?6UxtY`Ebp9ChGtRfX zvdFR6*Sngla7RJF;y?U1`t~6D0^c4S(zgc(`gT87583AZ(6PyLQ2N$PX}cB5qKBxX zLbcyNjn&qebM0GusKwh6#F~z3$G1fl*Ua``_ud4}Qd7UEj3_4}3M&AJ)-)_TK9u?rr-^*q!rxeg9xt`=`s=KPhehThWQp?|L`A zYP-5 zGgf&#?$zG1Rhc-TWDxb#W*Dp1RkpMYP$;ne8h5|KmHx__0c;vs8w@n5mX|aHLt%GS zW1#vOgZ%j6hM*paQE_EOD2t zD6d%NS?$R%miuAe)QGz&5cIpNHiZ2l8e1J`YH9R`{q9OP*oPa%%T|<}7bRtUwOlbx zA8u%Sm-(CP!u9S(nC}kPS2nwI@?v_UThtxOb%!=ISBKn{t++kR+tKbybT5Rv!R|!` zLRj{^qGA08=yop+`YUk*Tj~x3-Ttd0m5uC5&K&o;2DGdcp5v~rY^;tnR*KQD4pwL3 zFiKXIxR;?8it{psFq-$ zwV_5LL|m?}m&4$0XvRJ9Fbrx432t`31)Xg~XB$FRd|tpPz#VvZNxdJTQc~I22=*HH z^qKShO)bFZ%x{pP;?6}$yV*T!zK9#Xr#)b4aU@JB&zU$hCkixTCTjum^A#AP;`N#lyUMrD3j5H7AX5x;jl~D)IbiZ#-<7K?ZdU&Tkk~ zKqr6wkrO9c$eWzHBzgR~DM{;G8;!*i7o0t7%IQQ?z7&7k!H0dCbx@Xvd3D7yVTtqm zr>41$NzxvvpKW{>_Eg#N3C5l1Xi;+Njkc1J4(}$reT^NKOB)^n-!J|mZ<$#JdLigc9{TkkwCGbn{}l9NG4wu*UJ80Q z#_o|A`u!HY2J{Osray_HKV{K3gZ=^Nh46#bzI}mk0R8w7=*$j2O^Bu+OQ3>Mp!R~^ zhYPG9WurJb^*grWBCeJNOo>`PUy*Swo zKJXVOyTs>7BM?L5vAeM+BOYE6hrdbH^>^;XXMVup%Ov7>X1s(G zR9%0caFVL)djb-89f~e)QUT*q9T2%c z>dG8rjAXaYN{!K}zMrRa+)l-z?}OkYBXNvV@N(6##^0+JeE4uw9J>9}R9*Ao z7LDj1%oQkn)j-t8D}DH`kEm-qaXUcN#b=bzg|s||uGIgp0sX!5c!g)Gj?YnWiGmj> zSgT;Gg7NZSRoCAi)qMCO?R@w2HC4Dr9&zVq;XAdNx%m-M&G}}|+^m^-XGyei4n*WA zN*~{&T+O>lgB_CpVFa>d{9J|1TpikRLiYpD8!n8o4vbR59Z<|$G=nu{GhOB2vDuub zAz*9?&ZjWYHkb1;0@J}eDE1A|W}BJ`g*IDaF)H>0q)y8NCLtjaUpR(Dq8%;RM^ecx zVG!&)SnOai(dBU6O=;6{0rWXpcDT0T?0gs}7rtJNY56#G4$Fp;gfE6Ce8JD2lkC^m zz)?x|jkgJK<8V-u?CsM8xTQ#djtd01^-2N0vr&Mpj|*_yD+1i{djanLM1Xrnp$AF! z@0SShgK7b`Z5H6cI|O+60RbL)Mt~o^A;6;_3Gi4Nx{zdlV!8lNE*GHhHDTbfPtb=X z`zH+od3>_~|9o43Pwy7svmF9_{&xUl#AP@ooEQb+k)r3OnVevnKNVW`OPvR$vOh~@ zhoqLnQp@{NbuX2r)HJjj_BS7ZMhd3x)hCV$%83VyL9)5+KZ6%+sR?|(!j_QGz>#z% zOhDg&91SqaDBmFg&Y3kGnEB!4Lf zUGaNZb{TeB>R1wx{N-a18#GYzFK1EluVC55c={3r`&ckKD(*uOG0EGBqi=@!j;Zz| zKsj80!+8uXV(_I}Cs2j~F?QTa^v6+QBZr$DJb`#7!1xKTlDNi3Kn8}BWSE%4R{c3p z&frRY7*u0o36b^WWT+{mm&hyGM+Tlmj+;Z7bin35=k)k`Cw}NhryN)^^7H;tp%Z5@#iJn5si=cH}IlKBpAJciMv%Bqmz@QD7E zQknw<;+!m0lAQTsm37YLL`ZVZ6RWIqK7&2Uxlk;3&P8ICbry*>1OmdcrRo3Yd ztE_XWSY@4FvAjCZ70avhJh8kwmx<-oSuU1W=W?;UIxEET>O7yz>*QBqkUI;dgRWz1 za1BhW1H$!*Ff@%{kaK;;p>w6p#;CYH7sHt5CjJYS$EWqM{3Xlov`Xl4onU!-#zION zCMz>DUPFIfrl`!#IGYrks1#+ z;u>$>4Q-n;4zic0n2(`ybHFIdSEm2DZnWhGlw9?f`% zm6@WlJ>$Pw$u$}AJ2JjYN6iwp?aJ6gLuZ>$qn*9R>7!`EJ?`hhG2XR}olGkw_x&sy zX_wHB2iRR#+5&d>5e`o(Cefw9Ib3f-*%`d>)9fk5C=koh6xf$EHr<$d5&Cx~S9aH8 zllU`7(8NMnew0QPiSo2X;2Cxk+niR2CWqZDirkXsvI=gzK^U8s!>s#(gmA zK5(bifqTT1^H4O>T3DXSvMp^Q_(z<{aza`!m`6-w*NL^< zXlukd9Eb|zY#)F#fotQ4nID65#wDN{Gp2&yobeorwi#Pdw$F$FpJ1d>>4?nl2t_-o zXdxACPfKD01@{5JBQ2j+EF!);Eg$1GVsRlfA57cARtkylNqd5NidgQoe@y)JD)2bH zNL$XK2S!Y4hjz0O^-la{J`K%s@&Bn+qSpQk0`|Ls zS%0Gs=Kcds?gV8P{uWsrdr&g6{z!A?1!41k)Ystea*Kn0F|yBP6Z0PgAIC5hOEu1* z!#EHk%7+z&=9&!)Hy>g0K(xS+Gg6$hJiC(tI#2bIOn+0j+stZ#qZzE zd#}S*KbN1ho1-ai-}?5oxmmE$97~<{t$o+#UJHHZcrx0z_IxvU9jlYr5Bt{MYjcls zP%=6cbygzG;;}*k<1!HP8VvJPDRA&wWAHnhPoj7KOG!#1ofw;`Yyd`ODl9r&PS+2~Br}yn zmYuGLaZY?3CzYu@4U_sam0chpQ)xg~kg0HAoMgW-1wBEga*hDEED@mN5&>>)5#T#* z0&IO+fZJXb;Eo;v?*2@Gd&Xkuk*RnE_yM1ZOR{fk7vRC~3-Iud1bF0U0{rNA0zAsx zJIVgoI1DZ_l}rJiTqQtXw=nS7XXpbmm1coF-Y&pD-xc7~9}4iVNqu)EXQXm4*?gKsr(fvr|V;!MW*7y(56}^Q23Z#Or|oG z96W(I17JX=!f=udDpO&?!Qe_|kVa=J3^j$6nF{;Jz>`RwsqmR@#$mr*sT^r}`V&f4 zrb1UURK+e)ZWVQ=!fPqRSE*K+3VqFJPG!sD6qBhi!i9in%gR*P`W%wPiM^6^r)wdw zDpN^hIXY9}1c{f>nF?o3D*GAVGo7h$KFJOZmZ@-l#bhdU`EQ97#<7Iaq6<`}!tQb! z_S2>Es7!^^GoBossc_y3x|ONWExcQk%7#)!i72$pZFY2~!l@{^=p-vs;e6xtjGA*Q zQ(-W3#>xg&ra~m=Z@iT%Q~5o}oYw=$GE>P0ne)A$tTUAYP*QP)j-nt_5o@M%hFCM5 zSz?)U&SJnJQ(+iIXDVfs7TX78Dzi{QrXp5Z=UlPMI_HU1);V9Svd)EKxpOWOtE{t7 ztg_A$vC2A2#VYIch*j3PRIIX2uUKB4=ZfXkd7fBaoy)}X>MR$_t8=+nUY!+Ud3B!8 zK{6E%oz7ImFse+2Wu2+8tTPpstxSa#D^p>`%2ZgfG8I;=OobIIQ(?u* zRK5!ftxV-ERK7;0vJnctMyB#ZXtOevr%1J`aZXgGG8WhjO-ZFy(V5CCpv=WziN)~?l%g}0-=Kam z{`?jP{Suw2a17VSQjIg{Fb;%>a%3uu5)Oc_3l+ed~_vXWfd5xs&?rTc5c;?-Evj z&SA7|y*%$M)^<_Iwsmcuo3&Ti7u(ilv*(Q#`i(*f3_sHhq$3B|dE3?sWA=ZkPt(p- z95*SB_e3VJwbaO8pgu3t9F+g3q{=l61L}P^2Q-Ih>oLi3fo$t3S^Gx*w-j@9TaU}O>hn7lF}AHIr0k_s zpTnRuFZ~O;v_$#lC#qTVUSdZl$M|OLT=eBqH9&daqUk<4y7fj5r;U03JV0pFcsF5Tqmy4&r<@h=wtbYm1pR6*|7Dv@e%@&`xYc zoc8=16&r64@}RzKHBgvrT;t3c#^n$T;ctPSVhf7l<1hslQstMpy4?d9RNByWahUfK z`yl=bsKU0j-k5(GRc07JLH#5ASt=J*0?n2eRiVJubWyd&)S$qryvVOHwW?q&rgnbp zIu^OVPV-x>_K7WETWGuB1pzNFctyaq1-}xoqTp=-mlgB~SXgjGKnNyR~lkCZp zl1G_o&Qwfm+Y}=yX%SFZSjHOm+!&*%2eH$k^zTggE%!E8t9@k^Q1E%v>44{7o-rdS|X-rpo?eOVwyTT0o6rG z98f)kGp0ik?*yJ>^#K0PO{cdr)wlVdmtLuhEx?aIsMeKbOvAH z_&bWl2;}zLYa7qIjfm1TC;gEJiW*o_W=jetwQvGgj(;(%$*t)&Nb;epc65XI8{VAv%)D>md+|eI;yHdntq=X8|?Wy*yln))FhafWyUvq zr<_OgHN~AIC*%Tc2d-*aW=?u@a=)ocrXbPC5q2%=Z^bYc55kSf_9*US+KkmWo91W9 zBXKrSHdxP&go4?4?yoUY zzHGeuZ=m{o-ExdVd|v?%-DXv{w7^CqyrIP(%BrWa)%Ye2bn){RG=b+?Ya8l7!DbYM z8h|>G%lHW;=V-gR1`V zPJx)7@}NDi)}H1{vp2gI0(K&|FwI_W?u|?S&x}>Hcm6L8nckt<-KOin;r}@N_Tj^e zZz$h{p|Lw|-~c&X=>)C?>kcp8X`7ku8XZM@nf_k}riF)ukk z!}wwr31IN~n`?|FJnh{qFzfJ;zF**~`E;{S#A1_t0-kR&ZI0kQq3aD_ZDVB}UMgB0 z3Hqu7jgh8iV;$cnidKA0mBB0Vo>D_R+U^Sne4zl$;HuEf=6x40pJyqWh3_+Yps(Ds zYE{uvkFRXGeoo$~@mDu;rJCLxX>4o>2hTEs{_0jAwF;}yonSZsnjvh&lhjqzos$za zeR6We+fCU|ysE&{YJ~9409BLnjWr538ori5h&~EL!f;49u&!EoBvjcd9inX%k53!5 zje*LrQO!3TSk_-qw5+VuC!X9NU`k1zr>Ua8slKVn!24e7+~O2z4mH#@`|-p%w8(B? zMEJ-(e9iSTXAV8ek;1!MBQU)(gg3i3@>^h);Q;!MH@0Hv0tQC3r3l{rW>oJDD&n{Y z@g%#kuAwGeFLdF#{Tiu>%qyy{FsefS%3yUpdyhA~Vw~1Piqaeam?AoxlRFo$g%$5Y z@QEkc`4(DO7w_{Nsb9Jran=;5@f)*YGMG6^+W%I3h=<^XWioX7jl{4US49FGj}Qk0 z5eHw$7!|HyHP@Ge_tU~~UzBI*&?q9tlyBZ$;S-}NM5_V;xR24ClOui4Igni+X!2)Q zUKy&d+)#DJ%-r0Z>{5T|%5b11o6f2b*R19Kb+I++Y4QF55ukkCE}#3ygs5#sx2>yh zY?5&#q1J&h5JH@l|yydHWF^)@T|qXLk@ zDU47{NG+B?L@7d5Eh&8Sw!37;jGR3AJ#KeqQ#jJ>FR1flA#A8dm6NVOzSrBGS?A8I z74K-y#49So{_1cbmQ-Xv)Z!})4)?B`or#Em9OWEpXHiAu&JE9*oE1HRVL1woLMnJLDTvtF4|?t!_+x> zuo3eh67n<6E ztR&U-!8#$RUtQv_5iycugzFnHyW`p^$+Z@DhA7pp3j`s8iS<@rNB-_8o)b9fp41BwEI9IK_w1(Kwdv_};>J?Cs+ZyD`kT zc~JatLqAUvEn_#54EJ7JD$$b&jH2a$Kv-6+|ejew&QEu z`njEGqMc9s%p8n=f-!zjynYHPS_{WOjchk0>= z@%Iz)0=%DWGm?#6apTJy<-{Z8VvY=j*UxonVm=C{(eDSg$72cp%t8F$1U&WY=fud% zV*~z7yyZnd*CmiR-G#rw?7x2q{80Vm*k2gK)Zgr0%%^LxQR zdO*B=sPOUq;((Zg#M>BjKz)iMB=zYmflnTABfb>)RK#a|9G<86<3Cv`#(Lx)B%ZGU z|0rnE^ORph;lY;_o-T_q=SP%&eWyS_4fO=|;Qmtl^HzM{P#VTP{HD?Np3UDa2*hlkM5FM3A%e}Xy=52bz5BrdCD2z>SRyC4h{p%pUaFef^zZ}9`qbA_1!)Cp* z(N}|AW5`z-!OmR0P_8B`f6lx)gER5>J{o+L!C>VETm1nhYbx|>r5cR7ig@yX3NBDyy19oLO)~?Lwuc-`I4&cc7s$78? zqev~eC53g-zmXE#xJaxp5}|+(@7k+Dsugd}fSVDe7iI-W!?L4b9LeAu?P+X~q4#hCp*n#Rpo@-&jcjRcdJr8(Eyu zMiz=$b+~bpg}Vnh3vXrx17a3t`RmonQeOilx(4m|F(d!_YJW@EC+=iOWpdGxI&>Lr zRyH+M!%9x;EJUi2g$1t(ix_bJsz@C;E1T=EI;v_zb8SGEE32x4{#ISXuWR{r8Gegi zs{gGrci7kpV2>#eo!@E5FY!emQaM(3aqEwA%M4X0>E z1>@yQfyZkX1G;^kS8Ay3*J+>LFKM;QQNSnXmi;@FA`R!N4&!?z!cSUWU51SdfXAiK zlGk~vhWb4SU=c^W|Goh%-!Y)==a+AJXs9zIZNKKz@JjIVodvqC^Ii?bXK3J|{j^it zkD@sEOe~w!@;X1(@StSlhiT%_^1A<*12n{Ujbe`Y{y(PV_4w(0M8lDB0@`k^ROWg8<3H5z3u^v2bq4c3`d_!N z??Y%z?+ukU}X z&!o2gc$KyOx|aV41UaNAc#}!S}pQKSv=dq$by#FFjdLN zu^Gim{_;42meXi{|2Q5;+5<}dn7#lgfp}g%TON-i>z(CNV38iUA>`)`A^+woDR5WZ zgo$sx&+HDIw2=^%A -#include -#include -#include -#include -#include -#include - -/* - pixy_buf_size = 17; - pixy_buf[17]= {}; - pixy_len = 0; - blob_buffer_write_idx = 0; - bytes_to_sof = 0; - bytes_to_block = 0; -*/ -int main() { - pixy_parser pixyObj; - - uint8_t input_bytes[] = {0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x17, 0x01, 0x01, 0x00, 0x69, 0x00, 0x56, 0x00, 0x27, 0x00, 0x30, 0x00, 0x55, 0xAA, 0x17, 0x01, 0xF1, 0xE0, 0x09, 0x10, 0x46, 0x00, 0x27, 0xE0, 0x00, 0xF0, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x90, 0x01, 0x01, 0x00, 0xE5, 0x00, 0x56, 0x00, 0x25, 0x00, 0x2F, 0x00, 0x55, 0xAA, 0x00, 0x01, 0xF1, 0x0A, 0xE0, 0x10, 0x55, 0x00, 0x15, 0x11, 0x2F, 0x00, 0x55, 0xAA, 0x55, 0xAA, 0x0F, 0x01, 0x01, 0x00, 0x68, 0x00, 0x52, 0x00, 0x24, 0x00, 0x30, 0x00}; //array of 15 bytes of SOF -// uint8_t input_bytes[] = {85, 170, 85, 170, 15, 1, 1, 0, 104, 0, 82, 0, 36, 0, 48, 0, 85, 170, 144, 1, 1, 0, 229, 0, 86, 0, 37, 0, 47, 0, 85, 170, 85, 170, 23, 1, 1, 0, 105, 0, 86, 0, 39, 0, 48, 0, 85, 170, 23, 1, 241, 224, 9, 16, 70, 0, 39, 224, 0, 240, 124 }; //array of 15 bytes of SOF - - size_t size_input_bytes = sizeof(input_bytes)/sizeof(input_bytes[0]); - - for (size_t i=0; i<=size_input_bytes; i++) { - printf("%u, ", (unsigned)input_bytes[i]); - } - - for (size_t i=0; i<=size_input_bytes; i++) { -// printf("Calling recv_byte_pixy : %d : %u\n", i, (unsigned)input_bytes[i]); - printf("\nNEW BYTE IN:\n"); - pixyObj.recv_byte_pixy(input_bytes[i]); - } - return 0; -} diff --git a/libraries/AP_IRLock/pixy_parser_old_working.c b/libraries/AP_IRLock/pixy_parser_old_working.c deleted file mode 100644 index 5ce930a831..0000000000 --- a/libraries/AP_IRLock/pixy_parser_old_working.c +++ /dev/null @@ -1,274 +0,0 @@ -#include -#include -#include -#include -#include -#include - -#define PIXY_BUF_SIZE 17 - -enum message_validity_t { - MESSAGE_EMPTY, - MESSAGE_INVALID, - MESSAGE_INCOMPLETE, - MESSAGE_VALID_SOF, - MESSAGE_VALID_BLOCK -}; - -static uint8_t pixy_buf[PIXY_BUF_SIZE]; -static size_t pixy_len; -static uint8_t blob_buffer_write_idx; -static size_t bytes_to_sof; -static size_t bytes_to_block; - -typedef struct { - uint16_t center_x; - uint16_t center_y; - uint16_t width; - uint16_t height; -} pixy_blob; - - -static struct blob_buffer { //Frame (full of blobs) - pixy_blob blobs[10]; - size_t count; -} blob_buffer[2]; - - -void empty_pixyBuf() { - for (size_t i=0; i= 10) { - return false; - } - writebuf.blobs[writebuf.count] = blob1; - printf("SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); - writebuf.count++; - print_buffer(); - return true; -} - -// Blob buffer indexing swap -void swap_buffer() { - blob_buffer_write_idx = (blob_buffer_write_idx+1)%2; - printf("Swapping Main Buffer: Swapped to %u\n", blob_buffer_write_idx); -// struct blob_buffer* writebuf = &blob_buffer[blob_buffer_write_idx]; - struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; - writebuf.count = 0; //This is probably wront. But helps me get rid of an error!!!----------------------------------------------------------- - print_buffer(); -} - - -// - read blob i: - -const pixy_blob* read_buffer(size_t i) { - printf("Reading Main Buffer: Reading from %u\n", (blob_buffer_write_idx+1)%2); -// struct blob_buffer* readbuf = &blob_buffer[(blob_buffer_write_idx+1)%2]; - struct blob_buffer& readbuf = blob_buffer[(blob_buffer_write_idx+1)%2]; - if (i >= readbuf.count) { - return NULL; - } - return &readbuf.blobs[i]; -} - -static enum message_validity_t check_pixy_message(size_t pixy_len) { -// printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); - - if (pixy_len == 0) { - return MESSAGE_EMPTY; - } - if (pixy_len >= 1 && pixy_buf[0] != 0x55) { //checking if 1st byte of the message is 0x55 - printf("First block not 0x55 .. Message Invalid!\n"); - return MESSAGE_INVALID; - } - if (pixy_len >= 2 && pixy_buf[1] != 0xAA) { //checking if 2nd byte of the message is 0xAA (Combined it verifies if the message is 0x55AA) - printf("Second block not 0xAA .. Message Invalid!\n"); - return MESSAGE_INVALID; - } - if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { - bytes_to_sof = 16 - pixy_len; - if (bytes_to_sof == 0) { - printf("SOF COMPLETE!\n"); - } - else { - printf("Need %u more bytes to complete a SOF\n", (unsigned)bytes_to_sof); - } - } - if (pixy_buf[2] != 0x55 && pixy_buf[3] != 0xAA) { - bytes_to_block = 14 - pixy_len; - if (bytes_to_block == 0) { - printf("BLOCK COMPLETE!\n"); - } - else { - printf("Need %u more bytes to complete a Block\n", (unsigned)bytes_to_sof); - } - } - if (pixy_len < 14) { // Looks for at least 14 bytes i.e. "sync+blob_data" = 2+12 bytes) - printf("Message Length less than 14.. Message Incomplete!\n"); - return MESSAGE_INCOMPLETE; - } - - if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { - - printf("2 syncs available and size >= 14..\n"); - - if (pixy_len >= 16) { - - printf("PixyLen Greater than or equal to 16 with 2 syncs, calculating crc....\n"); - /* check crc */ - uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 - for (size_t i = 6; i <= 15; i+=2) { - uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; - crc_calculated += word; - } - - uint16_t crc_provided; //Getting true crc by concatinating 4 & 5 message fields(original crc) into a single 16 bit - crc_provided = pixy_buf[4] | (uint16_t)pixy_buf[5]<<8; - if (crc_provided != crc_calculated) { - printf("CRC Failed Message Invalid!\n"); - return MESSAGE_INVALID; - } - return MESSAGE_VALID_SOF; - } else { - return MESSAGE_INCOMPLETE; - } - - - } else { - printf("Only 1 SYNC available and size < 16, calculating CRC....\n"); - - uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 - for (size_t i = 4; i <= 13; i+=2) { - uint16_t word = pixy_buf[i] | (uint16_t)pixy_buf[i+1]<<8; - crc_calculated += word; - } - uint16_t crc_provided; //Getting true crc by concatinating 4 & 5 message fields(original crc) into a single 16 bit - crc_provided = pixy_buf[2] | (uint16_t)pixy_buf[3]<<8; - printf("Crc calculated: %u Crc provided: %u\n", (unsigned)crc_calculated, (unsigned)crc_provided); - - if (crc_provided != crc_calculated) { - printf("CRC Failed Message Invalid!\n"); - return MESSAGE_INVALID; - } - return MESSAGE_VALID_BLOCK; - } -} - -void recv_byte_pixy(uint8_t byte) { -// printf("INSIDE recv_byte_pixy:-\n"); - -// Read 2 bytes - pixy_blob blob1; //%%%%%%%%%%%%%%%%%%%%$$$$$$$$$$$$$$$$$$$$$$$$-------------- should I put struct as prefix or not?-------------------------%%%%%%%%%$$$$$$$$$ - - struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; - - printf("The byte inputted is: %u and pixylen is %u\n", byte, (unsigned)pixy_len); - pixy_buf[pixy_len++] = byte; // Append byte to buffer - - enum message_validity_t validity = check_pixy_message(pixy_len); // Call parser - printf("Validity Check Call: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); - printf("Pixy Len: %u\n", (unsigned)pixy_len); - printf("Pixy_buf: "); - for (size_t i=0; i<17; i++) { - printf("%u, ", pixy_buf[i]); - } - printf("\n"); - - if (validity == MESSAGE_VALID_SOF) { -// pixy_frame_received(pixy_len, pixy_buf); - - if (!(writebuf.count >= 10)) { - if (writebuf.count != 0) { - swap_buffer(); //swap buffer - - blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; //Extract blob information - blob1.center_y = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; - blob1.width = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; - blob1.height = pixy_buf[14] | (uint16_t)pixy_buf[15]<<8; - - writebuf.count = 0; //Turn the count to 0 - printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); - - write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) - empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' - - } - else { - write_buffer(blob1); //Writing inside the buffer(the count increment happens inside the write_buffer()) - empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' - - printf("\n--------------------------AFTER EMPTY: "); - for (int i=0; i= 10)) { - blob1.center_x = pixy_buf[6] | (uint16_t)pixy_buf[7]<<8; //Extract blob information - blob1.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; - blob1.width = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; - blob1.height = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; - printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)blob1.center_x, (unsigned)blob1.center_y, (unsigned)blob1.width, (unsigned)blob1.height); - - write_buffer(blob1); //Writing inside the buffer - empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' - - printf("\n------------------------------AFTER EMPTY: "); - for (int i=0; i Date: Thu, 29 Nov 2018 14:36:08 -0800 Subject: [PATCH 25/31] Fixed data integrity issue --- libraries/AP_IRLock/AP_IRLock_I2C.cpp | 54 +++++++-------------- libraries/AP_IRLock/pixy_parser.cpp | 69 ++++++++++++++------------- 2 files changed, 52 insertions(+), 71 deletions(-) diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.cpp b/libraries/AP_IRLock/AP_IRLock_I2C.cpp index 8e89667117..057417ff28 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.cpp +++ b/libraries/AP_IRLock/AP_IRLock_I2C.cpp @@ -28,9 +28,7 @@ extern const AP_HAL::HAL& hal; #define IRLOCK_I2C_ADDRESS 0x54 -#define IRLOCK_SYNC 0xAA55AA55 -#define IRLOCK_SYNC1 0xAA55 void AP_IRLock_I2C::init(int8_t bus) { if (bus < 0) { @@ -41,23 +39,12 @@ void AP_IRLock_I2C::init(int8_t bus) { if (!dev) { return; } - sem = hal.util->new_semaphore(); - // read at 50Hz // printf("Initializing IRLock on I2C\n"); - - dev->register_periodic_callback(20000, FUNCTOR_BIND_MEMBER(&AP_IRLock_I2C::read_frames, void)); + dev->register_periodic_callback(200, FUNCTOR_BIND_MEMBER(&AP_IRLock_I2C::read_frames, void)); } -/* - synchronise with frame start. We expect 0xAA55AA55 at the start of - a frame -*/ - - - - /* converts IRLOCK pixels to a position on a normal plane 1m in front of the lens based on a characterization of IR-LOCK with the standard lens, focused such that 2.38mm of threads are exposed @@ -72,37 +59,22 @@ void AP_IRLock_I2C::pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, fl void AP_IRLock_I2C::read_frames(void) { - uint8_t buf[142]; + uint8_t buf[16]; dev->transfer(nullptr, 0, buf, 16); - const pixy_parser::pixy_blob* temp; for (size_t i=0; i<16; i++) { pixyObj.recv_byte_pixy(buf[i]); - temp = pixyObj.read_buffer(i); - printf("\n\n\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); } - printf("\n&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&------------------OUT"); - printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); - - -// pixyObj.pixy_blob* temp = pixyObj.read_buffer(i); - - - - - - // printf("\nSTART: \n"); -// if (!sync_frame_once()) { //It just sync's the frame -// return; -// } - -// struct frame irframe; - -// if (!read_block(irframe)) { // Try reading blobs until I get a sync (Nope! does not work!) -// return; -// } + const pixy_parser::pixy_blob* temp; + temp = pixyObj.read_buffer(0); + if (temp != nullptr) { + printf("\n\n\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); + } +//} +// printf("\n&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&------------------OUT"); +// printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); int16_t corner1_pix_x = temp->center_x - temp->width/2; int16_t corner1_pix_y = temp->center_y - temp->height/2; @@ -123,6 +95,12 @@ void AP_IRLock_I2C::read_frames(void) { sem->give(); } + +// +// } +// + + } // retrieve latest sensor data - returns true if new data is available diff --git a/libraries/AP_IRLock/pixy_parser.cpp b/libraries/AP_IRLock/pixy_parser.cpp index e528668623..23015abcf5 100644 --- a/libraries/AP_IRLock/pixy_parser.cpp +++ b/libraries/AP_IRLock/pixy_parser.cpp @@ -44,6 +44,7 @@ pixy_parser::pixy_parser() { bytes_to_sof = 0; bytes_to_block = 0; blob_buffer[blob_buffer_write_idx].count = 0; +// if_swap_buffer = 0; } // Destructor - pixy_parser @@ -56,33 +57,33 @@ void pixy_parser::empty_pixyBuf() { } pixy_len = 0; - printf("\n--------------------------AFTER EMPTY: "); + // printf("\n--------------------------AFTER EMPTY: "); for (size_t i=0; i= 10) { return false; } writebuf.blobs[writebuf.count] = received_blob; - printf("SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); + // printf("SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); writebuf.count++; print_buffer(); return true; @@ -92,7 +93,7 @@ bool pixy_parser::write_buffer(const pixy_blob& received_blob) { // Blob buffer indexing swap void pixy_parser::swap_buffer() { blob_buffer_write_idx = (blob_buffer_write_idx+1)%2; - printf("Swapping Main Buffer: Swapped to %u\n", blob_buffer_write_idx); + // printf("Swapping Main Buffer: Swapped to %u\n", blob_buffer_write_idx); // struct blob_buffer* writebuf = &blob_buffer[blob_buffer_write_idx]; struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; writebuf.count = 0; //This is probably wront. But helps me get rid of an error!!!----------------------------------------------------------- @@ -102,7 +103,7 @@ void pixy_parser::swap_buffer() { // Method - read_buffer // - read blob i: const pixy_parser::pixy_blob* pixy_parser::read_buffer(size_t i) { - printf("Reading Main Buffer: Reading from %u\n", (blob_buffer_write_idx+1)%2); + // printf("Reading Main Buffer: Reading from %u\n", (blob_buffer_write_idx+1)%2); // struct blob_buffer* readbuf = &blob_buffer[(blob_buffer_write_idx+1)%2]; struct blob_buffer& readbuf = blob_buffer[(blob_buffer_write_idx+1)%2]; if (i >= readbuf.count) { @@ -113,49 +114,49 @@ const pixy_parser::pixy_blob* pixy_parser::read_buffer(size_t i) { // Method - check_pixy_message enum pixy_parser::message_validity_t pixy_parser::check_pixy_message() { -// printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); +// // printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); if (pixy_len == 0) { return MESSAGE_EMPTY; } if (pixy_len >= 1 && pixy_buf[0] != 0x55) { //checking if 1st byte of the message is 0x55 - printf("First block not 0x55 .. Message Invalid!\n"); + // printf("First block not 0x55 .. Message Invalid!\n"); return MESSAGE_INVALID; } if (pixy_len >= 2 && pixy_buf[1] != 0xAA) { //checking if 2nd byte of the message is 0xAA (Combined it verifies if the message is 0x55AA) - printf("Second block not 0xAA .. Message Invalid!\n"); + // printf("Second block not 0xAA .. Message Invalid!\n"); return MESSAGE_INVALID; } if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { bytes_to_sof = 16 - pixy_len; if (bytes_to_sof == 0) { - printf("SOF COMPLETE!\n"); + // printf("SOF COMPLETE!\n"); } else { - printf("Need %u more bytes to complete a SOF\n", (unsigned)bytes_to_sof); + // printf("Need %u more bytes to complete a SOF\n", (unsigned)bytes_to_sof); } } if (pixy_buf[2] != 0x55 && pixy_buf[3] != 0xAA) { bytes_to_block = 14 - pixy_len; if (bytes_to_block == 0) { - printf("BLOCK COMPLETE!\n"); + // printf("BLOCK COMPLETE!\n"); } else { - printf("Need %u more bytes to complete a Block\n", (unsigned)bytes_to_sof); + // printf("Need %u more bytes to complete a Block\n", (unsigned)bytes_to_sof); } } if (pixy_len < 14) { // Looks for at least 14 bytes i.e. "sync+blob_data" = 2+12 bytes) - printf("Message Length less than 14.. Message Incomplete!\n"); + // printf("Message Length less than 14.. Message Incomplete!\n"); return MESSAGE_INCOMPLETE; } if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { - printf("2 syncs available and size >= 14..\n"); + // printf("2 syncs available and size >= 14..\n"); if (pixy_len >= 16) { - printf("PixyLen Greater than or equal to 16 with 2 syncs, calculating crc....\n"); + // printf("PixyLen Greater than or equal to 16 with 2 syncs, calculating crc....\n"); /* check crc */ uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 for (size_t i = 6; i <= 15; i+=2) { @@ -166,7 +167,7 @@ enum pixy_parser::message_validity_t pixy_parser::check_pixy_message() { uint16_t crc_provided; //Getting true crc by concatinating 4 & 5 message fields(original crc) into a single 16 bit crc_provided = pixy_buf[4] | (uint16_t)pixy_buf[5]<<8; if (crc_provided != crc_calculated) { - printf("CRC Failed Message Invalid!\n"); + // printf("CRC Failed Message Invalid!\n"); return MESSAGE_INVALID; } return MESSAGE_VALID_SOF; @@ -176,7 +177,7 @@ enum pixy_parser::message_validity_t pixy_parser::check_pixy_message() { } else { - printf("Only 1 SYNC available and size < 16, calculating CRC....\n"); + // printf("Only 1 SYNC available and size < 16, calculating CRC....\n"); uint16_t crc_calculated = 0; //addition of all the message fields from 5 to 15 for (size_t i = 4; i <= 13; i+=2) { @@ -185,10 +186,10 @@ enum pixy_parser::message_validity_t pixy_parser::check_pixy_message() { } uint16_t crc_provided; //Getting true crc by concatinating 4 & 5 message fields(original crc) into a single 16 bit crc_provided = pixy_buf[2] | (uint16_t)pixy_buf[3]<<8; - printf("Crc calculated: %u Crc provided: %u\n", (unsigned)crc_calculated, (unsigned)crc_provided); + // printf("Crc calculated: %u Crc provided: %u\n", (unsigned)crc_calculated, (unsigned)crc_provided); if (crc_provided != crc_calculated) { - printf("CRC Failed Message Invalid!\n"); + // printf("CRC Failed Message Invalid!\n"); return MESSAGE_INVALID; } return MESSAGE_VALID_BLOCK; @@ -197,14 +198,14 @@ enum pixy_parser::message_validity_t pixy_parser::check_pixy_message() { // Method - recv_byte_pixy void pixy_parser::recv_byte_pixy(uint8_t byte) { -// printf("INSIDE recv_byte_pixy:-\n"); +// // printf("INSIDE recv_byte_pixy:-\n"); // Read 2 bytes //%%%%%%%%%%%%%%%%%%%%$$$$$$$$$$$$$$$$$$$$$$$$-------------- should I put struct as prefix or not?-------------------------%%%%%%%%%$$$$$$$$$ struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; - printf("The byte inputted is: %u and pixylen is %u\n", byte, (unsigned)pixy_len); + // printf("The byte inputted is: %u and pixylen is %u\n", byte, (unsigned)pixy_len); PIXY_PARSER_ASSERT(pixy_len < PIXY_PARSER_PIXY_BUF_SIZE); if (pixy_len >= PIXY_PARSER_PIXY_BUF_SIZE) { @@ -215,13 +216,13 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { pixy_buf[pixy_len++] = byte; // Append byte to buffer enum message_validity_t validity = check_pixy_message(); // Call parser - printf("Validity Check Call: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); - printf("Pixy Len: %u\n", (unsigned)pixy_len); - printf("Pixy_buf: "); + // printf("Validity Check Call: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); + // printf("Pixy Len: %u\n", (unsigned)pixy_len); + // printf("Pixy_buf: "); for (size_t i=0; i= 10)) { @@ -233,9 +234,10 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { if (writebuf.count != 0) { swap_buffer(); //swap buffer +// if_swap_buffer = 1; writebuf.count = 0; //Turn the count to 0 - printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); + // printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); write_buffer(received_blob); //Writing inside the buffer(the count increment happens inside the write_buffer()) } @@ -253,7 +255,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { received_blob.center_y = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; received_blob.width = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; received_blob.height = pixy_buf[12] | (uint16_t)pixy_buf[13]<<8; - printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); + // printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); write_buffer(received_blob); //Writing inside the buffer } @@ -267,6 +269,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { if (writebuf.count < 10 && writebuf.count != 0) { swap_buffer(); //swap buffer +// if_swap_buffer = 1; } } } From 6b3f480b11d796aeeb6d8d879427ce13aaa238f9 Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Fri, 30 Nov 2018 15:37:08 -0800 Subject: [PATCH 26/31] Added thread safe interface(between AC_Precland and pixy_parser) logic --- libraries/AP_IRLock/AP_IRLock_I2C.cpp | 87 ++++++++++++++++++-------- libraries/AP_IRLock/AP_IRLock_I2C.h | 2 + libraries/AP_IRLock/AP_IRLock_SITL.cpp | 10 +-- libraries/AP_IRLock/IRLock.cpp | 9 +-- libraries/AP_IRLock/IRLock.h | 6 +- libraries/AP_IRLock/pixy_parser.cpp | 7 ++- libraries/AP_IRLock/pixy_parser.h | 3 +- 7 files changed, 83 insertions(+), 41 deletions(-) diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.cpp b/libraries/AP_IRLock/AP_IRLock_I2C.cpp index 057417ff28..81e1f371ae 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.cpp +++ b/libraries/AP_IRLock/AP_IRLock_I2C.cpp @@ -56,44 +56,79 @@ void AP_IRLock_I2C::pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, fl 4.79331390531725e-6f*((pix_y - 100.0f)*(pix_y - 100.0f)) - 1.0f); } +//void AP_IRLock_I2C::convert_pixy_data(uint16_t x, uint16_t y, uint16_t w, uint16_t h) { +//} void AP_IRLock_I2C::read_frames(void) { uint8_t buf[16]; dev->transfer(nullptr, 0, buf, 16); + pixyObj.if_swap_buffer = 0; + for (size_t i=0; i<16; i++) { pixyObj.recv_byte_pixy(buf[i]); } - const pixy_parser::pixy_blob* temp; - temp = pixyObj.read_buffer(0); + // if (pixy parser just swapped buffers) { ----------$$ + // take semaphore -----------$$ + // CONVERT frame + // copy frame data from pixy parser to target info array + // update target_count + // update frame_timestamp_us -> uint32_t timestamp_us = micros(); + // give semaphore + // } + + + // printf("\n----IF_SWAP: %d", pixyObj.if_swap_buffer); + if (pixyObj.if_swap_buffer) { + if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { // take semaphore + + const pixy_parser::pixy_blob* temp; + temp = pixyObj.read_buffer(0); + + if (temp != nullptr) { + printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); + +// convert_pixy_data(temp->center_x, temp->center_y, temp->width, temp->height); // CONVERT frame + +//--------------------- + int16_t corner1_pix_x = temp->center_x - temp->width/2; + int16_t corner1_pix_y = temp->center_y - temp->height/2; + int16_t corner2_pix_x = temp->center_x + temp->width/2; + int16_t corner2_pix_y = temp->center_y + temp->height/2; + float corner1_pos_x, corner1_pos_y, corner2_pos_x, corner2_pos_y; + pixel_to_1M_plane(corner1_pix_x, corner1_pix_y, corner1_pos_x, corner1_pos_y); + pixel_to_1M_plane(corner2_pix_x, corner2_pix_y, corner2_pos_x, corner2_pos_y); +//--------------------- + + _target_info[target_count].pos_x = 0.5f*(corner1_pos_x+corner2_pos_x); // copy frame data from pixy parser to target info array + _target_info[target_count].pos_y = 0.5f*(corner1_pos_y+corner2_pos_y); + _target_info[target_count].size_x = corner2_pos_x-corner1_pos_x; + _target_info[target_count].size_x = corner2_pos_y-corner1_pos_y; + + target_count++; // update target_count + + _target_info[target_count].timestamp = AP_HAL::micros(); // update frame_timestamp_us + + sem->give(); // give semaphore + + } + } + } - if (temp != nullptr) { - printf("\n\n\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); - } -//} -// printf("\n&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&------------------OUT"); -// printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); - int16_t corner1_pix_x = temp->center_x - temp->width/2; - int16_t corner1_pix_y = temp->center_y - temp->height/2; - int16_t corner2_pix_x = temp->center_x + temp->width/2; - int16_t corner2_pix_y = temp->center_y + temp->height/2; +/* + copy_pixy_data_to_target(); + } + } + } - float corner1_pos_x, corner1_pos_y, corner2_pos_x, corner2_pos_y; - pixel_to_1M_plane(corner1_pix_x, corner1_pix_y, corner1_pos_x, corner1_pos_y); - pixel_to_1M_plane(corner2_pix_x, corner2_pix_y, corner2_pos_x, corner2_pos_y); +*/ - if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { - /* convert to angles */ - _target_info.timestamp = AP_HAL::millis(); - _target_info.pos_x = 0.5f*(corner1_pos_x+corner2_pos_x); - _target_info.pos_y = 0.5f*(corner1_pos_y+corner2_pos_y); - _target_info.size_x = corner2_pos_x-corner1_pos_x; - _target_info.size_y = corner2_pos_y-corner1_pos_y; - sem->give(); - } +//} +// printf("\n&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&------------------OUT"); +// printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); // @@ -110,10 +145,10 @@ bool AP_IRLock_I2C::update() { return false; } if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { - if (_last_update_ms != _target_info.timestamp) { + if (_last_update_ms != _target_info[0].timestamp) { new_data = true; } - _last_update_ms = _target_info.timestamp; + _last_update_ms = _target_info[0].timestamp; _flags.healthy = (AP_HAL::millis() - _last_read_ms < 100); sem->give(); } diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.h b/libraries/AP_IRLock/AP_IRLock_I2C.h index bccb507dca..6032118e83 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.h +++ b/libraries/AP_IRLock/AP_IRLock_I2C.h @@ -23,7 +23,9 @@ class AP_IRLock_I2C : public IRLock void read_frames(void); void pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, float &ret_y); +// void convert_pixy_data(uint16_t x, uint16_t y, uint16_t w, uint16_t h); AP_HAL::Semaphore *sem; uint32_t _last_read_ms; + size_t target_count; }; \ No newline at end of file diff --git a/libraries/AP_IRLock/AP_IRLock_SITL.cpp b/libraries/AP_IRLock/AP_IRLock_SITL.cpp index 5601347e2a..c6d6f31cca 100644 --- a/libraries/AP_IRLock/AP_IRLock_SITL.cpp +++ b/libraries/AP_IRLock/AP_IRLock_SITL.cpp @@ -69,11 +69,11 @@ bool AP_IRLock_SITL::update() if (s == sizeof(irlock_packet) && pkt.timestamp > _last_timestamp) { // fprintf(stderr, " posx %f posy %f sizex %f sizey %f\n", pkt.pos_x, pkt.pos_y, pkt.size_x, pkt.size_y); - _target_info.timestamp = pkt.timestamp; - _target_info.pos_x = pkt.pos_x; - _target_info.pos_y = pkt.pos_y; - _target_info.size_x = pkt.size_x; - _target_info.size_y = pkt.size_y; + _target_info[0].timestamp = pkt.timestamp; + _target_info[0].pos_x = pkt.pos_x; + _target_info[0].pos_y = pkt.pos_y; + _target_info[0].size_x = pkt.size_x; + _target_info[0].size_y = pkt.size_y; _last_timestamp = pkt.timestamp; _last_update_ms = _last_timestamp; new_data = true; diff --git a/libraries/AP_IRLock/IRLock.cpp b/libraries/AP_IRLock/IRLock.cpp index 7bdddc15d3..63feca3f40 100644 --- a/libraries/AP_IRLock/IRLock.cpp +++ b/libraries/AP_IRLock/IRLock.cpp @@ -1,3 +1,4 @@ + /* * IRLock.cpp * @@ -17,8 +18,8 @@ bool IRLock::get_angle_to_target_rad(float &x_angle_rad, float &y_angle_rad) con } // use data from first (largest) object - x_angle_rad = atanf(_target_info.pos_x); - y_angle_rad = atanf(_target_info.pos_y); + x_angle_rad = atanf(_target_info[0].pos_x); + y_angle_rad = atanf(_target_info[0].pos_y); return true; } @@ -32,8 +33,8 @@ bool IRLock::get_unit_vector_body(Vector3f& ret) const } // use data from first (largest) object - ret.x = -_target_info.pos_y; - ret.y = _target_info.pos_x; + ret.x = -_target_info[0].pos_y; + ret.y = _target_info[0].pos_x; ret.z = 1.0f; ret /= ret.length(); return true; diff --git a/libraries/AP_IRLock/IRLock.h b/libraries/AP_IRLock/IRLock.h index 6d888b2568..56ba58a925 100644 --- a/libraries/AP_IRLock/IRLock.h +++ b/libraries/AP_IRLock/IRLock.h @@ -1,3 +1,4 @@ + /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by @@ -60,7 +61,7 @@ class IRLock uint32_t _last_update_ms; // irlock_target_info is a duplicate of the PX4Firmware irlock_s structure - typedef struct { + struct irlock_target_info { uint32_t timestamp; // milliseconds since system start float pos_x; // x-axis distance from center of image to center of target in units of tan(theta) float pos_y; // y-axis distance from center of image to center of target in units of tan(theta) @@ -68,5 +69,6 @@ class IRLock float size_y; // size of target along y-axis in units of tan(theta) } irlock_target_info; - irlock_target_info _target_info; + struct irlock_target_info _target_info[10]; + }; diff --git a/libraries/AP_IRLock/pixy_parser.cpp b/libraries/AP_IRLock/pixy_parser.cpp index 23015abcf5..795b87fc30 100644 --- a/libraries/AP_IRLock/pixy_parser.cpp +++ b/libraries/AP_IRLock/pixy_parser.cpp @@ -44,7 +44,7 @@ pixy_parser::pixy_parser() { bytes_to_sof = 0; bytes_to_block = 0; blob_buffer[blob_buffer_write_idx].count = 0; -// if_swap_buffer = 0; + if_swap_buffer = 0; } // Destructor - pixy_parser @@ -201,6 +201,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { // // printf("INSIDE recv_byte_pixy:-\n"); // Read 2 bytes //%%%%%%%%%%%%%%%%%%%%$$$$$$$$$$$$$$$$$$$$$$$$-------------- should I put struct as prefix or not?-------------------------%%%%%%%%%$$$$$$$$$ +// printf("\n---- IF_SWAP BEFORE: %d", if_swap_buffer); struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; @@ -234,7 +235,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { if (writebuf.count != 0) { swap_buffer(); //swap buffer -// if_swap_buffer = 1; + if_swap_buffer = 1; writebuf.count = 0; //Turn the count to 0 // printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); @@ -269,7 +270,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { if (writebuf.count < 10 && writebuf.count != 0) { swap_buffer(); //swap buffer -// if_swap_buffer = 1; + if_swap_buffer = 1; } } } diff --git a/libraries/AP_IRLock/pixy_parser.h b/libraries/AP_IRLock/pixy_parser.h index 46412bd98a..9b5c72952d 100644 --- a/libraries/AP_IRLock/pixy_parser.h +++ b/libraries/AP_IRLock/pixy_parser.h @@ -27,6 +27,7 @@ */ class pixy_parser { public: + bool if_swap_buffer; typedef struct { uint16_t center_x; @@ -72,7 +73,7 @@ class pixy_parser { }; - + From ca1fe8b195c65cc3417c56e73da64aa1eebd695e Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Mon, 3 Dec 2018 17:35:24 -0800 Subject: [PATCH 27/31] Pixy parser driver complete, still needs testing --- libraries/AP_IRLock/AP_IRLock_I2C.cpp | 107 +++++++++----------------- libraries/AP_IRLock/AP_IRLock_I2C.h | 2 +- libraries/AP_IRLock/IRLock.h | 6 +- libraries/AP_IRLock/pixy_parser.cpp | 55 +++++-------- libraries/AP_IRLock/pixy_parser.h | 23 +----- 5 files changed, 62 insertions(+), 131 deletions(-) diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.cpp b/libraries/AP_IRLock/AP_IRLock_I2C.cpp index 81e1f371ae..c00df6a1b8 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.cpp +++ b/libraries/AP_IRLock/AP_IRLock_I2C.cpp @@ -56,85 +56,50 @@ void AP_IRLock_I2C::pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, fl 4.79331390531725e-6f*((pix_y - 100.0f)*(pix_y - 100.0f)) - 1.0f); } -//void AP_IRLock_I2C::convert_pixy_data(uint16_t x, uint16_t y, uint16_t w, uint16_t h) { -//} +void AP_IRLock_I2C::copy_frame_from_parser() { + for (size_t i=0; i<10; i++) { + pixy_parser::pixy_blob blob; + if (!pixyObj.read_buffer(i, blob)) { + break; + } + int16_t corner1_pix_x = blob.center_x - blob.width/2; // 3. CONVERT frame + int16_t corner1_pix_y = blob.center_y - blob.height/2; + int16_t corner2_pix_x = blob.center_x + blob.width/2; + int16_t corner2_pix_y = blob.center_y + blob.height/2; + float corner1_pos_x, corner1_pos_y, corner2_pos_x, corner2_pos_y; + pixel_to_1M_plane(corner1_pix_x, corner1_pix_y, corner1_pos_x, corner1_pos_y); + pixel_to_1M_plane(corner2_pix_x, corner2_pix_y, corner2_pos_x, corner2_pos_y); -void AP_IRLock_I2C::read_frames(void) { - uint8_t buf[16]; - dev->transfer(nullptr, 0, buf, 16); + _target_info[target_count].pos_x = 0.5f*(corner1_pos_x+corner2_pos_x); // 4. copy frame data from pixy parser to target info array + _target_info[target_count].pos_y = 0.5f*(corner1_pos_y+corner2_pos_y); + _target_info[target_count].size_x = corner2_pos_x-corner1_pos_x; + _target_info[target_count].size_x = corner2_pos_y-corner1_pos_y; - pixyObj.if_swap_buffer = 0; + target_count = i+1; - for (size_t i=0; i<16; i++) { - pixyObj.recv_byte_pixy(buf[i]); - } +// printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); + printf("\nBLOCK:- \nX: %03u - Y: %03u - W: %03u - H: %03u\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); - // if (pixy parser just swapped buffers) { ----------$$ - // take semaphore -----------$$ - // CONVERT frame - // copy frame data from pixy parser to target info array - // update target_count - // update frame_timestamp_us -> uint32_t timestamp_us = micros(); - // give semaphore - // } - - - // printf("\n----IF_SWAP: %d", pixyObj.if_swap_buffer); - if (pixyObj.if_swap_buffer) { - if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { // take semaphore - - const pixy_parser::pixy_blob* temp; - temp = pixyObj.read_buffer(0); - - if (temp != nullptr) { - printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); - -// convert_pixy_data(temp->center_x, temp->center_y, temp->width, temp->height); // CONVERT frame - -//--------------------- - int16_t corner1_pix_x = temp->center_x - temp->width/2; - int16_t corner1_pix_y = temp->center_y - temp->height/2; - int16_t corner2_pix_x = temp->center_x + temp->width/2; - int16_t corner2_pix_y = temp->center_y + temp->height/2; - float corner1_pos_x, corner1_pos_y, corner2_pos_x, corner2_pos_y; - pixel_to_1M_plane(corner1_pix_x, corner1_pix_y, corner1_pos_x, corner1_pos_y); - pixel_to_1M_plane(corner2_pix_x, corner2_pix_y, corner2_pos_x, corner2_pos_y); -//--------------------- - - _target_info[target_count].pos_x = 0.5f*(corner1_pos_x+corner2_pos_x); // copy frame data from pixy parser to target info array - _target_info[target_count].pos_y = 0.5f*(corner1_pos_y+corner2_pos_y); - _target_info[target_count].size_x = corner2_pos_x-corner1_pos_x; - _target_info[target_count].size_x = corner2_pos_y-corner1_pos_y; - - target_count++; // update target_count - - _target_info[target_count].timestamp = AP_HAL::micros(); // update frame_timestamp_us - - sem->give(); // give semaphore - - } - } - } + } + _frame_timestamp = AP_HAL::micros(); // 6. update frame_timestamp_us +} +void AP_IRLock_I2C::read_frames(void) { + uint8_t buf[16]; + dev->transfer(nullptr, 0, buf, 16); -/* - copy_pixy_data_to_target(); - } - } + for (size_t i=0; i<16; i++) { + if (pixyObj.recv_byte_pixy(buf[i])) { + if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { // 2. take semaphore + copy_frame_from_parser(); + sem->give(); // 7. give semaphore + } } + } -*/ - -//} // printf("\n&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&------------------OUT"); -// printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", temp->center_x, temp->center_y, temp->width, temp->height); - - -// -// } -// - +// printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); } @@ -145,10 +110,10 @@ bool AP_IRLock_I2C::update() { return false; } if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { - if (_last_update_ms != _target_info[0].timestamp) { + if (_last_update_ms != _frame_timestamp) { new_data = true; } - _last_update_ms = _target_info[0].timestamp; + _last_update_ms = _frame_timestamp; _flags.healthy = (AP_HAL::millis() - _last_read_ms < 100); sem->give(); } diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.h b/libraries/AP_IRLock/AP_IRLock_I2C.h index 6032118e83..6707fc8b78 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.h +++ b/libraries/AP_IRLock/AP_IRLock_I2C.h @@ -22,8 +22,8 @@ class AP_IRLock_I2C : public IRLock AP_HAL::OwnPtr dev; void read_frames(void); + void copy_frame_from_parser(void); void pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, float &ret_y); -// void convert_pixy_data(uint16_t x, uint16_t y, uint16_t w, uint16_t h); AP_HAL::Semaphore *sem; uint32_t _last_read_ms; diff --git a/libraries/AP_IRLock/IRLock.h b/libraries/AP_IRLock/IRLock.h index 56ba58a925..5d87748ba2 100644 --- a/libraries/AP_IRLock/IRLock.h +++ b/libraries/AP_IRLock/IRLock.h @@ -59,16 +59,16 @@ class IRLock // internals uint32_t _last_update_ms; + uint32_t _frame_timestamp; // milliseconds since system start // irlock_target_info is a duplicate of the PX4Firmware irlock_s structure - struct irlock_target_info { - uint32_t timestamp; // milliseconds since system start + typedef struct { float pos_x; // x-axis distance from center of image to center of target in units of tan(theta) float pos_y; // y-axis distance from center of image to center of target in units of tan(theta) float size_x; // size of target along x-axis in units of tan(theta) float size_y; // size of target along y-axis in units of tan(theta) } irlock_target_info; - struct irlock_target_info _target_info[10]; + irlock_target_info _target_info[10]; }; diff --git a/libraries/AP_IRLock/pixy_parser.cpp b/libraries/AP_IRLock/pixy_parser.cpp index 795b87fc30..912d8dd7a3 100644 --- a/libraries/AP_IRLock/pixy_parser.cpp +++ b/libraries/AP_IRLock/pixy_parser.cpp @@ -41,15 +41,9 @@ pixy_parser::pixy_parser() { pixy_len = 0; blob_buffer_write_idx = 0; - bytes_to_sof = 0; - bytes_to_block = 0; blob_buffer[blob_buffer_write_idx].count = 0; - if_swap_buffer = 0; } -// Destructor - pixy_parser -pixy_parser::~pixy_parser() { } - // Method - empty_pixyBuf void pixy_parser::empty_pixyBuf() { for (size_t i=0; i= 10) { + if (writebuf.count >= PIXY_PARSER_MAX_BLOBS) { return false; } writebuf.blobs[writebuf.count] = received_blob; @@ -102,17 +96,19 @@ void pixy_parser::swap_buffer() { // Method - read_buffer // - read blob i: -const pixy_parser::pixy_blob* pixy_parser::read_buffer(size_t i) { + bool pixy_parser::read_buffer(size_t i, pixy_parser::pixy_blob& ret) { // printf("Reading Main Buffer: Reading from %u\n", (blob_buffer_write_idx+1)%2); // struct blob_buffer* readbuf = &blob_buffer[(blob_buffer_write_idx+1)%2]; struct blob_buffer& readbuf = blob_buffer[(blob_buffer_write_idx+1)%2]; - if (i >= readbuf.count) { - return NULL; + if ( i >= PIXY_PARSER_MAX_BLOBS || i >= readbuf.count) { + return false; } - return &readbuf.blobs[i]; + ret = readbuf.blobs[i]; + return true; } // Method - check_pixy_message +// Checks Validity of a inpyt byte stream enum pixy_parser::message_validity_t pixy_parser::check_pixy_message() { // // printf("INSIDE CHECK_PIXY_MSG:%u\n", (unsigned)pixy_len); @@ -127,24 +123,6 @@ enum pixy_parser::message_validity_t pixy_parser::check_pixy_message() { // printf("Second block not 0xAA .. Message Invalid!\n"); return MESSAGE_INVALID; } - if (pixy_buf[2] == 0x55 && pixy_buf[3] == 0xAA) { - bytes_to_sof = 16 - pixy_len; - if (bytes_to_sof == 0) { - // printf("SOF COMPLETE!\n"); - } - else { - // printf("Need %u more bytes to complete a SOF\n", (unsigned)bytes_to_sof); - } - } - if (pixy_buf[2] != 0x55 && pixy_buf[3] != 0xAA) { - bytes_to_block = 14 - pixy_len; - if (bytes_to_block == 0) { - // printf("BLOCK COMPLETE!\n"); - } - else { - // printf("Need %u more bytes to complete a Block\n", (unsigned)bytes_to_sof); - } - } if (pixy_len < 14) { // Looks for at least 14 bytes i.e. "sync+blob_data" = 2+12 bytes) // printf("Message Length less than 14.. Message Incomplete!\n"); return MESSAGE_INCOMPLETE; @@ -197,10 +175,10 @@ enum pixy_parser::message_validity_t pixy_parser::check_pixy_message() { } // Method - recv_byte_pixy -void pixy_parser::recv_byte_pixy(uint8_t byte) { +// Logicbase of Pixy_parser. Receives the byte from here and adds into pixyBuf if valid. +bool pixy_parser::recv_byte_pixy(uint8_t byte) { // // printf("INSIDE recv_byte_pixy:-\n"); // Read 2 bytes - //%%%%%%%%%%%%%%%%%%%%$$$$$$$$$$$$$$$$$$$$$$$$-------------- should I put struct as prefix or not?-------------------------%%%%%%%%%$$$$$$$$$ // printf("\n---- IF_SWAP BEFORE: %d", if_swap_buffer); struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; @@ -220,13 +198,13 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { // printf("Validity Check Call: %d (0:empty 1:invalid 2:incomplete 3:valid_SOF 4:valid_block)\n", validity); // printf("Pixy Len: %u\n", (unsigned)pixy_len); // printf("Pixy_buf: "); - for (size_t i=0; i= 10)) { + if (!(writebuf.count >= PIXY_PARSER_MAX_BLOBS)) { pixy_blob received_blob; received_blob.center_x = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; //Extract blob information received_blob.center_y = pixy_buf[10] | (uint16_t)pixy_buf[11]<<8; @@ -241,6 +219,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { // printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); write_buffer(received_blob); //Writing inside the buffer(the count increment happens inside the write_buffer()) + return true; } else { write_buffer(received_blob); //Writing inside the buffer(the count increment happens inside the write_buffer()) @@ -250,7 +229,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { } if (validity == MESSAGE_VALID_BLOCK) { ///-----------------------------how can I store the block inside a frame?----------------- - if (!(writebuf.count >= 10)) { + if (!(writebuf.count >= PIXY_PARSER_MAX_BLOBS)) { pixy_blob received_blob; received_blob.center_x = pixy_buf[6] | (uint16_t)pixy_buf[7]<<8; //Extract blob information received_blob.center_y = pixy_buf[8] | (uint16_t)pixy_buf[9]<<8; @@ -260,7 +239,7 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { write_buffer(received_blob); //Writing inside the buffer } - empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' + empty_pixyBuf(); //Emptying The pixy_buf once read the SOF into 'writebuf' } if (validity == MESSAGE_INVALID) { // If message invalid, wait and read 2 bytes @@ -268,9 +247,11 @@ void pixy_parser::recv_byte_pixy(uint8_t byte) { memmove(pixy_buf, pixy_buf+1, pixy_len); // This discards the first block of the pixy_buf and makes pixy_buf have everything except the fisrt block value validity = check_pixy_message(); - if (writebuf.count < 10 && writebuf.count != 0) { + if (writebuf.count < PIXY_PARSER_MAX_BLOBS && writebuf.count != 0) { swap_buffer(); //swap buffer if_swap_buffer = 1; + return true; } } + return false; } diff --git a/libraries/AP_IRLock/pixy_parser.h b/libraries/AP_IRLock/pixy_parser.h index 9b5c72952d..d0a6c3c99b 100644 --- a/libraries/AP_IRLock/pixy_parser.h +++ b/libraries/AP_IRLock/pixy_parser.h @@ -15,20 +15,10 @@ #include #define PIXY_PARSER_PIXY_BUF_SIZE 17 +#define PIXY_PARSER_MAX_BLOBS 10 -/* - pixy_buf_size = 17; - pixy_buf[17]= {}; - pixy_len = 0; - blob_buffer_write_idx = 0; - bytes_to_sof = 0; - bytes_to_block = 0; -} -*/ class pixy_parser { public: - bool if_swap_buffer; - typedef struct { uint16_t center_x; uint16_t center_y; @@ -37,19 +27,16 @@ class pixy_parser { } pixy_blob; pixy_parser(); - ~pixy_parser(); void empty_pixyBuf(void); void print_buffer(void); void swap_buffer(void); - void recv_byte_pixy(uint8_t byte); - const pixy_blob* read_buffer(size_t i); - - + bool recv_byte_pixy(uint8_t byte); + bool read_buffer(size_t i, pixy_blob& ret); private: struct blob_buffer { //Frame (full of blobs) - pixy_blob blobs[10]; + pixy_blob blobs[PIXY_PARSER_MAX_BLOBS]; size_t count; } blob_buffer[2]; @@ -68,8 +55,6 @@ class pixy_parser { uint8_t pixy_buf[PIXY_PARSER_PIXY_BUF_SIZE]; size_t pixy_len; uint8_t blob_buffer_write_idx; - size_t bytes_to_sof; - size_t bytes_to_block; }; From 38ebfaee656881d383c9fb20835ed555a36a13ee Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Tue, 4 Dec 2018 15:30:56 -0800 Subject: [PATCH 28/31] Pixy_parser driver code-complete, solved semaphore block issue (print statements caused sem block) --- libraries/AP_IRLock/AP_IRLock_I2C.cpp | 31 +++++++++++++++++++++------ libraries/AP_IRLock/pixy_parser.cpp | 14 ++++++------ 2 files changed, 32 insertions(+), 13 deletions(-) diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.cpp b/libraries/AP_IRLock/AP_IRLock_I2C.cpp index c00df6a1b8..b9cc15458d 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.cpp +++ b/libraries/AP_IRLock/AP_IRLock_I2C.cpp @@ -1,4 +1,4 @@ -/* + /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or @@ -31,6 +31,7 @@ extern const AP_HAL::HAL& hal; void AP_IRLock_I2C::init(int8_t bus) { + // printf("\nINIT"); if (bus < 0) { // default to i2c external bus bus = 1; @@ -41,8 +42,9 @@ void AP_IRLock_I2C::init(int8_t bus) { } sem = hal.util->new_semaphore(); -// printf("Initializing IRLock on I2C\n"); +// // printf("Initializing IRLock on I2C\n"); dev->register_periodic_callback(200, FUNCTOR_BIND_MEMBER(&AP_IRLock_I2C::read_frames, void)); + // printf("\nINIT END -----"); } /* @@ -50,13 +52,17 @@ void AP_IRLock_I2C::init(int8_t bus) { based on a characterization of IR-LOCK with the standard lens, focused such that 2.38mm of threads are exposed */ void AP_IRLock_I2C::pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, float &ret_y) { + // printf("\nPIXEL TO 1M PLANE"); + ret_x = (-0.00293875727162397f*pix_x + 0.470201163459835f)/(4.43013552642296e-6f*((pix_x - 160.0f)*(pix_x - 160.0f)) + 4.79331390531725e-6f*((pix_y - 100.0f)*(pix_y - 100.0f)) - 1.0f); ret_y = (-0.003056843086277f*pix_y + 0.3056843086277f)/(4.43013552642296e-6f*((pix_x - 160.0f)*(pix_x - 160.0f)) + 4.79331390531725e-6f*((pix_y - 100.0f)*(pix_y - 100.0f)) - 1.0f); + // printf("\nPIXEL TO 1M PLANE END-----"); } void AP_IRLock_I2C::copy_frame_from_parser() { + // printf("\nCOPY FRAME FROM PARSER"); for (size_t i=0; i<10; i++) { pixy_parser::pixy_blob blob; if (!pixyObj.read_buffer(i, blob)) { @@ -78,33 +84,43 @@ void AP_IRLock_I2C::copy_frame_from_parser() { target_count = i+1; -// printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); - printf("\nBLOCK:- \nX: %03u - Y: %03u - W: %03u - H: %03u\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); +// // printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); + // printf("\nBLOCK:- \nX: %03u - Y: %03u - W: %03u - H: %03u\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); } _frame_timestamp = AP_HAL::micros(); // 6. update frame_timestamp_us + // printf("\nCOPY FRAME FROM PARSER END----"); + } void AP_IRLock_I2C::read_frames(void) { + // printf("\nREAD FRAMES"); uint8_t buf[16]; dev->transfer(nullptr, 0, buf, 16); + // printf("\nUPDATE CALL AFTER"); for (size_t i=0; i<16; i++) { if (pixyObj.recv_byte_pixy(buf[i])) { + // printf("\nREAD FRAMES BEFORE SEMAPHORE"); + if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { // 2. take semaphore copy_frame_from_parser(); sem->give(); // 7. give semaphore + // printf("\nGIVE SEMAPHORE"); + } } } + // printf("\nREAD FRAMES END -----"); -// printf("\n&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&------------------OUT"); -// printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); +// // printf("\n&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&&------------------OUT"); +// // printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", blob.center_yr_x, blob.center_y, blob.width, blob.height); } // retrieve latest sensor data - returns true if new data is available bool AP_IRLock_I2C::update() { + // printf("\nUPDATE"); bool new_data = false; if (!dev || !sem) { return false; @@ -118,5 +134,6 @@ bool AP_IRLock_I2C::update() { sem->give(); } // return true if new data found + // printf("\nUPDATE END ----"); return new_data; -} \ No newline at end of file +} \ No newline at end of file diff --git a/libraries/AP_IRLock/pixy_parser.cpp b/libraries/AP_IRLock/pixy_parser.cpp index 912d8dd7a3..0e1e1807c2 100644 --- a/libraries/AP_IRLock/pixy_parser.cpp +++ b/libraries/AP_IRLock/pixy_parser.cpp @@ -180,7 +180,7 @@ bool pixy_parser::recv_byte_pixy(uint8_t byte) { // // printf("INSIDE recv_byte_pixy:-\n"); // Read 2 bytes // printf("\n---- IF_SWAP BEFORE: %d", if_swap_buffer); - + bool if_swap = 0; struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; @@ -213,13 +213,14 @@ bool pixy_parser::recv_byte_pixy(uint8_t byte) { if (writebuf.count != 0) { swap_buffer(); //swap buffer - if_swap_buffer = 1; +// if_swap_buffer = 1; + if_swap = 1; writebuf.count = 0; //Turn the count to 0 // printf("@@@SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); write_buffer(received_blob); //Writing inside the buffer(the count increment happens inside the write_buffer()) - return true; +// return true; } else { write_buffer(received_blob); //Writing inside the buffer(the count increment happens inside the write_buffer()) @@ -249,9 +250,10 @@ bool pixy_parser::recv_byte_pixy(uint8_t byte) { if (writebuf.count < PIXY_PARSER_MAX_BLOBS && writebuf.count != 0) { swap_buffer(); //swap buffer - if_swap_buffer = 1; - return true; +// if_swap_buffer = 1; + if_swap = 1; +// return true; } } - return false; + return if_swap; } From 6a77ae0ef4920cfe5f80841110e2acd79ce3c61d Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Fri, 7 Dec 2018 13:38:42 -0800 Subject: [PATCH 29/31] Added multi-target detection and contingency landing logic. Pixycam driver completed. Ready for Live testing --- libraries/AC_PrecLand/AC_PrecLand.cpp | 16 +++- libraries/AC_PrecLand/AC_PrecLand.h | 3 + libraries/AC_PrecLand/AC_PrecLand_Backend.h | 4 +- .../AC_PrecLand/AC_PrecLand_Companion.cpp | 3 +- libraries/AC_PrecLand/AC_PrecLand_Companion.h | 3 +- libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp | 87 ++++++++++++++++++- libraries/AC_PrecLand/AC_PrecLand_IRLock.h | 12 ++- libraries/AP_IRLock/AP_IRLock_I2C.cpp | 25 +++--- libraries/AP_IRLock/AP_IRLock_I2C.h | 5 +- libraries/AP_IRLock/IRLock.cpp | 20 +++++ libraries/AP_IRLock/IRLock.h | 3 +- libraries/AP_IRLock/pixy_parser.cpp | 11 +++ libraries/AP_IRLock/pixy_parser.h | 4 +- 13 files changed, 171 insertions(+), 25 deletions(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index d811fe5dbb..4c0b72f32a 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -11,6 +11,8 @@ #include #endif +//param show PLND_type + extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AC_PrecLand::var_info[] = { @@ -178,8 +180,7 @@ void AC_PrecLand::update(float rangefinder_alt_cm, bool rangefinder_alt_valid) } } -bool AC_PrecLand::target_acquired() -{ +bool AC_PrecLand::target_acquired() { if ((AP_HAL::millis()-_last_update_ms) >= 2000) { _estimator_initialized = false; _target_acquired = false; @@ -188,6 +189,17 @@ bool AC_PrecLand::target_acquired() return _target_acquired; } +void AC_PrecLand::set_target_acquired(bool _target_acquired_value) { + if (_target_acquired_value == false) { + _target_acquired = _target_acquired_value; + _estimator_initialized = false; + } + else { + _target_acquired = _target_acquired_value; + } +} + + bool AC_PrecLand::get_height_above_target_cm(int32_t& ret) { #if !HAL_WITH_UAVCAN return false; diff --git a/libraries/AC_PrecLand/AC_PrecLand.h b/libraries/AC_PrecLand/AC_PrecLand.h index 05cecd4b03..7e352ea8dc 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.h +++ b/libraries/AC_PrecLand/AC_PrecLand.h @@ -77,6 +77,9 @@ class AC_PrecLand // returns true when the landing target has been detected bool target_acquired(); + // sets the value of _target_acquired + void set_target_acquired(bool _target_acquired_value); + // process a LANDING_TARGET mavlink message void handle_msg(mavlink_message_t* msg); diff --git a/libraries/AC_PrecLand/AC_PrecLand_Backend.h b/libraries/AC_PrecLand/AC_PrecLand_Backend.h index e38ee89edc..2ec18760c7 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Backend.h +++ b/libraries/AC_PrecLand/AC_PrecLand_Backend.h @@ -10,7 +10,7 @@ class AC_PrecLand_Backend { public: // Constructor - AC_PrecLand_Backend(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state) : + AC_PrecLand_Backend(AC_PrecLand& frontend, AC_PrecLand::precland_state& state) : _frontend(frontend), _state(state) {} @@ -43,6 +43,6 @@ class AC_PrecLand_Backend int8_t get_bus(void) const { return _frontend._bus.get(); } protected: - const AC_PrecLand& _frontend; // reference to precision landing front end + AC_PrecLand& _frontend; // reference to precision landing front end AC_PrecLand::precland_state &_state; // reference to this instances state }; diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp index 05c2122950..b64544ca9c 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp @@ -1,10 +1,11 @@ + #include #include "AC_PrecLand_Companion.h" extern const AP_HAL::HAL& hal; // Constructor -AC_PrecLand_Companion::AC_PrecLand_Companion(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state) +AC_PrecLand_Companion::AC_PrecLand_Companion(AC_PrecLand& frontend, AC_PrecLand::precland_state& state) : AC_PrecLand_Backend(frontend, state), _timestamp_us(0), _distance_to_target(0.0f), diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.h b/libraries/AC_PrecLand/AC_PrecLand_Companion.h index 5b45e03e09..939980482c 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.h +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.h @@ -1,3 +1,4 @@ + #pragma once #include @@ -13,7 +14,7 @@ class AC_PrecLand_Companion : public AC_PrecLand_Backend { public: // Constructor - AC_PrecLand_Companion(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state); + AC_PrecLand_Companion(AC_PrecLand& frontend, AC_PrecLand::precland_state& state); // perform any required initialisation of backend void init() override; diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp index bc014a3e23..ba511c63d9 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp @@ -1,23 +1,59 @@ + #include #include "AC_PrecLand_IRLock.h" extern const AP_HAL::HAL& hal; // Constructor -AC_PrecLand_IRLock::AC_PrecLand_IRLock(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state) +AC_PrecLand_IRLock::AC_PrecLand_IRLock(AC_PrecLand& frontend, AC_PrecLand::precland_state& state) : AC_PrecLand_Backend(frontend, state), irlock(), _have_los_meas(false), - _los_meas_time_ms(0) + _los_meas_time_ms(0), +// _multiple_target_start_flag(false), +// _multiple_target_timestamp_start(0), +// _multiple_target_timestamp_latest(0), + _multiple_target_timestamp_log(), + _index(0) { } // init - perform initialisation of this backend -void AC_PrecLand_IRLock::init() +void AC_PrecLand_IRLock::init() { irlock.init(get_bus()); } + +void AC_PrecLand_IRLock::multiple_target_check() +{ + if (_index == 24) { + _index = 0; + } + _multiple_target_timestamp_log[_index] = irlock.num_targets(); + _index++; + + printf("\n _multiple_target_timestamp_log: "); + for (size_t j=0; j<24; j++) { + printf("%u ", _multiple_target_timestamp_log[j]); + } + + size_t count = 0; + for (size_t j=0; j<24; j++) { + if (_multiple_target_timestamp_log[j] > 1) { + count++; + } + } + uint16_t multiple_target_count_percentage = count*100/25; + printf("\nCount: %u -- Multiple_target_count_percentage: %u", irlock.num_targets(), multiple_target_count_percentage); + if (multiple_target_count_percentage >= 80) { + printf("\n----------------------------------------------------------------------HIGH COUNT PERCENTAGE: %u ------setting TARGET ACQUIRED FALSE -- %", multiple_target_count_percentage); +// count = 0; + _frontend.set_target_acquired(false); + } +} + + // update - give chance to driver to get updates from sensor void AC_PrecLand_IRLock::update() { @@ -27,12 +63,57 @@ void AC_PrecLand_IRLock::update() // get new sensor data irlock.update(); +// size_t no_targets_tmp = irlock.num_targets(); +// printf("\nOUTSIDE Number of targets - BEFORE %u", irlock.num_targets()); +// printf("\nHEALTHY: %u", irlock.healthy()); + if (irlock.num_targets() > 0 && irlock.last_update_ms() != _los_meas_time_ms) { + +// printf("\nNumber of targets OR Count: %u", irlock.num_targets()); + printf("\n\nAP_HAL::millis(): %u - _los_meas_time_ms: %u - irlock.last_update_ms(): %u",AP_HAL::millis(), _los_meas_time_ms, irlock.last_update_ms()); + irlock.get_unit_vector_body(_los_meas_body); _have_los_meas = true; _los_meas_time_ms = irlock.last_update_ms(); + +// printf("\n_multiple_target_start_flag: %u", _multiple_target_start_flag); + multiple_target_check(); + + +/* + + // Logic for Contingency Landing + if (irlock.num_targets() > 1) { // If found multiple targets + + if (_multiple_target_start_flag == 0) { //If it is the 1st time found multiple targets so put the value inside a "start variale" + _multiple_target_timestamp_start = AP_HAL::millis(); + _multiple_target_start_flag = 1; + } + + if (_multiple_target_start_flag == 1) { //If multiple target is seen again i.e. repeated so put the value inside "other variable" + _multiple_target_timestamp_latest = AP_HAL::millis(); + } + + if (_multiple_target_timestamp_latest - _multiple_target_timestamp_start > 500) { //If we are getting multiple targets for more than 500ms, go to contigency +// _frontend.target_acquired(true); + printf("\n----------setting TARGET ACQUIRED FALSE"); + _frontend.set_target_acquired(false); +// _frontend._target_acquired = false; +// _frontend._estimator_initialized = false; + } + } + else { // If found a single value within 500 ms so put the start_flag = 0 and restart looking for the multiple target + _multiple_target_timestamp_latest = AP_HAL::millis(); + if (_multiple_target_timestamp_latest - _multiple_target_timestamp_start < 500) { //If we are getting multiple targets for more than 500ms, go to contigency + _multiple_target_timestamp_start = 0; + _multiple_target_start_flag = 0; + } + } +*/ } + _have_los_meas = _have_los_meas && AP_HAL::millis()-_los_meas_time_ms <= 1000; + } // provides a unit vector towards the target in body frame diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h index bcf78f57c2..60e8c77950 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h @@ -1,3 +1,4 @@ + #pragma once #include @@ -19,7 +20,7 @@ class AC_PrecLand_IRLock : public AC_PrecLand_Backend public: // Constructor - AC_PrecLand_IRLock(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state); + AC_PrecLand_IRLock(AC_PrecLand& frontend, AC_PrecLand::precland_state& state); // perform any required initialisation of backend void init() override; @@ -37,10 +38,19 @@ class AC_PrecLand_IRLock : public AC_PrecLand_Backend // return true if there is a valid los measurement available bool have_los_meas() override; + void multiple_target_check(); + + private: AP_IRLock_I2C irlock; Vector3f _los_meas_body; // unit vector in body frame pointing towards target bool _have_los_meas; // true if there is a valid measurement from the camera uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured + + uint32_t _multiple_target_timestamp_log[25]; // array of timestamps when multiple targets detected +// uint32_t _multiple_target_timestamp_start; // array of timestamps when multiple targets detected +// uint32_t _multiple_target_timestamp_latest; // array of timestamps when multiple targets detected +// bool _multiple_target_start_flag; + size_t _index; }; diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.cpp b/libraries/AP_IRLock/AP_IRLock_I2C.cpp index b9cc15458d..ee695c1551 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.cpp +++ b/libraries/AP_IRLock/AP_IRLock_I2C.cpp @@ -77,18 +77,21 @@ void AP_IRLock_I2C::copy_frame_from_parser() { pixel_to_1M_plane(corner1_pix_x, corner1_pix_y, corner1_pos_x, corner1_pos_y); pixel_to_1M_plane(corner2_pix_x, corner2_pix_y, corner2_pos_x, corner2_pos_y); - _target_info[target_count].pos_x = 0.5f*(corner1_pos_x+corner2_pos_x); // 4. copy frame data from pixy parser to target info array - _target_info[target_count].pos_y = 0.5f*(corner1_pos_y+corner2_pos_y); - _target_info[target_count].size_x = corner2_pos_x-corner1_pos_x; - _target_info[target_count].size_x = corner2_pos_y-corner1_pos_y; + _target_info[i].pos_x = 0.5f*(corner1_pos_x+corner2_pos_x); // 4. copy frame data from pixy parser to target info array + _target_info[i].pos_y = 0.5f*(corner1_pos_y+corner2_pos_y); + _target_info[i].size_x = corner2_pos_x-corner1_pos_x; + _target_info[i].size_x = corner2_pos_y-corner1_pos_y; - target_count = i+1; + _num_targets = i+1; +// printf("\n Num_targets in the loop: %u", _num_targets); // // printf("\nBLOCK:- \nX: 0x%04x - Y: 0x%04x - W: 0x%04x - H: 0x%04x\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); - // printf("\nBLOCK:- \nX: %03u - Y: %03u - W: %03u - H: %03u\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); - + // printf("\nBLOCK:- \nX: %03u - Y: %03u - W: %03u - H: %03u\n\n\n", blob.center_x, blob.center_y, blob.width, blob.height); } - _frame_timestamp = AP_HAL::micros(); // 6. update frame_timestamp_us + + _frame_timestamp = AP_HAL::millis(); // 6. update frame_timestamp_us +// printf("\nFrame Timestamp Init: %u", _frame_timestamp); + // printf("\nCOPY FRAME FROM PARSER END----"); } @@ -123,14 +126,16 @@ bool AP_IRLock_I2C::update() { // printf("\nUPDATE"); bool new_data = false; if (!dev || !sem) { - return false; + return false; } if (sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { if (_last_update_ms != _frame_timestamp) { new_data = true; } _last_update_ms = _frame_timestamp; - _flags.healthy = (AP_HAL::millis() - _last_read_ms < 100); + _flags.healthy = (AP_HAL::millis() - _last_update_ms < 100); +// printf("\nHEALTHY COMPARE STATUS: %u", _flags.healthy); +// printf("\nHEALTHY COMPARISON (AP_HAL::millis(): %u - _last_read_ms: %u < 100)", AP_HAL::millis(), _last_update_ms); sem->give(); } // return true if new data found diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.h b/libraries/AP_IRLock/AP_IRLock_I2C.h index 6707fc8b78..8c42433b4f 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.h +++ b/libraries/AP_IRLock/AP_IRLock_I2C.h @@ -18,7 +18,7 @@ class AP_IRLock_I2C : public IRLock pixy_parser pixyObj; -private: +private: AP_HAL::OwnPtr dev; void read_frames(void); @@ -27,5 +27,4 @@ class AP_IRLock_I2C : public IRLock AP_HAL::Semaphore *sem; uint32_t _last_read_ms; - size_t target_count; -}; \ No newline at end of file +}; \ No newline at end of file diff --git a/libraries/AP_IRLock/IRLock.cpp b/libraries/AP_IRLock/IRLock.cpp index 63feca3f40..6276539832 100644 --- a/libraries/AP_IRLock/IRLock.cpp +++ b/libraries/AP_IRLock/IRLock.cpp @@ -32,6 +32,26 @@ bool IRLock::get_unit_vector_body(Vector3f& ret) const return false; } + //Here there shold be aa check that cmpares the timestamp at which the previous velue of count was plural + //And then if even after 500 millisec timestamp it shows plural count so return false + +/* + if (current_timestamp >= prev_multiple_count_timestamp + 500ms) { + if (count > 1) { + return false; + } + } + + //REAL CODE: + if (!AP_HAL::millis() >= get_multiple_count_start_timestamp() + 500) { + if (readbuf.count > 1) { + return false; + } + } + + + ALSO CODE WRITTEN IN PIXY_PARSER.CPP : RECV_BYTE_PIXY() +*/ // use data from first (largest) object ret.x = -_target_info[0].pos_y; ret.y = _target_info[0].pos_x; diff --git a/libraries/AP_IRLock/IRLock.h b/libraries/AP_IRLock/IRLock.h index 5d87748ba2..42415937cd 100644 --- a/libraries/AP_IRLock/IRLock.h +++ b/libraries/AP_IRLock/IRLock.h @@ -38,7 +38,7 @@ class IRLock uint32_t last_update_ms() const { return _last_update_ms; } // returns the number of blocks in the current frame - size_t num_targets() const { return _flags.healthy?1:0; } + size_t num_targets() const { return _flags.healthy?_num_targets:0; } // retrieve latest sensor data - returns true if new data is available virtual bool update() = 0; @@ -70,5 +70,6 @@ class IRLock } irlock_target_info; irlock_target_info _target_info[10]; + size_t _num_targets; }; diff --git a/libraries/AP_IRLock/pixy_parser.cpp b/libraries/AP_IRLock/pixy_parser.cpp index 0e1e1807c2..0196533a19 100644 --- a/libraries/AP_IRLock/pixy_parser.cpp +++ b/libraries/AP_IRLock/pixy_parser.cpp @@ -203,6 +203,17 @@ bool pixy_parser::recv_byte_pixy(uint8_t byte) { // } // printf("\n"); + +/* + if (writebuf.count > 1) { + if (!AP_HAL::millis() <= multiple_count_start_timestamp + 500) { + multiple_count_start_timestamp = AP_HAL::millis(); + } + } + +*/ + + if (validity == MESSAGE_VALID_SOF) { if (!(writebuf.count >= PIXY_PARSER_MAX_BLOBS)) { pixy_blob received_blob; diff --git a/libraries/AP_IRLock/pixy_parser.h b/libraries/AP_IRLock/pixy_parser.h index d0a6c3c99b..a846958718 100644 --- a/libraries/AP_IRLock/pixy_parser.h +++ b/libraries/AP_IRLock/pixy_parser.h @@ -32,7 +32,6 @@ class pixy_parser { void swap_buffer(void); bool recv_byte_pixy(uint8_t byte); bool read_buffer(size_t i, pixy_blob& ret); - private: struct blob_buffer { //Frame (full of blobs) @@ -55,6 +54,9 @@ class pixy_parser { uint8_t pixy_buf[PIXY_PARSER_PIXY_BUF_SIZE]; size_t pixy_len; uint8_t blob_buffer_write_idx; + + +// uint32_t multiple_count_start_timestamp; }; From 9886d1418605aa065d112a085213d41718e5266f Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Fri, 7 Dec 2018 14:20:50 -0800 Subject: [PATCH 30/31] Cleaned the code and cleared garbage print statements --- libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp | 57 ++------------------ libraries/AC_PrecLand/AC_PrecLand_IRLock.h | 6 +-- 2 files changed, 7 insertions(+), 56 deletions(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp index ba511c63d9..7a65c3fb1c 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp @@ -10,9 +10,6 @@ AC_PrecLand_IRLock::AC_PrecLand_IRLock(AC_PrecLand& frontend, AC_PrecLand::precl irlock(), _have_los_meas(false), _los_meas_time_ms(0), -// _multiple_target_start_flag(false), -// _multiple_target_timestamp_start(0), -// _multiple_target_timestamp_latest(0), _multiple_target_timestamp_log(), _index(0) { @@ -24,7 +21,7 @@ void AC_PrecLand_IRLock::init() irlock.init(get_bus()); } - +//multiple_target_check - Checks if multiple targets detected for 500 ms continously. If yes, sets target_acquired=False which calls contingency landing void AC_PrecLand_IRLock::multiple_target_check() { if (_index == 24) { @@ -33,11 +30,12 @@ void AC_PrecLand_IRLock::multiple_target_check() _multiple_target_timestamp_log[_index] = irlock.num_targets(); _index++; +/* printf("\n _multiple_target_timestamp_log: "); for (size_t j=0; j<24; j++) { printf("%u ", _multiple_target_timestamp_log[j]); } - +*/ size_t count = 0; for (size_t j=0; j<24; j++) { if (_multiple_target_timestamp_log[j] > 1) { @@ -45,10 +43,9 @@ void AC_PrecLand_IRLock::multiple_target_check() } } uint16_t multiple_target_count_percentage = count*100/25; - printf("\nCount: %u -- Multiple_target_count_percentage: %u", irlock.num_targets(), multiple_target_count_percentage); +// printf("\nCount: %u -- Multiple_target_count_percentage: %u", irlock.num_targets(), multiple_target_count_percentage); if (multiple_target_count_percentage >= 80) { - printf("\n----------------------------------------------------------------------HIGH COUNT PERCENTAGE: %u ------setting TARGET ACQUIRED FALSE -- %", multiple_target_count_percentage); -// count = 0; +// printf("\n----------------------------------------------------------------------HIGH COUNT PERCENTAGE: %u ------setting TARGET ACQUIRED FALSE -- %", multiple_target_count_percentage); _frontend.set_target_acquired(false); } } @@ -63,57 +60,13 @@ void AC_PrecLand_IRLock::update() // get new sensor data irlock.update(); -// size_t no_targets_tmp = irlock.num_targets(); -// printf("\nOUTSIDE Number of targets - BEFORE %u", irlock.num_targets()); -// printf("\nHEALTHY: %u", irlock.healthy()); - if (irlock.num_targets() > 0 && irlock.last_update_ms() != _los_meas_time_ms) { - -// printf("\nNumber of targets OR Count: %u", irlock.num_targets()); - printf("\n\nAP_HAL::millis(): %u - _los_meas_time_ms: %u - irlock.last_update_ms(): %u",AP_HAL::millis(), _los_meas_time_ms, irlock.last_update_ms()); - irlock.get_unit_vector_body(_los_meas_body); _have_los_meas = true; _los_meas_time_ms = irlock.last_update_ms(); - -// printf("\n_multiple_target_start_flag: %u", _multiple_target_start_flag); multiple_target_check(); - - -/* - - // Logic for Contingency Landing - if (irlock.num_targets() > 1) { // If found multiple targets - - if (_multiple_target_start_flag == 0) { //If it is the 1st time found multiple targets so put the value inside a "start variale" - _multiple_target_timestamp_start = AP_HAL::millis(); - _multiple_target_start_flag = 1; - } - - if (_multiple_target_start_flag == 1) { //If multiple target is seen again i.e. repeated so put the value inside "other variable" - _multiple_target_timestamp_latest = AP_HAL::millis(); - } - - if (_multiple_target_timestamp_latest - _multiple_target_timestamp_start > 500) { //If we are getting multiple targets for more than 500ms, go to contigency -// _frontend.target_acquired(true); - printf("\n----------setting TARGET ACQUIRED FALSE"); - _frontend.set_target_acquired(false); -// _frontend._target_acquired = false; -// _frontend._estimator_initialized = false; - } - } - else { // If found a single value within 500 ms so put the start_flag = 0 and restart looking for the multiple target - _multiple_target_timestamp_latest = AP_HAL::millis(); - if (_multiple_target_timestamp_latest - _multiple_target_timestamp_start < 500) { //If we are getting multiple targets for more than 500ms, go to contigency - _multiple_target_timestamp_start = 0; - _multiple_target_start_flag = 0; - } - } -*/ } - _have_los_meas = _have_los_meas && AP_HAL::millis()-_los_meas_time_ms <= 1000; - } // provides a unit vector towards the target in body frame diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h index 60e8c77950..fa46658615 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h @@ -38,6 +38,8 @@ class AC_PrecLand_IRLock : public AC_PrecLand_Backend // return true if there is a valid los measurement available bool have_los_meas() override; + //multiple_target_check - Checks if multiple targets detected for 500 ms continously. + //If yes, sets target_acquired=False which calls contingency landing void multiple_target_check(); @@ -47,10 +49,6 @@ class AC_PrecLand_IRLock : public AC_PrecLand_Backend Vector3f _los_meas_body; // unit vector in body frame pointing towards target bool _have_los_meas; // true if there is a valid measurement from the camera uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured - uint32_t _multiple_target_timestamp_log[25]; // array of timestamps when multiple targets detected -// uint32_t _multiple_target_timestamp_start; // array of timestamps when multiple targets detected -// uint32_t _multiple_target_timestamp_latest; // array of timestamps when multiple targets detected -// bool _multiple_target_start_flag; size_t _index; }; From 59575de37ff664d6fa51aa0791d26e28d4182b4c Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Thu, 28 Feb 2019 17:13:42 -0800 Subject: [PATCH 31/31] Added Multi target detection alert & made it ready to be uploded on vehicle with no couts --- libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp | 3 +++ libraries/AP_IRLock/AP_IRLock_I2C.cpp | 2 +- libraries/AP_IRLock/pixy_parser.cpp | 8 +++++--- 3 files changed, 9 insertions(+), 4 deletions(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp index 7a65c3fb1c..89a6abc036 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp @@ -1,6 +1,7 @@ #include #include "AC_PrecLand_IRLock.h" +#include extern const AP_HAL::HAL& hal; @@ -46,6 +47,8 @@ void AC_PrecLand_IRLock::multiple_target_check() // printf("\nCount: %u -- Multiple_target_count_percentage: %u", irlock.num_targets(), multiple_target_count_percentage); if (multiple_target_count_percentage >= 80) { // printf("\n----------------------------------------------------------------------HIGH COUNT PERCENTAGE: %u ------setting TARGET ACQUIRED FALSE -- %", multiple_target_count_percentage); + gcs().send_text(MAV_SEVERITY_CRITICAL, "Multiple Targets Detected"); + // Send sn alert telling multiple targets detected _frontend.set_target_acquired(false); } } diff --git a/libraries/AP_IRLock/AP_IRLock_I2C.cpp b/libraries/AP_IRLock/AP_IRLock_I2C.cpp index ee695c1551..ccce43195d 100644 --- a/libraries/AP_IRLock/AP_IRLock_I2C.cpp +++ b/libraries/AP_IRLock/AP_IRLock_I2C.cpp @@ -135,7 +135,7 @@ bool AP_IRLock_I2C::update() { _last_update_ms = _frame_timestamp; _flags.healthy = (AP_HAL::millis() - _last_update_ms < 100); // printf("\nHEALTHY COMPARE STATUS: %u", _flags.healthy); -// printf("\nHEALTHY COMPARISON (AP_HAL::millis(): %u - _last_read_ms: %u < 100)", AP_HAL::millis(), _last_update_ms); +// printf("\nHEALTHY COMPARISON (AP_HAL::millis(): %u - _last_read_ms: %u < 100)", AP_HAL::millis(), _last_update_ms); sem->give(); } // return true if new data found diff --git a/libraries/AP_IRLock/pixy_parser.cpp b/libraries/AP_IRLock/pixy_parser.cpp index 0196533a19..12a8f9ec4f 100644 --- a/libraries/AP_IRLock/pixy_parser.cpp +++ b/libraries/AP_IRLock/pixy_parser.cpp @@ -57,6 +57,7 @@ void pixy_parser::empty_pixyBuf() { } } +/* // Method - print_buffer void pixy_parser::print_buffer() { struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; @@ -67,6 +68,7 @@ void pixy_parser::print_buffer() { } // printf(" - Count: %u\n", (unsigned)writebuf.count); } +*/ // Method - write_buffer bool pixy_parser::write_buffer(const pixy_blob& received_blob) { @@ -79,7 +81,7 @@ bool pixy_parser::write_buffer(const pixy_blob& received_blob) { writebuf.blobs[writebuf.count] = received_blob; // printf("SEE THIS---- [%u, %u, %u, %u], ", (unsigned)received_blob.center_x, (unsigned)received_blob.center_y, (unsigned)received_blob.width, (unsigned)received_blob.height); writebuf.count++; - print_buffer(); +// print_buffer(); return true; } @@ -90,8 +92,8 @@ void pixy_parser::swap_buffer() { // printf("Swapping Main Buffer: Swapped to %u\n", blob_buffer_write_idx); // struct blob_buffer* writebuf = &blob_buffer[blob_buffer_write_idx]; struct blob_buffer& writebuf = blob_buffer[blob_buffer_write_idx]; - writebuf.count = 0; //This is probably wront. But helps me get rid of an error!!!----------------------------------------------------------- - print_buffer(); + writebuf.count = 0; //This is probably wrong. But helps me get rid of an error!!!----------------------------------------------------------- +// print_buffer(); } // Method - read_buffer

LYz@z*qUi%`waT5Ki@M1O2abSD4)LoYjXwR02c66Mi zaUi~m9}6k?HM;vnKkRsSJIXIKOYbK@xk{T{i2x8ooHs`^LC-n{Q1iSsWBEA;H7;Y)kj&Us-mih&uOI|7dN} z8xI2eDEiT9B0t?aP~{EdSLH3M;+GKl^_PCJeVuiobX#oi}1T6~8VCKWxvg68)<5%S!a~@6UB$e-rUk_0oE}b3d~9 zo#UQg%kENdez6_ZuM^`qOZ2OXqvU|%>Y&j2OMqV*2gOTk@@tpapcdb6 zSBrL3KMSwLo6hZLDC*@wcfV8@hiq`ExfZr3`G>%h+U zrk`%SY_zv}R_Ukfw^`yB+q0yo3)R`OTk8IO7+v6pT`%HE^KtRO=-f1>IGwF{7m56+ zE``>8rzXFW1D)fr_}wDvO!+0CJ-bP?qxqn5WX^FO52#(+MCa!mTl|)J^Na0t>z*F> zDZlzUXZ@%h`c>h@0Z+v*rD^9oNRMAu5(n~ToubaP4qCtudq}jSbztFLA=W*$qxz*< zoa@EHd%@i=#lv>0e4w2wAI)R+bdG?X3J?9N_;qRe?LJST-;<(#G{4A){mon6y3Tj@ ztD6tY?`tAIRlQ(4mCl)Zo;Q_UaGYL#(XT3RXot_c34hP=sV?o{SH-Va!VmqhXGQ&J ze(V3t{j+C8JC)9f3%%u66-Nqq=&nboboL#rm){WBQNNact?u&@%kD){KdN&F_+ee5 zol57Hi=B10{J!a}Ut&8|KF|)g!L|8(n$~G#eE;^3)FEkG1tI{P3@v3xb zA^c={L%*v2+kUBD98EVVu9v+d>P+*Irwh3*9(jsiZ>-1b{%?tRs=WCkV%}u;DFiOl zi_ z>K{B>S4rS2)#YQ+Z(h7e@NUtL#*1d`Yj-=!58F{)s9n=Ut~-r`+94ipWyg<_Nn-zy zjT=#7hvROZU($c^`Y*NXSir{(dwYIy8^J?e z5RcvGu?~oS7%$Z?*ek|?`dNPOFV3&*J|mhB-}Iq^{_GofzZSpmH0_3Z`@DGkzoIVq z`B2O6kM4e{&NNTZ%&o7zp>gw$KMf8h0Q@@ zw-@S%#^GOw*RxlCc%P~z*DuB8SK5Cq2mA%j5AZo8ZRx{Yzqcj0jK^1cw|Kmi&6`pR zJE|Ye8}<*R9lgihZyp{tgl*;=@p(QyUh&9rTJ||AbW6X_N5&6%pnaYl@!JdEgOFzj zju8iW$n28q?~?0}T}SeMkY`8y%I0-6Z@P9kuBrU$-k+`OS9;$tiMPM)q|YTLes$x; zevWx&!@SL#qMM2LZQ{I1m5<;N&f_U#BA#?SCGq-JIv;=Q*LMEAl@;&Tn(KsP-E~2{ zNIUNj_@18UQC-68I`gA;h)367dhmSuBX8qxgwlb#8(7?0auI`!kBV-%0eV${X^fy3lw_8=d2&c8I6SM>F85 z{3a!S(GOcsjF;-%1MS(mqMfcTsyGrKEAla+L|A8`eyuomD~z8?Kg3tr#Wvynm-aVo z&o&VGQJtf+Vcb|>w3Eg=)ZLEORcwW`&eRV1s^aYhzBFEn*R9fJV=)e@OS}nm*+{gb zx=_ERE1l!T_}EBqc-T&*i*Jr|KgagWC;FxF#-KghRJ2pY+og)P!W$m)RmCf_!~JXv z(JzfR@>j_3=As>q*TSoDx1)7{?Fx;9;`IPuTKDLORg3&+yy0UZ-b&Gq#!LMozG^&e z1$fiv;j>hZR?}3Hksp<;jQq_TPzM>Asiu|Z9F=)@~L_3u($uAV+eZ4n4-FS8FN*5?} zIYi_~b!mq7>|oK3>VkaOcz3(L?;)Qyd-lS{+0zy`Hq4nnW5K*R^Jh0qn>lk~-aNKLfhW_2_Fwed(jl%F(|VEN zVf*m8e7(2_)<*;Pig-Qei}B0wC=Zz(;-kIH4*!lkWp=o}+j|_0x6q)I#6fjI-1G%v zeAJHmO|QeR?|0m=L+-qVwr45#^HucgBf3(*XcxZF8$WEx3^9SnR21cdW{86Mu(99=5*bM}XOyfQppe(1Ls{8BvMQ1O1B?jX5ux8hsN9j{Pb!Y7KnrFB5&O|tq!zSxg?PT=^I zUpL&3PR~EEJv(Dy;*Fl97jMfJVt@0hixtON0~1HDW*oHcb@SE^_%v@;T<}8H-`Y;r z)45Q7^#q@_c+{EHv-EqlAWmARcz;PJd|#GqOZ7|d#g88pkLoJ>J_5^b#rnc=l+Np@ z-=-BjAFB1C=t?nfrRSFle%Qqr#h)O<}rHWUE7r08Xu5!4y>wdKVrk``ZkD{cE*S)I# z(g{(Q%m`;Z>bH5h#18U7>%~gbk>29%1%5P+mNu>{yUD#@T7EBex1;$j35drd*?83f zJSacQ?*rcac1!RmKg5@gYYpCXj-BD$FH5fmoiBHf1NpE{(T=Xe$>N~(LhVY=!M|+K(EMf%a^MXs4^6s{WD^etB^~LTElPPi%T&{3ssv+XMVmafHuv z&WFWsp10#=E8x+*QGQJlJIn8}qAoPQ!Sgw9Hb=Ch`L*zF@z#$LhdTEU3vZUYUm7pA zQ{_$9E^vW!-l*UBKb+^;)UF=zXx@+yTO`Iy^O1t~Y=LMe&Bu#kJ}92=Ldb8IXh-pA z9LTr7bZ!A2s(#b~c2fP07j>cWvWp>8FYp@s&E$UjK+)tJgo80FUxR9oUJY&NROnXwOa%?Pz`rjkn`4=kZDx&x+%` zf#H|FL@yt`U`KVPadb=aX2o%e7zfQqycPP}$)X+2hlTfqW`BEIw4;7$9LdA=@|NCB zJnxPT8Je44WigJoM87l+>KEfu^`n+c_43vMcB;J5^^(k1d*dIbp*Tu5?P~@koQ*4LNNoa%qLivT3>OE%+ z@lTT!e zY}0t7BRM}+9LSgIjQiOo?sZ_C7Szt@O(w4Sj&yVB!vdT%{lBJF&fL_c^P zo9axDGqUT+!RvV4TX?$-bzFa@c+%%gj1ub)pO=xx4;{i*b{~qiU((-n?~_TB_}Tg1 z^43h^#p7k6@%oZtJ_^2X=|cB7EctI0?Nt4vhsF!fNr)luTSPqCKMK{Q^oHVek@>~@ z+`56k%uYHUT*cqN*h$ApGM-`_dHjf-^mqhuV1MfcJt$r(sh8g@#6j~*@n}Bqcx1_XkC+dd-`Fjn z>)oQAZr;+|g`hwS(pxmB+YlEhA02f$AmM}c+F4f^KkLhxkuS8}srJiSlM z8_lmJ|KCKr|J(U3Y1hkJkl0D{M)cF|m!1CU8sJlyyf+`HW5#ybLM#Gb%8v; zRwCW|QT#SBKH2=Ljo9_K&H=!0yPelBd(@jQ7_PEk9wg4klSBFZ9^13Od-L0JBF_gM zcM&hPcVVADQpM4IJI|ZyxXF&cPZ-hRgoXnxfj~Amqk03&hfjsU#vITx_le4>+R;xd!_NFh@EUarFp|~ zh~iN@>HXsnfU53&_vqDq2<)VF|CXpT%|{EgXK#phs(fG`RB?1`#=$zA>ncxYP5mN( zr>f^>iC>J5y)WuQ_3MK6tXs6}Fa3~*Dvr!5=XFeM&#v{xFMO}Jd{BOt-|M~k?YdC> z9I5Pl0r6@5;ePgaZ{JTGy-%;dwSyh)Z-v%rucqI?{m%KY;=R$E&e)FXN8@O{zbDcxv!_Hms$bu8ab`3f8*iA` zIB!P$gogPGrq7>g{BP_7!g+C!`I>57p2mwhux0N2sNdk)&bm-L#HW6#UHV~XJZ#UN z7x_`01D(7*drq{YI#a)hui{sFtn)mZ;>Cf7bliBMfA}Hq*8h4t5A{8w(D@aSAJw@9 z+OwBLyZ+L-TgC4+cfY6$n9CuwEo_9_e=3mPgVbDeN3Utd!k>eO9tArcSSp@i;Q2}3H*Cbkgv>66^H*gy?!2j zToLaF?r|VbcJjc~Y2XP3zmG(IG#|S9#la8zw}_{kH@r^Lv<06x>iVU2ZIXDYo$pD7 zE*}>bhpMjH7xKDN*>y|!(KxVvRCuLNDdN4rTm6+Buh&1iw{|`cK;Ginav z*_j`?c3_vSv=r{?0T~ARK0$QcvKgvbNllg5AE^$I`BQ)b+Bt4P`uQ3-r`l| zH+h;~yj_}h-P=3!v*NwgTOH7KQM|53bwPYpyrDClK;^)BJx zOV)d}^SW~S0cZVayxl>~`-_j_co<*o3unLhcUc_x_qOTc`kL(eG|gLJrL*78=lJ-7 z_+I&8JNAS7eJxbK#B$NE?0P_&*m+$~q<(t|Ua{8=njhx*RgFWa6V9(X;Cc<^7n5A) z?0FByu~*h}9k0+2+g9^_(RJO|SuMQv-H$UEhcCKp=HvXy@l>Vo=hhIr|D zD7BOM#r^D4aXwDZQ~WQ2t}8@4I={+4pN=~(u%Y7}-RoI54r$Pv`6G0l-t~ zBIAeq*#_?8AJrwL>9-B+Xg(;O?-i~ywX^uG67xp;8^yzRDqT8Me!p|~%U*^0_*S%| z{oH)sq4^s=hks9X>TuC4sL>moBiA=Hq)YUYZa8 zYoJSyXh(HH-i*1|pJlg^yB*aJ+o|I11isREH*xoieps&vQzBd_ zD{AN8+u5%5J?PJnsM1ONdlfKm*|4|!1*qT9)1?27caInSCPumYMLRaZ9WSr0$oU(7 zj|AfRN4xu_c)|BY{esJ!&j)*nT{qaF-}*7${8F81-dMz47xc>}x!cirqn|jhD_eM* zxsL}F58Kgk7x$Mg@uo}a1HJK}bh+Mq9C@gYzg_2w>)x{U2;aXH_wplCX{|9j|)yo|7Lw&6{70i|UN~*|zSw(7I~x;`x=vv7I+O-jDD$hrP#9LX#{FOl;5lQ(|4`n3Z;S_hOL`-ff}Y0Y@)cS zyci#Q$=!~|QJ>*)V0-jS?ffr0*E6+499pNipS|FXpYLP6x{84vtrr=;`m@FRuPlC# zc{?7_yy5j<3vY2U&J_6{VhIS>~E+Gt%KxHO@5@Va2&Gu z1-*^C&7V8xjq*!D94h^KNF7M~IS^L$x5(FgKBUTTILqTu*`ZEKJEAk@4coJSd8>m` z`uVp#ock~B=d$sX+7)}eOnf2Mfv#U1pDkT>(7PW5?GyJa=DQENf3AquX}D4BZ%k8X zT|11I`pteR>L3{(Ig z{?etbOw6xrT#L-%`Bue&d{z3jf1{^g8tkZF^uwO_rc3BqKK@~QS-iBr;c=hVOZ;1+ z-)GM2&(UMKeyZbO3h<=yzUUq=#>JvyKce#{Uk~tpLBykWG+xA4<=1ySKYvlh8@+<_ zpz%__@wwu02Cs7>ANJC~#6jx-KSyf$eMR(3`=w(kv$izo7m~bTmQaop*r#mmv9Vd0`ioxgkRrR7<&$|5n$Jto}EPoMP+xd9ebC}+EK{ zi?@f^$&MdQH}msB)IpZFa6&wvk@<}tE%KA$p+7v%M1U_H4?2Gn@ud18ptW`GMsNQ&Z3R84&TYqtx)gg{2>c=9$>#S|KbbCZf+w@n z#Y^=wo^Q1nuP#4X|A-ZcCz}^{6o@CQgVg#wUe$SbDRW-WvAXF#9>-m1NY@1{yv@Ab zKb{1BsyKR7aU3AVLC?==e@o1FUWW@0g7t^}M7;i5FX;q)RlFInqw6J>&Z7o~Uvw?K z^{WKfN%_@@{AfPX(4LJE?WoRHyzs(j+hPCyJeprLqjgH{S{isiqH$2W^lAKfhPXI? zp?3IpmEY9bdOFkbR5o5^0guLkeAvOF&NLsfb)fFYiFPy}g~rQb^E)ahZOU4Q8k1$(%5JC{gHqjL47b9EbMoDABIJbWQ=j zO6RO34mutr?{r>&w(2=HFmbf3uQwiafSt5nW{Ui1KG+6O_tQnY{>n!L@KyO}20LjS zvj&D=k0w9=hKjoXtH_V)+yw1elW3>Xx%3S2c%)iaQOysMs_}WQH-6X;RDS7vL-u`! z(T()#z8&nO^%583p!w*9_H4drr^<(Jyzv>%$3Z&2=;F0)tfxx~?4-IZ7UQM5_%?y@ zV3BC2(j`30`MeS1V@tf@VLMe_bpT&FzF>QHyy%z4%Ql60mx^|(c+(Tbei@K_A2{+* z#nB8rXdJX&l3*vzZ?m^JXup)52Xr0@I$=PX_i1%5cYZEJ?^&XLGQX4`{Tv!Q)O}q5 z>9U{2>+CeYmR)jv;rTn%j^@K^XT9KYQM)Ah+>>k^Pj4pbEL(5tC3d>&iL!Of)bYIk zVi+>NO;?F|!{_kPcxm2r*DKqAfC2G<)q?tWNz~iTu3g4Y}Y}mtVR~>>s$! zia2cJ!3B*k*7Xz;KO5mKZ^5laUA*Rv<|9GyWcg?(cE#pnBTG=m?Db;p-ljO6O9)>! z(p_iEFTB{qw!_Yk>X+TdIUly>xtCtoC;QqvACE$Q(XT9TEyND<)`!nuY4aoZ56O;4 z-NdhqU+K1D9R1Btcie3wc|?6=y5Qg08Q$tjhDYnlzn!Ry*M4sCgBJnY4!3%4C4Oaj z>m+uVHyQ_>M_|2JbRP9MUnBLGcR!}bc##K=&po6b*_rP7rSbaUd1KEha+d7XMZNx9;x33+46}IhgtCtkP^I8Wqj@B4C{=)s#HafYNy8K$FI6udM z`bB)KgEZ)#XGiJ}?>ofy>~Z&cw(Q_V*tWw>XEgI25D?}cDt>rB9JUX<>+yL7BwpEh zPxGI|dX`=9j+5sm%k1ij9e%D7<6u*~^-DSq^?u=e-(h$sF%I-gb&kyt>lEX#_)Yc3 zFPad~-=yDrNb(Wya=tIJmpm^Q@AI(u9qo-D)i3pev)@EO)X(>lvmNqKj*~l!c%3pl zqD#|@&VIXQih0BPHjxjTR-7)fb&xg^M|Y6(v;5BR<~ItTXTtVA_ONPj`}A|pc`Myjtb^v|&UVT;7P#}X;yBLTj>bX#VjWm`H}(%6 z_1i;q@vU?o*JS)CUU-P8bBW~hOc+<>9Le)7Zg!6s+p}BT?I^#NGZZSH<8yE`@Q?$WfoThs0yO}h?FyQeknp3$^h=59ypnbu3*`0|`Po|TW~ns(1? z+I4B#y`X9LlBV6uns%?a+fkjH{wmH7@O~~!zt`OHEW5O(-5Z*AZ|T_uo^_w!Tm0T} z$D_JrRJy$94X@)Gaa@y*e`FlW8~;A=<`?5vUC*QaO*T%}597xV)jT#1cIaP**9La< zd>`Af6UBJ*u7`qQ^IzTTz_%A1_f8P;bg!4G^h+I~xbNnqf$_`WdD5zUl&YRPeTvAB z>f8+N*~y}vO25>)eEy>1hxw*D<9_zW`ocPZ%5RURF5wZpE@=JH@c?;He$=iN@Ko`3 zO8lZ9mJoHO`6w9)^?aIWr_u%SX&kse{Goe4qVaY~p4W$X>~wd2Xczj}o8KPrtI|0T zbj~mOW#@|gsLnLr()rHE%Q*O9XN!1+=7ajp0=_C>rnB#NaRQJ z!OEfTFA(keOXmpStKw(|JJq;R@{8X28`dN3m$VLgH2HNd5bG4@&lJyJ;ao4&E(~_a z6F+B&?_;03_uuffF#oyKTiz0&pDG_sfUmL(RyxOvaj+}B@xykiytRX06~DBK-_;^N z+CKtS&_Avc?fR>K!~vhifjX3a?p_D9uG#>P_9Mh&XShGth2mj5RX#%1Tqha_#Y_FF z*MDPxCynEJF&{K<-O!$0E86u}-s+Fz`O5;cl48N`#y?pe5os{2wB0s8g zI0XIU2GLGeXO(`s_16hJRCujmN8_b+nvvKcA9lZcyq4Xxf$4AUwR-tYgB^|6;`h4V zeUZHn?&5mBVB!5B-j7M^CB8S*%LAJFZQnooS^ReNhL?fkpj5vH_2Ov1+1ogdd{yHv z+NtWkV;{YGVf%7B8ZYf1-GE2!kPmxU)P>eTGx%W-iFS0{u<&Mk%Nw>+>DL21RQmb% z)6*rg$oaT{eCls>uLHDWo$k8Od|*3OyiJlguzkl3?)<3V4B)BsOYaZ;9vsQ$&rz_W zbw&Ns^)-5*rQd5DBgOSZyl#cMB$D2A!FDQL;s@x}Rd_M4E2<0nVe<;>A1Z!{>qK3s z&c5UM{r$*;_Fvt+QM;C~STFQGnZ(lK{30Ipn~~^D?RtqWc>e~qqjie+o2l$%{F0-b zby49-uj^Kb`E6Rkum55`JFoLt_hh|2_Gxj~lUqlN@yf=H^b+y>T&5q*2i}i_@v`^b z=RyH&K4)pOf{BpO?%e&nS-{sVltiklLj*`O!L%#j9%(Cf%JNJ7hWB#r zA58>LW|vq;yx&4r_a%3U{WmM|8(87(e%8{{#rtzq^%5H49B;H<)K6BY*}KI!bn7$- z_rpSuwKi&Mw@Nm3V&ByDBUzskUKa2b#+c@_lT7NQrS>jh$XW8+W`jy$m zNF1_wb@4g~UeR$JEb1)NkMhI&F=_op2%c`dGCWzw6m`D(q++z3Yqf;`lH8x##FN@`t-$iihoF zx?~l2*gmn^-7nht*$}PkDIJ=2^@H5;yvEzSmPb5teva#07%w}*{rfA>&bPKlzf+vY z-Mn}SKUy#C9{q+kbiY3_ypDSu7;m?xUCFw7cughlc2t)rd0qh?KagK~J$F2`Yg^yl zj{3!Rvi_F3S@U}1(Ry_i_@^FT@CH4*)|>R~T5ff>^QsFw%iDFKrme*OQR3t0=cqqB z#~shITi5-03YJ}qCf@m)b{D$aQT;+w#dvWZM(yHPi|fTWf1!3Ug4g}E^ZG`Mrd_wD zosZb*u16$a7O#tRD(arb8#zKxzh+`5(n2r;Bxk*AXc{|E;2(tp3``bFxY#>+Nl4i+Hl{pNX9#+R6N8E)(tWe3iyQb(VeJ zncB&o8`abz`jzpEknphCpJvl#OkBZ|Ey`Q1}XlVb4Xy^5MXtCcPl|mjc zAj`gIs(V|0-bjzXs{F>!a~}Uf@crF*9Kd-*7k*Fpt`{=bU(l^qAe)DF(0 z0{A`G%LgVOo#0p1&of{r?dM$s!%tV|#IZzY$@zXev6J-=>KE7LX}|0xc(Q&Tm@D#= zjT^dt*>~dkmdtMi>{R(p0Y92w8ZT>h9-ouQ=jHyX1MH{GZ+ILJprI<>j(I#EG+y+( zX8XTWfk8&tRmN{%GJoD9Zu$N}tZNeAkK3{lWue-din7Yus*0+b@`|#W>Z)LQS$TCu zsH!4Z5v;8--Zc)ZtgR>?Zz@_gqPD!Mw!F5sva%v%*jJfmRaLb$HMN!HRiVn-@|ueB z#^Du}2bGnF4EvEw7A+h(Xa0=2OJ+8XYz|d7R96n4J7@lq=HavFFBv&~&f-NQ7d6gp zoUwRBlL@b5-#CBfoN4pHJ~$$%_$jL!UR_pMabS)<8*}9$j{1CJ?msPGpN599S!BZK$ssbzt4ZhH-~P#@8KEH(~Oq$>R>4pu_+8X-3qG zr!8Kx$cRBhAJcx;+-b8-bB6itiSj(+R+it|5w)tHIzygHkjKKuy1}gs-<|)W6G(a$ z@tQTUXz`NixlncMVeXvia~423Fy`AVcmDbN+PUV^|JF19V#b7eHaBoRaVv|razt%q zu)3G%s2!;%EgMY<{it6&RpwWRV%F4=vwG~yt z>T=^>O--oG=!s=DRpr&e#^GlF&EcQ<=7wxwr_U8KyjbF=tyl79% zt+$r_2Yel7C+jcHFU)yVF5VuG`KspEkG1hv@^w0G{Ws$A>f&b>@0qKIjUh~?eg^zZ)MSGl=;1>BHZ``6i^2RONqb|5bd&I>p+9MC#qCMi`7VVJ-ZdLZk1Gi|8 zJaCKn$OE@%k34XT_K1sHv`1Xrn)@TCm8@lM&GEhdn?L3H1KRh(d)%t*>u=(p6Tz*@ z9&vH2viJYN`Qg?$p4L=V)*45_pmDG*57kr!Yif<7Z$)*Lao{z6Dve{Yar_M(#QSLV zh{~EOqe)qr(IyluH(ms5%gxDaZIuB~Q*9i=tIXqLb#-pWS~emWsw_9=yfx*Op{lB& zVObdr))+_NP%s#(Hs-x$HD!&%%W88+Q*%CCR%;w~%MCb#NvN#6%3(U%IJ^ev7{_a4 z>QGi|%(lxyq4LU_%4&mCd8jg2Ra;R}ZICRh4H@$XV>(`z^H4sbyxbsB9W-XvRmNf7 zIPe<;YmE81X&x%8HfAG+eOWc14tSV9@cBu_h{|AjsJx=G+MMy1heB1gp)zxtQ5G_0 zAO_WH!>=*l2pv>WZYruj|KWs8{)R9HcF5S22g@o##z{r6yrR6un4cKaq@WRik*{Eg z^U;sDqP*GQqhAl4zjl5(9j4FU5Xc}@X6RW~UK^^ct~7!(=3v1ZqdJVzG|H{QsFK>U z>aq$Wzg3{8 z$?ZMlD>r}kP|vyidg#Bo3>^ED&p59vS*z{1opR$WZezVZV;t_AZ-?RU$*p!}TNt5a zE9d6s-?;tU*l(VncHgu^4hOg4hjtgn^VI3wPbRm25Hsg(<~Z*^1NJu#WqTO=%yHM; z|J|&ie2L6>ZhNWmK6L$IIls8wYIb#QKGQRpuVdl%=Q+lHgHO-*eExu2_w&Kr`TpV) z;*E>uoY3=Wu5JCgJzi)dvnT=i9BD^7_Q>>8x&0nUVLdYdAh``EpJ) z+A!hJhC@eBI&^&9A9D z_zgcgf|o(K3?si8?%9hVZTV+W2Wdg5&nWmhYAS-*Ys#_aEcV$2jWde(*l>b%9UoS^Pfw z=-cAw+^GHf#J-2v?{8F-Sxdq1_YvXhwd|*#u()y2@zdhDCK~t+V;g2Hm_KXIY&9SA`pAr#jk7#m?=Tw8n>J(N z0*(1|?)r<}T%nI?FUZ3Z$9?NK-^dvI&H0J{8d#r!t=HohTgAs811k4p&b916_}*Hd z-;1xuqCG!(>1%=S(cT=p+}68r-3qrJ&X@Ta_JFzJr4v$C1qHh8DTRdl8<3fy1OPBcKriBK}oUFsAEu7J$ zKCbnx^Nck8^|@2z!LH}9VSPtYEuL7PIJ3=_4%TM^>Qi@%?c&f*cWbRL)Q>u>u3^&D zLk=_U5ivHS4;|kyvCdptFm4^0IAy}*afcXxo)U>1I&rc|6#E0-2RxSahYalx=kWfp zHyfOrpSS7;RoL$Sa_#tf%J3Nr=FMAREvsm>Gv|%-7Y{dntyWrfW=xVA8W%2{ zJ7*Ezv}A~*;g8p+F)U4++t(v**JgkoW&fi()OQDBV%|Gz0uDRhfCG>=~2<9Z<8XMkH= z55)CB+~R(`zX7-Xh4a92e*X#U;P)BgHugd_+tRqc?C;_CspB?b>^JYB?q0~R`{Q=) zubuDfxH-2!|2~je-|TO!qYh%NxA5!lxIOnl=leHqdWheTfqLO~^uwlo{<`bfTb%E^ zm~kt=j{@7{cCCM!_W3wUe^LN%EOW2IeV#Yq^zq=S)^EUy%%Z;u1OMmikt}P4)>j&4baf|ha^@m&B zkM)P!8x|g&yZ^_$E@0m86gZGyugDntw=mx0eJ8lxd68jn=xpMd_OT$p-ytuqql=3R z^NL&KkMZCZ_hUS`rF>@pyD&aYzPjA~8|leBPTbzQnX%vKUwA(aZj+nW4H|0G$A4@* zcfZ)#2TaM~bpD0o;C6a=%AoxX9P^lD>e;*_UnkBO`<-yY!G=Lw8g{7v1B?0nHZzU= z_WQV^kHL6Q)-cHI?`R(f`^?4j)~d1X?;6GZvPSA;K|^x$%;Zu&&%|xY*l!+pS{CvBxE*qsGfu|XZ_Zb- zJ#N|I&Nz(+?UCby$5Gsl9=iv#A5Y`Pg;VqXpp>!SJf7lxuDA`o%jeIfJM;TLaT|MI zGJiJqn{na18MkZyCYe9y_B+gv8AZ}5bi&RDOw-F01KzmYGjZ`?j(?swpmcYNQku;Y6k&b)rYIi;U)F6t+o zy9&d>@mY3U(%s)*<4<0`UMVcDJe+Hn_RIO#?0+BMKR90(hO^!$&i9A!x`N*yj{OR^ z&zbv;{)P98W?3@e$4rN=0=#$@6G4yft%nxZufFSfjui1=c9AMu9a7{O?o%&r6zn`RAv6|K;0u*oJ@M?|atapW|v7 z%(vaJKl3yHJF16x@yoeg@(R99U&*)ObKpMX%lS49?_=lk_uZFqJH%VFU8BGn1=c9A zMu9a7tWjW%0&5glqre&k)+n$>fi()OQJ{DQ%;BIT!Zu#bymmqGeNL=sG`K7l|AG6Mt^OW(Mx?UswJKbzr*{$G6_bcbbiFVB6wwvk!B= z=Dj`(Pub-H&HLX_@;g>PTv&7YmPhF3og44 z_01HiLm=G8_ms*z+7UNgWIqnubU4$7%Z3-HZ}@h8U*RT(4!ivPg7MHoUcZ?l`$YtF z*v7zp`lBN&5jR$(4sE;h{$}0_xqI-2mk~EpJb&M_j)Rck6z{O+r1H`X0Q`Ka5Yk@JysM>&&pmOJP<{%oi;oUJvGT>S{iz z`BwO&@y18K_m}=1>w)&SZsUN7b+(Oz4lVHgZxj#To45gdW7~GE&F5#k8v8!|biX(| z&-O=+m&iBIw2I^IZv0_o^uGO3-{jGH{aA(@4)FHoyzlIDKQxXP;!g?v9$)d#kY(dJ zM`S!p87C~Luiru6SSue#37qv-#<$hS$20T%;=T*I+E9l~k#!a^KEP=5HS6s11);n; z>%#9#wit>pkT2CCVC!$&I_MC%q%a-Ycj7vj^VFAzF1W_hp~!mZ3HKf6KVP)pJ7Sc^ z_f~x=ey=3`yG(~tn+}s4bVwDbLu_>4@%W1s``lsapg&J_9Cun_+*#KMaJTa341L9) z68e40;-97cB52cLvV#s;^8LXC*21OxTR{i29!|O8&NS)}7_nBauBknJFUwoTHcn1) z;G4X(u=))HFXQ8?Y()8~Ly>QIJ8iy>d26%fZJ0yelB)`<-;gbDhdJnwzPK=X3UA0f% z@wk3m<=MHBUe3{`_v44lV!b!#!{7o!>+qQu;br9PBSLkMa67 z=VzS`^$;ZAFKusYzLxP#+`w^-(@xfO+#h+zw`hSnL~Qj?z1HD<^`JkVIo3mmtsa&; z)I+SNuzt}BI+*9V<6C0pFf9CZK2cab1V;7Eqr#y*-W5QNH>LP}*z^zZUY57GF(WhQ zsV3h^4t$#mba>(c;c8f)k7%IH$HrE?ap1O18XQw-=wX64|d?o9xse< z{Pw=%<~4Ws{1y48imZpG`}jJG`5jpYJo5T<3s-;L-f?_L+3MjehkD2!r<|8Kl>_Ur z={wFr-$;S_Wo|Y&sn6phH~UFC6pM zWgFLDbQsr57ZsMbw2kjy9Qd|BQdqz6y~X>*Muz&m4?Xe)O+s{^!qyREFix7+$u_}CwoL9D&)!=7=KWZ|fkbiRS^U7h z`Q&zQl;4Rug#V(A>sV)Ls5A5Y;^y*4^Ug0i7Z+A%EjGRZ8{e2d-@KfeI})~j{N0Ju zDyUJ(lEU~l+m6Sfz0Rq|yruN(%u(NNTR&bs{jskp-`)cG2KL~2H|zJhpWbPwxbb}p z>u;%Bct1Ah)v2j3=II+8Q`k6}hI%m9VcrYvv^~~uQokM?_08DyeRb53Z>SF0rG?c) z>}1}L&Fh8jR~&qI9&Um9W_0>%jnmcX`cV{WFOyWhHUgO)^GSR z?eQTW)7aB(>ldfl_@;`?Th^Ah_fMGe6Ls!Cp|HI9>v%g;-y=`B)i}E!l!MOb^QBaB z??blpmQ@>X{UtTZsQEh9Zx85T&e!*R`PzFZZu^Oa=}@v8Z)f(mV{U)aye}wVykvoi z#nnUbJzi(#xmN9_`8vc;DvWP4rWL1et4)WwHXUO6I^=lJ|01^f-O!hxx6)Gz(;)?X%{u$_pyj(^ zoh9`7I_8bl^5c-%FUGx^pSP|8`9`2$nB#iIVSA0jyajgAo=-aREdjpk8MvuePRtw6 zGN%@%um7XII(zox5@UQA6fj({l)k>EdEQUtAkN3k+rFDkdJSYl@44nf+qw{>K}%2L+6mEUC}eQQuOVzAqhj?#(8q{U>{0VSKwl2lM{l zFD~BkXgj9)I&p1bxCt01O&yj^xX98WRiq9<+xYPCkvDHj`F1@}7~dr1ZEFK?kDU%W z66-9Z&zDl+?sl-XR#u2TNm`L zPi}qG=4SeYpV)?lofoEO^_>^)u=T590n~UC*{Cqw{wF)3zJZ_g$A819oukRb6#@Nd1H-rd(I%? zp&kO1jPX9aU*9}x$g(kco5WP-&L<=I>h~bxcB~NedD_6pn!>$ERt_%1g|4= z-7{1Ef^j-KC}6x~sUmSZZ1dl#vw}5{!!=S|F8;4tmHIUYA#XY=|s zuj@tr`0XuI1N%?>h{DF54Cr9$yQ<6R)ND||c*$Z=f97kqA6Y$g?8NhCo)`Yq`oRMh zuD%YAg&De#*O_^o-{HESH)45L_T1QFHu7!!+j3l!?{7A~2@ibpQH|&A1Fos>(#t-u z^i36s>)XArUz}{i%@m0nIGoq1IZu6NtAmYl8x$~JvQ&}vkOCddap$%juiOhWktq_l zWILWWLs<6S+jo76d}9!Y$=&ToR=-i3zDvK#T6s$riJJhvW}W^0njek3HwFcamy8Y3 zKJU(%)Bk*%_w|eUZ$D$*CzdL5-LnJun)Q3KO^4V{#qrJ9ba?cd?H)%RGDYg!8R#2# zQZ`%`)gFJTw7K^I$dB1CE*kZXHLng7i5s@zZoS1NmDn$mMdGHQy~%e68*ZjpT-*Bk z-nZR14f%#2FHYYid`@TwgYW)_Z1FPU28x_VwLrfx>-WWBI~|3%u_F2Ucjk3wj%TZa zmzww62aK02Fts=x>UZG%*qs0VeD5ijBi}@kxPdYo-}=4ZH@Vt>LX-L5?fdMnW#eSX zhWnlaZmdAuCcrhv^@p!MYDYU4^L1oOVSE!d+$XQd$89bUxBmCO zPo@Bm?Ru(l_Q^95fc;b#`d*f|He23yxi7ySx(ejmVZ+_j0k@|>+%6mL4i32f!wRd1 zjIAEt>OL~B&ioG*cHf|{ysy8Fx+h=XrULnf;rM2bJ0l!$TMNW31-|CEv+l3EoK5Q} zQy^{_aLs-^j7{H&;zkcIEN_8L`252>z9k;5HE-Jxei8-ZMuD$+{*q^L+lWTVDxM+;oAsNn76PPX5-sZBF=Uix#GD%*J>9MNN6@;3btvjAxJVt+Hojx_{`bEr-*AC^vo_p^2jBJ%#ce7OmsM~bOnrYCf7448x3xgrxb1kc z(LVV)WD3M>vEe4x&DWuItHQ>IpiPG-4$0S{gRUDe!*rJ$G6$WH`;Pc9^XWPeB+<@>Fd9?J`cCO zK-_xJ!Mx9AhoAbMD-kGChgO>ooBeHU9^Z63N2 zPj?KNn1@>+-*(W!#GN|0E)O?wbYcCi+lIUO79;X-;|1dO*l;)8Xm}oOTY$4kWRTB)jT_q7>wAoO7srQG zk$f`&j+>jO?tA6Oh?^{O{h`&iuCd|as}>?|sz}@b+%IbKU2D5ne?is-TroBAu_vLlMa?Y8N=LHLnV5jRjIZUA&J=c(_{ThW2I z$s%=#rFgvC8@Rt7du+l(hgVO&NfY!7b6zs;$+yo!Ty|7(d?P#Z zamPGf9Q1m%HSUCqye~chxaN6Q{g%^TM82uP#a+kg0$g)^*dn&h69#U;c*(*=>RZ1D zKW>`1+uCqrMdBtPKW04~G3=UCP>0yF#pTTh&!61fz}@txRff!i0>(?0D3WgsbTH2^ zR_*d)7xGOOi+gC_{V=cfvI9-7UVdc#A`Uv3b$04jTNuL{w+s~d9M1NAc|DjqG_4K~ zMch=8Iz;c_{msnV$3I*-4sqFY#nnS(zdpX(T~-@J+}MAM!)>zV?d^WdTPNhr)c5*1 z@BW5-14WK!SzA3U-M7UW&k{wBXBp7fth3--7wwIFS&`2-YI~+{-Zwb=_TLaUQDi-Y z_viIs&L_(|Hl2&Ofg<_V!*ia@yfw`GTNUDli^PrDo*(u0TAx|tWTHsi*8O<>oA)tI z`D%wtkuN)@xPB3U_U1ZmTk_oDh#M{vw+D1E>+J1y?ua37tVrB$c;2gdod0h1jw!@V z6p5RJ_U1fw{>ZzILEKc4xEbS zX9?IQVH-H9oSDC2_@&Hbe3Q^GHZ>Y7J>ush488&5C5vhDmEp$W^I7Kju~D8Z-s?ovfff0D z+AQ!jasR!f4>w#SZUmmEYtDb~Zk^YPd=o|DX5e!u=K90Ab&(X}24)o3k7Ll@9DlES z{M#jnn0fUZ%0I&d#}Zm$Ar~6?y+;3hv7=&*vBXxYty~ z%@ldR27~+J%)I^M_k(Xo+(2V-c?&~(lkZE1maRnGSdq91Xm8fT$jrIFB5txs+~^*B zerEQI-3M)F-gjlZGVV_;61N3#&Ev)8FZ}i+;%17(jqSqunz*s-4ebVQz<9|LMc#)O zfa_Lfzu4*cuVctJT;%nvH0WTCXR9~A;(EkQ6p5Rx>N_8L5xK84c#I{&-j*6~Mn zyl8^Yii+qzs@{RA=cOJ0rqUXOg-~*1tBs*n%V{qMSN2A@Q7wu$RAL5pY zBClsP!*#OU@oh}vI>b#DiQ5jiX8neLd&oHZ_;s$r&^M|z!+=DjgzxhK3c$xFb zAAaB90p!byT(3?|L6-B470I{W zrmrvh?^47~Jy+cPp~H5a?A_gm_S@&ln&AAxtcS<`d2A*ps)zr$YWWSiY<&M+Am2bf zEK7XC$FmaSZ+8xT`OVw|7#-|nyJUP5w(B@oRxa%~edD%u#9w|L*Kg~;rOW!}XN&L4 z8pll@S!Q{0bruI)bN%dr*$cZq zJm1&|KfVIzJ0W8w*<6P)`^BD}@0`kR6kwHaWOWuZp2TY6n)Unp((8=V0d5(%w>TYI zU>;@8&*naIh;iMC1&m+q9~s{y@ZH!zI`}W&8u|j?SaEz?VcZ#P;GXmNo?mJc1w$F% zF8E#;vwq+BW~jNmA^gM_6!yHq%)vZw>l$dMp0{cg>JWQTTL&}c`9IYh*X$QJC-Y6> z;lhq@9md4LtTPk$*&(J3khdb&H3D#-jX5uA-RFScjg9b=E$}{@kPWxAHUIv;&@qLb zw=~1|lbQ8U(vP3Rj@bC_d|v+jeX#=hhW-z2*8%55@wS&D9H0`ahZL74CsG0yj=uCm z0R#BQfG9x)4-pL26BI&|qZ$O^EMOGDLqQ_-1cX?CLlA;e4it&fPEZI%IQlnlc9zV} z>}HZlzWM!fbCc{odGgHrzVpt^W}}4dOuCV{@ghK6FZY+h^>Ueld;@r#hx~U~&bivC zlF=jTV&=!`#PwX$zhuVF3@3;uQHHxv<_vL>t=EvzcF9CgDPoTb8 z1mDWH+x4J3%qDn0o4m)v`vHxo-vZjYQm{|VkG%xnyDqTT_jv^Q2C%*m&w73P{Q*?T zI>MZWnf^D2%Zyg)|c#P(oFUVJV zIJ_^icm9R15UxyPM{1k(n?lStzdGA4Ve?Jz3Y9O+T^3pT!@dYiVI)tSe(b{bdl$m` z{=A&9`KA}!1LTwK^TsgilfXSvG1J#c*h5ae+03|^D!8s;C;UxH;C_o|r#cUY{eb2# z_Cu>BYQHIQ?#E_g9V#N+VS5j?rM1iy)WK3cJZ=`W|2Sds*STE9h3j{&FPiZFopESy z)awNFM+~)HMbz_Q9p`cP<*MR+&$A3S8_AjXNi`Y1yiTw@6w_6F+ zHwW7T@a7_WC-%LVq6$6iu&36 zN(2RQbBJ;CySLc=pT?X)fz!cR=a%#YKs4&WERR)$+8 zfUe_@t(ft35PaW!HvbTfY8T|2jDM#Xbl9H2e#;>E&N1L?Jtn4a7LE@vZf;4SzHY)V z9Jg-nq4jkM>YGcfPj;!@6V1XC6Mu8Cok3om{P1We&6n3Uv$Jfh1I&+WPdd!3Pi711 z;KBU{e1lc?4B+vjUpM1xN4K(sxez>R9Zfn)pC^4IW@lEM_kjRwCbBwY9T&s(<2VWN z*OtKbR3FiAiw)M5{et}#D5vJt5Pu62xQ-Yk_>L%YFI1!kG;mS4kK4n=K1^E*8 zFe-uTh%(OC!N6W^n7@$LA>*JJ-vVO2`kn;NFVYEnsA7=+1_k+MV|^iixT~%830enU z+sqzZggq24{};H2uB7LQ>6=C1mNCE$2;ycFc~q$c>fj~#W;L`h^ZC4UTpeJjVTxB) z$Dxwwm3C8}h2dUTTE z#y7W97`OWoHs8rwFNT{&tb@D$>(M$G~z=^+`kfO>L^?s1SGF`Oy8Djx1^<3I0xnpV;TU{l&98XmAh2Z6tjqr)+A`0_$k)xr3qPL6LOlDtMo%W5+5ZsZ>m%}=7yIq*LUM`bf3x^t z$NIv2e$=@`KwDSRj*9VB2>V@`!0|%96<$X?zw`mLUQ#I36?f@an>Wn*%})45*-NZn zSOQ`?xCuL(Ui988h?#88j(x?f-yDQr*jBNAVG~{dCDwO(i_K#V$Dwq>&Qb=HVy;(q z39cii;dM_~P(Egty{M8|70sV9vj;DZXQk1pH}@4r-d9LQ|4M;<@r@TwqTdEKo5SP} znJ2{T%ue{*uDV}lBdQ_3z&V;?rh|`|Urao3qH8o*psQBrB4a9a|yq2)~NHM;Xx6eG}FQQyE+em!2A9LHve_y zi}B4S^7UWD?7>jq48o6J?#B9Yn&7&TpUC@0Cs5xUY-gbFH{^8T354r zBY$7m3^xzk1LP%*RwOPj2@r8IAZ8DS@hpqzx20cJW%|upN=%2Odf|PX#`hP>L~_Wn zbex&K88}YD0%Gn}c3sZT=WD2g2kQXqJH>L?{4DEkFAxRaVd9rB5JOWrkBhtzw- z_$o`(xKkSGaB9u)sVF{#y3H{^>i7^kp8n$?#y9JyvlxFX5RB{jgkSt#<}K#>Nty@U zMxV~m9 zi`FBxV=HF*dWpERu+i`$G-|FOUk~ALbrYzsjIaNN{kK0~D~_&e(wCqh-yo5%w@6@K zl1I#2x{39h{sZDx5a$oD-goHFsc4>6NJjrkQuO!9G4wZwKfEu}@6g;0Axz>=dTGAD z6(x?>{&gQ$?HBT$b0;UipgkXLZRT&O*pFeHZ`pLnPpFck#f0O`aIMwVI1Bks$=Nbo z)}<>sQRtvM0XOW5s>5BV-Mz&Vr;Uz@^qiR==U_hu?UTIMZ)=}SDWP6pnq=Yko6-B) z2z}cnP~T)6C*e8}`+y(T(C=*(I;GF$MuQ350SJ~#l0KhS{gL0c}L&MQQvRd z(BBknXW+*Jf2^{S*1;vHLpsrKPwg3&Fu$;2zL1x=#tu%U`DP39O{pICix+?CCgK+~ zl~CKVLd6BXm0I0=2vu_Eg(&}+`I`^>8~E|;7q?!Z;R*zGC_p1SuR4kfI^hhjPy;!5?^`7iKY-Tdr% zZQOK3KW-Z0W)c2&C~JJe{7pg`B-jJk*}ot5O_*OO=t2z*_hJHZy;ui`>&pD8=TIf1 zN7Mz`uVKl>xNv<*%dsW9qe?bB(Bw%o+yJrf-ywnDs|yf(z3baAP844^5zqSU+R;k0 zUj^U4%;e+WdD=_|55|Rj=V;9Z=z2u;NZ-%#%{MLe)qE2Ctxcz6g;6D=N7TiPZ*uK0 zZl?s|reMC1PaZu#Ghu$L5IXellmzLC9JL7OKrV)r+)Vq92H-L||Av(9B%Cx&Z#Th#&fv%b0qF3VIE^R0@{er<#f4M**P z@l98LvEx#6jZ}w2!1G!pf-B=a(^i7LbV4!eDEB41n`6IN3(v*$Ll+x z{Or=8gym;hSYN;mG)l^&`DBg|yU&w{=(m?o*P2e_dZWZGc)w1_547`rM8EaedK}G; zs4`NFui{Ys4dP_E-tQjN>_Luxf0H7jHvM?s5*p_dn6C$jIQji6523iOT8<-5zBzSO z9bh~z`0o<(x7doA{km|T3i;W>1kT^&)~dfkKKWwfm!3vC$mn16rJv~h*o?1&aUrh% z^HfErrmt^oe7H6O_p{%t-NALl$v2tsx89Wky+azr@W)ICUx8{5u&&`YScmZmj`JR@ z1H|9VT1B>L`g-Ej!H369SpWU|hiS_+Twk2HRy=M(-q)|{*4?O*(Ie_&rmvr{-)Fyd zpng-2l%4U}Spgm|Apb2=q0O|YiQ)rI`C@$`Kdb%t50_CT<5Qxl%y4Bi)3zW47>Bx^ zD+S}5j2=-JGh7GOF&QE4S<>jv{-!HVeS^5)z%PpTIElu$LNfYS^2CX2A;z}}g1hI17&_myAe(Z|#KL0^%zYrgq zR@#`b{K1Oj8SH26FImd1@l{5~7k2_UK9oebolbu{1XVE=GrtJpby~dG zuohazo;>>If|2oWc07(SQDQP`NZ`PuRb~UI|LcR1?*^w8DF`A$_sQjyQO$9 zjjtT#{MZcFLiokS1kPiv)m42V-?6m2GB%peP99^%H@HH@g>k-N#nqXplF9RU|C`}v zU>$&Oz2Dxy^ZP?SYt;L^hHtF|RKDOBJGac7p!J*QSbTQo#C{C+@a*(UC|anWED!@< zqw6)4e3dWEv$j+mJrh+i6*GOE*nVMt@yFT1+cdsPoc3!c*4JN7;QG4sRk+{Uznh$a zXv?t(VWxviQE|b}{`%nI5tX*QItbd)V z1FRD?Zad^ZO^3jh`24~}tiw3&`3C7wNJeiVx#HAUx?9~phK-9ZkM==PNMAgs#PVMk z5qGwD|F{!(JaO{PNmJK<%OIM&*P}(>1ldFIfQoBDfXxQ%AE41F$3){nQk98ePzs_r$@s<8o{Q~@WV(FBf zJRJIUGh9F67p^|`m72dPajs8#i1@pq)P=xq-E7xM)jx>P+~U&D1AjL+XJm@nAbLsxd8Wnh(W zU}$`}4(!LUuIx*oJt#H9@QJ%Nr(;*G>g}5{P z$-B|IhN`a;uf9aToss+Q)^O!G*Hc}0sh=0}$!#5bjMH$XtMTa&!0{IX!(bTfV=QL= zW@5{UP*U6{kn!rKQAd^9k$FaK8AUn^Mo0$msppZR-;E7 z4h-|M8LkEM1sNk;jvdZZlZdbO9ZvlaC_7ihSF810N+ua+@ih-Yti-yfhqXo}#z zv=8%z`Fz7KKSzJDV)5=Xpo|Rc4E&q{#8PF=ghH%@zyR;fBbUb3w0i)gx~G6=+(M_Di~3_-s?GX>4(3(4qT$@6BM`rf0S z4}LLW(cfrYF1BK(uZ-;h`mOoUiOV&)4_^$0DW6`y-@#-4srTLiZwiseXy4m?c)@Z(OXEKIPKStap5}X!5{um1>pj$ z7afxc|?5n>u(VDH}|Zm=K(*K zVybVaFmB&`=r{F9C0@RYiVO3h;SCe_{kKf4FZA2j?}x8baKyAM`$+W;Z zvcaoXw1NtGRAKZudh_<}5~v?zDP~+`+;1?yxbmp@{DS6^O5i5Hk~rLK+;1=*_rAIv zjhnF*GacN-x?IlrG6S^U^ToMdE#v$Q^6JkTRrokIwi*leESsXn0l=;0YMC%x7lAu$ z0^q8Od1CYndfwv3xG)bGY-QtbhTy!#Un!iYZp#kO-+XcM^I?C#$46_K^%7^{==7!S*GJgH)n%+bnIYPozdrI?o#J(Xc<`g z+_CpB`t?A2v2{5G-{&9Z7nWW_zN2vq_&U(1gxU@Qw_a}+S3WGJZvpmW(08DLzP6%b z`W6uOaJd%yyK-54zJ@wv7g0Ya*o0iJWDWYDTs~hzJChozb_VhH`Mq;a(YWrr#B}hT zR{a?4A%AD_tu$`FpbiCFi1h~p9g>QP@pTcuD|dIVuJ6!%bAwzvqfZI7J;d){Z2Dyl zS{2uqpdfC5h-ZBb;+b4rOa~=Z{hTlk4=MJ)T6(tVw}XD?>R@PR7HntWZ?72mTb3YS zANC92o0)mzdxr1hVmkPUxO1Z3Dkh#O{QGzt>JY^J2J4gaPyO#(nr~i`7+)vuH`qTe zu_Cyg#!am*hMRFy^*6wMwAqm(G_He>Yp6pqwgI`W_OvMb>L)h;x2KMXi$<^18NAQ(!zfCgew^Tvg9D?sn1HZ`n zl*`x99#RNx_ZnD_FEM?y3EXzK z+A+9RLENOGYW#)VFK6MSkJDl){lxhC2);$iHDLG#_~V74{o06e=<>6hnEUV89b$a5 z28ZX}n+o0~IBy^~M{#|tc2Ys>D;^G?WU?+6AVW2}=T`sPk2yR(_4$p@wHr(?m zeUNV|f4q?ClTbUUq3UliKmPpe_zMzR$B(6$#fNM>AAsM;<~R8H-9j+-wYzIS9^sW-&_sE_*#g3=Y9i!OG*{P^>p=*CWadzboj0`tAmHHgCXAn0(Zfj zYPs}5K|x$gb9H=!dEtxy-R?)@rV7qm&}}B~?CVW#cktixl0rjAY@3Zkxx2&h_t1&Y z(60{aOX_1{{bnWdl8pWz-E1qsSJqPrwUi^O4lo{%dF0GG>2rgFB0L2;$Of<5FfOc5 z?z{R?A1T}5pa@Ty=^Mxm=f8)Fcg&(8tYs>P`jviOYn$Q9__~U_(ShU2|FB5g!FI%Z zUkQA@J*-!+xq4zc!j;j#k`n#(_J(mMw`tgZ7a82g+fr7{&K$&jI5W>zfXiZZC6$kB z$k$2S$9vnpH)iWVQNzo}rB4a9E%;iP4td>GePJCj(7tjT!#9uc zB(gI@9sIc80JqZn=VsCn9znj=E~;NZoP4)q(pegp*EaKuG>i-SUbY2R@o?zZ&2-2k zbSQPE@VoSRN_nw`L z#fLzg@xg=r4dTv>nbXeGpEId~n7$cUUzi76@>V`ahyB04ZO1k8Lyzcnd0$LRy&}}mvGKk-eTJq+#iS&7yg86T94>kV6`tOnsG%CN1_!{aPz;UNIf*8?x0uvt! z1of3M-y#V2B}m$1EN1!!aNI$GL8`gDD}*0iNr`eEKwsyWg89NaSIOS3f;v#t@K+L? z7ZSh2^ht%oRcYL`rebj?kBIBi_?8>A{45aT^}jS9KarQ*Z}59bxq|vyvA!_Q-+k@q zbM*VB_ZHJPAKNeZMRMr(lJv-yW@7rfiQhHKJb2cwM@9D)ixQW%vsA1D_?xY2eHe~( zCHFfq9Rj%DLf7v+p2n=67(Hbvf~>%P}E4BDRy5Uxp#OT>wdS!BQ$Pc6c^W!ZxHtzym+Jh zTbpUz?3P>|=u<*%1=|_;#q-QboifHCMbT>Ee>qor|p zDEL9Yui5x!C;F|wLBHiZ&+RuuJ1f9CK>YPSl)RYcV^iYP;Z3XquF?08L%N9S;3MM0 zfOoFtpfCW}VAEfQw60QQK|8<6EYW)xlSqe|?D&u#3>)-@h9% z^TO1-#p0w)=&*5J4l~cnds$2e3)TVrt!jz)defgN|4lJ_$RqOVnI#%CI#^4K>5xL` z(B}ZFgY^|L9b`g>*Xpr4I6oHC!Ajt|`?I*I9x>c3yblTStny=DI_Q3LuMo3eFUEy^ z^y+`^X7Y#Z=LK>1s__?a>lol>^%KJlV7?U)Zr;>eRcIY@`-|aviTg**xo2m>)|EX( z9`%Gl9%U&nW)Il}?ysZfwV`$3wavyi8I3%!Hw5c2%b#w*tQ%Pd2^<8Tj1x`&XW##Y!6_)^9c<-}!t03qBfG;>?e^`X0vm;@W|0 zQGKPS)bRrH$-1_auuuNj+WK$6t>%NgH!;I?5c-xG@i8+GaC{*a z*Yk+Dv+3`JZFv0X*SY=nL=ujZYVE*n(SCChI+QceA@@r$9b5!%B?Dah3Nc&{#)a#c zMm8^am)0-kb+LR>!Q&=u6)vtVL)xP+PBA|Y5cg~AeK@_lX1`LD`(#{uI9)=u2V6UF zEou)wtS?-DHg3?B(RvZkZv_4%)^851FN_x@4zS}}eviog#?|48lGrcQ+JW1mI!IO2 z_yRikXR2hw(3u?v3h%hFc$3y8lt{gat>Ir)+pUm4>jA>2XP{e3#J zs9~EYmY-P(+_5`Z+|2)p@l`M`^xKpwYnXnMu8ZN?2z~2il^jm%;Co&S*FoU!8K2DJ zmKD2B*HvBh3s|rIW%pu~?_iIQ^Zvh1%opNs(TDpo-w#MBFUXg`JvnK69<6Vnf*7uw zzOSO0n{g~_Y! z%c2|SX&urDeJ}ND$mna2k}r*GPYcJh3-c#2I%G$QOY7jk`#3OeE)Cr`RP{_(l=A@1 zk7>Rh9Cu*c{A2a-7wPvch>|aj>m>BO(xcQY8aJ(5boRjD68l*mgZn|-qP(9YjhjL6 z9XP1?V4ANlO1|`YUaT+7Tb_LFA7p20Psnk`2N&UQb(;3NOuw(?sp#~j&r5zbybg2l z#>BE3UnNGqG_DoT13-rw_icJv!*#@nOZQtgO4PNuzUbz|LHd2Yf;#w!e!Jc1E3_$d`89J)8B_Z>U)#K@QCW9c5YhmT*Vf~3aw8{_X$(fyW( zb%1f``lv0B((juqsDq#AxB8ziMd4EA>x)qbns0#Uw;f%xnYbPlo={f)pkPPX^m_DtLdx6sIP{n)#)u%eIZ|;ROiLlAJATivNq%E zS*hYed?@*R%RPv%jQ*9B-(vF%y5EwCep|A2(QLpZi(9bYoLFDv9@5Dh_cqn^b;PM} zZcSAOm|wKN>Sy8($=&FGOhgY^Ypc3rFRlcujLMtx}=WNZ&$zcaUPIz_*4fUg66N~j%}7S11LE^{F}Q+vV_ zBVQU^!S@k>31O4QKOUoB&lJ3mfSrgtlS{Do=?(Jl(@RqcwPlO?yX|nnN}06AXf;A# zGM^K)2do3c$*C(EGPu^YVz_=H?hO4=8mIM}FUGi||CH#S)db(UYqotyzwQ&ff0Wch z9S=Z<>E-KuPvZvp*CW!WgxY!dK2Lz#`L8_;U-wI5`eqXM%RJGAyzXgf=l+E8; zv6T)KH8Nin!&T0x<0jZch1;{y{8(QCL&b0d#Qow+COentQPG~!|HN=T*dBmy&YrUC zXxwbU`!NLw+@UusGq_Ht7+V`ooU>_2r=9|;=YSFO4aW{H8rNaoUEbinU!Ew(V>(Yw zA?7W)SJRi$e62mATYsQ&EqERP^Q`AGC*;t$_9$`b^V0BoD#Z1XuQx!$RUsMuD+OZA ze`&rl<_r6q-j{|v1DIrSMah@OO~v}cJge%#b*QB;*-_%^&q6I?y!h21uBS$M|2~>; z9tvbI7XqR$>}G}`DXnL8_Q3G%q0U=i9y|5XPv6nA)1Utjx**>~~^;@Sw@0ne;wa8v#l9bfu$ zW)b%V99?lZdtF78_XVVNu;Kk7Scge!y_Mmc5hY(5*MW6_xPIX51?GF$o+xo?9h?O2 zkCisPq{VeP#`wVCV*7=8%^$ZDcl}u|(QmEqWBV=V3$eV!h4~gne4o0WIKG(}7vf~g ziPf3;8?77NHk%g)@pu8aW8V`I*_xPo*Z43{J@T3{v0?ZfU?;mBi&Wr$I z_>vi}hu~YfT8V`5&BnOEcUif_@pTY+RE5qAzCl;KTifD(UIk%bEQw-aBZx zbo})bcGj-t;W0Fh>zU}rAsW|5=zGYz0o++v>`~(CPC^Yo5!Z`VyIo!Dx4;{*<$W}6 z9@YW+ZSj^{BKjKUeVI7#gMRD$&1MEy5u9%ZFkhGleBw#m@44HEdExbWZf3nNiGP24 zTG~)Mfcp(ZT6lgBl3BG#PxO9lsIMFA3p$i|>-1Ur%`=*djhj+?)t=x@FWuZ7<{PJ- z$tZJz`4G&z3%$qcn_r7NpEuMYi_oF8fewKdVmdgmJ;3_!q#f*ivE604*Y_Fn^$>nB z;SB2+zU5+korL`^{$?R#zXj#Q_+}IOe*MW6#?HL0#rOta4co&q1HL(p#O%RK@Lg}f z*Ro2CuMOWfA6wX?pRe)FtSTwFst%fa!X2m&lrlARZ(WOH$8DxtPzh#Jpeycjk1 zIJk$dD9gCGhJ1a*crjw(7AB9%5yZ_Ua7P*7%3q4{^%L=T)}s%e(}@6$A!7FH!}b9A z!;~(&nE0D7$TyGRJJ*13j^KWw6UQ^Khp`6sU|S)kZ-D5xHw^mCwUUbqy}%S3VZUkZ z{$}jg=jGxW+HXF=x8r~x8T++W;o>q};R!!s4~?_#ew;oiZ7mnqkZ+K%2gNloNaMPy zadGKWLTwk3|E3!8-N3~)O5>O2ehK5w6b_FD?c=wHbZ<$Xr9 zbqzR&EEZz^7C0Q9zxkq{Z<26#{?EqyPLTip()P2<+B{Z@b6%K-amypzU2~Sat>MZs z;?nCdHbRGL?Xy3+^Fi=G!6?_)Y1|-Qe}HwwSCm0ZY25T)(XAWN=P5`4m>QoG4>n%e(*(f&;j)Qs@~}@ znb$c_nDI@0P~{8P%l-S|59o3Q^~gY+{^r1T2J@B&3(dZXaAowb$DjP zn6VUj(-Vc^q2PxL)$s7)$6u(1hw`oZn1X6}I5w+~OjN_evqgRQPz?`FU)nE{iGF*n zN#Qy)*CfGp&lHRceo^z+)*ZBdQ^v%%?rF#V2Kz(hZ?fYM&7W>-I?&Hs3BEs-e{3xM zI%e@$FD~}m_kgB@BTgOCiMZ48hVxyTpI@-w{DfbeJJTJevoRGj9ej8{7WPf+ z?fC82m_X6NX1IQgTM8X>`oQOm{qo+&3^zdN(ECUEZ5|H&x*4vG@VB!ct)57qC)>rw zp&-HcM4KMWdI|kLblZ$?8onPi#P*--jon3`7Zm(Gs-)HGx~7Z(8;+SVTEq1%8n$xM zc&%k#oAFI@spAD0ZtAA{TGI%5Yq{&G^eLfsI_@`ANjo0A=elN*p7HU;GbdpWkF_na zO2hTViJOFfpP>xmd+fvenY`NYLlRG#>FdLB3$A-@^Xme{S1roN@%5Y3LDdoB!;p{a z*fiW|Ycsy-*d9QDq{+)h(Rl9lV)o#~@fYmj(B8!DXJui&u9y?~$^mWCnFZ$#Vdm)eNV5!`O=F4lF`9%uxyNJUFyN}Q~ z!LP)0aQvd`0M`{)9PmGeZ}N9y_G=raj*ATu?#4GecGvhSmE(&$-uqR)ut?L~;C|-X z`38$hR~IapTu-dfz%+ zJ8&&}A2<*C<~7(a#P!!lO+e$OB%?>v#Z2D}V%)qk#nL2dKzyJXt~6HF7sj`i{!Mqr zH(#9Nn~ZVM`gEhvrAO&G=>#>oEHgc%7~r1n&6%5{CKo)_lMD*m4a8i+IB zk+D4h-@s0Ev)UMo*$ECD*P-8j>)d!}jIgG0$BA*_dYC`l2O$mC6(@ha&v5_P+Dz>? zSXW+AHV>se>L+uYSMyhg;Pph`*9i>uO(pbIx|{(Q(G@rU`VvFjv_@fnJNw^0#^2IY#QZow=rH!s zA|_J$`8w!6pVsga{r2_fPy1=lYqekSd+r4fh3)sgCWSg`_UrpkwOYGOB+va3@W_(K){QkUy;Je_Hy?@aos zZX@`PX_W-aiMmoSlB_vV7LtSY7L^~!@ZRQsN{C#Oyf0#LO zP&FFEH(rcyfQSzt&l~*;jqCoFd;Jc5N~rA`8O|SmKXPjieNd*0%h%A(>_oo}>3d7{vpdSx^d*yj9h3e9-11@jh4rWx?s+x5ZiHVCPT=x2)WJdM zP+iWePQQ7w;Pp{n+;89zs}_96?8oLz7Ah{9#z_s%d}*Wk<~bs-gQGZU*l$jv-yYnb&e%iJyJ9*> z<<-0d{CN5!qnZ3yJ|(6@3ej)#iao*XZ)UtIhAaJ}=3y{ieEP*x>9oEnZ;R<5V;unZ z<4JFIr*V^~is32*?xt<`_os2)d|X3&@YGOsfEQovJFOdyE4?SiH-+%yzlWT>O5^76 z`O>F^+6rM0Cp)~8OCMw(A!ZK>!8g14I}G0dpRb|5F2di|l&y%ayF#9ciVM$U)8~un zYbW?_KmHTL*P1DaOX$0F-kSZizDWzja2-T^=<@G=w11&5$^744H`F(i(0642=9zj_ zvSVmpJ0X1ym`w4rfb8Df6yB>bXsxy`@RxCQ)vGqf`=5huSmIq4dW>-j*e z-!cilhXVr{zVb9NTo0k|&OxlcS$(+q1N{+0Z4bfs>aspgXq zc>gf?9cV{cuD*u-<|q2C;hXE=`UhRfTFAxK9j`TV2s`s^o4QAPUaNhAIwT!Yb%1^g z9$4N^!_(@tabo@EC;0Z8XJz>23-VR)@72LVbyr6rX5OOlHml9%0Rf`lhK{&&gE{|W zv3|?PI)I%`?A8!20-D!L_AydMs9l@C~A1ei}joIylM|{J?+NK{)-u0K3_w> z2om~QD_U;Rxal4-9g+#YE2px2^Z0yeDxtQY(D%&V8EN!ENuP-EwPLnN@hGqeXw&G0;{@0?uN*3y-f?P5CQ z;`Jz4C#ZD1*S6U|4Z(h7E2XQ^+jb$IueC>id1ik9M9$csJ>XvuVwzt|7 zj-&DI>v{0`ux{j8^nsP;%WIq2gBRyJu-~$~Zt*KT9Qt)`ocsy@K02-)xQ-%D(r*=N z`>+nMj@bP~iN1yhMR?Lw2O^JZ-GcocbKiEc-yf1*QthEM;xw{`(uAhwZzhK8pQ7Tz zbrlb9*^gS1Ok+oCBOMImPI6-v_bznu#F8JJr!n02$m6CNu8eWvdamaTzK@yw7KX$0;%16=p( zk?q$sP7;1`yTe%+Hgv_xUzaoFYr}jYKHPkH2XkF!0UuY#Lu*)x_wO>VWUCx2y1LTwSUVIJhZ(Rzb&iZ#?{Vk7= ztJf8`YztL?gLSzNyopWVgRR#&L_t4h2X&rI}f49$ramymW;)l0)pm9@=ij8kM1a9w}EUv{T z)^C0ScTD44hOg%g*UspVsJ4r#=YhV{*R%RcK{4E9j0^g9U%r{)D;?qHCB}T6;rKA~ zO*TGco)WX)Y;3w6&#&g})bfYGsHpRY5MTQKMpIH zn~QN_9O~nIeIo%G`Zq)H_q%hOsCEz6_pNDcsYT*Q4xGU%aBfA4~kcX`SCsjM1Z_>vx`w93RYd@au zaGeC-Cu^K!_~sN9iw`*jZpX2CHkz-qzZl;XzYpCu(>ELcz6b=! z#dTW$rukbS&hMkA?o-!cVBGxX=aqJvPipb#^rhpO2Y>Gi=JVsLR9!;jN`1KZr83UX z9t+3c)~VANT+bh3{^oo-yubPN8|%<;gnPmjUp(^?-veBDxXwjJ2S;@AjMmqOaUq^L zep~z}jhj46EUxEaJA?hr?4}PQcUE;!;?%)U@LjX77PF3+F32~T_`Tco8Ku6bb+8VI z&W~w*0|ejiy4|;x#?6V6FO3_-xR96JJ=OIIjT?v(mp)G+eph*8yIIZY*ZqPzNF7!C z4{exEEB^|On>1U@&K%gDDkH#4UwD>kcIJxF&S*X!?8mTf^z`Mx%NnjHPFxqE@8qUk zchT>gKQKBwqtBBksQRLSBkh|v>u1DQM*m6<{5d8lFzJWi*_{zlZysirFV{~v262lGP&szl% zeSgX9A2l7MN%7gQjL!#Ld!PBR4lbjAB_&Q==Q{OsR!3On_I{1ru8@rWl^k*6y72iB z9~ulU3Hy37`d9MAiEHbn+5_a)|MgsQTEh**iEG9A1B@5zwtvgGWp0%5fgb16F<*$k zJ0JJdM3t^s1;Au36dh<34dw&lbF3H_=JPKnuY5fUDBU4uxC((=q+SJ> z7R6M|aGe;p6hce8+Ulv8K+(ZwxPiXmakJ9OAak8=p5T2j9C%&`>qcz~A7U8EVtVf-x)&<;ISL{Win{Vn) zLJc3G@5+WF*3qxaPO)(_6@L#K)-~qse4sUrYi|tu0Qw@5{yBxPTT!Trv>!;I!Z>?muC<1>B8!DOt^O7TGSpqU#omkqAtB$Ysfb= zUtZhH-~5+UT)18?)iY`ps$?D(`MMcye)n*{oxk}Fl36{{_j=U*M!wCR|8wzmnJ^yD zeC$5NUd46&86U0}>w7Q4z0&a791YhKB`((<>f-yS;@W|0QF~BUs{ID*Mq~Q*cu(W& zI~1P|N@4YUh?7H~eWnwtVk&0#;3M?ib>P6FJA9+mSHq?AGX-ssX@30Qq8jaKvIRZ3 z>yz{;p>_~oUk&+W>!UwhpbyFryuLcApXwKYYc;_23tnHHj`I?TXYcRX*@ouJYn$oo zCGvG^{{{1C9OpY?>qau6!=Fc3eS?Df$~doqb(oReHvUKR<+U{(=;H!t<_dNOele&< zmCc&{Du2c2Z^@Tbdw_9sT;9T`>G$Qe&G_cxek+3j9{asf6CMuzx*4uCTICDz_vKl` zn0*}S{mA1yH%^|$aT3=KT#Lp@8@4mx+xi`ruZ_dkOot5YZ!ixy)nIxnT0dUf3^$$N zYc=2-_(Ci{ldGzB3iHjy`6u4y@uOci<15V#=MPhV*yYsxLcT}6uL+Gqx6N=}gbqOi zJ4^afOa~V+kNv6H9(8{}>z?{z7u45^?F{m$^2K`P=u!DCZhUy+E;X;lwFB3p@j)SUs9TTK!4;(r zbY4jhoa1pO5!cVJ`@JcTAN{%+Uk{=0E(3p)my5+S z1^XMsoelG@?WOtf+Gczed|wn;|Go5i`71PzQ;=^K))!UMxNe)<(73#|8DB4vPp-}H zx0=Su`Y3W_~xAaK4E-w3BFICs{RnoH(yX+7aqr;-{u5{-I-^3VjSP-cxHJf z>~AB!cW$Tox&+t3eb_I6ufN5wEot23m12GoAoT4#{g{WwRRnRp*dFdefIi2)X#XO% zVrFMjT{TWZK3SsqcCQxCq|5QmFAA^@6%g*4g8N|mNmtSZb;u$7qDrPWVSW+7_5ehe z-ZKTJMY`hqM9`0k{A|I31&ei{Q8Y~Ztz!7T!UyZKeC=K_`}JbJFwVc6Re4(!6m^G~ z@s$a_y+*TqgI`CNPtx(hUps8Sx8=o(jtpw#trye5fyW`(pYOVL^+6gpbCnpbpRfnV z=+wzHF0XB-uY&ajzBU8CDXYc!+K6#}mc3=d_&Nx_UH)P94GQuNV0~d8VA)WoFHcYU zbu)c)aomA8xuj74cJz6?wi&L6(Ba*NYZyDTuNCVz7h%6c|7P_~t0v}eQm62IzRAW1 zAPv@)Jh#}ooR83<BO67-tlt8dFN_!O{#kS+4P}e+dsK8h zOTqaL3_u6YzVQT&n-=B#jmA|lE}FPWGd{XCn#Q#Y=27x}>No^(=if$C>@;rrf6?_D z&DVnM4EBf0ji}0uLm7j_*4I7QFQDIAAAgj&{vl~}>J6h57C{bCS_FQ;@I4q2}wb&oJ@+i^FvyphkX_eChMD z@O281Pd@(HNEC+Ep76yuzo2oYzruXGR%ZF8J|w1Z0P71I=(RK60r$|AY(al>V0);F z(0*>8#;l)Z3i1sS_HfO;vA>QiYS`w8#dR0KH>(57*P9{cZysV^`1Y-pOgzgKPw&JBXC!HS=@}eVs_>y;`-P3_MA<>Z-Jnld7G>80S%wh`PvP9 zG%l}g7ANyDU)Ud-+dXe5jibCPXlL!zyad*x8jLOaF^$V>YkcYB@`(Fr{W|dJ-t_Ak zyTrz~q`_+3fp}JQ(S+SJZjPW1QUz5%*mr7wCNDta^4drTkdP_1nqhsr7x@U%2wm|C zexEmp^@Vi+$ZwflSSyxWkk1M@9`aKAdW?mHb>)X3f)UBA)i!8Z+HoQLaS-u}Tl zKpThTFQQ&AG34tc^ldb^Ff2>yiiPvNTQmDj+N;_bbXa!!>{oQ4sF9J+jXQ>XT?F3; z?>bPE!QCsSueD=%JpL;Gol`V!@-JezDR@5sUA7@T{0aNLX8L{Twwb=ESYOC@+6_Jo z>7TAxf8pA%?s%<{i->}q0pI`CUVdA9KHA!huMP8s_%Px7VlU8m`Nzcc4eV0w9}M?O z#oqmC+`QvrxXLKi9)NGf4&70fqA%%Xx%R6+0k<4Kt9)U9bNBd985?(>6yuwU?W_pG zy@YmoV=ZR==D~bH-!(^$_n~nEf_wvn4*%tKV&-oJr^Iw{2f}f3&4$(}KPx0ls5p*C z9Vg*%w(Jhu+24&HeuO^2nJ>oIxg%_6H%9o5(ztSYF*{QTzCX2?c#Fo({9BB#1LK1I zUb-vSL*v>`i{ZKmzDuvJt4HIy2S%5#)8~2ccmeaFj)NX*OuwFfhRc`nQNYM*rrH_o zi#*+Z5;GsN{=>zksf5~I%oo-lnmtjU@e4m6*O0FV^M&}3dF&Pw*BxiY_y%87`=u7b z-Pv-|lF)}B|C|%U_2BpmV^Og0PR1T`f?Qlf9kQ_wFu!O}x#tBfkCLXS{+*pJ=5INe zFABrb{5qwXb-C16#BlR5F3ej#daD(rmAYcvAm$eqw2}eZf)17P8#DWm>B92>6&Kd4 zcP(APu7lge=2_`Q)$<@BP9;G=oo8W9-*DH*&x6u4D3)922^Z$%pFzu0^k7 zNS@#LrAT(}``+FzYuN+XLjk^4st?wqk~xf^lKI7_fLm;n+~`L@DMpD`98W zPd0624&Xdt##h0(U=NcAK3AOs!@O*UYa?*y4S7CcxK^w$sw8P!;;y@L5PZiuKWF%+ ziQXTE=(q2lD#YN*g19b>3l~oQ@$O6p*I$7xL9p3^^is@j(xTuoON$)xJDo9d#c`;l&ft%*&;i7S!mBnx! z1n!d$f6$)B<+XWnUFrK)D6Ttj?ZUNaT({u34*IUYKK?At&r(H9hjc=RK^v|?daWy| zg1Fun)o}>s7vsC^dQ=CB8d+b8*{_q}Yk9UMGk=q+is|5dEzEb$cOSH-`KING@pTb= zA6&rZeHns$-9()1V*8^m&6n5a*{|GjoO*pVt{u1*wckuahadJnmPYeSuO`-SZUT3b z>q|6?iLLN-kou}R$hcOt_SnV}XrbT-{jP=RCve;KQrOOJ&3h!3J}k&z{|%i&?{~X# zo(k*WA2r&@3`9u}aP>8u7kbgk0OXU9pWXe|EHp3Fmt4Vhn4RiY@9X@Yf&cQ$p=Dd|y_uwT#J4n0c)Aycl0U!FQbjU&{kreGU0~ zalgTUx$ZM|Jt`=3aSi(|5Ay{FF4~H{-(coNt`3HLEhr-cZDB*CRq_Q`F3=VGFz$MZ zA>RPzTNI(SXvWSrgO|kk`Ui*kwm0A#tSzQ*KEb!G0blE7F}^-*51_BjfNxrg7~del zx0?Z9=M^qr!+tBkxDeOvZPs1T83Qz~a&ehc;E4d%0rEau@4iet^YC#E`AUz3$D!v9 z_@-YI=A+L>~ji)+YNChY8ZOV-Y;l9)YMFkjGjX6NUa_>k0G zOy3kj-wztCXX07bOI%z-eQkK$1itSY@J$)W#WmE|O7Qg<@O269x5$LPTjq>l^tJH! zTMYT85`2Gt<7Yq9npyI$;6Yeo}Ge z6Y=3Xh&;7I_14=EyspSY#q2@B`a)ja^XRr2I#AS5%8BWlLGZ0?z}L~2i)&~PX$0Ti z27ImMxw!O447K43F33~C-;T`b&CCl6hKuQIBkcFg8>=tUZ=O1mi%XxPw(&X_~ZTFAr^$(!Mxs+kd`fr+ptFK|d*@=Fuf2v?R{pQ|^TwMB;P}^r$ z`65S?#(maZM*fB#lH__TYJW52>mc|(V!$`|J~6&-9Cx7KTJ(7iO}7fk=wGy088zR~ z;q*F;(q26u;*Nd#?uSAL5r33kV&9W+qYI6|7GPfZ;THBf1>!9X|5c+O`;wPfM||_> zu3GdF86Cvz*YT&y7uKUTZ(SbN_hfAP(tJFtRa`I@`^wS)A5$^Y!AIy&b~< z_zB#}eIKnsllAl0<>*sF?I3|$yUU-|>4RK?xSo<~|G>INUW3c^B2{4+X9-sky%30F9fmFYi~W+v*^KPG~d*n(dj_PGY^iFfIIpA@v~@L>oa2UOeXp*xMo8W8rRn~ zI==LIUSeIj^Tshu{!1TEx6SO=kL?!%&Xz@AFxLg;bra*8i?9C$8~*wJm8WPvIh!Ke znHgUn)&bTDzFTZKw9;>-Yn$QbVO+>lhx98wUUw2|*q##8!B;1I9n<%<+rC5N790@M zK_UF&+r16Ys!VLfOb5R+Jic9h>@G#iA6(bs8{cf0Zz)7`e<#cO*w|{b9QLd{9M8(3 zm$n(`>*M^s-mca4C3v{jst*sU;qfzmNRKQoykvcSNyfE;Ye!Cf2_7!|pqZKJ>mu@~ zlS5v^3|c`gLwxU%gn3>$rB{S~RY^2^}tV{%!M}9v%~&o$>g( z%6t~$>%p}T*P?ubSYK30&WG9`qV+2nCl(*vb=1!b^TPY45ARLmrW_KB4=GQo^A;HA zPmaj9=NX(i(1tCudUqj9Z6#o~JAn(#W}?|-Zy0~r@ zAN-gvtP}kE?=KDS@QpI=@bnE-|01NXR70(0trmZ^Pn_KP<*E=5sO?O|7y_~NfZ#Isjte7c+Fn=v}F zJ#h7Hyj=B*N7P!@YC(N1SYJe2y1(1rOq#DfBQjqzzp&%)HA4=ZG;YBd8aE(|`CEQ% zwck*ONdxXKeVWGQwaxg-gq_{`yHPb7$IsD$*KeLlE7b7<*8yCMju)2K)c8;l5xv~u zrv|8!Y0i<_W;%EmsQN-aS+cbK%$>Ls?`_5ULjL>R(Cv(0SjI%QGoHS#`d@|g z_2AlvYo5Mb+EeqC{{?>I4ESbx~G zwdJFl4l@4UIL)7KYkYkV)d{T&Xs^2n+~2>jGvDj5{wSt{7wZ7)M%SM?zg6SwiBSi7 zpUjQ#-B=A*aKh|{6KEGBwi>UT=H+mwu+Pht~=cBDPTyK57z8-?_)^e8y z(RjI0-Y=6r&qa*$?%fYArC(1L{N7?F#)a|i!!C)t-?kU)0ONe{=*a)ke0gn6U-~#V z!S`HAi0=C05nT7Q5#Ixx+1I^DkBV$$wV0iGFkf_`hIG9W`@I9tb7HvZ1mFHQK2F$v zY&PZ#^W$ZEd)A|M;I+;A&5Lni-*j!Ad~`jczNAFiZ%lkRrsfY|2@6}DdR31qNd+6k z;+c=Iv+7$;UZrsZg7)Ae{9=-)|F<+QuWhDp9?@@>GKuTAe4^i8bF=poQw~O_FWqm> z2i1N9JDXi=c2oLuXKjp(%gsx6uT}FBT>EexZC*n2wH^=KS=)=>wxId?IDF0eEd%>8 z#NYR>ZfE?$9i_fBpCsfEFc$(`r$N8@^CIhO#y6S3eX`D8hOhHbWL$2)&0eSW8?Jr0 zj<(-u9a8XpdXdahr|q^c>DROCiLKKr7#H?0-u=c}i^g>ees3lP>kIn~^ZHqsd93ZX z$oiV~n*|vf*h6{ru#H%sLG$(Tzc)jl5^7s9U-07>DlK@3J}B_J7+*Wq7v=$d2r*8pZ`X z8)vJvoPIq+5I2DD{|oEjvwj%G#7XB3F@0@>4*A)M%TuLfb^Wap;`?LM?Vr&)VwI{si1gC+xTSxq2JugM#;n`Gp6^ zUs#`<)cDFu8aJh>n7%=*FYE_=JZ#2n8kg7B?19cFZ70OswCeS>b$r$Ip!i z(YTod1aaR8`^BM4gIqMOU-bK%1mB%AnvS4xd2P+k=;QoYU&vD(TV8yHe!W1DuNCt} z(?hAoqKp+ZF0XCIHy`tbxU(enSYsL|d68JZDFoj-l{_tJTwdFZZ=j*NjtKh~e~hj2 zG7pD--3-@7elT!ciJfQa%A28#wx3(Cr?}=v+NAl>;X?su% zHyb5pFmHi;r{!#Roq&EHx^1SfY*qUW?Dw|^UYJ0imy{yLHx=2@A>vuhw|XUPpTUj!f*(I|z4$jYUwf2% z>Ac!~Qtda;;Vb!xIW(?+i&$QrP3Z8AC#^1x%WI>416O5=2kQX#`$zAz*XRTMQR+aS zmyfU4fIO=6!-rRE`>{%t`^UiN|D$O3OZS_Xh`+n zUTxU45Ip2Y>O(;_Jci(h@(609N8sk}!Y)*M@WY2{cm(i+ep53$b1hNrs0KR0-Ma?6 zu1o__Z8KcS8McQV?)U$oPUALBac8UfdNM+2@X@ndxj@tbX1G?u9u_6g9#RS1FB6EH zyHT}!8GXLN9lmcweN1lCOa~k03+tY@q&OPY(Jp)U0rcUEFO>xl* zHTW^`EnMN)gW7dhfuL$9JYX~20Okw%!{wj)_;@(<>t?t?j0@L6zfz$Klc&-+blVKq zm!;|ec~rl>S37AsxTeRagM?N(L0`~ea;;e*9mW53kKzPxbw^A+(+vz_oNtZHum_%2;2pvrfMb zxW(f~ziy_ljP(V37}}&2`ddgweTUM=D0q)Z#f+~N>u@hRdHO5g z{1^$t=rvPZLWcu2=N?BogiiOw>2Hprs-510&^ms<7g=2)8T~7{uEb}*>DYc@9{cFJ zjR~8_Dp+4g%zP_*1MQfKnZ8b}1K@6*)PFmwEqjTxvv0%cnX1Ey`7sjCz z&(yD)C|n2O$H!|mte+@c7okJp6|u)NGaWJs+}6DxJeM%Ogq>vvs(BKHn}+jLwA>}7 zH(#ExambDNLY(~c`iZ`Y;_Jb<_aeYat!yX?#a6U_qvu&!xZhwt)aa$_OngY)6y16W zjq4$B8ynzeOo=>?<&B%JvzyfG#BlAyb+qFq%{QCi`-lNw|6#H34|xgPM-6a!y=c~N zIRx%w2DtgZMdpi6|9>ff8{+(BiBSHSs5kll;%laF9-(hj1AT)dBkOC18z69-8Q?0T z#BlR5E{yY*)SXP;=jPz@{7wF;NXXw5Tsv?bt-sNB;KTa?kgvOru6vt)JzH?y(`8Zb zcLmoIH2P)~y6#Ht2{|jiJSsm;UDtqhxuYGrKS%S;5ZsSVX&$~m*BkOUCayakj4uAt ze0jw5Qm4)eF~m)3Dg%M1>R@D%ihZ1B2^!1Z{)=_Iu@ zI4HtXn!nM91n~EdVBIMA za3jBtsxR7pk{Vr3+SdE2e|zH`U)@ z4dTI*OKWTMA;-D+{5U}T-tEkCMRwABllb>RrcVjAlSha74jeqyM<3)H!C$YI>61`9 zP(B=YzJ2J)g;FPjgCabI>=&j|Oz}2T?F{BEpFLEXiNC3W_bawy9l$SME;)j^zAs}7 ze|(b}w&;62SO?f|v5$W3Z;9C{GdPKO%FK_0ggu;pjs3lu0@3RUuB!S%zP>i?I9wK^ zE9v#c{6eaw+CPk&TZ(K!-wV|j|951q0ythe~~OP>R63+4+8 z1SN*E`eu$3!g(+c!2dxEVk4ab?7bE*7*C0^=vxISzTknbe5x_*?#^^6t6&B6C+0Eg&! ztln4}SAIYY*M$rh^o4nBLo`~%TFm044ch|*(I>C9W&GHeD#kahks8+l@WtX6C)0fM z1#vwV_4^Ev?~Hwa#V#7x`>$Qfu)Y$$< zk7XMj6X`iK`^~}QJnUaop1AfrjS&>o!GY};d~RCTt8db{N^`!xGJO(i%QIEKfN_4z z%3;$a#xo2~BAzmfXG#aveqkI+Ki+!~aY|JGn(6B!@~G{lCbXr&a-z_IJ_p)<;(j*c z4D|JH=Z>3(d0#HUcas6%>=yifGve#Q`3{W7_kHke6Z)6}KCU5OKViSM4eZz1QjD+s zdN^ONV`J^t7X_|Ne@N7}Z4KM+g}~JxrKtu7MR>~0&hm(U8*ndcXQ{2kbVwz1sA8al zoGWH$0fKKI1HO5JeC0CX@y*rh(?+zEPM_HL=EUPX-Nct7+-0R8Ydxt__^Zyf71FUwGqRW3EY_tTaTh~vjuTI zgH*m%5n!E%0IHTrbzecs0S`MEsQ5c${@kjgyd=ZJ71MQf-|!5X1V8 zZ1A>j%op;gx!wUkCyK8P=MSJm0vcK6h~)!vOa7T5yap{Q(UyL zqs5)S4emQ*0Hu4%4A+?w=G$<2`~F(LDKk_*)PWc@09Q76-hyVBz!&c%POa~Vp=V89ttI&hFq zY`P?UU~o``r_A^&WyAU8`LC-me6t&f<&(MXRlZ=j%ZE*PiKZ41T$gi|Q~82l3>!Xp z1C8q!{2dS<{yj_J`+;}iVj4F|a9!E^fEpjb9-jYiC$pX!EX}nCa8;(HKN60U>2KBQ zMIR7I=I1-~Inb7g`P-Uh9nk)-Ia}+w(SkjBlbCu1w(W zHNdq^=HtpV8Pv7~!uk$>*19B=q!=7$_LP~vshBTZhgZH+(pmcaq__Ee>2si+j&Wgr zkvXhx7y1}SrWkG(fqQ)iiz{~$^EcSfguD;p_&?F`0aY2?G#LmRX3 zf0V^6o;mP%41PSQ_QmEjoTV$5uc4h~Vmm|2iPG!$biGXDdil7LOrM0>1<1d&`R3#6 z3#AKOcV)=eP58y$$#qB5Z=KssOouE2_n-l8&Qn}mno6kc#Qg^QL+>AA*Zb@?F)sr5XHsg1>mkQz|HE;%DVnzNznX<0O4bsGUQ^hju*z ztLTHgJ-B=g?bnSQ5$qTIV*J~;|CJu6kt4Uw{Mb*#om+L+`e_tTPd;Dz9BAhgxVCOA zZu--FT-gX1T`vhbz<$7`&o|$en3N`1|uReG;_)RP}{*u6iA&wUE%tTr9;*2d7uX zh41TqQgbtUm)HuzHS}W%U)KgN4jTF^^Y+<-_xVqIKD=&UrRZ&DzdP-7vH0M?xaARF z`GHf1Xcd(A#QehNRP}{%{>*a?E=tT5NAx@C+l+AdWf>6#e}nwD!S?oT^k?x~X1D=t z572L~PEY_orUJOK!5KN|1>g(&PEX{beW#%Y2Ss?wjIZk*b$#c4bnbz{b(cqgFnr03 zufL(n7xMM`@65Yf@)(|O`lK0d;7=77^xf0e@knUkFhyZsFvZ1up~GI7R<*5^%AOnP z8Nf9vPGXW~P@=zc+(x2d+iGH)BC7$;l&%dw`moEg1?I>W4@4ASDnx1)$ZY9d<%#?)s>fzb~E(F z6UBbF{tUI{Cawc%{^@x}U!?<=uMw2;~lUxg!Wv6!_=M z%r>*LyV+!>^E~Zlc4ywadFPvNzM0utZ_xklLtrQ0I)RrwC#MF&o%!sG(@bcYo;K4VsZ=CR&FGOdf(7tA z%f~m6i*=}k0C&F8QRmh3U3~T+k#Q65v&m^V3%yHx$*kQHNV|bwKm6>pODt+;A3nbB zGT6>wU9L^u_o&@)OL%VK^X&Vud9!x&QT;8q^Cew>%h}8~50HtzcOW9SKXqr3>1(6< z#il;nb$&9bFQ2~Y-F_<^35at7<@#{*B*b+ z=)I$zGqc}BO5eXH>GgH=(ZYam5FxFtlebNZV<26>^sTFVx;xwYqt=w zGnf~y9p7{di))oP(>J>U_A9XdP-BSqT^2_kz{l4`^sS8mr>#D}k;S#jo9UZG>3ib7 z8oK-Y@;Uk12I9|o7a}&`ky&@J{G7>rc4pg#`vo}k=U(g}v$$4yvv!lnbEd)XT&|M! z6N?kF=4%-5*onR{f4gUA-BB!V#>;&6;G^uJ!L)bKE_Hm#Ooxyi`!kpjmOVSHSA3}E z{>)GLowxql2JTXmvIkk}V5qNyvfl^RJgNKMZPqK6xEda6#+Mg~tLHEBy{Mj#^=PJV zF3|z(cXykmM_9aqW0rA=p$^Js%op0NfAgU)vADT|`E*c-z7VgU?r~igm$2`{=FM~{ zpmg}ItzL)hd`lhJw+iRe(HGp+`Ni19uzD0xDfw# z_^ij|_}H5FH|d^8TwQEOY2AHSR_|k`gF@my;OqVA$aNOS@8;7Xm-3SrizOdoajo)Z zc9ux|I*jwZUn~t_geE0guM=p>s~JC;x4`;CpRu>kQd`0$;rr;+a%M*}zDeZw)Zo6L zN{zIqhB1!jIWK@8LWfP*|L3k9FXCnX1EUOcjaz; zh&H#FWXs~SGnw#(c02mxx&sWXWft)@^be`TenHh?F~jePyhOTI4+4+Cnwri&l4eSA7NsrYQvqTBaq*;wby zbnsE*#lfV~D_JD@J3hX)n^<3n&wf0x0NHP`Fa^WT$-XJdoAH&$N5UnGsThH0RnlD=i@|jO!z7VgUy2|w& z0YiI8C(l~}U%BSP4-MM@-rp>l>EK5Zj_QB=Tpd=x*0;aGr-Sc!MBjvWMtWIXf08w> zkv({bJwU%WU4;F@HwWtgesc6P-=KLRRxG$A=6+$=Zhney{ZmEPkEIh>UzoogZSjI` zeJ9_+r>{E;>j3%|FG9X9!WR}EMtAOqqIYddvUtw4nf-dsV!m)+=KH()J&q2t7CCy( z4A)f&ua`o+^GDvqZ&Z8mEsfnCjNaLEC$10v?6nWP+g03Ph8S*A6RZRHovka2&hG?H zM)dvS+^|oLK2x-FX8KAf5&^#h^S8y%{g4t3!|0kBZs-ZzFJPP>^5okyRec@ri0SJ* ziE&|{q0bfl@5iQnY8{st`7`Aj)&cAxVF=&&W`tWneb4>J_gns9q+zskX8NWPJA>=! zvA0FGe&(g_Gw(BRac!1c@HgxI3nLx8ry}}pEW-Ffq4>URz&F6T?{6QB`NH~di%lbS z>pQ7!E&aM-Y~Z^W<3fCP?uNeIvN`wt17Ak;o$_pn^uqpjU97)(2Vh(nkMsBG??-eG zv+Qq%I%E?az)!Xvrq>~_ou$60rat*7z84JmW?1ic>p{^O7x^7?m|s*}^UV8fp+v8x z4u)|_km?sJ2XpxyLw)^}z8wtoO>A$euOV&@WxwYQ>^H=@@9(GDt?7QfofX{2$5)|r zc*j5oJLmp!r}^?K`fZ-P!n(*?8fg{Mldwf9Cqa(tZu? zAwb!~-8c39*xuQ)-3&jVI~DsK&|%+v>2JeAQBEQq4Eg3!?dBe<=bM+p$2UmXZ_-)4 z{W>17#x)u@-T4u}-jr|LG}IwT>F~CJ4h5Y1{+X2h9{S-BTJ?%Anc1(C*e~2ye0X}l z&MazPH$Hv6L|>Sl%$Egrozcse-~8{JIg0_2K{(t?O$~MOqs^Xm(t;InQmydtW7rSeQ86!1%xlm zhiY%y{(=@2`R6bB_$HLY;{n)%+p}#tiyN$E`CK2iN;oeQT$pDy`f}VDwvfLzA8s;* z+sptr>lwavS|_E$!soYt#q!Ndv&1!QH~9XpI*&bH>#060ZUN`MX*#9D%#Ld}vA78_ z{4NYz2l5^Yca8yW(u;gL*oY3WFFm|mw|Ch0&UuLsR~m@*1@SMf==C#;>-wC}pZSRn zww+e#_U7b1A;d%f7DToBawOUmMXE_;xMU zT*o(as_+yVR9u*U#*)l%17trI{O_DU&pv^0VW=~l>lwWd;2O1C zCe?24KZ~y2GLVqqC&Txxe0_DC$`|snBr_dcWPcMr%diehnjzcKEG(u8dxy4lK5=;URpX10TP7|2l*l4!<3Oxbj}CFW|nv{R8wp6pZT;#Py?Y z0PP0)E~`@8rRv}l#C49veBt}CZ~VLaAr)5<#7!6ziGNEBn~CB++`{tbV(per;co4` zv=G-Lh?_u^^fSVv2*s5st!IuzS+JAuJd21jf$%X;s(k68sHC~~YsR`qoV^0j{-@eiFUY)MyfJu%|KehMV_`lrLco0rQR z@zwbMo9W;ne8K;YaQ1_^Bn7MJ>$;o*y`-D5E>>`OQP11+`_z79dY zF4Q4l+=PCyy-7a$UI*5}MZVukQ8#>PW)DtcXBAK_dGw!X6vZVyf_wv{-C)0a+?dW2 zRa`|7H=p2w{nkz1dtSv23gWsb|L{igeM?ka$38JT^L>fi4dTAHa-YgZ2TjWUhwu3W z$`FhT{-NONWHejWrmS<8_6s4HE@idDxTVpR4KIw%WDCeUt>ENo{GumAo=&9_wCpdhYm5!SIL!ktjI#p5cj zN6=5ACm)CXFX%huM)&S2u4AfLyJbwr_J9IOsq5epg}5F;+z`P9KiQ~R{n;vCMG!aP zE6f*gQ&OfC>KhcqRYqYQ??ku*E)<|yZ7~_Wl!D|uypER4#y6S#E;xMu;*M9mK2-};<4Yvd+y3p)gHU8EnwcyV_8kd`X0PY^eg%->)guJf52 zx6mQ3WM;n}!WZJR#?N#@?x&cHUZRK9irJZu;KID7-hj7XRdrAV{iK8Ns)cZ8m#u*g z#boqSatZQHej3{Y#K1GR)n23GDr3ZSuyw=rVIFHc)Dyz?xRP1B1=nJ};CC*(yBx`k zOS*m*l+-#boC7|9mM=ltGG4)uMUV+P;H zan0b1*WDD~dIo%@nU=WhM-1l!)c5r|bT0N9TgYdPYpAcSA+~?GxN3iDBNjJgjmuUE z=Tph|>Y%@sap?KFms#py$XBNLjys^|o4ni-*N|^M(HF+!P5qzzkS%22WI4|=phUgP5y}wH<8@u2;;>MU2dTH zkT#|7u+&#uf#ke|FIw1<9!>am8CxiobAFsk_(D8c_FBI>EUpx^+>g~&ffE@77x?ZT zAAZuQrd-lGK7Ad;&S3u5bw>r54ro%y8rRT%Gl)Nfv82mir*v^t<{r*=BRar3;^u4R zdTYp{OxAur+=NzWeEnzFRGZ-(bHeHAIkF_b66IXs0<3hVVkuq_r78U)T(nUVL$__lv zCnCVq+)7tj+=P%NuAzT$QGRFqyf@!takH&)*(%|DGSLC-;f1F+>-t*(C$5v=g5Q~% znmm?$bN63-I%E<*3HzJgH&9HAg=v?SYNP*&I_I@T$huaVmhP}To^YymRQ(O<*Nwt4H7$p__vPT zagT}{6vXuszTkgfl^Xd~TZA6WN9uh6|bg18~lZZJ>`*qemHN{ky6#Ff6r?E`#IKfLK(6;~$bfqS%s zS?Ei6NPUQZ+rPebt%~dVSj--h21Vk@#cTg-tm66v`6gAy>u%7G+oeoJ>yzY@-63}0 zm6DA=FZjuu8)u{cq}|AQbRudp(>Lu~tON9m-x?lRqT)((#PszMT&0aB zQgR9EU_&1rFk%0qT=^wv-hw}wN06`kt%wexgX=E=S32d+;ah)j5WcWpJ#KEJ`6^#U zkZ&rvZxF_}zq69jJOJz96V%s5>Dz4UkA>sBd_l|}l3&95f}gxL{(+BZZQ*s|Tt0o> zl)f8(nf!^WgCeLykleQdan$w9v}~5IRo<+>1<5`R1gHz1d=~i1=%wTsE2eMYTx6f& z;`OGeAIF!>_}a>2e+G8e^2?W=V^Qs2@~smDNV`G&u;DS^Cbivyg6)<@_`-ZhDtYA? z%U7As$Jb5amNvlkz0YUASyaC`GT{w0ZfaAa_47Rq*9j6^V|yr#;5v8t{$(vHx~~8| z;vD>_Su(SS9LgSQX1=Z47fCv5sjnelnec`A{Hb0y>ax7De&ge-{DgIYecsTz$s1W* ztGt;G0ZNB~A5YTh5IoCg5BZdxb!**w0n0Car==C%T@{J6UgreK)mz8%Dqe3LjDDO_M1ldmO_Bv&iVTv z7T31dQU|t5IG;-CTYi?l-SVt)4fSHD~WzV-u_xQ3s`N&ExEXMv3s zkt*7h9Ev{9>&A=aMK)d->fk0iz=qRrr}A%U*`jA29pux&Mfu4s27WTg`TU&>!Wa5+ zo|qN9zmIMYI=^$Z$ovjVC7cftJA?Jq zSxbL;!LU%2lV)}nnvLxY{BOl~{z3arxTO4%*g8RweE%5i_w8wIA5d|9bH#977cgI# zXBB_*`$j6R=TnTEzb*QBVWxxhLqvy1mw3Kbaiu%O#(5isJN0Z?G=C%d3gSvNBKBK3 zW1MatklDbpzZqIf)_0Nh$)WcjM`2|#849`t*X6uuzy!Yn^X})XZ2S~3<4I=iCR6(M z&v^8*s;@Lp%+72bFkg7z%SHLTOk%&#j~`wAz!p}6gaDuY$`s!NMab7l^aZ|4XCMAW z)mIkOw}99g*hH_MgZiqtKEZxrn}O{Y*5zEM$`|r=2=Yy$a1UK*S%|9$@>PmsI|V=4 zqt$|gst(cwG5d9sc7t_-$_<~}pyCDv`Fbea2fX77b?^x4>!omaH}!W^`O3B9^S|u< z>p9P0d#H+ZX!pgi6X>8xq0cSvU)PjZGd_y%dtLnPRlYt!9Tb8KT1tX8VEF2wV#jvnur`QHG=_uhsp&#QbDK^+2Ae|zQL>~SitBTjoz+eR=r}-^(e@%BbgKJ(}rYpN_{1@RJi$s->!YJ(tA#u|)g>+-Kfw^@ImiTzS42u4^Xl z7qEYPq#WATQ};Io_01r-wVG>5`3mabdmv)JC;Fe8SBNY49Qr^gV!!i7|Aua_z?Lpw7PB+Y z_Ywd5qjaFRiW?NPGdUacg?YecXUDHpT&Yfc;|1H^eu{7K)zZ(ZxIw{olY$YxkKeNg z&6csgj$>l_rgezudtmLzKiSWd@jRdXdirBturIRm)3 zZOET#Q{W;WU+0vFzHRml?uzu40ofy{uZ!aQ_LIei0VbW?$M|&cQMfyvsISnN@H!by zy>x>#Rmf}{%DIf~0q(PzueyAm<4_zVh~nJ?!f| z6~bUm@^Rui2yRV;mM8n0X+TjXRGH7tTvsq(*f_qnwN{F1XYwofJo`Ru-b`QlUL1eb zLlwGD%xZxSGFvxV-V8U5YPWuO9)af5q_k6yP=Bf6V$=>H@07xzx`dI>^gLi(O=BTOb3N(x8KJ1SXRhaP=`<^ zwlf&Rx=#1hM+Z4(vZ$aLU)Su2{T{se@Na5KMNr?gA0xPxUKzHn5LZx#0GW5gz}8{q zpjNB~@*uu(D3jtlqtv$#seFTiI=IGSJA?W0FU`KlQ*osq#r%$w_%qO9&+F&TsJIS6 zTsze-8V&0CL?P}~F}`lX7uL_JZD{=o!j;iWDJWKZX3jw9{f~{uYF;} zejn{xw$Pus1of5b;`tPOQTq9ZYkO6`9zop9&6qFT@A>k`PO!Y8Nx5#me&I>N;}DE* z)mHTQLgg!y&!Kq}gN&Kq@e#fdK#g2FC%{%MSk1R??|CSq!|}%&9bj?o6)g98*(%|D zHn9irzl*<}J6Y915o|Xv=@+oh^?K;#b1H675Z6cfho7e(ajLk|La~04M|6Pkc*MIY z(2v9VI0WrMq4*wN^y@z=t}Mv6fU@7co$3x&aeab(L*=lJ5J$cGQ&Z&Lu@0URV(TTg z<#@aRdnmK6-8B_AD7Y>cr1br4;zcyOC+#MvZhlaeGw&2zByHrH0uer9Nca&4t;-9|2u;PxA^u0Boz6B&w+9N zLC@kORR>uXw6jIH-Jl=;Iqr+bDsC`N9Z+>mvQd0ro|d&!#dV1C{TS;2{cYlf9#=GP z8biix97^gH(c$d)ZPrsNu0s%4Ci;T?e%`BPs*39p)HnYW z)&bVJRv!rJ))CW=#Ad(jexXd-4fr-IwoNxbr0lt|>8q)PGWOjV7yQn)b4xa|*Igg; z@pVxBxW+K0@ID()jCOYJ?N$=}`7-dIf{yTahWyF1M-(6MZY#+_jxKVP-)kkopM(6d zpU12pyD5KmvBb#nYQK>EV)2f*JgyJ^_XGb#=pLG++{YJB`UqbbH@ED1^DdRIFGhXM zbjT=!?ExL6QXNa}(2zx$q}qJ;kT4$iH<({^8uDV{I#*B;)7MGt4D1*ETr-+2<4@*^ zvE3}~>?*M{a&(a+ubm|>#yY^5yroUWy8-UC z%eDKcxKcf__`yy2hvJp5ex%|C1$D@2g2w~s7wh}fNAE%uBhN=hr=un_eG^e232jyy z{k2=;oWz3oIQxZ%=m7Tn$FK7~Q~5d;i}ee8U(6Q;)Y8uLmo~9{t@36%geW`v_oq9N zD!8OakgvQXG9G_a{j)+`pCE3=!x$Ih)Dvq{rm&wo+08d@I!|NVu>ZZ#p%sgp_z_?H zkVSL=zNf!SF01M*EfKQ^H(5u7^|SPem;P39WkFm&;R}BKWS2YykL|%Bh?`4rLEi(- z2Nv%8y99A1v~vUf82VfHn}cVfLtM$UUkt*ypzp;a`tJcc|Hrp}mPPz8=y2&+&yuRX zK0zJ4{V`vNOG-|;H<=Z|dzz20Li`!%Aieaj+8i1r(T{FEZu163zM77%& z*UzE*cd)*SAZ{Mv3p(6i`IV9H=o}r=!ES7`r8XnzNqLJKWd3k43AHR0nAKX3vLbdp_s zIyebmn7>utdg2w8uS<}xhdg%?;)i*^2U^lx;dS6TA72}}zZ%xLX7@{MuJZK={?4HH ze(cXmA>5U#?mhz?>11omw+@p<^acBEU2gD-LcW6fdMSOoU+bvTH~D?Obv6 zywH?aGr@nboxwnHsoA|d)${7np2&wQ&BeITFO+5*+NnCoE5!U+Ch@=E&zhc@c|+x? z91&&JeXFXgdUVy|k#CdOU4VZvnNKkzMJLi>(3WIWK-(|SCZb)%>zPfIpiPvi#n=w#}ioP>Ymk(ENg!>ir#vL&wJyf7J!XfW4= z{eax6EyuICnX~xXP2Pibfc3r&RrbI-t&Cnuz7t~pAxOnL^V8R&{X%UD*0a<>TY==# znqmJ7e!W%65@>c$)-?p}%trZ#xeqNn%D#DaeLlW+VrS5giywFc&EK>s>n=WAC*^m1 zH_x|Fb&ytywVO955|<>@uJWCVD+}TlQ2uOkpNUPhDoB#U&ZmQm^f!plW+*){9s5-a=bqEoC!5-RqUqg@rh^_gLRNz6|-LtWe@i^d0>@B1jsDpo67nTQ-B`ThNxTUlgp4^y3en9bZ!AD+}`V5q)7DX8-Vgx|Ld`9UouC zhWSE&JMnqwCzY>5kgvQGw-3a>Z#8u{WA(Ky;j;(Z&k=pUa}Qpi@^uOFRfxXOkC)uG zYZ1#=YR{*ygYX4?|9$8Hig$?L5#*b+4eJ2@EOGI<*fJLPFx>lzdawF z{IF^dK|yt>(oe8fzdWVWD3*rVp zj*M@c?w?pss{(r7YhAwm7Dr?Jc_H3ee);=s7B{n_rM`yqi|p2zFB&MM1cT@7C6=(n zWvPVoE}|p&-}!ee{9M)7BdD)}JQ&0eFb=g`ncX@3X4JoeqkQ@n5PN`ixl#Xqy+q~f zi=D5bzJ8)F><4uGt~iR;w8>tQPhT7PUJ__A;LW5tT2y3b*0_dza|mCUZ_d2OKZM0~ zm*V4_K|P=LRRg}B#g_9}L%s^dca8yHe`!9xUW)JHx4P=|b(XQjHRPL1@eSR(O{cFT z!4j8kl5k!jd@G~e;LT@xu!VxwxQ2WKgfHBud*9SI(0w-A6e!EbH;>{w)PQelIZIqa zzIha1hXG$(c|P1A!395Ab>w-S4pId^+>xHlcUXrX0@wSQmwR z!vHtXhi^WVL2$vZ&+oZkw||`dKR#S9g?n?D9ygbB-zl5ItvgqbE6?QP>!+TVdC%@g z8mRuvb5(2}kbHl{9^_(rdyuTx?X?C(avp*U?RNF9-*xSlzKTx=H`U+j81%Pf>v@17 z-ym9{R^#f{C4Wg_3%OVG@%0eC5U<~7fSdd?A8v@UvjJb%f^9=hN}tDvoA4X92WU6@ z|Ma-h8a`Z^;DRBn-*i>)e>rhoWSj>l`up)e`f5aoA%jEvFtA@rcYX#i>6C6AKhVVs zUk8algLb>rt z?N$ci6t8?cT8D{mz0b^kU27u!*n2L!o2suz@b@fzb1`3tCljW9cvHm<#=cIVDyBL5 zDcp}g>sN>?troKfFQtQHa{%pcV#Q=Z+z^HP*TQZ-6<4y0eP1tOZKU09|Fv1+`lL^g zuR`hjRjbACsC*Sc+(guYVcdlEl48rJOwu$e%7nap>rrwE-0o!&MryHBX!ykK<`aD0 zU^=Dm`kB2>sJOCVySdN~0O$bz>{!;Hs8?gYiXh)C!WZ@#Hgg5>POn` z$&0H}R9x2!Vz~Z_c>IF#VsFPLXnIKcTa0|I_Afjy{t({3@R6fJj=cL9ZqjaGXInm) z{Ef;tDA;bfq}^bg-_|eCN5yr-r~_6FRc4awZ|oncq4QJk{{WU_WTr^etQl^A_y?GG zKYeIiVZZPQ@|CIk%=32lDa7>&;yRQ_9QDmJhi0q#DuTE{QXkgsy>n02RdJ;?V*Nro zi}}KS)<1Xt^gY{1X`J`*Cw~+fFCN?7|2LJdEO^JgAXA9Y~q zVAqRNRa~DSZh%@>{&v^X`hA9>eD~7^39ma5-+CXoN2`1#Ma=KWq(0g>mg>~&gN9|S zm_ra(`33U=zW-Zu`YRRJ^}HD0;CfuYCc=GjU!^Bh+@RodB|_BrmMj(fTE+Ek5aXNv zOT_<cfv@@E^=vY} zL0t0il$n<_peU1Oy&ua~3FlpeZ#k6fz3Pz(hJ~V>H1iK>2{=xLb*_5vJ=%+f@RsE3 z$H`P&{pG+d=UH5cie6e@J+b=OEf<&9)|LgafBDwLHNS@L!0sMWn1B}*Uk9a zDEocB#TH>uMuh8NHM|lg0c)0684M1UsAj&#$`m$&5{W{lY57^V<2rK1aMLN=C9S?d%McjXBZ%vy`rC=-W16bCiXd(Q zWxtO!-l?#T#$%SyMh0$y=fYX-nGf`EZ;a3Xcme4hQ2w%q4IT*`**ePqR*M> zAR`NaegS;@)ST9Yt*Pwg^E*zWFZi7@y*JoZzKWo}nM7Z(vs=U0qj)mDWTr!KL1aEO zYHC)(iRVLzZ(Uil*` zUs;fEkkU8Q@X5glUS=pq&6?S7h#H61F8*Het#bP&ass^Lp!eErn;R^^qnGgdh4bu-+=>ezl^zFED) zl|Ksk{w}72Z4<_Yw)^&Lm?jsK(Mw4dvg=Pc@{byHJP=W?MJLH@Ljj)hYVE*-)mwzq>*-map=bm4?cnp zGWv@-nekOfzbJ>0E@amjs`7RGDaO}L@wHW6GF`_le#&BWkhRFsb7p*f zWITp-x%^A7A@I|yGGhuWpQEUR|r5wzce?pO!-JiCkVcQT!XFSOgp+e*KO z4sj(jeLZ=YFU;qE-*6P&x1vpHNqqXcD1Ae|5-%ZCS&JM!XU5k{=Etzl;QyrbaTX>0 zZ9e;TEXO*)xH<37i?a&tLGZpdKhdEg!oBa)=lm+JLonV^2rl%uK%+CqR9ufBuCpZe zv!KJd_fpU@1a1k3;Qh32JH`b&>wiz*QRtvaiOpiOGxqmpvhK$12Ju6|k#@THA#I=K z_aQYr)J%}*3p!LU*Zl`oUx#4aCx3Z7`{D9bB3wHop0Z{X+auGkwR0>gR~{ zsP;EjUu6Q;7yRUJpDo(S;-xK(t=-sq3dMKjU&%gIUq#T)`I3IEe z;<_llU$%O9u-a}uL0mV%y$$hgJjOSt5LXei2QR^eII5aYLaQgZCFCJuxJh?mJA-xb zp9WVrqvE;*aXrNE0NMM@$Dtg~oo#YpoR{N4Hp8{KFkiquI>Oa59!w}}h8sjZ0rUkOmK325t~{&*td}I*v1*ZO zXFhTsosOE!__~Nc13P=YWzpGLuoU(WaKC4>Jt=#lk~6qy#y1ZII-oDi15&>=&Z?sZkmk@t%Aw;<60-WRar zO=f)aDO~6q@g_6e5W$7{{DX^&->>T664W8I9NPooI9#C<8|B31A%a7n5*z;OI z#g#9L;bxNl2Ju7RMHLI<2cMu0ZZxn#zkq(+^7oLTjn zv#5T~=QJdvH-vrx{Vnv1{VM1jPcq}1K|Swv$G5{_KCexk_|_*wWV}FunY86X<$LUH()animpcI_oqU{pg9I1G`Mv9(`-;Yd*NL6^bVw!b2K~6x?$8iekBKLl zwVR7P7ZCKlzV>-ohR~!SFW(LkJDZ%cwj``W#FNbUdWoIE{X0V*8-6c~>F0bNNFMP! z;Lm)X{9CYp8c#Cg>%5M20DWgXoT1Yel7*y71|s5PLx3lr+l#H}?TPTz3v`H?Z66;jcDO{f=B(Y=6^^ zJR|sDSl6iDTw+AT!sFwa1Tz=M1`xTt>IY)<2=wc{a+%9`;_7=hy`v=Jbc zesJ6KEUeOvkFSri-%kbyboQI*;lnMs8@C&Lp1+H5e^Vwpfc@?`|8oJWLy(iN{SC|) z=0Z(p9DNXlKXE0s-E{jRXkwwp)ouI#tDA2obN((@GNnVnKnKq#zIKzEM%pdjSP}$N zbzsGFQha|m;F~&{kFOKGA?OR^(2Xzk&rM=^uz54S0m}dGHsEU;!^hXY8uNv@@#4(g z5LU*O%=mhUzA&zpzN@*;?Iexm<13++E!BQ|-hM-8zgFZ;`4T?~@!8Q9|IW92bc%ln(>Uw>T|Q#&2&g4&zA$g-uvGpm)Uy0d#vvVm)S}v?;?D`Kh)WSTJKGR zLQzhsd|AI9p!|BWfnU!b%C~<}K-vv-X!YPNUEF8OuP;m7g#! z#J>;SdHVe*QW{=T^<^(+5&r;V(Em=}yj4eXutlQg&2VkRpMl@G*=6$Ijv~UfFUS1? z<}Kx~?4G8^zmAv1*87sF=gTesMIWDe?zQe0MnWZ0I?P}4ROc#1q(eI43wHMViSKpa z^O0Ng@y(>{_YVVHg%j6J`~wWcZ*6aQ@y;UB!AJ4^(}1u26TbeILvUdpV3U((v2B~p zi5noeFm66wZJ2J{%xuHgZb>^L^OiI7GGAx;rhdw&Lk4L#@DCl|MRUUZVSLNZy?+J!-We0E^=0co-bHZ1 zPxfl$)GaHAIB_#5+@}n1bK6?>W5ex0|I64OP}n0)H+UXt;tQ5K7~(1f7v@8AnhiRH z4w{tkA|Gym;(K_(_%<3)lu3Pw4>w5Ro-n|5x%hBH6z;hd{o1p9Gy3r1O6j=WV85l2 zTvIpS%<0RAYol_m9)k`EX@|3-M&B zy=@n;?dE!g4>yUzEpLFEIM@=Gr4r8DNxMOu>T4*2ThpY}JNW#Ao$!Tu);AC7*SXw7 z`1m>r-%1F##O^^|HDpmH)P--JCBKI440M=nphNO^mV6UfE|5>AbokythdgUsBUs5s z;wV_(`J?u~zp#ZeyIbmD$k$Eu1^?Tp+DZqDn>dqC2M@u8@uJLBcZkKce{YG)Rte{W z`Zw#GHo!9nZ+_*OLFn>ve+ZyISg@M+rzyrr8TXIbMK^QHYmgBvNV z4#~6m___&S*v}i`TRDlvO?!^dKco`A&|uwPb3Dl6W<76-%T@{JGbz4f4EW~$V5x(l zzD|m7PXoT`*?hQZlz-S+7QCf4$$j{AklomyfuH;$ducZ2 zKA#R=q65Td`RyA#PJP6fUYhCPUWn}haNp0rZ;U!03JTsQ<{`K+UhJy(-msWRQiaU; zdMVto>&||z@|DmXSl~OYk{PbF57&nck+FAw5L9txL0lhcHyAHIKls2F71wh^jIWQZ zBUVJXfl>aC(LqLkF()$}0(W71fPS2u>pvGWASq~u>!;f7?#XqYP<8ML>Z=f3h|iiY z>zu3Nx&(1^cSY6-p1oXWfQsu8#8oJJc;?zF1W4mR39Ry|4P0 z8#`6LQX{eT5}EKVfrx&*_9ogdEGDCuQc&-2SI~Y#q`!ebyZYJek=CDF zTf$5S=>Yz`iKuw3(n(`fzA`zlMbYQXaBU4D_E2*46T01k9; z*4B)kGsAT~jQtMWhqv?4>a(g24nZB{bc_r0!uuu-M*A(rWb{&U3F6wy;C2K1{V{iM z5a9x>C1MyHQd9b|Ie>V3@Y z!9nVSzU_~t%u;b(g19+Ha6g8AQPF?(0>YKiOUWY`KRAhri?;+Co_~ef_Pl{ldJk#|tOW zw6mCuUP_9fz8=CC=CO6231tChJjsl2#v(jlml2rz^KWLTe1n2~)2Q*{@m8*!c(_7Y zGrk_;*I~Tay?qx7BXCLO7S`SBeavt(iT##B0QS2ool$j=4vFDzbsMtdfpe)!Fd}!{KA(zcV+OL|d`Kbo z0Q!FRP+*9P>p{QMV2eQ!GaUl|MB=k4hkD*01C*wS8Llz`>sS|+J~VY33>&hhqD96G z*YN?yt%d5RjjhpFh4FZX3VpvY^=+&J*qQCpAeaYeQo3Tf-=Zn6W-`#k4cZ3+)DN%d z_czsYW=As}vMWXA^UoOU``f*I>yxR0$T4eGuddAInInf=P1h@IVMz}LB)k8d)C+sObomlM}Xa8Z~h zebAvTTG!Af#|l2aeu7&K!F4?JuI@gNv>ZO%Y|`JL?fU2J-L7Se=FN5Z>?}y}eZYWk z;-{ATEi9FAzJO{sTZ1GB|1>F`6F1$4{UofPU9E9sfd&+15+?BRwT+6{ZldjMZYcv?g%ej!!u|mQos?~>QnYNXb7tebi{e|xfN%0zJ{<~D zBKA<;0N2ln>mvRP=2;b|Ki7`^$KXG#Q8hs&JMWUU_PH1 zoc^9Rzmio0rjgi8guH@wJs`I#XCS6XHY20DYJHSklzV_`ycL`_H$Df zB7LhhU$ze96$;m3fScv#>lYGvjy<$nyHCFv%D#8OHa@;G!G->|dB?>!SzPyaK3v}- zJb#0A`$_iCHlTGF8NHMgavoksOJ?m>&?4f06E5z%UN0Jm!8J2nH}MY;_f2k{AT>0o z8|{=CZvJNMe<7w^aJuOT79+>OXAc?n$hyXWg)6>eaUD(geiz2E0_zKLYNsnppHvtn$4@wK}LTuCo{f2e?*5Nm*=7Tu8PS3 z>JeP8&ZEB9+}_}Ow|36&Z~6&e&^PnVJ9+@uc#@e8PGY~%FBU)DqkEy96&LFlZt8n= z_Ub!y`%Vtdd7(mdfQ^7U_t&ha@(l{Mo0r_L0qeiXCkCVSNut={nERXI{Md~mNbr%c zewK1?9|$8fDdgvy#|9{S$VqQLK;DYA zz4n&+ez6|S>{nWZalwA&Pqto%L#&uk&I~u3j6*e0nN2rr0Ix|QCmyFXC#j4XuKyLx z7y5Cz>|?t1U;A0UannY0fN^MhFr-`OqNo|ZG~=s~egQhXvGIi$RmD7l_8=3!(2vjj z@o!s0Qc+Ht@W>|A)pdbdb?s%*hm&vIm#Fmd+j$d-Bqzz{hpcsRxe!vixXyilhFDp*ct5WjX?Kn$VH@Yko2os2=|A!Yc{DZ5fs!R zkGdc6#D-_CskqW8F@2>Vu73yO`}E@HA?}mWU(Cr&-+a<;u%6MpSpA9UAjb@f3Yy^- zJc;8;SXX|mbcKlj9VNDZ?4b@Dg&A5W5wN!ud)K$8Tj>{jn_<3aUFuVF2War zmaX@kM0OTmGUF@l#`;!9a0~w^Gh5~B66EVdD;dz=N}<31UVjDMw-R46<10Uc`NDm= z{oXpLTPLu37c<;sf(tqvcW*tQ>fjU9A&uxz8sRS3`h8C;e(ZHKzS(J!d6w(%NoW+s zC4+)|Gl)GvKQ2?T!G|iYd_>IecnL17pVe(KsL1xEC2F0vdI9ufCUHKe!9hMRtVeym zzkimhgG*3{Y^uLqZr$?(1TQm;qh`(Q!A0y0#lHk2E%&kBdVZiefwi*!DB3L{z5*!0gCS$ z1HKst`S^M$zW*8U&DqDt*Yy>)Ul=!Ec<{!O!hTH7v%0W(T|<)se#*`kE#3MMThG4V zlCNRAWm0yw_Unc)d}>m_8dpyjuLS<|4`{hxqoTm5!15 zMdMmCzGQI|4_opzv@?a+FI=3p{PYtnZjLoBTP2*g6CEHhYi_{T9^~U2p!m)+;2W^U zHRPK|^o6nLO@n@s6trwNLw&O;J6mL6XBpPGhI|WlVtW8PyJ%o%xz@ObeEozk>@)nF z{Lw7-&HYC$+l{Rf&WDJ;!1sy)U&j$XeRC+j>katkaN;Ty?jskz(fPBS<9s?Kbc*!j zgtg9ttXR2!S&o}*m2lpFCm!FRQSWX4ibEaWTqE##!%EaiG`<8-Ay4A7UkCZ! z-)abV|KWA8AD~ITVwSju_8^mXE055cWE?>2M%t86!V*_of#f{palZl`rVZ@qVGAYM zEO8C_+9|&6R}4h!>)KSn%a_<0tXEg8a!w11a+$sO=5JnN53sIW{;wlzS>Vi4mO8Li z!ud2}55V_!1HQqh`S?1BzQDJ#0bfTMOTLEfmP^Kq5(xLYjQ%l6E^CR))WF#+(r(b_ zZf~#bWDB__TaKG-m2h5p6!&8o=W{N+=3@(`RpI07ONgxRWb_O!W^t3B;PYo04KZKP zcg3=z`~F)#**68;cCA>p)_Jpep@;A-g&=kmeAI3E;T z|MjCt1Z)h}cV@rdX{3rP9gR7DF#ddHu|0(6Lt~Z&*h2QF`0OD-_*O)K^QZRwNaZUF z@=YXsL5qPc^!Dp^@$r=oVSRz`^0Sp|s(f97eC-tOC#StPRa}oCu2LJfJJ{Lp8}52a z#q|l|ItgDGkE`GHD2OZ1!F*wT=g8nckz2z(NWMet{xi>jNPp|_&~4~0SZ&H{ z#pfqolnx78M|6;miS;)H1$Sul+INvh^}3|M0tSHQH6zro`5< z*#pbhPw6n^t+hHGl5+TT2vE3BJlO{Al4z5Y6E{fw1L*t1yeFnr0;TQ7)0Y3Og@*XzDtBbU9NRXVoug0%-brNd`y z_vv&)|ueDPdJ?cBa#T;+uFqD@0?$Yda@y zfWq~@xgL%4+LXqL8zi_e&X4QyRE`!E{U*k&*!l%qPd*><59|LKQkT8%yT-Q;BL^`q z_=giUugz5B2Uncq8_Oq^dY;0bifdq4)}-9mV;e6tl~5)~zRv)@r|RK_+tu+{iG#1q zf}*@!2ge_v!<6k$2c&lm3Pm}k`Ukd%>uanp%)5Ubb@MKjuY6oA-f;&bxD`WV3RGN& zC@#7G0sMNeH(x`1<4a~b_<|9>*ON9rqS~29kgq~;Vg9ykd-=log-;OIPx>45;~n?Z z?u`zbl=hExf0H#ea3+(CL(m}>9D8cN^r}IjD5uQymC9jzg7M;7$-1MXKp0*!!wsSl z0{R-*@1hHr(W*gw$qd&!8{@(}>r#zdh3)3JAl5Hj*?5bnVvGU^xFl+XFSMGu90 z$N)Fvk`v=xJ`#|@~gPg2{C;YN{66<4$=-j z9fB0@aRXc*C$8-X)))MGhgVkgRCRC&>L3llI>LS1r>lLXi%Sv%d^*S!->#Kk_#458 zQ*g^`LeJ;&lIIBAj?gyNdUGRzEj*-i@>Q-!_G6!EFuaMXuSZbdY{Iu1V%VqpOOF>4 zB`<=Ud=rmizJS};05@$XU%UC6VmpKR#Y5d&oMHJ|<<0!0o#NZyfUhl=FOG5$I|IL7 zqmpwlYBw3ZloY{sOCJ`|H{F1*{5zk%cH+-~Z}#RV{!sY_1^K2DePO?4?Vm?={ld-3 z*F|uvAlw$8b@&$@G|Bb{pAOP8Y-gZD-#))IQgx6|iuv^{s@?utlY2}<7G*Ma$2Nas z>v@Qs!8lYuqv~muuS1ZpyD|Q}fIF{VIq1&Xw2Mz)AK?q}Z2-Z0>zvCtL3**Iq4ZD2CB852h4WgApHJ^JfmC1K8Q<+OM8d`8ovoDx@C+?z`Xh{*mSy%WJcK;URt!^c{cj@h@4dygWX8 za8WuODpALy>fjO7!F3(m1L&~tqoL2TeEl`~;vF}IyWarUS&I)htvil)z)#+L^xMs< z4od9zpRpe?ocED-104<;@Xh7q>n40*UwTK4chD@nn2cVcAJY=+Z+?pJ5d*%CJNWcX zIEM8FA91zP_4F`T>R*r(*G=pf2B4-VM?9|T;1JZou^a1%7Br-BO`jW0Q4POLxRXx@ z55a}`W{dvw11zqG6W2-NYVZ$rN3ST1Cq05XC=}nn`sw)=aPm#;f$ah8_ua%x6V!I| z3Gxk6d@mXB&8p4UZh<_^7v=#eM=vZ?`6_YpW%orCvfc;n_Ue5%b@t%sVtJn!s;N(o zJ=lK1&I$~4$gIPsgF^fR#1BuVyqv_ob4Fc0+#u=4fZKENhP|r3j?-fPOs4!!*OAlE zJV2XrIr(}Xjrg+}P18|$QcMP9mmuF{if zfUmtCAK!Ee_cjCEY))J|(E-L|Deu$;qyxN?6hR$4gfIBB_pZ&-&12>Id^))HVmqsW zaNk`Fy z?9{eUhcjY26W{!}fLaGXwYVbpIylQW zi_-VSlpXhJ$fAsGb!>cDT<39YXQ1yJZ+z9A#r1RIdI&D)TWRgnLs;BQPFyJ~!uR#- zM}f9B{miF>pYVl!vb$2#kl)cJCns(mX}8h{uG7Y)DOyytuFQ!morvgA`go7oEUu3e zS0=dNf1lYkdmD=@WyjXvJPVtI{g+zbMZPx!@w&fkrM~KU^;pm;ws@VjUpL_kcJ}n) z`MQ0E#5H{OU~i1|1^+w!{OZ;!Pxa{F#PyK*Cd|7(eK~c9il-jEG2;3gYV}np9a>$M z$E$eiF(*b`R^K4O1-?y2)SIf}smCBEuI(h&7y8>C`7w`*rydj5^0k|T;DY`BG`$0w z4{4K~6W2xI_HMlSiWU|9mJ}zhm)HZ$-!{!2g+?W9^2CU%t%a7ep2Yf=L>JmBCD_ZB zd38ONwFf`Z0r;-Ut~Q?q^3I9PKd`t#${t1@J)yhbz92>&SX|pFtONLmDZxcL`;`?w zJM-_0tiuc&q5pnBkXHu^w^4_Wo@4b*o6D!KgXjPQX7IylO<3I27BBVX1Y`~(;LS<ppR(x?Z9P-q#i&aUaAFng0%Ntj=SDg18>S7wl}<*~D`yu5?jse(dRp>jUoW-Ob<- zS5o~iTPZ-|DCozogT-gF*RAqqxCLaqD2)K7y&Gtx>JTgu`+az_!JGTY_eH=S9CgpU zDZOM+D9S0|D;r#w7hwN;JG!=_|6>y+mqDQ@r_6A@|Tv=Kjb!?QO4CxvBCEejIzh zkPY59K=_tH*G_-*Pf}6w4I+;KIuu8Lbvb`0Q$}^!{RQ&{*^p2Lxu~Q@y#dw0{qT_#tpWp{X+UA_I_c+#C96% z3j;;_bz2vyxSlxtgAr~PT3Cm6gBgH-?af<8Wul!k)7Mrl;vcTJ>%LOz91TT(%}n2f zqzK=|Mab7reQ&YrGt*v>D(N{zJ7dPzM)-pNeUo#&Pd0et5aoAvPtL7hRD5&E^Q*yr zUrdVFuP+WeGvb>^`SpM9f2?WP;0!*O*(o!9WvXBN6z&&VgyeO6ajKo*qJdZ%aeR14 zi)x)S>lZTl-YxXwp~L&^mcFsZqDz?RV5j_g)%=t=M|tc`WcrQBYX{*A^NXR4mHN^s zgF;bGnelZIeF66)sUs{y#FfnSwS9s81B@3nx}f{d9C5*ts7qhRL-<0R`b2Jr(fSh6 z&zSL*316_Y)u}Zfllnx*VXvC$>!bQbgFM?mY(1;I8Q%ozcjc}J`j3?2RKg5b%EjYj zO+>7z{f;bYj1@!ebu%3tq+gUp#eaIZZ$E7<>zo;`i^Bb8p1jTe zu{2&=&njoeS2~0H1=#QDS`Rg`!eOtQ;vR_1vzj!Cj2DXFc;O;CBqAc2fp&AHOqNmf zycu5`(E5$oX(&o+hrW5;xb(rsdt=>nSZ_07ZV`c4Ig>xao7yR$Ta~Iu|CK?oqa>|Ua zhvK_-)guT2m-I9jTb~S3^TP38o<1jeqmVPW1T18O^XX)L67Fkz`AX%U(job?Pm10*%a=Tr@k$&;yOZN>l%Iv_w`Dpd@8O>5I68v#Glm~(Fwvo zO-dik_q`5<;(H-C(l0!5@Rc=8aK?Q&5}#G+bN7$Z6oW!hPMO(R=3SBJy}nxY$Y+vn zhcgN&x@2Z&K}v^ju5>}eJuc}Hw6lB)H*sP1OchrV)Hg`Q)#V5N@gLkL6i+hKH~1p9 zf3%S${WLh?w1nmb@gy@`iR}A>pUl6lcU9@Dcu=uwvOyJv*co()3YFUommV-E6y=l| z-!v-jyK#J53OsK)o@9obPu7hfo-Al^C`IZL530EiA)*85JNwsxUxXjv5eKvxUwaVu zW5BIbcH3Ry2O<{%u7{d;r;Ya1l%9_R6csh&n@h$a*q5&U$HO=)vwFP9Wc zm!6G|!(KJR%|sV~FU;SroI>mNajy88;krmahIwq~y~}S&uu&98GQ&-$a3_`e>6X-2 z3+ioVegA{3trE^9bi_Kq`udKNCof2^7!-=6`j5jg+A+q_nZV&r#M^3Fm^r2=2RMuC8H!RLz;dr>}?T5Z3o_!;3uY_C|c| zM8FKL`0^ z-vaExD7kNoJg<1%TfN5`m5FxF%+9jV1?b1%AGW67>yp|;L(yL|<7@u`UdQ*1uuCH87@xuFGx6RQojINpLOZY>Yn3zO>pl|c7s{6H*%Am6M>50BrgUia+|n)*4ES** zGh83K0QL*|b}F-}OLzga2yp#`FZi93(-&Wo(7b?737qYgLvUf-{HhbOU)?uR=y%b- zHq#-S(xJlnJ)cNb^mU`1F~e0TJ8SyS&RbIZXejz?X1FpLH=*5X92}Ej{3|bdJoStj zZZ4(om7z%AMrsXwbaRfIcET6plDyOTx578_P|%)IeB+y+v>W(e=d{kHCAi@+j%22T zgUsI`jBJ^{yqfe{9H6ME8Lsz8#6Qd!_~@_FxAEgPFsS0Ea0f4Z;ezBgC=}(C8Q(l& z51{Y%lju3q1EYW#TmoFfWXJ6dpXJXQN8U6n6Xm2CUxnxZ?bfNw-AARDqktG(GQ&-# z`rGSoS6V6!FsK~ml$j2`?8vxzdUa*AoQO+$&`$$`U$#nSxLLy^>u0b3wGFo6G$}Ei zufGM!JQlcx9-4YadS3%;nK9$*J&XCmu=d{Cs~1_IeDny-XnG*r1hx+3lhM2i>Vf@s zT=V2sI7g?1L3}#olYRl?ThjQB#lvqv0q1f)uh`i)qQkWx#x0~E!!I*PzhTd-dC*r@ zGt|-DIWo?FJSAxwyRH!|$)|&B8pehFp=tlssUdwwy=e?D&G_1mVqBQMK2a%YgES%r zFsg_du7WOrJ;1oRV$bK_OUdLZIy2L5N27-}`S)0V-(S{N3Fpu&)>m~jd{KJA&WX({J zN`V;SYN~kQOMf1=Gr--rOdlcK0^v z_M*X+DZf*7JDObFt;Ka;w~R})71Z2KtS^jjRcfw!SUnxC%9k_QxeLTkx)LKWTu0g{LUZ>sHGie zA3LGLEN`uYt`0ikqsEJz%qEMZ*+!+z&mq3hrF1E;4Q@B^zyHhm6ZL9s%HZVdCw##k zq(2)CmA=>FTIJ02^^@N(1bzQB&^N@%H|WMXKs>qc+s9f+v#c0uubb%`r1YI>ps%+A zr#%q=3w-wvzoRqHzMl3I;9TG}tOML%?Hk!#w~A=5Xvx>m&g{i8F2sG``1C~ztZ|L# zN+D{TzpkVWlx7+hGd*c$XU;(p9cCElkae4-4uGhBem3ZZH!4eO4U3tcG}9qO`Lo#u z{Wzg7A72OI3nCqFw)IJAi77S13ub)t$b269o6;c8%>Y!#3|FDz_4OUw9hR0F(lR}1 zhU=#MWbq0ubmN6QhOb|s+qS}f2jY@aBU)^ga!jciUO?3i?Kh!q#Ggqmz}mDaGlkC{ z?DydNxnSS)^A_6|X;H0nX8O7)JNy3O)6=C@)>w22Gh7ele}i(xRJsnlwvFX$HxI@4 zER4rLvB=T$X6{Q5)No#1{n zDX%-9zHlFf4IzQP54PHWU8<*nwal358#s@3sE!Z{3eb;{F)8OGKE4XoZk-L<&G#8! zySa#+LA?I+*K2P{cQJ%5vPcKRc5_he_NYO-1s~k<9z!1$oenzjfW;qtIN_; zCh_TDJC6Gs=+NdwEI+fKtCSWqwWb7C8;N$4ms4m|C32~c9H6{$kFp= zc9u^0^*O7iPLk?G$6>FU>5xWrfVi)Hse7)m^)g)6I>>A#l$S}nK_~ZaYu!%TsV(Hc z%D0b`ORa;ykvzAn7FCiwd#vrOBwGpP9fWWAd!f_%{K6KowY0=F^k*(g-_8d5=Jc`F z*NCs1+%FeiM?Ci1ZkBJdHD9($IBzHM4&YW9_~65Ap~U@`IvC#4>L&UE?%r39>(&We z)_e{1O(*(7{3}29t!|u8?Z>BYKKVWltVAtpaHpTuA=8>KTP2*&OvU3o_{rZEH)+lm zN;+(+7cFxQ{xQV{tCo8p^AYHi36>5Fyd>=inQAWKE8$@FE|L}f=~$#xw3hid5JoxMjcXUpU^;IlIa(E}Tmya)* z@l7Ip!B6geY?)3fM?-7AMojEyu)bgq|NHyEb+(LSytO^Bbs%3rewP;JoB!*r{~c0$ zH$Ge^#W#C&*%15Q2_N#|I*7i&_ZtJg361#lbyIw&T-$Jz<(tjPH;v-!GvMoqfv?Vp z5V@pHk$zG4=^O{k*D7yjzaC15_sjG=$>OAD^0k|dJWm1I?Rx_qQX5;hn~@IEX6z?n zfnf66<>UNzY~kt(`!OXi(E-NINw+Qkm@SaZx$fzv{MoWaFN|by6;2%-#2(;&f<>;U z(d<6HWM&VUls{`WzD6$=H93i|-BPP#`vrUGHKBZW7S}3o#@G90#7{n-a{O-=$MXgs zUl$qQz#cAhj+-nO$OowYw(O;@nF9LoQeH{hFb#d?3p$nSV5dvFwC+$Wul z*zc>~A~J)}*A*`1ppXdCQt2Y`4tN|Jl3p z_$G??y^R8uGblm@gatXm9T2gK$npiHAWGzrDk?z*$|0tpSWzT$Sr8#8M^V9Wh?O(o zRZ$@vLPd^vVZ9*8RS_hDNCA=GyqTG1GP~PNW>bFuFrQC4oz3nu&pz|cJMYX+l8C}rL_gX*Z>HolE#c(&P% zjlXY&zXr-#L|<4Z*qJ)LD}PRCvY0<}F*+nA(EkQfaJyL$(c`e6AkL&`XC9&h#FM$c z-DtFnPI)n`YiQYno6%wMh{X9Fnb;rHopx@!lurCT*}96^ zZ-}wq4GCOV4l+7y`)|-)NCz1>drf}-q?Z{lMla4?2bgRs5F9T;#2%_5utw|u9K>S6 z|GpU3qqO{kbTks5%}k)aX~a*$bM#F&-37y3R7ziBY!6WvkV5j2NZj|(nc746bFyOC zho_~3%;=CeHgSH^L3AjKi2m=dZK{63^XJQY8B|Uw8q+dXsddJ8A zOyg0LW7wan)i11txZPm=ci{7h>lZnUJuK?eA;j}FD(mTx&-k;o6`xZ1Gq<1)@Vz)N z?}PbJ?ug5pY__JH?>GB$XUBR`+<1v2?l#3YLb{e>;4l%#uWbC0+0@q>O zOuu+(M&LiKdn)Oep1#(j5&xU2p+mtqV;!{W%@`ZOy+Z@n_qws)(ZcmI{bEYzfv_wU zSJKnLMsxuGFz&tmU3t)~*OuKFF^re;y;j4-&17EF+f@C~~=OXofZk;ecsSq6? z-nnCsI^I!wiP=LA(E;W|<&+t5eo6vIpISQjNq++!4m9tFX7}+WJ$p!J`bEy-$*MRi z6vKXSEhb*Z9=z)hp3pj{q+@z~Z8G-1pzp5Vws$HCL+d>~TxT}!$FL55r0fJ6od-y* z%soGLEW&)RLAd?)FB-1Jsib4TSIZtGvcCkzqKxZ%s@CO7!i4wqbg+`=u`s@+H8`(Y zhY`h<2`<>LeQk5a2#0@PkFWAO))#Q^KJk`noq)&T%X+vDf(uV@9(n%Ao&0r1Wj)+v z!}T$^Ro|_u z+Q+X8NZ!!H4KTP>#>{POgu}nDhwEhe+n8T3%KUXkWj*17gzq&7VCUkO(0X-zNe|ab z?5rGu`)N(@=JBEG`-dz$wqKaPxtAtxJ|7}F!2DwTqBE$L_>!IuZo(G=sKI{;^*60< zA!QR>Fx;;-MtS$&V(XI%S&st0^YF%LFUO~Xe!E#~;OD#$_er1bx+_t*GFs8GA~5j3 zdjqo)7N;r%7sMa%XYI*};_D>1FurZ8(r{YBa7nvCKVH0R%%nu&y2!W*e!asd`|BkN z*UPlq()G2QB?>q6N5mfbTJPALDBJ+qcLnFN@^99c7wUz_zxRM^<6yy;A6a3_%oaxDEkR+Mf88+`J5meV^gZ&=U5Buk$pB32YmZ6iwXbd z-H+erkJGZAzNuDx9r*Q*`^Mfz&!>4HPi!0tHpBCt6a=*5$elfD5Ar(A?I$Sci0uL5 zlGP_Z=}dXXn(OHhutq*lmgFk`Myz=BJU!gtHyF1LI`QFdkK^G)a* zH!LYo*@G8-7cRV~m-P7B$T$xj_^l-s&!Bdb(Z7;X*4#X{;9ATFaQ6)S@-d3*G>I#H zhxLW8XSi+N=c;iiv_nka^d8vGV4dLBt-H~D2rK3`$=CiA#s&Y-YMc6VmKnE+tsD8t z^G4`z!7*>3eu4Q0<9rTTG{13_-8hIptAcQ!=#dHCE-Lw!$Hte(brD<`hu-|L!}n33 zs9=3pY#q@}aA7*Dw5NB?I~s@NNBbi*z0*^^Vwd;IH#Cd~=fq{Kvm< zRMz7gXoC4dgWY{|msBGh{(Xv@_EWSygb3gA=zM;MZc5!%IrR zudXPEmvRGsO+h)l_@t+=(kT-6bv~4_t(b2dzvs@^1!WJT!<5RNXDF^R9k*L*ygJM+ zT^+m(-}LfL4pP2B(r$$Y`+`*Mwybpd`We25g4TYNuk<(8H+i|(xEW+{f4pYqeu^s- z+<*bDN{4NwtV3mdzu+HQmVN79%2z=PI*I?4 z*O%OG2p2*yRSMmVaUtHRv2E8Q{0T0D-z`zKTiJ=FI=&T=bpm+ydEJXAF7bSg$~@oS ztCud{>>d$)+az7=#PdtlZ#ohb8?xs@7AT`^EN0SxJ9`xO&*df8XZm`ZpT(H~x}vImqz!zg4uFKPhXI z7_M{@>kE8)REJ+T#fr%$=R=_;7#Gmc&sN9X-}Kte&hUMFR?|h4uVRv~gTb{wHG43{ zb(+L=Gq{%FExx0;67j!$JMv{c9rA9%@jC4PeayQOjTiV#xu&^zC&cibIPCReT(3zT zRZ?w9N@*$f zIbk=$_thV&cBOn}ll{$4#$$Nyv?_t0W0g*0dw}@t;FwAeP`*Jj9;3r0COta~ka++E zZ+riIIG+dc_7aO9WWpD4%hhbY3h|ZEzmnIazPV(-9Qd;vs|8-6I{1g;xESgvDe37T zox#_`^ML6yueqD@4VuK232t44oB!VP@Z4WUub7h_-vVN15bsP&;C>i|;d^*?5n8S# z42GH0x2O${JL)06?;Z3aubCJfLjS}5p#}nM{D~9oUdDW#CdW6I9rrir$Gf)uo3OY< zA^oBf!d=np>YgYIr{K$@)=V5vOZqu!4b=$_f(w4V`uC^Nsx8)6uAONL*F|u_@6-uA zh^#I#?dBl!*vbfSLfOY>({__==He1B;S0FiW>$voETdPnV)PDvE5Ozadk?xc6wnlQgEAq%h~Oz6iKkDMKtD8BC2*nh)#+_vIF$B{+C z&=GUevj>^*t%8uIkF1NL2}zC_6rHGt>v$gP0DkhqS$7MR$>yN_H) zbpZbsOVYzlxfk<=b*^4xZbIy%Q^+M2M|lZf(0ANj6?;>@Xkd;h>G5?ic9t9*0jJ3^ z0g{vSaNX#W9ALk|H+1aKig+;LTs>ST;S2ZOv*zMo6NOvEe2!|q#^+G{1!C(Z%JbMy zRzpPJ)WEe1{w|`6!F^i;*Z;8CdQ>*^`K-a&=jQVI27VFKAwc+|jwbEAboN0W*SSv& z*Z&H(Gq4AL#V-nZT%)p{ok=g?c7uIwa-H`V@Hh_9@6BiQt*3z-62$d0{-IZun>V2z z6rLl?9&_<}9>e!04ZhN#lGlIr^bIh$jWuxdV)#COzD=NCLN{&x3ky}sqOD$EemA&u~@iU2=5{Z4HjH+zg2Unju@f9Cz{qRO8Y3>D*>#o#W| zz|A-;<|nO7v7dx^=bN{0Z&N(N&NAm8tS{nr10CMg;OiMDrf)jIg?`~r&v+GOQ7LV_ z7_Q%s@An3T*7o))C|cvvOJca5C$J6>^Q4SBhQc1~`4p4-<`R2=ap*#`G=*a;<&F@u zGiTGt{vGMZNys{)lmDogo#iq*Z1X?Yo9f^+se_-<;n53sz81|^lAMKNd<$A&9pH1f ze|+5=%`b4fx%-;y7X^eb;7%_;?+nk^|D;&Eg$ORJb4~bd!&V+QIa|dxy3V3? z&-jw=INuoSSP8*-I;Cuk50$ot`l{sLaeo7ScURf~)2*mfFj7okWiR%Vu)g#C@%O)o z0!0PIC59^#zR+%euHCSO#|;YN1{r<-wWe&~aYGZu_Dg}qqr=m0sdaF4E}5?$u4`RHhY1(d zIur?hzg(z2#)XX!ZGPE-hGoLwHFN$fmFaK8t?K@kl_sWxhu8!3x1lH1{Vmu{3^(`# zzTY|scW0ZcK1W$plJ612l?o!bo0jg~9tDaD8TX0dy4|?HLA<$cJIHDJ;>-^$!XFa6h?>UJ=eYkm~1L^80r9&R4Kb1wqJPO(m}O)CP_Jh^8jgB zq`#dx&@!E`*m1}(e$eFWVfc2|;F~Qt53mxx&@XCh{GM7q`r&Qxqk0MTdQHALgs%l% z_>+cn${HqSXO58(ecSw|);IZxp}v~8qEyBG4b~BB=Jgw)c~S`n^>pwu?dH~Kw~XOp zI>?NjrE2KlHr7G2-EtYeQ#AOx1?K^_!I62(pjNl#7LOONn;S3ejQu{SVZS-X^9xNK ze2o3p03+s-OE9i>yCU}6EYK5_fRvNgI?-~;kKzoB_nd`Yig z_!&DJht^j4U>&I z&{xfXw(y|v_gu?6#eB(edY)dcr*A&d_iA+E%q1IC`w8*|<8=qIGw_r59-h{g=att{ zY&;GSzVMK+|E@!S^0@ZNV)l?n{0^*Ze0*K)8>zltllI_bbm*<2L+%B`eyr(t3K$&* zYUp5nSxg5P!}o_X>UK-pg!?(KJ1y(kS&-p-_*ZqiWn~-k)zqPo;KGFa&8kNxQyw%= z7mQO=hD74u?MwdKOzlCM9rHM($v4FCU7*3Y@D)QH=&eQNp>HGp?EPJ9RPkiUc)y$` z-y*^n=5H^((GHetqmu1aF}{IG5q)isom)@!l}+j^-HOLe;QO)$-{hHMd~F>uU+}?? z_kPqLB?2lGJRs)Jk_lh1-$feskmC{K>p?5Yz!m)ZkKMjj`Sr8|hJ4YL>f|Q=0miov zC#%Od&oyH4gZF!^FFYrEI(a`@pG=a`zmnhN_+};gf)4M$s~+EMuZijFCgVJeZ=alh zMK!+pD;Vma+22wKUl`xE|8`h4z9r8VY-e zL?IZP{kHpoZ z{+C%uabwLsgfDdRS`U7nL)*=5a=)^V;DX;-IscV?D3j4E=A_5hPjF#c7wpdwrCQvy7-bFuD2=Pk6RbPWsm;tr}$7y;7fEUj{w*78U*lh zB|W}bts~>x)#I;k5f>;rSr1qK2u@$>(=e4@Dg_m?;35Qh{*~Nhe?Rn_Kgcg0>pDN}z`MC}c!G(VOLS}<56gOy+ zubtVie5m}~@f6qjPt1N@Q>HY6TMfP2XU3hYDX!Nft`*%m_+J<=ZmxK4I$wFd;O{^? zPDaMfI}T5sMfv(o@(qx71HW@!*0*0%+@ML^X_9Xi<9AL^O?e%`%h7~OF41=5&+-slSf^d)OAk`M z!Qtlmn}hTV@M+hV8~858RZQaAiM}wtJ@EUT4vOnEiJMK<*FlHsj}@unk`%$;XUJv7 zA@6I4(KH#iggbV=&{b6_z}T;~Pvai^3BfsH^EaguZg+@N7v4Bf_3?=0xrVqrm2g?U zFEYOE>0kXN{-m@%V*Rae)~t#8`!T$IV^6?4KYG){j5k8kjxW!dCfXd5Ly(`k~gn;GAB z%}ed8QFDoh^!WOj{`Pb5@i8TWXuPS18zSun^MKAP3*M(Xcune%j1&bQ3GvRdF20vF zD3y3fkFTHD1H|hqr$4URe^w$WdQ%TKo3tBpWK!qhk6bD~6Md8j?!zeQ;acCpI)J`O z1L_Vf#+_>pH$Zd%C%X6Aj~5&9#3l_s;4g$_hT>Gd}PKyWH9mM;8p(&r~1mT#)r%6pb#Cvejf;IU%=~-@ndXp z36JYx#}(l*5mNKVwl%_a5=ammmR?`xJQTpz)O3Ad|Gm1Bv*^)q~j zNWo5`xO_kM5`CdxJX>o)Lmt=mYi$03zb>EAA-Jq^!gO#G`-OOY)tkxXsr~v*+HZi- zcjl!x@8s{ts7&pQ*Vo64L-*}@#>M00Zxfqu<}>@Nn^yP(ru9+DVZ2`>>U>&olYP*z zKwx`q(Vz4<%{{%v*10msetYnf?eafY?XS)f-3LPSg?VAi{C*b7GuE888-Ko^(P47s znX3Ml(^pJ~0%B({zqqU6N;JQSFX{1hGy1;XWrZqEO*P(MqDiEH_;oO_>p$%_Q}d(} z4(johe#GM=*x8bU6+h=8as~I<1c|;dzsO&*K-F%1J$zY@Zw{mH+8dgn_$)dp1%~_D zqAwt&P%`fS^-y_Yk4mcfaq7=vxDICi)@RLx|EQmI=9r61d_;#Di0}PBeEvFrQ||Jy z`7_>6hL~}_`>_IW6H&<_=qGc?@A*I+HLJt^uc!`glR9L-gyX*I2zODrnJPc&s~DRO zQ8x*NGPr%fpLKqG;StK$8RtBJ#|<8g^tZ?69#D<*c?$%`d8S{uc3%9JuQwpL-zZ4t z0bmHB!7qP^bdb@%=m)sX*{@VF^4x!7XzKf6Oy*DOF|qzuMEJrw?dmR(?+taEZ8t{W zS&fzrWT=M!wayi5H|sxukz8GsecHX zY&Yw%$ofO?zLn?lI=J2!Yd3{yw`INuk&z|IfbBM^L)L@{-#WYQ9|o9g@_iu2*Gc$7 zfBUCN)p3-s-y~n>VQgo$5bm}zA5LPqhX4OijIWFEg?a2xZ{3Q*)g&4HD+Occ3rl3G zWFz(f@o%4{Pb2>joxFm4oy1Rq4qLBR>)?7#EPn7X?bd%yZ=^5wXY#q2$4yNg6h?<$ zAErk|nq2G?r6Vum6^o8+aPF{u2m?->LbB5nmawgC_arGr#Nk;?@1e7V9uSHapX6Hy3F)h#w|?Ur#mf_I)DO zZeB*;Esv}9wXHYA)wHt^883kEONZ5bL&mt!9I6yx{LZ&27t+uPvg)J~4j_FsQ_83K zKI@}*zqqRmnh!;%4Dx>T(MU-TH%RzaL8neyTILg!$&ss!|3kQ%`ua(`r67pTZ{3#4 zBPD-k*lzqKxO@k;Q+Q5R@6Enw-99>HJs^hbJ%VweAAk4Hb)%zE(LR1rzGX2ki1fdS zNB-e)jmmoM=A4XiAx`Z)KNZab64P$kOh0}t>-JlCe*VwJ^erUoQE)%7CKYd@I`Hcy z!Hf7gI>bBA9Qiee$CX=(#SeC}Ujw+_+y2`Zd0eA1;;Y#&yo|n{Y_-114l#X0L|@>W z`p-8ad^K+=gYW^r^Y4^qEBTXbC&cDMsYG9R?)2ucj;(oIqq3g9QYE~u0e)xfuj=1T z4SXf0uR?GkP7N+u6y*8YPa5i=X%F&5Ja2)xdgT8GLKc;5yT$lgiQj>FOPMFm#_~u$ zs$SaPq7I^hlhI+{`)VBu{xZ~ohYXi}Xhs1fVIEs9C3BtTNhKWAvxhv=-$2+Az0~@q z2gLN18NdGfvy%puKuz;4J$)aDN{LEi2 z8~?7oru_zpzCiT8%6}f^ah>0Y>1$`~ciV)Iz>MQcdOA4wVmkxC&;B<>wGSlgteE{O z4BtaFo`J79iYw{y^Vld+$i^wmmlTu3X&IJpPmjO^1Gfe&R_RnSDDUR3HvAOZGY58aTSxep;~zT9DLfLwoO}7TyH~je1n8nO@y1#<<&kEH`v4+Zs1PL z_d0}Yf4==Pge#+eCFurpxXJ-+XW$>^{<;x)dE62~ll#O98NTgUzRk_?&8UrafPOJ6 zl)I4Xpj0r2n@@0I92$S{Hy72xY0@5?%s5oz;r+sXhmWhR&9I+@`0SUS8Ld$km4aKv zo)2Z;hjGgww9KDh`8^6WhJs!{E+YC~k1(1I3~i?RdQG;Q{VcX$=*P2~?JHiFlggU2 z2PeUWao+aIsX3IdbP><%jHJ-h!CMFO1sz_>nD#Wq4fZ#On?mdX3~cae_`Reg8T~8C zCizMqV|##gxs88q{g(1oOyXJzE{qp>-GA*zah)b{gQUO0I>855-~SQH;!1k$<|F+W z_%=Mz=nu-*Ym#q(;KKO!+b$PcPbL1>ByNcDJ0sHqXg>_bmH#tmXHq$QJ;Y~M?VZt^ z;wmO_T{mKX1^unVp%xB`8#L)3LX3Y1HLo*`;yO+8wWdVI&GkdRDdsEnHK(sk`UT9h z?)rTRS~tS&<~7OJi8?U&NEk0Vta}615?|8m7j|L~!1wzxImoRM`!&f|A-K>lo|u%} zjp9m|%<1c3`1*FwXh(5nlekU>x9+WDkT=FUC?;{;MUnC1h4kAuQe3A=TsyHd(0Ad^ z1@PQ7Y!F_PxIw}fY;DuNmI$8MgGpTLxrh!m{TGp6$GDPYZk*4XhH-)KmuGtwk3+Ia zTo17aSO@=RNL{opN9@5Qu9va1S6a?`gyOnQ#_K6}M|8-%+p!~T49uU@U&ZF#Uea!` zzhp@6DHKl1 zclq~?%6hl~Vh_l@OG6smy^HD)G^s<7;KHKP*HsUqbr`}R$y|R6lHU`C{As%nw`J2}}y(7=JXp7+fk7uhFb(}ABK=aYB`=0mqWaRJSTqEmKzF&&EPM)V!K=3|xp7R?va!TNnf-@g}q zH9VRv`VEgIhW=O6&J@&AH169xvR54*w`i#$E`Le5TtLPPu!r*+e3gg9zV9`S;hV3) z*ZZy*Unv>)V~A5P%ze6$`Ul0NKTBu62X2PO_rN8;C&pJs5hQK5eeFCp%GYUf4@@g?16v7wgLw8mAWeer2#Lky* zl5p8e>`SnqrDhxtX*U+z4EGMUFNsf>E3 zroL{X@73tyAUZEZprzv>A>Uq7~G!@ZGz>EsAMtdioYJesap&|Dxx- z(JB8_YX8{zpM?1O%6ct%GW_xZ_j&5M|WdVVK3GBUn>rlEskG1P&nCGxL}8Q*-p zn}s6p#P%QM%f}_s{)nHHp8H<|9xd%lv3_hVisXM#J?~^S(x}5vtNWU0uTc@%!z8=1;H@*dkpM>?_Dg~=&^4Ap!@=arO_(4O5 zf&qs5YWnp8hVS(ne6z0>(>L%=#2zNqI`R_r>)toat!sFgcFS0?Po&-WCJC1V#6Q3~ zOxvxk6wQ-LIH=bzq^t1w1`em)-#wsv#Fg}L3kl!r5Zc#QRXraUC^}gWH+doUXEo3{ zKiyzMVGlX;Pjl_&C;QjI?@Ya~>gS2#8z8t~+_SfLS3Sousz*VVeA9>GegXY$r#!cKKcck2oW5Cg@VXq# zIa6nqxeaA9dc~ad?AJrqx$7gO9%-wK?ZJt@$^_~%N_x1;d-!_TSG=}LTjY1}nND(C z6u00}tS{_)9rEjzQ#_92J+bvDISK0vabL##pAYf4+5d>G!=y5}kGyl{eje8@_`Fa$ z5$VU@cG`53$CU&>_vIjbLEk@j&A*q&bqL}H-p1_)`abv5l!eqDf+x(`S>b7n3+vUV zpPqp}=M$Y$n~TLIX*Xbf%OSYKAJs&&x%iS^zsT;2?F<%_zr62NG@VV7(Z7j^ z8G<@E86A985~qWU@CAFg-*;j=&o@tyubt=%I#@DqznS_ScP(@M%~uEet?~%BZq{CC zzNqAGCFXbBL|?Gqan+y9E{{Z&8 zddsx6)IS8@GZ&WxERlG!^27r#^8B)r#nx$qLqY}^bHzThBhY%N6A9ADDoD_w>4g*bKF*d=XvRIi}E*2l1)1i!xPg}-b(u2ET! zuaCq#(2uWn!Kz7oNe|a!$9&NOjP%x<8x!_iI`9U@g?RF>FFx-PA6wds)K}#YzGcx{ zpWis~NTjXtxO;HSNyh8kP0*%_V$cp7q<~Et(tQ z@bBy4%ETU^zvVg`tfuWIlXX@ehcD~l+6gX*-|pIxv-#_c%6hmyMu+{=?nZHHd`S=2 z&9vLn-^bk@A1YN%eN_?pToTOZo6H~3pFbmGwAeaK9?=2(S@l~B6Xwsdi4I_AGv57T z5YN}Btf#M!_y-t|*ByN62dbE2(m(hadpKi5g*cNQUxl&X#}{$-^nL@!9P6J zeU6XE&8aSC4<4r7?%3R7D35DY*3-c`68p0X2;kMPzxdP$hksuW*Fp3J+&kh>Q2a3t?y`F#2nP)>m)irTs>#a)|JKm z!leIo5WXAqrrla@`b`y28iDKKItgE}2anRDw-FBiz872EAA|p$v_}0oKvCRW(vQm^fbQ+PA2Y(?-`C??K=^`R|Gn3@()}! zs-m6_*~ITy(G^LPYA@z5%>PO(o^+9Z0V3J!b$gA+H7e`rTgceMtKE-6coLO@e~a<; z6Z-`_8&RWAyC~2Y3VM9qj1I5en!ARFDiYks?;-vH=CPU6KS-E=@DRQ*9~zoB<_OQ% zsH|sa9x|T?JDcTOs+zZm;^vcfgScen+V46U;qdS4@%0fMV0>$9^G@KeGb-!h1{l7p z63DlJ!Cjp|+@k!*bG^FRW1i&i+qy@rzXch-YZAz}kiqqd;cEJITU#7Yf`2&C=VD!6 z2cMu0A;K5Ni^smXFJa@RkN5|;nP)aDBJ*xd9Rf^T^5TP!f}4m+1&ZPNuO_aY(YI~C z8{{ZZR0stO?MxFlMAqeC{P<7V(YY09=2bItJk-yi~JekYcgI}$o<}kaL>J9nMZNmvFm`Y)JPQ~ z&)@E@&v%?LGnS3noB&S=hv-mv3<(u>I>g>&!Bw$vHyOHX1!LT z0~pKIdE@$Oo>am?J-#x7``r01!t>+gdzwb=BeD}*7&kYyuK7QnTHumlKjtsNW#qx2 z&EWe>ayR~WN&6)Iqg02Y8n!6D3gHWm?9SmoALS9!IvV;j{*rLna|e#sVSZ8c`m$e9 zCWqgM@lP?|`HiFaW)b^^=OR<4u-gz{!Af$ z9mcl-@BOX%ULVKzvDpL9*Td-Wc%ce=0cw{9fN? zO~z4vq64fG_~(`XiLWmo=qwi@2ikZey@9wX}7aI|7p+HYgE>= zGnfI<_+c0Yf0aI=XHjS$|-F8?}dyU8YXC?Mk-EO5;Xv_;*SFt|GA`Gw{krZGB< z-y|MK@!%oC_geJE-O4-tDPP$nUnhx6K!-e^^DMDZ0?#KI(4l?>za+|a>nc;h@{p^Q;8BfyV>l%#v8;qNQO>cDM zF|GfK`5k#89&c?3Fm=eQXcr4+;5Dg377BF0KR~>5-OzO5`2~NUIUTS)z=oAUo#!8= z?ItyixgTo=Umhl|&iF_jSLenU|MGlg!VB!|nl8T$;NLeY>)C^cu?OdFwLKIH&a)K4 z7uFw+PR&Hs69xm#?cd2E<1zT1&ZqaI=NA|^c-|bYkLUnHQ2A|@s_}XTI*Y}V!DZNf zVctE~`gtG9*SXvrUwILp55YWk=M6(XqquI9xDJ8~`tGn=(K-y)*KZOx)EM6{#5)(#DsFWhO&pb$Y!Th3N@R(MVuTneaejLSv798aF)L^`LuW^Tu>G9%R@Ov-{$?sf& zPa9b2gKvuQ$Up9Lg6oJjtS{K_x|5f{ETU4{c`@9SKO%Ovcg~(EQJ|=hBZzBd_|}%H ztNNQ&aNnyJMW%GTs9FE7gpC(6;S1wt$E!DY;&qS&=NGwzFU+&3)RY~)V}3G#IizTkha>egWak84!c z<7+4V0t|QaKM()H<0u!!^tGWU3t+!6F`imh;No=23 zh~azbhIi2Cnxj+d4`R5=V(iz!eyz>dqIDx|>CP4A;*wwuj0^2{-#d?8q`1?Y zueT3wAHYprx~CE4>nF#fYf+c<{F#I33(py@e{tC({FVOlVtg~0cKi9r8P#*A`~ori zwN8rIL&4myRpXFN@OzVT7`_MB1ys0sKZ^17F}UT(@+3F77x9bgK089(GPe81E1zgdFc%bKzT_X~*6);3Fffbw;kj7ywky&Bdh z>+ML~_tU15^D0l-(M1)(gmNBSsC2H3tv&;CJW+*NWXyj@rEUH?<#J$mFC6^1x2PXFNF28 z>Q8h$60HJ?1rLb%$t?052e8}Q)|caPm7QYk<|TFtaq4L+v>x^kev|fVC+!CF`DT;6 z^C+%V2G1{Yf?_%-1Q*tKMmFm3B*m2pu2*oseLm^OpzmXsKHfud6@u#!#FcWfJ%F7J zd}V2|oq5grGr|knEzqvpT*}w!F=xLa;(x(E+_w=vzlrU^YqDPiiM|j&44+!5fa1Ez zeW1f7Cd@*8io7&3UTjRh5vfh=*Cby*@xQR%w`%!ozpHC5`G_807t=4QC+~Zl^7We3 z!OGa#m=B&GN^$)r?aV{?!o2(Sw>y5p-*v$bLBB(ApltWRB+f8kP0h%}(qW#?AhzccWU!nXAnCvjAgfUq3tTMI(Ov z`+9s+dte5Tc7MF5}9S~wW}_( z627pmalB@?sj3qU4(Ra>pcQrSub@MNfA@V$8TkJ;*WVn3Z!*GtrpkK;?9^}T@pY28 z8tlwF@7;6iD@#72hpP~O265`(UGtwU8AbiB9Fa$JI#DM<_18 zpEiy79k8<}@&}=H`{Q}1gB6$ypt^XfkkL4<0fegFQ@b z_eqfAx=r$RGIsXHwPOcUT)#uO6qkaVa6fhv9X!V4kS4Cej6)r6hVPNZxL$&rXN;@j3I_^_J%B&UEjMiu#SO;Z-!%EU zi4G7yq)c=a^Ys(H$vws52S4e@Fz@cLy=@(o#g(vX>PtKf-?m;!wVxnYkgxrJ5r6jL z!<80LeWjWv`vqfX<7ZbsroN++kLc-;M(hmix9v-b!e{j{faXgN@kD;Auj>o}UBlCb=L)70ZoKjY7 z9^fQ?rwSsvZ2gl8&$q~!FMmn6>}Gxk@8wP#+VUrP1o^rdKiU72_QQBwS6?xG3yHqa zkLNT|f6m=rPE6kr;~yGi`q3(Abn+YXjlO`CJdD1tYUmpf+{xSY{7GQOo(`)U_|lJgodzR3*V zQ1*Bqk86KYjBm=ah@U)s^7BuqpY+DQA5pX2ayw#uA%2+qO|RE^zP9pWI(V6WeD3Rm zn|a)Tpbk#*dy5c1?7OegFFbC(AYXT9JRa9TfXNF#LOS3Pz~3_FxI|OmBGNCwepl97 zHG}8tsUW7Wn~X!SZd5se`?-9i-6|m52S%=2&+}C>4eeJ`2MI;!5KDp%>ojzbD~ah~ zMLhv<;dxfYJx8~pEUu(C&dWs++@@m>UB`o_J|PzW2Fbh<;!hjFU;p1JKbA&T%)qyc#(!yUZCB;er<25-@O@-zpJjaIfl*@pEt&K;h<676+VCWgYpWur zuS~`_z`fzo#H~LBiT$S_+}#`J{Yv|VbicWNVYTAx!9NVkTMS`vRFX%F>1$>59igGG zQ}B22+{+_==Z24}4W~MIUp1$LgY;wQ7dO_jR*VuMhJv1-^pk!8`d&3%?I#Nabx3Ov znIB*C{(F(lin6${n$?WF~oh%CeC>+>LyVktG?LxVh0#MdDEhR%1@@(5F0mBnYeoDH_xk{ zqX)-`^<$ao$E~L}RryJ~;P13K89Q5EvsWcvUpdQ=FMmn69AxxuqM>gLuC&xL48AvzRSN=+pn{=7~ibP*gwE? z)AF01L*smsjQ*AUCg*Q2WWA8U@A3e#>sX|!9~En+%2 zn10bRH*xW=B;z;%0@N)x{HPi?J%arro$$R1;d;fsr&m+oG{*0IopiHm+>~w=(>KKQ zi&f=seVVt2q8G%*O-B)qt3ltLvo5sfaSNUmn;++raTDf4NeTSEOm{Bk3xUHcgBx$8 z{mpAKo^&w%VnEh|Z}2)~q>8nhwJNq>FqY9f{kMB=4bp_{j?dRAH(|DAEVA5W+Q*KUDNBYwT1M!OXle?C^zeqD?XH*4sS{iv7@e&Tna z-MZI0KAOKzqq3e3In48{?W0pv`!zfV#p3GxU}RlmK)njXjQH{I>)BZr<0s3s@uE*n zM5hd=n7&y|e0I;pH&oAKJ%WC+fEkB&Y3Q3gP>ipe@C85lMYpff=L>NQ%h%xNPK7^+ z`SpBTWc}=Qdy94y*In1#^DH;hZWT1zEmu&7Y-W6`KfQ}L+8WS$)X!q;QFg|!H_`A9 z(owN~;V1sA5+d5+Pzde+jZVS+V(n(DiQ5h4$1{5L9Tkl#N%Ao|ynyGM zQ$M-xEbSNm*!u-fC0q`Yc>wg|+CKH~IQj(l%jGcstiOgob5$0zhXSVE=Km#i;cqG} zUCf_ZuZ_%O8~1MgFOO?f)*IivjGz2I>?e(oqTdHxIr>nzr0mD`0PBbc+jX=^vouaB z;gB9*2l?K7h*KB*eeXgZ!dFGC-MmX9^TI`^j-%(iNityjXPb*BGkmxoUyHCB_FjnM zYI0}O%;AP^$JayL*XV(vkj0hs^v$^&`xSUF|6HFR))e#YZH}+h9$yds;hIjB5N>=) zkFS;BLa_OWT;nv4ntZL8J>(M|U|spp{sjl94zgJtkVk+q2-ZElp;~wHeBFY46~YTX z7y8_TZQPWv(|JBd&SYW_;2(lxzdwSq zsH9XE?ei{b`$`+ILmZLJZeO=Eo5KPR?7>nCI*HP%KU@BKpF* z+@IHNt;^%4HxuJ4-G}`z;P!fS^kE)X7Sz{8^o4==#eve(Jg&E;7+*KjZm#Lmn)A3B zt;BGXi4IpIz=dmfqWN)jDsYJ5S_v-nx5A&FP_6%F-7kjgAv#n7+*@9p6U`QV)^3hi zfAbPtSU1}I%=NW++(1pS`A`a@!;$&*7V)?l#(Xu`&wPwM3~b@Jo5#)VZK$s%uAksS ze75Dog8Pm9H)FqD1EKZ$ zuXC>`P*g~JM9i-%4BwBx|6~Y{TM(lT{OA1@qA%!h&z4`C@wl#rV*S{D29FnD4y$^`lZyIA~7s|})#N!&3_4vw!FX(XFhz@8UX>_um z7xTY%f(sibw_bb8iD*>x+3a*N9Tb8K4OVg5!W($p?1#i~om+6b)j@!sug*0np0|+W zd_8(!z z|1dvxzT0Le#SNOob&__gjBuZ>aQ#aZ*IC}&dTIgT3+t(?hh@7cuG=K8cP(Czu8(j# zfCixoF;!B%^;Nze!vt@ek0hM=o7b#eGmmNlDKhTui(9 zE5GnTNf=u1>EWg_IxHX4>L_hDse(Csa1dPRZ}Qs(Xq6c=kWJ#c8NZYC!cxsxOY8pW zF+Cm9Nk0a@uYPNX`EmFXr%ArnTCZkVhHDlbX18E9MJv^&4L~`|{iZnTELhCE;=* z`P~Qb56_<&`Xzso<0i4^kkX%#@nXhbYTPVAT<^Y!f2dsM+U>O6{3f51r7(Oeu2KK4 zT)rS*JA?c9;Tga1`r6Kl^|v$zH~F9%H?M(MyEz%$`S;CK@eK;%W~W5#;p5ZSpyik( z8MKg1et&gNOYG0Ue(&s|=36BAyPiGbqJDi9-f;%{Kr>M@j6J|#MWVKgfEQ8K6xCP2Sler zLB1&$v7G_#7aF+M#$xvCA#pXV8{NNW&rCXA$gRx9>k6a8&#Q*s7_9>OT^K>Wg~UHV zNBhrZJ4E>^515+=q%(X&8ho9CeDg_v1HL!ikmiZ?i_ma9AA)tyK&6670Ta3_vYrx(04a6S02bVQ`16 zQS0Cl#C2DS%wr$ezV}aF-#kHFFN3>zry4gXh#MsR4c4QQAKLH{wO{x9=K5QR{N4=s zhjWj1ZH;hc^sl7!Glv^wbQoLd2bI3*O~vd%{vGpz`TUV<)wtF-#rlO*IbsjzHTdQV z^0ms?pTTp}<(8^2t&d7_Gcg@fYewRz{ok)b`&N=<0Ct;fH&-&|3-RRZ+ZOu(lTEh! z#Nx>i>BkWF&9Qb;#ZkHFqs~yLUecRi*oeM>`&I=tZdz|K-1HByzR=(D+8yad`uQ9rgK^0F=9y2aJ@`%9LpEa%^EK>2=_zIpL9(s~&rOHD z+4gy=uhiIFydFG++Xu$^4NY#kKyhW0xC*%*{7$NU<69KhX%aW34sJK_5AS?FZUAjJ ziTu7fI$UDX>lcBJIIf2E>P)fEqifci@*(aQ5TCXAX8l^KgWqJo$Rq2iz;{tw&8ka0 zsHcOi7Um23jym=150tNxZmu8u$a4{xZ+dTg>+urFX}qb&S3xr?@PjZPx~9_OD>W`H z@sJ*FHt`P-PqtWhJ;KFjI!)>jWbABl0^7|++70;L`p>*Il&>V4^ACPz-F|$X&mS&P zOpQ17^bJ{XyTOL5fp@ZCfm(P>F>kkj^M460UF(*B~QU}~V5U9`1Jl-K@KysoUZn71R^U&YQ zJ>2>gY7b76>yw4V|H1<8ms0QMiQ;P|I>6`kp7b6={x`m)r$c~zE+6z=5d2X!4=}1l z4>zBUAJA^Oc#|G(i0F&lyOf#0{ZS4w4*+{OlBRxsVe2b450FW_!NcXOGdpidlnw!A z+R1de1=@&niYqL-vLHiv&+7+$h9iaB>ChK3? zXpy6OxJAtR!_VLLSNUJ%0WrVhXX28)f3I3W`36n$bsoe06^J&S8JJ6Py(ahf1xdVA z3*pwBvwv7IE~zh~r1pP$`pV=v8LY!BU;D>xD3i4jw2$iHrV?C;cUCsL^Ih$$^^fY| z2Fd+`4!=*Rik`;dGrcx*^Q@G0__+v51Q0mALK&eNabO6Se_ zbw9aZST_pQn|%yrGJ3_F^z`-L5sCYHKD9S-e!WcuxBLz1zwkth`ib@9gB|W|cq}^cN(lhnWhvGvm zwo3J7J+Zz}@7D>8CzCs1{XpNlthb_e!*}NX!(6{et&ed*hsnRM&84_X6LbE-Qx@Zb zpKQ>rZ}EIyHrbEeL(%nJ2T@$VNgcf8eqmjC!Q(rY zQ(U({cD^#YmQRiY*v=sCOKsi0n-phcf~|)~MSFpWz7Sh?ziut!8(-4JW$Y~Je|Fa(SKOb(3 zuH7(e^A4)7vw^vO;b<1|>!0n|S%>0!0#8=;6=!Pg z1GL+zr?dZ|`npZFTMqG);CHV1=QzZvGWu6?)-&hVy^K9f>U=D}n6F8F^B8+bRu+w> zxRNurc7uDnlCCIlMS&{{Tv6bP0#_8cqQDget|)Ltf!GvygPbNeYZSFlKClh1i^PVa ze-_2hYgM}VMQuwLKj+rc#m{bEy7;*_moC2hzlNo1Kgs<|m%roD(#06IhKINa)$C&>u=>F0j*nVhE^`~}8b2tw6*$llvAL#}B9JwTYMDUvu{NT9K!KeJ4 zqmA)d`>{V3pZ&OFY+uk1^o$js`V(tQKid~{qBf4C0*NF981ToWH1*TVnu6^x&82j)+6`BiOv z1s&JIccSB(_$zeqSLxuRzFWEl)m!vBj(=$GUa>pO-~Kv@uSmWQ z9f$L!diBD7vp8S9TN7Wl{v3|e=zWcL;qgmB$IHNY!{Iy8aTwp}`9b18-RQU$|BC)# z62yn@S8Ip)(A>W%m;~`>&NG?e_><;`(Q&qYv%kRCc{c}>SbT+C_eYfjVf^4yd>+l+ zRS#(5zk`lz;XAKApove{CsUrVVLd@xloB<6L4F*hj6bEtJpT$~7i@^0$0dsYh>H6) z+gGZ*AL$>llc8gO=jHD1REiNe1!xd;2ke`wYyV=F$Nj{^+)f4_U~(PW7y7UuI%e!f$2d3{zTtYF`f5=aKW7i-L38)6 zMPYo~Da?oFOVDwazyA#3zk5*_pRW7RTzLFCUnZ<4XjW1Z#*7<3% ze?SvSD-sBBz<&57tk1P#{9~Q}QvLyh`6-RB^1dyd^;L?W6DnQ&!oNxvKX|%y@Ok@; zb^U>kzg~m*it2AaQ#$-9epXTG;-{S~UHssUr8B>v`lSC`YWU!uq}+?8gU{RNgE6jO z(e*c*!SfNMPndtvf2G5p>YviJY1DX>sQDMg&-tWu=64i7^|R8!pD?C@(Y9f$GJJLbu7+(UE9KXkTq_}_iJV|ae& zScTV#Xs(>-7@ptJd5vuy<~0Q!kBZ->;p?1#c8s3iT^Js|56a(jzI6Cg{Oo^A7r)?Q z>EfsSS-SYnze)%H%L;h?vv}Q{uA^7dS^q@GqvCV&eAbDMhvP%;`RteNF@9=0+>dB3 zchJE{$2IZMaZUXGI{1(1;G^T3_~^J6e&AD#PoG=UT-uDw;N>PSFUsNNC$BkIKWLfyWM7MaBz_%5IlL?`{BoikUQ5YK$?R)^mz%tnp&VXI zN8y(;8oiHRPV(a0bk5)DmZ_`ySp2K;>nO_MW%1#c6Xoz)N?yv^J{EYn$!i(P;k9%f zekt#x_tDEqUVMG=mUDmA{=Im*pVI$Q{it~*i{BL$a%bHXem~oXb176MTuz%w%IpOt z{O|h2`222gJ=u2}T0_paTEq3ZhZtYaR-e2cpI_4bh3jK4LjUJB$MY%fuwl_xJGS~7 zNbt#dw4d?=ydGq~4PV#wg-odl`c{nm2{_KC@3R#vsDQqD>k@k`ZFI?>qv7kbPQ>lq zb$X_Rwm?f+6XUBdE6)1dw7$18rDmu;+obsFOZzmw`wP+fR%S}gQGNEw@zv*v^ZuNZ zu%2n3WlAkjeW_F8tIr>2eF0Km*PWRX+F~vRW@CGe)m{qXtWTLt?B$nCsTHa(^m2Un z7mBk!AFc0rresI;d9&lIPkuT+dy%J*`};RjYK`j4of=<#jyUV{(E2KllF$}@$u}*& z`hwHryFck=a(}f)NjIbV@?MFrKI^OT)#sx1H6JClMfLfo$5)^G;n?a+xq$s=&Lr$V zzq;=?=@V36)&RU;fWFWAN-h7H?uoBHM>f_o@aS*SdQ_jy8DD*_IP3G1`gV`}P5Kno z=Q)7aH)FlO>^SSQPsR7Q=f&To&rp4Zan@(6jK9x@)t&vHjz{@t@OpXR6jWcAw z8qGHkf#;Nw{a*ArWtR+eK6)NWpHI?U8j7D&(&vygm(g)}4iVlghVl`En}q*;V%U?G zTTnTaj^izwHyVzPqk3&C@IEY>OCz4NG(+bX+>7^b(fo;P|GL&PXe@e<i>G9{=NHTgUEm#{ zPLjJx?k9PWB)Qz0)Jt-+^}1igcwUnGNiL1Y$7PZ` zN$#e{P2R8j#r3#-N$w}PG#($9N$w=Mn;ti)w=uLf+Psl|GY}!Lv$SawNi-V8=AY1!}&>4 z>P);Pj|EiLLj!>OdZ|WTAv8f5bO0<35S<(BVf?G1AI&AxreVAVIeKFUf#_=NrT5n#Q z-y=io%^nk7uQTsSsUBM|*`JwA?8l1gRhW9^IPHqoo0cAJ&(4&QQUkVLvad2x_Dt*L zb#`Wrlp3@3lFx%AN@uifGn}le@O(m9jq?JMyVl@x-Z4Bc%6T7`bIJLsYjHV1@{D!3 zERpk)eYor;IjIiY6%-0No$uOesX>DRc%OX#MxyRFtTTdj{2pDeGuu5`9ACk$LGm{I!g3>9FZsR>T5q#N^dnSHZsX{B-Gjcc$ZWmjdpxK;H%0ZjnSKm|=?XuWX1tbZ2Oncq*T z)DBplVe2L9EQzX@LVL)3;d13ie`pq-FSu6XxPs==kIgjq|20I%+5Jhb)p$KHh>kRn&llixCK;>n`K)bU`TvRnrKLc90$ebiJnt;uAUsYT`7+ItRuRpU z(ND=+(K&SgF&&?-O}bjz&WsbW#(8@CqA4!D&wJq?Iaw+KXC;vM{mcRonwOy89fO~~ zktlx7HCV6h&vmnOLwbcyW4*j{NIXPQtY~m!^rD9omBa6$K?-vFxP#fMKci?J?uz0u8b58`Df_C?R9c93ZMO5x%O z$}8nv%qxEp<~4XlH%kx1EA@Z49ZQ=RyG4@AVPqE!^#k|tr!Fu@z++%SdUP@-^Y?szr2eb8-ldq=p!N4y?nk`5m)q`1gHT@9ZCJ1DWtdl^<~=OE5U&u? zOJ!f^dIh}_-5;r6puBvih<#1393H1L-tBK0f_N3py1afu_Fz9sd8MDmyz<_~dUdVw zuq6ZWl3u^Oyz)6-xqo9`j$F)ZYQKjqLlLj^%gig~wP?K@XE3iq%4^=kmSKoj^6bm2 zSH|nnyov}f_j^RI?T=W7BVKuznU`x;G%xQzSg(}jnAcZ7JYpGvcv;)zG8*xc7G55`vPfK~rx#tf|KjXW%hSN?WgJH*svY&# z9r?JB*NZ-P_@dk}%QJ|V?=tbyv@ax!?+9LRrq4lEG#X|ZgLv6DC$>N8>7{933@`fp z=G}I~EYBid*_VlzrhOq^h3AN0CC`b1Im0Z^Aznq3qwUK_{3Fae$}#@S9i!j$NZR`x zJzDDk2tSw1bLn%gLHWZhV-c_1Dbc*B-lFRhdb}tuk|>;byQk0Tww)bjc^>gfemk*# z!aqxUKF9Y*v+)G~Id^)$W^)=(Q2eZwIG(6JVua-dq*v+|+#gl*v{H^IMD@y>kK2R) zT)n7H&KINO8LF470rp?1x%fHn$nk$l=g@QK^w;#(O)QdvNF;h*OYe)$ACvFIyzDD5 zue(1uC$%e&zK^@C4le{y8oZoyqURl{7ov5P$BwX!W9*CCAHAP=UTNp>^CWsc^)sUWE8e(}^0IwQcr6@Z8IO2*-^Ko`w0Y6{ zr7|M>Lf#&&laqGL{{ZuPYWWC@8}TY4yi|SyU8A5^qV1mEzo?%;l){Pseh+#)-aJ%* zzYm>WNBsoF4-xyat{7=~3F&2DgWFN1S1J2d>L={n_m0TxM_MK@yeMyaKk@cQSB(9U z))VfJs4^NC7JiED>+p_|mWha0st@Z$&!=(a<({XxKf}Dr{xZ@s3Gpht9{bhO=0)$9 zwg<0Q%IBEZkz*q*lY!S|(u?;K)UVR{wvX^CSMe#!6vQiM?d54ly*QfMSK0<*U)`Uw zyo`9ItxGH~y?F;87t(fg9>(K#kns9GbZLAx;$P5$)y!DvZax6ocu61p|N48|B^>7zY{GiUJ6x9O3@^&N_`c(Op5~3w z-_v@+!GvU!vf_L$n(_v=2mX7lig}y-hqfcdFUrSyIghz4uOhwDe#GNEy^rGRF4MT3 zaT2#<>edLa84NGVyO>v;?N}INJJNcnzb_*DL+#r!ue&a}EHe==&mla2r03IqQ`&K~ z*|?DZUbA97P5wjei^uoY%(QrrUPZ*ds9wd@T_*c-+oFF@5O~dEc=5dBjSHQm{}$hu z&OfvsYF{*-$k~SNYf|$}%WH^N@`u>3((~y!R@!kPjia4*POs&emNyWu+@G+Y;D5h0 zUcG#6qQ^fSxg=T-uUCNhiOF|lT3$!ItRGz-y=Xg7zI5EC?c~~w+wo}kOv`M<%TIVw zyJ!8x%S@bOcE6ln{6*`{+l6^G_{C+JgLu(I{e6U&l+b;AJTKAl(S9qo7yfsN>3x{Z zssG~fontdCbCF&SV)s<9;`%O=|MIuM{W1M3+>XF&9>a_09dCbh$JiffJ+wd4@lhuB z)oo^`B?s|xeT@4fJwIY!iQOm4+n3q#k@}nB_D#?~)V_FpFY>GNkzUlVQoV|+EoJ+n z?MTO=?44vB`YhA(CgMfMA-EP^nU)2JS9&3i3u!yDc7HkiJ+0TVoA~*|+VzC3-#typ}P%DDPrD;#{8y z{vUf^0v|<@{a;-I3HN{p0R@IL0Tr^Yy73;7Be?4tcRix(x+8K#*CV?M22g20CEoE^ zjk@ZH903)_3xel}9O074WxPk^2&gdL0Tuplrs`E{Dl^^H)01KUpU-bTpGhZ^p7;H} z?|b#Cy1KesbNq!kSicJRb3%L@nO@$*uBUUOygq01_qac{n`oWLl8!r?W&Ib3fb-Fw z4UE^Ep4ZbV;N^RR<$WSva{riaUf3QHw`@J*b==_V={(>S;k=sU7x?0Xce>jnn2f#L zw#Ujp#OEd2b-Ts(i1zDveueM7p3VooJf9xi_UJ2!_dCk#S&0|&7CJa=j}4mb5pmS^ zSo;CXFEZ2`BhTK^t#))fxZB|8Zyia$AQQzd@|4b4;im}hTK4dz^m%5%<6^p9qUB- zDU4So=k@$`H_#V>SMl3Pcs28JE$Wqjs!}Izxq-eU@j~7hf2Z>%p5N=uVFr`|U`Q^?AY%{)?maInnR%b&oY4F6Nz}qb)va=VVx-cjMoYOc={Uf!a9Mx zGF>MSH}omvHR!tW^mX7>9ZJ#=QR_sq zb@jpz{)^K(QGGG16J^^NFLT3q`Zn;wI+2K%Tql}~S51EWa}cBF|CYtB^ka^eEoSSf z#d;?Ac!e}Sk!(Jf%Op0A^aA^JPcvLJ5aqQ(;#IPkty>fIEBb$lS98rrpfoI7}&}5YI*$xx)gX}y~q9K<21QWG}mz&9zPcBV!T4rC(vcU3+sI%UUI!}E?zh; zEUjm}hF46W%YhfxFXWY}`h|4@aqD(4UW1>SKvw{-oF)H%)`_Ca;@gX87cPInI)V0U zd47f8n?P$oueyU=Ckp-Xen)w&lz1U;A%nwlVWDQ7Kpd$;+^Y$2-Kvx4VY>$a}$@MGUys$kYF5$d>e_#S#1H2l(O>$i( z1k?xb<~mM8Ugcw09R0hQUiV*qBV7x;yzgeVPE=gMcp$If8*Ds^c^w_Eu7UAt&CN_N z{9GPKN0*=ry^^f=$L~4a;5$lfl+ov68r@hbn0<$ZX=jkFecVg17W0|(eRO1%z0*}4ef z2meL)xC41%{VM*J*RSx6^nKuk^-J)=`;9mA@esC0#0^ClulzkX()GZrHp6uS^>y1G zbFPlhOSJ2Di|rBZd%x%T)uW7V0KMwB9NhL;a!tJ7Vc@k<;)T404i4L6m1cWH9L#$> zzgGVP(`(KdWpuNY_qe}&9(jgT@0)A=1mYHPUdNwXMn3>vbxSkbKVm#E?^B(h2;UnY zf3)j(8)A8k-^08Y_8(yP<7;#4B>DyDmDhn?hu`G9Rff)smfsiexBtOObc@7G@J5Fm z=6y&r?-3`K_mIDJuQ6Vpy)5tFoi&Mm3A_RuSbpLD@;JIV$Ezx@D&+ObB)S!NHDrhv z`itREdHMD+y_PPWM7II2qK)a*E7?43!gZoR66;r_1-oBI-o{CEJMgMfc)6`#$#~i6 z75H>FpvWaA-~m)rW~eJj2lV}7{ZV*L{K&ukUDpJ>}xZlUek!}ac; zCaL!ss$YSl;^*)E@7_Y&OS}Yc6vAQsifGm^#KC?$Z!U{R?Qbl<0-JB49e|hTcyCNU z+#j$1j*g>8Nd0zBn(w2l@+#TSczJi+LOTMl!p~S7o0}K z2Y3}d6t9=t`vW99?nrn)1&9aos^q*{wwgja0k43fS99^IdMJLr8uh~KtpdL?y@upW zp`C$O*`D|~Vx38KeNM8vs@8ju3SQEQGYqiqwlcmQ>we8{Kd4_ZYM!IH{mZjr?e9;& z1?k6lqws1NEz1~Z<1gY&xPMS4H* zs>v{~;IWKHHcK#4x|s37xNm8(lpY2TfvJ6uGdl3GwYM!7gzh zsk|yE<2Q8iDmoB&Wp8EAhl%?V|HB7cU0x+FdF36#cnw>*iXIKTO17nkm+6of_Ct8R zg83t>U;g9E=%(oSi(jvR$CvWBFbi@3^-A|~E%L(gYI#ehSMJtHbO-Pv%D7PGmCEsU zvbvhE9|CyfRmaEoxj#&z^}wq*&AgJ0SJirt{ZROEHXmJl8q=$Mok^~M`vjV=vwpjJ z18cu-`=R_K;~}&Q62)Fvze`8}ln>EDb+A zTbVw{i!5P!RJUS!)tpdBz5rfD`;yE900$qu)6EOVHOQ;}dd90Li}7kTtdML0US57( zW~TI#*15+je#H%pS3T!7_ku$5WptSFOJ?=L>*i3eg7J)(na%Xtacd#j3cQMw@-mtw zjwN4;`~p#6edBrT@0`|*SKfaL$u{5>Ovk_OHp}*gSgS z{k|}c_&m|VHcYRTuNIOWz{{VMSM%tlw#WP%S$>5%ubQQWq#k&Ae#@+0*zcfT_#D)- zwoI?qn+nNJ;1x>Bt9kTN>qH&b%hQhWD*3UH>;hgn`!lN-o~J^+@cFG(oY%aTBgt35 zt28OE=Fv;7UwIQ*e)-xny=L4xl6(!kYBJ1A)vK2Cs^h%o{bwZk26%Z7B#UFS>lLf3 zWs{g*r5%`FcN}&$*$uqPGR#ZTE5^$^iq-qiPG))qIIrOo z&nFS!73#spg_#;psJv=8uL2L#Yxo`KlW&1nPS4EpQtMagO-!#^Xki}@v7mxhVML|{0zJzhh;X7QeBN5cN9-! zy!?l8z4o3@8h}^e@Po^%YC7Z9zx#p zF1GM+VjujG?s*fme@^rlZ#GGF-DA$^cz@8Y+b!xGM$m&-U zoEC)o;KSz93wQxKjI+4k6^FC@n)d5~Df{3*Wv3>os~NhlPe_SJl-Dm3FXSEdA@*{3 z9@$^2*B%iE;~0FH$C1NEJE!M?SHzbjj?J9+SSPB-viz;@#^N{w^!gQeRkmil&<~uS zjh=s$=gHH(o_qk$ul#QrFRc4fy%qqkhNF|@7yRD`Z{582-fM{V1Yfg#VH{D9BCglC zt{0HsfS1`Tv;8&_MqUk%vivGr$l@6N{|msYY7o2L9rqX8=C2d6@mGC0<5k$5@hTs1 z0of0{>Uw2ZFMb~k)GP29;}zz-qPhfu7dbXbdu)Eaq7+EQ9XyUbm|o*fx_}%2UirN< ztCuvskMRmW#dyX3fFIG|E&^WJgOcdg%=HW7Sa2ufRn?Q}HE-kvgupnb{2=KSOL{l! zCs5!tZ$YmZwJ_JK&dc=bckuDx!>uRH97sG!%gIRuIKOkg* zb!k5ML$}_G?`i&mdX?YBcxCtI?eWSB2nD?g`ee2};&E-P-;RotJ0RA7c@{BV(T`q> zDajnf>-0sx4Ii(7olviI_uHsf{@qNkfV?HQ>qh@;}~yQFS$-6 zTi=2@H zdId79S6sghP9$oNZ%gfw@b$B@UYTf*HC(UAK&IEcM=vC8K(B^_q!-4q^nMmc?=g(m zSMx3;ZGl%&|IFq+#u4)#>R<&HJ1Om|oSW*M}F9cA!^PhV{bZN2`A5 z9VzeYpJ2Q*o%bQGSN*XpzmDB?A!!eKk=)GY7wYADi&M^E-X6PN zL^^<8g=w0X)8&hLAurEEj8|bkkK@3LNJromJVgJE`ewbhQoN&)^EWgSpUPL;9UjBom7x0Q@k?MC;$EEO} z&G52zRTq&% zK`+mM%(h3hu9j4>I0jB&yk=wX`}%1Xwo&pEbc^uL4n@r-DcnRM4e~0S< zeD~#R_(z=w=i1CJx=IhBkBUUka#d~WsfYx2T=JMt0Zm3J!3uhvCV$vEJZ|3;EJ z0lC#2`BlhyATQr1j92;Tj92dTsiXvWm1me2>Vv!*>KHF_SesZswC$9~$)mulq$OL| zk?HmKZu_CaJ=`CNtE*QI(*tc_KZN$H&tP#JcgA+|80b~oIf-5w>W7MFv2kL(kMWv) z`F!#?@X9+h2`_NW2k&&(Rn!ObE5hSpp2>JU^WA*%U*J`FLuRkjL0*_&PS<04?_+fz z*R^6^q-%@$h4yoXFulCXSCc0|FY~k{=aHL#-D9lZ#{2H0ztM5Va`=yb^1+#p#(oIT zcZ9dH`vXLI)x;Pxrg&d|d48ff&v&>Te<5GgIbGYBUO*0?W8i$(k z!2e~v(!H+3tzPNUN410bg~x4?C5?K$C+SuCI_q!5I(INM1DwLTs(b&5WalZ9jlVGO z>xMV-T9<%Vrt%)^7wUm}M&nxxysAs%>x8&3Ec{=dFHCk{3AE>QtL8m^Kg#QUNw3H| zZ2rP+-Y4UqFpfY1+hd@xF^=n-fmgEpLVr;gHSY^XHuBn#fY-sw`&x|jEokrheGJAVr8-0)9Z~slF)98B{d~Z5z$<6HTg>Cfh z<8M33RJ|(y$nt*JfYtO^(5rq%{P_;qo)7-OdM|&T==Wf{^;(#sUhuti>Q(b6rq`b? zUQGvqUcU15=v9+$y_Tn_7kn?BdNrKG^g8Q~)pT$gujdOp)Jx6#ymL9PM_1E);8n3J zJ#lPs$t#4s=B=i`174A@(!*U(4T(9?leUYhEc-zBdw=QVQW8hQrs zilk}$Rpydc*+slg>|H~Bz{~SNdg@n&OJ1I0#%p-%we(EjRq$SV@~g@vuPV-KXxFuL z2=FRNlU^a0ynGk)_BdcIJqvgh?@rJ7tIj2_I^=cIS~?VX1%6HsuZT-trI+yh8o8DZ z171}P>EV@K;I6J_|Bc7-;1mGz zE_oGP%JsTqEiD9IwMV9hSCLCz7^C4M*U{^MSLycj$SI* zJ_fuRzD`em`CRg<;k<^oexE)Lyh?sa53gdEy!?Kq*NCp~)BggmoL|$!tJEd02F`2P zN$=AqfLHkT^zbTo$*baWrq}S1@6#uNS3#QQR|6^XDi1O~wY=WXS@k}B3V5Zfu2#F` z6&l6(&D!-o4FIon)zw;;yo#^jyxOd%PXn)X)zx~Jyds>}%x>%HOyHHSc_!lUerY&g zi1}4Mn(H-iJ$(jvrK{fOxa8#>!+D*(p3VYZ>8khnE_qdRUb8P*PiF(Kbk(mym%NI` zGQH+pwVuuaUg_$G{4ROGQQ6cFMNK0%WS)rooY zH_+!H@6$D37;@MiG4FlfvUOD1*D_wwb&pR<>mG4kBsM?QPCbt!%Ip7WH3>i* z>-hRr)EECxnt%Oj465S0_;uk?UQbKBRNhYWt4K4y5J!z;&NnQMS3I_nE`m6w>-=Md z!}}rQdO5s~j{J-98lAm{%mlrBN3gnzeu(v7%6&U^*FEZ952NZ;a2?P4`5S39=#{SX zqD2n#9@op^bIJm|e))3NkY_-z(tFwQb|Ss9ptHjB$jz-+Nh!~-*EZ6{pjW!i*H)#H zU(g~^58u^{*PQ-q$SlySlIIuJiRQ{Lw2O5}&96$H_gAdiNM8fJ(sdrW#9@A6|A=}N zp2hUK>cllX$*ydN6ZW)poA;+U@W06~Xw#Jn&6AwC{a zz2-`Kp`Ic>4#$O+n*BE7V7h@+`#Bb6=9{3^QC;>nAc^V!+MW;;dnL3s?_Oquly{_C7CNG0t`4=Y9tC{bo5UXF1`89i)-zC!- zufE0?xJzk1iT8bOD`|o zyjOYUl`~#E4Gj@;~;8k-&dU<6(kXjsz?&kID+#O^k z@G2Xh8D7cs!tqx<=au`f9b^^oDx8#FUiq5$m&3fr@t1iI(`#GB4ze0}HDriaLcO5K z;`l3gFXJ`*g&kxK@FF+G>*coJ*1b=ldc0l5=S{|~+C*2t@pihd@9>aUAo}CRzh}rR%yAufzEX)CqPc;X5aS!(`$ZFJy{2OdChpeviGz6^}zAa2x&clmw#>pPaNDIGd6D$+Rl$V z;O1?x6pqZldNW-K`PDE!@jSVaiQ{eHQSv3ztA?*jJI7y7YC*4BMX!n#Os|fhm%M(W zihrJ}UKj`bKF)uY>|lD8KFH$eE!|94NqPxA@rw@U$@4Vp7vcb~oG6s1p79Di#CV0S z{eXS~yaHQUKH~mJi!^f_@whg)EB?4P%Ii~!7xEUo9O_lBsTbk^uV|VJy=wo%^vZkl z1Nu4esz08ccWv_&6$Pj?<5pvf!BCHi9XaycZ`dAXu*;&o;oDG zy*wu;(JMpwRgo26x4q#H=ob<%mAB)06U{gx4)%}vZ5Xf0M_7IZ_IyCM0Iw3R7w%v9 z5UXF&`$x<5i=3u6j&V9~g7^0=d6@AUy8i?ECGZLwwck!Q51<}Ds^gqs3FGzL zqz&{r;FYfXMg<+NzsERweq-&b?pwwyR9a8ohkhu0V|>5eT>VfTIil%!0-80Re{6V^ z@fz;iNj3m4->vby+{Q8J@c1#vpVwFM7~^%@+dIid;MH(jW_Y2$Sov`Lg}m|}=e*YK zB%6R&)$Qr!6;4sF5c2wbC)o_V$c)VJveT>hzg(|9JIM#YE0|_po(B`xIkiq;9I<{y zIIr0qcab{am0g}*y^`@ts279_kGIR8V0sPhxr=-Vys8ymc$}B&`3|2Gy?|FqC)N+; z-^O?aM(iRV0WZ%T@p^gq`2n>b3Tv+0NX85O#r7CGiOe1)g&+M-Y+;-eJ09|MW_ktg zVE2!{`t4ohW6-N0#~Z7|P0qW+IL8Mb=#C4WIt#pFl6giBWcW9-yMdSQzRboE^Bj3q9L4l1oXPci@f)%ScttYI z3-cU#6?A93!kpKI?|efdz^kw#vwC5k<9ZXP&sX5#Ct>an{++HZ=oPE?Xus?k7Dsdc zH{@H;%R4fOUd_Bt6vsLFJy{&7Sxm3GKkp_#126JGlDvn1`QV-I@dTKRy^vQ;AEsA;$8qDR z-J}6{)nxd&fv6AiD%#I@Azy!&14da}=pWBu^IuiJ#sA;wJX7H#iI0O254VW(KRk|( zQT3e4_1MUsn>4m>1NnXQ#sw#5HotJaD#o!IdCg~e-(q6}IUaaby_s2Fc>WA|`A=hd zRdQa#hwddO0I%$~Gs_F-m4H_)#e%0ZUKI=3@zAio`^X=Fmp{Y2@VXr2ReT2HRr4&1 zqRwn|R z7_UHY7RTF8Kg+lrc;WNr@ctB7|DszTywlwe;r&doJr;b#c;zi%ylVb@mN5!=6&ftR zGQ~@Mu5Os~3UOZbx142M0laEDWtLa?DK;-YfRCebeR(uK(U`vnO-5jjqVqH`5p3typPq1njd+c*vIMwDgVS62fXSZN;1y` z$3s5AQ+Y)>q~nF{5qbIUX8AOt<`d(ez{_*bLAxF%=3dUvOs}GsSbm*7c)M{m@QTdK zEHBSk#smAuk_Ps7J?B-kd%JNB@Tz(?v%GxAhSATpQJ^9lH;> z+xDoNb5*(Vy!`tZubfvHuN|d(jq8AyzdEye1qQ_P%KnA%3UXfc=02koczG5d9A4`A z+B$x}jSW!$0}~@PlC_y!{hbN@bL=R33;Xa`bXr2&y$Xv#`Ie7jY-D9 z@pj?IOt0pCo;3Q)RA{^&rslGydJTe|^3GxNU%0>6HuHVlV#SMfkpj}mFY5DBoqX47 zUmWMC`!K%H9$#R3xvi_dm8p%t67iz&VHxM8{y+M+58jyf(Z8);euuooc;fi@{EA{6 z0`KsmBy|G*=YzK{FWA-5%WZx+0&}o4>Q#9`yk1ehE#O`8Qj+!v|MS7Sx%2{FvFfQl zA2-TtCH$x4ruaBU_&S>C|3mNtd4-hqHSlj&uinvbgMGYTTIHLpu10ZN!n>a9g?i%o z@#wuXVaP6crThM0DzE&v8hNz>Y~RZ)j?K*r{RPO_3wh!CoEnK&7VJ@}@WTEgQ~e|I z;&fyEb~N!KY3AkVyh4;rJsTIwyjDx&iRON8GsXe&u};zp#GcbDI%2s@GbnJ>qk)vE8IvzmnAnw2Szd_kmqa>qJM`seIDGjbq_gO?gEZ z=9e9$IHF!fJDc)~#;W!p^GbAI>qCK8-a)#rbu_>E5G?ka(;wI#oPN)4e~cquZ-x6u z`5po9f@=;=ov`B71$fmTWL|i^m8@6v!lDSjp8|d^w#{5uQ7=z|``>p35&?cc1;Gb@ zX?|X@s;)k#J(^#e;6FJR#@E$q%GU2k|1TeRWRKE2-;ZwDZS9_;?t3`3=UmT*@1^rO z*WSOdO`z73i5gKLVo}I^80@={sjYk z@9UYJCodex=1JVHdo2DnejH-g{&oKkdd2D&+Am$h+N1xG{l>pRuL{1NsmXj{Gp~EZ zdQX&fR8d~nOT3V`@Ymt>qWPNZtPm$Qz6UTot}R)|^y*W!-?#yIRc&GUh5O_DMyl6$ zI9iV>@hW(a@#N= z@MG;QuDese;C(s%dVlr*c7J1g6!vR*dxZ6cH-cWczA)465%V7BC;aOfuXpnf7!#$u zN8Wh+nUQtKQBnE)S8WyJwWQ#HF-gk%=H`X|Vtg_05jX#R#%uP71IA?FRkH2>&%AF? z*1e*?MRU`W_h`R?=a+xc0pljn%jaYB_nFRnjAP(HeE%Eeb+g0^d7~aq*ZcZ4`ys@E z_82Q%I6o2D#PaKkl?RMlfEV^dxIgA+2HImBuh2%uYt)Aaj48ki`=RFMh5lkZFph|u z$9c`!alkNv7e2?cNq&I=AH4DW5ZX)E7I~GmWY?>a=^bM0+J-%PIPC@#zjduMyAGzL zxPJ^Ed6i}{UfvH_9LLT(oE{0h^4nyV7g@sAaUidf){Iv*=hb)d;q)lrRi0s9_1DMq z^0#HYit3nN!&V+ny92L+wwcwd;)Zx$!FG&SJ@WeSaM}ZSRb-e~-o$ubRUH^F^FyZB zjGc$mp1{kO;q_m&3a@~N@yhv#$8qoB)C;^SGt4VzH0yUD?_M4g?GpG; z(Zu-k+x5%Yd{T5yI0QS1`lWdvB(!h0744DVpGn@ooBT(D-+l0z;FaM2ZazX@_?*S? z$1ILfn@8Fh_QC&~n-?BGmVMI5>!|+$UO0~SeA>vX`~LthJa1Jc@#+D*iuiqD6H)ZR zhs_;FoR9W>)~Hv{L}aATGQkVachpI|yb^~*zh;6Lo<}bIyiu=SiO5KwWr7!;N6rp6 z@)F0q5*PW`Oz^_>E;!+8+{?K zlFJ#d;`&Bjzk~nRW|&vSMe%xxe(1OM;`&K1EUc|N{@|{I!Rx}xcQ)$P3wUKed2o2) z*bmpil)S{QGn_x-Dq05f0L4$T`JBkl?EXz|@As(tJPP%CtEzu8y+-fbKo`JycRZgK zOGf2~5B}E8`$C7;TdBN?yD(l?oV}601iUJCvGW}YrP!ZNcx9jMY@H0A=S%fIy7(OG zM7-U6rs`FC4byAXog3*w(5tRf{Ctj#5XU836Iq>pi==m_}eNI{ZswBTg9~zaytN5$<@ni}n5`G2s z%JH!IX+OX3@X%mASr1grsjS~l*K?$jJ;wms6OzRIigaT0_d%S$A9)1r1^sqm`^=t) zDXEG--%)=k<5l_{%dft796@^nuZ9fs%DFk7SHa>uaZug z~@yU~HbtL)Is@(SM>&#T;E zd0)eMja}T09u2(m4$CYr^PYHK<{^xizk%od%5L-+;ALi*muFr)ucDI}uLjPm?|>ue zvA`?;-puNicW*qe2F|NuFV}15k#rF7DmWsuyz0y2c?C{pdgbk7ysGXziVg-|zAl;N zRjcS#cnaec;=G0(*`4MCufm+n@+!Y8Uatt}Rs0K&<8$5V?|@gNcV>B&-51ZR@>Hf* zg!5YYTX%X~RIfgn<&}STJTKpAj92-uOs`$1^`O58UJV)MRj2T(=e)eXF)0tk?oL9@kPN63NugW=@<%Q?jkypVPj91Zqrq@}0PN63PFVZiw zyzo3b@(Oca^_+G7m7lw$syS0r2wo zPo`J%@CrBbik)fwiMe`CB}<`AY=5P9`Jjh+m=Jh_?G zt4`rn-Xnf}bo9RI-@!Zp-ZvfZpDdEZ;dMHmhxO)t5eM_W_AI7Xp~2#~^xFedP6542 zlIqnw=ZA2e5b`P;%6OGg#_L7kbt>=*Wtf**zr4d3FV7*2*OS2OG~kt!mn^@UM=!O0 zl@4dTsyMH^fY<53t0u#|)PAV)A$C0EYr*syx&3r{2JrF@$gEztZV%6Qr22e?oDocC z(N5F!3*>!l{VLk8<9db1jG#Wy%U8#)A8E4wK10_Th9BYc0NmdwuQMfH$Xm$auzrYi|%!XSicZAoAVlQ z`v`hgH1GFhIPW=sg8&>0*>~Cz3 zXul+z>9xGFkPZXA>XPY|q33wkzZUOzcy1vbF7ZO%!at|&v19ym6onn-7sSE#h{w4k zz}5o{TUmEhjgs+9*dpQ4q>myV<=xC^`A=b0uXVER<A$tE& zQ_>&rKPv2?<9zGU#pnC~2>4?FKX_hx@VyT4$6Pd#ehB#W?{oZn-T5E3!N=#+nr+#* zhSv8oI>B|vVg6i9@=MED{@Ud~+EL^uf%jn!Nc|B0#{3s?JB-DD*`kT`W7+=-cm79g z{Ks`QCda>H@kIIw;8(8a`g43c|ItnpSC6#Le^s|DmrkUg0)A;b_8beMiLcs09v&Nf zmG{b4lj!HN{}1T3f7K4+du{N|``LBfUB4Yp2*XyU7OkVfh2n)%;_`G4EE$@Ck*7w!LHclmGH_}_3Oo5w}I zE&e%~?w0lE_;&fP+Ch7!uKzi_{Xa69Mr8jh-T5D|@xSgeHa~1~{GE?Yrr!d-X#X7F z&VRIne&aT1gD=``SLXkfvnJE;0AI9!O?+Vof%(?^gmwO@?Pm0%$@F_U{+jrz9i$Pm z@n7iHjrl*Ielmqee>Lj=m|puAb`Y3vBR2Rd@4gL_=})r%n)s?6q~W{XT7S|1@h|k7 zaTDDO_@ezk=`R2MHuyPr#*cr8t+i0sA-b{`568^F7@Iy}Vciv1}$oMC?!;d(`_g#DoZ3Flf zpK$%pbcgS|!8-n)CH>j>um@}ZJFc8U4+VTP!tsZx_=%6dgdGe#ZWmhPS0g^(f5wC< z^f15|{l6x@Y6syc07c)tnaW%#XH8^)Q@=ZUW3R0Y7J*m$l2TOn*E7 zRXeCdz#;y$mDD&}#_#41KV*ZCaWi`}{rlc|i18=DuUW(6f21Bh+Cjf@TdRqW``>!^ zA;vj?Z@$mB0Bu;`d|z-*Hzf<6_zWUM~G#p{Kve z@s~f^%D6=K-zC1!2ESssl7I7B8Gi$Ok$;-_svS&&A{%_n8?!&x|Jf|#@3Q{A-RW;? z;v?VXi?fW&Wc^*@S7_p!xy=8StFsKh?0+A3{s(mNdH>h{!z|-+*?*V#K^uIvZV$~d zjG=&EoTmQ2)TaKbc{{E?%NPatBL6l0SM6Xv)!O*4j$3EUnL=~q@vr9iPql;i{@bnV zj~IUrWcjz_!zr|zJpTN%I{tMw{)||SKVkgSu!0|daKbCLPoYQ3{%hi^cF=z^-r9dL z{y&=e?{96=?tm|jfB&lb?`-_0e}nuj;mi!B=^&m|)W0vj3X+svYz{V1tkOXCBM*?@^QX z1$>cze^dQ;mVZGTeAJ%|V)(gLChaHd-vr;8{-rkcN7Ze`LX-BF_1DB#?V$dq6@GLl zet&SYn)#povq|#+zx-o9|FKlnKe7L42XS#5ve93}e=x&02TY|$1AfEJUUvMqT*Y@5 ze=@N=AeD%D+?B!GG?*KpeIY0h6yiF_*?2i9cJE*^37yme>|D5ep>F)tQ z@B`2P+p=BZ2Xyf{;o0?5>G87vF7Yd@+CPjx#B)1;&-|Y?b{ahq@awj6{fFu4FYKW3 zd>eA;|Co|#^bfNCn)u1$Uu%OecpuOFANun&dXnt_I<@^J&VOM?@!xx+b^Sr!CdY5J zcN#qz@J0S<;-eh}p5$xd+cfZXM?Zm)_3@HdYY{NUt4RnKh+NU6SB#F zRkwcseVU#j`|o$x{wr+!SMgh3HKh+NUUu)yP{~mt+?GG&fSG+xwo)yLa ziPyi=^xD6$gTQC&Lfv;-AFy z-_`ROIzsmUO?T^`NSSs0QRg4FePhsaSbtT%6YopL?uTdB|EhLS&p>;FjpOhGzQy%d zs%~R?KSK*;{ayO+vGKp*+x~I<{K04F9|1qq!1M1j&Gx6*L3e!)@d=$p&yn%N?(j_; z{Hm6G{Cf(^KkqZM=y@{!7Cn4n2Oa0zkPW_Cw};M}MgJ1T|ALP{H1SnCNTb#YA9fPw zzxWqMbeK)g2mJ7GzW%Kh>wi)`|L2)#(f$(PXI(d&UMSpX~f& zz70O=W}eR4-JBgx`mc&IMI;9N?Rucv-*ni5`Bk{PQ}* zUwO+sdZmnia+cQkI~l&uA%5$g^XWfj{8QZF7wO^;VfnxFv-$KI8UHkQ_@!3(3G#ne zcs{)r@atOf{O9 z`p*ky>%q^_>t+9kx${4)iEj?Y{Ckd$m+?os!;e_uC(wU;_&GWO@Ux%d{U66qRe#T9 zz4~Vk!~A=mmdXB~B{&`%l{}pz)AGoQVYMuYM{sZ@))wP2$3-If=bNpM~t$)a0V~vmfwmFjdKl1Yh zbc&pR7r4v6kd6MhZovGS;ZNJu$#@m~7wi9~>gkVmP)FR>PP6bIb`r;bXEXe>zgR#` zIsdu;spfyJmH#q6Cp`Ac1$3&M|1R+(R``(r>TyHKlo#l9!1o*MI(~AoUi?)%sK05| z|0lqo{lyFPHozChpMQ6UUtxnU+TWj8{D(~q(it-T<$CzS4myt8n=JAV{8z6VS$S`e zmIHpMn9o0G;;VKL-eZGLa{2u4In4j1Z@)+%0Q@o!AAgR~^IzCOV7{%;#5Xy9za=ly z2LZp~XFmVv5}0zU(DhDaZdxz5GKvh>KhA&DQNt z#I1(jk|K~5$=VbqX)ocG~2mQcp zktROwKlY24>GQJxF7f>~_?S25g}nasdWF6q`~RDs|7ZvOz-_4}KJGt!&?_`3`|lFp zw86*clA0HB|M$N_Ujlq_{^3Bp|FLHz!nj$z{|(wfKX6-NgOBZx6f^vB4I;MX6@ z+aJeIwfz;9Tht%$qohB({>0??a}Ifxz5@8Z!{YJn&cCA_^c%N+O?=$HUx!!etAJnd zcYge#=-(N3OmzRDWcUFa{V{Il#XSC(y-F9!@u%_YZ=A-z)&^h1{}LX5|EsiGjz7mw zHU42Md^!Fcf6f)J(#3N875|;;AJN1Y@xS&}`kEYnm-u9gMg9Y*i2vVs{NH+&z9GlI zrMvihZ16?=FXizMy-MGdaz1C9l%A0AJjHM)5yc{8c+>FW(9u zb`sCM{5$ji_MQuANY+1_>0iH`-DmoksA1Yzf5{5=xv+!4eCxNtNBvEXpWAC8eMi=x zX@xJfKXMuKfB2w#`pfZCt-q$j`a9-#3+cOnFY2#L{0b|4h>?ifKY0Al zT}YS7@o(!c{y{7K0bj(Q?w&+$`@f5-}7j=!JB|FVU2g&cp5pKAPTb@6$7 z8FTqUS|i8bC4SfnUylFfJpNM_(p7T&JGhH~#0Fo)pX29FT}W5U@#pxd#-ErL{ZE4W z+jsgxx(4t?{pI*}@lRHNJy!Ujzv%x)G5wc+wvfIj>ks$ujo!Zw@tux;d^Y%~Ke>Y8 zj|(rP>ty{oeyaKxS>a3V&*b=XzFbIa0bkT##s6geU$XJ1UlX5ZM{)5J$RkScMnkPW^%Z`I(bp*L}#(KWgHuc92A= zY0>^*Cz1c-c>Z@-L^lDxIQ~1#UH*rx@Iim|z7Z?R4>y*`*FWE>cm7qigZ`UqE&NY_ zpS7=xv0BEj)?5Fb3_oOr4lGb8%N=6W|v;=CyxJl{-uf^HZAbw`p5C-9J+{p z0QjQ*Df#cT{zWwL$(79iemxe^I=~n8&m}&YYVAMPEtBI9?X`%02>7D@Y2u?DNR_yk z#|B@mTP==VL_Y$2QU5gYRXa$+YlROx;rQFUis^s*xr^v0fG_G_7kA^Yd>eex{{PAF zbI)5uKLvb|{~SNn{4cV?H>CM5jz9deMf5Yk7x~Zeas1;n|NWZyCXM_`{!EM7IIH$bXKX zYW{~c@yT^O|DRq&w*$V&f0y_X8+^=LljDzGu!!yee3Ac}_-F_7UTm$_e}VpL-u4YH zqV<3;@?R5QwS)K`8+=?hWtKAihxDwby8vITf9oDU{!Lc@&<^6_)@y^W@?PStre6WR zxc|B)zG?^Y^KI}Wm*%qZ-M^Usql>EPH-PUwlAr(Z>iLg$5Er+88+@^D>)#BY{-c`i zmi5=f7j_VsZzERqFG2oI^HHqxfI( zgvIy|_RYJLuRr788(vXOzXSZdqj>x|zFqxQ?I4YS6+Y-M^5zESf4}#u=?{Qk-ksz3 z*YjW4L14Zude6dtz{k8XIsTH*s_Boi{+jq`M}a3H8~@e384|9hKLNgI|C;!!9pq7K zgO7FF9MAKQET#>z|Ig{^k9H6jw-Fot$;GVxkO@5g9T(HRa{M*%g&hRO?UUB=S9PPE z7SnyQ{+jrz9fbGT;H&+{9ZxN$zXE<`PoDqJ>*=rBL43c}@jv8$`HVbP|8HdamlwT8 z_X9rZ&GBE*!$&)ai`$UZ@ju{`={){r41dNyUZV#9Kj;u&*g;^v&9~8C<-OwC*C^=# z>#zHy$A6yLz`X$!#5>Bs$lh2h)P zf7K4+n-1}(fA%_U71e(epMP594!^=7{=3({LEFgqZ@R+|>f%pk`Ty=`Z_su!e#jku ztrb4BKO8rh9Diu|4cZ>?#rU7&+a3R)9gI6}!#4P8-OSqZ2JHa&b-6tMH1SnCh@Wrs z{2~0Fnbj{=2bbLFHCn*^H$?xtTW|gs?I130ORefJ?4-7vvG>18JA?m~1G)dp-NoPg zRMP%0T7BU_J1^#U?05J6p5B`PTW0uh# zGJe1K`(F$Md=nyv>+kUSXQ~~<57^-2{3q_eW%e@KOU56_@TK)9K0+Ju?be_8HdyCh zU{`$p4ar(g`^xx(;_(j!{}bV>cF>=ojsL!5;*Wop^jkr5W&Gpf@sCY{ui8QUS{r=P zZl<#OKkCD^bR^)5_IDz~x66NF2Z8xEqKnV>pZU>RdN$yf4CeL6B|Zrxi$9!If;_H# zk&pkTG5^VDYw5XwUwElEt}Y4x;cJQNkFcZopX^Uo?VHx$D1H&(hn|ne7vmqmPt^X@ zI-U#{Kab(d{^LIY|1Yxtrz-JJr~gUtFOcz1Z!Uar81Sp+@%GQ3KRD}?UPedgf5rU| zHJ?8y?4XW(YbNdgmHfl+f&Rs^|NQf2$-gA}Un1iVX)gVf`+up7|8(=>m(JnsU()|F zz*k>FfA~kD_TR(~H;^CDt3T##jrHdrvj5zUz)xHIgY1X+n`QC-4}G_U9Mu|p#OrTp zlk2Y&jz3g8oHmKvo6LWPUp^ropH^Q(dIG)}f3;!w+56c#Q*hts1Kv3P@bb@-)j!XD z*7$|R@%=x|xt8>n@jEkoQGWs7l<;xwGwkI#Rc;%@y->3WCw z;QvtBf3G|LLk{ErIN%SL@%y;LuXTujAK*iiZ+!K4hwpJ1|LK5#wv0c-9e&uM|Fq`> z@@K#o>(9oz!}mJ$pPoB`6v_Dic85av{HJat7t8pU zxXVAEL;NDhzrO*#c=_GMzsMo}P{9AYj6cd9zTXNT#!OZ+(ul}3-{u6Bh|KBqHh3@?KSmA^J zMQ_I+|IB)$zi}Ll{|dYC@!xzl{6(sHJ6c{9~-7{wG=cQ|$1sCEZ~CuT;Jl z#h)bOKdOV#HpBobR&7{Bi zWF!7m8UKaM>pxA_U&RMK64l>i`Uf@jH=kwFF|A9vR%Vqt!A%Wjq`Tuky{+%-ZmgbGWs#~=E-zDp> z;)5Pe^p9xjZ_aG={~p=@ZJGD~UfF*Y-=Y8HX}$b2pK0{JLiWEo^ABv}{0oO6(fHpF z_!(P&k)Z#7Q1-vRdE=jG{PD1izpJ_ML2(#?igkpV0 z|Erk)UjY7O8UHeO{+C+eC-DDEz`rR0eyaYPR`|02^O*k|0RI*lzXiMhYO48PVTGT- z|4o2DB>{e_{s*k^W&clLD*~4R{!|&il{^1~n)u{drvDVJ_Hz8wD`kAL-a z@}TU0XLtVlt?(20Kkc>Y zW$^e@iGK$0zmoBP$t-@f{(K|j|CV|D zh>U-rx$q(4Q2*8I??-$@>HV<&Bzq5k{?xSg@%10RmZ<%!b}*l6I~Z&nhad25zvx!R zKbG|fxhJ=xb7lMrcld!$*7z0P`1+Uii%AE-{F@o!*WWH>>mNn?1KNrFSM6{&N$vP# z^^fhL)}L|j&8EeGFP^`CySwp6zRmNWbNcc1AFr|c)Bn}oWFL$_vLEE@pN?escK!=H z=s4dNX|6vuIsWQ}y9qRT;#crfo&P9$&_aL6Kk?k2*O~t#Lc7VYfM0jFGyjDh#ecsQ zKI|Lr9>4x(>C)WAv{<4-DBupyV{Z zy6eSXwSxvqt>O>PsNeJcWe+jn{-@&A(;dEPrN4~-CX2s0Y7aR?#_#P8zrqS1oK)NY z7Qlxozs48GPc{DoR`|029PtYJ9f2t~Qt<-Mf4CVibosXDU)4CG13@c%*a`hN-(vdD z?DQRhDYwS?hh+>uRsTa)_zC=aPabkse|_(MM-G+o z*SN#?I>q1c9XVXaU+WG(-v-~4%lbca32Xm5*MCpC$oTK+;iDZ9H~x#y24CDa?p=o8 zdh_=rCk1?AMtNjFRU z`0)qgt9Fn_sSQ5H&0Nak|K0cGC>ej9yZBew;ET8|ID zug0we;@`s(-&y>FHu$37TF(6U9r^?D%J{W<`U^XX|Fu^5u&?OQ)&4(h zgYW-O{P=e)=nq4##+Ro5svR^CvBH>clvw(W8MFVedq-O6atzkdq&svV@^v%wd6yOQ}IIO_+JC*!Yor@!9{A4nEYWBF%t z{88ZlfE4i24*HGTQX711e`FQ&f99|s$iM{nskT2;7oQUzGW-W}bQUDD~=Mm#nz;9T=kALA|FgoLZ)ed)ucr@|NwJiUZt|Z3kQU6zR z{7y~o|Cez5mki&liI05yt|7)5fM1*@{CpdH^|?J+U0WFE0>1ek_x~t8|5ZEaPsAa9 z?!FerUuAr_8Hi5&li_4R6;%wtez_0m0@juo1Un_iwzZkczXZ}xX-P-sk z;EU%kOxDw1*irm1vcbo3o5}H8v~6u%4fx{u6PoyFM}a4P8+j1yvV;=uo^z=tNh>P2R4Sx92`121{SGP7wqyB&53}3Z_ z_(2=|is9VG0Fg6T>q=-ziJ0%@Y&#t_= zMb>|sp8l#G#1Grxi}-)Y+yB6}hAHFU-%@M*iFObdx1n3C+rK()nQ>BEV=Ca+Z1cu& zi6*{k2l2@&XZX2ywKb;8_*r`EFOuPxPO-)pdHXTbf7<-E#%+Kv#y{8T;R`#$arR4* zL;q(iZfn4jk4F79@ss)Qx4{>A^9l2RX18`mx$OUBJ^zIr#s5+peB^C%{M;Vxj5}oi zHSy7o0#7Pz@YVVEzIpA8I{`oR1t0%3!FM+Q9w@iYKjdwG%Jd&Gxt(#h?Ef8l`lB7y z|Byrfx8B^&xJUNC3BEJ`Yi;nc-I$;A{CljOaUbA|_BTt1glfi8L*|y!S z=mJ=OR=$(3e|t!8{aG^oi#i*ujw-}r>)+rr9RJ|IpXu=i&4%@V;`sly?AZ5H9sdMu zp8p|uhnfDlPqs5EKz~vHHT4&E&=I~3+r+;~`>Sea+z~rAB>cX$|6<&< zg~$KvcE&^Cf9V!p|1|v%N=Ae6{_JKDE8^7~qTc*91Rt{;76Qf4>br zt{XPDGXJ;EZ*Tk;@Wt~7?$R57qaDP>ZG{a!>Sk_Z_%j!@H=Y3e@@+i-HSy67;^H=7 zg%3Na^`Gv4i9Q4Cf5rXZi`~_KVl)0%<2JOqz44?R|0e!Bi+|9{e>ncexS89T{w+Rk zZv^D{Pj?spS{r;dZd-S@H=YLk`t3aan)s?6jDOe$AN?nV%>SirIvCH${@?1(fA1QL z`X}dKJ;Og_Vh3Xm;EVCcZ45uv@rTa}AL5U?nH+!CO&yH6vi=;uvHwfF{s`@$?zkgNf|1R-sb@9Jp z{%7s(WGs~Nr@He$Y=f`XpB4?Bj75Mi>Q57VXZ0sygD>L0oB5yn&(6kT+5ZRJ`5&=q zf2#jWujy>OCi~w6-CWaLGv{ez`mR3WxYvXLm7bWc(g_ z_a9gNK>q_)_^^{W{u#^iZ)QUm11|Y!y#A+}_5Z1kKZCmX-!uGa**V5q8GnvDe2>%o zYn@}jB@d19=lFKxuVng@_blq4tUnLfmXaI;mOMA=e;liSsp{|1#5aFn`Y$=Ds{u=H z8}Z+9r@z+EaShx{7)I*D*qD1pRVd^)XDmv z?k@g5hyJf9=w^H*`+tnP`s264m;L{lxBrrE#wUQEeY%&;+Ye&+spfyF6@G&J+i_(# z<5Ssxj-P7$O&ffi|0E6E|6SdT&jDYIfAaP87j}3Z!A*q~zNEj&@n?S3%?Ja&SbxFs zQ`J9Ug%A4U@h9>fx4WD1g{;4(|Ee9d7qr1g-ORmA|CxU~%J@>&|2TL0*IMCA`jdUU z{$6^Nu~pWeVFv@xw;mh(!spofH!_a5zbm^N^|Jn&_`;5Y@3p~KbsI6UyRl2wUlU)ogEV|L z_^6xtEAzkRuI|Ryvi^T?r@!9@U+DH5!yoc!cjFsbe@%R02OZ~I(+VHD zSa)ML;8$b*ar{)X)DD$7L?qU20_+tFGinV{c@u#qZzQul=JP#Kmoq4Zc{n(vsniY3DWe1HM>)tcfq|ATZzhHStZ3KeLP1H~{$K z_{SxFsSUo`ZpL-<8U*H_#r&rxzG??$Fm3Rw=CSdI*^23Z>p#5)1$+_z-7RD7z%KvL z4&vfAXoD}}#@AmByT)rA0{9~Sn)t#F0`qOi3Lo|n?f-r@{yPEs|10JGpFe*!)%IUe zVNrh)^#9W)d5xCfzo`G3{wIrnt(E_PkNt+3&Ens?T`wa`#{WPs{%A*$pO{wjUkUtQ zk<-h_27HnKn)u25_t>nz!@6a*X8tdIy_eAj@J0R)bXWhpHuxfM+c5mw-t1+x1$>eJ zn)t$w5&)kjzRB^otmtL51AI~cT;dnm;Hz<)yQ-JbUXH&ezG??$D7C>Cx*f{e|CrBu z86H{xU-a@{*g;^vt+2sYd9T>j%jhiouZgePK^j3Dd>l8J?O6WpDCun+CgXec@*nLW zE^b3s_|cu}`SEXihClS5y^X^GzjiO5|Ix%3b`Y3vE3E1d?1S|mzc%;k-o_DtpSLd_ zKh^qQYvq4}@!yQay^S1M|Nidu_pG<>f7H0;w(etelkxN1;rn#)JF@s^eb~o;{S8~jQ+C!n)s?6#E;nEBX6@a^MAx0{f#`?|GDn` z582dTao?On8UE6{`WpiPU$j3>d|?M2=iB@Z7WEJIQR{#1J^hV=fG_Gl$4|BX7g^ya zX#ZJ{^*4@@^{;ZLziESy?bbYu>Azxre`Ao0KTi)I?I`k-fDL~AyYcxyYe9cwFyM>! zuZgePK^{RHe3AbTvHCx5aew1?vj6k-{6{;8i`%d!KJGtmZ-3)>8UI;#_}+~c`JW*F zR^;RwC(8KGxx>$Qh@W**u2CT4Kkp9T=MaC!q+H`<8GnI0{30uS2zp6FeEu&fXhSyx zzPSFSJ6nHPzntBF{McxsP(lvCE0!}W*ypO9*#F>1t4VO*F3`q_+tL$MLm4g4(e~(;H&y)y*AJoF8lwI9=>V^ z@dFO=bK4$m6w3H7yTcFK;0xXU!|HGSV@Dfj1HRwr&F0^C>){JK=s4eoZ17dxvi2Qq zoFn`HtscH=2WfVCC!4JM zpPaS4{&i>LkE+v-HO>e8(nEOsf6~JjcF=LY_1NI6^OiHtKGwJZ@Wu5fn)s?6q~W!} z7xP9vnE%VZZbLrM<5P!ubgN(n+_IImq~jjK9wv ze#i!2Z8!Z+F(};fsPX<6zvklV9=5d3< zC6A5x2i)QNZSb+(ntgcvJ(bcsWqiZk{YSz!__+QK<2CMVO5u|4#^--&;;VMhUc?4p z_}`cLKl{Iw-Xr@@-T7an`}{FZc*J~4@0I=6#82kGS#6#F!v95V{CV42N-JdlHJ`tR zc2IZR25tNo-|NrxANKqq^g$W_R(JY)I$F0sRky6y4xtap`fK8=cF_NP8+_q^F89BE z3;M9^|LyMlFSWr}d1rNNK_8L**Th%tp#K%R_W%-B;rsrpng4kV z|F&yd&_`wc%iZZ;tLr}(Y{aA%^fB3gP5fm3M|9i&0Pg?V7WBWe|986cKYy{c{wnVg zAGM%Q$o^~Mt9CH|iagfsAKRZfko$jZOZt@T|K0BV57^+Vyhohek_Ke|HStwD=zq`# zU-*AC^S|XcE$K|z|9jo}Pi&rlDR>{l@K@|@NuQDZ*Tffg&~d)?TH(V!>iLh`erZW( z0e-{J{QhekKh^Ue`BwNa|A+dMYS#Y_8`O%_5j( z)&HOszU==X7XR5#w4(E6{~vIfe^&Ru1ANRIljDz@--pQ`@(R`|02gL(Vg*NVO%`>%Qb!DRmXt?(20f7`FEXi)Z_sTIDI ze`Y@Of7vxz^d-O-_g{S2UH(uvgjgNe@%R}qsULfR^y)p`Y&6Z zMXP1~Iex18*V_1x^XBI7nf|v8%%-mae(i6(|9ebNf3(xYe;a%;Z+kq$A9GALeI4+{ z{I4dyu%i%&*x=**kIC_O49cc&0KS<2*2G6U3Opf)T8uwo=fHsY^B-FZvgwDz!W;{RWF@z1yNAMkyju=QuicLh9uYMQ+M zyp`Vbk5oHoFLb~4@dxIO$^9R5bv6xw|04f1{YN{9i(8+K{~~Yx!1Uj7Z8m)e@J0S< z;tM+n%(q2W_^?k^ZhZbNDa)oy0AJ)E$H)3J5WZtV-0=K+<$iYlUA2QW{8spK{uS{2 zo1aaW%K7)CyZo!L!N<6n9DmGn*>ss4e@%R}gMQ;SV1qB>b`p>Of^526j=v_pu!F#S z8??fQeF_K0$A8-5Y`Q{@KgY-Q7so{HCRl%=+TrjdWQ8xs|77O>va4Ftm2&(8?&2S@ z!N<6n9DnxJt?4Q`{+jq`2mKaXoAoCmZl^H+M_kvMu9oAki7)I3VD^jG>ii?@;@KO& z{$|v~)^v>=e~xe0{#83j!(-#W=zsYA$Cj;XP2ZE_uX+D5VF!Wv)@Oq+;>Pd4HhWEL zx=xP2Ccdzv;1^lp!@mA~ivAzArti!8EBHslcM|pgsvV?JniSs?yZ$+Q7w>;xV)GB? zlbh*#9iT2;>SgOszG)qQ{TqBO5x%g4z&6`hwnO_@zZZCWGu?wUz4Ye)g&l=J#0DRAGdcdUyW7wYW&Jhr(T)O7 zi0=B6Gr9ivwV@x$`fK7R)8Au-4`j1{iLXCPD%;SH0bh*&6#S#%I|9+EL(1zzQFB7W3~zng7d< zY)7{OzL4*HGTfEB(R|FfC@x8=2` z-^=mm_^HM}Xoa7k{m&ZMp8g=mU(^3&@ekSHi}wFV-v0mIp8h1qKhItK!#4OBHh`oj)?X7}wS)Mii*@}+{mnly{kQ$MJ>4hkKfs;- z`8N1Mw{sZ&jQQ>9FS7oc_`;5Goc-dn!B=(L`doYZtE|5!zG??)1Z?WB(4Vh=TlQ&t zx?k2`bNv_EL0sJW9r{0dZ+lAGN#j3F{AB)@+TaV`=kogZd0 z|Hs~Yz&le^|Nnch0--*khaNy6^w2L&Bkc)2^iYj}c#&c#LI9Ca#ES|B5sd{5NC`bs zFHHhcLXQFxdXN_SMHDXmzsZ?To;&B+**Uw!FTVai9$$Fw+3e1|_j6`uXJ%)2iz@%= zH_bEr6*vEW|6iCt(t+-MzWnr-S^Pmi(cAF{AWfV%qSmQ}tiv z^XWff$-l4L4wV1&m8K2PHdTLN{{3`t;;=FQ_K)lKwe_bBN2cm8%%7)&?4y?ap}(^u zo&Q~@PaB?Ns{X5fKKZaY){Kba#sJZ-A}!u6FR260|8TzHh1~r6@BcbUraw;y`A_)e z?~XtCyzRa#&p#Y<^Y1_Zda^8ko(}SlF5=VvyE|e2rMR0af0u7Nypx;%_^|r^>nW6f z*zs4&FMs#^Gxt-zPL^ziq}jZa2KQn}5Ij z3G?r#gMz1Q%`gA%KCJ!kEdQh7S?6}gUr(v>zrO7K%RHSv#*zN@uTWi{?lY(ZQXBqg zIO66%dAz#+zA?|=`}t>{4)Tv1^2hIA+AkIOe^G%|ZdlD($35}r8dT3<+vBS_3!E_2 zUE=1Pe1iKPw5t!fs%xDa-R-V%o6O$!(zUcb;coAyGr1-8mta#jt>!E^W&iZ`w0}-* zZ>e-)-DNesf2G@~z4)T6!sxe2_xBfNIZw7kJYSUMJVh0+FUo>vftOcs*6Ehh zZ>aZXC|mEW&@0bhaewNT<7W<7v0JpAf4bWdaOQWnSB|3c3R`ry zujlTK{R`8moL1cJ-Ez+Vy?Xb`J)ZocbRC6FHCFblUq`yzyY(o!AU$^g>)gL`k0){X zuDyB)yP3N^GlggL3gU0O+q*odSFosGUsRlsFLat~x_A3iPkXmN?e2E>VCawbXSOXV zoy0e&9fNhY@@{|PYCCj+ooo8)p6y{hy}D<-+THD*Jd{r9YKjM}v(@UJ?O|MP2L~+T zl~?uai?WE9Q;SlY=my{y?#46lLv+60_5)^hoLAjS_Fk`c;YW8KVb3Rq>+XL=Y${*b z`>Xl9+c9(h#kXFzcf?%Xz;^#C&D%?_>vsRm;{JEnDUQ?oy|;z_5Bi{7eNh%j;Q6Ai zTgaF5d{N~F`Enj`eo>b5fb)y8;OUn4ZhPW>dZc%qI{I65o$7Ay)`8@?)c(VExA(3W zM=sr~FG*!-|L*_m|GHan{p$XbTa>O}-R)l2uWgoJ*0Viy63h15LtGbOZV`V(E(U{fnD+shZt#lh;joKxG~L$rU}tgxy#&x)&hw$JhIb~lCY`E{@R zxL$1OZtwCmucG!Dwz$%&eV*?A?Q7KaUu{Rb42$~yMU@-m3z7OfXHx$#{{>mjQ&${c zlm$<>989fWv*z^rmAdfYUjGWVyMMQwI1_3fSlRCOS$d_a`{Rs%-R)EBS8Egh`h|Fv z)b;&~vN!|qjH>a@7iBq5T9uzK%5t7Bs-J;;!Slvf*79r*E3>TS*&f!r+ueh^<#cL$ z_#bzBx17grr1lWD5?RZ$zgkz@6Sq?P2>ZarYkTq(FIl_C(^BIX*h+W12hW4<_AXDn zNj$K{%hvAkly0MZVJm7oIAHIo#)i7%!CH;3kFf1aVnf~ejpoze@6~tM;Y(vfnJGN! zG98z5w|B>b(5>|h9d~|j{~7Znso&84&SkNo1>OBychG*Y)34ZOxXTk?gT{lfxhuCB z?(!i0qt9HecS$_a-9D9Pd^0+(?r!h$6jnLB#}7NpRo(q(@I*IP`@7q_Jmt-4f7sUT z3v2yscb9?u>z+rLe?Q;Nd;FE!-Fy6%>uz^5f^N9J|IFRqEkCJisQkb>dm6@HYCEp$ zu-`c>JKX&*`_5-4Y<75dcz0!IJ0d&W{clg#-}K1r@ZPR{(Y5<1`z>X2%3kz?>~QzL ztB<1poMW=Xz5l|9q|P_wp`M3@jaTN!vHz*^gOdw;J~*D+u<1p1`BERQS{frHNaGvPVif8zB=UJDhF(95vAEb>%nK&;}uq)WWe?i`jiyUoCmHnw7JXEW;{6mp!!sV`pifle+|aEMJv?5 z@~&TA-~EKcd_w*Xs@JXC$&TDfwsbGq$p+c%{bZ|kvdMeMChjAfd5COB+2X_G$C_j# ze zs-NiZcW|D4aClqy{VM%`>(cvG@P32&-ARS1{X<86U#q|W=lmn=`Ixc|o8IU?|6Aq9 zjn`0j;%o9#JzgiR*c?8}jaPFGH4lFoiPmCBhF^5`iEcpgs=MoQx_yD>Su~Cs8d_WHKiALnA73Rm_W!*X zB=`S%JZ@#cduVb$A)d?jX$`;Z@-#NodHUl)#$y`~7DDp0eo5ogD-LZ9zvA-5HyR92 zNyyWEZ%A*L^~>34K199O%6XgWlcU}<<-Du>|0w&uvL7k?fwG?{`b0*C*!@k_xKIC+6ru*HnFVC6M)@zl2s^ULas&`+b@DAPAfZgWG^@h6XV_hb! zQ(MpT{zbgI-QB-?J?P!PewOY(On0|;)4{qZ*wmlb>)og5wz=K?abF{+w&T79>;tQf zc=8mJBc42!?sgBJ``ztbp2}mS8*FOL5pN!~9UQQ8EwzCsPd&bYCr`V(-GgWDr74}t zwTegC`Z61M^0d`<=$t+v-@6Yp{Z=Z^rEgIAfzAEJyF8!hZuh*u<8JpV&$HZSxWD6W zU(h`-+}DA{{fpJz`w-px7fEGt|6)zo@7}*yTivHvN7;3iT~FCT-M@Hjf!&8sTXomr z`fBvw%dYMIS6`j}n>D%XaQDBq`Y*o5uEX8`rmO$zDd)EvNeByZ*QIdEjyH`^&{Ayzehpy4&3o>XwhG>m?p^xA(4J?0Qjr%KQFu zMQz7@W!Qt?^1i;uC%muksqXeEJZ*J-A9c5PdGOo?Z1ElM>w86Q$8{9;^l$FoOK0p@ zx(>poHr?I5o;uD~ln$vQY28%L-M-!wp6bT5-l^zrpSoTmelT4h&r|!OztK+9{%v=A z_xd%PO8?v=D1F!M{R>+^aXhzS)9d!1-P>;NgPC(u|M{T^*+-RKPW6LVQg$_E*Hl)` zGdOCz$hm_0e7w^u{75GwtFBSOzqXG-5lS;m$-)}3a`<+#G-*cPZz-d}<(WdX(%LLejh;nkv(8B8t?HRln+jaeNW1y=XOHQ%z3(=+~+t| zA!mP`nM%OKneRS)=*)&JsO`O{c z^{kw)>&bo2k$6K^KC`drx|ldKLeBJ`bWZMb&Vq%r`&?;vu$^6RB`r?456bU*?%?j5 za^`c~sRZA())S1A`<&C}Bkufr7A8G+6zW;NK-ZJ|oGUsitMAf!w3CoCb)nA5ea@Ma zatiCw&O*)(CoOU8L*Dea}pNHllpignIr~sOQMV zIw$uzQYtst^0}*!v&}fU&p9U!6mkmn+)cb}%IhzN`%BS>tw5O1>sW>N#6eswc4}SXK!E){;SlvYbUd2|25bllu(Q8U4;+<9?8kGjqMJC-*sL zTgWMm`@uraNyf>2&RIM_rl&OShX^?@hZz2nS_4- zB|Q%l>RGy3FAv-YKWyf}VC6G;9+d|?Kgpk$yq=X$kS~02HUe@+kPx$`dGB$T)4eZKw3ScvyUV{){Tn_%@F#Em z8lTehc5P*Wh5FuJP``g<>W5t4T`)Z5z9G`#Hu)F5d~%=fU&sV2pY;pqJnO%r^U9r} zKTmjLFYZJA_Otb--XBE%EybCr6EA$kee5F2C!zA2xX@eQ`gdqM^o%bi)AI(Qo=wFE z?&58_zSs_%+F`JI-b8v@+fV2R4)~u}&xTOX@sN6QeZdbqYS9z-VOx*raWU2R2dKU~ zw)$SUozkoQlgclAa0Rs}pSiE;^}$r%Zxrg8|Eqr9@jG;%b4GUbFQ0hN2--UwZ>sON zQ2Dg#*-%`uJBbfI(&u(Gt=D7zJM@&cpErfnlk3Yll0rSlZq?&r((~4UdV*(AdP>{R zn}vFg-o?&a#UI?D=qa7|epIMu<7xf+=G>?2%ei8Edh6M)(t0*<^73Q4Zr&!W z@9o!h&g{MZoaLSTubbeM>iPG8de%^%Lh1?K!70`AcA=h=`0l34sA}OH+u2{we!q^5 zXH4zVo!#~`ZeL%=zw2olpFl60g`T`Vn#$)LA@$_?a;}}c$1!Yb@ddiSH%1n zzSjvK=?ArlyOi^8Vcfw7p3lpPxJ$1`cM9V^!M>l$eelDM@9JNVz}ebC|1PAdeBLGG z?5KGqaFieNZ$Bfu`E$}&ijdk2YnlgZ^xDrE^R%U=cmA0FYODD$KEH%{Ea^NL^i1p| z)AR0-dUAbdC_;ZFEqbCJ;rwyDslMMUtnbhn-$#Xy^n+UHDIIs*Bh)j=<^x9XU04HP zJnLURgX(#ouw8IUAPyT;P=ULmm|B*%;EV!|}&;Zq8ZRW3YN2A=I`{08uCuQX`EquP? zcp+!*XWu`$;kPpM5^L#yGhTKG@<3 zGCig1X-^VzW}nsdw4Z#MkhAiUpVrbFPfDaJPOR#dLjtMcAL8V4U3NoUxXS)3(k(cMYYp!f-bSdppmccQ3!7>&rQ% z&%aCCrJo7oo_bN|;y&k0MP=7bX@CCbLe3837j+whl0+o+}@Hn|R^3 zJ|Q3Zq;9A6fcTyt!*MD{>FejE?NUXk=S(-@P=|qqkK(n#;|=@BNCocZjc;p!-Ph5&wQZ>U)@@cX_X`b&l5SkyOto0_q99 z!s>~2l|k1hKk0Hx)`MYvaun-*+4|)1fa{Zkay}K1v!==?xS?;R>K$j(I%?i7)t{l` z$A_t0NA}g9lbWk{Vnfz;sk)Yae-l2|35>TXpM=V9;#qI*_71e2vc*}>u%>$Sv`|m< z6Z2cpItKX2p<~c9`WfjGzi&u;k77{HX999o|4sFta~3c0*3Xv{CppEM^n6yxiSn3z zSGD)79>p&8<}{Vhpn5(hJ{GHb;EPJINmXE z{*ySZ?Gm`UXVv`&ADmIeCFSguPdA-LTfbjyiu(%`_oA&|m->Ko>_NK!$9-()wyE9^ z5M$4`;`um!->_DucC4r@(tDBgbjI8besS+GPVOT;SlfB<^4YkS%86+`?Mpq*8S80H z>-(^-u>BF~3LkMtK1r2d{RZ#yS^NQQ56by6aazkKxS$t&a3&Pje~Yuj^aKaD;2JUL zIWbN;h2@OjM8})@A+J*TtlR3**vAy_q#9qshn~o1>_*Bjb2C|fzHLL?alDE1HR80! z9bCv4J~+pf9$`77bviG6f0uu6_jRG37^f#bBVFNx6Zzz>qx>58c^$$! zIgL65*6UI6Q{wB4P(KttIIAyHJ{gr?>;(hoj;Da6co&P)oIHl`;9}?cz=Id0s4?ft2aGk2{zIORJI^PY1aqm2; z$2~vnANS4&gN^$I!nnu2qH}Q{I>NSuahI-7epndy+^jlhopFN?w(@sb`Lx|fC|^P8 zEG~>Yf1mg0S9Nai!4CTU-ggM&9-T$!;y(EL_EMRi();fh3OUCaC-?h&>W`}M{h!iy zsTs0-^76_#Yp==lw3W|}DxXV)ET56t^m4#CrR7r^_ltyauQ4v}bI#7bGCig3(%*z} z&&;9gmyPH?=Nwo42fiIXuAA2TM=#U)ri5{y>3bcs`*TXa-y!YST`Y`ym2q(&I>Bay z?O79_sc>(`8wZ@g)=JD z)7CB(|4e!=Bh<70E<5jO{(7cAmFX$H9^ENymqwyG7xxh#*wme}@+s{vT_)sgGfwV< z4>lrvK2G|6n|}z)XKOxP&#`%RAAGR!$7Fii%4b!T&t*fF&m`jpAFQ-|O5bnuct}0D zzTksR4@l2QhvKrSP)~k6D$eg8cj@&=T92*})}zD%Iv4k$BkcHj{^c{G-Hpdlj$>-) zzw7Q2ai*QvomTGN=PK^0x06Vr$vDT^^P%Yj_3v8ZxY8$df32=8wu{Fd>VTH8eC8L{ z^(-u?`^X=*JfQMfeUsv{jj()1-q&@GFXYeJ5nhj^+==0r+53@5nf9?fi&({%Cn&+73k$jGQD9gp4~c2jGLv4Jhst*HT816!XO_}^qzBs?ke;P!)PC+I)U)!DuIHqMGt;K@!Od;Z z{?fI=dQ^$)`f;CgG%uIccWK<83mJD_4mhXtxQx@*uWMdU>8v7*JD*>gVC9u_O2_Zg z_VYSn+{?@8apykgY;Pj#*Gc2v7RJ53oX(kAR`)q)VnA_^-#~F+HDug77EWp0rTwK_ zg>f%^P1le6T+g;;o&oKWw0vGKA2&CkmZw?SMb4>-}2|=>ysxNs@xdL=Q~tBt?Sa`D^r~7 ztCEF}^}om`r}9hO=e<7J$)OBEG(b=y%7z?4gI*y$7J^nrRDQRVfoCj zqSqVlbIwV1e~NF1kME)I`fhp-JTmx->fbH-Hsk#A5Nw0!x@wOmRKA=$r`n~Uoc|VH-@%1^;e*q; zoAi)!27Qh%;vOLR{$^wiy*zRs{M_O>zU*51^VfKekH6={^t|DFq^DzxdyR2&pYu(e zs=s%E{|-)mpVajH=Ir!bkM()O?3%is+~*uNy?OhYe3HtIiE|F(v_5|{wjpsQHzErk z&-Ij^rhKC6Ii%cEDqnU2MfLnU=d?YiKc|or&*eLKu3SC056=JgbNU~-dqP3gBD zCEHfK)knO!>#F?>%J~U#TE|D=f`0H3_n@4;;^rnMeGYnV_W()U)9aFs;N(8GbBp$K z+|YjVcFFYo<~&r7tnJbSYtXG%R62_JDEZBah? z$Hl(~n%bqW zx(CFad5gB|JNgUp&FMWS@cS7&;T`9iY6o*S>-`XnH>KmahHxA=vVmUTx!>m%{?XIZ zV_%b=vk3LXIHvVY(i1+iDjW37C_P8n^@Z1WTR&u0Dk$Q9h@-CSydQ#m!uCUOys5u5 z8*y6e5xAfqeAJ_c>X%75gO<;mgyplP`g7pqKDNWAPWGQ)3d(u2kh8e4UXQpBKG>F8 z#|59;pq#e|ITK&kIl0d{#{MYNQ+ogCK_O?8adMw?M(&bvO54xB2ssPi(Dmd#=gbM$ zgGu$gO~@Hf>73l>oZ}bC^ptWwB;;%`PVRHgq%iJM&bp8@|4m&_?sLw}jf2(mb|GhM z6P=U$oO9$787IH~@_9w1`>>Fc-#4r?Zlnh*y>BRu`(K5eqnqk_avyxK&ALoaDd$~` zv$>PbgM6c#>D#%F{iGJxBWc|K&Nxl^j4RH`v*~?a@J;*2@0RIld#)Vm-y`JAZLaId zeWWL~&{G=sdxe~lEp$%qbG}jG^ITF+_w|hKKl^)MYmAfooUAo=qVqZ|AwsFrBRM`Yz@Cn~*cJCB;2@9JNdE zIUoF{h12wX*a?T)v%0cKul&{SU-tLDPAX0uH+rM~Uc}K`=sBtA=41<-c|SLW+shUt`kTdt=FTL3lF}ZCJKlGU<4pDaaiN|g+v}X%M?SDE zp`Nz(v!9-jleeF3#*Oq~2i1O7H>7rc17Y0xcO1qty1w9pP0u&j_1;el^-S)db8#Ph zu<`r->pRx5R9Dc~$C%bH9qsBl?Cfn_zr^21!k-fapVXorN!!n7g?biu)b->(=c_$1 zSUn3N_2l|;PMbeRcL!G^KE5`s4|&erSMq%XKCb7!jf?+|xJ$>yZDHICJL_@hKIce0 z=pXk!r{#K7-iX?zjfL$J|BiZm7oD4PO24aaYv=2V^Xnlw8w28$jyGQr#y!8Qt{?Zg zo&{mt`8pHR_5DR5XKXi}llz=AqTZXtx5G#Il(wJ82;<(|TJLw)88`BWjm+-<95meq z#NIQkNzbY~-gMu~(OWLyx84TtvoF6vyzr63_^jUJ%lbWZKRc%^_V01Jj&vQ%yzT*# zbu7`{^|*5%`E!ePEU~rq`|qapb*A@G&!++~=4Rlh=Q!i!KIgNYN6_;5ny?<__R#g@ zKIa^N$iJQE_upHusPzzr?@i24dRp(lNA@Jn>|SKy1m($t};&UBR$ysulzZAJ#yZl@@(pVF5Kgs&svW%`;eaL99j5?d+sgDXY_Tl z$v3_0k+TzRhn~E@ZMq))NO;|xRGiR@``8XU(UQ$C+4^;b7wGyM8SbWRk9#bqj|(f` zV&xTpLK`&hF^apjz9Y`Sfd6^pZX0*hXQSs(CWQ5Ud~I3>2F?jpPT_Og+{=HS!8Cq1 z)uR*K@;T(}<>0xV55rN^!TYr%mlkT$zjLJmBLz zxXnN6e;%msl@)beczus0sUH1H829SKdU_qj&H3OrC;jVtgckB*_r5i)S6s~1Q?mZE zv>)lyR_iNydop>OcR$&*UNLC-EVA<1vXsxp2=(VtUi(4>`~z{f)%Ve3=(;wSu>FiY zL*JJHPFvM0_}rG(@~`hfrs7zuKN}B-Nq8Tzqv%OU9x}YuBEt|qr?Xv*Q5BmluttCH}Q^lKP0F6 zA=A`d2Ck>6{XCJ?qu2)eI300B{ek~^+j+#DmmePY$z!P=%_FQw?Tht#lu){Yo7;&4 z{p(TCxGza@xAsF2XYjxe8+YiLUP&+aT+hbZRFB>h)}u^QPp@#Ge?6MC)T5p}?nz7M zLzZ$6kj#g~zo&C?A3Af3`H+%uKEzbt;}mymKcvApxzG7*=YhCachT!Dk9&GOiu

Rgq(!Nri_1~5AHGB2U3Q$wg5?{%iw{lUz|0QWHmT_^Nv zs{RB?Ev~&)H3(z=QTyvoGu8U8#@rJ%=9ZlPiE8%N)$Zv`d_5Veag{BxF2DwW%v@qy zO~fvu5Bm019ZVGlKnF*&Ym^yjvg~xOfJ5YdNV+&?yoNgvBJD>|peDhOlwQK>%t~LP#odSsZ^bi4LQ+Dtnhap8kzdI|N-_UEeYO({)A97YX zE->N)`lQ-9Oxn>Qq47H6Dj-{vj}3(5HxltX>>GDf+7WiPM@` zr=LR6$z4AHgdI@XiN`s1196&DTv`N#K=J8^`}g#hgILC@gY?IWfEqjeVTzVtWQCx| zhq&PywqOU22M+!sEt&r0*Kd0`_M(q+WdwXds}xiPiVsUM53KK zSFlk;#z6arBS7b4>;Pi|b5F4Kb7=FRic@Ko*A>7CwTx?7Iz!XqCP8?{%TppQPu(+W z1nj9{RVu0i{vVbfDh#)=MmH|XycVKr0YH*{D)&Se z!DK}MlloIQjxGxBn~BB}P}Q)d4wtXAKx0q`=>Nf!>$>%3t*8rUe6mTNklmQ9_yp$ z9)17xbjWQI&UrwVQz&FXkcM&0faijsI$;;*VHhl~^nv~w_D+aOo??;2=a?Lb)KSUI0xT@?z2KfN~*0#B@vyDrBXhu4JhJ z5{@C(aL|H(a%G}>%9`7|vFi3th~UnNY-$vgNe|@cV@CJ^-TuzQ$gPpW{f6*CZrPsb zMfl@hk3JZXkcqR}X?4IKbqbX~m^%3*DTv?|Hq!lRp4w=DsS4_8UHW^Y1li5u4-%BU z9DE=Uy;FYKm_!T9tW;$V{z(dY1heE{T)tAy{HVlNbAq2UesD-+MY?hL2iBJSqwNVE zEdLlAE2s*+G0@)=h|Ymnayy_n89*+>;{%H+KCtNGgE!*g$=mesfZ2ld0&%I)jw4G? za~J<1;PG&9#;k|~<#G;QnGm_JO0XE5>=-UMuUz(Sb`nSCCCko@_5zU>pLAgGmV1{D zUvxW{36X*c{K92}>Xs^yivHDtOa&;i+zK&d_fWnl;p@?H*F zmIkI(o)Vs(@<@YBoChu^53bS?XcC%dwWD)WH6H%)!q(`rOI|#>K0Acuq!0As(gGV< zy6%rpI~)&i(yuhM3U*d-h-4w&Shq729{hxiuxehz$aOi$;s`5qY^K)mcg&wt`B7(& zZvG6xk89Kfh)FUXnB73Y?km>4otoZ*=pKlxx~Up+j6Y~j`Qxssg&X4sbxZ9M0c2Hn zT<{rZu`Ey7mmz_+rQ@@6*(`8Rv@u+g19^aPK=Sm4%ca>e+HgR9k9(p$yos563dLy` zvBXyu;&@oEjfZpi3m0R_O;ZVB)H+7dq7Wn$e(Mz{^XUuKsQ#ix^u|T(g4A%h4jNgM z_M*T^Q-rv{exN*Pxm%N|m_IYl7Dyh?GGGR>pjcYR)oR&7kEM zBg#Ed$>PFza!*e|oeD)X3F2B-0+r#;emYoBd)sL>lBT_KEm%H#>t!)zuT5Y*CwI!w zR`nQAWi~j_qmJ<4Jr(#x0{w@59POTAApj_9Vn%LF2jKNrcw&A*aCAvz4-Y@%UHJWa zZ|7X|*H-x3$x4go+Qk4(=k1(pUXSChwFpMeHE-Swhfa#l#L?gG5Ved zRqYD*&!BHOT{;do)Of%Fi|DKCSJkd-xb2a5Jo08o+~>$!9C>#mZfxW|jl7)^_np-E z?|-^~bU%YXQ~td@KZ(Ks&&1!eZ34gd?zP%~tx(HQe`m^N(EsK7Uo}wH!0+9A@Liw% z8MWH%eSLbL*FEb%=pKjXU8RQ(_ez65#o*W7mvln-HyHfm2LFWOXZaVt+4#TJ;NLX( zcMSeLga5$bKQ{PJ4gPb3|I*;M8T_{f*It>H|5*mVi^1=1@Ov5j-Ui<^xMA>ZgP$~b z+u&Ci?AyUV_l^I7!A}`{*Wh~w`*i*DzVZKLgA0R)22TvWGWgYs{p)J4HTbg({u~qk z^9=q1gTKh&*BSfjp0vykzhT4Sun~ zy9PH6e#+qc27j`_g~5jgcMLu?_@TjlgFnmQ&oTJ(4E_Sep;^Aj;IB9Mn+*PDgTK|_ zZ&w`Vm+vt6I}HvQagOgY{;xCm^#=c#!EZ3wrvFCc|0aWf(%`ok{L==%)!<(@_%{sx zO@n{S;NLa)_YM9-ga63jKQ`Ew|4)qn|7Y-@8vJJl|5t-;`hRZx|H9z^X7FDc{8tA5 zwZU&Q_-_pU?*{*^;*ibRPfq2id4m@XUNQJZ2EWwcn+7)wzO6Wnk4=MLZt#-^ZyVe) zxNUI9;A4YN41QqnnZf6ZLw$}6zA*UO#DA5+uQvEK27kK2uQm8H4E|n&zu({=H28-N z{!xQpZ}1xpev`pJY4BSN{uzUR&fs4#_?Ha+6@!1x;6F3?FAV-Gga5|h|6%Y)d`c=W ze6+zIYw*Vz{J6oh2G1M3Xz+@`FEaS028WL69DByUY4E&27iKyf79TG!M6>5(%@}_U!geUXW!tv2EWqaPciu1;E}->245Te z8pUCL{tV;)r3Qbw!Cz(Ke~rOkXYltJ{Cx)hfWbdx@Q)b$GY0>h!M|YeFB$wR2LGDD zziIIA82oz%|AE1OZ1DRQX@C6y#i2iZu)!Z<@N*5GHF)0OMT1uiev!d1RUG=mO@kW- z-!}M3gSQQC8QeDb#NY=8pBem_27k7}pKI{v8~lX^f3d;eYw-6Q{DTJnu)#lS@aqkJ zqrq=7_$Lj1i^0Ec@NXIXy9WQh!GCD*pBVhiPfPpjvkZPGgWuWUcQg1s4Su%4s|K$d zd`oc{FE2Ovj={Soe$(Km48CvhCmUQCJT!P>@Rh-@Hu$v$e~H0gX7E=U{M813t-;@I z@V_Vx4gL=X|3`y=*5IEv_!kZSWrKg!;6GIy+V{^5{!4@3X7JxC4*ctVT511% ze}g~B;O8g~@Bc94|2*S=)8K}|w+(($ame4c!7YQ^2A>%GKyk?LnZciF!hg2$|6Jq$ z`38TX!C!3fHyZq}4E`2_zfE!2U-?eOA^)#8{%=&wT}k=(CgcB;#{VtG|JRNGZyEpJ zHTd^U_&+rMf1=oDr}oT4>0hBd@2oiF_uY*Ddnyj`pKbi>1}_-AWbg|OezCzXGkDG5 z4TCog-ZFT{;Gw}2#i9IH#{bm@zt-R{G5E_2{z`+t+TgD>_;m)q!QdZP9P;}U#{bO* zzg2MjP#~S=`20w1_%M4yq9P+KJ?vB6(&@HZ$9{o!94{I5;;Z!!Mg zX8gb1;O{W_I}QFWgI{Ox>ka-fgWq8A8x;qB{U+o8pA?7k{*>{5v%zmM_@@nitK!hV z{>=FQg~9*L;J-BZuMGZcgWqQG-x&Pg4gOn$|A*p`-}mXH^7X~TRGzss_}btrgI{Iv zs||jQ!JlsMYYqMkgC_=mror#0~27j5sUvBVM82pt6f0e=i%;2v!_-hRQ=LUbR!Cz59jT92llu0vKX9gGoW`GF; zVPYLScI?=(W7}odve>bs>ngSt``FpFu~ydlKj)s`8D^d##JcL<`Q+uxx#!mN?z`{a z`|f@3MVI`NOMclUzv7Z#b;)s;{F+OC-6g-_lHYX6Z@J{RUGh6FxyL2{(;~v%q4H{l6P>)SuS};m%Nip&UVSeUGfN*Jklla?2<>h zos@k#OJ44h4|U0hyW}HX@}FJu%`W+` zF8Owse3wh^aLM<(e412cX zU@;g58^IQ^9qa;oKxb2lF9Y;|g`gjdf=ys6*a3EfyDc}I-8^Xpa(1j{a_Sq0$afjup8_J)3!kQ!936lR)8_E z8EgYP!8q6lrf-SzgZW@F7zP``7O)-c0<}I`S_@bUSPNJS{Jt#EbgSGa+QB%O_E&ND zfW=@8Yz4c(J}|Rg!WDvHuo>(Cd%*PD#D5;>2OGgQup4x47ysFy7mR`}U?mk(8Fx$l+7{*89#s2>q2CeiBV76) zoBxWtB>jyL@20N!JD}ej?pwL^>CmUceZ(kF%JubQ^Jl|b3;a)80QaZuaDV#Lb$|Mw zwv8>kwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvN zwScw2@5%yc_saT(-&LV(VXOtL1*`>r2NvkNP1@%NHy&-)g-!c<`1e{L=Dl6Qe{;)8 zCft)v-*0_c#a|@+Kd^4*XYqQCOE&N0@)^gwSOn{TSC9atx``_@2(%~yYxRiXA&~=X35{%N6Pgz zYJm7>;QS4g-uyxI2M(Z*BK_ho#~8af&(x*ZN7Gw8KzP+h2GJirh+g9vh=Y}Xpm2k^ zyU+g(f0p&(VvNB;ue$z=D|TFAl(Adn{O`2?SfgLPO4hk+{p*H)!g|tf9zIL_seaXS zuwtKGIR9Ui9AnZy{^r#BpN;e@o|b&Q?rOg>(SDwe^P9D=)T2cH+N6A^Zkuc3f56o~ z=c9c*4dHuS@i#-?41MnLE53i6Fi8D6V-Wp{t>ZYw$p1!H%K3YF#&M<`=06G)zg5at z{;0HX7rE@$^jFbmBK_+gNxi=Epnu{q34f(4d=KXu- zW2zr0ytZEhg;)K5yZknNYXNHkYXNHkYXNHkYXNHkYXNJ4U(N!4j6Wjl%e?BnJIefw zjxT<>oY<6phy~Jbl<{N3|LtT>S^X|@9(8`Y0{Rc}{9@>VBaA=QcR;^A!cSi;^UJEw z!2I&(2!BDPJO@yHE1r*>^N`HDotZD=R~=s#;`z%5n7^4cCsiLiNAiE^kvS$`Z$%}2 zTmODYZLnc}X$uTie=}~9`u*a`GB5wpr>X6082b01AG;uRezp_(C!k-eEOq{;1J4g1 zub27VS6%bdgW016*XKtF*Z$S_dp4*d)0>{#5rD_w(7u zvwqt6f2{4Icz&(V2mZMKI8*dhE`Nu#U%TS@!k#6m&!3B-_dq`$)cb!M^b_Ge8PwPTzhPM{57O)nu7O)nu7Wj2qpsRjMC!Mm^0y@h?4nxjY_f^b(FT%UMdmAKP zxBFmn(?1-Ozrp-jy|sX~fVIH?ngtqf+3A0}eax7Xol^d`I=Rop!1yU5ci*vz@#nvH zh+$mylf~T&d9eE9AK?C`;qo7n_`|14x*qt?{EN7&zyDcwuPNv28So$A3!ob2C6}!3 z$~g3|gKvUwgFWECKqpPoT@73dTmxJe)cD=}Kj=3c#GgBym8}JS%NAIBeYtMd1Jl8c zKrP!QxGpllEx~Pm;_GE7()|OtCb$FA84lLqx{rX%z~$h@U<-H!cr|z}cmwz+@Gsyk zU^{pRcsF=2_yG7Y_$c@o_&C@FJ_V{>e<^MSJ7$78U@kZw%mXKZyMda|Js{`1+*Lmq zry$(49~gc*!WDvhfiuC`pckAEE(8~W`+~3FeC!YTK+p#Uz)~;>E(R;XC14dem>sO% zTEJSsTEJSsT3}TyP=ou*Qt)!{3h+wsD)4IX8n6|-7Q7C;9=rj(5&R?gC$J6tGk7m} zA9z3b0QeyI5cn|I2|fZo3jPgz4E#IzIQRtE1wI8n1O5Yi4tySb5p4T|^mG3L-VELf zwu85WcY=3=9pHW78{nJZTj1N^J75p^Pw-#hyWpyv``?0}_fVeq!4JR>!Cvs+;K$&n z;OF3fz%RkC!EeDKt7DuGt`4pVt_7|Gt_S`fxB<8kxG}g1xGA_9m;r7MZUJryZUt@) zZUb%$W`f&+!@%vqao{fC1TYVr2u=cb1$P5?2loK?1oOek;1qBwI1O9~E&}%h4*(AW z{a^{W39hRQung|yU)wwulD-!yk#i z=q9P|8gI`%qK{o5Y(GZ)#h%HM{HRATBW;9nZ=RVNU+-5EUcGm3DRTEt;;-YVRR8JE ziQKb(s=J0y-*l%HrmuQs*WoJ;ull?vS6mL&e_uvt%6aQNa^>kZKc1Ry`W7qquleXc zG}WK~*i>2l{o0xRf}H=}yM)bKh~0`eU$yi4YcF5sZc>ieL}AAs!u)KxKKcqo&Rk#0 zot7c;K;>$FC{^E6lqxqDitL}9>h6xOVp!^Rn7+2;NBy;&DD|n&Bk>eJBK5TOQDOY= zqHo+_#r3Z1$yE0|N8-;`_ZL(3olmFAnh!Ud9ut4v>!+5_E%!bm{+e@B{b_ui8>YH< zJRs%D*jn-#yC?O!)NrfH%rzvQ%=;uBW%p*Oc6P^CxbDjB5WiQ>TXCBB>lr8I=vYnU z%;#2~@75Dilf26RG~)`5j1Z$&q-o(^KPDIq$Spi??x%l(%q$mD_Eg zd{}pDf!~t_@`t9j+nEoi%39WrMJv9(+WrpzPY63cm-~)}^FJo;u?JQhullpJ7O)mr zbql0zwc_h>)noX1e0I-Dy+3zg-1hUN)*ox*%+z%IHTExS0c!zk0c!zk0c!zkfm924 zw?w~Ti(gm&q4&WR=ci&5anGJ3>;h9uWhH9?YXNJ4U!Mi^xtu&oKI=`*+ z$2!le&kJ-uUgy_!9$e>{S9L!4*JmMDj__P#pm}(;n=90RP4xU*=KtE?6sChJ``;4x zwzq|8Su!u^{b#EGH0X=p5%)gmHN5II9`&be?U8UAuZGwBXn422btlPB%Wz@g2x0!t z!r1=8=77w1pf}AFJ4dNt_MZ#o-6)49uYZXl*r8|3&Wk_{$D$BKU2ba z#Zs;|oagvxk@G-zvfZ9kJEWf?ayyuDQmWn^elR)xZxY^f|Bs7juyj^cul1?5T=J8d zC-ru~@Ti||ea56g!np(d+T`okGV3nls4q>6ejVrM*JdW0pP$D99T`JY*8Rla`(fX` zjcYvb|FG}_l`bP7-}}uRD;&t5b^nc8;Fh&h>)*ptfBawzmFQG6R`Ac@?cn|3W8e$m+h8yFHMrIq z65mGPrr_q_R^Yba4xk6z4J-ur0R!O4;Mw5C;ML%tz*|AJ!)=gn2k!vy1n&aX|J{)9 z1s??e1^yfS9Q+zwZA~eE8n_O)KDYt6F}NF82rdBqUWzqJ~$Pe4i(F8woSO>ix69dHA1GjMBgTW~v2)87H|PT+8GBsdCG|6?HMfVto<-~@0Y zxGT6jxF4W0`&gBO4;;LYIe;GN*zU!95NHw5k#I0hUK?gq{W z_W}0<4+Q;SDOdqkgLU8`U<^D5Yz8j`F99zDZw7A%JHUs)$H1q+Zt!LB4X_9N5L|sd z-1otC!1cimz++IajskT7 z*bd$eJ^(%nc7gu@UjknTd%zFCPrxaP0nP#!fct@d zupA75wO~CM1rG&}0FMGs1WyOg0WSnwz?;BZz;^Hs@NV!)a4z@~cnjLoJHUIv2fFB+z}iO?hK9r$AZ(rB5)=+2b>Eo0QUz2 z;9{@}jDRPACxNGeP2gGJ72plvE#TeY!{F0k9Q+sf8Mqqy_5TNs1}A~j!3CfXTntu$ z5pX$pBzQb{I@k1C9lA z!ExYtZ~~YIP6Q``yMnucvq3Mo4|o805LgNZ!Np)DxCA^5JQ_S1JPkYpJR3X@ya2oy zYyqzTuLiFL+rXQ^TflbkUhom{G4KiSDezhFpWuh!C*Xg;Z@|^iFJ2p57hE4q2R8&W zz-_=C!6I-DI2T+5?hE?BAXpAof=j?^a4C2kcrth@csh6ncpi8$coq0p@GkIv@DcC{ z@SorZ;3wc0;8)-`po4zI5O65C8n`;R4!8lh5x6&#&jDm-Nhk-|cG4MFB7WHi``n7eCBVawa3~T_S;BxQ~ za4C2=cmmRC1Wy7_1y2Xh0M7!?0j~vb0NcQu!P~&QzD38j=Kt3Kk5nKo1*8|hRjlfO8EO19~Comfv0qzWr0!M=$Fc;hf91l(aCxW|z zyMtcb7x#ob8Jr3hfHS}%aBpxHI0u{y&IcEQi@<%s{lNo49~b~j!63L8tOS>URbUOc z6pVoNU;}svcsO_$cn{bC-UmJaJ_vS#kAjbZPk>K?PlL~b&w6=1D{tt?%yv#eg%w!uY+%bZ-Z|j+&>||3%(Eb zf**q$W1PJSxEZ)PxFxtXxGlIHxILH!?gS18M}nikF<=gu3+@6=0Q0~};BMd^U_Lkn zoCfNB>HBi}j|~5P)3g4q1*`?E1*`?E1*`?E1*`?E1*`>re-2QLOM1Fr!83f=|Y4?Y4u0X_@92)+is1HKP_41Njz{?4Q= zk+p!efVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_N zfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVIG?S>P1BU*$}& z8N38M9XtoT5WGy-8P7KFA#8qiN5k-IB6qwl)bD>(ydkoFhhwnsc{n}df1vMqwERo- zh3^Vit+4&Rvi~UWv(|iRe)PK{n!cu^`PT1;xW6}|`DlJm@{|9*um^1VK;-y`!hz!H z_?Khs*!8XCuLpFTO^tg7SO|7KB>q|-7G{7R=$jyS?vp9!2kclVawFnz2M78NidwF9 zq2#}J#BdXzejlZ0XOZ&`5WV{E94GD>I@wGf4cIf!K$oUV8?0;Xv zwH_?)g;l~H=$o$2GVvGhD)BZ~i@tAnksE78ZqA21O&Bc{R?HOUPZq`>k#swYL~frY z%!7MuI@}MHc>S}XpDOHZ5ciI~MNV5y;u|#oUhzLzIa=q6zrpO;^>;~kFuS(Qm-v2c z`F^Z@^Y4}K0w`PWz;zGmb);wYD7598F3^tx5?v1M7 zP~>*V8m}@8eHZj;+0u^nK+c2gTr2TpfU#}Gp9gXw*pB%8kfUG|m~pbilRjL+x5B*x z>_PZ$$j(OMzZbF};qwtb?K;sHLykh93HK(*d5~M+uL5!*;%|oRhun&AUGU$g@j)Ml z+zPn|{yHG{L7#p->^1`S0y_|YHuU*mA@pI$X&X!UM#!0vqwv=P_ja)RWbxkxxfTAL z8^k>i;d|jPbEM=e53B$);J*U?J&>EB_d||?X{Sj1O^{o`4zL?+*7PB_LDu?cX)Rza zU@c%R@cXhr@$Q?M{!Z69((ma5GtU*d5DbIOU*J2iUZ? z*a_xuA@0q+65g{V!b6T80sC(y?&({D{}%t}LebWERhMe&+@-tJ|1i2mb%n|oER}9W8yH?D?hdY#w&UTiK^TU+Cn|CW*p-Fp0YtN_-ieX&DRgJK={9OU1_@Cmp`nO|GS~uaDQsUeaOLm$qzPx9bhl~W#WG1 z)%z6Kg!@nj;dz^u%2)AukK(B zYyw-rHq|412jng=4)%iH7bQOq+QD?NN%IFejPiRR=Yw9*560jxtTNaHYCob0{@Rd! zi^}lV2DuAz9P9<14xDE&6ZC-jV2j!ja);&*atv%z|6pA61G!7xK}Y+wV6VF0i+q8Z zO8E0Y&Ii4qAN0UqJ{X333~U0u(6>PLLvDlI0mfn9F37!*<0^w;gm=(h#vrFd&IFs_ z?tz>SdO<%J24kS}JNPJ(b^e?-&$NGeWZeUGjO zam()KM7edY+ zFY~N^$h}*O9EIEp|9xQQ$C6GV7zT^Cm2e%9d%*Nh#J?YG1pDB>4RSY_y=*&E{%$Zf zE7Qo04dUJu750G5%SHBYvaRvga)`*ShYH&cgZ^+~`Vqp6BZZw{G$wNPQNnJp@o15o zjuG~N&Buydc$_eQeaUAFWbg6fp0=U5JD-XjvOzDHF+uE>4_1IpVEA&;_kb-3*9k^X z7JV<|7RZfXi+gyHu#5@21@?hW zuZer}X+qEEl5Q~=Q@$>G|LMXuu%b-lSWwsn|9xOfg}BEnh2AD%TahrcPtuF-C2|W` z2=|V#xOXoVHp9Ig&u2Oyd+@xa80>+2`hO&TKNy}R@w7qi2Awa&Up5#8TfmA7C0wWK z=ZM@3Ipa$S-wXGOZ$+OE_wX2zyDk$p!95f8r5$n{O#4dW%kUx|uo&)5kkd~Refkx` zM#ycDTj9S8>;ntGmiWD>PhrT-UH01gs+hJ;}=PL;Eu(AndmDn7j|B<;&Qmd{nq5Bi+)}^|JLkb^J^_& zEnqEREnqEREnqG1V=WLL>X>m<;V5Co6rnrbOt|-6A^P6W;1AC~y0?XVr7&He?|>R# z9N|@7RaUGf@p=ZxUpCyMdyBug=4VwC_>K7UZvs32M)GU3X)RzaU@c%RU@c%RU@h=# zw?Hxand!SrKP!y>q&wf?O;_Fz^CKR2xSvYyLH{;yfc|h4`O82#9IOlZsnY+o#MAXV z?dShm>}&I3EnqEREnqG1`?f$D)}8#mOZnd~UFP|jDeHc+FG!VJu|6SscIxx|wj)#h zX-V47S+Tq7qgSq6-*b6tIvP&tIaJmkRGcaP2FgcapJgHNv{WNK1}4o!-b6(3VWMzy)G2_w{lJ@ zkl*-mlJB15h0P}jyN^vRPse$w@^7V_eOTw~&ad8Q-R^F=@XFNtX#8riL(etB_R zy2D%9THx1YfnuyX&^+}{c2fGsF|0FayCT)y>k6mg`*u$Cr|!z$LFNlvw_17lJfxcs z4wR4fy(FFve0Aog5`T;ooR0ff2z~x` zqEE{dwigMbn7@vJam}CWJTz^9_%{-U;opn%7(;&OwYDZ7=>yDHyYn}goc|NWqvakf zy)Klm73FcugN3(xYk}Xh1u}-99r%R`*;pv)^=LZ-IgIuxyt(K*(cY(PJM|0Y@5d&i z`HkXzbn)Y*JWZbpTb>hYI$pH9D*skku}*3^G~arkRe2z~?*oOnFZAhsJ`?dP2a3qL zTMPUOED%ROL$lK9lJk#|`W!}oO#OKV=nq$*-=+TC%pRoO_7Bp}>ZJ&|f7t`JWUTml zj_UR3&H&_!{1t~A!25TciwDVP3+$6NfIVW!cL(xWfqq^)yh2^kIaS*ZY}Vewm@uv_W0*2R4YZy z?Nc7ww>GpZ&B#Zqwnuv1{>s{&!R*q5{I+f(%KWy{J$1`>j3Aa zk21*Tcd%cptK98+|Iv9EtOx8_#ddzM^sHVi(07@<$3ox7)4Dj(8eVW&M7j6G?T~ z_`WaOPC+~^G*IVX?+79Nzbe;t!n6IuTEJQ$2PXKrnKeKV4gvv@U(220@UceL zY;#mMi2DKXo(FndtUPC)!^fE8z2@jRN^S#HmEtiR0wcn}Y~kWyb+ERw)QRSeA2oiQ z<3uVC3D%T5PEC#Im(~l@>!tarEH4X^+6jgtLDp23R~v_#>QW<a-6L>F#Q6ND#Mc6U|)K2sI6g_y5-?uCHZ4={_CqNYbZF!XG%=D3WP$-owDWCfhsC* zAQGuuOdh71)E&p?D+`9|0?y)UDR7{)Cc@W|0=oh96DH^~U#?6{-2A9k29KKH#Le2k^K$G^(zn(^a&Y)Sc*1(zjBj*)}|Xl@l*vOOPtx$r%fqZFyEOz%{RYb0bPe>6n)rXdFo86vgrll-{-3)71jGl zFchQczI+v6`(GZO$vb?IKhU#{7p2Rm}_Ck~8nUy8A zf!gJcxroT6gkC4kzY2jf9qmXZm6?Bh-SdTBQZEh-xSqlxbGbST(4G~UtJrat*T{8V z#*GI3=ycYH=+EY-q+43c5t2LSnSW_#NdA<@aV7uxeC46Q;s}+unwm1liN8=WlnmHDE?%4$8goF3V+Dp*y*f0`fPr}&SKPvyL5IjD})6)b-Ee>xBK)g;$c`+`x5 zaB;9MSdBKZ-xt;2dU2;(ZuC`4B6Yzks_+B+s+N?kR6jtlgmXzG7^p3+p!_Wfa@AfM zG0jOrUsfrZgC5G-A0Y76@>4cAe;a(^p_yGFd&B`rN zGnc}__$P-dx*7AeSyfV3(?Is6^T%)+O6zL)H2HiDr4<3HFX5^{9hKAlBRiXdFQ)oX zNBIrcMd-$ii{Z9I|9 zmYg$(@SzT5SM#UOx71MM@pqg(gb%8{5xR_>l2AcjD2$v81K@t1lNE2krun2Pc5i6BzBA z2sy_@Nb#8ni6%m#iI8X_B$^0`CPJc#fYL|!u?RmF;pC1@dK0ej0~xlLoV%fue3({= zI%H^068AB+pPN!@>Zf>e#(Bohbfi>{BUb6}zo?w(_lOxBmB-~uev{(M^-xK3Cgx3G z3yk%6Ca}z83neknLnSA9qK6VEj)Q)@`a`(!!kk^$vPt0)Z;nZi$}uoaI;5BM@;p=q z&95gq!Q82G<@7tsoUu|umDyi8`Se8jf2M>}JILAmu3r6fpPzq7#>tV>Nklq`NNNY= z&jY)96l7J=_lL~f38O&_)h#%ZJnI)xp|y*>c^U_50)=2 zr}ldj;kfYhOQc^gYT_=_raL(Wqs9}Q+&r;NZk}9k3A&{b{wBGPV!SQ zDmQo9%tX9uU!`2lN$H~gj^AaMT>djBH^(!9JSXyHa`|1E>emF%`2KX<{`ERh_X!?x zQTeB)rl-{MChDQ99O_T=F>Lo~!`REP9D{+&uk~-NSYE@U+Bw5K5?*EHF0k`BBrLU< z9(y2PN_AI%uOBVG#sAY=?{&1SPl^U zYI;h(Kk)fgz1}aFa=(#!rv8;bRem*|NLVsTQ$OZcj(HH(S4PEs)F>g3Mfn%56YBr& z;XidgbqKCr47FbQd~?nCn+CTg2mVeOXP7}Y`K0kP51$j`=k2o=IDC{#H<8E5`xVTa z<6u}!{aG1F7GXdeSuPn3AioX4kSQ5;8_j%|j%Na!l@H}3C6gpjf4i24raUezrHQlt z@nb_IxYTiCdsPhOWAdcM=6G%2ilKaToFs=Cf6=(2938Wej>~BDN5iqikNV-JTVAzf z<-;8_e&K-vewcpZetbR6ps2HqBS-WJ~Wxgt8aEjijxN%VhkE@(c})O76+=P#9co2!rC)Zs(p z3)Ir21O0GWILi?~*}IPCvAT|taPi}W8jfmHIj0a^E)$Niwp6`d-|F8Tz69wE7S0`y z#^)xYbMl`_&Bs9g)W7z}^nN_%T$&G0I@CS)oVgAk!*7v8-Iennoa^whR>3@TxbNTE zA5j0wvkK-qe5kzS(|HabDqnHu{th3QzH%0$ozimA^=#UKDztOzKNQRvUsqG%=)AsC z%Uy|j%;QdWQ#-5P=PT@=Pt?u>DSeBIW-st9pz&#S9XE&?PRH9Cep$e0+9hIXO?bIO z!DcVu@V?SAnyPUE@Mh+LosZ^=-koN_Y>Ft@{EICsn?N~m-^A;J#;ZrcSgs36EObM@t}_X z%s7qw!Cl68I`6LIF^$)=P!cwor9aj5dY!BPep&9XD%bL)3jIuDMpS!gze&?kCfW@e zAF-Qzoa7#lX}gn)3~D^Ppkc~oBXB(Cf671HRj=d1gg=bSG@Xes_(T|7#{o1>GN(x6 zRcbj^*7K#|)O}E*V1xQYx!nHLE@L&{@Td0wPChZ;klat=Aj5XAH9fpxrKN^CuF!Fa zrmOL)tjr!R2`B7;akR}PzM%#5cst!Fwu)p|saT+PpI z|Ac>0|LA;`ElW+O3jHI^r>3X*h}4SzF#MI`IZhB9wTC=-49pjQS?I6r2!`OkC+;!7utd8W-1-TJkH%SY&~qw!!U#`<_{k@mLtWgmyPxTn-TpP6NR4@1 ztzv@OFHncJ{bkux?1_RQd{l-)!Nv4kuRKs`dJG|Y{>*;;drlj|hlca{X6v7Z8n2I^ zXH!VJt4Au#45E0WVa4JcPr1XzXJ>kxP)%MEaU6udu)M$tVBFLApgcd*_y;0Aml;1U zO5>+9-y4#A==0!sfSwD};STRV{mmhKsJn)3+4RmKd}uh8%jYGsZ2r)B>cN;AistFV z^~Q%KI+i8j|NhX zvpxO@*F;Rm-sdZrIi37zxio!xT5A5Jr=^CfS8D%%Rhc|D&wpz?Zu)#)lOA!_0{ZK_ z`UQpa<}9M}&0bJQdc)Z>6aLIYPjXL-N&mgwMeV=(d?lt<8PdhC;}ds!`f#W!BI7L8 zhihxaL8nr#pN!pCr$JlmpqNDj*|Lx_)ZWglp74 ziawuNDPh)5=@^hn^NG|tQhWcP*BoXZh6XyrpY@u9!kMWd9iI(Ep6vT&ZmhsL90 zSq*pcvvVCjRHpoy1u`mYIF+xhpXczQ^3%u7bNEnMIsB@54j=vbk{L7ApLokWhmW(K z#qk!Emkv$u`cLONeB87;&1ci$&iA{U%yanA_`ajxh4gf&Ug`Fy?!Kb=wA9QoV{0BW z7Zyo%nmI?P*Q3^3m1&)V@j&fQg#YSyUoxKCakqb!l{8*Q_y$m}W*xUz)YX*G(A^>O z5IzwHNFqZ|Y5~qh*zg`8<};x*hJwsGZ&EyJeZDj8Ocg0iG+?{AqYOOLU)_ zU$kEV&3E_~n7>3`KqvZV{_%Pho?oG5hvtvk`f4N3UO00mC++i1FPd3E>#NNF{h6Wj zU{(m2^%TY*t*a4nCjT8npV!^q)&ZHD-Y;+0&#<_la^|fu;3H zYB$AO9yVFkc`hoKk$L$G|3Up+?=2yiHeSIT8&vAm3<37 zBaL~sQA=NNl8?qwG>)M|$5T5ahG792hwD6(&PR~R%uoF*bqq8T`cX=Zv#|Wr8HIJt z8cyc{l?diUWSTjVuL$P3%BarrFN6w8r_%iB)S6!op7*-fRpfYNeT$YynRs5M;Xz#o zpz|@gI?rQfrD)zmpD(+@X}L5%Zm#M)mCPUZKTp@@^Saa0P(7U- znw+iV>ybtoX0#d%8PN&La$~01n(W9n2BPkBHVa`Q4ier`lJQM1CY zn$}$LPv@y?YK_{V_1or;ZH$)dcS#^ZEj{%+s%V;)SY6LE*nxV}Eq6+4cy%YW|GXHC z8KN98YpTuiMrs#m#T~T|=nR(C)blcLDv!Bs&^qw2Sr|tbUx0H|jtni9Za=TLLVEw6?Bqw)j49&#&)RA)K zP&-x5EsxHJN9v?SE~RCU*Uly!{NHPyzTbUw^V_fRmv$vNfKnUOF(fHe0} zatYVhn)6;=lew%W9C0G00kdG8*2$Mw(bNL3XXkKCZkP-yoFShta_1Ap>)nk%EOl11uYVvJBqg=>xt73|Y@I$44a5(4+@-W$j3BB<^vWbW4A!$h;4Vx7b zhUCMLd=O1jz%=m?O+3-C#1oYr7^JV_YuQl3SLKk$@_<(=SQ+&%W&XiT zk5RgqCKGbJG;PNAG34}E7I#xWNH+C@$vG#Qo)VLD&V;)u2+1ru$d-`fbD{JFeD#D z(+^{EewbVUqA3Tq?Kn)MC$fT?Df-`#omn>VpcykV{F!*_P@jb5j*#|SP)DB|7(

LYz@z*qUi%`waT5Ki@M1O2abSD4)LoYjXwR02c66Mi zaUi~m9}6k?HM;vnKkRsSJIXIKOYbK@xk{T{i2x8ooHs`^LC-n{Q1iSsWBEA;H7;Y)kj&Us-mih&uOI|7dN} z8xI2eDEiT9B0t?aP~{EdSLH3M;+GKl^_PCJeVuiobX#oi}1T6~8VCKWxvg68)<5%S!a~@6UB$e-rUk_0oE}b3d~9 zo#UQg%kENdez6_ZuM^`qOZ2OXqvU|%>Y&j2OMqV*2gOTk@@tpapcdb6 zSBrL3KMSwLo6hZLDC*@wcfV8@hiq`ExfZr3`G>%h+U zrk`%SY_zv}R_Ukfw^`yB+q0yo3)R`OTk8IO7+v6pT`%HE^KtRO=-f1>IGwF{7m56+ zE``>8rzXFW1D)fr_}wDvO!+0CJ-bP?qxqn5WX^FO52#(+MCa!mTl|)J^Na0t>z*F> zDZlzUXZ@%h`c>h@0Z+v*rD^9oNRMAu5(n~ToubaP4qCtudq}jSbztFLA=W*$qxz*< zoa@EHd%@i=#lv>0e4w2wAI)R+bdG?X3J?9N_;qRe?LJST-;<(#G{4A){mon6y3Tj@ ztD6tY?`tAIRlQ(4mCl)Zo;Q_UaGYL#(XT3RXot_c34hP=sV?o{SH-Va!VmqhXGQ&J ze(V3t{j+C8JC)9f3%%u66-Nqq=&nboboL#rm){WBQNNact?u&@%kD){KdN&F_+ee5 zol57Hi=B10{J!a}Ut&8|KF|)g!L|8(n$~G#eE;^3)FEkG1tI{P3@v3xb zA^c={L%*v2+kUBD98EVVu9v+d>P+*Irwh3*9(jsiZ>-1b{%?tRs=WCkV%}u;DFiOl zi_ z>K{B>S4rS2)#YQ+Z(h7e@NUtL#*1d`Yj-=!58F{)s9n=Ut~-r`+94ipWyg<_Nn-zy zjT=#7hvROZU($c^`Y*NXSir{(dwYIy8^J?e z5RcvGu?~oS7%$Z?*ek|?`dNPOFV3&*J|mhB-}Iq^{_GofzZSpmH0_3Z`@DGkzoIVq z`B2O6kM4e{&NNTZ%&o7zp>gw$KMf8h0Q@@ zw-@S%#^GOw*RxlCc%P~z*DuB8SK5Cq2mA%j5AZo8ZRx{Yzqcj0jK^1cw|Kmi&6`pR zJE|Ye8}<*R9lgihZyp{tgl*;=@p(QyUh&9rTJ||AbW6X_N5&6%pnaYl@!JdEgOFzj zju8iW$n28q?~?0}T}SeMkY`8y%I0-6Z@P9kuBrU$-k+`OS9;$tiMPM)q|YTLes$x; zevWx&!@SL#qMM2LZQ{I1m5<;N&f_U#BA#?SCGq-JIv;=Q*LMEAl@;&Tn(KsP-E~2{ zNIUNj_@18UQC-68I`gA;h)367dhmSuBX8qxgwlb#8(7?0auI`!kBV-%0eV${X^fy3lw_8=d2&c8I6SM>F85 z{3a!S(GOcsjF;-%1MS(mqMfcTsyGrKEAla+L|A8`eyuomD~z8?Kg3tr#Wvynm-aVo z&o&VGQJtf+Vcb|>w3Eg=)ZLEORcwW`&eRV1s^aYhzBFEn*R9fJV=)e@OS}nm*+{gb zx=_ERE1l!T_}EBqc-T&*i*Jr|KgagWC;FxF#-KghRJ2pY+og)P!W$m)RmCf_!~JXv z(JzfR@>j_3=As>q*TSoDx1)7{?Fx;9;`IPuTKDLORg3&+yy0UZ-b&Gq#!LMozG^&e z1$fiv;j>hZR?}3Hksp<;jQq_TPzM>Asiu|Z9F=)@~L_3u($uAV+eZ4n4-FS8FN*5?} zIYi_~b!mq7>|oK3>VkaOcz3(L?;)Qyd-lS{+0zy`Hq4nnW5K*R^Jh0qn>lk~-aNKLfhW_2_Fwed(jl%F(|VEN zVf*m8e7(2_)<*;Pig-Qei}B0wC=Zz(;-kIH4*!lkWp=o}+j|_0x6q)I#6fjI-1G%v zeAJHmO|QeR?|0m=L+-qVwr45#^HucgBf3(*XcxZF8$WEx3^9SnR21cdW{86Mu(99=5*bM}XOyfQppe(1Ls{8BvMQ1O1B?jX5ux8hsN9j{Pb!Y7KnrFB5&O|tq!zSxg?PT=^I zUpL&3PR~EEJv(Dy;*Fl97jMfJVt@0hixtON0~1HDW*oHcb@SE^_%v@;T<}8H-`Y;r z)45Q7^#q@_c+{EHv-EqlAWmARcz;PJd|#GqOZ7|d#g88pkLoJ>J_5^b#rnc=l+Np@ z-=-BjAFB1C=t?nfrRSFle%Qqr#h)O<}rHWUE7r08Xu5!4y>wdKVrk``ZkD{cE*S)I# z(g{(Q%m`;Z>bH5h#18U7>%~gbk>29%1%5P+mNu>{yUD#@T7EBex1;$j35drd*?83f zJSacQ?*rcac1!RmKg5@gYYpCXj-BD$FH5fmoiBHf1NpE{(T=Xe$>N~(LhVY=!M|+K(EMf%a^MXs4^6s{WD^etB^~LTElPPi%T&{3ssv+XMVmafHuv z&WFWsp10#=E8x+*QGQJlJIn8}qAoPQ!Sgw9Hb=Ch`L*zF@z#$LhdTEU3vZUYUm7pA zQ{_$9E^vW!-l*UBKb+^;)UF=zXx@+yTO`Iy^O1t~Y=LMe&Bu#kJ}92=Ldb8IXh-pA z9LTr7bZ!A2s(#b~c2fP07j>cWvWp>8FYp@s&E$UjK+)tJgo80FUxR9oUJY&NROnXwOa%?Pz`rjkn`4=kZDx&x+%` zf#H|FL@yt`U`KVPadb=aX2o%e7zfQqycPP}$)X+2hlTfqW`BEIw4;7$9LdA=@|NCB zJnxPT8Je44WigJoM87l+>KEfu^`n+c_43vMcB;J5^^(k1d*dIbp*Tu5?P~@koQ*4LNNoa%qLivT3>OE%+ z@lTT!e zY}0t7BRM}+9LSgIjQiOo?sZ_C7Szt@O(w4Sj&yVB!vdT%{lBJF&fL_c^P zo9axDGqUT+!RvV4TX?$-bzFa@c+%%gj1ub)pO=xx4;{i*b{~qiU((-n?~_TB_}Tg1 z^43h^#p7k6@%oZtJ_^2X=|cB7EctI0?Nt4vhsF!fNr)luTSPqCKMK{Q^oHVek@>~@ z+`56k%uYHUT*cqN*h$ApGM-`_dHjf-^mqhuV1MfcJt$r(sh8g@#6j~*@n}Bqcx1_XkC+dd-`Fjn z>)oQAZr;+|g`hwS(pxmB+YlEhA02f$AmM}c+F4f^KkLhxkuS8}srJiSlM z8_lmJ|KCKr|J(U3Y1hkJkl0D{M)cF|m!1CU8sJlyyf+`HW5#ybLM#Gb%8v; zRwCW|QT#SBKH2=Ljo9_K&H=!0yPelBd(@jQ7_PEk9wg4klSBFZ9^13Od-L0JBF_gM zcM&hPcVVADQpM4IJI|ZyxXF&cPZ-hRgoXnxfj~Amqk03&hfjsU#vITx_le4>+R;xd!_NFh@EUarFp|~ zh~iN@>HXsnfU53&_vqDq2<)VF|CXpT%|{EgXK#phs(fG`RB?1`#=$zA>ncxYP5mN( zr>f^>iC>J5y)WuQ_3MK6tXs6}Fa3~*Dvr!5=XFeM&#v{xFMO}Jd{BOt-|M~k?YdC> z9I5Pl0r6@5;ePgaZ{JTGy-%;dwSyh)Z-v%rucqI?{m%KY;=R$E&e)FXN8@O{zbDcxv!_Hms$bu8ab`3f8*iA` zIB!P$gogPGrq7>g{BP_7!g+C!`I>57p2mwhux0N2sNdk)&bm-L#HW6#UHV~XJZ#UN z7x_`01D(7*drq{YI#a)hui{sFtn)mZ;>Cf7bliBMfA}Hq*8h4t5A{8w(D@aSAJw@9 z+OwBLyZ+L-TgC4+cfY6$n9CuwEo_9_e=3mPgVbDeN3Utd!k>eO9tArcSSp@i;Q2}3H*Cbkgv>66^H*gy?!2j zToLaF?r|VbcJjc~Y2XP3zmG(IG#|S9#la8zw}_{kH@r^Lv<06x>iVU2ZIXDYo$pD7 zE*}>bhpMjH7xKDN*>y|!(KxVvRCuLNDdN4rTm6+Buh&1iw{|`cK;Ginav z*_j`?c3_vSv=r{?0T~ARK0$QcvKgvbNllg5AE^$I`BQ)b+Bt4P`uQ3-r`l| zH+h;~yj_}h-P=3!v*NwgTOH7KQM|53bwPYpyrDClK;^)BJx zOV)d}^SW~S0cZVayxl>~`-_j_co<*o3unLhcUc_x_qOTc`kL(eG|gLJrL*78=lJ-7 z_+I&8JNAS7eJxbK#B$NE?0P_&*m+$~q<(t|Ua{8=njhx*RgFWa6V9(X;Cc<^7n5A) z?0FByu~*h}9k0+2+g9^_(RJO|SuMQv-H$UEhcCKp=HvXy@l>Vo=hhIr|D zD7BOM#r^D4aXwDZQ~WQ2t}8@4I={+4pN=~(u%Y7}-RoI54r$Pv`6G0l-t~ zBIAeq*#_?8AJrwL>9-B+Xg(;O?-i~ywX^uG67xp;8^yzRDqT8Me!p|~%U*^0_*S%| z{oH)sq4^s=hks9X>TuC4sL>moBiA=Hq)YUYZa8 zYoJSyXh(HH-i*1|pJlg^yB*aJ+o|I11isREH*xoieps&vQzBd_ zD{AN8+u5%5J?PJnsM1ONdlfKm*|4|!1*qT9)1?27caInSCPumYMLRaZ9WSr0$oU(7 zj|AfRN4xu_c)|BY{esJ!&j)*nT{qaF-}*7${8F81-dMz47xc>}x!cirqn|jhD_eM* zxsL}F58Kgk7x$Mg@uo}a1HJK}bh+Mq9C@gYzg_2w>)x{U2;aXH_wplCX{|9j|)yo|7Lw&6{70i|UN~*|zSw(7I~x;`x=vv7I+O-jDD$hrP#9LX#{FOl;5lQ(|4`n3Z;S_hOL`-ff}Y0Y@)cS zyci#Q$=!~|QJ>*)V0-jS?ffr0*E6+499pNipS|FXpYLP6x{84vtrr=;`m@FRuPlC# zc{?7_yy5j<3vY2U&J_6{VhIS>~E+Gt%KxHO@5@Va2&Gu z1-*^C&7V8xjq*!D94h^KNF7M~IS^L$x5(FgKBUTTILqTu*`ZEKJEAk@4coJSd8>m` z`uVp#ock~B=d$sX+7)}eOnf2Mfv#U1pDkT>(7PW5?GyJa=DQENf3AquX}D4BZ%k8X zT|11I`pteR>L3{(Ig z{?etbOw6xrT#L-%`Bue&d{z3jf1{^g8tkZF^uwO_rc3BqKK@~QS-iBr;c=hVOZ;1+ z-)GM2&(UMKeyZbO3h<=yzUUq=#>JvyKce#{Uk~tpLBykWG+xA4<=1ySKYvlh8@+<_ zpz%__@wwu02Cs7>ANJC~#6jx-KSyf$eMR(3`=w(kv$izo7m~bTmQaop*r#mmv9Vd0`ioxgkRrR7<&$|5n$Jto}EPoMP+xd9ebC}+EK{ zi?@f^$&MdQH}msB)IpZFa6&wvk@<}tE%KA$p+7v%M1U_H4?2Gn@ud18ptW`GMsNQ&Z3R84&TYqtx)gg{2>c=9$>#S|KbbCZf+w@n z#Y^=wo^Q1nuP#4X|A-ZcCz}^{6o@CQgVg#wUe$SbDRW-WvAXF#9>-m1NY@1{yv@Ab zKb{1BsyKR7aU3AVLC?==e@o1FUWW@0g7t^}M7;i5FX;q)RlFInqw6J>&Z7o~Uvw?K z^{WKfN%_@@{AfPX(4LJE?WoRHyzs(j+hPCyJeprLqjgH{S{isiqH$2W^lAKfhPXI? zp?3IpmEY9bdOFkbR5o5^0guLkeAvOF&NLsfb)fFYiFPy}g~rQb^E)ahZOU4Q8k1$(%5JC{gHqjL47b9EbMoDABIJbWQ=j zO6RO34mutr?{r>&w(2=HFmbf3uQwiafSt5nW{Ui1KG+6O_tQnY{>n!L@KyO}20LjS zvj&D=k0w9=hKjoXtH_V)+yw1elW3>Xx%3S2c%)iaQOysMs_}WQH-6X;RDS7vL-u`! z(T()#z8&nO^%583p!w*9_H4drr^<(Jyzv>%$3Z&2=;F0)tfxx~?4-IZ7UQM5_%?y@ zV3BC2(j`30`MeS1V@tf@VLMe_bpT&FzF>QHyy%z4%Ql60mx^|(c+(Tbei@K_A2{+* z#nB8rXdJX&l3*vzZ?m^JXup)52Xr0@I$=PX_i1%5cYZEJ?^&XLGQX4`{Tv!Q)O}q5 z>9U{2>+CeYmR)jv;rTn%j^@K^XT9KYQM)Ah+>>k^Pj4pbEL(5tC3d>&iL!Of)bYIk zVi+>NO;?F|!{_kPcxm2r*DKqAfC2G<)q?tWNz~iTu3g4Y}Y}mtVR~>>s$! zia2cJ!3B*k*7Xz;KO5mKZ^5laUA*Rv<|9GyWcg?(cE#pnBTG=m?Db;p-ljO6O9)>! z(p_iEFTB{qw!_Yk>X+TdIUly>xtCtoC;QqvACE$Q(XT9TEyND<)`!nuY4aoZ56O;4 z-NdhqU+K1D9R1Btcie3wc|?6=y5Qg08Q$tjhDYnlzn!Ry*M4sCgBJnY4!3%4C4Oaj z>m+uVHyQ_>M_|2JbRP9MUnBLGcR!}bc##K=&po6b*_rP7rSbaUd1KEha+d7XMZNx9;x33+46}IhgtCtkP^I8Wqj@B4C{=)s#HafYNy8K$FI6udM z`bB)KgEZ)#XGiJ}?>ofy>~Z&cw(Q_V*tWw>XEgI25D?}cDt>rB9JUX<>+yL7BwpEh zPxGI|dX`=9j+5sm%k1ij9e%D7<6u*~^-DSq^?u=e-(h$sF%I-gb&kyt>lEX#_)Yc3 zFPad~-=yDrNb(Wya=tIJmpm^Q@AI(u9qo-D)i3pev)@EO)X(>lvmNqKj*~l!c%3pl zqD#|@&VIXQih0BPHjxjTR-7)fb&xg^M|Y6(v;5BR<~ItTXTtVA_ONPj`}A|pc`Myjtb^v|&UVT;7P#}X;yBLTj>bX#VjWm`H}(%6 z_1i;q@vU?o*JS)CUU-P8bBW~hOc+<>9Le)7Zg!6s+p}BT?I^#NGZZSH<8yE`@Q?$WfoThs0yO}h?FyQeknp3$^h=59ypnbu3*`0|`Po|TW~ns(1? z+I4B#y`X9LlBV6uns%?a+fkjH{wmH7@O~~!zt`OHEW5O(-5Z*AZ|T_uo^_w!Tm0T} z$D_JrRJy$94X@)Gaa@y*e`FlW8~;A=<`?5vUC*QaO*T%}597xV)jT#1cIaP**9La< zd>`Af6UBJ*u7`qQ^IzTTz_%A1_f8P;bg!4G^h+I~xbNnqf$_`WdD5zUl&YRPeTvAB z>f8+N*~y}vO25>)eEy>1hxw*D<9_zW`ocPZ%5RURF5wZpE@=JH@c?;He$=iN@Ko`3 zO8lZ9mJoHO`6w9)^?aIWr_u%SX&kse{Goe4qVaY~p4W$X>~wd2Xczj}o8KPrtI|0T zbj~mOW#@|gsLnLr()rHE%Q*O9XN!1+=7ajp0=_C>rnB#NaRQJ z!OEfTFA(keOXmpStKw(|JJq;R@{8X28`dN3m$VLgH2HNd5bG4@&lJyJ;ao4&E(~_a z6F+B&?_;03_uuffF#oyKTiz0&pDG_sfUmL(RyxOvaj+}B@xykiytRX06~DBK-_;^N z+CKtS&_Avc?fR>K!~vhifjX3a?p_D9uG#>P_9Mh&XShGth2mj5RX#%1Tqha_#Y_FF z*MDPxCynEJF&{K<-O!$0E86u}-s+Fz`O5;cl48N`#y?pe5os{2wB0s8g zI0XIU2GLGeXO(`s_16hJRCujmN8_b+nvvKcA9lZcyq4Xxf$4AUwR-tYgB^|6;`h4V zeUZHn?&5mBVB!5B-j7M^CB8S*%LAJFZQnooS^ReNhL?fkpj5vH_2Ov1+1ogdd{yHv z+NtWkV;{YGVf%7B8ZYf1-GE2!kPmxU)P>eTGx%W-iFS0{u<&Mk%Nw>+>DL21RQmb% z)6*rg$oaT{eCls>uLHDWo$k8Od|*3OyiJlguzkl3?)<3V4B)BsOYaZ;9vsQ$&rz_W zbw&Ns^)-5*rQd5DBgOSZyl#cMB$D2A!FDQL;s@x}Rd_M4E2<0nVe<;>A1Z!{>qK3s z&c5UM{r$*;_Fvt+QM;C~STFQGnZ(lK{30Ipn~~^D?RtqWc>e~qqjie+o2l$%{F0-b zby49-uj^Kb`E6Rkum55`JFoLt_hh|2_Gxj~lUqlN@yf=H^b+y>T&5q*2i}i_@v`^b z=RyH&K4)pOf{BpO?%e&nS-{sVltiklLj*`O!L%#j9%(Cf%JNJ7hWB#r zA58>LW|vq;yx&4r_a%3U{WmM|8(87(e%8{{#rtzq^%5H49B;H<)K6BY*}KI!bn7$- z_rpSuwKi&Mw@Nm3V&ByDBUzskUKa2b#+c@_lT7NQrS>jh$XW8+W`jy$m zNF1_wb@4g~UeR$JEb1)NkMhI&F=_op2%c`dGCWzw6m`D(q++z3Yqf;`lH8x##FN@`t-$iihoF zx?~l2*gmn^-7nht*$}PkDIJ=2^@H5;yvEzSmPb5teva#07%w}*{rfA>&bPKlzf+vY z-Mn}SKUy#C9{q+kbiY3_ypDSu7;m?xUCFw7cughlc2t)rd0qh?KagK~J$F2`Yg^yl zj{3!Rvi_F3S@U}1(Ry_i_@^FT@CH4*)|>R~T5ff>^QsFw%iDFKrme*OQR3t0=cqqB z#~shITi5-03YJ}qCf@m)b{D$aQT;+w#dvWZM(yHPi|fTWf1!3Ug4g}E^ZG`Mrd_wD zosZb*u16$a7O#tRD(arb8#zKxzh+`5(n2r;Bxk*AXc{|E;2(tp3``bFxY#>+Nl4i+Hl{pNX9#+R6N8E)(tWe3iyQb(VeJ zncB&o8`abz`jzpEknphCpJvl#OkBZ|Ey`Q1}XlVb4Xy^5MXtCcPl|mjc zAj`gIs(V|0-bjzXs{F>!a~}Uf@crF*9Kd-*7k*Fpt`{=bU(l^qAe)DF(0 z0{A`G%LgVOo#0p1&of{r?dM$s!%tV|#IZzY$@zXev6J-=>KE7LX}|0xc(Q&Tm@D#= zjT^dt*>~dkmdtMi>{R(p0Y92w8ZT>h9-ouQ=jHyX1MH{GZ+ILJprI<>j(I#EG+y+( zX8XTWfk8&tRmN{%GJoD9Zu$N}tZNeAkK3{lWue-din7Yus*0+b@`|#W>Z)LQS$TCu zsH!4Z5v;8--Zc)ZtgR>?Zz@_gqPD!Mw!F5sva%v%*jJfmRaLb$HMN!HRiVn-@|ueB z#^Du}2bGnF4EvEw7A+h(Xa0=2OJ+8XYz|d7R96n4J7@lq=HavFFBv&~&f-NQ7d6gp zoUwRBlL@b5-#CBfoN4pHJ~$$%_$jL!UR_pMabS)<8*}9$j{1CJ?msPGpN599S!BZK$ssbzt4ZhH-~P#@8KEH(~Oq$>R>4pu_+8X-3qG zr!8Kx$cRBhAJcx;+-b8-bB6itiSj(+R+it|5w)tHIzygHkjKKuy1}gs-<|)W6G(a$ z@tQTUXz`NixlncMVeXvia~423Fy`AVcmDbN+PUV^|JF19V#b7eHaBoRaVv|razt%q zu)3G%s2!;%EgMY<{it6&RpwWRV%F4=vwG~yt z>T=^>O--oG=!s=DRpr&e#^GlF&EcQ<=7wxwr_U8KyjbF=tyl79% zt+$r_2Yel7C+jcHFU)yVF5VuG`KspEkG1hv@^w0G{Ws$A>f&b>@0qKIjUh~?eg^zZ)MSGl=;1>BHZ``6i^2RONqb|5bd&I>p+9MC#qCMi`7VVJ-ZdLZk1Gi|8 zJaCKn$OE@%k34XT_K1sHv`1Xrn)@TCm8@lM&GEhdn?L3H1KRh(d)%t*>u=(p6Tz*@ z9&vH2viJYN`Qg?$p4L=V)*45_pmDG*57kr!Yif<7Z$)*Lao{z6Dve{Yar_M(#QSLV zh{~EOqe)qr(IyluH(ms5%gxDaZIuB~Q*9i=tIXqLb#-pWS~emWsw_9=yfx*Op{lB& zVObdr))+_NP%s#(Hs-x$HD!&%%W88+Q*%CCR%;w~%MCb#NvN#6%3(U%IJ^ev7{_a4 z>QGi|%(lxyq4LU_%4&mCd8jg2Ra;R}ZICRh4H@$XV>(`z^H4sbyxbsB9W-XvRmNf7 zIPe<;YmE81X&x%8HfAG+eOWc14tSV9@cBu_h{|AjsJx=G+MMy1heB1gp)zxtQ5G_0 zAO_WH!>=*l2pv>WZYruj|KWs8{)R9HcF5S22g@o##z{r6yrR6un4cKaq@WRik*{Eg z^U;sDqP*GQqhAl4zjl5(9j4FU5Xc}@X6RW~UK^^ct~7!(=3v1ZqdJVzG|H{QsFK>U z>aq$Wzg3{8 z$?ZMlD>r}kP|vyidg#Bo3>^ED&p59vS*z{1opR$WZezVZV;t_AZ-?RU$*p!}TNt5a zE9d6s-?;tU*l(VncHgu^4hOg4hjtgn^VI3wPbRm25Hsg(<~Z*^1NJu#WqTO=%yHM; z|J|&ie2L6>ZhNWmK6L$IIls8wYIb#QKGQRpuVdl%=Q+lHgHO-*eExu2_w&Kr`TpV) z;*E>uoY3=Wu5JCgJzi)dvnT=i9BD^7_Q>>8x&0nUVLdYdAh``EpJ) z+A!hJhC@eBI&^&9A9D z_zgcgf|o(K3?si8?%9hVZTV+W2Wdg5&nWmhYAS-*Ys#_aEcV$2jWde(*l>b%9UoS^Pfw z=-cAw+^GHf#J-2v?{8F-Sxdq1_YvXhwd|*#u()y2@zdhDCK~t+V;g2Hm_KXIY&9SA`pAr#jk7#m?=Tw8n>J(N z0*(1|?)r<}T%nI?FUZ3Z$9?NK-^dvI&H0J{8d#r!t=HohTgAs811k4p&b916_}*Hd z-;1xuqCG!(>1%=S(cT=p+}68r-3qrJ&X@Ta_JFzJr4v$C1qHh8DTRdl8<3fy1OPBcKriBK}oUFsAEu7J$ zKCbnx^Nck8^|@2z!LH}9VSPtYEuL7PIJ3=_4%TM^>Qi@%?c&f*cWbRL)Q>u>u3^&D zLk=_U5ivHS4;|kyvCdptFm4^0IAy}*afcXxo)U>1I&rc|6#E0-2RxSahYalx=kWfp zHyfOrpSS7;RoL$Sa_#tf%J3Nr=FMAREvsm>Gv|%-7Y{dntyWrfW=xVA8W%2{ zJ7*Ezv}A~*;g8p+F)U4++t(v**JgkoW&fi()OQDBV%|Gz0uDRhfCG>=~2<9Z<8XMkH= z55)CB+~R(`zX7-Xh4a92e*X#U;P)BgHugd_+tRqc?C;_CspB?b>^JYB?q0~R`{Q=) zubuDfxH-2!|2~je-|TO!qYh%NxA5!lxIOnl=leHqdWheTfqLO~^uwlo{<`bfTb%E^ zm~kt=j{@7{cCCM!_W3wUe^LN%EOW2IeV#Yq^zq=S)^EUy%%Z;u1OMmikt}P4)>j&4baf|ha^@m&B zkM)P!8x|g&yZ^_$E@0m86gZGyugDntw=mx0eJ8lxd68jn=xpMd_OT$p-ytuqql=3R z^NL&KkMZCZ_hUS`rF>@pyD&aYzPjA~8|leBPTbzQnX%vKUwA(aZj+nW4H|0G$A4@* zcfZ)#2TaM~bpD0o;C6a=%AoxX9P^lD>e;*_UnkBO`<-yY!G=Lw8g{7v1B?0nHZzU= z_WQV^kHL6Q)-cHI?`R(f`^?4j)~d1X?;6GZvPSA;K|^x$%;Zu&&%|xY*l!+pS{CvBxE*qsGfu|XZ_Zb- zJ#N|I&Nz(+?UCby$5Gsl9=iv#A5Y`Pg;VqXpp>!SJf7lxuDA`o%jeIfJM;TLaT|MI zGJiJqn{na18MkZyCYe9y_B+gv8AZ}5bi&RDOw-F01KzmYGjZ`?j(?swpmcYNQku;Y6k&b)rYIi;U)F6t+o zy9&d>@mY3U(%s)*<4<0`UMVcDJe+Hn_RIO#?0+BMKR90(hO^!$&i9A!x`N*yj{OR^ z&zbv;{)P98W?3@e$4rN=0=#$@6G4yft%nxZufFSfjui1=c9AMu9a7{O?o%&r6zn`RAv6|K;0u*oJ@M?|atapW|v7 z%(vaJKl3yHJF16x@yoeg@(R99U&*)ObKpMX%lS49?_=lk_uZFqJH%VFU8BGn1=c9A zMu9a7tWjW%0&5glqre&k)+n$>fi()OQJ{DQ%;BIT!Zu#bymmqGeNL=sG`K7l|AG6Mt^OW(Mx?UswJKbzr*{$G6_bcbbiFVB6wwvk!B= z=Dj`(Pub-H&HLX_@;g>PTv&7YmPhF3og44 z_01HiLm=G8_ms*z+7UNgWIqnubU4$7%Z3-HZ}@h8U*RT(4!ivPg7MHoUcZ?l`$YtF z*v7zp`lBN&5jR$(4sE;h{$}0_xqI-2mk~EpJb&M_j)Rck6z{O+r1H`X0Q`Ka5Yk@JysM>&&pmOJP<{%oi;oUJvGT>S{iz z`BwO&@y18K_m}=1>w)&SZsUN7b+(Oz4lVHgZxj#To45gdW7~GE&F5#k8v8!|biX(| z&-O=+m&iBIw2I^IZv0_o^uGO3-{jGH{aA(@4)FHoyzlIDKQxXP;!g?v9$)d#kY(dJ zM`S!p87C~Luiru6SSue#37qv-#<$hS$20T%;=T*I+E9l~k#!a^KEP=5HS6s11);n; z>%#9#wit>pkT2CCVC!$&I_MC%q%a-Ycj7vj^VFAzF1W_hp~!mZ3HKf6KVP)pJ7Sc^ z_f~x=ey=3`yG(~tn+}s4bVwDbLu_>4@%W1s``lsapg&J_9Cun_+*#KMaJTa341L9) z68e40;-97cB52cLvV#s;^8LXC*21OxTR{i29!|O8&NS)}7_nBauBknJFUwoTHcn1) z;G4X(u=))HFXQ8?Y()8~Ly>QIJ8iy>d26%fZJ0yelB)`<-;gbDhdJnwzPK=X3UA0f% z@wk3m<=MHBUe3{`_v44lV!b!#!{7o!>+qQu;br9PBSLkMa67 z=VzS`^$;ZAFKusYzLxP#+`w^-(@xfO+#h+zw`hSnL~Qj?z1HD<^`JkVIo3mmtsa&; z)I+SNuzt}BI+*9V<6C0pFf9CZK2cab1V;7Eqr#y*-W5QNH>LP}*z^zZUY57GF(WhQ zsV3h^4t$#mba>(c;c8f)k7%IH$HrE?ap1O18XQw-=wX64|d?o9xse< z{Pw=%<~4Ws{1y48imZpG`}jJG`5jpYJo5T<3s-;L-f?_L+3MjehkD2!r<|8Kl>_Ur z={wFr-$;S_Wo|Y&sn6phH~UFC6pM zWgFLDbQsr57ZsMbw2kjy9Qd|BQdqz6y~X>*Muz&m4?Xe)O+s{^!qyREFix7+$u_}CwoL9D&)!=7=KWZ|fkbiRS^U7h z`Q&zQl;4Rug#V(A>sV)Ls5A5Y;^y*4^Ug0i7Z+A%EjGRZ8{e2d-@KfeI})~j{N0Ju zDyUJ(lEU~l+m6Sfz0Rq|yruN(%u(NNTR&bs{jskp-`)cG2KL~2H|zJhpWbPwxbb}p z>u;%Bct1Ah)v2j3=II+8Q`k6}hI%m9VcrYvv^~~uQokM?_08DyeRb53Z>SF0rG?c) z>}1}L&Fh8jR~&qI9&Um9W_0>%jnmcX`cV{WFOyWhHUgO)^GSR z?eQTW)7aB(>ldfl_@;`?Th^Ah_fMGe6Ls!Cp|HI9>v%g;-y=`B)i}E!l!MOb^QBaB z??blpmQ@>X{UtTZsQEh9Zx85T&e!*R`PzFZZu^Oa=}@v8Z)f(mV{U)aye}wVykvoi z#nnUbJzi(#xmN9_`8vc;DvWP4rWL1et4)WwHXUO6I^=lJ|01^f-O!hxx6)Gz(;)?X%{u$_pyj(^ zoh9`7I_8bl^5c-%FUGx^pSP|8`9`2$nB#iIVSA0jyajgAo=-aREdjpk8MvuePRtw6 zGN%@%um7XII(zox5@UQA6fj({l)k>EdEQUtAkN3k+rFDkdJSYl@44nf+qw{>K}%2L+6mEUC}eQQuOVzAqhj?#(8q{U>{0VSKwl2lM{l zFD~BkXgj9)I&p1bxCt01O&yj^xX98WRiq9<+xYPCkvDHj`F1@}7~dr1ZEFK?kDU%W z66-9Z&zDl+?sl-XR#u2TNm`L zPi}qG=4SeYpV)?lofoEO^_>^)u=T590n~UC*{Cqw{wF)3zJZ_g$A819oukRb6#@Nd1H-rd(I%? zp&kO1jPX9aU*9}x$g(kco5WP-&L<=I>h~bxcB~NedD_6pn!>$ERt_%1g|4= z-7{1Ef^j-KC}6x~sUmSZZ1dl#vw}5{!!=S|F8;4tmHIUYA#XY=|s zuj@tr`0XuI1N%?>h{DF54Cr9$yQ<6R)ND||c*$Z=f97kqA6Y$g?8NhCo)`Yq`oRMh zuD%YAg&De#*O_^o-{HESH)45L_T1QFHu7!!+j3l!?{7A~2@ibpQH|&A1Fos>(#t-u z^i36s>)XArUz}{i%@m0nIGoq1IZu6NtAmYl8x$~JvQ&}vkOCddap$%juiOhWktq_l zWILWWLs<6S+jo76d}9!Y$=&ToR=-i3zDvK#T6s$riJJhvW}W^0njek3HwFcamy8Y3 zKJU(%)Bk*%_w|eUZ$D$*CzdL5-LnJun)Q3KO^4V{#qrJ9ba?cd?H)%RGDYg!8R#2# zQZ`%`)gFJTw7K^I$dB1CE*kZXHLng7i5s@zZoS1NmDn$mMdGHQy~%e68*ZjpT-*Bk z-nZR14f%#2FHYYid`@TwgYW)_Z1FPU28x_VwLrfx>-WWBI~|3%u_F2Ucjk3wj%TZa zmzww62aK02Fts=x>UZG%*qs0VeD5ijBi}@kxPdYo-}=4ZH@Vt>LX-L5?fdMnW#eSX zhWnlaZmdAuCcrhv^@p!MYDYU4^L1oOVSE!d+$XQd$89bUxBmCO zPo@Bm?Ru(l_Q^95fc;b#`d*f|He23yxi7ySx(ejmVZ+_j0k@|>+%6mL4i32f!wRd1 zjIAEt>OL~B&ioG*cHf|{ysy8Fx+h=XrULnf;rM2bJ0l!$TMNW31-|CEv+l3EoK5Q} zQy^{_aLs-^j7{H&;zkcIEN_8L`252>z9k;5HE-Jxei8-ZMuD$+{*q^L+lWTVDxM+;oAsNn76PPX5-sZBF=Uix#GD%*J>9MNN6@;3btvjAxJVt+Hojx_{`bEr-*AC^vo_p^2jBJ%#ce7OmsM~bOnrYCf7448x3xgrxb1kc z(LVV)WD3M>vEe4x&DWuItHQ>IpiPG-4$0S{gRUDe!*rJ$G6$WH`;Pc9^XWPeB+<@>Fd9?J`cCO zK-_xJ!Mx9AhoAbMD-kGChgO>ooBeHU9^Z63N2 zPj?KNn1@>+-*(W!#GN|0E)O?wbYcCi+lIUO79;X-;|1dO*l;)8Xm}oOTY$4kWRTB)jT_q7>wAoO7srQG zk$f`&j+>jO?tA6Oh?^{O{h`&iuCd|as}>?|sz}@b+%IbKU2D5ne?is-TroBAu_vLlMa?Y8N=LHLnV5jRjIZUA&J=c(_{ThW2I z$s%=#rFgvC8@Rt7du+l(hgVO&NfY!7b6zs;$+yo!Ty|7(d?P#Z zamPGf9Q1m%HSUCqye~chxaN6Q{g%^TM82uP#a+kg0$g)^*dn&h69#U;c*(*=>RZ1D zKW>`1+uCqrMdBtPKW04~G3=UCP>0yF#pTTh&!61fz}@txRff!i0>(?0D3WgsbTH2^ zR_*d)7xGOOi+gC_{V=cfvI9-7UVdc#A`Uv3b$04jTNuL{w+s~d9M1NAc|DjqG_4K~ zMch=8Iz;c_{msnV$3I*-4sqFY#nnS(zdpX(T~-@J+}MAM!)>zV?d^WdTPNhr)c5*1 z@BW5-14WK!SzA3U-M7UW&k{wBXBp7fth3--7wwIFS&`2-YI~+{-Zwb=_TLaUQDi-Y z_viIs&L_(|Hl2&Ofg<_V!*ia@yfw`GTNUDli^PrDo*(u0TAx|tWTHsi*8O<>oA)tI z`D%wtkuN)@xPB3U_U1ZmTk_oDh#M{vw+D1E>+J1y?ua37tVrB$c;2gdod0h1jw!@V z6p5RJ_U1fw{>ZzILEKc4xEbS zX9?IQVH-H9oSDC2_@&Hbe3Q^GHZ>Y7J>ush488&5C5vhDmEp$W^I7Kju~D8Z-s?ovfff0D z+AQ!jasR!f4>w#SZUmmEYtDb~Zk^YPd=o|DX5e!u=K90Ab&(X}24)o3k7Ll@9DlES z{M#jnn0fUZ%0I&d#}Zm$Ar~6?y+;3hv7=&*vBXxYty~ z%@ldR27~+J%)I^M_k(Xo+(2V-c?&~(lkZE1maRnGSdq91Xm8fT$jrIFB5txs+~^*B zerEQI-3M)F-gjlZGVV_;61N3#&Ev)8FZ}i+;%17(jqSqunz*s-4ebVQz<9|LMc#)O zfa_Lfzu4*cuVctJT;%nvH0WTCXR9~A;(EkQ6p5Rx>N_8L5xK84c#I{&-j*6~Mn zyl8^Yii+qzs@{RA=cOJ0rqUXOg-~*1tBs*n%V{qMSN2A@Q7wu$RAL5pY zBClsP!*#OU@oh}vI>b#DiQ5jiX8neLd&oHZ_;s$r&^M|z!+=DjgzxhK3c$xFb zAAaB90p!byT(3?|L6-B470I{W zrmrvh?^47~Jy+cPp~H5a?A_gm_S@&ln&AAxtcS<`d2A*ps)zr$YWWSiY<&M+Am2bf zEK7XC$FmaSZ+8xT`OVw|7#-|nyJUP5w(B@oRxa%~edD%u#9w|L*Kg~;rOW!}XN&L4 z8pll@S!Q{0bruI)bN%dr*$cZq zJm1&|KfVIzJ0W8w*<6P)`^BD}@0`kR6kwHaWOWuZp2TY6n)Unp((8=V0d5(%w>TYI zU>;@8&*naIh;iMC1&m+q9~s{y@ZH!zI`}W&8u|j?SaEz?VcZ#P;GXmNo?mJc1w$F% zF8E#;vwq+BW~jNmA^gM_6!yHq%)vZw>l$dMp0{cg>JWQTTL&}c`9IYh*X$QJC-Y6> z;lhq@9md4LtTPk$*&(J3khdb&H3D#-jX5uA-RFScjg9b=E$}{@kPWxAHUIv;&@qLb zw=~1|lbQ8U(vP3Rj@bC_d|v+jeX#=hhW-z2*8%55@wS&D9H0`ahZL74CsG0yj=uCm z0R#BQfG9x)4-pL26BI&|qZ$O^EMOGDLqQ_-1cX?CLlA;e4it&fPEZI%IQlnlc9zV} z>}HZlzWM!fbCc{odGgHrzVpt^W}}4dOuCV{@ghK6FZY+h^>Ueld;@r#hx~U~&bivC zlF=jTV&=!`#PwX$zhuVF3@3;uQHHxv<_vL>t=EvzcF9CgDPoTb8 z1mDWH+x4J3%qDn0o4m)v`vHxo-vZjYQm{|VkG%xnyDqTT_jv^Q2C%*m&w73P{Q*?T zI>MZWnf^D2%Zyg)|c#P(oFUVJV zIJ_^icm9R15UxyPM{1k(n?lStzdGA4Ve?Jz3Y9O+T^3pT!@dYiVI)tSe(b{bdl$m` z{=A&9`KA}!1LTwK^TsgilfXSvG1J#c*h5ae+03|^D!8s;C;UxH;C_o|r#cUY{eb2# z_Cu>BYQHIQ?#E_g9V#N+VS5j?rM1iy)WK3cJZ=`W|2Sds*STE9h3j{&FPiZFopESy z)awNFM+~)HMbz_Q9p`cP<*MR+&$A3S8_AjXNi`Y1yiTw@6w_6F+ zHwW7T@a7_WC-%LVq6$6iu&36 zN(2RQbBJ;CySLc=pT?X)fz!cR=a%#YKs4&WERR)$+8 zfUe_@t(ft35PaW!HvbTfY8T|2jDM#Xbl9H2e#;>E&N1L?Jtn4a7LE@vZf;4SzHY)V z9Jg-nq4jkM>YGcfPj;!@6V1XC6Mu8Cok3om{P1We&6n3Uv$Jfh1I&+WPdd!3Pi711 z;KBU{e1lc?4B+vjUpM1xN4K(sxez>R9Zfn)pC^4IW@lEM_kjRwCbBwY9T&s(<2VWN z*OtKbR3FiAiw)M5{et}#D5vJt5Pu62xQ-Yk_>L%YFI1!kG;mS4kK4n=K1^E*8 zFe-uTh%(OC!N6W^n7@$LA>*JJ-vVO2`kn;NFVYEnsA7=+1_k+MV|^iixT~%830enU z+sqzZggq24{};H2uB7LQ>6=C1mNCE$2;ycFc~q$c>fj~#W;L`h^ZC4UTpeJjVTxB) z$Dxwwm3C8}h2dUTTE z#y7W97`OWoHs8rwFNT{&tb@D$>(M$G~z=^+`kfO>L^?s1SGF`Oy8Djx1^<3I0xnpV;TU{l&98XmAh2Z6tjqr)+A`0_$k)xr3qPL6LOlDtMo%W5+5ZsZ>m%}=7yIq*LUM`bf3x^t z$NIv2e$=@`KwDSRj*9VB2>V@`!0|%96<$X?zw`mLUQ#I36?f@an>Wn*%})45*-NZn zSOQ`?xCuL(Ui988h?#88j(x?f-yDQr*jBNAVG~{dCDwO(i_K#V$Dwq>&Qb=HVy;(q z39cii;dM_~P(Egty{M8|70sV9vj;DZXQk1pH}@4r-d9LQ|4M;<@r@TwqTdEKo5SP} znJ2{T%ue{*uDV}lBdQ_3z&V;?rh|`|Urao3qH8o*psQBrB4a9a|yq2)~NHM;Xx6eG}FQQyE+em!2A9LHve_y zi}B4S^7UWD?7>jq48o6J?#B9Yn&7&TpUC@0Cs5xUY-gbFH{^8T354r zBY$7m3^xzk1LP%*RwOPj2@r8IAZ8DS@hpqzx20cJW%|upN=%2Odf|PX#`hP>L~_Wn zbex&K88}YD0%Gn}c3sZT=WD2g2kQXqJH>L?{4DEkFAxRaVd9rB5JOWrkBhtzw- z_$o`(xKkSGaB9u)sVF{#y3H{^>i7^kp8n$?#y9JyvlxFX5RB{jgkSt#<}K#>Nty@U zMxV~m9 zi`FBxV=HF*dWpERu+i`$G-|FOUk~ALbrYzsjIaNN{kK0~D~_&e(wCqh-yo5%w@6@K zl1I#2x{39h{sZDx5a$oD-goHFsc4>6NJjrkQuO!9G4wZwKfEu}@6g;0Axz>=dTGAD z6(x?>{&gQ$?HBT$b0;UipgkXLZRT&O*pFeHZ`pLnPpFck#f0O`aIMwVI1Bks$=Nbo z)}<>sQRtvM0XOW5s>5BV-Mz&Vr;Uz@^qiR==U_hu?UTIMZ)=}SDWP6pnq=Yko6-B) z2z}cnP~T)6C*e8}`+y(T(C=*(I;GF$MuQ350SJ~#l0KhS{gL0c}L&MQQvRd z(BBknXW+*Jf2^{S*1;vHLpsrKPwg3&Fu$;2zL1x=#tu%U`DP39O{pICix+?CCgK+~ zl~CKVLd6BXm0I0=2vu_Eg(&}+`I`^>8~E|;7q?!Z;R*zGC_p1SuR4kfI^hhjPy;!5?^`7iKY-Tdr% zZQOK3KW-Z0W)c2&C~JJe{7pg`B-jJk*}ot5O_*OO=t2z*_hJHZy;ui`>&pD8=TIf1 zN7Mz`uVKl>xNv<*%dsW9qe?bB(Bw%o+yJrf-ywnDs|yf(z3baAP844^5zqSU+R;k0 zUj^U4%;e+WdD=_|55|Rj=V;9Z=z2u;NZ-%#%{MLe)qE2Ctxcz6g;6D=N7TiPZ*uK0 zZl?s|reMC1PaZu#Ghu$L5IXellmzLC9JL7OKrV)r+)Vq92H-L||Av(9B%Cx&Z#Th#&fv%b0qF3VIE^R0@{er<#f4M**P z@l98LvEx#6jZ}w2!1G!pf-B=a(^i7LbV4!eDEB41n`6IN3(v*$Ll+x z{Or=8gym;hSYN;mG)l^&`DBg|yU&w{=(m?o*P2e_dZWZGc)w1_547`rM8EaedK}G; zs4`NFui{Ys4dP_E-tQjN>_Luxf0H7jHvM?s5*p_dn6C$jIQji6523iOT8<-5zBzSO z9bh~z`0o<(x7doA{km|T3i;W>1kT^&)~dfkKKWwfm!3vC$mn16rJv~h*o?1&aUrh% z^HfErrmt^oe7H6O_p{%t-NALl$v2tsx89Wky+azr@W)ICUx8{5u&&`YScmZmj`JR@ z1H|9VT1B>L`g-Ej!H369SpWU|hiS_+Twk2HRy=M(-q)|{*4?O*(Ie_&rmvr{-)Fyd zpng-2l%4U}Spgm|Apb2=q0O|YiQ)rI`C@$`Kdb%t50_CT<5Qxl%y4Bi)3zW47>Bx^ zD+S}5j2=-JGh7GOF&QE4S<>jv{-!HVeS^5)z%PpTIElu$LNfYS^2CX2A;z}}g1hI17&_myAe(Z|#KL0^%zYrgq zR@#`b{K1Oj8SH26FImd1@l{5~7k2_UK9oebolbu{1XVE=GrtJpby~dG zuohazo;>>If|2oWc07(SQDQP`NZ`PuRb~UI|LcR1?*^w8DF`A$_sQjyQO$9 zjjtT#{MZcFLiokS1kPiv)m42V-?6m2GB%peP99^%H@HH@g>k-N#nqXplF9RU|C`}v zU>$&Oz2Dxy^ZP?SYt;L^hHtF|RKDOBJGac7p!J*QSbTQo#C{C+@a*(UC|anWED!@< zqw6)4e3dWEv$j+mJrh+i6*GOE*nVMt@yFT1+cdsPoc3!c*4JN7;QG4sRk+{Uznh$a zXv?t(VWxviQE|b}{`%nI5tX*QItbd)V z1FRD?Zad^ZO^3jh`24~}tiw3&`3C7wNJeiVx#HAUx?9~phK-9ZkM==PNMAgs#PVMk z5qGwD|F{!(JaO{PNmJK<%OIM&*P}(>1ldFIfQoBDfXxQ%AE41F$3){nQk98ePzs_r$@s<8o{Q~@WV(FBf zJRJIUGh9F67p^|`m72dPajs8#i1@pq)P=xq-E7xM)jx>P+~U&D1AjL+XJm@nAbLsxd8Wnh(W zU}$`}4(!LUuIx*oJt#H9@QJ%Nr(;*G>g}5{P z$-B|IhN`a;uf9aToss+Q)^O!G*Hc}0sh=0}$!#5bjMH$XtMTa&!0{IX!(bTfV=QL= zW@5{UP*U6{kn!rKQAd^9k$FaK8AUn^Mo0$msppZR-;E7 z4h-|M8LkEM1sNk;jvdZZlZdbO9ZvlaC_7ihSF810N+ua+@ih-Yti-yfhqXo}#z zv=8%z`Fz7KKSzJDV)5=Xpo|Rc4E&q{#8PF=ghH%@zyR;fBbUb3w0i)gx~G6=+(M_Di~3_-s?GX>4(3(4qT$@6BM`rf0S z4}LLW(cfrYF1BK(uZ-;h`mOoUiOV&)4_^$0DW6`y-@#-4srTLiZwiseXy4m?c)@Z(OXEKIPKStap5}X!5{um1>pj$ z7afxc|?5n>u(VDH}|Zm=K(*K zVybVaFmB&`=r{F9C0@RYiVO3h;SCe_{kKf4FZA2j?}x8baKyAM`$+W;Z zvcaoXw1NtGRAKZudh_<}5~v?zDP~+`+;1?yxbmp@{DS6^O5i5Hk~rLK+;1=*_rAIv zjhnF*GacN-x?IlrG6S^U^ToMdE#v$Q^6JkTRrokIwi*leESsXn0l=;0YMC%x7lAu$ z0^q8Od1CYndfwv3xG)bGY-QtbhTy!#Un!iYZp#kO-+XcM^I?C#$46_K^%7^{==7!S*GJgH)n%+bnIYPozdrI?o#J(Xc<`g z+_CpB`t?A2v2{5G-{&9Z7nWW_zN2vq_&U(1gxU@Qw_a}+S3WGJZvpmW(08DLzP6%b z`W6uOaJd%yyK-54zJ@wv7g0Ya*o0iJWDWYDTs~hzJChozb_VhH`Mq;a(YWrr#B}hT zR{a?4A%AD_tu$`FpbiCFi1h~p9g>QP@pTcuD|dIVuJ6!%bAwzvqfZI7J;d){Z2Dyl zS{2uqpdfC5h-ZBb;+b4rOa~=Z{hTlk4=MJ)T6(tVw}XD?>R@PR7HntWZ?72mTb3YS zANC92o0)mzdxr1hVmkPUxO1Z3Dkh#O{QGzt>JY^J2J4gaPyO#(nr~i`7+)vuH`qTe zu_Cyg#!am*hMRFy^*6wMwAqm(G_He>Yp6pqwgI`W_OvMb>L)h;x2KMXi$<^18NAQ(!zfCgew^Tvg9D?sn1HZ`n zl*`x99#RNx_ZnD_FEM?y3EXzK z+A+9RLENOGYW#)VFK6MSkJDl){lxhC2);$iHDLG#_~V74{o06e=<>6hnEUV89b$a5 z28ZX}n+o0~IBy^~M{#|tc2Ys>D;^G?WU?+6AVW2}=T`sPk2yR(_4$p@wHr(?m zeUNV|f4q?ClTbUUq3UliKmPpe_zMzR$B(6$#fNM>AAsM;<~R8H-9j+-wYzIS9^sW-&_sE_*#g3=Y9i!OG*{P^>p=*CWadzboj0`tAmHHgCXAn0(Zfj zYPs}5K|x$gb9H=!dEtxy-R?)@rV7qm&}}B~?CVW#cktixl0rjAY@3Zkxx2&h_t1&Y z(60{aOX_1{{bnWdl8pWz-E1qsSJqPrwUi^O4lo{%dF0GG>2rgFB0L2;$Of<5FfOc5 z?z{R?A1T}5pa@Ty=^Mxm=f8)Fcg&(8tYs>P`jviOYn$Q9__~U_(ShU2|FB5g!FI%Z zUkQA@J*-!+xq4zc!j;j#k`n#(_J(mMw`tgZ7a82g+fr7{&K$&jI5W>zfXiZZC6$kB z$k$2S$9vnpH)iWVQNzo}rB4a9E%;iP4td>GePJCj(7tjT!#9uc zB(gI@9sIc80JqZn=VsCn9znj=E~;NZoP4)q(pegp*EaKuG>i-SUbY2R@o?zZ&2-2k zbSQPE@VoSRN_nw`L z#fLzg@xg=r4dTv>nbXeGpEId~n7$cUUzi76@>V`ahyB04ZO1k8Lyzcnd0$LRy&}}mvGKk-eTJq+#iS&7yg86T94>kV6`tOnsG%CN1_!{aPz;UNIf*8?x0uvt! z1of3M-y#V2B}m$1EN1!!aNI$GL8`gDD}*0iNr`eEKwsyWg89NaSIOS3f;v#t@K+L? z7ZSh2^ht%oRcYL`rebj?kBIBi_?8>A{45aT^}jS9KarQ*Z}59bxq|vyvA!_Q-+k@q zbM*VB_ZHJPAKNeZMRMr(lJv-yW@7rfiQhHKJb2cwM@9D)ixQW%vsA1D_?xY2eHe~( zCHFfq9Rj%DLf7v+p2n=67(Hbvf~>%P}E4BDRy5Uxp#OT>wdS!BQ$Pc6c^W!ZxHtzym+Jh zTbpUz?3P>|=u<*%1=|_;#q-QboifHCMbT>Ee>qor|p zDEL9Yui5x!C;F|wLBHiZ&+RuuJ1f9CK>YPSl)RYcV^iYP;Z3XquF?08L%N9S;3MM0 zfOoFtpfCW}VAEfQw60QQK|8<6EYW)xlSqe|?D&u#3>)-@h9% z^TO1-#p0w)=&*5J4l~cnds$2e3)TVrt!jz)defgN|4lJ_$RqOVnI#%CI#^4K>5xL` z(B}ZFgY^|L9b`g>*Xpr4I6oHC!Ajt|`?I*I9x>c3yblTStny=DI_Q3LuMo3eFUEy^ z^y+`^X7Y#Z=LK>1s__?a>lol>^%KJlV7?U)Zr;>eRcIY@`-|aviTg**xo2m>)|EX( z9`%Gl9%U&nW)Il}?ysZfwV`$3wavyi8I3%!Hw5c2%b#w*tQ%Pd2^<8Tj1x`&XW##Y!6_)^9c<-}!t03qBfG;>?e^`X0vm;@W|0 zQGKPS)bRrH$-1_auuuNj+WK$6t>%NgH!;I?5c-xG@i8+GaC{*a z*Yk+Dv+3`JZFv0X*SY=nL=ujZYVE*n(SCChI+QceA@@r$9b5!%B?Dah3Nc&{#)a#c zMm8^am)0-kb+LR>!Q&=u6)vtVL)xP+PBA|Y5cg~AeK@_lX1`LD`(#{uI9)=u2V6UF zEou)wtS?-DHg3?B(RvZkZv_4%)^851FN_x@4zS}}eviog#?|48lGrcQ+JW1mI!IO2 z_yRikXR2hw(3u?v3h%hFc$3y8lt{gat>Ir)+pUm4>jA>2XP{e3#J zs9~EYmY-P(+_5`Z+|2)p@l`M`^xKpwYnXnMu8ZN?2z~2il^jm%;Co&S*FoU!8K2DJ zmKD2B*HvBh3s|rIW%pu~?_iIQ^Zvh1%opNs(TDpo-w#MBFUXg`JvnK69<6Vnf*7uw zzOSO0n{g~_Y! z%c2|SX&urDeJ}ND$mna2k}r*GPYcJh3-c#2I%G$QOY7jk`#3OeE)Cr`RP{_(l=A@1 zk7>Rh9Cu*c{A2a-7wPvch>|aj>m>BO(xcQY8aJ(5boRjD68l*mgZn|-qP(9YjhjL6 z9XP1?V4ANlO1|`YUaT+7Tb_LFA7p20Psnk`2N&UQb(;3NOuw(?sp#~j&r5zbybg2l z#>BE3UnNGqG_DoT13-rw_icJv!*#@nOZQtgO4PNuzUbz|LHd2Yf;#w!e!Jc1E3_$d`89J)8B_Z>U)#K@QCW9c5YhmT*Vf~3aw8{_X$(fyW( zb%1f``lv0B((juqsDq#AxB8ziMd4EA>x)qbns0#Uw;f%xnYbPlo={f)pkPPX^m_DtLdx6sIP{n)#)u%eIZ|;ROiLlAJATivNq%E zS*hYed?@*R%RPv%jQ*9B-(vF%y5EwCep|A2(QLpZi(9bYoLFDv9@5Dh_cqn^b;PM} zZcSAOm|wKN>Sy8($=&FGOhgY^Ypc3rFRlcujLMtx}=WNZ&$zcaUPIz_*4fUg66N~j%}7S11LE^{F}Q+vV_ zBVQU^!S@k>31O4QKOUoB&lJ3mfSrgtlS{Do=?(Jl(@RqcwPlO?yX|nnN}06AXf;A# zGM^K)2do3c$*C(EGPu^YVz_=H?hO4=8mIM}FUGi||CH#S)db(UYqotyzwQ&ff0Wch z9S=Z<>E-KuPvZvp*CW!WgxY!dK2Lz#`L8_;U-wI5`eqXM%RJGAyzXgf=l+E8; zv6T)KH8Nin!&T0x<0jZch1;{y{8(QCL&b0d#Qow+COentQPG~!|HN=T*dBmy&YrUC zXxwbU`!NLw+@UusGq_Ht7+V`ooU>_2r=9|;=YSFO4aW{H8rNaoUEbinU!Ew(V>(Yw zA?7W)SJRi$e62mATYsQ&EqERP^Q`AGC*;t$_9$`b^V0BoD#Z1XuQx!$RUsMuD+OZA ze`&rl<_r6q-j{|v1DIrSMah@OO~v}cJge%#b*QB;*-_%^&q6I?y!h21uBS$M|2~>; z9tvbI7XqR$>}G}`DXnL8_Q3G%q0U=i9y|5XPv6nA)1Utjx**>~~^;@Sw@0ne;wa8v#l9bfu$ zW)b%V99?lZdtF78_XVVNu;Kk7Scge!y_Mmc5hY(5*MW6_xPIX51?GF$o+xo?9h?O2 zkCisPq{VeP#`wVCV*7=8%^$ZDcl}u|(QmEqWBV=V3$eV!h4~gne4o0WIKG(}7vf~g ziPf3;8?77NHk%g)@pu8aW8V`I*_xPo*Z43{J@T3{v0?ZfU?;mBi&Wr$I z_>vi}hu~YfT8V`5&BnOEcUif_@pTY+RE5qAzCl;KTifD(UIk%bEQw-aBZx zbo})bcGj-t;W0Fh>zU}rAsW|5=zGYz0o++v>`~(CPC^Yo5!Z`VyIo!Dx4;{*<$W}6 z9@YW+ZSj^{BKjKUeVI7#gMRD$&1MEy5u9%ZFkhGleBw#m@44HEdExbWZf3nNiGP24 zTG~)Mfcp(ZT6lgBl3BG#PxO9lsIMFA3p$i|>-1Ur%`=*djhj+?)t=x@FWuZ7<{PJ- z$tZJz`4G&z3%$qcn_r7NpEuMYi_oF8fewKdVmdgmJ;3_!q#f*ivE604*Y_Fn^$>nB z;SB2+zU5+korL`^{$?R#zXj#Q_+}IOe*MW6#?HL0#rOta4co&q1HL(p#O%RK@Lg}f z*Ro2CuMOWfA6wX?pRe)FtSTwFst%fa!X2m&lrlARZ(WOH$8DxtPzh#Jpeycjk1 zIJk$dD9gCGhJ1a*crjw(7AB9%5yZ_Ua7P*7%3q4{^%L=T)}s%e(}@6$A!7FH!}b9A z!;~(&nE0D7$TyGRJJ*13j^KWw6UQ^Khp`6sU|S)kZ-D5xHw^mCwUUbqy}%S3VZUkZ z{$}jg=jGxW+HXF=x8r~x8T++W;o>q};R!!s4~?_#ew;oiZ7mnqkZ+K%2gNloNaMPy zadGKWLTwk3|E3!8-N3~)O5>O2ehK5w6b_FD?c=wHbZ<$Xr9 zbqzR&EEZz^7C0Q9zxkq{Z<26#{?EqyPLTip()P2<+B{Z@b6%K-amypzU2~Sat>MZs z;?nCdHbRGL?Xy3+^Fi=G!6?_)Y1|-Qe}HwwSCm0ZY25T)(XAWN=P5`4m>QoG4>n%e(*(f&;j)Qs@~}@ znb$c_nDI@0P~{8P%l-S|59o3Q^~gY+{^r1T2J@B&3(dZXaAowb$DjP zn6VUj(-Vc^q2PxL)$s7)$6u(1hw`oZn1X6}I5w+~OjN_evqgRQPz?`FU)nE{iGF*n zN#Qy)*CfGp&lHRceo^z+)*ZBdQ^v%%?rF#V2Kz(hZ?fYM&7W>-I?&Hs3BEs-e{3xM zI%e@$FD~}m_kgB@BTgOCiMZ48hVxyTpI@-w{DfbeJJTJevoRGj9ej8{7WPf+ z?fC82m_X6NX1IQgTM8X>`oQOm{qo+&3^zdN(ECUEZ5|H&x*4vG@VB!ct)57qC)>rw zp&-HcM4KMWdI|kLblZ$?8onPi#P*--jon3`7Zm(Gs-)HGx~7Z(8;+SVTEq1%8n$xM zc&%k#oAFI@spAD0ZtAA{TGI%5Yq{&G^eLfsI_@`ANjo0A=elN*p7HU;GbdpWkF_na zO2hTViJOFfpP>xmd+fvenY`NYLlRG#>FdLB3$A-@^Xme{S1roN@%5Y3LDdoB!;p{a z*fiW|Ycsy-*d9QDq{+)h(Rl9lV)o#~@fYmj(B8!DXJui&u9y?~$^mWCnFZ$#Vdm)eNV5!`O=F4lF`9%uxyNJUFyN}Q~ z!LP)0aQvd`0M`{)9PmGeZ}N9y_G=raj*ATu?#4GecGvhSmE(&$-uqR)ut?L~;C|-X z`38$hR~IapTu-dfz%+ zJ8&&}A2<*C<~7(a#P!!lO+e$OB%?>v#Z2D}V%)qk#nL2dKzyJXt~6HF7sj`i{!Mqr zH(#9Nn~ZVM`gEhvrAO&G=>#>oEHgc%7~r1n&6%5{CKo)_lMD*m4a8i+IB zk+D4h-@s0Ev)UMo*$ECD*P-8j>)d!}jIgG0$BA*_dYC`l2O$mC6(@ha&v5_P+Dz>? zSXW+AHV>se>L+uYSMyhg;Pph`*9i>uO(pbIx|{(Q(G@rU`VvFjv_@fnJNw^0#^2IY#QZow=rH!s zA|_J$`8w!6pVsga{r2_fPy1=lYqekSd+r4fh3)sgCWSg`_UrpkwOYGOB+va3@W_(K){QkUy;Je_Hy?@aos zZX@`PX_W-aiMmoSlB_vV7LtSY7L^~!@ZRQsN{C#Oyf0#LO zP&FFEH(rcyfQSzt&l~*;jqCoFd;Jc5N~rA`8O|SmKXPjieNd*0%h%A(>_oo}>3d7{vpdSx^d*yj9h3e9-11@jh4rWx?s+x5ZiHVCPT=x2)WJdM zP+iWePQQ7w;Pp{n+;89zs}_96?8oLz7Ah{9#z_s%d}*Wk<~bs-gQGZU*l$jv-yYnb&e%iJyJ9*> z<<-0d{CN5!qnZ3yJ|(6@3ej)#iao*XZ)UtIhAaJ}=3y{ieEP*x>9oEnZ;R<5V;unZ z<4JFIr*V^~is32*?xt<`_os2)d|X3&@YGOsfEQovJFOdyE4?SiH-+%yzlWT>O5^76 z`O>F^+6rM0Cp)~8OCMw(A!ZK>!8g14I}G0dpRb|5F2di|l&y%ayF#9ciVM$U)8~un zYbW?_KmHTL*P1DaOX$0F-kSZizDWzja2-T^=<@G=w11&5$^744H`F(i(0642=9zj_ zvSVmpJ0X1ym`w4rfb8Df6yB>bXsxy`@RxCQ)vGqf`=5huSmIq4dW>-j*e z-!cilhXVr{zVb9NTo0k|&OxlcS$(+q1N{+0Z4bfs>aspgXq zc>gf?9cV{cuD*u-<|q2C;hXE=`UhRfTFAxK9j`TV2s`s^o4QAPUaNhAIwT!Yb%1^g z9$4N^!_(@tabo@EC;0Z8XJz>23-VR)@72LVbyr6rX5OOlHml9%0Rf`lhK{&&gE{|W zv3|?PI)I%`?A8!20-D!L_AydMs9l@C~A1ei}joIylM|{J?+NK{)-u0K3_w> z2om~QD_U;Rxal4-9g+#YE2px2^Z0yeDxtQY(D%&V8EN!ENuP-EwPLnN@hGqeXw&G0;{@0?uN*3y-f?P5CQ z;`Jz4C#ZD1*S6U|4Z(h7E2XQ^+jb$IueC>id1ik9M9$csJ>XvuVwzt|7 zj-&DI>v{0`ux{j8^nsP;%WIq2gBRyJu-~$~Zt*KT9Qt)`ocsy@K02-)xQ-%D(r*=N z`>+nMj@bP~iN1yhMR?Lw2O^JZ-GcocbKiEc-yf1*QthEM;xw{`(uAhwZzhK8pQ7Tz zbrlb9*^gS1Ok+oCBOMImPI6-v_bznu#F8JJr!n02$m6CNu8eWvdamaTzK@yw7KX$0;%16=p( zk?q$sP7;1`yTe%+Hgv_xUzaoFYr}jYKHPkH2XkF!0UuY#Lu*)x_wO>VWUCx2y1LTwSUVIJhZ(Rzb&iZ#?{Vk7= ztJf8`YztL?gLSzNyopWVgRR#&L_t4h2X&rI}f49$ramymW;)l0)pm9@=ij8kM1a9w}EUv{T z)^C0ScTD44hOg%g*UspVsJ4r#=YhV{*R%RcK{4E9j0^g9U%r{)D;?qHCB}T6;rKA~ zO*TGco)WX)Y;3w6&#&g})bfYGsHpRY5MTQKMpIH zn~QN_9O~nIeIo%G`Zq)H_q%hOsCEz6_pNDcsYT*Q4xGU%aBfA4~kcX`SCsjM1Z_>vx`w93RYd@au zaGeC-Cu^K!_~sN9iw`*jZpX2CHkz-qzZl;XzYpCu(>ELcz6b=! z#dTW$rukbS&hMkA?o-!cVBGxX=aqJvPipb#^rhpO2Y>Gi=JVsLR9!;jN`1KZr83UX z9t+3c)~VANT+bh3{^oo-yubPN8|%<;gnPmjUp(^?-veBDxXwjJ2S;@AjMmqOaUq^L zep~z}jhj46EUxEaJA?hr?4}PQcUE;!;?%)U@LjX77PF3+F32~T_`Tco8Ku6bb+8VI z&W~w*0|ejiy4|;x#?6V6FO3_-xR96JJ=OIIjT?v(mp)G+eph*8yIIZY*ZqPzNF7!C z4{exEEB^|On>1U@&K%gDDkH#4UwD>kcIJxF&S*X!?8mTf^z`Mx%NnjHPFxqE@8qUk zchT>gKQKBwqtBBksQRLSBkh|v>u1DQM*m6<{5d8lFzJWi*_{zlZysirFV{~v262lGP&szl% zeSgX9A2l7MN%7gQjL!#Ld!PBR4lbjAB_&Q==Q{OsR!3On_I{1ru8@rWl^k*6y72iB z9~ulU3Hy37`d9MAiEHbn+5_a)|MgsQTEh**iEG9A1B@5zwtvgGWp0%5fgb16F<*$k zJ0JJdM3t^s1;Au36dh<34dw&lbF3H_=JPKnuY5fUDBU4uxC((=q+SJ> z7R6M|aGe;p6hce8+Ulv8K+(ZwxPiXmakJ9OAak8=p5T2j9C%&`>qcz~A7U8EVtVf-x)&<;ISL{Win{Vn) zLJc3G@5+WF*3qxaPO)(_6@L#K)-~qse4sUrYi|tu0Qw@5{yBxPTT!Trv>!;I!Z>?muC<1>B8!DOt^O7TGSpqU#omkqAtB$Ysfb= zUtZhH-~5+UT)18?)iY`ps$?D(`MMcye)n*{oxk}Fl36{{_j=U*M!wCR|8wzmnJ^yD zeC$5NUd46&86U0}>w7Q4z0&a791YhKB`((<>f-yS;@W|0QF~BUs{ID*Mq~Q*cu(W& zI~1P|N@4YUh?7H~eWnwtVk&0#;3M?ib>P6FJA9+mSHq?AGX-ssX@30Qq8jaKvIRZ3 z>yz{;p>_~oUk&+W>!UwhpbyFryuLcApXwKYYc;_23tnHHj`I?TXYcRX*@ouJYn$oo zCGvG^{{{1C9OpY?>qau6!=Fc3eS?Df$~doqb(oReHvUKR<+U{(=;H!t<_dNOele&< zmCc&{Du2c2Z^@Tbdw_9sT;9T`>G$Qe&G_cxek+3j9{asf6CMuzx*4uCTICDz_vKl` zn0*}S{mA1yH%^|$aT3=KT#Lp@8@4mx+xi`ruZ_dkOot5YZ!ixy)nIxnT0dUf3^$$N zYc=2-_(Ci{ldGzB3iHjy`6u4y@uOci<15V#=MPhV*yYsxLcT}6uL+Gqx6N=}gbqOi zJ4^afOa~V+kNv6H9(8{}>z?{z7u45^?F{m$^2K`P=u!DCZhUy+E;X;lwFB3p@j)SUs9TTK!4;(r zbY4jhoa1pO5!cVJ`@JcTAN{%+Uk{=0E(3p)my5+S z1^XMsoelG@?WOtf+Gczed|wn;|Go5i`71PzQ;=^K))!UMxNe)<(73#|8DB4vPp-}H zx0=Su`Y3W_~xAaK4E-w3BFICs{RnoH(yX+7aqr;-{u5{-I-^3VjSP-cxHJf z>~AB!cW$Tox&+t3eb_I6ufN5wEot23m12GoAoT4#{g{WwRRnRp*dFdefIi2)X#XO% zVrFMjT{TWZK3SsqcCQxCq|5QmFAA^@6%g*4g8N|mNmtSZb;u$7qDrPWVSW+7_5ehe z-ZKTJMY`hqM9`0k{A|I31&ei{Q8Y~Ztz!7T!UyZKeC=K_`}JbJFwVc6Re4(!6m^G~ z@s$a_y+*TqgI`CNPtx(hUps8Sx8=o(jtpw#trye5fyW`(pYOVL^+6gpbCnpbpRfnV z=+wzHF0XB-uY&ajzBU8CDXYc!+K6#}mc3=d_&Nx_UH)P94GQuNV0~d8VA)WoFHcYU zbu)c)aomA8xuj74cJz6?wi&L6(Ba*NYZyDTuNCVz7h%6c|7P_~t0v}eQm62IzRAW1 zAPv@)Jh#}ooR83<BO67-tlt8dFN_!O{#kS+4P}e+dsK8h zOTqaL3_u6YzVQT&n-=B#jmA|lE}FPWGd{XCn#Q#Y=27x}>No^(=if$C>@;rrf6?_D z&DVnM4EBf0ji}0uLm7j_*4I7QFQDIAAAgj&{vl~}>J6h57C{bCS_FQ;@I4q2}wb&oJ@+i^FvyphkX_eChMD z@O281Pd@(HNEC+Ep76yuzo2oYzruXGR%ZF8J|w1Z0P71I=(RK60r$|AY(al>V0);F z(0*>8#;l)Z3i1sS_HfO;vA>QiYS`w8#dR0KH>(57*P9{cZysV^`1Y-pOgzgKPw&JBXC!HS=@}eVs_>y;`-P3_MA<>Z-Jnld7G>80S%wh`PvP9 zG%l}g7ANyDU)Ud-+dXe5jibCPXlL!zyad*x8jLOaF^$V>YkcYB@`(Fr{W|dJ-t_Ak zyTrz~q`_+3fp}JQ(S+SJZjPW1QUz5%*mr7wCNDta^4drTkdP_1nqhsr7x@U%2wm|C zexEmp^@Vi+$ZwflSSyxWkk1M@9`aKAdW?mHb>)X3f)UBA)i!8Z+HoQLaS-u}Tl zKpThTFQQ&AG34tc^ldb^Ff2>yiiPvNTQmDj+N;_bbXa!!>{oQ4sF9J+jXQ>XT?F3; z?>bPE!QCsSueD=%JpL;Gol`V!@-JezDR@5sUA7@T{0aNLX8L{Twwb=ESYOC@+6_Jo z>7TAxf8pA%?s%<{i->}q0pI`CUVdA9KHA!huMP8s_%Px7VlU8m`Nzcc4eV0w9}M?O z#oqmC+`QvrxXLKi9)NGf4&70fqA%%Xx%R6+0k<4Kt9)U9bNBd985?(>6yuwU?W_pG zy@YmoV=ZR==D~bH-!(^$_n~nEf_wvn4*%tKV&-oJr^Iw{2f}f3&4$(}KPx0ls5p*C z9Vg*%w(Jhu+24&HeuO^2nJ>oIxg%_6H%9o5(ztSYF*{QTzCX2?c#Fo({9BB#1LK1I zUb-vSL*v>`i{ZKmzDuvJt4HIy2S%5#)8~2ccmeaFj)NX*OuwFfhRc`nQNYM*rrH_o zi#*+Z5;GsN{=>zksf5~I%oo-lnmtjU@e4m6*O0FV^M&}3dF&Pw*BxiY_y%87`=u7b z-Pv-|lF)}B|C|%U_2BpmV^Og0PR1T`f?Qlf9kQ_wFu!O}x#tBfkCLXS{+*pJ=5INe zFABrb{5qwXb-C16#BlR5F3ej#daD(rmAYcvAm$eqw2}eZf)17P8#DWm>B92>6&Kd4 zcP(APu7lge=2_`Q)$<@BP9;G=oo8W9-*DH*&x6u4D3)922^Z$%pFzu0^k7 zNS@#LrAT(}``+FzYuN+XLjk^4st?wqk~xf^lKI7_fLm;n+~`L@DMpD`98W zPd0624&Xdt##h0(U=NcAK3AOs!@O*UYa?*y4S7CcxK^w$sw8P!;;y@L5PZiuKWF%+ ziQXTE=(q2lD#YN*g19b>3l~oQ@$O6p*I$7xL9p3^^is@j(xTuoON$)xJDo9d#c`;l&ft%*&;i7S!mBnx! z1n!d$f6$)B<+XWnUFrK)D6Ttj?ZUNaT({u34*IUYKK?At&r(H9hjc=RK^v|?daWy| zg1Fun)o}>s7vsC^dQ=CB8d+b8*{_q}Yk9UMGk=q+is|5dEzEb$cOSH-`KING@pTb= zA6&rZeHns$-9()1V*8^m&6n5a*{|GjoO*pVt{u1*wckuahadJnmPYeSuO`-SZUT3b z>q|6?iLLN-kou}R$hcOt_SnV}XrbT-{jP=RCve;KQrOOJ&3h!3J}k&z{|%i&?{~X# zo(k*WA2r&@3`9u}aP>8u7kbgk0OXU9pWXe|EHp3Fmt4Vhn4RiY@9X@Yf&cQ$p=Dd|y_uwT#J4n0c)Aycl0U!FQbjU&{kreGU0~ zalgTUx$ZM|Jt`=3aSi(|5Ay{FF4~H{-(coNt`3HLEhr-cZDB*CRq_Q`F3=VGFz$MZ zA>RPzTNI(SXvWSrgO|kk`Ui*kwm0A#tSzQ*KEb!G0blE7F}^-*51_BjfNxrg7~del zx0?Z9=M^qr!+tBkxDeOvZPs1T83Qz~a&ehc;E4d%0rEau@4iet^YC#E`AUz3$D!v9 z_@-YI=A+L>~ji)+YNChY8ZOV-Y;l9)YMFkjGjX6NUa_>k0G zOy3kj-wztCXX07bOI%z-eQkK$1itSY@J$)W#WmE|O7Qg<@O269x5$LPTjq>l^tJH! zTMYT85`2Gt<7Yq9npyI$;6Yeo}Ge z6Y=3Xh&;7I_14=EyspSY#q2@B`a)ja^XRr2I#AS5%8BWlLGZ0?z}L~2i)&~PX$0Ti z27ImMxw!O447K43F33~C-;T`b&CCl6hKuQIBkcFg8>=tUZ=O1mi%XxPw(&X_~ZTFAr^$(!Mxs+kd`fr+ptFK|d*@=Fuf2v?R{pQ|^TwMB;P}^r$ z`65S?#(maZM*fB#lH__TYJW52>mc|(V!$`|J~6&-9Cx7KTJ(7iO}7fk=wGy088zR~ z;q*F;(q26u;*Nd#?uSAL5r33kV&9W+qYI6|7GPfZ;THBf1>!9X|5c+O`;wPfM||_> zu3GdF86Cvz*YT&y7uKUTZ(SbN_hfAP(tJFtRa`I@`^wS)A5$^Y!AIy&b~< z_zB#}eIKnsllAl0<>*sF?I3|$yUU-|>4RK?xSo<~|G>INUW3c^B2{4+X9-sky%30F9fmFYi~W+v*^KPG~d*n(dj_PGY^iFfIIpA@v~@L>oa2UOeXp*xMo8W8rRn~ zI==LIUSeIj^Tshu{!1TEx6SO=kL?!%&Xz@AFxLg;bra*8i?9C$8~*wJm8WPvIh!Ke znHgUn)&bTDzFTZKw9;>-Yn$QbVO+>lhx98wUUw2|*q##8!B;1I9n<%<+rC5N790@M zK_UF&+r16Ys!VLfOb5R+Jic9h>@G#iA6(bs8{cf0Zz)7`e<#cO*w|{b9QLd{9M8(3 zm$n(`>*M^s-mca4C3v{jst*sU;qfzmNRKQoykvcSNyfE;Ye!Cf2_7!|pqZKJ>mu@~ zlS5v^3|c`gLwxU%gn3>$rB{S~RY^2^}tV{%!M}9v%~&o$>g( z%6t~$>%p}T*P?ubSYK30&WG9`qV+2nCl(*vb=1!b^TPY45ARLmrW_KB4=GQo^A;HA zPmaj9=NX(i(1tCudUqj9Z6#o~JAn(#W}?|-Zy0~r@ zAN-gvtP}kE?=KDS@QpI=@bnE-|01NXR70(0trmZ^Pn_KP<*E=5sO?O|7y_~NfZ#Isjte7c+Fn=v}F zJ#h7Hyj=B*N7P!@YC(N1SYJe2y1(1rOq#DfBQjqzzp&%)HA4=ZG;YBd8aE(|`CEQ% zwck*ONdxXKeVWGQwaxg-gq_{`yHPb7$IsD$*KeLlE7b7<*8yCMju)2K)c8;l5xv~u zrv|8!Y0i<_W;%EmsQN-aS+cbK%$>Ls?`_5ULjL>R(Cv(0SjI%QGoHS#`d@|g z_2AlvYo5Mb+EeqC{{?>I4ESbx~G zwdJFl4l@4UIL)7KYkYkV)d{T&Xs^2n+~2>jGvDj5{wSt{7wZ7)M%SM?zg6SwiBSi7 zpUjQ#-B=A*aKh|{6KEGBwi>UT=H+mwu+Pht~=cBDPTyK57z8-?_)^e8y z(RjI0-Y=6r&qa*$?%fYArC(1L{N7?F#)a|i!!C)t-?kU)0ONe{=*a)ke0gn6U-~#V z!S`HAi0=C05nT7Q5#Ixx+1I^DkBV$$wV0iGFkf_`hIG9W`@I9tb7HvZ1mFHQK2F$v zY&PZ#^W$ZEd)A|M;I+;A&5Lni-*j!Ad~`jczNAFiZ%lkRrsfY|2@6}DdR31qNd+6k z;+c=Iv+7$;UZrsZg7)Ae{9=-)|F<+QuWhDp9?@@>GKuTAe4^i8bF=poQw~O_FWqm> z2i1N9JDXi=c2oLuXKjp(%gsx6uT}FBT>EexZC*n2wH^=KS=)=>wxId?IDF0eEd%>8 z#NYR>ZfE?$9i_fBpCsfEFc$(`r$N8@^CIhO#y6S3eX`D8hOhHbWL$2)&0eSW8?Jr0 zj<(-u9a8XpdXdahr|q^c>DROCiLKKr7#H?0-u=c}i^g>ees3lP>kIn~^ZHqsd93ZX z$oiV~n*|vf*h6{ru#H%sLG$(Tzc)jl5^7s9U-07>DlK@3J}B_J7+*Wq7v=$d2r*8pZ`X z8)vJvoPIq+5I2DD{|oEjvwj%G#7XB3F@0@>4*A)M%TuLfb^Wap;`?LM?Vr&)VwI{si1gC+xTSxq2JugM#;n`Gp6^ zUs#`<)cDFu8aJh>n7%=*FYE_=JZ#2n8kg7B?19cFZ70OswCeS>b$r$Ip!i z(YTod1aaR8`^BM4gIqMOU-bK%1mB%AnvS4xd2P+k=;QoYU&vD(TV8yHe!W1DuNCt} z(?hAoqKp+ZF0XCIHy`tbxU(enSYsL|d68JZDFoj-l{_tJTwdFZZ=j*NjtKh~e~hj2 zG7pD--3-@7elT!ciJfQa%A28#wx3(Cr?}=v+NAl>;X?su% zHyb5pFmHi;r{!#Roq&EHx^1SfY*qUW?Dw|^UYJ0imy{yLHx=2@A>vuhw|XUPpTUj!f*(I|z4$jYUwf2% z>Ac!~Qtda;;Vb!xIW(?+i&$QrP3Z8AC#^1x%WI>416O5=2kQX#`$zAz*XRTMQR+aS zmyfU4fIO=6!-rRE`>{%t`^UiN|D$O3OZS_Xh`+n zUTxU45Ip2Y>O(;_Jci(h@(609N8sk}!Y)*M@WY2{cm(i+ep53$b1hNrs0KR0-Ma?6 zu1o__Z8KcS8McQV?)U$oPUALBac8UfdNM+2@X@ndxj@tbX1G?u9u_6g9#RS1FB6EH zyHT}!8GXLN9lmcweN1lCOa~k03+tY@q&OPY(Jp)U0rcUEFO>xl* zHTW^`EnMN)gW7dhfuL$9JYX~20Okw%!{wj)_;@(<>t?t?j0@L6zfz$Klc&-+blVKq zm!;|ec~rl>S37AsxTeRagM?N(L0`~ea;;e*9mW53kKzPxbw^A+(+vz_oNtZHum_%2;2pvrfMb zxW(f~ziy_ljP(V37}}&2`ddgweTUM=D0q)Z#f+~N>u@hRdHO5g z{1^$t=rvPZLWcu2=N?BogiiOw>2Hprs-510&^ms<7g=2)8T~7{uEb}*>DYc@9{cFJ zjR~8_Dp+4g%zP_*1MQfKnZ8b}1K@6*)PFmwEqjTxvv0%cnX1Ey`7sjCz z&(yD)C|n2O$H!|mte+@c7okJp6|u)NGaWJs+}6DxJeM%Ogq>vvs(BKHn}+jLwA>}7 zH(#ExambDNLY(~c`iZ`Y;_Jb<_aeYat!yX?#a6U_qvu&!xZhwt)aa$_OngY)6y16W zjq4$B8ynzeOo=>?<&B%JvzyfG#BlAyb+qFq%{QCi`-lNw|6#H34|xgPM-6a!y=c~N zIRx%w2DtgZMdpi6|9>ff8{+(BiBSHSs5kll;%laF9-(hj1AT)dBkOC18z69-8Q?0T z#BlR5E{yY*)SXP;=jPz@{7wF;NXXw5Tsv?bt-sNB;KTa?kgvOru6vt)JzH?y(`8Zb zcLmoIH2P)~y6#Ht2{|jiJSsm;UDtqhxuYGrKS%S;5ZsSVX&$~m*BkOUCayakj4uAt ze0jw5Qm4)eF~m)3Dg%M1>R@D%ihZ1B2^!1Z{)=_Iu@ zI4HtXn!nM91n~EdVBIMA za3jBtsxR7pk{Vr3+SdE2e|zH`U)@ z4dTI*OKWTMA;-D+{5U}T-tEkCMRwABllb>RrcVjAlSha74jeqyM<3)H!C$YI>61`9 zP(B=YzJ2J)g;FPjgCabI>=&j|Oz}2T?F{BEpFLEXiNC3W_bawy9l$SME;)j^zAs}7 ze|(b}w&;62SO?f|v5$W3Z;9C{GdPKO%FK_0ggu;pjs3lu0@3RUuB!S%zP>i?I9wK^ zE9v#c{6eaw+CPk&TZ(K!-wV|j|951q0ythe~~OP>R63+4+8 z1SN*E`eu$3!g(+c!2dxEVk4ab?7bE*7*C0^=vxISzTknbe5x_*?#^^6t6&B6C+0Eg&! ztln4}SAIYY*M$rh^o4nBLo`~%TFm044ch|*(I>C9W&GHeD#kahks8+l@WtX6C)0fM z1#vwV_4^Ev?~Hwa#V#7x`>$Qfu)Y$$< zk7XMj6X`iK`^~}QJnUaop1AfrjS&>o!GY};d~RCTt8db{N^`!xGJO(i%QIEKfN_4z z%3;$a#xo2~BAzmfXG#aveqkI+Ki+!~aY|JGn(6B!@~G{lCbXr&a-z_IJ_p)<;(j*c z4D|JH=Z>3(d0#HUcas6%>=yifGve#Q`3{W7_kHke6Z)6}KCU5OKViSM4eZz1QjD+s zdN^ONV`J^t7X_|Ne@N7}Z4KM+g}~JxrKtu7MR>~0&hm(U8*ndcXQ{2kbVwz1sA8al zoGWH$0fKKI1HO5JeC0CX@y*rh(?+zEPM_HL=EUPX-Nct7+-0R8Ydxt__^Zyf71FUwGqRW3EY_tTaTh~vjuTI zgH*m%5n!E%0IHTrbzecs0S`MEsQ5c${@kjgyd=ZJ71MQf-|!5X1V8 zZ1A>j%op;gx!wUkCyK8P=MSJm0vcK6h~)!vOa7T5yap{Q(UyL zqs5)S4emQ*0Hu4%4A+?w=G$<2`~F(LDKk_*)PWc@09Q76-hyVBz!&c%POa~Vp=V89ttI&hFq zY`P?UU~o``r_A^&WyAU8`LC-me6t&f<&(MXRlZ=j%ZE*PiKZ41T$gi|Q~82l3>!Xp z1C8q!{2dS<{yj_J`+;}iVj4F|a9!E^fEpjb9-jYiC$pX!EX}nCa8;(HKN60U>2KBQ zMIR7I=I1-~Inb7g`P-Uh9nk)-Ia}+w(SkjBlbCu1w(W zHNdq^=HtpV8Pv7~!uk$>*19B=q!=7$_LP~vshBTZhgZH+(pmcaq__Ee>2si+j&Wgr zkvXhx7y1}SrWkG(fqQ)iiz{~$^EcSfguD;p_&?F`0aY2?G#LmRX3 zf0V^6o;mP%41PSQ_QmEjoTV$5uc4h~Vmm|2iPG!$biGXDdil7LOrM0>1<1d&`R3#6 z3#AKOcV)=eP58y$$#qB5Z=KssOouE2_n-l8&Qn}mno6kc#Qg^QL+>AA*Zb@?F)sr5XHsg1>mkQz|HE;%DVnzNznX<0O4bsGUQ^hju*z ztLTHgJ-B=g?bnSQ5$qTIV*J~;|CJu6kt4Uw{Mb*#om+L+`e_tTPd;Dz9BAhgxVCOA zZu--FT-gX1T`vhbz<$7`&o|$en3N`1|uReG;_)RP}{*u6iA&wUE%tTr9;*2d7uX zh41TqQgbtUm)HuzHS}W%U)KgN4jTF^^Y+<-_xVqIKD=&UrRZ&DzdP-7vH0M?xaARF z`GHf1Xcd(A#QehNRP}{%{>*a?E=tT5NAx@C+l+AdWf>6#e}nwD!S?oT^k?x~X1D=t z572L~PEY_orUJOK!5KN|1>g(&PEX{beW#%Y2Ss?wjIZk*b$#c4bnbz{b(cqgFnr03 zufL(n7xMM`@65Yf@)(|O`lK0d;7=77^xf0e@knUkFhyZsFvZ1up~GI7R<*5^%AOnP z8Nf9vPGXW~P@=zc+(x2d+iGH)BC7$;l&%dw`moEg1?I>W4@4ASDnx1)$ZY9d<%#?)s>fzb~E(F z6UBbF{tUI{Cawc%{^@x}U!?<=uMw2;~lUxg!Wv6!_=M z%r>*LyV+!>^E~Zlc4ywadFPvNzM0utZ_xklLtrQ0I)RrwC#MF&o%!sG(@bcYo;K4VsZ=CR&FGOdf(7tA z%f~m6i*=}k0C&F8QRmh3U3~T+k#Q65v&m^V3%yHx$*kQHNV|bwKm6>pODt+;A3nbB zGT6>wU9L^u_o&@)OL%VK^X&Vud9!x&QT;8q^Cew>%h}8~50HtzcOW9SKXqr3>1(6< z#il;nb$&9bFQ2~Y-F_<^35at7<@#{*B*b+ z=)I$zGqc}BO5eXH>GgH=(ZYam5FxFtlebNZV<26>^sTFVx;xwYqt=w zGnf~y9p7{di))oP(>J>U_A9XdP-BSqT^2_kz{l4`^sS8mr>#D}k;S#jo9UZG>3ib7 z8oK-Y@;Uk12I9|o7a}&`ky&@J{G7>rc4pg#`vo}k=U(g}v$$4yvv!lnbEd)XT&|M! z6N?kF=4%-5*onR{f4gUA-BB!V#>;&6;G^uJ!L)bKE_Hm#Ooxyi`!kpjmOVSHSA3}E z{>)GLowxql2JTXmvIkk}V5qNyvfl^RJgNKMZPqK6xEda6#+Mg~tLHEBy{Mj#^=PJV zF3|z(cXykmM_9aqW0rA=p$^Js%op0NfAgU)vADT|`E*c-z7VgU?r~igm$2`{=FM~{ zpmg}ItzL)hd`lhJw+iRe(HGp+`Ni19uzD0xDfw# z_^ij|_}H5FH|d^8TwQEOY2AHSR_|k`gF@my;OqVA$aNOS@8;7Xm-3SrizOdoajo)Z zc9ux|I*jwZUn~t_geE0guM=p>s~JC;x4`;CpRu>kQd`0$;rr;+a%M*}zDeZw)Zo6L zN{zIqhB1!jIWK@8LWfP*|L3k9FXCnX1EUOcjaz; zh&H#FWXs~SGnw#(c02mxx&sWXWft)@^be`TenHh?F~jePyhOTI4+4+Cnwri&l4eSA7NsrYQvqTBaq*;wby zbnsE*#lfV~D_JD@J3hX)n^<3n&wf0x0NHP`Fa^WT$-XJdoAH&$N5UnGsThH0RnlD=i@|jO!z7VgUy2|w& z0YiI8C(l~}U%BSP4-MM@-rp>l>EK5Zj_QB=Tpd=x*0;aGr-Sc!MBjvWMtWIXf08w> zkv({bJwU%WU4;F@HwWtgesc6P-=KLRRxG$A=6+$=Zhney{ZmEPkEIh>UzoogZSjI` zeJ9_+r>{E;>j3%|FG9X9!WR}EMtAOqqIYddvUtw4nf-dsV!m)+=KH()J&q2t7CCy( z4A)f&ua`o+^GDvqZ&Z8mEsfnCjNaLEC$10v?6nWP+g03Ph8S*A6RZRHovka2&hG?H zM)dvS+^|oLK2x-FX8KAf5&^#h^S8y%{g4t3!|0kBZs-ZzFJPP>^5okyRec@ri0SJ* ziE&|{q0bfl@5iQnY8{st`7`Aj)&cAxVF=&&W`tWneb4>J_gns9q+zskX8NWPJA>=! zvA0FGe&(g_Gw(BRac!1c@HgxI3nLx8ry}}pEW-Ffq4>URz&F6T?{6QB`NH~di%lbS z>pQ7!E&aM-Y~Z^W<3fCP?uNeIvN`wt17Ak;o$_pn^uqpjU97)(2Vh(nkMsBG??-eG zv+Qq%I%E?az)!Xvrq>~_ou$60rat*7z84JmW?1ic>p{^O7x^7?m|s*}^UV8fp+v8x z4u)|_km?sJ2XpxyLw)^}z8wtoO>A$euOV&@WxwYQ>^H=@@9(GDt?7QfofX{2$5)|r zc*j5oJLmp!r}^?K`fZ-P!n(*?8fg{Mldwf9Cqa(tZu? zAwb!~-8c39*xuQ)-3&jVI~DsK&|%+v>2JeAQBEQq4Eg3!?dBe<=bM+p$2UmXZ_-)4 z{W>17#x)u@-T4u}-jr|LG}IwT>F~CJ4h5Y1{+X2h9{S-BTJ?%Anc1(C*e~2ye0X}l z&MazPH$Hv6L|>Sl%$Egrozcse-~8{JIg0_2K{(t?O$~MOqs^Xm(t;InQmydtW7rSeQ86!1%xlm zhiY%y{(=@2`R6bB_$HLY;{n)%+p}#tiyN$E`CK2iN;oeQT$pDy`f}VDwvfLzA8s;* z+sptr>lwavS|_E$!soYt#q!Ndv&1!QH~9XpI*&bH>#060ZUN`MX*#9D%#Ld}vA78_ z{4NYz2l5^Yca8yW(u;gL*oY3WFFm|mw|Ch0&UuLsR~m@*1@SMf==C#;>-wC}pZSRn zww+e#_U7b1A;d%f7DToBawOUmMXE_;xMU zT*o(as_+yVR9u*U#*)l%17trI{O_DU&pv^0VW=~l>lwWd;2O1C zCe?24KZ~y2GLVqqC&Txxe0_DC$`|snBr_dcWPcMr%diehnjzcKEG(u8dxy4lK5=;URpX10TP7|2l*l4!<3Oxbj}CFW|nv{R8wp6pZT;#Py?Y z0PP0)E~`@8rRv}l#C49veBt}CZ~VLaAr)5<#7!6ziGNEBn~CB++`{tbV(per;co4` zv=G-Lh?_u^^fSVv2*s5st!IuzS+JAuJd21jf$%X;s(k68sHC~~YsR`qoV^0j{-@eiFUY)MyfJu%|KehMV_`lrLco0rQR z@zwbMo9W;ne8K;YaQ1_^Bn7MJ>$;o*y`-D5E>>`OQP11+`_z79dY zF4Q4l+=PCyy-7a$UI*5}MZVukQ8#>PW)DtcXBAK_dGw!X6vZVyf_wv{-C)0a+?dW2 zRa`|7H=p2w{nkz1dtSv23gWsb|L{igeM?ka$38JT^L>fi4dTAHa-YgZ2TjWUhwu3W z$`FhT{-NONWHejWrmS<8_6s4HE@idDxTVpR4KIw%WDCeUt>ENo{GumAo=&9_wCpdhYm5!SIL!ktjI#p5cj zN6=5ACm)CXFX%huM)&S2u4AfLyJbwr_J9IOsq5epg}5F;+z`P9KiQ~R{n;vCMG!aP zE6f*gQ&OfC>KhcqRYqYQ??ku*E)<|yZ7~_Wl!D|uypER4#y6S#E;xMu;*M9mK2-};<4Yvd+y3p)gHU8EnwcyV_8kd`X0PY^eg%->)guJf52 zx6mQ3WM;n}!WZJR#?N#@?x&cHUZRK9irJZu;KID7-hj7XRdrAV{iK8Ns)cZ8m#u*g z#boqSatZQHej3{Y#K1GR)n23GDr3ZSuyw=rVIFHc)Dyz?xRP1B1=nJ};CC*(yBx`k zOS*m*l+-#boC7|9mM=ltGG4)uMUV+P;H zan0b1*WDD~dIo%@nU=WhM-1l!)c5r|bT0N9TgYdPYpAcSA+~?GxN3iDBNjJgjmuUE z=Tph|>Y%@sap?KFms#py$XBNLjys^|o4ni-*N|^M(HF+!P5qzzkS%22WI4|=phUgP5y}wH<8@u2;;>MU2dTH zkT#|7u+&#uf#ke|FIw1<9!>am8CxiobAFsk_(D8c_FBI>EUpx^+>g~&ffE@77x?ZT zAAZuQrd-lGK7Ad;&S3u5bw>r54ro%y8rRT%Gl)Nfv82mir*v^t<{r*=BRar3;^u4R zdTYp{OxAur+=NzWeEnzFRGZ-(bHeHAIkF_b66IXs0<3hVVkuq_r78U)T(nUVL$__lv zCnCVq+)7tj+=P%NuAzT$QGRFqyf@!takH&)*(%|DGSLC-;f1F+>-t*(C$5v=g5Q~% znmm?$bN63-I%E<*3HzJgH&9HAg=v?SYNP*&I_I@T$huaVmhP}To^YymRQ(O<*Nwt4H7$p__vPT zagT}{6vXuszTkgfl^Xd~TZA6WN9uh6|bg18~lZZJ>`*qemHN{ky6#Ff6r?E`#IKfLK(6;~$bfqS%s zS?Ei6NPUQZ+rPebt%~dVSj--h21Vk@#cTg-tm66v`6gAy>u%7G+oeoJ>yzY@-63}0 zm6DA=FZjuu8)u{cq}|AQbRudp(>Lu~tON9m-x?lRqT)((#PszMT&0aB zQgR9EU_&1rFk%0qT=^wv-hw}wN06`kt%wexgX=E=S32d+;ah)j5WcWpJ#KEJ`6^#U zkZ&rvZxF_}zq69jJOJz96V%s5>Dz4UkA>sBd_l|}l3&95f}gxL{(+BZZQ*s|Tt0o> zl)f8(nf!^WgCeLykleQdan$w9v}~5IRo<+>1<5`R1gHz1d=~i1=%wTsE2eMYTx6f& z;`OGeAIF!>_}a>2e+G8e^2?W=V^Qs2@~smDNV`G&u;DS^Cbivyg6)<@_`-ZhDtYA? z%U7As$Jb5amNvlkz0YUASyaC`GT{w0ZfaAa_47Rq*9j6^V|yr#;5v8t{$(vHx~~8| z;vD>_Su(SS9LgSQX1=Z47fCv5sjnelnec`A{Hb0y>ax7De&ge-{DgIYecsTz$s1W* ztGt;G0ZNB~A5YTh5IoCg5BZdxb!**w0n0Car==C%T@{J6UgreK)mz8%Dqe3LjDDO_M1ldmO_Bv&iVTv z7T31dQU|t5IG;-CTYi?l-SVt)4fSHD~WzV-u_xQ3s`N&ExEXMv3s zkt*7h9Ev{9>&A=aMK)d->fk0iz=qRrr}A%U*`jA29pux&Mfu4s27WTg`TU&>!Wa5+ zo|qN9zmIMYI=^$Z$ovjVC7cftJA?Jq zSxbL;!LU%2lV)}nnvLxY{BOl~{z3arxTO4%*g8RweE%5i_w8wIA5d|9bH#977cgI# zXBB_*`$j6R=TnTEzb*QBVWxxhLqvy1mw3Kbaiu%O#(5isJN0Z?G=C%d3gSvNBKBK3 zW1MatklDbpzZqIf)_0Nh$)WcjM`2|#849`t*X6uuzy!Yn^X})XZ2S~3<4I=iCR6(M z&v^8*s;@Lp%+72bFkg7z%SHLTOk%&#j~`wAz!p}6gaDuY$`s!NMab7l^aZ|4XCMAW z)mIkOw}99g*hH_MgZiqtKEZxrn}O{Y*5zEM$`|r=2=Yy$a1UK*S%|9$@>PmsI|V=4 zqt$|gst(cwG5d9sc7t_-$_<~}pyCDv`Fbea2fX77b?^x4>!omaH}!W^`O3B9^S|u< z>p9P0d#H+ZX!pgi6X>8xq0cSvU)PjZGd_y%dtLnPRlYt!9Tb8KT1tX8VEF2wV#jvnur`QHG=_uhsp&#QbDK^+2Ae|zQL>~SitBTjoz+eR=r}-^(e@%BbgKJ(}rYpN_{1@RJi$s->!YJ(tA#u|)g>+-Kfw^@ImiTzS42u4^Xl z7qEYPq#WATQ};Io_01r-wVG>5`3mabdmv)JC;Fe8SBNY49Qr^gV!!i7|Aua_z?Lpw7PB+Y z_Ywd5qjaFRiW?NPGdUacg?YecXUDHpT&Yfc;|1H^eu{7K)zZ(ZxIw{olY$YxkKeNg z&6csgj$>l_rgezudtmLzKiSWd@jRdXdirBturIRm)3 zZOET#Q{W;WU+0vFzHRml?uzu40ofy{uZ!aQ_LIei0VbW?$M|&cQMfyvsISnN@H!by zy>x>#Rmf}{%DIf~0q(PzueyAm<4_zVh~nJ?!f| z6~bUm@^Rui2yRV;mM8n0X+TjXRGH7tTvsq(*f_qnwN{F1XYwofJo`Ru-b`QlUL1eb zLlwGD%xZxSGFvxV-V8U5YPWuO9)af5q_k6yP=Bf6V$=>H@07xzx`dI>^gLi(O=BTOb3N(x8KJ1SXRhaP=`<^ zwlf&Rx=#1hM+Z4(vZ$aLU)Su2{T{se@Na5KMNr?gA0xPxUKzHn5LZx#0GW5gz}8{q zpjNB~@*uu(D3jtlqtv$#seFTiI=IGSJA?W0FU`KlQ*osq#r%$w_%qO9&+F&TsJIS6 zTsze-8V&0CL?P}~F}`lX7uL_JZD{=o!j;iWDJWKZX3jw9{f~{uYF;} zejn{xw$Pus1of5b;`tPOQTq9ZYkO6`9zop9&6qFT@A>k`PO!Y8Nx5#me&I>N;}DE* z)mHTQLgg!y&!Kq}gN&Kq@e#fdK#g2FC%{%MSk1R??|CSq!|}%&9bj?o6)g98*(%|D zHn9irzl*<}J6Y915o|Xv=@+oh^?K;#b1H675Z6cfho7e(ajLk|La~04M|6Pkc*MIY z(2v9VI0WrMq4*wN^y@z=t}Mv6fU@7co$3x&aeab(L*=lJ5J$cGQ&Z&Lu@0URV(TTg z<#@aRdnmK6-8B_AD7Y>cr1br4;zcyOC+#MvZhlaeGw&2zByHrH0uer9Nca&4t;-9|2u;PxA^u0Boz6B&w+9N zLC@kORR>uXw6jIH-Jl=;Iqr+bDsC`N9Z+>mvQd0ro|d&!#dV1C{TS;2{cYlf9#=GP z8biix97^gH(c$d)ZPrsNu0s%4Ci;T?e%`BPs*39p)HnYW z)&bVJRv!rJ))CW=#Ad(jexXd-4fr-IwoNxbr0lt|>8q)PGWOjV7yQn)b4xa|*Igg; z@pVxBxW+K0@ID()jCOYJ?N$=}`7-dIf{yTahWyF1M-(6MZY#+_jxKVP-)kkopM(6d zpU12pyD5KmvBb#nYQK>EV)2f*JgyJ^_XGb#=pLG++{YJB`UqbbH@ED1^DdRIFGhXM zbjT=!?ExL6QXNa}(2zx$q}qJ;kT4$iH<({^8uDV{I#*B;)7MGt4D1*ETr-+2<4@*^ zvE3}~>?*M{a&(a+ubm|>#yY^5yroUWy8-UC z%eDKcxKcf__`yy2hvJp5ex%|C1$D@2g2w~s7wh}fNAE%uBhN=hr=un_eG^e232jyy z{k2=;oWz3oIQxZ%=m7Tn$FK7~Q~5d;i}ee8U(6Q;)Y8uLmo~9{t@36%geW`v_oq9N zD!8OakgvQXG9G_a{j)+`pCE3=!x$Ih)Dvq{rm&wo+08d@I!|NVu>ZZ#p%sgp_z_?H zkVSL=zNf!SF01M*EfKQ^H(5u7^|SPem;P39WkFm&;R}BKWS2YykL|%Bh?`4rLEi(- z2Nv%8y99A1v~vUf82VfHn}cVfLtM$UUkt*ypzp;a`tJcc|Hrp}mPPz8=y2&+&yuRX zK0zJ4{V`vNOG-|;H<=Z|dzz20Li`!%Aieaj+8i1r(T{FEZu163zM77%& z*UzE*cd)*SAZ{Mv3p(6i`IV9H=o}r=!ES7`r8XnzNqLJKWd3k43AHR0nAKX3vLbdp_s zIyebmn7>utdg2w8uS<}xhdg%?;)i*^2U^lx;dS6TA72}}zZ%xLX7@{MuJZK={?4HH ze(cXmA>5U#?mhz?>11omw+@p<^acBEU2gD-LcW6fdMSOoU+bvTH~D?Obv6 zywH?aGr@nboxwnHsoA|d)${7np2&wQ&BeITFO+5*+NnCoE5!U+Ch@=E&zhc@c|+x? z91&&JeXFXgdUVy|k#CdOU4VZvnNKkzMJLi>(3WIWK-(|SCZb)%>zPfIpiPvi#n=w#}ioP>Ymk(ENg!>ir#vL&wJyf7J!XfW4= z{eax6EyuICnX~xXP2Pibfc3r&RrbI-t&Cnuz7t~pAxOnL^V8R&{X%UD*0a<>TY==# znqmJ7e!W%65@>c$)-?p}%trZ#xeqNn%D#DaeLlW+VrS5giywFc&EK>s>n=WAC*^m1 zH_x|Fb&ytywVO955|<>@uJWCVD+}TlQ2uOkpNUPhDoB#U&ZmQm^f!plW+*){9s5-a=bqEoC!5-RqUqg@rh^_gLRNz6|-LtWe@i^d0>@B1jsDpo67nTQ-B`ThNxTUlgp4^y3en9bZ!AD+}`V5q)7DX8-Vgx|Ld`9UouC zhWSE&JMnqwCzY>5kgvQGw-3a>Z#8u{WA(Ky;j;(Z&k=pUa}Qpi@^uOFRfxXOkC)uG zYZ1#=YR{*ygYX4?|9$8Hig$?L5#*b+4eJ2@EOGI<*fJLPFx>lzdawF z{IF^dK|yt>(oe8fzdWVWD3*rVp zj*M@c?w?pss{(r7YhAwm7Dr?Jc_H3ee);=s7B{n_rM`yqi|p2zFB&MM1cT@7C6=(n zWvPVoE}|p&-}!ee{9M)7BdD)}JQ&0eFb=g`ncX@3X4JoeqkQ@n5PN`ixl#Xqy+q~f zi=D5bzJ8)F><4uGt~iR;w8>tQPhT7PUJ__A;LW5tT2y3b*0_dza|mCUZ_d2OKZM0~ zm*V4_K|P=LRRg}B#g_9}L%s^dca8yHe`!9xUW)JHx4P=|b(XQjHRPL1@eSR(O{cFT z!4j8kl5k!jd@G~e;LT@xu!VxwxQ2WKgfHBud*9SI(0w-A6e!EbH;>{w)PQelIZIqa zzIha1hXG$(c|P1A!395Ab>w-S4pId^+>xHlcUXrX0@wSQmwR z!vHtXhi^WVL2$vZ&+oZkw||`dKR#S9g?n?D9ygbB-zl5ItvgqbE6?QP>!+TVdC%@g z8mRuvb5(2}kbHl{9^_(rdyuTx?X?C(avp*U?RNF9-*xSlzKTx=H`U+j81%Pf>v@17 z-ym9{R^#f{C4Wg_3%OVG@%0eC5U<~7fSdd?A8v@UvjJb%f^9=hN}tDvoA4X92WU6@ z|Ma-h8a`Z^;DRBn-*i>)e>rhoWSj>l`up)e`f5aoA%jEvFtA@rcYX#i>6C6AKhVVs zUk8algLb>rt z?N$ci6t8?cT8D{mz0b^kU27u!*n2L!o2suz@b@fzb1`3tCljW9cvHm<#=cIVDyBL5 zDcp}g>sN>?troKfFQtQHa{%pcV#Q=Z+z^HP*TQZ-6<4y0eP1tOZKU09|Fv1+`lL^g zuR`hjRjbACsC*Sc+(guYVcdlEl48rJOwu$e%7nap>rrwE-0o!&MryHBX!ykK<`aD0 zU^=Dm`kB2>sJOCVySdN~0O$bz>{!;Hs8?gYiXh)C!WZ@#Hgg5>POn` z$&0H}R9x2!Vz~Z_c>IF#VsFPLXnIKcTa0|I_Afjy{t({3@R6fJj=cL9ZqjaGXInm) z{Ef;tDA;bfq}^bg-_|eCN5yr-r~_6FRc4awZ|oncq4QJk{{WU_WTr^etQl^A_y?GG zKYeIiVZZPQ@|CIk%=32lDa7>&;yRQ_9QDmJhi0q#DuTE{QXkgsy>n02RdJ;?V*Nro zi}}KS)<1Xt^gY{1X`J`*Cw~+fFCN?7|2LJdEO^JgAXA9Y~q zVAqRNRa~DSZh%@>{&v^X`hA9>eD~7^39ma5-+CXoN2`1#Ma=KWq(0g>mg>~&gN9|S zm_ra(`33U=zW-Zu`YRRJ^}HD0;CfuYCc=GjU!^Bh+@RodB|_BrmMj(fTE+Ek5aXNv zOT_<cfv@@E^=vY} zL0t0il$n<_peU1Oy&ua~3FlpeZ#k6fz3Pz(hJ~V>H1iK>2{=xLb*_5vJ=%+f@RsE3 z$H`P&{pG+d=UH5cie6e@J+b=OEf<&9)|LgafBDwLHNS@L!0sMWn1B}*Uk9a zDEocB#TH>uMuh8NHM|lg0c)0684M1UsAj&#$`m$&5{W{lY57^V<2rK1aMLN=C9S?d%McjXBZ%vy`rC=-W16bCiXd(Q zWxtO!-l?#T#$%SyMh0$y=fYX-nGf`EZ;a3Xcme4hQ2w%q4IT*`**ePqR*M> zAR`NaegS;@)ST9Yt*Pwg^E*zWFZi7@y*JoZzKWo}nM7Z(vs=U0qj)mDWTr!KL1aEO zYHC)(iRVLzZ(Uil*` zUs;fEkkU8Q@X5glUS=pq&6?S7h#H61F8*Het#bP&ass^Lp!eErn;R^^qnGgdh4bu-+=>ezl^zFED) zl|Ksk{w}72Z4<_Yw)^&Lm?jsK(Mw4dvg=Pc@{byHJP=W?MJLH@Ljj)hYVE*-)mwzq>*-map=bm4?cnp zGWv@-nekOfzbJ>0E@amjs`7RGDaO}L@wHW6GF`_le#&BWkhRFsb7p*f zWITp-x%^A7A@I|yGGhuWpQEUR|r5wzce?pO!-JiCkVcQT!XFSOgp+e*KO z4sj(jeLZ=YFU;qE-*6P&x1vpHNqqXcD1Ae|5-%ZCS&JM!XU5k{=Etzl;QyrbaTX>0 zZ9e;TEXO*)xH<37i?a&tLGZpdKhdEg!oBa)=lm+JLonV^2rl%uK%+CqR9ufBuCpZe zv!KJd_fpU@1a1k3;Qh32JH`b&>wiz*QRtvaiOpiOGxqmpvhK$12Ju6|k#@THA#I=K z_aQYr)J%}*3p!LU*Zl`oUx#4aCx3Z7`{D9bB3wHop0Z{X+auGkwR0>gR~{ zsP;EjUu6Q;7yRUJpDo(S;-xK(t=-sq3dMKjU&%gIUq#T)`I3IEe z;<_llU$%O9u-a}uL0mV%y$$hgJjOSt5LXei2QR^eII5aYLaQgZCFCJuxJh?mJA-xb zp9WVrqvE;*aXrNE0NMM@$Dtg~oo#YpoR{N4Hp8{KFkiquI>Oa59!w}}h8sjZ0rUkOmK325t~{&*td}I*v1*ZO zXFhTsosOE!__~Nc13P=YWzpGLuoU(WaKC4>Jt=#lk~6qy#y1ZII-oDi15&>=&Z?sZkmk@t%Aw;<60-WRar zO=f)aDO~6q@g_6e5W$7{{DX^&->>T664W8I9NPooI9#C<8|B31A%a7n5*z;OI z#g#9L;bxNl2Ju7RMHLI<2cMu0ZZxn#zkq(+^7oLTjn zv#5T~=QJdvH-vrx{Vnv1{VM1jPcq}1K|Swv$G5{_KCexk_|_*wWV}FunY86X<$LUH()animpcI_oqU{pg9I1G`Mv9(`-;Yd*NL6^bVw!b2K~6x?$8iekBKLl zwVR7P7ZCKlzV>-ohR~!SFW(LkJDZ%cwj``W#FNbUdWoIE{X0V*8-6c~>F0bNNFMP! z;Lm)X{9CYp8c#Cg>%5M20DWgXoT1Yel7*y71|s5PLx3lr+l#H}?TPTz3v`H?Z66;jcDO{f=B(Y=6^^ zJR|sDSl6iDTw+AT!sFwa1Tz=M1`xTt>IY)<2=wc{a+%9`;_7=hy`v=Jbc zesJ6KEUeOvkFSri-%kbyboQI*;lnMs8@C&Lp1+H5e^Vwpfc@?`|8oJWLy(iN{SC|) z=0Z(p9DNXlKXE0s-E{jRXkwwp)ouI#tDA2obN((@GNnVnKnKq#zIKzEM%pdjSP}$N zbzsGFQha|m;F~&{kFOKGA?OR^(2Xzk&rM=^uz54S0m}dGHsEU;!^hXY8uNv@@#4(g z5LU*O%=mhUzA&zpzN@*;?Iexm<13++E!BQ|-hM-8zgFZ;`4T?~@!8Q9|IW92bc%ln(>Uw>T|Q#&2&g4&zA$g-uvGpm)Uy0d#vvVm)S}v?;?D`Kh)WSTJKGR zLQzhsd|AI9p!|BWfnU!b%C~<}K-vv-X!YPNUEF8OuP;m7g#! z#J>;SdHVe*QW{=T^<^(+5&r;V(Em=}yj4eXutlQg&2VkRpMl@G*=6$Ijv~UfFUS1? z<}Kx~?4G8^zmAv1*87sF=gTesMIWDe?zQe0MnWZ0I?P}4ROc#1q(eI43wHMViSKpa z^O0Ng@y(>{_YVVHg%j6J`~wWcZ*6aQ@y;UB!AJ4^(}1u26TbeILvUdpV3U((v2B~p zi5noeFm66wZJ2J{%xuHgZb>^L^OiI7GGAx;rhdw&Lk4L#@DCl|MRUUZVSLNZy?+J!-We0E^=0co-bHZ1 zPxfl$)GaHAIB_#5+@}n1bK6?>W5ex0|I64OP}n0)H+UXt;tQ5K7~(1f7v@8AnhiRH z4w{tkA|Gym;(K_(_%<3)lu3Pw4>w5Ro-n|5x%hBH6z;hd{o1p9Gy3r1O6j=WV85l2 zTvIpS%<0RAYol_m9)k`EX@|3-M&B zy=@n;?dE!g4>yUzEpLFEIM@=Gr4r8DNxMOu>T4*2ThpY}JNW#Ao$!Tu);AC7*SXw7 z`1m>r-%1F##O^^|HDpmH)P--JCBKI440M=nphNO^mV6UfE|5>AbokythdgUsBUs5s z;wV_(`J?u~zp#ZeyIbmD$k$Eu1^?Tp+DZqDn>dqC2M@u8@uJLBcZkKce{YG)Rte{W z`Zw#GHo!9nZ+_*OLFn>ve+ZyISg@M+rzyrr8TXIbMK^QHYmgBvNV z4#~6m___&S*v}i`TRDlvO?!^dKco`A&|uwPb3Dl6W<76-%T@{JGbz4f4EW~$V5x(l zzD|m7PXoT`*?hQZlz-S+7QCf4$$j{AklomyfuH;$ducZ2 zKA#R=q65Td`RyA#PJP6fUYhCPUWn}haNp0rZ;U!03JTsQ<{`K+UhJy(-msWRQiaU; zdMVto>&||z@|DmXSl~OYk{PbF57&nck+FAw5L9txL0lhcHyAHIKls2F71wh^jIWQZ zBUVJXfl>aC(LqLkF()$}0(W71fPS2u>pvGWASq~u>!;f7?#XqYP<8ML>Z=f3h|iiY z>zu3Nx&(1^cSY6-p1oXWfQsu8#8oJJc;?zF1W4mR39Ry|4P0 z8#`6LQX{eT5}EKVfrx&*_9ogdEGDCuQc&-2SI~Y#q`!ebyZYJek=CDF zTf$5S=>Yz`iKuw3(n(`fzA`zlMbYQXaBU4D_E2*46T01k9; z*4B)kGsAT~jQtMWhqv?4>a(g24nZB{bc_r0!uuu-M*A(rWb{&U3F6wy;C2K1{V{iM z5a9x>C1MyHQd9b|Ie>V3@Y z!9nVSzU_~t%u;b(g19+Ha6g8AQPF?(0>YKiOUWY`KRAhri?;+Co_~ef_Pl{ldJk#|tOW zw6mCuUP_9fz8=CC=CO6231tChJjsl2#v(jlml2rz^KWLTe1n2~)2Q*{@m8*!c(_7Y zGrk_;*I~Tay?qx7BXCLO7S`SBeavt(iT##B0QS2ool$j=4vFDzbsMtdfpe)!Fd}!{KA(zcV+OL|d`Kbo z0Q!FRP+*9P>p{QMV2eQ!GaUl|MB=k4hkD*01C*wS8Llz`>sS|+J~VY33>&hhqD96G z*YN?yt%d5RjjhpFh4FZX3VpvY^=+&J*qQCpAeaYeQo3Tf-=Zn6W-`#k4cZ3+)DN%d z_czsYW=As}vMWXA^UoOU``f*I>yxR0$T4eGuddAInInf=P1h@IVMz}LB)k8d)C+sObomlM}Xa8Z~h zebAvTTG!Af#|l2aeu7&K!F4?JuI@gNv>ZO%Y|`JL?fU2J-L7Se=FN5Z>?}y}eZYWk z;-{ATEi9FAzJO{sTZ1GB|1>F`6F1$4{UofPU9E9sfd&+15+?BRwT+6{ZldjMZYcv?g%ej!!u|mQos?~>QnYNXb7tebi{e|xfN%0zJ{<~D zBKA<;0N2ln>mvRP=2;b|Ki7`^$KXG#Q8hs&JMWUU_PH1 zoc^9Rzmio0rjgi8guH@wJs`I#XCS6XHY20DYJHSklzV_`ycL`_H$Df zB7LhhU$ze96$;m3fScv#>lYGvjy<$nyHCFv%D#8OHa@;G!G->|dB?>!SzPyaK3v}- zJb#0A`$_iCHlTGF8NHMgavoksOJ?m>&?4f06E5z%UN0Jm!8J2nH}MY;_f2k{AT>0o z8|{=CZvJNMe<7w^aJuOT79+>OXAc?n$hyXWg)6>eaUD(geiz2E0_zKLYNsnppHvtn$4@wK}LTuCo{f2e?*5Nm*=7Tu8PS3 z>JeP8&ZEB9+}_}Ow|36&Z~6&e&^PnVJ9+@uc#@e8PGY~%FBU)DqkEy96&LFlZt8n= z_Ub!y`%Vtdd7(mdfQ^7U_t&ha@(l{Mo0r_L0qeiXCkCVSNut={nERXI{Md~mNbr%c zewK1?9|$8fDdgvy#|9{S$VqQLK;DYA zz4n&+ez6|S>{nWZalwA&Pqto%L#&uk&I~u3j6*e0nN2rr0Ix|QCmyFXC#j4XuKyLx z7y5Cz>|?t1U;A0UannY0fN^MhFr-`OqNo|ZG~=s~egQhXvGIi$RmD7l_8=3!(2vjj z@o!s0Qc+Ht@W>|A)pdbdb?s%*hm&vIm#Fmd+j$d-Bqzz{hpcsRxe!vixXyilhFDp*ct5WjX?Kn$VH@Yko2os2=|A!Yc{DZ5fs!R zkGdc6#D-_CskqW8F@2>Vu73yO`}E@HA?}mWU(Cr&-+a<;u%6MpSpA9UAjb@f3Yy^- zJc;8;SXX|mbcKlj9VNDZ?4b@Dg&A5W5wN!ud)K$8Tj>{jn_<3aUFuVF2War zmaX@kM0OTmGUF@l#`;!9a0~w^Gh5~B66EVdD;dz=N}<31UVjDMw-R46<10Uc`NDm= z{oXpLTPLu37c<;sf(tqvcW*tQ>fjU9A&uxz8sRS3`h8C;e(ZHKzS(J!d6w(%NoW+s zC4+)|Gl)GvKQ2?T!G|iYd_>IecnL17pVe(KsL1xEC2F0vdI9ufCUHKe!9hMRtVeym zzkimhgG*3{Y^uLqZr$?(1TQm;qh`(Q!A0y0#lHk2E%&kBdVZiefwi*!DB3L{z5*!0gCS$ z1HKst`S^M$zW*8U&DqDt*Yy>)Ul=!Ec<{!O!hTH7v%0W(T|<)se#*`kE#3MMThG4V zlCNRAWm0yw_Unc)d}>m_8dpyjuLS<|4`{hxqoTm5!15 zMdMmCzGQI|4_opzv@?a+FI=3p{PYtnZjLoBTP2*g6CEHhYi_{T9^~U2p!m)+;2W^U zHRPK|^o6nLO@n@s6trwNLw&O;J6mL6XBpPGhI|WlVtW8PyJ%o%xz@ObeEozk>@)nF z{Lw7-&HYC$+l{Rf&WDJ;!1sy)U&j$XeRC+j>katkaN;Ty?jskz(fPBS<9s?Kbc*!j zgtg9ttXR2!S&o}*m2lpFCm!FRQSWX4ibEaWTqE##!%EaiG`<8-Ay4A7UkCZ! z-)abV|KWA8AD~ITVwSju_8^mXE055cWE?>2M%t86!V*_of#f{palZl`rVZ@qVGAYM zEO8C_+9|&6R}4h!>)KSn%a_<0tXEg8a!w11a+$sO=5JnN53sIW{;wlzS>Vi4mO8Li z!ud2}55V_!1HQqh`S?1BzQDJ#0bfTMOTLEfmP^Kq5(xLYjQ%l6E^CR))WF#+(r(b_ zZf~#bWDB__TaKG-m2h5p6!&8o=W{N+=3@(`RpI07ONgxRWb_O!W^t3B;PYo04KZKP zcg3=z`~F)#**68;cCA>p)_Jpep@;A-g&=kmeAI3E;T z|MjCt1Z)h}cV@rdX{3rP9gR7DF#ddHu|0(6Lt~Z&*h2QF`0OD-_*O)K^QZRwNaZUF z@=YXsL5qPc^!Dp^@$r=oVSRz`^0Sp|s(f97eC-tOC#StPRa}oCu2LJfJJ{Lp8}52a z#q|l|ItgDGkE`GHD2OZ1!F*wT=g8nckz2z(NWMet{xi>jNPp|_&~4~0SZ&H{ z#pfqolnx78M|6;miS;)H1$Sul+INvh^}3|M0tSHQH6zro`5< z*#pbhPw6n^t+hHGl5+TT2vE3BJlO{Al4z5Y6E{fw1L*t1yeFnr0;TQ7)0Y3Og@*XzDtBbU9NRXVoug0%-brNd`y z_vv&)|ueDPdJ?cBa#T;+uFqD@0?$Yda@y zfWq~@xgL%4+LXqL8zi_e&X4QyRE`!E{U*k&*!l%qPd*><59|LKQkT8%yT-Q;BL^`q z_=giUugz5B2Uncq8_Oq^dY;0bifdq4)}-9mV;e6tl~5)~zRv)@r|RK_+tu+{iG#1q zf}*@!2ge_v!<6k$2c&lm3Pm}k`Ukd%>uanp%)5Ubb@MKjuY6oA-f;&bxD`WV3RGN& zC@#7G0sMNeH(x`1<4a~b_<|9>*ON9rqS~29kgq~;Vg9ykd-=log-;OIPx>45;~n?Z z?u`zbl=hExf0H#ea3+(CL(m}>9D8cN^r}IjD5uQymC9jzg7M;7$-1MXKp0*!!wsSl z0{R-*@1hHr(W*gw$qd&!8{@(}>r#zdh3)3JAl5Hj*?5bnVvGU^xFl+XFSMGu90 z$N)Fvk`v=xJ`#|@~gPg2{C;YN{66<4$=-j z9fB0@aRXc*C$8-X)))MGhgVkgRCRC&>L3llI>LS1r>lLXi%Sv%d^*S!->#Kk_#458 zQ*g^`LeJ;&lIIBAj?gyNdUGRzEj*-i@>Q-!_G6!EFuaMXuSZbdY{Iu1V%VqpOOF>4 zB`<=Ud=rmizJS};05@$XU%UC6VmpKR#Y5d&oMHJ|<<0!0o#NZyfUhl=FOG5$I|IL7 zqmpwlYBw3ZloY{sOCJ`|H{F1*{5zk%cH+-~Z}#RV{!sY_1^K2DePO?4?Vm?={ld-3 z*F|uvAlw$8b@&$@G|Bb{pAOP8Y-gZD-#))IQgx6|iuv^{s@?utlY2}<7G*Ma$2Nas z>v@Qs!8lYuqv~muuS1ZpyD|Q}fIF{VIq1&Xw2Mz)AK?q}Z2-Z0>zvCtL3**Iq4ZD2CB852h4WgApHJ^JfmC1K8Q<+OM8d`8ovoDx@C+?z`Xh{*mSy%WJcK;URt!^c{cj@h@4dygWX8 za8WuODpALy>fjO7!F3(m1L&~tqoL2TeEl`~;vF}IyWarUS&I)htvil)z)#+L^xMs< z4od9zpRpe?ocED-104<;@Xh7q>n40*UwTK4chD@nn2cVcAJY=+Z+?pJ5d*%CJNWcX zIEM8FA91zP_4F`T>R*r(*G=pf2B4-VM?9|T;1JZou^a1%7Br-BO`jW0Q4POLxRXx@ z55a}`W{dvw11zqG6W2-NYVZ$rN3ST1Cq05XC=}nn`sw)=aPm#;f$ah8_ua%x6V!I| z3Gxk6d@mXB&8p4UZh<_^7v=#eM=vZ?`6_YpW%orCvfc;n_Ue5%b@t%sVtJn!s;N(o zJ=lK1&I$~4$gIPsgF^fR#1BuVyqv_ob4Fc0+#u=4fZKENhP|r3j?-fPOs4!!*OAlE zJV2XrIr(}Xjrg+}P18|$QcMP9mmuF{if zfUmtCAK!Ee_cjCEY))J|(E-L|Deu$;qyxN?6hR$4gfIBB_pZ&-&12>Id^))HVmqsW zaNk`Fy z?9{eUhcjY26W{!}fLaGXwYVbpIylQW zi_-VSlpXhJ$fAsGb!>cDT<39YXQ1yJZ+z9A#r1RIdI&D)TWRgnLs;BQPFyJ~!uR#- zM}f9B{miF>pYVl!vb$2#kl)cJCns(mX}8h{uG7Y)DOyytuFQ!morvgA`go7oEUu3e zS0=dNf1lYkdmD=@WyjXvJPVtI{g+zbMZPx!@w&fkrM~KU^;pm;ws@VjUpL_kcJ}n) z`MQ0E#5H{OU~i1|1^+w!{OZ;!Pxa{F#PyK*Cd|7(eK~c9il-jEG2;3gYV}np9a>$M z$E$eiF(*b`R^K4O1-?y2)SIf}smCBEuI(h&7y8>C`7w`*rydj5^0k|T;DY`BG`$0w z4{4K~6W2xI_HMlSiWU|9mJ}zhm)HZ$-!{!2g+?W9^2CU%t%a7ep2Yf=L>JmBCD_ZB zd38ONwFf`Z0r;-Ut~Q?q^3I9PKd`t#${t1@J)yhbz92>&SX|pFtONLmDZxcL`;`?w zJM-_0tiuc&q5pnBkXHu^w^4_Wo@4b*o6D!KgXjPQX7IylO<3I27BBVX1Y`~(;LS<ppR(x?Z9P-q#i&aUaAFng0%Ntj=SDg18>S7wl}<*~D`yu5?jse(dRp>jUoW-Ob<- zS5o~iTPZ-|DCozogT-gF*RAqqxCLaqD2)K7y&Gtx>JTgu`+az_!JGTY_eH=S9CgpU zDZOM+D9S0|D;r#w7hwN;JG!=_|6>y+mqDQ@r_6A@|Tv=Kjb!?QO4CxvBCEejIzh zkPY59K=_tH*G_-*Pf}6w4I+;KIuu8Lbvb`0Q$}^!{RQ&{*^p2Lxu~Q@y#dw0{qT_#tpWp{X+UA_I_c+#C96% z3j;;_bz2vyxSlxtgAr~PT3Cm6gBgH-?af<8Wul!k)7Mrl;vcTJ>%LOz91TT(%}n2f zqzK=|Mab7reQ&YrGt*v>D(N{zJ7dPzM)-pNeUo#&Pd0et5aoAvPtL7hRD5&E^Q*yr zUrdVFuP+WeGvb>^`SpM9f2?WP;0!*O*(o!9WvXBN6z&&VgyeO6ajKo*qJdZ%aeR14 zi)x)S>lZTl-YxXwp~L&^mcFsZqDz?RV5j_g)%=t=M|tc`WcrQBYX{*A^NXR4mHN^s zgF;bGnelZIeF66)sUs{y#FfnSwS9s81B@3nx}f{d9C5*ts7qhRL-<0R`b2Jr(fSh6 z&zSL*316_Y)u}Zfllnx*VXvC$>!bQbgFM?mY(1;I8Q%ozcjc}J`j3?2RKg5b%EjYj zO+>7z{f;bYj1@!ebu%3tq+gUp#eaIZZ$E7<>zo;`i^Bb8p1jTe zu{2&=&njoeS2~0H1=#QDS`Rg`!eOtQ;vR_1vzj!Cj2DXFc;O;CBqAc2fp&AHOqNmf zycu5`(E5$oX(&o+hrW5;xb(rsdt=>nSZ_07ZV`c4Ig>xao7yR$Ta~Iu|CK?oqa>|Ua zhvK_-)guT2m-I9jTb~S3^TP38o<1jeqmVPW1T18O^XX)L67Fkz`AX%U(job?Pm10*%a=Tr@k$&;yOZN>l%Iv_w`Dpd@8O>5I68v#Glm~(Fwvo zO-dik_q`5<;(H-C(l0!5@Rc=8aK?Q&5}#G+bN7$Z6oW!hPMO(R=3SBJy}nxY$Y+vn zhcgN&x@2Z&K}v^ju5>}eJuc}Hw6lB)H*sP1OchrV)Hg`Q)#V5N@gLkL6i+hKH~1p9 zf3%S${WLh?w1nmb@gy@`iR}A>pUl6lcU9@Dcu=uwvOyJv*co()3YFUommV-E6y=l| z-!v-jyK#J53OsK)o@9obPu7hfo-Al^C`IZL530EiA)*85JNwsxUxXjv5eKvxUwaVu zW5BIbcH3Ry2O<{%u7{d;r;Ya1l%9_R6csh&n@h$a*q5&U$HO=)vwFP9Wc zm!6G|!(KJR%|sV~FU;SroI>mNajy88;krmahIwq~y~}S&uu&98GQ&-$a3_`e>6X-2 z3+ioVegA{3trE^9bi_Kq`udKNCof2^7!-=6`j5jg+A+q_nZV&r#M^3Fm^r2=2RMuC8H!RLz;dr>}?T5Z3o_!;3uY_C|c| zM8FKL`0^ z-vaExD7kNoJg<1%TfN5`m5FxF%+9jV1?b1%AGW67>yp|;L(yL|<7@u`UdQ*1uuCH87@xuFGx6RQojINpLOZY>Yn3zO>pl|c7s{6H*%Am6M>50BrgUia+|n)*4ES** zGh83K0QL*|b}F-}OLzga2yp#`FZi93(-&Wo(7b?737qYgLvUf-{HhbOU)?uR=y%b- zHq#-S(xJlnJ)cNb^mU`1F~e0TJ8SyS&RbIZXejz?X1FpLH=*5X92}Ej{3|bdJoStj zZZ4(om7z%AMrsXwbaRfIcET6plDyOTx578_P|%)IeB+y+v>W(e=d{kHCAi@+j%22T zgUsI`jBJ^{yqfe{9H6ME8Lsz8#6Qd!_~@_FxAEgPFsS0Ea0f4Z;ezBgC=}(C8Q(l& z51{Y%lju3q1EYW#TmoFfWXJ6dpXJXQN8U6n6Xm2CUxnxZ?bfNw-AARDqktG(GQ&-# z`rGSoS6V6!FsK~ml$j2`?8vxzdUa*AoQO+$&`$$`U$#nSxLLy^>u0b3wGFo6G$}Ei zufGM!JQlcx9-4YadS3%;nK9$*J&XCmu=d{Cs~1_IeDny-XnG*r1hx+3lhM2i>Vf@s zT=V2sI7g?1L3}#olYRl?ThjQB#lvqv0q1f)uh`i)qQkWx#x0~E!!I*PzhTd-dC*r@ zGt|-DIWo?FJSAxwyRH!|$)|&B8pehFp=tlssUdwwy=e?D&G_1mVqBQMK2a%YgES%r zFsg_du7WOrJ;1oRV$bK_OUdLZIy2L5N27-}`S)0V-(S{N3Fpu&)>m~jd{KJA&WX({J zN`V;SYN~kQOMf1=Gr--rOdlcK0^v z_M*X+DZf*7JDObFt;Ka;w~R})71Z2KtS^jjRcfw!SUnxC%9k_QxeLTkx)LKWTu0g{LUZ>sHGie zA3LGLEN`uYt`0ikqsEJz%qEMZ*+!+z&mq3hrF1E;4Q@B^zyHhm6ZL9s%HZVdCw##k zq(2)CmA=>FTIJ02^^@N(1bzQB&^N@%H|WMXKs>qc+s9f+v#c0uubb%`r1YI>ps%+A zr#%q=3w-wvzoRqHzMl3I;9TG}tOML%?Hk!#w~A=5Xvx>m&g{i8F2sG``1C~ztZ|L# zN+D{TzpkVWlx7+hGd*c$XU;(p9cCElkae4-4uGhBem3ZZH!4eO4U3tcG}9qO`Lo#u z{Wzg7A72OI3nCqFw)IJAi77S13ub)t$b269o6;c8%>Y!#3|FDz_4OUw9hR0F(lR}1 zhU=#MWbq0ubmN6QhOb|s+qS}f2jY@aBU)^ga!jciUO?3i?Kh!q#Ggqmz}mDaGlkC{ z?DydNxnSS)^A_6|X;H0nX8O7)JNy3O)6=C@)>w22Gh7ele}i(xRJsnlwvFX$HxI@4 zER4rLvB=T$X6{Q5)No#1{n zDX%-9zHlFf4IzQP54PHWU8<*nwal358#s@3sE!Z{3eb;{F)8OGKE4XoZk-L<&G#8! zySa#+LA?I+*K2P{cQJ%5vPcKRc5_he_NYO-1s~k<9z!1$oenzjfW;qtIN_; zCh_TDJC6Gs=+NdwEI+fKtCSWqwWb7C8;N$4ms4m|C32~c9H6{$kFp= zc9u^0^*O7iPLk?G$6>FU>5xWrfVi)Hse7)m^)g)6I>>A#l$S}nK_~ZaYu!%TsV(Hc z%D0b`ORa;ykvzAn7FCiwd#vrOBwGpP9fWWAd!f_%{K6KowY0=F^k*(g-_8d5=Jc`F z*NCs1+%FeiM?Ci1ZkBJdHD9($IBzHM4&YW9_~65Ap~U@`IvC#4>L&UE?%r39>(&We z)_e{1O(*(7{3}29t!|u8?Z>BYKKVWltVAtpaHpTuA=8>KTP2*&OvU3o_{rZEH)+lm zN;+(+7cFxQ{xQV{tCo8p^AYHi36>5Fyd>=inQAWKE8$@FE|L}f=~$#xw3hid5JoxMjcXUpU^;IlIa(E}Tmya)* z@l7Ip!B6geY?)3fM?-7AMojEyu)bgq|NHyEb+(LSytO^Bbs%3rewP;JoB!*r{~c0$ zH$Ge^#W#C&*%15Q2_N#|I*7i&_ZtJg361#lbyIw&T-$Jz<(tjPH;v-!GvMoqfv?Vp z5V@pHk$zG4=^O{k*D7yjzaC15_sjG=$>OAD^0k|dJWm1I?Rx_qQX5;hn~@IEX6z?n zfnf66<>UNzY~kt(`!OXi(E-NINw+Qkm@SaZx$fzv{MoWaFN|by6;2%-#2(;&f<>;U z(d<6HWM&VUls{`WzD6$=H93i|-BPP#`vrUGHKBZW7S}3o#@G90#7{n-a{O-=$MXgs zUl$qQz#cAhj+-nO$OowYw(O;@nF9LoQeH{hFb#d?3p$nSV5dvFwC+$Wul z*zc>~A~J)}*A*`1ppXdCQt2Y`4tN|Jl3p z_$G??y^R8uGblm@gatXm9T2gK$npiHAWGzrDk?z*$|0tpSWzT$Sr8#8M^V9Wh?O(o zRZ$@vLPd^vVZ9*8RS_hDNCA=GyqTG1GP~PNW>bFuFrQC4oz3nu&pz|cJMYX+l8C}rL_gX*Z>HolE#c(&P% zjlXY&zXr-#L|<4Z*qJ)LD}PRCvY0<}F*+nA(EkQfaJyL$(c`e6AkL&`XC9&h#FM$c z-DtFnPI)n`YiQYno6%wMh{X9Fnb;rHopx@!lurCT*}96^ zZ-}wq4GCOV4l+7y`)|-)NCz1>drf}-q?Z{lMla4?2bgRs5F9T;#2%_5utw|u9K>S6 z|GpU3qqO{kbTks5%}k)aX~a*$bM#F&-37y3R7ziBY!6WvkV5j2NZj|(nc746bFyOC zho_~3%;=CeHgSH^L3AjKi2m=dZK{63^XJQY8B|Uw8q+dXsddJ8A zOyg0LW7wan)i11txZPm=ci{7h>lZnUJuK?eA;j}FD(mTx&-k;o6`xZ1Gq<1)@Vz)N z?}PbJ?ug5pY__JH?>GB$XUBR`+<1v2?l#3YLb{e>;4l%#uWbC0+0@q>O zOuu+(M&LiKdn)Oep1#(j5&xU2p+mtqV;!{W%@`ZOy+Z@n_qws)(ZcmI{bEYzfv_wU zSJKnLMsxuGFz&tmU3t)~*OuKFF^re;y;j4-&17EF+f@C~~=OXofZk;ecsSq6? z-nnCsI^I!wiP=LA(E;W|<&+t5eo6vIpISQjNq++!4m9tFX7}+WJ$p!J`bEy-$*MRi z6vKXSEhb*Z9=z)hp3pj{q+@z~Z8G-1pzp5Vws$HCL+d>~TxT}!$FL55r0fJ6od-y* z%soGLEW&)RLAd?)FB-1Jsib4TSIZtGvcCkzqKxZ%s@CO7!i4wqbg+`=u`s@+H8`(Y zhY`h<2`<>LeQk5a2#0@PkFWAO))#Q^KJk`noq)&T%X+vDf(uV@9(n%Ao&0r1Wj)+v z!}T$^Ro|_u z+Q+X8NZ!!H4KTP>#>{POgu}nDhwEhe+n8T3%KUXkWj*17gzq&7VCUkO(0X-zNe|ab z?5rGu`)N(@=JBEG`-dz$wqKaPxtAtxJ|7}F!2DwTqBE$L_>!IuZo(G=sKI{;^*60< zA!QR>Fx;;-MtS$&V(XI%S&st0^YF%LFUO~Xe!E#~;OD#$_er1bx+_t*GFs8GA~5j3 zdjqo)7N;r%7sMa%XYI*};_D>1FurZ8(r{YBa7nvCKVH0R%%nu&y2!W*e!asd`|BkN z*UPlq()G2QB?>q6N5mfbTJPALDBJ+qcLnFN@^99c7wUz_zxRM^<6yy;A6a3_%oaxDEkR+Mf88+`J5meV^gZ&=U5Buk$pB32YmZ6iwXbd z-H+erkJGZAzNuDx9r*Q*`^Mfz&!>4HPi!0tHpBCt6a=*5$elfD5Ar(A?I$Sci0uL5 zlGP_Z=}dXXn(OHhutq*lmgFk`Myz=BJU!gtHyF1LI`QFdkK^G)a* zH!LYo*@G8-7cRV~m-P7B$T$xj_^l-s&!Bdb(Z7;X*4#X{;9ATFaQ6)S@-d3*G>I#H zhxLW8XSi+N=c;iiv_nka^d8vGV4dLBt-H~D2rK3`$=CiA#s&Y-YMc6VmKnE+tsD8t z^G4`z!7*>3eu4Q0<9rTTG{13_-8hIptAcQ!=#dHCE-Lw!$Hte(brD<`hu-|L!}n33 zs9=3pY#q@}aA7*Dw5NB?I~s@NNBbi*z0*^^Vwd;IH#Cd~=fq{Kvm< zRMz7gXoC4dgWY{|msBGh{(Xv@_EWSygb3gA=zM;MZc5!%IrR zudXPEmvRGsO+h)l_@t+=(kT-6bv~4_t(b2dzvs@^1!WJT!<5RNXDF^R9k*L*ygJM+ zT^+m(-}LfL4pP2B(r$$Y`+`*Mwybpd`We25g4TYNuk<(8H+i|(xEW+{f4pYqeu^s- z+<*bDN{4NwtV3mdzu+HQmVN79%2z=PI*I?4 z*O%OG2p2*yRSMmVaUtHRv2E8Q{0T0D-z`zKTiJ=FI=&T=bpm+ydEJXAF7bSg$~@oS ztCud{>>d$)+az7=#PdtlZ#ohb8?xs@7AT`^EN0SxJ9`xO&*df8XZm`ZpT(H~x}vImqz!zg4uFKPhXI z7_M{@>kE8)REJ+T#fr%$=R=_;7#Gmc&sN9X-}Kte&hUMFR?|h4uVRv~gTb{wHG43{ zb(+L=Gq{%FExx0;67j!$JMv{c9rA9%@jC4PeayQOjTiV#xu&^zC&cibIPCReT(3zT zRZ?w9N@*$f zIbk=$_thV&cBOn}ll{$4#$$Nyv?_t0W0g*0dw}@t;FwAeP`*Jj9;3r0COta~ka++E zZ+riIIG+dc_7aO9WWpD4%hhbY3h|ZEzmnIazPV(-9Qd;vs|8-6I{1g;xESgvDe37T zox#_`^ML6yueqD@4VuK232t44oB!VP@Z4WUub7h_-vVN15bsP&;C>i|;d^*?5n8S# z42GH0x2O${JL)06?;Z3aubCJfLjS}5p#}nM{D~9oUdDW#CdW6I9rrir$Gf)uo3OY< zA^oBf!d=np>YgYIr{K$@)=V5vOZqu!4b=$_f(w4V`uC^Nsx8)6uAONL*F|u_@6-uA zh^#I#?dBl!*vbfSLfOY>({__==He1B;S0FiW>$voETdPnV)PDvE5Ozadk?xc6wnlQgEAq%h~Oz6iKkDMKtD8BC2*nh)#+_vIF$B{+C z&=GUevj>^*t%8uIkF1NL2}zC_6rHGt>v$gP0DkhqS$7MR$>yN_H) zbpZbsOVYzlxfk<=b*^4xZbIy%Q^+M2M|lZf(0ANj6?;>@Xkd;h>G5?ic9t9*0jJ3^ z0g{vSaNX#W9ALk|H+1aKig+;LTs>ST;S2ZOv*zMo6NOvEe2!|q#^+G{1!C(Z%JbMy zRzpPJ)WEe1{w|`6!F^i;*Z;8CdQ>*^`K-a&=jQVI27VFKAwc+|jwbEAboN0W*SSv& z*Z&H(Gq4AL#V-nZT%)p{ok=g?c7uIwa-H`V@Hh_9@6BiQt*3z-62$d0{-IZun>V2z z6rLl?9&_<}9>e!04ZhN#lGlIr^bIh$jWuxdV)#COzD=NCLN{&x3ky}sqOD$EemA&u~@iU2=5{Z4HjH+zg2Unju@f9Cz{qRO8Y3>D*>#o#W| zz|A-;<|nO7v7dx^=bN{0Z&N(N&NAm8tS{nr10CMg;OiMDrf)jIg?`~r&v+GOQ7LV_ z7_Q%s@An3T*7o))C|cvvOJca5C$J6>^Q4SBhQc1~`4p4-<`R2=ap*#`G=*a;<&F@u zGiTGt{vGMZNys{)lmDogo#iq*Z1X?Yo9f^+se_-<;n53sz81|^lAMKNd<$A&9pH1f ze|+5=%`b4fx%-;y7X^eb;7%_;?+nk^|D;&Eg$ORJb4~bd!&V+QIa|dxy3V3? z&-jw=INuoSSP8*-I;Cuk50$ot`l{sLaeo7ScURf~)2*mfFj7okWiR%Vu)g#C@%O)o z0!0PIC59^#zR+%euHCSO#|;YN1{r<-wWe&~aYGZu_Dg}qqr=m0sdaF4E}5?$u4`RHhY1(d zIur?hzg(z2#)XX!ZGPE-hGoLwHFN$fmFaK8t?K@kl_sWxhu8!3x1lH1{Vmu{3^(`# zzTY|scW0ZcK1W$plJ612l?o!bo0jg~9tDaD8TX0dy4|?HLA<$cJIHDJ;>-^$!XFa6h?>UJ=eYkm~1L^80r9&R4Kb1wqJPO(m}O)CP_Jh^8jgB zq`#dx&@!E`*m1}(e$eFWVfc2|;F~Qt53mxx&@XCh{GM7q`r&Qxqk0MTdQHALgs%l% z_>+cn${HqSXO58(ecSw|);IZxp}v~8qEyBG4b~BB=Jgw)c~S`n^>pwu?dH~Kw~XOp zI>?NjrE2KlHr7G2-EtYeQ#AOx1?K^_!I62(pjNl#7LOONn;S3ejQu{SVZS-X^9xNK ze2o3p03+s-OE9i>yCU}6EYK5_fRvNgI?-~;kKzoB_nd`Yig z_!&DJht^j4U>&I z&{xfXw(y|v_gu?6#eB(edY)dcr*A&d_iA+E%q1IC`w8*|<8=qIGw_r59-h{g=att{ zY&;GSzVMK+|E@!S^0@ZNV)l?n{0^*Ze0*K)8>zltllI_bbm*<2L+%B`eyr(t3K$&* zYUp5nSxg5P!}o_X>UK-pg!?(KJ1y(kS&-p-_*ZqiWn~-k)zqPo;KGFa&8kNxQyw%= z7mQO=hD74u?MwdKOzlCM9rHM($v4FCU7*3Y@D)QH=&eQNp>HGp?EPJ9RPkiUc)y$` z-y*^n=5H^((GHetqmu1aF}{IG5q)isom)@!l}+j^-HOLe;QO)$-{hHMd~F>uU+}?? z_kPqLB?2lGJRs)Jk_lh1-$feskmC{K>p?5Yz!m)ZkKMjj`Sr8|hJ4YL>f|Q=0miov zC#%Od&oyH4gZF!^FFYrEI(a`@pG=a`zmnhN_+};gf)4M$s~+EMuZijFCgVJeZ=alh zMK!+pD;Vma+22wKUl`xE|8`h4z9r8VY-e zL?IZP{kHpoZ z{+C%uabwLsgfDdRS`U7nL)*=5a=)^V;DX;-IscV?D3j4E=A_5hPjF#c7wpdwrCQvy7-bFuD2=Pk6RbPWsm;tr}$7y;7fEUj{w*78U*lh zB|W}bts~>x)#I;k5f>;rSr1qK2u@$>(=e4@Dg_m?;35Qh{*~Nhe?Rn_Kgcg0>pDN}z`MC}c!G(VOLS}<56gOy+ zubtVie5m}~@f6qjPt1N@Q>HY6TMfP2XU3hYDX!Nft`*%m_+J<=ZmxK4I$wFd;O{^? zPDaMfI}T5sMfv(o@(qx71HW@!*0*0%+@ML^X_9Xi<9AL^O?e%`%h7~OF41=5&+-slSf^d)OAk`M z!Qtlmn}hTV@M+hV8~858RZQaAiM}wtJ@EUT4vOnEiJMK<*FlHsj}@unk`%$;XUJv7 zA@6I4(KH#iggbV=&{b6_z}T;~Pvai^3BfsH^EaguZg+@N7v4Bf_3?=0xrVqrm2g?U zFEYOE>0kXN{-m@%V*Rae)~t#8`!T$IV^6?4KYG){j5k8kjxW!dCfXd5Ly(`k~gn;GAB z%}ed8QFDoh^!WOj{`Pb5@i8TWXuPS18zSun^MKAP3*M(Xcune%j1&bQ3GvRdF20vF zD3y3fkFTHD1H|hqr$4URe^w$WdQ%TKo3tBpWK!qhk6bD~6Md8j?!zeQ;acCpI)J`O z1L_Vf#+_>pH$Zd%C%X6Aj~5&9#3l_s;4g$_hT>Gd}PKyWH9mM;8p(&r~1mT#)r%6pb#Cvejf;IU%=~-@ndXp z36JYx#}(l*5mNKVwl%_a5=ammmR?`xJQTpz)O3Ad|Gm1Bv*^)q~j zNWo5`xO_kM5`CdxJX>o)Lmt=mYi$03zb>EAA-Jq^!gO#G`-OOY)tkxXsr~v*+HZi- zcjl!x@8s{ts7&pQ*Vo64L-*}@#>M00Zxfqu<}>@Nn^yP(ru9+DVZ2`>>U>&olYP*z zKwx`q(Vz4<%{{%v*10msetYnf?eafY?XS)f-3LPSg?VAi{C*b7GuE888-Ko^(P47s znX3Ml(^pJ~0%B({zqqU6N;JQSFX{1hGy1;XWrZqEO*P(MqDiEH_;oO_>p$%_Q}d(} z4(johe#GM=*x8bU6+h=8as~I<1c|;dzsO&*K-F%1J$zY@Zw{mH+8dgn_$)dp1%~_D zqAwt&P%`fS^-y_Yk4mcfaq7=vxDICi)@RLx|EQmI=9r61d_;#Di0}PBeEvFrQ||Jy z`7_>6hL~}_`>_IW6H&<_=qGc?@A*I+HLJt^uc!`glR9L-gyX*I2zODrnJPc&s~DRO zQ8x*NGPr%fpLKqG;StK$8RtBJ#|<8g^tZ?69#D<*c?$%`d8S{uc3%9JuQwpL-zZ4t z0bmHB!7qP^bdb@%=m)sX*{@VF^4x!7XzKf6Oy*DOF|qzuMEJrw?dmR(?+taEZ8t{W zS&fzrWT=M!wayi5H|sxukz8GsecHX zY&Yw%$ofO?zLn?lI=J2!Yd3{yw`INuk&z|IfbBM^L)L@{-#WYQ9|o9g@_iu2*Gc$7 zfBUCN)p3-s-y~n>VQgo$5bm}zA5LPqhX4OijIWFEg?a2xZ{3Q*)g&4HD+Occ3rl3G zWFz(f@o%4{Pb2>joxFm4oy1Rq4qLBR>)?7#EPn7X?bd%yZ=^5wXY#q2$4yNg6h?<$ zAErk|nq2G?r6Vum6^o8+aPF{u2m?->LbB5nmawgC_arGr#Nk;?@1e7V9uSHapX6Hy3F)h#w|?Ur#mf_I)DO zZeB*;Esv}9wXHYA)wHt^883kEONZ5bL&mt!9I6yx{LZ&27t+uPvg)J~4j_FsQ_83K zKI@}*zqqRmnh!;%4Dx>T(MU-TH%RzaL8neyTILg!$&ss!|3kQ%`ua(`r67pTZ{3#4 zBPD-k*lzqKxO@k;Q+Q5R@6Enw-99>HJs^hbJ%VweAAk4Hb)%zE(LR1rzGX2ki1fdS zNB-e)jmmoM=A4XiAx`Z)KNZab64P$kOh0}t>-JlCe*VwJ^erUoQE)%7CKYd@I`Hcy z!Hf7gI>bBA9Qiee$CX=(#SeC}Ujw+_+y2`Zd0eA1;;Y#&yo|n{Y_-114l#X0L|@>W z`p-8ad^K+=gYW^r^Y4^qEBTXbC&cDMsYG9R?)2ucj;(oIqq3g9QYE~u0e)xfuj=1T z4SXf0uR?GkP7N+u6y*8YPa5i=X%F&5Ja2)xdgT8GLKc;5yT$lgiQj>FOPMFm#_~u$ zs$SaPq7I^hlhI+{`)VBu{xZ~ohYXi}Xhs1fVIEs9C3BtTNhKWAvxhv=-$2+Az0~@q z2gLN18NdGfvy%puKuz;4J$)aDN{LEi2 z8~?7oru_zpzCiT8%6}f^ah>0Y>1$`~ciV)Iz>MQcdOA4wVmkxC&;B<>wGSlgteE{O z4BtaFo`J79iYw{y^Vld+$i^wmmlTu3X&IJpPmjO^1Gfe&R_RnSDDUR3HvAOZGY58aTSxep;~zT9DLfLwoO}7TyH~je1n8nO@y1#<<&kEH`v4+Zs1PL z_d0}Yf4==Pge#+eCFurpxXJ-+XW$>^{<;x)dE62~ll#O98NTgUzRk_?&8UrafPOJ6 zl)I4Xpj0r2n@@0I92$S{Hy72xY0@5?%s5oz;r+sXhmWhR&9I+@`0SUS8Ld$km4aKv zo)2Z;hjGgww9KDh`8^6WhJs!{E+YC~k1(1I3~i?RdQG;Q{VcX$=*P2~?JHiFlggU2 z2PeUWao+aIsX3IdbP><%jHJ-h!CMFO1sz_>nD#Wq4fZ#On?mdX3~cae_`Reg8T~8C zCizMqV|##gxs88q{g(1oOyXJzE{qp>-GA*zah)b{gQUO0I>855-~SQH;!1k$<|F+W z_%=Mz=nu-*Ym#q(;KKO!+b$PcPbL1>ByNcDJ0sHqXg>_bmH#tmXHq$QJ;Y~M?VZt^ z;wmO_T{mKX1^unVp%xB`8#L)3LX3Y1HLo*`;yO+8wWdVI&GkdRDdsEnHK(sk`UT9h z?)rTRS~tS&<~7OJi8?U&NEk0Vta}615?|8m7j|L~!1wzxImoRM`!&f|A-K>lo|u%} zjp9m|%<1c3`1*FwXh(5nlekU>x9+WDkT=FUC?;{;MUnC1h4kAuQe3A=TsyHd(0Ad^ z1@PQ7Y!F_PxIw}fY;DuNmI$8MgGpTLxrh!m{TGp6$GDPYZk*4XhH-)KmuGtwk3+Ia zTo17aSO@=RNL{opN9@5Qu9va1S6a?`gyOnQ#_K6}M|8-%+p!~T49uU@U&ZF#Uea!` zzhp@6DHKl1 zclq~?%6hl~Vh_l@OG6smy^HD)G^s<7;KHKP*HsUqbr`}R$y|R6lHU`C{As%nw`J2}}y(7=JXp7+fk7uhFb(}ABK=aYB`=0mqWaRJSTqEmKzF&&EPM)V!K=3|xp7R?va!TNnf-@g}q zH9VRv`VEgIhW=O6&J@&AH169xvR54*w`i#$E`Le5TtLPPu!r*+e3gg9zV9`S;hV3) z*ZZy*Unv>)V~A5P%ze6$`Ul0NKTBu62X2PO_rN8;C&pJs5hQK5eeFCp%GYUf4@@g?16v7wgLw8mAWeer2#Lky* zl5p8e>`SnqrDhxtX*U+z4EGMUFNsf>E3 zroL{X@73tyAUZEZprzv>A>Uq7~G!@ZGz>EsAMtdioYJesap&|Dxx- z(JB8_YX8{zpM?1O%6ct%GW_xZ_j&5M|WdVVK3GBUn>rlEskG1P&nCGxL}8Q*-p zn}s6p#P%QM%f}_s{)nHHp8H<|9xd%lv3_hVisXM#J?~^S(x}5vtNWU0uTc@%!z8=1;H@*dkpM>?_Dg~=&^4Ap!@=arO_(4O5 zf&qs5YWnp8hVS(ne6z0>(>L%=#2zNqI`R_r>)toat!sFgcFS0?Po&-WCJC1V#6Q3~ zOxvxk6wQ-LIH=bzq^t1w1`em)-#wsv#Fg}L3kl!r5Zc#QRXraUC^}gWH+doUXEo3{ zKiyzMVGlX;Pjl_&C;QjI?@Ya~>gS2#8z8t~+_SfLS3Sousz*VVeA9>GegXY$r#!cKKcck2oW5Cg@VXq# zIa6nqxeaA9dc~ad?AJrqx$7gO9%-wK?ZJt@$^_~%N_x1;d-!_TSG=}LTjY1}nND(C z6u00}tS{_)9rEjzQ#_92J+bvDISK0vabL##pAYf4+5d>G!=y5}kGyl{eje8@_`Fa$ z5$VU@cG`53$CU&>_vIjbLEk@j&A*q&bqL}H-p1_)`abv5l!eqDf+x(`S>b7n3+vUV zpPqp}=M$Y$n~TLIX*Xbf%OSYKAJs&&x%iS^zsT;2?F<%_zr62NG@VV7(Z7j^ z8G<@E86A985~qWU@CAFg-*;j=&o@tyubt=%I#@DqznS_ScP(@M%~uEet?~%BZq{CC zzNqAGCFXbBL|?Gqan+y9E{{Z&8 zddsx6)IS8@GZ&WxERlG!^27r#^8B)r#nx$qLqY}^bHzThBhY%N6A9ADDoD_w>4g*bKF*d=XvRIi}E*2l1)1i!xPg}-b(u2ET! zuaCq#(2uWn!Kz7oNe|a!$9&NOjP%x<8x!_iI`9U@g?RF>FFx-PA6wds)K}#YzGcx{ zpWis~NTjXtxO;HSNyh8kP0*%_V$cp7q<~Et(tQ z@bBy4%ETU^zvVg`tfuWIlXX@ehcD~l+6gX*-|pIxv-#_c%6hmyMu+{=?nZHHd`S=2 z&9vLn-^bk@A1YN%eN_?pToTOZo6H~3pFbmGwAeaK9?=2(S@l~B6Xwsdi4I_AGv57T z5YN}Btf#M!_y-t|*ByN62dbE2(m(hadpKi5g*cNQUxl&X#}{$-^nL@!9P6J zeU6XE&8aSC4<4r7?%3R7D35DY*3-c`68p0X2;kMPzxdP$hksuW*Fp3J+&kh>Q2a3t?y`F#2nP)>m)irTs>#a)|JKm z!leIo5WXAqrrla@`b`y28iDKKItgE}2anRDw-FBiz872EAA|p$v_}0oKvCRW(vQm^fbQ+PA2Y(?-`C??K=^`R|Gn3@()}! zs-m6_*~ITy(G^LPYA@z5%>PO(o^+9Z0V3J!b$gA+H7e`rTgceMtKE-6coLO@e~a<; z6Z-`_8&RWAyC~2Y3VM9qj1I5en!ARFDiYks?;-vH=CPU6KS-E=@DRQ*9~zoB<_OQ% zsH|sa9x|T?JDcTOs+zZm;^vcfgScen+V46U;qdS4@%0fMV0>$9^G@KeGb-!h1{l7p z63DlJ!Cjp|+@k!*bG^FRW1i&i+qy@rzXch-YZAz}kiqqd;cEJITU#7Yf`2&C=VD!6 z2cMu0A;K5Ni^smXFJa@RkN5|;nP)aDBJ*xd9Rf^T^5TP!f}4m+1&ZPNuO_aY(YI~C z8{{ZZR0stO?MxFlMAqeC{P<7V(YY09=2bItJk-yi~JekYcgI}$o<}kaL>J9nMZNmvFm`Y)JPQ~ z&)@E@&v%?LGnS3noB&S=hv-mv3<(u>I>g>&!Bw$vHyOHX1!LT z0~pKIdE@$Oo>am?J-#x7``r01!t>+gdzwb=BeD}*7&kYyuK7QnTHumlKjtsNW#qx2 z&EWe>ayR~WN&6)Iqg02Y8n!6D3gHWm?9SmoALS9!IvV;j{*rLna|e#sVSZ8c`m$e9 zCWqgM@lP?|`HiFaW)b^^=OR<4u-gz{!Af$ z9mcl-@BOX%ULVKzvDpL9*Td-Wc%ce=0cw{9fN? zO~z4vq64fG_~(`XiLWmo=qwi@2ikZey@9wX}7aI|7p+HYgE>= zGnfI<_+c0Yf0aI=XHjS$|-F8?}dyU8YXC?Mk-EO5;Xv_;*SFt|GA`Gw{krZGB< z-y|MK@!%oC_geJE-O4-tDPP$nUnhx6K!-e^^DMDZ0?#KI(4l?>za+|a>nc;h@{p^Q;8BfyV>l%#v8;qNQO>cDM zF|GfK`5k#89&c?3Fm=eQXcr4+;5Dg377BF0KR~>5-OzO5`2~NUIUTS)z=oAUo#!8= z?ItyixgTo=Umhl|&iF_jSLenU|MGlg!VB!|nl8T$;NLeY>)C^cu?OdFwLKIH&a)K4 z7uFw+PR&Hs69xm#?cd2E<1zT1&ZqaI=NA|^c-|bYkLUnHQ2A|@s_}XTI*Y}V!DZNf zVctE~`gtG9*SXvrUwILp55YWk=M6(XqquI9xDJ8~`tGn=(K-y)*KZOx)EM6{#5)(#DsFWhO&pb$Y!Th3N@R(MVuTneaejLSv798aF)L^`LuW^Tu>G9%R@Ov-{$?sf& zPa9b2gKvuQ$Up9Lg6oJjtS{K_x|5f{ETU4{c`@9SKO%Ovcg~(EQJ|=hBZzBd_|}%H ztNNQ&aNnyJMW%GTs9FE7gpC(6;S1wt$E!DY;&qS&=NGwzFU+&3)RY~)V}3G#IizTkha>egWak84!c z<7+4V0t|QaKM()H<0u!!^tGWU3t+!6F`imh;No=23 zh~azbhIi2Cnxj+d4`R5=V(iz!eyz>dqIDx|>CP4A;*wwuj0^2{-#d?8q`1?Y zueT3wAHYprx~CE4>nF#fYf+c<{F#I33(py@e{tC({FVOlVtg~0cKi9r8P#*A`~ori zwN8rIL&4myRpXFN@OzVT7`_MB1ys0sKZ^17F}UT(@+3F77x9bgK089(GPe81E1zgdFc%bKzT_X~*6);3Fffbw;kj7ywky&Bdh z>+ML~_tU15^D0l-(M1)(gmNBSsC2H3tv&;CJW+*NWXyj@rEUH?<#J$mFC6^1x2PXFNF28 z>Q8h$60HJ?1rLb%$t?052e8}Q)|caPm7QYk<|TFtaq4L+v>x^kev|fVC+!CF`DT;6 z^C+%V2G1{Yf?_%-1Q*tKMmFm3B*m2pu2*oseLm^OpzmXsKHfud6@u#!#FcWfJ%F7J zd}V2|oq5grGr|knEzqvpT*}w!F=xLa;(x(E+_w=vzlrU^YqDPiiM|j&44+!5fa1Ez zeW1f7Cd@*8io7&3UTjRh5vfh=*Cby*@xQR%w`%!ozpHC5`G_807t=4QC+~Zl^7We3 z!OGa#m=B&GN^$)r?aV{?!o2(Sw>y5p-*v$bLBB(ApltWRB+f8kP0h%}(qW#?AhzccWU!nXAnCvjAgfUq3tTMI(Ov z`+9s+dte5Tc7MF5}9S~wW}_( z627pmalB@?sj3qU4(Ra>pcQrSub@MNfA@V$8TkJ;*WVn3Z!*GtrpkK;?9^}T@pY28 z8tlwF@7;6iD@#72hpP~O265`(UGtwU8AbiB9Fa$JI#DM<_18 zpEiy79k8<}@&}=H`{Q}1gB6$ypt^XfkkL4<0fegFQ@b z_eqfAx=r$RGIsXHwPOcUT)#uO6qkaVa6fhv9X!V4kS4Cej6)r6hVPNZxL$&rXN;@j3I_^_J%B&UEjMiu#SO;Z-!%EU zi4G7yq)c=a^Ys(H$vws52S4e@Fz@cLy=@(o#g(vX>PtKf-?m;!wVxnYkgxrJ5r6jL z!<80LeWjWv`vqfX<7ZbsroN++kLc-;M(hmix9v-b!e{j{faXgN@kD;Auj>o}UBlCb=L)70ZoKjY7 z9^fQ?rwSsvZ2gl8&$q~!FMmn6>}Gxk@8wP#+VUrP1o^rdKiU72_QQBwS6?xG3yHqa zkLNT|f6m=rPE6kr;~yGi`q3(Abn+YXjlO`CJdD1tYUmpf+{xSY{7GQOo(`)U_|lJgodzR3*V zQ1*Bqk86KYjBm=ah@U)s^7BuqpY+DQA5pX2ayw#uA%2+qO|RE^zP9pWI(V6WeD3Rm zn|a)Tpbk#*dy5c1?7OegFFbC(AYXT9JRa9TfXNF#LOS3Pz~3_FxI|OmBGNCwepl97 zHG}8tsUW7Wn~X!SZd5se`?-9i-6|m52S%=2&+}C>4eeJ`2MI;!5KDp%>ojzbD~ah~ zMLhv<;dxfYJx8~pEUu(C&dWs++@@m>UB`o_J|PzW2Fbh<;!hjFU;p1JKbA&T%)qyc#(!yUZCB;er<25-@O@-zpJjaIfl*@pEt&K;h<676+VCWgYpWur zuS~`_z`fzo#H~LBiT$S_+}#`J{Yv|VbicWNVYTAx!9NVkTMS`vRFX%F>1$>59igGG zQ}B22+{+_==Z24}4W~MIUp1$LgY;wQ7dO_jR*VuMhJv1-^pk!8`d&3%?I#Nabx3Ov znIB*C{(F(lin6${n$?WF~oh%CeC>+>LyVktG?LxVh0#MdDEhR%1@@(5F0mBnYeoDH_xk{ zqX)-`^<$ao$E~L}RryJ~;P13K89Q5EvsWcvUpdQ=FMmn69AxxuqM>gLuC&xL48AvzRSN=+pn{=7~ibP*gwE? z)AF01L*smsjQ*AUCg*Q2WWA8U@A3e#>sX|!9~En+%2 zn10bRH*xW=B;z;%0@N)x{HPi?J%arro$$R1;d;fsr&m+oG{*0IopiHm+>~w=(>KKQ zi&f=seVVt2q8G%*O-B)qt3ltLvo5sfaSNUmn;++raTDf4NeTSEOm{Bk3xUHcgBx$8 z{mpAKo^&w%VnEh|Z}2)~q>8nhwJNq>FqY9f{kMB=4bp_{j?dRAH(|DAEVA5W+Q*KUDNBYwT1M!OXle?C^zeqD?XH*4sS{iv7@e&Tna z-MZI0KAOKzqq3e3In48{?W0pv`!zfV#p3GxU}RlmK)njXjQH{I>)BZr<0s3s@uE*n zM5hd=n7&y|e0I;pH&oAKJ%WC+fEkB&Y3Q3gP>ipe@C85lMYpff=L>NQ%h%xNPK7^+ z`SpBTWc}=Qdy94y*In1#^DH;hZWT1zEmu&7Y-W6`KfQ}L+8WS$)X!q;QFg|!H_`A9 z(owN~;V1sA5+d5+Pzde+jZVS+V(n(DiQ5h4$1{5L9Tkl#N%Ao|ynyGM zQ$M-xEbSNm*!u-fC0q`Yc>wg|+CKH~IQj(l%jGcstiOgob5$0zhXSVE=Km#i;cqG} zUCf_ZuZ_%O8~1MgFOO?f)*IivjGz2I>?e(oqTdHxIr>nzr0mD`0PBbc+jX=^vouaB z;gB9*2l?K7h*KB*eeXgZ!dFGC-MmX9^TI`^j-%(iNityjXPb*BGkmxoUyHCB_FjnM zYI0}O%;AP^$JayL*XV(vkj0hs^v$^&`xSUF|6HFR))e#YZH}+h9$yds;hIjB5N>=) zkFS;BLa_OWT;nv4ntZL8J>(M|U|spp{sjl94zgJtkVk+q2-ZElp;~wHeBFY46~YTX z7y8_TZQPWv(|JBd&SYW_;2(lxzdwSq zsH9XE?ei{b`$`+ILmZLJZeO=Eo5KPR?7>nCI*HP%KU@BKpF* z+@IHNt;^%4HxuJ4-G}`z;P!fS^kE)X7Sz{8^o4==#eve(Jg&E;7+*KjZm#Lmn)A3B zt;BGXi4IpIz=dmfqWN)jDsYJ5S_v-nx5A&FP_6%F-7kjgAv#n7+*@9p6U`QV)^3hi zfAbPtSU1}I%=NW++(1pS`A`a@!;$&*7V)?l#(Xu`&wPwM3~b@Jo5#)VZK$s%uAksS ze75Dog8Pm9H)FqD1EKZ$ zuXC>`P*g~JM9i-%4BwBx|6~Y{TM(lT{OA1@qA%!h&z4`C@wl#rV*S{D29FnD4y$^`lZyIA~7s|})#N!&3_4vw!FX(XFhz@8UX>_um z7xTY%f(sibw_bb8iD*>x+3a*N9Tb8K4OVg5!W($p?1#i~om+6b)j@!sug*0np0|+W zd_8(!z z|1dvxzT0Le#SNOob&__gjBuZ>aQ#aZ*IC}&dTIgT3+t(?hh@7cuG=K8cP(Czu8(j# zfCixoF;!B%^;Nze!vt@ek0hM=o7b#eGmmNlDKhTui(9 zE5GnTNf=u1>EWg_IxHX4>L_hDse(Csa1dPRZ}Qs(Xq6c=kWJ#c8NZYC!cxsxOY8pW zF+Cm9Nk0a@uYPNX`EmFXr%ArnTCZkVhHDlbX18E9MJv^&4L~`|{iZnTELhCE;=* z`P~Qb56_<&`Xzso<0i4^kkX%#@nXhbYTPVAT<^Y!f2dsM+U>O6{3f51r7(Oeu2KK4 zT)rS*JA?c9;Tga1`r6Kl^|v$zH~F9%H?M(MyEz%$`S;CK@eK;%W~W5#;p5ZSpyik( z8MKg1et&gNOYG0Ue(&s|=36BAyPiGbqJDi9-f;%{Kr>M@j6J|#MWVKgfEQ8K6xCP2Sler zLB1&$v7G_#7aF+M#$xvCA#pXV8{NNW&rCXA$gRx9>k6a8&#Q*s7_9>OT^K>Wg~UHV zNBhrZJ4E>^515+=q%(X&8ho9CeDg_v1HL!ikmiZ?i_ma9AA)tyK&6670Ta3_vYrx(04a6S02bVQ`16 zQS0Cl#C2DS%wr$ezV}aF-#kHFFN3>zry4gXh#MsR4c4QQAKLH{wO{x9=K5QR{N4=s zhjWj1ZH;hc^sl7!Glv^wbQoLd2bI3*O~vd%{vGpz`TUV<)wtF-#rlO*IbsjzHTdQV z^0ms?pTTp}<(8^2t&d7_Gcg@fYewRz{ok)b`&N=<0Ct;fH&-&|3-RRZ+ZOu(lTEh! z#Nx>i>BkWF&9Qb;#ZkHFqs~yLUecRi*oeM>`&I=tZdz|K-1HByzR=(D+8yad`uQ9rgK^0F=9y2aJ@`%9LpEa%^EK>2=_zIpL9(s~&rOHD z+4gy=uhiIFydFG++Xu$^4NY#kKyhW0xC*%*{7$NU<69KhX%aW34sJK_5AS?FZUAjJ ziTu7fI$UDX>lcBJIIf2E>P)fEqifci@*(aQ5TCXAX8l^KgWqJo$Rq2iz;{tw&8ka0 zsHcOi7Um23jym=150tNxZmu8u$a4{xZ+dTg>+urFX}qb&S3xr?@PjZPx~9_OD>W`H z@sJ*FHt`P-PqtWhJ;KFjI!)>jWbABl0^7|++70;L`p>*Il&>V4^ACPz-F|$X&mS&P zOpQ17^bJ{XyTOL5fp@ZCfm(P>F>kkj^M460UF(*B~QU}~V5U9`1Jl-K@KysoUZn71R^U&YQ zJ>2>gY7b76>yw4V|H1<8ms0QMiQ;P|I>6`kp7b6={x`m)r$c~zE+6z=5d2X!4=}1l z4>zBUAJA^Oc#|G(i0F&lyOf#0{ZS4w4*+{OlBRxsVe2b450FW_!NcXOGdpidlnw!A z+R1de1=@&niYqL-vLHiv&+7+$h9iaB>ChK3? zXpy6OxJAtR!_VLLSNUJ%0WrVhXX28)f3I3W`36n$bsoe06^J&S8JJ6Py(ahf1xdVA z3*pwBvwv7IE~zh~r1pP$`pV=v8LY!BU;D>xD3i4jw2$iHrV?C;cUCsL^Ih$$^^fY| z2Fd+`4!=*Rik`;dGrcx*^Q@G0__+v51Q0mALK&eNabO6Se_ zbw9aZST_pQn|%yrGJ3_F^z`-L5sCYHKD9S-e!WcuxBLz1zwkth`ib@9gB|W|cq}^cN(lhnWhvGvm zwo3J7J+Zz}@7D>8CzCs1{XpNlthb_e!*}NX!(6{et&ed*hsnRM&84_X6LbE-Qx@Zb zpKQ>rZ}EIyHrbEeL(%nJ2T@$VNgcf8eqmjC!Q(rY zQ(U({cD^#YmQRiY*v=sCOKsi0n-phcf~|)~MSFpWz7Sh?ziut!8(-4JW$Y~Je|Fa(SKOb(3 zuH7(e^A4)7vw^vO;b<1|>!0n|S%>0!0#8=;6=!Pg z1GL+zr?dZ|`npZFTMqG);CHV1=QzZvGWu6?)-&hVy^K9f>U=D}n6F8F^B8+bRu+w> zxRNurc7uDnlCCIlMS&{{Tv6bP0#_8cqQDget|)Ltf!GvygPbNeYZSFlKClh1i^PVa ze-_2hYgM}VMQuwLKj+rc#m{bEy7;*_moC2hzlNo1Kgs<|m%roD(#06IhKINa)$C&>u=>F0j*nVhE^`~}8b2tw6*$llvAL#}B9JwTYMDUvu{NT9K!KeJ4 zqmA)d`>{V3pZ&OFY+uk1^o$js`V(tQKid~{qBf4C0*NF981ToWH1*TVnu6^x&82j)+6`BiOv z1s&JIccSB(_$zeqSLxuRzFWEl)m!vBj(=$GUa>pO-~Kv@uSmWQ z9f$L!diBD7vp8S9TN7Wl{v3|e=zWcL;qgmB$IHNY!{Iy8aTwp}`9b18-RQU$|BC)# z62yn@S8Ip)(A>W%m;~`>&NG?e_><;`(Q&qYv%kRCc{c}>SbT+C_eYfjVf^4yd>+l+ zRS#(5zk`lz;XAKApove{CsUrVVLd@xloB<6L4F*hj6bEtJpT$~7i@^0$0dsYh>H6) z+gGZ*AL$>llc8gO=jHD1REiNe1!xd;2ke`wYyV=F$Nj{^+)f4_U~(PW7y7UuI%e!f$2d3{zTtYF`f5=aKW7i-L38)6 zMPYo~Da?oFOVDwazyA#3zk5*_pRW7RTzLFCUnZ<4XjW1Z#*7<3% ze?SvSD-sBBz<&57tk1P#{9~Q}QvLyh`6-RB^1dyd^;L?W6DnQ&!oNxvKX|%y@Ok@; zb^U>kzg~m*it2AaQ#$-9epXTG;-{S~UHssUr8B>v`lSC`YWU!uq}+?8gU{RNgE6jO z(e*c*!SfNMPndtvf2G5p>YviJY1DX>sQDMg&-tWu=64i7^|R8!pD?C@(Y9f$GJJLbu7+(UE9KXkTq_}_iJV|ae& zScTV#Xs(>-7@ptJd5vuy<~0Q!kBZ->;p?1#c8s3iT^Js|56a(jzI6Cg{Oo^A7r)?Q z>EfsSS-SYnze)%H%L;h?vv}Q{uA^7dS^q@GqvCV&eAbDMhvP%;`RteNF@9=0+>dB3 zchJE{$2IZMaZUXGI{1(1;G^T3_~^J6e&AD#PoG=UT-uDw;N>PSFUsNNC$BkIKWLfyWM7MaBz_%5IlL?`{BoikUQ5YK$?R)^mz%tnp&VXI zN8y(;8oiHRPV(a0bk5)DmZ_`ySp2K;>nO_MW%1#c6Xoz)N?yv^J{EYn$!i(P;k9%f zekt#x_tDEqUVMG=mUDmA{=Im*pVI$Q{it~*i{BL$a%bHXem~oXb176MTuz%w%IpOt z{O|h2`222gJ=u2}T0_paTEq3ZhZtYaR-e2cpI_4bh3jK4LjUJB$MY%fuwl_xJGS~7 zNbt#dw4d?=ydGq~4PV#wg-odl`c{nm2{_KC@3R#vsDQqD>k@k`ZFI?>qv7kbPQ>lq zb$X_Rwm?f+6XUBdE6)1dw7$18rDmu;+obsFOZzmw`wP+fR%S}gQGNEw@zv*v^ZuNZ zu%2n3WlAkjeW_F8tIr>2eF0Km*PWRX+F~vRW@CGe)m{qXtWTLt?B$nCsTHa(^m2Un z7mBk!AFc0rresI;d9&lIPkuT+dy%J*`};RjYK`j4of=<#jyUV{(E2KllF$}@$u}*& z`hwHryFck=a(}f)NjIbV@?MFrKI^OT)#sx1H6JClMfLfo$5)^G;n?a+xq$s=&Lr$V zzq;=?=@V36)&RU;fWFWAN-h7H?uoBHM>f_o@aS*SdQ_jy8DD*_IP3G1`gV`}P5Kno z=Q)7aH)FlO>^SSQPsR7Q=f&To&rp4Zan@(6jK9x@)t&vHjz{@t@OpXR6jWcAw z8qGHkf#;Nw{a*ArWtR+eK6)NWpHI?U8j7D&(&vygm(g)}4iVlghVl`En}q*;V%U?G zTTnTaj^izwHyVzPqk3&C@IEY>OCz4NG(+bX+>7^b(fo;P|GL&PXe@e<i>G9{=NHTgUEm#{ zPLjJx?k9PWB)Qz0)Jt-+^}1igcwUnGNiL1Y$7PZ` zN$#e{P2R8j#r3#-N$w}PG#($9N$w=Mn;ti)w=uLf+Psl|GY}!Lv$SawNi-V8=AY1!}&>4 z>P);Pj|EiLLj!>OdZ|WTAv8f5bO0<35S<(BVf?G1AI&AxreVAVIeKFUf#_=NrT5n#Q z-y=io%^nk7uQTsSsUBM|*`JwA?8l1gRhW9^IPHqoo0cAJ&(4&QQUkVLvad2x_Dt*L zb#`Wrlp3@3lFx%AN@uifGn}le@O(m9jq?JMyVl@x-Z4Bc%6T7`bIJLsYjHV1@{D!3 zERpk)eYor;IjIiY6%-0No$uOesX>DRc%OX#MxyRFtTTdj{2pDeGuu5`9ACk$LGm{I!g3>9FZsR>T5q#N^dnSHZsX{B-Gjcc$ZWmjdpxK;H%0ZjnSKm|=?XuWX1tbZ2Oncq*T z)DBplVe2L9EQzX@LVL)3;d13ie`pq-FSu6XxPs==kIgjq|20I%+5Jhb)p$KHh>kRn&llixCK;>n`K)bU`TvRnrKLc90$ebiJnt;uAUsYT`7+ItRuRpU z(ND=+(K&SgF&&?-O}bjz&WsbW#(8@CqA4!D&wJq?Iaw+KXC;vM{mcRonwOy89fO~~ zktlx7HCV6h&vmnOLwbcyW4*j{NIXPQtY~m!^rD9omBa6$K?-vFxP#fMKci?J?uz0u8b58`Df_C?R9c93ZMO5x%O z$}8nv%qxEp<~4XlH%kx1EA@Z49ZQ=RyG4@AVPqE!^#k|tr!Fu@z++%SdUP@-^Y?szr2eb8-ldq=p!N4y?nk`5m)q`1gHT@9ZCJ1DWtdl^<~=OE5U&u? zOJ!f^dIh}_-5;r6puBvih<#1393H1L-tBK0f_N3py1afu_Fz9sd8MDmyz<_~dUdVw zuq6ZWl3u^Oyz)6-xqo9`j$F)ZYQKjqLlLj^%gig~wP?K@XE3iq%4^=kmSKoj^6bm2 zSH|nnyov}f_j^RI?T=W7BVKuznU`x;G%xQzSg(}jnAcZ7JYpGvcv;)zG8*xc7G55`vPfK~rx#tf|KjXW%hSN?WgJH*svY&# z9r?JB*NZ-P_@dk}%QJ|V?=tbyv@ax!?+9LRrq4lEG#X|ZgLv6DC$>N8>7{933@`fp z=G}I~EYBid*_VlzrhOq^h3AN0CC`b1Im0Z^Aznq3qwUK_{3Fae$}#@S9i!j$NZR`x zJzDDk2tSw1bLn%gLHWZhV-c_1Dbc*B-lFRhdb}tuk|>;byQk0Tww)bjc^>gfemk*# z!aqxUKF9Y*v+)G~Id^)$W^)=(Q2eZwIG(6JVua-dq*v+|+#gl*v{H^IMD@y>kK2R) zT)n7H&KINO8LF470rp?1x%fHn$nk$l=g@QK^w;#(O)QdvNF;h*OYe)$ACvFIyzDD5 zue(1uC$%e&zK^@C4le{y8oZoyqURl{7ov5P$BwX!W9*CCAHAP=UTNp>^CWsc^)sUWE8e(}^0IwQcr6@Z8IO2*-^Ko`w0Y6{ zr7|M>Lf#&&laqGL{{ZuPYWWC@8}TY4yi|SyU8A5^qV1mEzo?%;l){Pseh+#)-aJ%* zzYm>WNBsoF4-xyat{7=~3F&2DgWFN1S1J2d>L={n_m0TxM_MK@yeMyaKk@cQSB(9U z))VfJs4^NC7JiED>+p_|mWha0st@Z$&!=(a<({XxKf}Dr{xZ@s3Gpht9{bhO=0)$9 zwg<0Q%IBEZkz*q*lY!S|(u?;K)UVR{wvX^CSMe#!6vQiM?d54ly*QfMSK0<*U)`Uw zyo`9ItxGH~y?F;87t(fg9>(K#kns9GbZLAx;$P5$)y!DvZax6ocu61p|N48|B^>7zY{GiUJ6x9O3@^&N_`c(Op5~3w z-_v@+!GvU!vf_L$n(_v=2mX7lig}y-hqfcdFUrSyIghz4uOhwDe#GNEy^rGRF4MT3 zaT2#<>edLa84NGVyO>v;?N}INJJNcnzb_*DL+#r!ue&a}EHe==&mla2r03IqQ`&K~ z*|?DZUbA97P5wjei^uoY%(QrrUPZ*ds9wd@T_*c-+oFF@5O~dEc=5dBjSHQm{}$hu z&OfvsYF{*-$k~SNYf|$}%WH^N@`u>3((~y!R@!kPjia4*POs&emNyWu+@G+Y;D5h0 zUcG#6qQ^fSxg=T-uUCNhiOF|lT3$!ItRGz-y=Xg7zI5EC?c~~w+wo}kOv`M<%TIVw zyJ!8x%S@bOcE6ln{6*`{+l6^G_{C+JgLu(I{e6U&l+b;AJTKAl(S9qo7yfsN>3x{Z zssG~fontdCbCF&SV)s<9;`%O=|MIuM{W1M3+>XF&9>a_09dCbh$JiffJ+wd4@lhuB z)oo^`B?s|xeT@4fJwIY!iQOm4+n3q#k@}nB_D#?~)V_FpFY>GNkzUlVQoV|+EoJ+n z?MTO=?44vB`YhA(CgMfMA-EP^nU)2JS9&3i3u!yDc7HkiJ+0TVoA~*|+VzC3-#typ}P%DDPrD;#{8y z{vUf^0v|<@{a;-I3HN{p0R@IL0Tr^Yy73;7Be?4tcRix(x+8K#*CV?M22g20CEoE^ zjk@ZH903)_3xel}9O074WxPk^2&gdL0Tuplrs`E{Dl^^H)01KUpU-bTpGhZ^p7;H} z?|b#Cy1KesbNq!kSicJRb3%L@nO@$*uBUUOygq01_qac{n`oWLl8!r?W&Ib3fb-Fw z4UE^Ep4ZbV;N^RR<$WSva{riaUf3QHw`@J*b==_V={(>S;k=sU7x?0Xce>jnn2f#L zw#Ujp#OEd2b-Ts(i1zDveueM7p3VooJf9xi_UJ2!_dCk#S&0|&7CJa=j}4mb5pmS^ zSo;CXFEZ2`BhTK^t#))fxZB|8Zyia$AQQzd@|4b4;im}hTK4dz^m%5%<6^p9qUB- zDU4So=k@$`H_#V>SMl3Pcs28JE$Wqjs!}Izxq-eU@j~7hf2Z>%p5N=uVFr`|U`Q^?AY%{)?maInnR%b&oY4F6Nz}qb)va=VVx-cjMoYOc={Uf!a9Mx zGF>MSH}omvHR!tW^mX7>9ZJ#=QR_sq zb@jpz{)^K(QGGG16J^^NFLT3q`Zn;wI+2K%Tql}~S51EWa}cBF|CYtB^ka^eEoSSf z#d;?Ac!e}Sk!(Jf%Op0A^aA^JPcvLJ5aqQ(;#IPkty>fIEBb$lS98rrpfoI7}&}5YI*$xx)gX}y~q9K<21QWG}mz&9zPcBV!T4rC(vcU3+sI%UUI!}E?zh; zEUjm}hF46W%YhfxFXWY}`h|4@aqD(4UW1>SKvw{-oF)H%)`_Ca;@gX87cPInI)V0U zd47f8n?P$oueyU=Ckp-Xen)w&lz1U;A%nwlVWDQ7Kpd$;+^Y$2-Kvx4VY>$a}$@MGUys$kYF5$d>e_#S#1H2l(O>$i( z1k?xb<~mM8Ugcw09R0hQUiV*qBV7x;yzgeVPE=gMcp$If8*Ds^c^w_Eu7UAt&CN_N z{9GPKN0*=ry^^f=$L~4a;5$lfl+ov68r@hbn0<$ZX=jkFecVg17W0|(eRO1%z0*}4ef z2meL)xC41%{VM*J*RSx6^nKuk^-J)=`;9mA@esC0#0^ClulzkX()GZrHp6uS^>y1G zbFPlhOSJ2Di|rBZd%x%T)uW7V0KMwB9NhL;a!tJ7Vc@k<;)T404i4L6m1cWH9L#$> zzgGVP(`(KdWpuNY_qe}&9(jgT@0)A=1mYHPUdNwXMn3>vbxSkbKVm#E?^B(h2;UnY zf3)j(8)A8k-^08Y_8(yP<7;#4B>DyDmDhn?hu`G9Rff)smfsiexBtOObc@7G@J5Fm z=6y&r?-3`K_mIDJuQ6Vpy)5tFoi&Mm3A_RuSbpLD@;JIV$Ezx@D&+ObB)S!NHDrhv z`itREdHMD+y_PPWM7II2qK)a*E7?43!gZoR66;r_1-oBI-o{CEJMgMfc)6`#$#~i6 z75H>FpvWaA-~m)rW~eJj2lV}7{ZV*L{K&ukUDpJ>}xZlUek!}ac; zCaL!ss$YSl;^*)E@7_Y&OS}Yc6vAQsifGm^#KC?$Z!U{R?Qbl<0-JB49e|hTcyCNU z+#j$1j*g>8Nd0zBn(w2l@+#TSczJi+LOTMl!p~S7o0}K z2Y3}d6t9=t`vW99?nrn)1&9aos^q*{wwgja0k43fS99^IdMJLr8uh~KtpdL?y@upW zp`C$O*`D|~Vx38KeNM8vs@8ju3SQEQGYqiqwlcmQ>we8{Kd4_ZYM!IH{mZjr?e9;& z1?k6lqws1NEz1~Z<1gY&xPMS4H* zs>v{~;IWKHHcK#4x|s37xNm8(lpY2TfvJ6uGdl3GwYM!7gzh zsk|yE<2Q8iDmoB&Wp8EAhl%?V|HB7cU0x+FdF36#cnw>*iXIKTO17nkm+6of_Ct8R zg83t>U;g9E=%(oSi(jvR$CvWBFbi@3^-A|~E%L(gYI#ehSMJtHbO-Pv%D7PGmCEsU zvbvhE9|CyfRmaEoxj#&z^}wq*&AgJ0SJirt{ZROEHXmJl8q=$Mok^~M`vjV=vwpjJ z18cu-`=R_K;~}&Q62)Fvze`8}ln>EDb+A zTbVw{i!5P!RJUS!)tpdBz5rfD`;yE900$qu)6EOVHOQ;}dd90Li}7kTtdML0US57( zW~TI#*15+je#H%pS3T!7_ku$5WptSFOJ?=L>*i3eg7J)(na%Xtacd#j3cQMw@-mtw zjwN4;`~p#6edBrT@0`|*SKfaL$u{5>Ovk_OHp}*gSgS z{k|}c_&m|VHcYRTuNIOWz{{VMSM%tlw#WP%S$>5%ubQQWq#k&Ae#@+0*zcfT_#D)- zwoI?qn+nNJ;1x>Bt9kTN>qH&b%hQhWD*3UH>;hgn`!lN-o~J^+@cFG(oY%aTBgt35 zt28OE=Fv;7UwIQ*e)-xny=L4xl6(!kYBJ1A)vK2Cs^h%o{bwZk26%Z7B#UFS>lLf3 zWs{g*r5%`FcN}&$*$uqPGR#ZTE5^$^iq-qiPG))qIIrOo z&nFS!73#spg_#;psJv=8uL2L#Yxo`KlW&1nPS4EpQtMagO-!#^Xki}@v7mxhVML|{0zJzhh;X7QeBN5cN9-! zy!?l8z4o3@8h}^e@Po^%YC7Z9zx#p zF1GM+VjujG?s*fme@^rlZ#GGF-DA$^cz@8Y+b!xGM$m&-U zoEC)o;KSz93wQxKjI+4k6^FC@n)d5~Df{3*Wv3>os~NhlPe_SJl-Dm3FXSEdA@*{3 z9@$^2*B%iE;~0FH$C1NEJE!M?SHzbjj?J9+SSPB-viz;@#^N{w^!gQeRkmil&<~uS zjh=s$=gHH(o_qk$ul#QrFRc4fy%qqkhNF|@7yRD`Z{582-fM{V1Yfg#VH{D9BCglC zt{0HsfS1`Tv;8&_MqUk%vivGr$l@6N{|msYY7o2L9rqX8=C2d6@mGC0<5k$5@hTs1 z0of0{>Uw2ZFMb~k)GP29;}zz-qPhfu7dbXbdu)Eaq7+EQ9XyUbm|o*fx_}%2UirN< ztCuvskMRmW#dyX3fFIG|E&^WJgOcdg%=HW7Sa2ufRn?Q}HE-kvgupnb{2=KSOL{l! zCs5!tZ$YmZwJ_JK&dc=bckuDx!>uRH97sG!%gIRuIKOkg* zb!k5ML$}_G?`i&mdX?YBcxCtI?eWSB2nD?g`ee2};&E-P-;RotJ0RA7c@{BV(T`q> zDajnf>-0sx4Ii(7olviI_uHsf{@qNkfV?HQ>qh@;}~yQFS$-6 zTi=2@H zdId79S6sghP9$oNZ%gfw@b$B@UYTf*HC(UAK&IEcM=vC8K(B^_q!-4q^nMmc?=g(m zSMx3;ZGl%&|IFq+#u4)#>R<&HJ1Om|oSW*M}F9cA!^PhV{bZN2`A5 z9VzeYpJ2Q*o%bQGSN*XpzmDB?A!!eKk=)GY7wYADi&M^E-X6PN zL^^<8g=w0X)8&hLAurEEj8|bkkK@3LNJromJVgJE`ewbhQoN&)^EWgSpUPL;9UjBom7x0Q@k?MC;$EEO} z&G52zRTq&% zK`+mM%(h3hu9j4>I0jB&yk=wX`}%1Xwo&pEbc^uL4n@r-DcnRM4e~0S< zeD~#R_(z=w=i1CJx=IhBkBUUka#d~WsfYx2T=JMt0Zm3J!3uhvCV$vEJZ|3;EJ z0lC#2`BlhyATQr1j92;Tj92dTsiXvWm1me2>Vv!*>KHF_SesZswC$9~$)mulq$OL| zk?HmKZu_CaJ=`CNtE*QI(*tc_KZN$H&tP#JcgA+|80b~oIf-5w>W7MFv2kL(kMWv) z`F!#?@X9+h2`_NW2k&&(Rn!ObE5hSpp2>JU^WA*%U*J`FLuRkjL0*_&PS<04?_+fz z*R^6^q-%@$h4yoXFulCXSCc0|FY~k{=aHL#-D9lZ#{2H0ztM5Va`=yb^1+#p#(oIT zcZ9dH`vXLI)x;Pxrg&d|d48ff&v&>Te<5GgIbGYBUO*0?W8i$(k z!2e~v(!H+3tzPNUN410bg~x4?C5?K$C+SuCI_q!5I(INM1DwLTs(b&5WalZ9jlVGO z>xMV-T9<%Vrt%)^7wUm}M&nxxysAs%>x8&3Ec{=dFHCk{3AE>QtL8m^Kg#QUNw3H| zZ2rP+-Y4UqFpfY1+hd@xF^=n-fmgEpLVr;gHSY^XHuBn#fY-sw`&x|jEokrheGJAVr8-0)9Z~slF)98B{d~Z5z$<6HTg>Cfh z<8M33RJ|(y$nt*JfYtO^(5rq%{P_;qo)7-OdM|&T==Wf{^;(#sUhuti>Q(b6rq`b? zUQGvqUcU15=v9+$y_Tn_7kn?BdNrKG^g8Q~)pT$gujdOp)Jx6#ymL9PM_1E);8n3J zJ#lPs$t#4s=B=i`174A@(!*U(4T(9?leUYhEc-zBdw=QVQW8hQrs zilk}$Rpydc*+slg>|H~Bz{~SNdg@n&OJ1I0#%p-%we(EjRq$SV@~g@vuPV-KXxFuL z2=FRNlU^a0ynGk)_BdcIJqvgh?@rJ7tIj2_I^=cIS~?VX1%6HsuZT-trI+yh8o8DZ z171}P>EV@K;I6J_|Bc7-;1mGz zE_oGP%JsTqEiD9IwMV9hSCLCz7^C4M*U{^MSLycj$SI* zJ_fuRzD`em`CRg<;k<^oexE)Lyh?sa53gdEy!?Kq*NCp~)BggmoL|$!tJEd02F`2P zN$=AqfLHkT^zbTo$*baWrq}S1@6#uNS3#QQR|6^XDi1O~wY=WXS@k}B3V5Zfu2#F` z6&l6(&D!-o4FIon)zw;;yo#^jyxOd%PXn)X)zx~Jyds>}%x>%HOyHHSc_!lUerY&g zi1}4Mn(H-iJ$(jvrK{fOxa8#>!+D*(p3VYZ>8khnE_qdRUb8P*PiF(Kbk(mym%NI` zGQH+pwVuuaUg_$G{4ROGQQ6cFMNK0%WS)rooY zH_+!H@6$D37;@MiG4FlfvUOD1*D_wwb&pR<>mG4kBsM?QPCbt!%Ip7WH3>i* z>-hRr)EECxnt%Oj465S0_;uk?UQbKBRNhYWt4K4y5J!z;&NnQMS3I_nE`m6w>-=Md z!}}rQdO5s~j{J-98lAm{%mlrBN3gnzeu(v7%6&U^*FEZ952NZ;a2?P4`5S39=#{SX zqD2n#9@op^bIJm|e))3NkY_-z(tFwQb|Ss9ptHjB$jz-+Nh!~-*EZ6{pjW!i*H)#H zU(g~^58u^{*PQ-q$SlySlIIuJiRQ{Lw2O5}&96$H_gAdiNM8fJ(sdrW#9@A6|A=}N zp2hUK>cllX$*ydN6ZW)poA;+U@W06~Xw#Jn&6AwC{a zz2-`Kp`Ic>4#$O+n*BE7V7h@+`#Bb6=9{3^QC;>nAc^V!+MW;;dnL3s?_Oquly{_C7CNG0t`4=Y9tC{bo5UXF1`89i)-zC!- zufE0?xJzk1iT8bOD`|o zyjOYUl`~#E4Gj@;~;8k-&dU<6(kXjsz?&kID+#O^k z@G2Xh8D7cs!tqx<=au`f9b^^oDx8#FUiq5$m&3fr@t1iI(`#GB4ze0}HDriaLcO5K z;`l3gFXJ`*g&kxK@FF+G>*coJ*1b=ldc0l5=S{|~+C*2t@pihd@9>aUAo}CRzh}rR%yAufzEX)CqPc;X5aS!(`$ZFJy{2OdChpeviGz6^}zAa2x&clmw#>pPaNDIGd6D$+Rl$V z;O1?x6pqZldNW-K`PDE!@jSVaiQ{eHQSv3ztA?*jJI7y7YC*4BMX!n#Os|fhm%M(W zihrJ}UKj`bKF)uY>|lD8KFH$eE!|94NqPxA@rw@U$@4Vp7vcb~oG6s1p79Di#CV0S z{eXS~yaHQUKH~mJi!^f_@whg)EB?4P%Ii~!7xEUo9O_lBsTbk^uV|VJy=wo%^vZkl z1Nu4esz08ccWv_&6$Pj?<5pvf!BCHi9XaycZ`dAXu*;&o;oDG zy*wu;(JMpwRgo26x4q#H=ob<%mAB)06U{gx4)%}vZ5Xf0M_7IZ_IyCM0Iw3R7w%v9 z5UXF&`$x<5i=3u6j&V9~g7^0=d6@AUy8i?ECGZLwwck!Q51<}Ds^gqs3FGzL zqz&{r;FYfXMg<+NzsERweq-&b?pwwyR9a8ohkhu0V|>5eT>VfTIil%!0-80Re{6V^ z@fz;iNj3m4->vby+{Q8J@c1#vpVwFM7~^%@+dIid;MH(jW_Y2$Sov`Lg}m|}=e*YK zB%6R&)$Qr!6;4sF5c2wbC)o_V$c)VJveT>hzg(|9JIM#YE0|_po(B`xIkiq;9I<{y zIIr0qcab{am0g}*y^`@ts279_kGIR8V0sPhxr=-Vys8ymc$}B&`3|2Gy?|FqC)N+; z-^O?aM(iRV0WZ%T@p^gq`2n>b3Tv+0NX85O#r7CGiOe1)g&+M-Y+;-eJ09|MW_ktg zVE2!{`t4ohW6-N0#~Z7|P0qW+IL8Mb=#C4WIt#pFl6giBWcW9-yMdSQzRboE^Bj3q9L4l1oXPci@f)%ScttYI z3-cU#6?A93!kpKI?|efdz^kw#vwC5k<9ZXP&sX5#Ct>an{++HZ=oPE?Xus?k7Dsdc zH{@H;%R4fOUd_Bt6vsLFJy{&7Sxm3GKkp_#126JGlDvn1`QV-I@dTKRy^vQ;AEsA;$8qDR z-J}6{)nxd&fv6AiD%#I@Azy!&14da}=pWBu^IuiJ#sA;wJX7H#iI0O254VW(KRk|( zQT3e4_1MUsn>4m>1NnXQ#sw#5HotJaD#o!IdCg~e-(q6}IUaaby_s2Fc>WA|`A=hd zRdQa#hwddO0I%$~Gs_F-m4H_)#e%0ZUKI=3@zAio`^X=Fmp{Y2@VXr2ReT2HRr4&1 zqRwn|R z7_UHY7RTF8Kg+lrc;WNr@ctB7|DszTywlwe;r&doJr;b#c;zi%ylVb@mN5!=6&ftR zGQ~@Mu5Os~3UOZbx142M0laEDWtLa?DK;-YfRCebeR(uK(U`vnO-5jjqVqH`5p3typPq1njd+c*vIMwDgVS62fXSZN;1y` z$3s5AQ+Y)>q~nF{5qbIUX8AOt<`d(ez{_*bLAxF%=3dUvOs}GsSbm*7c)M{m@QTdK zEHBSk#smAuk_Ps7J?B-kd%JNB@Tz(?v%GxAhSATpQJ^9lH;> z+xDoNb5*(Vy!`tZubfvHuN|d(jq8AyzdEye1qQ_P%KnA%3UXfc=02koczG5d9A4`A z+B$x}jSW!$0}~@PlC_y!{hbN@bL=R33;Xa`bXr2&y$Xv#`Ie7jY-D9 z@pj?IOt0pCo;3Q)RA{^&rslGydJTe|^3GxNU%0>6HuHVlV#SMfkpj}mFY5DBoqX47 zUmWMC`!K%H9$#R3xvi_dm8p%t67iz&VHxM8{y+M+58jyf(Z8);euuooc;fi@{EA{6 z0`KsmBy|G*=YzK{FWA-5%WZx+0&}o4>Q#9`yk1ehE#O`8Qj+!v|MS7Sx%2{FvFfQl zA2-TtCH$x4ruaBU_&S>C|3mNtd4-hqHSlj&uinvbgMGYTTIHLpu10ZN!n>a9g?i%o z@#wuXVaP6crThM0DzE&v8hNz>Y~RZ)j?K*r{RPO_3wh!CoEnK&7VJ@}@WTEgQ~e|I z;&fyEb~N!KY3AkVyh4;rJsTIwyjDx&iRON8GsXe&u};zp#GcbDI%2s@GbnJ>qk)vE8IvzmnAnw2Szd_kmqa>qJM`seIDGjbq_gO?gEZ z=9e9$IHF!fJDc)~#;W!p^GbAI>qCK8-a)#rbu_>E5G?ka(;wI#oPN)4e~cquZ-x6u z`5po9f@=;=ov`B71$fmTWL|i^m8@6v!lDSjp8|d^w#{5uQ7=z|``>p35&?cc1;Gb@ zX?|X@s;)k#J(^#e;6FJR#@E$q%GU2k|1TeRWRKE2-;ZwDZS9_;?t3`3=UmT*@1^rO z*WSOdO`z73i5gKLVo}I^80@={sjYk z@9UYJCodex=1JVHdo2DnejH-g{&oKkdd2D&+Am$h+N1xG{l>pRuL{1NsmXj{Gp~EZ zdQX&fR8d~nOT3V`@Ymt>qWPNZtPm$Qz6UTot}R)|^y*W!-?#yIRc&GUh5O_DMyl6$ zI9iV>@hW(a@#N= z@MG;QuDese;C(s%dVlr*c7J1g6!vR*dxZ6cH-cWczA)465%V7BC;aOfuXpnf7!#$u zN8Wh+nUQtKQBnE)S8WyJwWQ#HF-gk%=H`X|Vtg_05jX#R#%uP71IA?FRkH2>&%AF? z*1e*?MRU`W_h`R?=a+xc0pljn%jaYB_nFRnjAP(HeE%Eeb+g0^d7~aq*ZcZ4`ys@E z_82Q%I6o2D#PaKkl?RMlfEV^dxIgA+2HImBuh2%uYt)Aaj48ki`=RFMh5lkZFph|u z$9c`!alkNv7e2?cNq&I=AH4DW5ZX)E7I~GmWY?>a=^bM0+J-%PIPC@#zjduMyAGzL zxPJ^Ed6i}{UfvH_9LLT(oE{0h^4nyV7g@sAaUidf){Iv*=hb)d;q)lrRi0s9_1DMq z^0#HYit3nN!&V+ny92L+wwcwd;)Zx$!FG&SJ@WeSaM}ZSRb-e~-o$ubRUH^F^FyZB zjGc$mp1{kO;q_m&3a@~N@yhv#$8qoB)C;^SGt4VzH0yUD?_M4g?GpG; z(Zu-k+x5%Yd{T5yI0QS1`lWdvB(!h0744DVpGn@ooBT(D-+l0z;FaM2ZazX@_?*S? z$1ILfn@8Fh_QC&~n-?BGmVMI5>!|+$UO0~SeA>vX`~LthJa1Jc@#+D*iuiqD6H)ZR zhs_;FoR9W>)~Hv{L}aATGQkVachpI|yb^~*zh;6Lo<}bIyiu=SiO5KwWr7!;N6rp6 z@)F0q5*PW`Oz^_>E;!+8+{?K zlFJ#d;`&Bjzk~nRW|&vSMe%xxe(1OM;`&K1EUc|N{@|{I!Rx}xcQ)$P3wUKed2o2) z*bmpil)S{QGn_x-Dq05f0L4$T`JBkl?EXz|@As(tJPP%CtEzu8y+-fbKo`JycRZgK zOGf2~5B}E8`$C7;TdBN?yD(l?oV}601iUJCvGW}YrP!ZNcx9jMY@H0A=S%fIy7(OG zM7-U6rs`FC4byAXog3*w(5tRf{Ctj#5XU836Iq>pi==m_}eNI{ZswBTg9~zaytN5$<@ni}n5`G2s z%JH!IX+OX3@X%mASr1grsjS~l*K?$jJ;wms6OzRIigaT0_d%S$A9)1r1^sqm`^=t) zDXEG--%)=k<5l_{%dft796@^nuZ9fs%DFk7SHa>uaZug z~@yU~HbtL)Is@(SM>&#T;E zd0)eMja}T09u2(m4$CYr^PYHK<{^xizk%od%5L-+;ALi*muFr)ucDI}uLjPm?|>ue zvA`?;-puNicW*qe2F|NuFV}15k#rF7DmWsuyz0y2c?C{pdgbk7ysGXziVg-|zAl;N zRjcS#cnaec;=G0(*`4MCufm+n@+!Y8Uatt}Rs0K&<8$5V?|@gNcV>B&-51ZR@>Hf* zg!5YYTX%X~RIfgn<&}STJTKpAj92-uOs`$1^`O58UJV)MRj2T(=e)eXF)0tk?oL9@kPN63NugW=@<%Q?jkypVPj91Zqrq@}0PN63PFVZiw zyzo3b@(Oca^_+G7m7lw$syS0r2wo zPo`J%@CrBbik)fwiMe`CB}<`AY=5P9`Jjh+m=Jh_?G zt4`rn-Xnf}bo9RI-@!Zp-ZvfZpDdEZ;dMHmhxO)t5eM_W_AI7Xp~2#~^xFedP6542 zlIqnw=ZA2e5b`P;%6OGg#_L7kbt>=*Wtf**zr4d3FV7*2*OS2OG~kt!mn^@UM=!O0 zl@4dTsyMH^fY<53t0u#|)PAV)A$C0EYr*syx&3r{2JrF@$gEztZV%6Qr22e?oDocC z(N5F!3*>!l{VLk8<9db1jG#Wy%U8#)A8E4wK10_Th9BYc0NmdwuQMfH$Xm$auzrYi|%!XSicZAoAVlQ z`v`hgH1GFhIPW=sg8&>0*>~Cz3 zXul+z>9xGFkPZXA>XPY|q33wkzZUOzcy1vbF7ZO%!at|&v19ym6onn-7sSE#h{w4k zz}5o{TUmEhjgs+9*dpQ4q>myV<=xC^`A=b0uXVER<A$tE& zQ_>&rKPv2?<9zGU#pnC~2>4?FKX_hx@VyT4$6Pd#ehB#W?{oZn-T5E3!N=#+nr+#* zhSv8oI>B|vVg6i9@=MED{@Ud~+EL^uf%jn!Nc|B0#{3s?JB-DD*`kT`W7+=-cm79g z{Ks`QCda>H@kIIw;8(8a`g43c|ItnpSC6#Le^s|DmrkUg0)A;b_8beMiLcs09v&Nf zmG{b4lj!HN{}1T3f7K4+du{N|``LBfUB4Yp2*XyU7OkVfh2n)%;_`G4EE$@Ck*7w!LHclmGH_}_3Oo5w}I zE&e%~?w0lE_;&fP+Ch7!uKzi_{Xa69Mr8jh-T5D|@xSgeHa~1~{GE?Yrr!d-X#X7F z&VRIne&aT1gD=``SLXkfvnJE;0AI9!O?+Vof%(?^gmwO@?Pm0%$@F_U{+jrz9i$Pm z@n7iHjrl*Ielmqee>Lj=m|puAb`Y3vBR2Rd@4gL_=})r%n)s?6q~W{XT7S|1@h|k7 zaTDDO_@ezk=`R2MHuyPr#*cr8t+i0sA-b{`568^F7@Iy}Vciv1}$oMC?!;d(`_g#DoZ3Flf zpK$%pbcgS|!8-n)CH>j>um@}ZJFc8U4+VTP!tsZx_=%6dgdGe#ZWmhPS0g^(f5wC< z^f15|{l6x@Y6syc07c)tnaW%#XH8^)Q@=ZUW3R0Y7J*m$l2TOn*E7 zRXeCdz#;y$mDD&}#_#41KV*ZCaWi`}{rlc|i18=DuUW(6f21Bh+Cjf@TdRqW``>!^ zA;vj?Z@$mB0Bu;`d|z-*Hzf<6_zWUM~G#p{Kve z@s~f^%D6=K-zC1!2ESssl7I7B8Gi$Ok$;-_svS&&A{%_n8?!&x|Jf|#@3Q{A-RW;? z;v?VXi?fW&Wc^*@S7_p!xy=8StFsKh?0+A3{s(mNdH>h{!z|-+*?*V#K^uIvZV$~d zjG=&EoTmQ2)TaKbc{{E?%NPatBL6l0SM6Xv)!O*4j$3EUnL=~q@vr9iPql;i{@bnV zj~IUrWcjz_!zr|zJpTN%I{tMw{)||SKVkgSu!0|daKbCLPoYQ3{%hi^cF=z^-r9dL z{y&=e?{96=?tm|jfB&lb?`-_0e}nuj;mi!B=^&m|)W0vj3X+svYz{V1tkOXCBM*?@^QX z1$>cze^dQ;mVZGTeAJ%|V)(gLChaHd-vr;8{-rkcN7Ze`LX-BF_1DB#?V$dq6@GLl zet&SYn)#povq|#+zx-o9|FKlnKe7L42XS#5ve93}e=x&02TY|$1AfEJUUvMqT*Y@5 ze=@N=AeD%D+?B!GG?*KpeIY0h6yiF_*?2i9cJE*^37yme>|D5ep>F)tQ z@B`2P+p=BZ2Xyf{;o0?5>G87vF7Yd@+CPjx#B)1;&-|Y?b{ahq@awj6{fFu4FYKW3 zd>eA;|Co|#^bfNCn)u1$Uu%OecpuOFANun&dXnt_I<@^J&VOM?@!xx+b^Sr!CdY5J zcN#qz@J0S<;-eh}p5$xd+cfZXM?Zm)_3@HdYY{NUt4RnKh+NU6SB#F zRkwcseVU#j`|o$x{wr+!SMgh3HKh+NUUu)yP{~mt+?GG&fSG+xwo)yLa ziPyi=^xD6$gTQC&Lfv;-AFy z-_`ROIzsmUO?T^`NSSs0QRg4FePhsaSbtT%6YopL?uTdB|EhLS&p>;FjpOhGzQy%d zs%~R?KSK*;{ayO+vGKp*+x~I<{K04F9|1qq!1M1j&Gx6*L3e!)@d=$p&yn%N?(j_; z{Hm6G{Cf(^KkqZM=y@{!7Cn4n2Oa0zkPW_Cw};M}MgJ1T|ALP{H1SnCNTb#YA9fPw zzxWqMbeK)g2mJ7GzW%Kh>wi)`|L2)#(f$(PXI(d&UMSpX~f& zz70O=W}eR4-JBgx`mc&IMI;9N?Rucv-*ni5`Bk{PQ}* zUwO+sdZmnia+cQkI~l&uA%5$g^XWfj{8QZF7wO^;VfnxFv-$KI8UHkQ_@!3(3G#ne zcs{)r@atOf{O9 z`p*ky>%q^_>t+9kx${4)iEj?Y{Ckd$m+?os!;e_uC(wU;_&GWO@Ux%d{U66qRe#T9 zz4~Vk!~A=mmdXB~B{&`%l{}pz)AGoQVYMuYM{sZ@))wP2$3-If=bNpM~t$)a0V~vmfwmFjdKl1Yh zbc&pR7r4v6kd6MhZovGS;ZNJu$#@m~7wi9~>gkVmP)FR>PP6bIb`r;bXEXe>zgR#` zIsdu;spfyJmH#q6Cp`Ac1$3&M|1R+(R``(r>TyHKlo#l9!1o*MI(~AoUi?)%sK05| z|0lqo{lyFPHozChpMQ6UUtxnU+TWj8{D(~q(it-T<$CzS4myt8n=JAV{8z6VS$S`e zmIHpMn9o0G;;VKL-eZGLa{2u4In4j1Z@)+%0Q@o!AAgR~^IzCOV7{%;#5Xy9za=ly z2LZp~XFmVv5}0zU(DhDaZdxz5GKvh>KhA&DQNt z#I1(jk|K~5$=VbqX)ocG~2mQcp zktROwKlY24>GQJxF7f>~_?S25g}nasdWF6q`~RDs|7ZvOz-_4}KJGt!&?_`3`|lFp zw86*clA0HB|M$N_Ujlq_{^3Bp|FLHz!nj$z{|(wfKX6-NgOBZx6f^vB4I;MX6@ z+aJeIwfz;9Tht%$qohB({>0??a}Ifxz5@8Z!{YJn&cCA_^c%N+O?=$HUx!!etAJnd zcYge#=-(N3OmzRDWcUFa{V{Il#XSC(y-F9!@u%_YZ=A-z)&^h1{}LX5|EsiGjz7mw zHU42Md^!Fcf6f)J(#3N875|;;AJN1Y@xS&}`kEYnm-u9gMg9Y*i2vVs{NH+&z9GlI zrMvihZ16?=FXizMy-MGdaz1C9l%A0AJjHM)5yc{8c+>FW(9u zb`sCM{5$ji_MQuANY+1_>0iH`-DmoksA1Yzf5{5=xv+!4eCxNtNBvEXpWAC8eMi=x zX@xJfKXMuKfB2w#`pfZCt-q$j`a9-#3+cOnFY2#L{0b|4h>?ifKY0Al zT}YS7@o(!c{y{7K0bj(Q?w&+$`@f5-}7j=!JB|FVU2g&cp5pKAPTb@6$7 z8FTqUS|i8bC4SfnUylFfJpNM_(p7T&JGhH~#0Fo)pX29FT}W5U@#pxd#-ErL{ZE4W z+jsgxx(4t?{pI*}@lRHNJy!Ujzv%x)G5wc+wvfIj>ks$ujo!Zw@tux;d^Y%~Ke>Y8 zj|(rP>ty{oeyaKxS>a3V&*b=XzFbIa0bkT##s6geU$XJ1UlX5ZM{)5J$RkScMnkPW^%Z`I(bp*L}#(KWgHuc92A= zY0>^*Cz1c-c>Z@-L^lDxIQ~1#UH*rx@Iim|z7Z?R4>y*`*FWE>cm7qigZ`UqE&NY_ zpS7=xv0BEj)?5Fb3_oOr4lGb8%N=6W|v;=CyxJl{-uf^HZAbw`p5C-9J+{p z0QjQ*Df#cT{zWwL$(79iemxe^I=~n8&m}&YYVAMPEtBI9?X`%02>7D@Y2u?DNR_yk z#|B@mTP==VL_Y$2QU5gYRXa$+YlROx;rQFUis^s*xr^v0fG_G_7kA^Yd>eex{{PAF zbI)5uKLvb|{~SNn{4cV?H>CM5jz9deMf5Yk7x~Zeas1;n|NWZyCXM_`{!EM7IIH$bXKX zYW{~c@yT^O|DRq&w*$V&f0y_X8+^=LljDzGu!!yee3Ac}_-F_7UTm$_e}VpL-u4YH zqV<3;@?R5QwS)K`8+=?hWtKAihxDwby8vITf9oDU{!Lc@&<^6_)@y^W@?PStre6WR zxc|B)zG?^Y^KI}Wm*%qZ-M^Usql>EPH-PUwlAr(Z>iLg$5Er+88+@^D>)#BY{-c`i zmi5=f7j_VsZzERqFG2oI^HHqxfI( zgvIy|_RYJLuRr788(vXOzXSZdqj>x|zFqxQ?I4YS6+Y-M^5zESf4}#u=?{Qk-ksz3 z*YjW4L14Zude6dtz{k8XIsTH*s_Boi{+jq`M}a3H8~@e384|9hKLNgI|C;!!9pq7K zgO7FF9MAKQET#>z|Ig{^k9H6jw-Fot$;GVxkO@5g9T(HRa{M*%g&hRO?UUB=S9PPE z7SnyQ{+jrz9fbGT;H&+{9ZxN$zXE<`PoDqJ>*=rBL43c}@jv8$`HVbP|8HdamlwT8 z_X9rZ&GBE*!$&)ai`$UZ@ju{`={){r41dNyUZV#9Kj;u&*g;^v&9~8C<-OwC*C^=# z>#zHy$A6yLz`X$!#5>Bs$lh2h)P zf7K4+n-1}(fA%_U71e(epMP594!^=7{=3({LEFgqZ@R+|>f%pk`Ty=`Z_su!e#jku ztrb4BKO8rh9Diu|4cZ>?#rU7&+a3R)9gI6}!#4P8-OSqZ2JHa&b-6tMH1SnCh@Wrs z{2~0Fnbj{=2bbLFHCn*^H$?xtTW|gs?I130ORefJ?4-7vvG>18JA?m~1G)dp-NoPg zRMP%0T7BU_J1^#U?05J6p5B`PTW0uh# zGJe1K`(F$Md=nyv>+kUSXQ~~<57^-2{3q_eW%e@KOU56_@TK)9K0+Ju?be_8HdyCh zU{`$p4ar(g`^xx(;_(j!{}bV>cF>=ojsL!5;*Wop^jkr5W&Gpf@sCY{ui8QUS{r=P zZl<#OKkCD^bR^)5_IDz~x66NF2Z8xEqKnV>pZU>RdN$yf4CeL6B|Zrxi$9!If;_H# zk&pkTG5^VDYw5XwUwElEt}Y4x;cJQNkFcZopX^Uo?VHx$D1H&(hn|ne7vmqmPt^X@ zI-U#{Kab(d{^LIY|1Yxtrz-JJr~gUtFOcz1Z!Uar81Sp+@%GQ3KRD}?UPedgf5rU| zHJ?8y?4XW(YbNdgmHfl+f&Rs^|NQf2$-gA}Un1iVX)gVf`+up7|8(=>m(JnsU()|F zz*k>FfA~kD_TR(~H;^CDt3T##jrHdrvj5zUz)xHIgY1X+n`QC-4}G_U9Mu|p#OrTp zlk2Y&jz3g8oHmKvo6LWPUp^ropH^Q(dIG)}f3;!w+56c#Q*hts1Kv3P@bb@-)j!XD z*7$|R@%=x|xt8>n@jEkoQGWs7l<;xwGwkI#Rc;%@y->3WCw z;QvtBf3G|LLk{ErIN%SL@%y;LuXTujAK*iiZ+!K4hwpJ1|LK5#wv0c-9e&uM|Fq`> z@@K#o>(9oz!}mJ$pPoB`6v_Dic85av{HJat7t8pU zxXVAEL;NDhzrO*#c=_GMzsMo}P{9AYj6cd9zTXNT#!OZ+(ul}3-{u6Bh|KBqHh3@?KSmA^J zMQ_I+|IB)$zi}Ll{|dYC@!xzl{6(sHJ6c{9~-7{wG=cQ|$1sCEZ~CuT;Jl z#h)bOKdOV#HpBobR&7{Bi zWF!7m8UKaM>pxA_U&RMK64l>i`Uf@jH=kwFF|A9vR%Vqt!A%Wjq`Tuky{+%-ZmgbGWs#~=E-zDp> z;)5Pe^p9xjZ_aG={~p=@ZJGD~UfF*Y-=Y8HX}$b2pK0{JLiWEo^ABv}{0oO6(fHpF z_!(P&k)Z#7Q1-vRdE=jG{PD1izpJ_ML2(#?igkpV0 z|Erk)UjY7O8UHeO{+C+eC-DDEz`rR0eyaYPR`|02^O*k|0RI*lzXiMhYO48PVTGT- z|4o2DB>{e_{s*k^W&clLD*~4R{!|&il{^1~n)u{drvDVJ_Hz8wD`kAL-a z@}TU0XLtVlt?(20Kkc>Y zW$^e@iGK$0zmoBP$t-@f{(K|j|CV|D zh>U-rx$q(4Q2*8I??-$@>HV<&Bzq5k{?xSg@%10RmZ<%!b}*l6I~Z&nhad25zvx!R zKbG|fxhJ=xb7lMrcld!$*7z0P`1+Uii%AE-{F@o!*WWH>>mNn?1KNrFSM6{&N$vP# z^^fhL)}L|j&8EeGFP^`CySwp6zRmNWbNcc1AFr|c)Bn}oWFL$_vLEE@pN?escK!=H z=s4dNX|6vuIsWQ}y9qRT;#crfo&P9$&_aL6Kk?k2*O~t#Lc7VYfM0jFGyjDh#ecsQ zKI|Lr9>4x(>C)WAv{<4-DBupyV{Z zy6eSXwSxvqt>O>PsNeJcWe+jn{-@&A(;dEPrN4~-CX2s0Y7aR?#_#P8zrqS1oK)NY z7Qlxozs48GPc{DoR`|029PtYJ9f2t~Qt<-Mf4CVibosXDU)4CG13@c%*a`hN-(vdD z?DQRhDYwS?hh+>uRsTa)_zC=aPabkse|_(MM-G+o z*SN#?I>q1c9XVXaU+WG(-v-~4%lbca32Xm5*MCpC$oTK+;iDZ9H~x#y24CDa?p=o8 zdh_=rCk1?AMtNjFRU z`0)qgt9Fn_sSQ5H&0Nak|K0cGC>ej9yZBew;ET8|ID zug0we;@`s(-&y>FHu$37TF(6U9r^?D%J{W<`U^XX|Fu^5u&?OQ)&4(h zgYW-O{P=e)=nq4##+Ro5svR^CvBH>clvw(W8MFVedq-O6atzkdq&svV@^v%wd6yOQ}IIO_+JC*!Yor@!9{A4nEYWBF%t z{88ZlfE4i24*HGTQX711e`FQ&f99|s$iM{nskT2;7oQUzGW-W}bQUDD~=Mm#nz;9T=kALA|FgoLZ)ed)ucr@|NwJiUZt|Z3kQU6zR z{7y~o|Cez5mki&liI05yt|7)5fM1*@{CpdH^|?J+U0WFE0>1ek_x~t8|5ZEaPsAa9 z?!FerUuAr_8Hi5&li_4R6;%wtez_0m0@juo1Un_iwzZkczXZ}xX-P-sk z;EU%kOxDw1*irm1vcbo3o5}H8v~6u%4fx{u6PoyFM}a4P8+j1yvV;=uo^z=tNh>P2R4Sx92`121{SGP7wqyB&53}3Z_ z_(2=|is9VG0Fg6T>q=-ziJ0%@Y&#t_= zMb>|sp8l#G#1Grxi}-)Y+yB6}hAHFU-%@M*iFObdx1n3C+rK()nQ>BEV=Ca+Z1cu& zi6*{k2l2@&XZX2ywKb;8_*r`EFOuPxPO-)pdHXTbf7<-E#%+Kv#y{8T;R`#$arR4* zL;q(iZfn4jk4F79@ss)Qx4{>A^9l2RX18`mx$OUBJ^zIr#s5+peB^C%{M;Vxj5}oi zHSy7o0#7Pz@YVVEzIpA8I{`oR1t0%3!FM+Q9w@iYKjdwG%Jd&Gxt(#h?Ef8l`lB7y z|Byrfx8B^&xJUNC3BEJ`Yi;nc-I$;A{CljOaUbA|_BTt1glfi8L*|y!S z=mJ=OR=$(3e|t!8{aG^oi#i*ujw-}r>)+rr9RJ|IpXu=i&4%@V;`sly?AZ5H9sdMu zp8p|uhnfDlPqs5EKz~vHHT4&E&=I~3+r+;~`>Sea+z~rAB>cX$|6<&< zg~$KvcE&^Cf9V!p|1|v%N=Ae6{_JKDE8^7~qTc*91Rt{;76Qf4>br zt{XPDGXJ;EZ*Tk;@Wt~7?$R57qaDP>ZG{a!>Sk_Z_%j!@H=Y3e@@+i-HSy67;^H=7 zg%3Na^`Gv4i9Q4Cf5rXZi`~_KVl)0%<2JOqz44?R|0e!Bi+|9{e>ncexS89T{w+Rk zZv^D{Pj?spS{r;dZd-S@H=YLk`t3aan)s?6jDOe$AN?nV%>SirIvCH${@?1(fA1QL z`X}dKJ;Og_Vh3Xm;EVCcZ45uv@rTa}AL5U?nH+!CO&yH6vi=;uvHwfF{s`@$?zkgNf|1R-sb@9Jp z{%7s(WGs~Nr@He$Y=f`XpB4?Bj75Mi>Q57VXZ0sygD>L0oB5yn&(6kT+5ZRJ`5&=q zf2#jWujy>OCi~w6-CWaLGv{ez`mR3WxYvXLm7bWc(g_ z_a9gNK>q_)_^^{W{u#^iZ)QUm11|Y!y#A+}_5Z1kKZCmX-!uGa**V5q8GnvDe2>%o zYn@}jB@d19=lFKxuVng@_blq4tUnLfmXaI;mOMA=e;liSsp{|1#5aFn`Y$=Ds{u=H z8}Z+9r@z+EaShx{7)I*D*qD1pRVd^)XDmv z?k@g5hyJf9=w^H*`+tnP`s264m;L{lxBrrE#wUQEeY%&;+Ye&+spfyF6@G&J+i_(# z<5Ssxj-P7$O&ffi|0E6E|6SdT&jDYIfAaP87j}3Z!A*q~zNEj&@n?S3%?Ja&SbxFs zQ`J9Ug%A4U@h9>fx4WD1g{;4(|Ee9d7qr1g-ORmA|CxU~%J@>&|2TL0*IMCA`jdUU z{$6^Nu~pWeVFv@xw;mh(!spofH!_a5zbm^N^|Jn&_`;5Y@3p~KbsI6UyRl2wUlU)ogEV|L z_^6xtEAzkRuI|Ryvi^T?r@!9@U+DH5!yoc!cjFsbe@%R02OZ~I(+VHD zSa)ML;8$b*ar{)X)DD$7L?qU20_+tFGinV{c@u#qZzQul=JP#Kmoq4Zc{n(vsniY3DWe1HM>)tcfq|ATZzhHStZ3KeLP1H~{$K z_{SxFsSUo`ZpL-<8U*H_#r&rxzG??$Fm3Rw=CSdI*^23Z>p#5)1$+_z-7RD7z%KvL z4&vfAXoD}}#@AmByT)rA0{9~Sn)t#F0`qOi3Lo|n?f-r@{yPEs|10JGpFe*!)%IUe zVNrh)^#9W)d5xCfzo`G3{wIrnt(E_PkNt+3&Ens?T`wa`#{WPs{%A*$pO{wjUkUtQ zk<-h_27HnKn)u25_t>nz!@6a*X8tdIy_eAj@J0R)bXWhpHuxfM+c5mw-t1+x1$>eJ zn)t$w5&)kjzRB^otmtL51AI~cT;dnm;Hz<)yQ-JbUXH&ezG??$D7C>Cx*f{e|CrBu z86H{xU-a@{*g;^vt+2sYd9T>j%jhiouZgePK^j3Dd>l8J?O6WpDCun+CgXec@*nLW zE^b3s_|cu}`SEXihClS5y^X^GzjiO5|Ix%3b`Y3vE3E1d?1S|mzc%;k-o_DtpSLd_ zKh^qQYvq4}@!yQay^S1M|Nidu_pG<>f7H0;w(etelkxN1;rn#)JF@s^eb~o;{S8~jQ+C!n)s?6#E;nEBX6@a^MAx0{f#`?|GDn` z582dTao?On8UE6{`WpiPU$j3>d|?M2=iB@Z7WEJIQR{#1J^hV=fG_Gl$4|BX7g^ya zX#ZJ{^*4@@^{;ZLziESy?bbYu>Azxre`Ao0KTi)I?I`k-fDL~AyYcxyYe9cwFyM>! zuZgePK^{RHe3AbTvHCx5aew1?vj6k-{6{;8i`%d!KJGtmZ-3)>8UI;#_}+~c`JW*F zR^;RwC(8KGxx>$Qh@W**u2CT4Kkp9T=MaC!q+H`<8GnI0{30uS2zp6FeEu&fXhSyx zzPSFSJ6nHPzntBF{McxsP(lvCE0!}W*ypO9*#F>1t4VO*F3`q_+tL$MLm4g4(e~(;H&y)y*AJoF8lwI9=>V^ z@dFO=bK4$m6w3H7yTcFK;0xXU!|HGSV@Dfj1HRwr&F0^C>){JK=s4eoZ17dxvi2Qq zoFn`HtscH=2WfVCC!4JM zpPaS4{&i>LkE+v-HO>e8(nEOsf6~JjcF=LY_1NI6^OiHtKGwJZ@Wu5fn)s?6q~W!} z7xP9vnE%VZZbLrM<5P!ubgN(n+_IImq~jjK9wv ze#i!2Z8!Z+F(};fsPX<6zvklV9=5d3< zC6A5x2i)QNZSb+(ntgcvJ(bcsWqiZk{YSz!__+QK<2CMVO5u|4#^--&;;VMhUc?4p z_}`cLKl{Iw-Xr@@-T7an`}{FZc*J~4@0I=6#82kGS#6#F!v95V{CV42N-JdlHJ`tR zc2IZR25tNo-|NrxANKqq^g$W_R(JY)I$F0sRky6y4xtap`fK8=cF_NP8+_q^F89BE z3;M9^|LyMlFSWr}d1rNNK_8L**Th%tp#K%R_W%-B;rsrpng4kV z|F&yd&_`wc%iZZ;tLr}(Y{aA%^fB3gP5fm3M|9i&0Pg?V7WBWe|986cKYy{c{wnVg zAGM%Q$o^~Mt9CH|iagfsAKRZfko$jZOZt@T|K0BV57^+Vyhohek_Ke|HStwD=zq`# zU-*AC^S|XcE$K|z|9jo}Pi&rlDR>{l@K@|@NuQDZ*Tffg&~d)?TH(V!>iLh`erZW( z0e-{J{QhekKh^Ue`BwNa|A+dMYS#Y_8`O%_5j( z)&HOszU==X7XR5#w4(E6{~vIfe^&Ru1ANRIljDz@--pQ`@(R`|02gL(Vg*NVO%`>%Qb!DRmXt?(20f7`FEXi)Z_sTIDI ze`Y@Of7vxz^d-O-_g{S2UH(uvgjgNe@%R}qsULfR^y)p`Y&6Z zMXP1~Iex18*V_1x^XBI7nf|v8%%-mae(i6(|9ebNf3(xYe;a%;Z+kq$A9GALeI4+{ z{I4dyu%i%&*x=**kIC_O49cc&0KS<2*2G6U3Opf)T8uwo=fHsY^B-FZvgwDz!W;{RWF@z1yNAMkyju=QuicLh9uYMQ+M zyp`Vbk5oHoFLb~4@dxIO$^9R5bv6xw|04f1{YN{9i(8+K{~~Yx!1Uj7Z8m)e@J0S< z;tM+n%(q2W_^?k^ZhZbNDa)oy0AJ)E$H)3J5WZtV-0=K+<$iYlUA2QW{8spK{uS{2 zo1aaW%K7)CyZo!L!N<6n9DmGn*>ss4e@%R}gMQ;SV1qB>b`p>Of^526j=v_pu!F#S z8??fQeF_K0$A8-5Y`Q{@KgY-Q7so{HCRl%=+TrjdWQ8xs|77O>va4Ftm2&(8?&2S@ z!N<6n9DnxJt?4Q`{+jq`2mKaXoAoCmZl^H+M_kvMu9oAki7)I3VD^jG>ii?@;@KO& z{$|v~)^v>=e~xe0{#83j!(-#W=zsYA$Cj;XP2ZE_uX+D5VF!Wv)@Oq+;>Pd4HhWEL zx=xP2Ccdzv;1^lp!@mA~ivAzArti!8EBHslcM|pgsvV?JniSs?yZ$+Q7w>;xV)GB? zlbh*#9iT2;>SgOszG)qQ{TqBO5x%g4z&6`hwnO_@zZZCWGu?wUz4Ye)g&l=J#0DRAGdcdUyW7wYW&Jhr(T)O7 zi0=B6Gr9ivwV@x$`fK7R)8Au-4`j1{iLXCPD%;SH0bh*&6#S#%I|9+EL(1zzQFB7W3~zng7d< zY)7{OzL4*HGTfEB(R|FfC@x8=2` z-^=mm_^HM}Xoa7k{m&ZMp8g=mU(^3&@ekSHi}wFV-v0mIp8h1qKhItK!#4OBHh`oj)?X7}wS)Mii*@}+{mnly{kQ$MJ>4hkKfs;- z`8N1Mw{sZ&jQQ>9FS7oc_`;5Goc-dn!B=(L`doYZtE|5!zG??)1Z?WB(4Vh=TlQ&t zx?k2`bNv_EL0sJW9r{0dZ+lAGN#j3F{AB)@+TaV`=kogZd0 z|Hs~Yz&le^|Nnch0--*khaNy6^w2L&Bkc)2^iYj}c#&c#LI9Ca#ES|B5sd{5NC`bs zFHHhcLXQFxdXN_SMHDXmzsZ?To;&B+**Uw!FTVai9$$Fw+3e1|_j6`uXJ%)2iz@%= zH_bEr6*vEW|6iCt(t+-MzWnr-S^Pmi(cAF{AWfV%qSmQ}tiv z^XWff$-l4L4wV1&m8K2PHdTLN{{3`t;;=FQ_K)lKwe_bBN2cm8%%7)&?4y?ap}(^u zo&Q~@PaB?Ns{X5fKKZaY){Kba#sJZ-A}!u6FR260|8TzHh1~r6@BcbUraw;y`A_)e z?~XtCyzRa#&p#Y<^Y1_Zda^8ko(}SlF5=VvyE|e2rMR0af0u7Nypx;%_^|r^>nW6f z*zs4&FMs#^Gxt-zPL^ziq}jZa2KQn}5Ij z3G?r#gMz1Q%`gA%KCJ!kEdQh7S?6}gUr(v>zrO7K%RHSv#*zN@uTWi{?lY(ZQXBqg zIO66%dAz#+zA?|=`}t>{4)Tv1^2hIA+AkIOe^G%|ZdlD($35}r8dT3<+vBS_3!E_2 zUE=1Pe1iKPw5t!fs%xDa-R-V%o6O$!(zUcb;coAyGr1-8mta#jt>!E^W&iZ`w0}-* zZ>e-)-DNesf2G@~z4)T6!sxe2_xBfNIZw7kJYSUMJVh0+FUo>vftOcs*6Ehh zZ>aZXC|mEW&@0bhaewNT<7W<7v0JpAf4bWdaOQWnSB|3c3R`ry zujlTK{R`8moL1cJ-Ez+Vy?Xb`J)ZocbRC6FHCFblUq`yzyY(o!AU$^g>)gL`k0){X zuDyB)yP3N^GlggL3gU0O+q*odSFosGUsRlsFLat~x_A3iPkXmN?e2E>VCawbXSOXV zoy0e&9fNhY@@{|PYCCj+ooo8)p6y{hy}D<-+THD*Jd{r9YKjM}v(@UJ?O|MP2L~+T zl~?uai?WE9Q;SlY=my{y?#46lLv+60_5)^hoLAjS_Fk`c;YW8KVb3Rq>+XL=Y${*b z`>Xl9+c9(h#kXFzcf?%Xz;^#C&D%?_>vsRm;{JEnDUQ?oy|;z_5Bi{7eNh%j;Q6Ai zTgaF5d{N~F`Enj`eo>b5fb)y8;OUn4ZhPW>dZc%qI{I65o$7Ay)`8@?)c(VExA(3W zM=sr~FG*!-|L*_m|GHan{p$XbTa>O}-R)l2uWgoJ*0Viy63h15LtGbOZV`V(E(U{fnD+shZt#lh;joKxG~L$rU}tgxy#&x)&hw$JhIb~lCY`E{@R zxL$1OZtwCmucG!Dwz$%&eV*?A?Q7KaUu{Rb42$~yMU@-m3z7OfXHx$#{{>mjQ&${c zlm$<>989fWv*z^rmAdfYUjGWVyMMQwI1_3fSlRCOS$d_a`{Rs%-R)EBS8Egh`h|Fv z)b;&~vN!|qjH>a@7iBq5T9uzK%5t7Bs-J;;!Slvf*79r*E3>TS*&f!r+ueh^<#cL$ z_#bzBx17grr1lWD5?RZ$zgkz@6Sq?P2>ZarYkTq(FIl_C(^BIX*h+W12hW4<_AXDn zNj$K{%hvAkly0MZVJm7oIAHIo#)i7%!CH;3kFf1aVnf~ejpoze@6~tM;Y(vfnJGN! zG98z5w|B>b(5>|h9d~|j{~7Znso&84&SkNo1>OBychG*Y)34ZOxXTk?gT{lfxhuCB z?(!i0qt9HecS$_a-9D9Pd^0+(?r!h$6jnLB#}7NpRo(q(@I*IP`@7q_Jmt-4f7sUT z3v2yscb9?u>z+rLe?Q;Nd;FE!-Fy6%>uz^5f^N9J|IFRqEkCJisQkb>dm6@HYCEp$ zu-`c>JKX&*`_5-4Y<75dcz0!IJ0d&W{clg#-}K1r@ZPR{(Y5<1`z>X2%3kz?>~QzL ztB<1poMW=Xz5l|9q|P_wp`M3@jaTN!vHz*^gOdw;J~*D+u<1p1`BERQS{frHNaGvPVif8zB=UJDhF(95vAEb>%nK&;}uq)WWe?i`jiyUoCmHnw7JXEW;{6mp!!sV`pifle+|aEMJv?5 z@~&TA-~EKcd_w*Xs@JXC$&TDfwsbGq$p+c%{bZ|kvdMeMChjAfd5COB+2X_G$C_j# ze zs-NiZcW|D4aClqy{VM%`>(cvG@P32&-ARS1{X<86U#q|W=lmn=`Ixc|o8IU?|6Aq9 zjn`0j;%o9#JzgiR*c?8}jaPFGH4lFoiPmCBhF^5`iEcpgs=MoQx_yD>Su~Cs8d_WHKiALnA73Rm_W!*X zB=`S%JZ@#cduVb$A)d?jX$`;Z@-#NodHUl)#$y`~7DDp0eo5ogD-LZ9zvA-5HyR92 zNyyWEZ%A*L^~>34K199O%6XgWlcU}<<-Du>|0w&uvL7k?fwG?{`b0*C*!@k_xKIC+6ru*HnFVC6M)@zl2s^ULas&`+b@DAPAfZgWG^@h6XV_hb! zQ(MpT{zbgI-QB-?J?P!PewOY(On0|;)4{qZ*wmlb>)og5wz=K?abF{+w&T79>;tQf zc=8mJBc42!?sgBJ``ztbp2}mS8*FOL5pN!~9UQQ8EwzCsPd&bYCr`V(-GgWDr74}t zwTegC`Z61M^0d`<=$t+v-@6Yp{Z=Z^rEgIAfzAEJyF8!hZuh*u<8JpV&$HZSxWD6W zU(h`-+}DA{{fpJz`w-px7fEGt|6)zo@7}*yTivHvN7;3iT~FCT-M@Hjf!&8sTXomr z`fBvw%dYMIS6`j}n>D%XaQDBq`Y*o5uEX8`rmO$zDd)EvNeByZ*QIdEjyH`^&{Ayzehpy4&3o>XwhG>m?p^xA(4J?0Qjr%KQFu zMQz7@W!Qt?^1i;uC%muksqXeEJZ*J-A9c5PdGOo?Z1ElM>w86Q$8{9;^l$FoOK0p@ zx(>poHr?I5o;uD~ln$vQY28%L-M-!wp6bT5-l^zrpSoTmelT4h&r|!OztK+9{%v=A z_xd%PO8?v=D1F!M{R>+^aXhzS)9d!1-P>;NgPC(u|M{T^*+-RKPW6LVQg$_E*Hl)` zGdOCz$hm_0e7w^u{75GwtFBSOzqXG-5lS;m$-)}3a`<+#G-*cPZz-d}<(WdX(%LLejh;nkv(8B8t?HRln+jaeNW1y=XOHQ%z3(=+~+t| zA!mP`nM%OKneRS)=*)&JsO`O{c z^{kw)>&bo2k$6K^KC`drx|ldKLeBJ`bWZMb&Vq%r`&?;vu$^6RB`r?456bU*?%?j5 za^`c~sRZA())S1A`<&C}Bkufr7A8G+6zW;NK-ZJ|oGUsitMAf!w3CoCb)nA5ea@Ma zatiCw&O*)(CoOU8L*Dea}pNHllpignIr~sOQMV zIw$uzQYtst^0}*!v&}fU&p9U!6mkmn+)cb}%IhzN`%BS>tw5O1>sW>N#6eswc4}SXK!E){;SlvYbUd2|25bllu(Q8U4;+<9?8kGjqMJC-*sL zTgWMm`@uraNyf>2&RIM_rl&OShX^?@hZz2nS_4- zB|Q%l>RGy3FAv-YKWyf}VC6G;9+d|?Kgpk$yq=X$kS~02HUe@+kPx$`dGB$T)4eZKw3ScvyUV{){Tn_%@F#Em z8lTehc5P*Wh5FuJP``g<>W5t4T`)Z5z9G`#Hu)F5d~%=fU&sV2pY;pqJnO%r^U9r} zKTmjLFYZJA_Otb--XBE%EybCr6EA$kee5F2C!zA2xX@eQ`gdqM^o%bi)AI(Qo=wFE z?&58_zSs_%+F`JI-b8v@+fV2R4)~u}&xTOX@sN6QeZdbqYS9z-VOx*raWU2R2dKU~ zw)$SUozkoQlgclAa0Rs}pSiE;^}$r%Zxrg8|Eqr9@jG;%b4GUbFQ0hN2--UwZ>sON zQ2Dg#*-%`uJBbfI(&u(Gt=D7zJM@&cpErfnlk3Yll0rSlZq?&r((~4UdV*(AdP>{R zn}vFg-o?&a#UI?D=qa7|epIMu<7xf+=G>?2%ei8Edh6M)(t0*<^73Q4Zr&!W z@9o!h&g{MZoaLSTubbeM>iPG8de%^%Lh1?K!70`AcA=h=`0l34sA}OH+u2{we!q^5 zXH4zVo!#~`ZeL%=zw2olpFl60g`T`Vn#$)LA@$_?a;}}c$1!Yb@ddiSH%1n zzSjvK=?ArlyOi^8Vcfw7p3lpPxJ$1`cM9V^!M>l$eelDM@9JNVz}ebC|1PAdeBLGG z?5KGqaFieNZ$Bfu`E$}&ijdk2YnlgZ^xDrE^R%U=cmA0FYODD$KEH%{Ea^NL^i1p| z)AR0-dUAbdC_;ZFEqbCJ;rwyDslMMUtnbhn-$#Xy^n+UHDIIs*Bh)j=<^x9XU04HP zJnLURgX(#ouw8IUAPyT;P=ULmm|B*%;EV!|}&;Zq8ZRW3YN2A=I`{08uCuQX`EquP? zcp+!*XWu`$;kPpM5^L#yGhTKG@<3 zGCig1X-^VzW}nsdw4Z#MkhAiUpVrbFPfDaJPOR#dLjtMcAL8V4U3NoUxXS)3(k(cMYYp!f-bSdppmccQ3!7>&rQ% z&%aCCrJo7oo_bN|;y&k0MP=7bX@CCbLe3837j+whl0+o+}@Hn|R^3 zJ|Q3Zq;9A6fcTyt!*MD{>FejE?NUXk=S(-@P=|qqkK(n#;|=@BNCocZjc;p!-Ph5&wQZ>U)@@cX_X`b&l5SkyOto0_q99 z!s>~2l|k1hKk0Hx)`MYvaun-*+4|)1fa{Zkay}K1v!==?xS?;R>K$j(I%?i7)t{l` z$A_t0NA}g9lbWk{Vnfz;sk)Yae-l2|35>TXpM=V9;#qI*_71e2vc*}>u%>$Sv`|m< z6Z2cpItKX2p<~c9`WfjGzi&u;k77{HX999o|4sFta~3c0*3Xv{CppEM^n6yxiSn3z zSGD)79>p&8<}{Vhpn5(hJ{GHb;EPJINmXE z{*ySZ?Gm`UXVv`&ADmIeCFSguPdA-LTfbjyiu(%`_oA&|m->Ko>_NK!$9-()wyE9^ z5M$4`;`um!->_DucC4r@(tDBgbjI8besS+GPVOT;SlfB<^4YkS%86+`?Mpq*8S80H z>-(^-u>BF~3LkMtK1r2d{RZ#yS^NQQ56by6aazkKxS$t&a3&Pje~Yuj^aKaD;2JUL zIWbN;h2@OjM8})@A+J*TtlR3**vAy_q#9qshn~o1>_*Bjb2C|fzHLL?alDE1HR80! z9bCv4J~+pf9$`77bviG6f0uu6_jRG37^f#bBVFNx6Zzz>qx>58c^$$! zIgL65*6UI6Q{wB4P(KttIIAyHJ{gr?>;(hoj;Da6co&P)oIHl`;9}?cz=Id0s4?ft2aGk2{zIORJI^PY1aqm2; z$2~vnANS4&gN^$I!nnu2qH}Q{I>NSuahI-7epndy+^jlhopFN?w(@sb`Lx|fC|^P8 zEG~>Yf1mg0S9Nai!4CTU-ggM&9-T$!;y(EL_EMRi();fh3OUCaC-?h&>W`}M{h!iy zsTs0-^76_#Yp==lw3W|}DxXV)ET56t^m4#CrR7r^_ltyauQ4v}bI#7bGCig3(%*z} z&&;9gmyPH?=Nwo42fiIXuAA2TM=#U)ri5{y>3bcs`*TXa-y!YST`Y`ym2q(&I>Bay z?O79_sc>(`8wZ@g)=JD z)7CB(|4e!=Bh<70E<5jO{(7cAmFX$H9^ENymqwyG7xxh#*wme}@+s{vT_)sgGfwV< z4>lrvK2G|6n|}z)XKOxP&#`%RAAGR!$7Fii%4b!T&t*fF&m`jpAFQ-|O5bnuct}0D zzTksR4@l2QhvKrSP)~k6D$eg8cj@&=T92*})}zD%Iv4k$BkcHj{^c{G-Hpdlj$>-) zzw7Q2ai*QvomTGN=PK^0x06Vr$vDT^^P%Yj_3v8ZxY8$df32=8wu{Fd>VTH8eC8L{ z^(-u?`^X=*JfQMfeUsv{jj()1-q&@GFXYeJ5nhj^+==0r+53@5nf9?fi&({%Cn&+73k$jGQD9gp4~c2jGLv4Jhst*HT816!XO_}^qzBs?ke;P!)PC+I)U)!DuIHqMGt;K@!Od;Z z{?fI=dQ^$)`f;CgG%uIccWK<83mJD_4mhXtxQx@*uWMdU>8v7*JD*>gVC9u_O2_Zg z_VYSn+{?@8apykgY;Pj#*Gc2v7RJ53oX(kAR`)q)VnA_^-#~F+HDug77EWp0rTwK_ zg>f%^P1le6T+g;;o&oKWw0vGKA2&CkmZw?SMb4>-}2|=>ysxNs@xdL=Q~tBt?Sa`D^r~7 ztCEF}^}om`r}9hO=e<7J$)OBEG(b=y%7z?4gI*y$7J^nrRDQRVfoCj zqSqVlbIwV1e~NF1kME)I`fhp-JTmx->fbH-Hsk#A5Nw0!x@wOmRKA=$r`n~Uoc|VH-@%1^;e*q; zoAi)!27Qh%;vOLR{$^wiy*zRs{M_O>zU*51^VfKekH6={^t|DFq^DzxdyR2&pYu(e zs=s%E{|-)mpVajH=Ir!bkM()O?3%is+~*uNy?OhYe3HtIiE|F(v_5|{wjpsQHzErk z&-Ij^rhKC6Ii%cEDqnU2MfLnU=d?YiKc|or&*eLKu3SC056=JgbNU~-dqP3gBD zCEHfK)knO!>#F?>%J~U#TE|D=f`0H3_n@4;;^rnMeGYnV_W()U)9aFs;N(8GbBp$K z+|YjVcFFYo<~&r7tnJbSYtXG%R62_JDEZBah? z$Hl(~n%bqW zx(CFad5gB|JNgUp&FMWS@cS7&;T`9iY6o*S>-`XnH>KmahHxA=vVmUTx!>m%{?XIZ zV_%b=vk3LXIHvVY(i1+iDjW37C_P8n^@Z1WTR&u0Dk$Q9h@-CSydQ#m!uCUOys5u5 z8*y6e5xAfqeAJ_c>X%75gO<;mgyplP`g7pqKDNWAPWGQ)3d(u2kh8e4UXQpBKG>F8 z#|59;pq#e|ITK&kIl0d{#{MYNQ+ogCK_O?8adMw?M(&bvO54xB2ssPi(Dmd#=gbM$ zgGu$gO~@Hf>73l>oZ}bC^ptWwB;;%`PVRHgq%iJM&bp8@|4m&_?sLw}jf2(mb|GhM z6P=U$oO9$787IH~@_9w1`>>Fc-#4r?Zlnh*y>BRu`(K5eqnqk_avyxK&ALoaDd$~` zv$>PbgM6c#>D#%F{iGJxBWc|K&Nxl^j4RH`v*~?a@J;*2@0RIld#)Vm-y`JAZLaId zeWWL~&{G=sdxe~lEp$%qbG}jG^ITF+_w|hKKl^)MYmAfooUAo=qVqZ|AwsFrBRM`Yz@Cn~*cJCB;2@9JNdE zIUoF{h12wX*a?T)v%0cKul&{SU-tLDPAX0uH+rM~Uc}K`=sBtA=41<-c|SLW+shUt`kTdt=FTL3lF}ZCJKlGU<4pDaaiN|g+v}X%M?SDE zp`Nz(v!9-jleeF3#*Oq~2i1O7H>7rc17Y0xcO1qty1w9pP0u&j_1;el^-S)db8#Ph zu<`r->pRx5R9Dc~$C%bH9qsBl?Cfn_zr^21!k-fapVXorN!!n7g?biu)b->(=c_$1 zSUn3N_2l|;PMbeRcL!G^KE5`s4|&erSMq%XKCb7!jf?+|xJ$>yZDHICJL_@hKIce0 z=pXk!r{#K7-iX?zjfL$J|BiZm7oD4PO24aaYv=2V^Xnlw8w28$jyGQr#y!8Qt{?Zg zo&{mt`8pHR_5DR5XKXi}llz=AqTZXtx5G#Il(wJ82;<(|TJLw)88`BWjm+-<95meq z#NIQkNzbY~-gMu~(OWLyx84TtvoF6vyzr63_^jUJ%lbWZKRc%^_V01Jj&vQ%yzT*# zbu7`{^|*5%`E!ePEU~rq`|qapb*A@G&!++~=4Rlh=Q!i!KIgNYN6_;5ny?<__R#g@ zKIa^N$iJQE_upHusPzzr?@i24dRp(lNA@Jn>|SKy1m($t};&UBR$ysulzZAJ#yZl@@(pVF5Kgs&svW%`;eaL99j5?d+sgDXY_Tl z$v3_0k+TzRhn~E@ZMq))NO;|xRGiR@``8XU(UQ$C+4^;b7wGyM8SbWRk9#bqj|(f` zV&xTpLK`&hF^apjz9Y`Sfd6^pZX0*hXQSs(CWQ5Ud~I3>2F?jpPT_Og+{=HS!8Cq1 z)uR*K@;T(}<>0xV55rN^!TYr%mlkT$zjLJmBLz zxXnN6e;%msl@)beczus0sUH1H829SKdU_qj&H3OrC;jVtgckB*_r5i)S6s~1Q?mZE zv>)lyR_iNydop>OcR$&*UNLC-EVA<1vXsxp2=(VtUi(4>`~z{f)%Ve3=(;wSu>FiY zL*JJHPFvM0_}rG(@~`hfrs7zuKN}B-Nq8Tzqv%OU9x}YuBEt|qr?Xv*Q5BmluttCH}Q^lKP0F6 zA=A`d2Ck>6{XCJ?qu2)eI300B{ek~^+j+#DmmePY$z!P=%_FQw?Tht#lu){Yo7;&4 z{p(TCxGza@xAsF2XYjxe8+YiLUP&+aT+hbZRFB>h)}u^QPp@#Ge?6MC)T5p}?nz7M zLzZ$6kj#g~zo&C?A3Af3`H+%uKEzbt;}mymKcvApxzG7*=YhCachT!Dk9&GOiu

Rgq(!Nri_1~5AHGB2U3Q$wg5?{%iw{lUz|0QWHmT_^Nv zs{RB?Ev~&)H3(z=QTyvoGu8U8#@rJ%=9ZlPiE8%N)$Zv`d_5Veag{BxF2DwW%v@qy zO~fvu5Bm019ZVGlKnF*&Ym^yjvg~xOfJ5YdNV+&?yoNgvBJD>|peDhOlwQK>%t~LP#odSsZ^bi4LQ+Dtnhap8kzdI|N-_UEeYO({)A97YX zE->N)`lQ-9Oxn>Qq47H6Dj-{vj}3(5HxltX>>GDf+7WiPM@` zr=LR6$z4AHgdI@XiN`s1196&DTv`N#K=J8^`}g#hgILC@gY?IWfEqjeVTzVtWQCx| zhq&PywqOU22M+!sEt&r0*Kd0`_M(q+WdwXds}xiPiVsUM53KK zSFlk;#z6arBS7b4>;Pi|b5F4Kb7=FRic@Ko*A>7CwTx?7Iz!XqCP8?{%TppQPu(+W z1nj9{RVu0i{vVbfDh#)=MmH|XycVKr0YH*{D)&Se z!DK}MlloIQjxGxBn~BB}P}Q)d4wtXAKx0q`=>Nf!>$>%3t*8rUe6mTNklmQ9_yp$ z9)17xbjWQI&UrwVQz&FXkcM&0faijsI$;;*VHhl~^nv~w_D+aOo??;2=a?Lb)KSUI0xT@?z2KfN~*0#B@vyDrBXhu4JhJ z5{@C(aL|H(a%G}>%9`7|vFi3th~UnNY-$vgNe|@cV@CJ^-TuzQ$gPpW{f6*CZrPsb zMfl@hk3JZXkcqR}X?4IKbqbX~m^%3*DTv?|Hq!lRp4w=DsS4_8UHW^Y1li5u4-%BU z9DE=Uy;FYKm_!T9tW;$V{z(dY1heE{T)tAy{HVlNbAq2UesD-+MY?hL2iBJSqwNVE zEdLlAE2s*+G0@)=h|Ymnayy_n89*+>;{%H+KCtNGgE!*g$=mesfZ2ld0&%I)jw4G? za~J<1;PG&9#;k|~<#G;QnGm_JO0XE5>=-UMuUz(Sb`nSCCCko@_5zU>pLAgGmV1{D zUvxW{36X*c{K92}>Xs^yivHDtOa&;i+zK&d_fWnl;p@?H*F zmIkI(o)Vs(@<@YBoChu^53bS?XcC%dwWD)WH6H%)!q(`rOI|#>K0Acuq!0As(gGV< zy6%rpI~)&i(yuhM3U*d-h-4w&Shq729{hxiuxehz$aOi$;s`5qY^K)mcg&wt`B7(& zZvG6xk89Kfh)FUXnB73Y?km>4otoZ*=pKlxx~Up+j6Y~j`Qxssg&X4sbxZ9M0c2Hn zT<{rZu`Ey7mmz_+rQ@@6*(`8Rv@u+g19^aPK=Sm4%ca>e+HgR9k9(p$yos563dLy` zvBXyu;&@oEjfZpi3m0R_O;ZVB)H+7dq7Wn$e(Mz{^XUuKsQ#ix^u|T(g4A%h4jNgM z_M*T^Q-rv{exN*Pxm%N|m_IYl7Dyh?GGGR>pjcYR)oR&7kEM zBg#Ed$>PFza!*e|oeD)X3F2B-0+r#;emYoBd)sL>lBT_KEm%H#>t!)zuT5Y*CwI!w zR`nQAWi~j_qmJ<4Jr(#x0{w@59POTAApj_9Vn%LF2jKNrcw&A*aCAvz4-Y@%UHJWa zZ|7X|*H-x3$x4go+Qk4(=k1(pUXSChwFpMeHE-Swhfa#l#L?gG5Ved zRqYD*&!BHOT{;do)Of%Fi|DKCSJkd-xb2a5Jo08o+~>$!9C>#mZfxW|jl7)^_np-E z?|-^~bU%YXQ~td@KZ(Ks&&1!eZ34gd?zP%~tx(HQe`m^N(EsK7Uo}wH!0+9A@Liw% z8MWH%eSLbL*FEb%=pKjXU8RQ(_ez65#o*W7mvln-HyHfm2LFWOXZaVt+4#TJ;NLX( zcMSeLga5$bKQ{PJ4gPb3|I*;M8T_{f*It>H|5*mVi^1=1@Ov5j-Ui<^xMA>ZgP$~b z+u&Ci?AyUV_l^I7!A}`{*Wh~w`*i*DzVZKLgA0R)22TvWGWgYs{p)J4HTbg({u~qk z^9=q1gTKh&*BSfjp0vykzhT4Sun~ zy9PH6e#+qc27j`_g~5jgcMLu?_@TjlgFnmQ&oTJ(4E_Sep;^Aj;IB9Mn+*PDgTK|_ zZ&w`Vm+vt6I}HvQagOgY{;xCm^#=c#!EZ3wrvFCc|0aWf(%`ok{L==%)!<(@_%{sx zO@n{S;NLa)_YM9-ga63jKQ`Ew|4)qn|7Y-@8vJJl|5t-;`hRZx|H9z^X7FDc{8tA5 zwZU&Q_-_pU?*{*^;*ibRPfq2id4m@XUNQJZ2EWwcn+7)wzO6Wnk4=MLZt#-^ZyVe) zxNUI9;A4YN41QqnnZf6ZLw$}6zA*UO#DA5+uQvEK27kK2uQm8H4E|n&zu({=H28-N z{!xQpZ}1xpev`pJY4BSN{uzUR&fs4#_?Ha+6@!1x;6F3?FAV-Gga5|h|6%Y)d`c=W ze6+zIYw*Vz{J6oh2G1M3Xz+@`FEaS028WL69DByUY4E&27iKyf79TG!M6>5(%@}_U!geUXW!tv2EWqaPciu1;E}->245Te z8pUCL{tV;)r3Qbw!Cz(Ke~rOkXYltJ{Cx)hfWbdx@Q)b$GY0>h!M|YeFB$wR2LGDD zziIIA82oz%|AE1OZ1DRQX@C6y#i2iZu)!Z<@N*5GHF)0OMT1uiev!d1RUG=mO@kW- z-!}M3gSQQC8QeDb#NY=8pBem_27k7}pKI{v8~lX^f3d;eYw-6Q{DTJnu)#lS@aqkJ zqrq=7_$Lj1i^0Ec@NXIXy9WQh!GCD*pBVhiPfPpjvkZPGgWuWUcQg1s4Su%4s|K$d zd`oc{FE2Ovj={Soe$(Km48CvhCmUQCJT!P>@Rh-@Hu$v$e~H0gX7E=U{M813t-;@I z@V_Vx4gL=X|3`y=*5IEv_!kZSWrKg!;6GIy+V{^5{!4@3X7JxC4*ctVT511% ze}g~B;O8g~@Bc94|2*S=)8K}|w+(($ame4c!7YQ^2A>%GKyk?LnZciF!hg2$|6Jq$ z`38TX!C!3fHyZq}4E`2_zfE!2U-?eOA^)#8{%=&wT}k=(CgcB;#{VtG|JRNGZyEpJ zHTd^U_&+rMf1=oDr}oT4>0hBd@2oiF_uY*Ddnyj`pKbi>1}_-AWbg|OezCzXGkDG5 z4TCog-ZFT{;Gw}2#i9IH#{bm@zt-R{G5E_2{z`+t+TgD>_;m)q!QdZP9P;}U#{bO* zzg2MjP#~S=`20w1_%M4yq9P+KJ?vB6(&@HZ$9{o!94{I5;;Z!!Mg zX8gb1;O{W_I}QFWgI{Ox>ka-fgWq8A8x;qB{U+o8pA?7k{*>{5v%zmM_@@nitK!hV z{>=FQg~9*L;J-BZuMGZcgWqQG-x&Pg4gOn$|A*p`-}mXH^7X~TRGzss_}btrgI{Iv zs||jQ!JlsMYYqMkgC_=mror#0~27j5sUvBVM82pt6f0e=i%;2v!_-hRQ=LUbR!Cz59jT92llu0vKX9gGoW`GF; zVPYLScI?=(W7}odve>bs>ngSt``FpFu~ydlKj)s`8D^d##JcL<`Q+uxx#!mN?z`{a z`|f@3MVI`NOMclUzv7Z#b;)s;{F+OC-6g-_lHYX6Z@J{RUGh6FxyL2{(;~v%q4H{l6P>)SuS};m%Nip&UVSeUGfN*Jklla?2<>h zos@k#OJ44h4|U0hyW}HX@}FJu%`W+` zF8Owse3wh^aLM<(e412cX zU@;g58^IQ^9qa;oKxb2lF9Y;|g`gjdf=ys6*a3EfyDc}I-8^Xpa(1j{a_Sq0$afjup8_J)3!kQ!936lR)8_E z8EgYP!8q6lrf-SzgZW@F7zP``7O)-c0<}I`S_@bUSPNJS{Jt#EbgSGa+QB%O_E&ND zfW=@8Yz4c(J}|Rg!WDvHuo>(Cd%*PD#D5;>2OGgQup4x47ysFy7mR`}U?mk(8Fx$l+7{*89#s2>q2CeiBV76) zoBxWtB>jyL@20N!JD}ej?pwL^>CmUceZ(kF%JubQ^Jl|b3;a)80QaZuaDV#Lb$|Mw zwv8>kwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvN zwScw2@5%yc_saT(-&LV(VXOtL1*`>r2NvkNP1@%NHy&-)g-!c<`1e{L=Dl6Qe{;)8 zCft)v-*0_c#a|@+Kd^4*XYqQCOE&N0@)^gwSOn{TSC9atx``_@2(%~yYxRiXA&~=X35{%N6Pgz zYJm7>;QS4g-uyxI2M(Z*BK_ho#~8af&(x*ZN7Gw8KzP+h2GJirh+g9vh=Y}Xpm2k^ zyU+g(f0p&(VvNB;ue$z=D|TFAl(Adn{O`2?SfgLPO4hk+{p*H)!g|tf9zIL_seaXS zuwtKGIR9Ui9AnZy{^r#BpN;e@o|b&Q?rOg>(SDwe^P9D=)T2cH+N6A^Zkuc3f56o~ z=c9c*4dHuS@i#-?41MnLE53i6Fi8D6V-Wp{t>ZYw$p1!H%K3YF#&M<`=06G)zg5at z{;0HX7rE@$^jFbmBK_+gNxi=Epnu{q34f(4d=KXu- zW2zr0ytZEhg;)K5yZknNYXNHkYXNHkYXNHkYXNHkYXNJ4U(N!4j6Wjl%e?BnJIefw zjxT<>oY<6phy~Jbl<{N3|LtT>S^X|@9(8`Y0{Rc}{9@>VBaA=QcR;^A!cSi;^UJEw z!2I&(2!BDPJO@yHE1r*>^N`HDotZD=R~=s#;`z%5n7^4cCsiLiNAiE^kvS$`Z$%}2 zTmODYZLnc}X$uTie=}~9`u*a`GB5wpr>X6082b01AG;uRezp_(C!k-eEOq{;1J4g1 zub27VS6%bdgW016*XKtF*Z$S_dp4*d)0>{#5rD_w(7u zvwqt6f2{4Icz&(V2mZMKI8*dhE`Nu#U%TS@!k#6m&!3B-_dq`$)cb!M^b_Ge8PwPTzhPM{57O)nu7O)nu7Wj2qpsRjMC!Mm^0y@h?4nxjY_f^b(FT%UMdmAKP zxBFmn(?1-Ozrp-jy|sX~fVIH?ngtqf+3A0}eax7Xol^d`I=Rop!1yU5ci*vz@#nvH zh+$mylf~T&d9eE9AK?C`;qo7n_`|14x*qt?{EN7&zyDcwuPNv28So$A3!ob2C6}!3 z$~g3|gKvUwgFWECKqpPoT@73dTmxJe)cD=}Kj=3c#GgBym8}JS%NAIBeYtMd1Jl8c zKrP!QxGpllEx~Pm;_GE7()|OtCb$FA84lLqx{rX%z~$h@U<-H!cr|z}cmwz+@Gsyk zU^{pRcsF=2_yG7Y_$c@o_&C@FJ_V{>e<^MSJ7$78U@kZw%mXKZyMda|Js{`1+*Lmq zry$(49~gc*!WDvhfiuC`pckAEE(8~W`+~3FeC!YTK+p#Uz)~;>E(R;XC14dem>sO% zTEJSsTEJSsT3}TyP=ou*Qt)!{3h+wsD)4IX8n6|-7Q7C;9=rj(5&R?gC$J6tGk7m} zA9z3b0QeyI5cn|I2|fZo3jPgz4E#IzIQRtE1wI8n1O5Yi4tySb5p4T|^mG3L-VELf zwu85WcY=3=9pHW78{nJZTj1N^J75p^Pw-#hyWpyv``?0}_fVeq!4JR>!Cvs+;K$&n z;OF3fz%RkC!EeDKt7DuGt`4pVt_7|Gt_S`fxB<8kxG}g1xGA_9m;r7MZUJryZUt@) zZUb%$W`f&+!@%vqao{fC1TYVr2u=cb1$P5?2loK?1oOek;1qBwI1O9~E&}%h4*(AW z{a^{W39hRQung|yU)wwulD-!yk#i z=q9P|8gI`%qK{o5Y(GZ)#h%HM{HRATBW;9nZ=RVNU+-5EUcGm3DRTEt;;-YVRR8JE ziQKb(s=J0y-*l%HrmuQs*WoJ;ull?vS6mL&e_uvt%6aQNa^>kZKc1Ry`W7qquleXc zG}WK~*i>2l{o0xRf}H=}yM)bKh~0`eU$yi4YcF5sZc>ieL}AAs!u)KxKKcqo&Rk#0 zot7c;K;>$FC{^E6lqxqDitL}9>h6xOVp!^Rn7+2;NBy;&DD|n&Bk>eJBK5TOQDOY= zqHo+_#r3Z1$yE0|N8-;`_ZL(3olmFAnh!Ud9ut4v>!+5_E%!bm{+e@B{b_ui8>YH< zJRs%D*jn-#yC?O!)NrfH%rzvQ%=;uBW%p*Oc6P^CxbDjB5WiQ>TXCBB>lr8I=vYnU z%;#2~@75Dilf26RG~)`5j1Z$&q-o(^KPDIq$Spi??x%l(%q$mD_Eg zd{}pDf!~t_@`t9j+nEoi%39WrMJv9(+WrpzPY63cm-~)}^FJo;u?JQhullpJ7O)mr zbql0zwc_h>)noX1e0I-Dy+3zg-1hUN)*ox*%+z%IHTExS0c!zk0c!zk0c!zkfm924 zw?w~Ti(gm&q4&WR=ci&5anGJ3>;h9uWhH9?YXNJ4U!Mi^xtu&oKI=`*+ z$2!le&kJ-uUgy_!9$e>{S9L!4*JmMDj__P#pm}(;n=90RP4xU*=KtE?6sChJ``;4x zwzq|8Su!u^{b#EGH0X=p5%)gmHN5II9`&be?U8UAuZGwBXn422btlPB%Wz@g2x0!t z!r1=8=77w1pf}AFJ4dNt_MZ#o-6)49uYZXl*r8|3&Wk_{$D$BKU2ba z#Zs;|oagvxk@G-zvfZ9kJEWf?ayyuDQmWn^elR)xZxY^f|Bs7juyj^cul1?5T=J8d zC-ru~@Ti||ea56g!np(d+T`okGV3nls4q>6ejVrM*JdW0pP$D99T`JY*8Rla`(fX` zjcYvb|FG}_l`bP7-}}uRD;&t5b^nc8;Fh&h>)*ptfBawzmFQG6R`Ac@?cn|3W8e$m+h8yFHMrIq z65mGPrr_q_R^Yba4xk6z4J-ur0R!O4;Mw5C;ML%tz*|AJ!)=gn2k!vy1n&aX|J{)9 z1s??e1^yfS9Q+zwZA~eE8n_O)KDYt6F}NF82rdBqUWzqJ~$Pe4i(F8woSO>ix69dHA1GjMBgTW~v2)87H|PT+8GBsdCG|6?HMfVto<-~@0Y zxGT6jxF4W0`&gBO4;;LYIe;GN*zU!95NHw5k#I0hUK?gq{W z_W}0<4+Q;SDOdqkgLU8`U<^D5Yz8j`F99zDZw7A%JHUs)$H1q+Zt!LB4X_9N5L|sd z-1otC!1cimz++IajskT7 z*bd$eJ^(%nc7gu@UjknTd%zFCPrxaP0nP#!fct@d zupA75wO~CM1rG&}0FMGs1WyOg0WSnwz?;BZz;^Hs@NV!)a4z@~cnjLoJHUIv2fFB+z}iO?hK9r$AZ(rB5)=+2b>Eo0QUz2 z;9{@}jDRPACxNGeP2gGJ72plvE#TeY!{F0k9Q+sf8Mqqy_5TNs1}A~j!3CfXTntu$ z5pX$pBzQb{I@k1C9lA z!ExYtZ~~YIP6Q``yMnucvq3Mo4|o805LgNZ!Np)DxCA^5JQ_S1JPkYpJR3X@ya2oy zYyqzTuLiFL+rXQ^TflbkUhom{G4KiSDezhFpWuh!C*Xg;Z@|^iFJ2p57hE4q2R8&W zz-_=C!6I-DI2T+5?hE?BAXpAof=j?^a4C2kcrth@csh6ncpi8$coq0p@GkIv@DcC{ z@SorZ;3wc0;8)-`po4zI5O65C8n`;R4!8lh5x6&#&jDm-Nhk-|cG4MFB7WHi``n7eCBVawa3~T_S;BxQ~ za4C2=cmmRC1Wy7_1y2Xh0M7!?0j~vb0NcQu!P~&QzD38j=Kt3Kk5nKo1*8|hRjlfO8EO19~Comfv0qzWr0!M=$Fc;hf91l(aCxW|z zyMtcb7x#ob8Jr3hfHS}%aBpxHI0u{y&IcEQi@<%s{lNo49~b~j!63L8tOS>URbUOc z6pVoNU;}svcsO_$cn{bC-UmJaJ_vS#kAjbZPk>K?PlL~b&w6=1D{tt?%yv#eg%w!uY+%bZ-Z|j+&>||3%(Eb zf**q$W1PJSxEZ)PxFxtXxGlIHxILH!?gS18M}nikF<=gu3+@6=0Q0~};BMd^U_Lkn zoCfNB>HBi}j|~5P)3g4q1*`?E1*`?E1*`?E1*`?E1*`>re-2QLOM1Fr!83f=|Y4?Y4u0X_@92)+is1HKP_41Njz{?4Q= zk+p!efVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_N zfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVIG?S>P1BU*$}& z8N38M9XtoT5WGy-8P7KFA#8qiN5k-IB6qwl)bD>(ydkoFhhwnsc{n}df1vMqwERo- zh3^Vit+4&Rvi~UWv(|iRe)PK{n!cu^`PT1;xW6}|`DlJm@{|9*um^1VK;-y`!hz!H z_?Khs*!8XCuLpFTO^tg7SO|7KB>q|-7G{7R=$jyS?vp9!2kclVawFnz2M78NidwF9 zq2#}J#BdXzejlZ0XOZ&`5WV{E94GD>I@wGf4cIf!K$oUV8?0;Xv zwH_?)g;l~H=$o$2GVvGhD)BZ~i@tAnksE78ZqA21O&Bc{R?HOUPZq`>k#swYL~frY z%!7MuI@}MHc>S}XpDOHZ5ciI~MNV5y;u|#oUhzLzIa=q6zrpO;^>;~kFuS(Qm-v2c z`F^Z@^Y4}K0w`PWz;zGmb);wYD7598F3^tx5?v1M7 zP~>*V8m}@8eHZj;+0u^nK+c2gTr2TpfU#}Gp9gXw*pB%8kfUG|m~pbilRjL+x5B*x z>_PZ$$j(OMzZbF};qwtb?K;sHLykh93HK(*d5~M+uL5!*;%|oRhun&AUGU$g@j)Ml z+zPn|{yHG{L7#p->^1`S0y_|YHuU*mA@pI$X&X!UM#!0vqwv=P_ja)RWbxkxxfTAL z8^k>i;d|jPbEM=e53B$);J*U?J&>EB_d||?X{Sj1O^{o`4zL?+*7PB_LDu?cX)Rza zU@c%R@cXhr@$Q?M{!Z69((ma5GtU*d5DbIOU*J2iUZ? z*a_xuA@0q+65g{V!b6T80sC(y?&({D{}%t}LebWERhMe&+@-tJ|1i2mb%n|oER}9W8yH?D?hdY#w&UTiK^TU+Cn|CW*p-Fp0YtN_-ieX&DRgJK={9OU1_@Cmp`nO|GS~uaDQsUeaOLm$qzPx9bhl~W#WG1 z)%z6Kg!@nj;dz^u%2)AukK(B zYyw-rHq|412jng=4)%iH7bQOq+QD?NN%IFejPiRR=Yw9*560jxtTNaHYCob0{@Rd! zi^}lV2DuAz9P9<14xDE&6ZC-jV2j!ja);&*atv%z|6pA61G!7xK}Y+wV6VF0i+q8Z zO8E0Y&Ii4qAN0UqJ{X333~U0u(6>PLLvDlI0mfn9F37!*<0^w;gm=(h#vrFd&IFs_ z?tz>SdO<%J24kS}JNPJ(b^e?-&$NGeWZeUGjO zam()KM7edY+ zFY~N^$h}*O9EIEp|9xQQ$C6GV7zT^Cm2e%9d%*Nh#J?YG1pDB>4RSY_y=*&E{%$Zf zE7Qo04dUJu750G5%SHBYvaRvga)`*ShYH&cgZ^+~`Vqp6BZZw{G$wNPQNnJp@o15o zjuG~N&Buydc$_eQeaUAFWbg6fp0=U5JD-XjvOzDHF+uE>4_1IpVEA&;_kb-3*9k^X z7JV<|7RZfXi+gyHu#5@21@?hW zuZer}X+qEEl5Q~=Q@$>G|LMXuu%b-lSWwsn|9xOfg}BEnh2AD%TahrcPtuF-C2|W` z2=|V#xOXoVHp9Ig&u2Oyd+@xa80>+2`hO&TKNy}R@w7qi2Awa&Up5#8TfmA7C0wWK z=ZM@3Ipa$S-wXGOZ$+OE_wX2zyDk$p!95f8r5$n{O#4dW%kUx|uo&)5kkd~Refkx` zM#ycDTj9S8>;ntGmiWD>PhrT-UH01gs+hJ;}=PL;Eu(AndmDn7j|B<;&Qmd{nq5Bi+)}^|JLkb^J^_& zEnqEREnqEREnqG1V=WLL>X>m<;V5Co6rnrbOt|-6A^P6W;1AC~y0?XVr7&He?|>R# z9N|@7RaUGf@p=ZxUpCyMdyBug=4VwC_>K7UZvs32M)GU3X)RzaU@c%RU@c%RU@h=# zw?Hxand!SrKP!y>q&wf?O;_Fz^CKR2xSvYyLH{;yfc|h4`O82#9IOlZsnY+o#MAXV z?dShm>}&I3EnqEREnqG1`?f$D)}8#mOZnd~UFP|jDeHc+FG!VJu|6SscIxx|wj)#h zX-V47S+Tq7qgSq6-*b6tIvP&tIaJmkRGcaP2FgcapJgHNv{WNK1}4o!-b6(3VWMzy)G2_w{lJ@ zkl*-mlJB15h0P}jyN^vRPse$w@^7V_eOTw~&ad8Q-R^F=@XFNtX#8riL(etB_R zy2D%9THx1YfnuyX&^+}{c2fGsF|0FayCT)y>k6mg`*u$Cr|!z$LFNlvw_17lJfxcs z4wR4fy(FFve0Aog5`T;ooR0ff2z~x` zqEE{dwigMbn7@vJam}CWJTz^9_%{-U;opn%7(;&OwYDZ7=>yDHyYn}goc|NWqvakf zy)Klm73FcugN3(xYk}Xh1u}-99r%R`*;pv)^=LZ-IgIuxyt(K*(cY(PJM|0Y@5d&i z`HkXzbn)Y*JWZbpTb>hYI$pH9D*skku}*3^G~arkRe2z~?*oOnFZAhsJ`?dP2a3qL zTMPUOED%ROL$lK9lJk#|`W!}oO#OKV=nq$*-=+TC%pRoO_7Bp}>ZJ&|f7t`JWUTml zj_UR3&H&_!{1t~A!25TciwDVP3+$6NfIVW!cL(xWfqq^)yh2^kIaS*ZY}Vewm@uv_W0*2R4YZy z?Nc7ww>GpZ&B#Zqwnuv1{>s{&!R*q5{I+f(%KWy{J$1`>j3Aa zk21*Tcd%cptK98+|Iv9EtOx8_#ddzM^sHVi(07@<$3ox7)4Dj(8eVW&M7j6G?T~ z_`WaOPC+~^G*IVX?+79Nzbe;t!n6IuTEJQ$2PXKrnKeKV4gvv@U(220@UceL zY;#mMi2DKXo(FndtUPC)!^fE8z2@jRN^S#HmEtiR0wcn}Y~kWyb+ERw)QRSeA2oiQ z<3uVC3D%T5PEC#Im(~l@>!tarEH4X^+6jgtLDp23R~v_#>QW<a-6L>F#Q6ND#Mc6U|)K2sI6g_y5-?uCHZ4={_CqNYbZF!XG%=D3WP$-owDWCfhsC* zAQGuuOdh71)E&p?D+`9|0?y)UDR7{)Cc@W|0=oh96DH^~U#?6{-2A9k29KKH#Le2k^K$G^(zn(^a&Y)Sc*1(zjBj*)}|Xl@l*vOOPtx$r%fqZFyEOz%{RYb0bPe>6n)rXdFo86vgrll-{-3)71jGl zFchQczI+v6`(GZO$vb?IKhU#{7p2Rm}_Ck~8nUy8A zf!gJcxroT6gkC4kzY2jf9qmXZm6?Bh-SdTBQZEh-xSqlxbGbST(4G~UtJrat*T{8V z#*GI3=ycYH=+EY-q+43c5t2LSnSW_#NdA<@aV7uxeC46Q;s}+unwm1liN8=WlnmHDE?%4$8goF3V+Dp*y*f0`fPr}&SKPvyL5IjD})6)b-Ee>xBK)g;$c`+`x5 zaB;9MSdBKZ-xt;2dU2;(ZuC`4B6Yzks_+B+s+N?kR6jtlgmXzG7^p3+p!_Wfa@AfM zG0jOrUsfrZgC5G-A0Y76@>4cAe;a(^p_yGFd&B`rN zGnc}__$P-dx*7AeSyfV3(?Is6^T%)+O6zL)H2HiDr4<3HFX5^{9hKAlBRiXdFQ)oX zNBIrcMd-$ii{Z9I|9 zmYg$(@SzT5SM#UOx71MM@pqg(gb%8{5xR_>l2AcjD2$v81K@t1lNE2krun2Pc5i6BzBA z2sy_@Nb#8ni6%m#iI8X_B$^0`CPJc#fYL|!u?RmF;pC1@dK0ej0~xlLoV%fue3({= zI%H^068AB+pPN!@>Zf>e#(Bohbfi>{BUb6}zo?w(_lOxBmB-~uev{(M^-xK3Cgx3G z3yk%6Ca}z83neknLnSA9qK6VEj)Q)@`a`(!!kk^$vPt0)Z;nZi$}uoaI;5BM@;p=q z&95gq!Q82G<@7tsoUu|umDyi8`Se8jf2M>}JILAmu3r6fpPzq7#>tV>Nklq`NNNY= z&jY)96l7J=_lL~f38O&_)h#%ZJnI)xp|y*>c^U_50)=2 zr}ldj;kfYhOQc^gYT_=_raL(Wqs9}Q+&r;NZk}9k3A&{b{wBGPV!SQ zDmQo9%tX9uU!`2lN$H~gj^AaMT>djBH^(!9JSXyHa`|1E>emF%`2KX<{`ERh_X!?x zQTeB)rl-{MChDQ99O_T=F>Lo~!`REP9D{+&uk~-NSYE@U+Bw5K5?*EHF0k`BBrLU< z9(y2PN_AI%uOBVG#sAY=?{&1SPl^U zYI;h(Kk)fgz1}aFa=(#!rv8;bRem*|NLVsTQ$OZcj(HH(S4PEs)F>g3Mfn%56YBr& z;XidgbqKCr47FbQd~?nCn+CTg2mVeOXP7}Y`K0kP51$j`=k2o=IDC{#H<8E5`xVTa z<6u}!{aG1F7GXdeSuPn3AioX4kSQ5;8_j%|j%Na!l@H}3C6gpjf4i24raUezrHQlt z@nb_IxYTiCdsPhOWAdcM=6G%2ilKaToFs=Cf6=(2938Wej>~BDN5iqikNV-JTVAzf z<-;8_e&K-vewcpZetbR6ps2HqBS-WJ~Wxgt8aEjijxN%VhkE@(c})O76+=P#9co2!rC)Zs(p z3)Ir21O0GWILi?~*}IPCvAT|taPi}W8jfmHIj0a^E)$Niwp6`d-|F8Tz69wE7S0`y z#^)xYbMl`_&Bs9g)W7z}^nN_%T$&G0I@CS)oVgAk!*7v8-Iennoa^whR>3@TxbNTE zA5j0wvkK-qe5kzS(|HabDqnHu{th3QzH%0$ozimA^=#UKDztOzKNQRvUsqG%=)AsC z%Uy|j%;QdWQ#-5P=PT@=Pt?u>DSeBIW-st9pz&#S9XE&?PRH9Cep$e0+9hIXO?bIO z!DcVu@V?SAnyPUE@Mh+LosZ^=-koN_Y>Ft@{EICsn?N~m-^A;J#;ZrcSgs36EObM@t}_X z%s7qw!Cl68I`6LIF^$)=P!cwor9aj5dY!BPep&9XD%bL)3jIuDMpS!gze&?kCfW@e zAF-Qzoa7#lX}gn)3~D^Ppkc~oBXB(Cf671HRj=d1gg=bSG@Xes_(T|7#{o1>GN(x6 zRcbj^*7K#|)O}E*V1xQYx!nHLE@L&{@Td0wPChZ;klat=Aj5XAH9fpxrKN^CuF!Fa zrmOL)tjr!R2`B7;akR}PzM%#5cst!Fwu)p|saT+PpI z|Ac>0|LA;`ElW+O3jHI^r>3X*h}4SzF#MI`IZhB9wTC=-49pjQS?I6r2!`OkC+;!7utd8W-1-TJkH%SY&~qw!!U#`<_{k@mLtWgmyPxTn-TpP6NR4@1 ztzv@OFHncJ{bkux?1_RQd{l-)!Nv4kuRKs`dJG|Y{>*;;drlj|hlca{X6v7Z8n2I^ zXH!VJt4Au#45E0WVa4JcPr1XzXJ>kxP)%MEaU6udu)M$tVBFLApgcd*_y;0Aml;1U zO5>+9-y4#A==0!sfSwD};STRV{mmhKsJn)3+4RmKd}uh8%jYGsZ2r)B>cN;AistFV z^~Q%KI+i8j|NhX zvpxO@*F;Rm-sdZrIi37zxio!xT5A5Jr=^CfS8D%%Rhc|D&wpz?Zu)#)lOA!_0{ZK_ z`UQpa<}9M}&0bJQdc)Z>6aLIYPjXL-N&mgwMeV=(d?lt<8PdhC;}ds!`f#W!BI7L8 zhihxaL8nr#pN!pCr$JlmpqNDj*|Lx_)ZWglp74 ziawuNDPh)5=@^hn^NG|tQhWcP*BoXZh6XyrpY@u9!kMWd9iI(Ep6vT&ZmhsL90 zSq*pcvvVCjRHpoy1u`mYIF+xhpXczQ^3%u7bNEnMIsB@54j=vbk{L7ApLokWhmW(K z#qk!Emkv$u`cLONeB87;&1ci$&iA{U%yanA_`ajxh4gf&Ug`Fy?!Kb=wA9QoV{0BW z7Zyo%nmI?P*Q3^3m1&)V@j&fQg#YSyUoxKCakqb!l{8*Q_y$m}W*xUz)YX*G(A^>O z5IzwHNFqZ|Y5~qh*zg`8<};x*hJwsGZ&EyJeZDj8Ocg0iG+?{AqYOOLU)_ zU$kEV&3E_~n7>3`KqvZV{_%Pho?oG5hvtvk`f4N3UO00mC++i1FPd3E>#NNF{h6Wj zU{(m2^%TY*t*a4nCjT8npV!^q)&ZHD-Y;+0&#<_la^|fu;3H zYB$AO9yVFkc`hoKk$L$G|3Up+?=2yiHeSIT8&vAm3<37 zBaL~sQA=NNl8?qwG>)M|$5T5ahG792hwD6(&PR~R%uoF*bqq8T`cX=Zv#|Wr8HIJt z8cyc{l?diUWSTjVuL$P3%BarrFN6w8r_%iB)S6!op7*-fRpfYNeT$YynRs5M;Xz#o zpz|@gI?rQfrD)zmpD(+@X}L5%Zm#M)mCPUZKTp@@^Saa0P(7U- znw+iV>ybtoX0#d%8PN&La$~01n(W9n2BPkBHVa`Q4ier`lJQM1CY zn$}$LPv@y?YK_{V_1or;ZH$)dcS#^ZEj{%+s%V;)SY6LE*nxV}Eq6+4cy%YW|GXHC z8KN98YpTuiMrs#m#T~T|=nR(C)blcLDv!Bs&^qw2Sr|tbUx0H|jtni9Za=TLLVEw6?Bqw)j49&#&)RA)K zP&-x5EsxHJN9v?SE~RCU*Uly!{NHPyzTbUw^V_fRmv$vNfKnUOF(fHe0} zatYVhn)6;=lew%W9C0G00kdG8*2$Mw(bNL3XXkKCZkP-yoFShta_1Ap>)nk%EOl11uYVvJBqg=>xt73|Y@I$44a5(4+@-W$j3BB<^vWbW4A!$h;4Vx7b zhUCMLd=O1jz%=m?O+3-C#1oYr7^JV_YuQl3SLKk$@_<(=SQ+&%W&XiT zk5RgqCKGbJG;PNAG34}E7I#xWNH+C@$vG#Qo)VLD&V;)u2+1ru$d-`fbD{JFeD#D z(+^{EewbVUqA3Tq?Kn)MC$fT?Df-`#omn>VpcykV{F!*_P@jb5j*#|SP)DB|7(

LYz@z*qUi%`waT5Ki@M1O2abSD4)LoYjXwR02c66Mi zaUi~m9}6k?HM;vnKkRsSJIXIKOYbK@xk{T{i2x8ooHs`^LC-n{Q1iSsWBEA;H7;Y)kj&Us-mih&uOI|7dN} z8xI2eDEiT9B0t?aP~{EdSLH3M;+GKl^_PCJeVuiobX#oi}1T6~8VCKWxvg68)<5%S!a~@6UB$e-rUk_0oE}b3d~9 zo#UQg%kENdez6_ZuM^`qOZ2OXqvU|%>Y&j2OMqV*2gOTk@@tpapcdb6 zSBrL3KMSwLo6hZLDC*@wcfV8@hiq`ExfZr3`G>%h+U zrk`%SY_zv}R_Ukfw^`yB+q0yo3)R`OTk8IO7+v6pT`%HE^KtRO=-f1>IGwF{7m56+ zE``>8rzXFW1D)fr_}wDvO!+0CJ-bP?qxqn5WX^FO52#(+MCa!mTl|)J^Na0t>z*F> zDZlzUXZ@%h`c>h@0Z+v*rD^9oNRMAu5(n~ToubaP4qCtudq}jSbztFLA=W*$qxz*< zoa@EHd%@i=#lv>0e4w2wAI)R+bdG?X3J?9N_;qRe?LJST-;<(#G{4A){mon6y3Tj@ ztD6tY?`tAIRlQ(4mCl)Zo;Q_UaGYL#(XT3RXot_c34hP=sV?o{SH-Va!VmqhXGQ&J ze(V3t{j+C8JC)9f3%%u66-Nqq=&nboboL#rm){WBQNNact?u&@%kD){KdN&F_+ee5 zol57Hi=B10{J!a}Ut&8|KF|)g!L|8(n$~G#eE;^3)FEkG1tI{P3@v3xb zA^c={L%*v2+kUBD98EVVu9v+d>P+*Irwh3*9(jsiZ>-1b{%?tRs=WCkV%}u;DFiOl zi_ z>K{B>S4rS2)#YQ+Z(h7e@NUtL#*1d`Yj-=!58F{)s9n=Ut~-r`+94ipWyg<_Nn-zy zjT=#7hvROZU($c^`Y*NXSir{(dwYIy8^J?e z5RcvGu?~oS7%$Z?*ek|?`dNPOFV3&*J|mhB-}Iq^{_GofzZSpmH0_3Z`@DGkzoIVq z`B2O6kM4e{&NNTZ%&o7zp>gw$KMf8h0Q@@ zw-@S%#^GOw*RxlCc%P~z*DuB8SK5Cq2mA%j5AZo8ZRx{Yzqcj0jK^1cw|Kmi&6`pR zJE|Ye8}<*R9lgihZyp{tgl*;=@p(QyUh&9rTJ||AbW6X_N5&6%pnaYl@!JdEgOFzj zju8iW$n28q?~?0}T}SeMkY`8y%I0-6Z@P9kuBrU$-k+`OS9;$tiMPM)q|YTLes$x; zevWx&!@SL#qMM2LZQ{I1m5<;N&f_U#BA#?SCGq-JIv;=Q*LMEAl@;&Tn(KsP-E~2{ zNIUNj_@18UQC-68I`gA;h)367dhmSuBX8qxgwlb#8(7?0auI`!kBV-%0eV${X^fy3lw_8=d2&c8I6SM>F85 z{3a!S(GOcsjF;-%1MS(mqMfcTsyGrKEAla+L|A8`eyuomD~z8?Kg3tr#Wvynm-aVo z&o&VGQJtf+Vcb|>w3Eg=)ZLEORcwW`&eRV1s^aYhzBFEn*R9fJV=)e@OS}nm*+{gb zx=_ERE1l!T_}EBqc-T&*i*Jr|KgagWC;FxF#-KghRJ2pY+og)P!W$m)RmCf_!~JXv z(JzfR@>j_3=As>q*TSoDx1)7{?Fx;9;`IPuTKDLORg3&+yy0UZ-b&Gq#!LMozG^&e z1$fiv;j>hZR?}3Hksp<;jQq_TPzM>Asiu|Z9F=)@~L_3u($uAV+eZ4n4-FS8FN*5?} zIYi_~b!mq7>|oK3>VkaOcz3(L?;)Qyd-lS{+0zy`Hq4nnW5K*R^Jh0qn>lk~-aNKLfhW_2_Fwed(jl%F(|VEN zVf*m8e7(2_)<*;Pig-Qei}B0wC=Zz(;-kIH4*!lkWp=o}+j|_0x6q)I#6fjI-1G%v zeAJHmO|QeR?|0m=L+-qVwr45#^HucgBf3(*XcxZF8$WEx3^9SnR21cdW{86Mu(99=5*bM}XOyfQppe(1Ls{8BvMQ1O1B?jX5ux8hsN9j{Pb!Y7KnrFB5&O|tq!zSxg?PT=^I zUpL&3PR~EEJv(Dy;*Fl97jMfJVt@0hixtON0~1HDW*oHcb@SE^_%v@;T<}8H-`Y;r z)45Q7^#q@_c+{EHv-EqlAWmARcz;PJd|#GqOZ7|d#g88pkLoJ>J_5^b#rnc=l+Np@ z-=-BjAFB1C=t?nfrRSFle%Qqr#h)O<}rHWUE7r08Xu5!4y>wdKVrk``ZkD{cE*S)I# z(g{(Q%m`;Z>bH5h#18U7>%~gbk>29%1%5P+mNu>{yUD#@T7EBex1;$j35drd*?83f zJSacQ?*rcac1!RmKg5@gYYpCXj-BD$FH5fmoiBHf1NpE{(T=Xe$>N~(LhVY=!M|+K(EMf%a^MXs4^6s{WD^etB^~LTElPPi%T&{3ssv+XMVmafHuv z&WFWsp10#=E8x+*QGQJlJIn8}qAoPQ!Sgw9Hb=Ch`L*zF@z#$LhdTEU3vZUYUm7pA zQ{_$9E^vW!-l*UBKb+^;)UF=zXx@+yTO`Iy^O1t~Y=LMe&Bu#kJ}92=Ldb8IXh-pA z9LTr7bZ!A2s(#b~c2fP07j>cWvWp>8FYp@s&E$UjK+)tJgo80FUxR9oUJY&NROnXwOa%?Pz`rjkn`4=kZDx&x+%` zf#H|FL@yt`U`KVPadb=aX2o%e7zfQqycPP}$)X+2hlTfqW`BEIw4;7$9LdA=@|NCB zJnxPT8Je44WigJoM87l+>KEfu^`n+c_43vMcB;J5^^(k1d*dIbp*Tu5?P~@koQ*4LNNoa%qLivT3>OE%+ z@lTT!e zY}0t7BRM}+9LSgIjQiOo?sZ_C7Szt@O(w4Sj&yVB!vdT%{lBJF&fL_c^P zo9axDGqUT+!RvV4TX?$-bzFa@c+%%gj1ub)pO=xx4;{i*b{~qiU((-n?~_TB_}Tg1 z^43h^#p7k6@%oZtJ_^2X=|cB7EctI0?Nt4vhsF!fNr)luTSPqCKMK{Q^oHVek@>~@ z+`56k%uYHUT*cqN*h$ApGM-`_dHjf-^mqhuV1MfcJt$r(sh8g@#6j~*@n}Bqcx1_XkC+dd-`Fjn z>)oQAZr;+|g`hwS(pxmB+YlEhA02f$AmM}c+F4f^KkLhxkuS8}srJiSlM z8_lmJ|KCKr|J(U3Y1hkJkl0D{M)cF|m!1CU8sJlyyf+`HW5#ybLM#Gb%8v; zRwCW|QT#SBKH2=Ljo9_K&H=!0yPelBd(@jQ7_PEk9wg4klSBFZ9^13Od-L0JBF_gM zcM&hPcVVADQpM4IJI|ZyxXF&cPZ-hRgoXnxfj~Amqk03&hfjsU#vITx_le4>+R;xd!_NFh@EUarFp|~ zh~iN@>HXsnfU53&_vqDq2<)VF|CXpT%|{EgXK#phs(fG`RB?1`#=$zA>ncxYP5mN( zr>f^>iC>J5y)WuQ_3MK6tXs6}Fa3~*Dvr!5=XFeM&#v{xFMO}Jd{BOt-|M~k?YdC> z9I5Pl0r6@5;ePgaZ{JTGy-%;dwSyh)Z-v%rucqI?{m%KY;=R$E&e)FXN8@O{zbDcxv!_Hms$bu8ab`3f8*iA` zIB!P$gogPGrq7>g{BP_7!g+C!`I>57p2mwhux0N2sNdk)&bm-L#HW6#UHV~XJZ#UN z7x_`01D(7*drq{YI#a)hui{sFtn)mZ;>Cf7bliBMfA}Hq*8h4t5A{8w(D@aSAJw@9 z+OwBLyZ+L-TgC4+cfY6$n9CuwEo_9_e=3mPgVbDeN3Utd!k>eO9tArcSSp@i;Q2}3H*Cbkgv>66^H*gy?!2j zToLaF?r|VbcJjc~Y2XP3zmG(IG#|S9#la8zw}_{kH@r^Lv<06x>iVU2ZIXDYo$pD7 zE*}>bhpMjH7xKDN*>y|!(KxVvRCuLNDdN4rTm6+Buh&1iw{|`cK;Ginav z*_j`?c3_vSv=r{?0T~ARK0$QcvKgvbNllg5AE^$I`BQ)b+Bt4P`uQ3-r`l| zH+h;~yj_}h-P=3!v*NwgTOH7KQM|53bwPYpyrDClK;^)BJx zOV)d}^SW~S0cZVayxl>~`-_j_co<*o3unLhcUc_x_qOTc`kL(eG|gLJrL*78=lJ-7 z_+I&8JNAS7eJxbK#B$NE?0P_&*m+$~q<(t|Ua{8=njhx*RgFWa6V9(X;Cc<^7n5A) z?0FByu~*h}9k0+2+g9^_(RJO|SuMQv-H$UEhcCKp=HvXy@l>Vo=hhIr|D zD7BOM#r^D4aXwDZQ~WQ2t}8@4I={+4pN=~(u%Y7}-RoI54r$Pv`6G0l-t~ zBIAeq*#_?8AJrwL>9-B+Xg(;O?-i~ywX^uG67xp;8^yzRDqT8Me!p|~%U*^0_*S%| z{oH)sq4^s=hks9X>TuC4sL>moBiA=Hq)YUYZa8 zYoJSyXh(HH-i*1|pJlg^yB*aJ+o|I11isREH*xoieps&vQzBd_ zD{AN8+u5%5J?PJnsM1ONdlfKm*|4|!1*qT9)1?27caInSCPumYMLRaZ9WSr0$oU(7 zj|AfRN4xu_c)|BY{esJ!&j)*nT{qaF-}*7${8F81-dMz47xc>}x!cirqn|jhD_eM* zxsL}F58Kgk7x$Mg@uo}a1HJK}bh+Mq9C@gYzg_2w>)x{U2;aXH_wplCX{|9j|)yo|7Lw&6{70i|UN~*|zSw(7I~x;`x=vv7I+O-jDD$hrP#9LX#{FOl;5lQ(|4`n3Z;S_hOL`-ff}Y0Y@)cS zyci#Q$=!~|QJ>*)V0-jS?ffr0*E6+499pNipS|FXpYLP6x{84vtrr=;`m@FRuPlC# zc{?7_yy5j<3vY2U&J_6{VhIS>~E+Gt%KxHO@5@Va2&Gu z1-*^C&7V8xjq*!D94h^KNF7M~IS^L$x5(FgKBUTTILqTu*`ZEKJEAk@4coJSd8>m` z`uVp#ock~B=d$sX+7)}eOnf2Mfv#U1pDkT>(7PW5?GyJa=DQENf3AquX}D4BZ%k8X zT|11I`pteR>L3{(Ig z{?etbOw6xrT#L-%`Bue&d{z3jf1{^g8tkZF^uwO_rc3BqKK@~QS-iBr;c=hVOZ;1+ z-)GM2&(UMKeyZbO3h<=yzUUq=#>JvyKce#{Uk~tpLBykWG+xA4<=1ySKYvlh8@+<_ zpz%__@wwu02Cs7>ANJC~#6jx-KSyf$eMR(3`=w(kv$izo7m~bTmQaop*r#mmv9Vd0`ioxgkRrR7<&$|5n$Jto}EPoMP+xd9ebC}+EK{ zi?@f^$&MdQH}msB)IpZFa6&wvk@<}tE%KA$p+7v%M1U_H4?2Gn@ud18ptW`GMsNQ&Z3R84&TYqtx)gg{2>c=9$>#S|KbbCZf+w@n z#Y^=wo^Q1nuP#4X|A-ZcCz}^{6o@CQgVg#wUe$SbDRW-WvAXF#9>-m1NY@1{yv@Ab zKb{1BsyKR7aU3AVLC?==e@o1FUWW@0g7t^}M7;i5FX;q)RlFInqw6J>&Z7o~Uvw?K z^{WKfN%_@@{AfPX(4LJE?WoRHyzs(j+hPCyJeprLqjgH{S{isiqH$2W^lAKfhPXI? zp?3IpmEY9bdOFkbR5o5^0guLkeAvOF&NLsfb)fFYiFPy}g~rQb^E)ahZOU4Q8k1$(%5JC{gHqjL47b9EbMoDABIJbWQ=j zO6RO34mutr?{r>&w(2=HFmbf3uQwiafSt5nW{Ui1KG+6O_tQnY{>n!L@KyO}20LjS zvj&D=k0w9=hKjoXtH_V)+yw1elW3>Xx%3S2c%)iaQOysMs_}WQH-6X;RDS7vL-u`! z(T()#z8&nO^%583p!w*9_H4drr^<(Jyzv>%$3Z&2=;F0)tfxx~?4-IZ7UQM5_%?y@ zV3BC2(j`30`MeS1V@tf@VLMe_bpT&FzF>QHyy%z4%Ql60mx^|(c+(Tbei@K_A2{+* z#nB8rXdJX&l3*vzZ?m^JXup)52Xr0@I$=PX_i1%5cYZEJ?^&XLGQX4`{Tv!Q)O}q5 z>9U{2>+CeYmR)jv;rTn%j^@K^XT9KYQM)Ah+>>k^Pj4pbEL(5tC3d>&iL!Of)bYIk zVi+>NO;?F|!{_kPcxm2r*DKqAfC2G<)q?tWNz~iTu3g4Y}Y}mtVR~>>s$! zia2cJ!3B*k*7Xz;KO5mKZ^5laUA*Rv<|9GyWcg?(cE#pnBTG=m?Db;p-ljO6O9)>! z(p_iEFTB{qw!_Yk>X+TdIUly>xtCtoC;QqvACE$Q(XT9TEyND<)`!nuY4aoZ56O;4 z-NdhqU+K1D9R1Btcie3wc|?6=y5Qg08Q$tjhDYnlzn!Ry*M4sCgBJnY4!3%4C4Oaj z>m+uVHyQ_>M_|2JbRP9MUnBLGcR!}bc##K=&po6b*_rP7rSbaUd1KEha+d7XMZNx9;x33+46}IhgtCtkP^I8Wqj@B4C{=)s#HafYNy8K$FI6udM z`bB)KgEZ)#XGiJ}?>ofy>~Z&cw(Q_V*tWw>XEgI25D?}cDt>rB9JUX<>+yL7BwpEh zPxGI|dX`=9j+5sm%k1ij9e%D7<6u*~^-DSq^?u=e-(h$sF%I-gb&kyt>lEX#_)Yc3 zFPad~-=yDrNb(Wya=tIJmpm^Q@AI(u9qo-D)i3pev)@EO)X(>lvmNqKj*~l!c%3pl zqD#|@&VIXQih0BPHjxjTR-7)fb&xg^M|Y6(v;5BR<~ItTXTtVA_ONPj`}A|pc`Myjtb^v|&UVT;7P#}X;yBLTj>bX#VjWm`H}(%6 z_1i;q@vU?o*JS)CUU-P8bBW~hOc+<>9Le)7Zg!6s+p}BT?I^#NGZZSH<8yE`@Q?$WfoThs0yO}h?FyQeknp3$^h=59ypnbu3*`0|`Po|TW~ns(1? z+I4B#y`X9LlBV6uns%?a+fkjH{wmH7@O~~!zt`OHEW5O(-5Z*AZ|T_uo^_w!Tm0T} z$D_JrRJy$94X@)Gaa@y*e`FlW8~;A=<`?5vUC*QaO*T%}597xV)jT#1cIaP**9La< zd>`Af6UBJ*u7`qQ^IzTTz_%A1_f8P;bg!4G^h+I~xbNnqf$_`WdD5zUl&YRPeTvAB z>f8+N*~y}vO25>)eEy>1hxw*D<9_zW`ocPZ%5RURF5wZpE@=JH@c?;He$=iN@Ko`3 zO8lZ9mJoHO`6w9)^?aIWr_u%SX&kse{Goe4qVaY~p4W$X>~wd2Xczj}o8KPrtI|0T zbj~mOW#@|gsLnLr()rHE%Q*O9XN!1+=7ajp0=_C>rnB#NaRQJ z!OEfTFA(keOXmpStKw(|JJq;R@{8X28`dN3m$VLgH2HNd5bG4@&lJyJ;ao4&E(~_a z6F+B&?_;03_uuffF#oyKTiz0&pDG_sfUmL(RyxOvaj+}B@xykiytRX06~DBK-_;^N z+CKtS&_Avc?fR>K!~vhifjX3a?p_D9uG#>P_9Mh&XShGth2mj5RX#%1Tqha_#Y_FF z*MDPxCynEJF&{K<-O!$0E86u}-s+Fz`O5;cl48N`#y?pe5os{2wB0s8g zI0XIU2GLGeXO(`s_16hJRCujmN8_b+nvvKcA9lZcyq4Xxf$4AUwR-tYgB^|6;`h4V zeUZHn?&5mBVB!5B-j7M^CB8S*%LAJFZQnooS^ReNhL?fkpj5vH_2Ov1+1ogdd{yHv z+NtWkV;{YGVf%7B8ZYf1-GE2!kPmxU)P>eTGx%W-iFS0{u<&Mk%Nw>+>DL21RQmb% z)6*rg$oaT{eCls>uLHDWo$k8Od|*3OyiJlguzkl3?)<3V4B)BsOYaZ;9vsQ$&rz_W zbw&Ns^)-5*rQd5DBgOSZyl#cMB$D2A!FDQL;s@x}Rd_M4E2<0nVe<;>A1Z!{>qK3s z&c5UM{r$*;_Fvt+QM;C~STFQGnZ(lK{30Ipn~~^D?RtqWc>e~qqjie+o2l$%{F0-b zby49-uj^Kb`E6Rkum55`JFoLt_hh|2_Gxj~lUqlN@yf=H^b+y>T&5q*2i}i_@v`^b z=RyH&K4)pOf{BpO?%e&nS-{sVltiklLj*`O!L%#j9%(Cf%JNJ7hWB#r zA58>LW|vq;yx&4r_a%3U{WmM|8(87(e%8{{#rtzq^%5H49B;H<)K6BY*}KI!bn7$- z_rpSuwKi&Mw@Nm3V&ByDBUzskUKa2b#+c@_lT7NQrS>jh$XW8+W`jy$m zNF1_wb@4g~UeR$JEb1)NkMhI&F=_op2%c`dGCWzw6m`D(q++z3Yqf;`lH8x##FN@`t-$iihoF zx?~l2*gmn^-7nht*$}PkDIJ=2^@H5;yvEzSmPb5teva#07%w}*{rfA>&bPKlzf+vY z-Mn}SKUy#C9{q+kbiY3_ypDSu7;m?xUCFw7cughlc2t)rd0qh?KagK~J$F2`Yg^yl zj{3!Rvi_F3S@U}1(Ry_i_@^FT@CH4*)|>R~T5ff>^QsFw%iDFKrme*OQR3t0=cqqB z#~shITi5-03YJ}qCf@m)b{D$aQT;+w#dvWZM(yHPi|fTWf1!3Ug4g}E^ZG`Mrd_wD zosZb*u16$a7O#tRD(arb8#zKxzh+`5(n2r;Bxk*AXc{|E;2(tp3``bFxY#>+Nl4i+Hl{pNX9#+R6N8E)(tWe3iyQb(VeJ zncB&o8`abz`jzpEknphCpJvl#OkBZ|Ey`Q1}XlVb4Xy^5MXtCcPl|mjc zAj`gIs(V|0-bjzXs{F>!a~}Uf@crF*9Kd-*7k*Fpt`{=bU(l^qAe)DF(0 z0{A`G%LgVOo#0p1&of{r?dM$s!%tV|#IZzY$@zXev6J-=>KE7LX}|0xc(Q&Tm@D#= zjT^dt*>~dkmdtMi>{R(p0Y92w8ZT>h9-ouQ=jHyX1MH{GZ+ILJprI<>j(I#EG+y+( zX8XTWfk8&tRmN{%GJoD9Zu$N}tZNeAkK3{lWue-din7Yus*0+b@`|#W>Z)LQS$TCu zsH!4Z5v;8--Zc)ZtgR>?Zz@_gqPD!Mw!F5sva%v%*jJfmRaLb$HMN!HRiVn-@|ueB z#^Du}2bGnF4EvEw7A+h(Xa0=2OJ+8XYz|d7R96n4J7@lq=HavFFBv&~&f-NQ7d6gp zoUwRBlL@b5-#CBfoN4pHJ~$$%_$jL!UR_pMabS)<8*}9$j{1CJ?msPGpN599S!BZK$ssbzt4ZhH-~P#@8KEH(~Oq$>R>4pu_+8X-3qG zr!8Kx$cRBhAJcx;+-b8-bB6itiSj(+R+it|5w)tHIzygHkjKKuy1}gs-<|)W6G(a$ z@tQTUXz`NixlncMVeXvia~423Fy`AVcmDbN+PUV^|JF19V#b7eHaBoRaVv|razt%q zu)3G%s2!;%EgMY<{it6&RpwWRV%F4=vwG~yt z>T=^>O--oG=!s=DRpr&e#^GlF&EcQ<=7wxwr_U8KyjbF=tyl79% zt+$r_2Yel7C+jcHFU)yVF5VuG`KspEkG1hv@^w0G{Ws$A>f&b>@0qKIjUh~?eg^zZ)MSGl=;1>BHZ``6i^2RONqb|5bd&I>p+9MC#qCMi`7VVJ-ZdLZk1Gi|8 zJaCKn$OE@%k34XT_K1sHv`1Xrn)@TCm8@lM&GEhdn?L3H1KRh(d)%t*>u=(p6Tz*@ z9&vH2viJYN`Qg?$p4L=V)*45_pmDG*57kr!Yif<7Z$)*Lao{z6Dve{Yar_M(#QSLV zh{~EOqe)qr(IyluH(ms5%gxDaZIuB~Q*9i=tIXqLb#-pWS~emWsw_9=yfx*Op{lB& zVObdr))+_NP%s#(Hs-x$HD!&%%W88+Q*%CCR%;w~%MCb#NvN#6%3(U%IJ^ev7{_a4 z>QGi|%(lxyq4LU_%4&mCd8jg2Ra;R}ZICRh4H@$XV>(`z^H4sbyxbsB9W-XvRmNf7 zIPe<;YmE81X&x%8HfAG+eOWc14tSV9@cBu_h{|AjsJx=G+MMy1heB1gp)zxtQ5G_0 zAO_WH!>=*l2pv>WZYruj|KWs8{)R9HcF5S22g@o##z{r6yrR6un4cKaq@WRik*{Eg z^U;sDqP*GQqhAl4zjl5(9j4FU5Xc}@X6RW~UK^^ct~7!(=3v1ZqdJVzG|H{QsFK>U z>aq$Wzg3{8 z$?ZMlD>r}kP|vyidg#Bo3>^ED&p59vS*z{1opR$WZezVZV;t_AZ-?RU$*p!}TNt5a zE9d6s-?;tU*l(VncHgu^4hOg4hjtgn^VI3wPbRm25Hsg(<~Z*^1NJu#WqTO=%yHM; z|J|&ie2L6>ZhNWmK6L$IIls8wYIb#QKGQRpuVdl%=Q+lHgHO-*eExu2_w&Kr`TpV) z;*E>uoY3=Wu5JCgJzi)dvnT=i9BD^7_Q>>8x&0nUVLdYdAh``EpJ) z+A!hJhC@eBI&^&9A9D z_zgcgf|o(K3?si8?%9hVZTV+W2Wdg5&nWmhYAS-*Ys#_aEcV$2jWde(*l>b%9UoS^Pfw z=-cAw+^GHf#J-2v?{8F-Sxdq1_YvXhwd|*#u()y2@zdhDCK~t+V;g2Hm_KXIY&9SA`pAr#jk7#m?=Tw8n>J(N z0*(1|?)r<}T%nI?FUZ3Z$9?NK-^dvI&H0J{8d#r!t=HohTgAs811k4p&b916_}*Hd z-;1xuqCG!(>1%=S(cT=p+}68r-3qrJ&X@Ta_JFzJr4v$C1qHh8DTRdl8<3fy1OPBcKriBK}oUFsAEu7J$ zKCbnx^Nck8^|@2z!LH}9VSPtYEuL7PIJ3=_4%TM^>Qi@%?c&f*cWbRL)Q>u>u3^&D zLk=_U5ivHS4;|kyvCdptFm4^0IAy}*afcXxo)U>1I&rc|6#E0-2RxSahYalx=kWfp zHyfOrpSS7;RoL$Sa_#tf%J3Nr=FMAREvsm>Gv|%-7Y{dntyWrfW=xVA8W%2{ zJ7*Ezv}A~*;g8p+F)U4++t(v**JgkoW&fi()OQDBV%|Gz0uDRhfCG>=~2<9Z<8XMkH= z55)CB+~R(`zX7-Xh4a92e*X#U;P)BgHugd_+tRqc?C;_CspB?b>^JYB?q0~R`{Q=) zubuDfxH-2!|2~je-|TO!qYh%NxA5!lxIOnl=leHqdWheTfqLO~^uwlo{<`bfTb%E^ zm~kt=j{@7{cCCM!_W3wUe^LN%EOW2IeV#Yq^zq=S)^EUy%%Z;u1OMmikt}P4)>j&4baf|ha^@m&B zkM)P!8x|g&yZ^_$E@0m86gZGyugDntw=mx0eJ8lxd68jn=xpMd_OT$p-ytuqql=3R z^NL&KkMZCZ_hUS`rF>@pyD&aYzPjA~8|leBPTbzQnX%vKUwA(aZj+nW4H|0G$A4@* zcfZ)#2TaM~bpD0o;C6a=%AoxX9P^lD>e;*_UnkBO`<-yY!G=Lw8g{7v1B?0nHZzU= z_WQV^kHL6Q)-cHI?`R(f`^?4j)~d1X?;6GZvPSA;K|^x$%;Zu&&%|xY*l!+pS{CvBxE*qsGfu|XZ_Zb- zJ#N|I&Nz(+?UCby$5Gsl9=iv#A5Y`Pg;VqXpp>!SJf7lxuDA`o%jeIfJM;TLaT|MI zGJiJqn{na18MkZyCYe9y_B+gv8AZ}5bi&RDOw-F01KzmYGjZ`?j(?swpmcYNQku;Y6k&b)rYIi;U)F6t+o zy9&d>@mY3U(%s)*<4<0`UMVcDJe+Hn_RIO#?0+BMKR90(hO^!$&i9A!x`N*yj{OR^ z&zbv;{)P98W?3@e$4rN=0=#$@6G4yft%nxZufFSfjui1=c9AMu9a7{O?o%&r6zn`RAv6|K;0u*oJ@M?|atapW|v7 z%(vaJKl3yHJF16x@yoeg@(R99U&*)ObKpMX%lS49?_=lk_uZFqJH%VFU8BGn1=c9A zMu9a7tWjW%0&5glqre&k)+n$>fi()OQJ{DQ%;BIT!Zu#bymmqGeNL=sG`K7l|AG6Mt^OW(Mx?UswJKbzr*{$G6_bcbbiFVB6wwvk!B= z=Dj`(Pub-H&HLX_@;g>PTv&7YmPhF3og44 z_01HiLm=G8_ms*z+7UNgWIqnubU4$7%Z3-HZ}@h8U*RT(4!ivPg7MHoUcZ?l`$YtF z*v7zp`lBN&5jR$(4sE;h{$}0_xqI-2mk~EpJb&M_j)Rck6z{O+r1H`X0Q`Ka5Yk@JysM>&&pmOJP<{%oi;oUJvGT>S{iz z`BwO&@y18K_m}=1>w)&SZsUN7b+(Oz4lVHgZxj#To45gdW7~GE&F5#k8v8!|biX(| z&-O=+m&iBIw2I^IZv0_o^uGO3-{jGH{aA(@4)FHoyzlIDKQxXP;!g?v9$)d#kY(dJ zM`S!p87C~Luiru6SSue#37qv-#<$hS$20T%;=T*I+E9l~k#!a^KEP=5HS6s11);n; z>%#9#wit>pkT2CCVC!$&I_MC%q%a-Ycj7vj^VFAzF1W_hp~!mZ3HKf6KVP)pJ7Sc^ z_f~x=ey=3`yG(~tn+}s4bVwDbLu_>4@%W1s``lsapg&J_9Cun_+*#KMaJTa341L9) z68e40;-97cB52cLvV#s;^8LXC*21OxTR{i29!|O8&NS)}7_nBauBknJFUwoTHcn1) z;G4X(u=))HFXQ8?Y()8~Ly>QIJ8iy>d26%fZJ0yelB)`<-;gbDhdJnwzPK=X3UA0f% z@wk3m<=MHBUe3{`_v44lV!b!#!{7o!>+qQu;br9PBSLkMa67 z=VzS`^$;ZAFKusYzLxP#+`w^-(@xfO+#h+zw`hSnL~Qj?z1HD<^`JkVIo3mmtsa&; z)I+SNuzt}BI+*9V<6C0pFf9CZK2cab1V;7Eqr#y*-W5QNH>LP}*z^zZUY57GF(WhQ zsV3h^4t$#mba>(c;c8f)k7%IH$HrE?ap1O18XQw-=wX64|d?o9xse< z{Pw=%<~4Ws{1y48imZpG`}jJG`5jpYJo5T<3s-;L-f?_L+3MjehkD2!r<|8Kl>_Ur z={wFr-$;S_Wo|Y&sn6phH~UFC6pM zWgFLDbQsr57ZsMbw2kjy9Qd|BQdqz6y~X>*Muz&m4?Xe)O+s{^!qyREFix7+$u_}CwoL9D&)!=7=KWZ|fkbiRS^U7h z`Q&zQl;4Rug#V(A>sV)Ls5A5Y;^y*4^Ug0i7Z+A%EjGRZ8{e2d-@KfeI})~j{N0Ju zDyUJ(lEU~l+m6Sfz0Rq|yruN(%u(NNTR&bs{jskp-`)cG2KL~2H|zJhpWbPwxbb}p z>u;%Bct1Ah)v2j3=II+8Q`k6}hI%m9VcrYvv^~~uQokM?_08DyeRb53Z>SF0rG?c) z>}1}L&Fh8jR~&qI9&Um9W_0>%jnmcX`cV{WFOyWhHUgO)^GSR z?eQTW)7aB(>ldfl_@;`?Th^Ah_fMGe6Ls!Cp|HI9>v%g;-y=`B)i}E!l!MOb^QBaB z??blpmQ@>X{UtTZsQEh9Zx85T&e!*R`PzFZZu^Oa=}@v8Z)f(mV{U)aye}wVykvoi z#nnUbJzi(#xmN9_`8vc;DvWP4rWL1et4)WwHXUO6I^=lJ|01^f-O!hxx6)Gz(;)?X%{u$_pyj(^ zoh9`7I_8bl^5c-%FUGx^pSP|8`9`2$nB#iIVSA0jyajgAo=-aREdjpk8MvuePRtw6 zGN%@%um7XII(zox5@UQA6fj({l)k>EdEQUtAkN3k+rFDkdJSYl@44nf+qw{>K}%2L+6mEUC}eQQuOVzAqhj?#(8q{U>{0VSKwl2lM{l zFD~BkXgj9)I&p1bxCt01O&yj^xX98WRiq9<+xYPCkvDHj`F1@}7~dr1ZEFK?kDU%W z66-9Z&zDl+?sl-XR#u2TNm`L zPi}qG=4SeYpV)?lofoEO^_>^)u=T590n~UC*{Cqw{wF)3zJZ_g$A819oukRb6#@Nd1H-rd(I%? zp&kO1jPX9aU*9}x$g(kco5WP-&L<=I>h~bxcB~NedD_6pn!>$ERt_%1g|4= z-7{1Ef^j-KC}6x~sUmSZZ1dl#vw}5{!!=S|F8;4tmHIUYA#XY=|s zuj@tr`0XuI1N%?>h{DF54Cr9$yQ<6R)ND||c*$Z=f97kqA6Y$g?8NhCo)`Yq`oRMh zuD%YAg&De#*O_^o-{HESH)45L_T1QFHu7!!+j3l!?{7A~2@ibpQH|&A1Fos>(#t-u z^i36s>)XArUz}{i%@m0nIGoq1IZu6NtAmYl8x$~JvQ&}vkOCddap$%juiOhWktq_l zWILWWLs<6S+jo76d}9!Y$=&ToR=-i3zDvK#T6s$riJJhvW}W^0njek3HwFcamy8Y3 zKJU(%)Bk*%_w|eUZ$D$*CzdL5-LnJun)Q3KO^4V{#qrJ9ba?cd?H)%RGDYg!8R#2# zQZ`%`)gFJTw7K^I$dB1CE*kZXHLng7i5s@zZoS1NmDn$mMdGHQy~%e68*ZjpT-*Bk z-nZR14f%#2FHYYid`@TwgYW)_Z1FPU28x_VwLrfx>-WWBI~|3%u_F2Ucjk3wj%TZa zmzww62aK02Fts=x>UZG%*qs0VeD5ijBi}@kxPdYo-}=4ZH@Vt>LX-L5?fdMnW#eSX zhWnlaZmdAuCcrhv^@p!MYDYU4^L1oOVSE!d+$XQd$89bUxBmCO zPo@Bm?Ru(l_Q^95fc;b#`d*f|He23yxi7ySx(ejmVZ+_j0k@|>+%6mL4i32f!wRd1 zjIAEt>OL~B&ioG*cHf|{ysy8Fx+h=XrULnf;rM2bJ0l!$TMNW31-|CEv+l3EoK5Q} zQy^{_aLs-^j7{H&;zkcIEN_8L`252>z9k;5HE-Jxei8-ZMuD$+{*q^L+lWTVDxM+;oAsNn76PPX5-sZBF=Uix#GD%*J>9MNN6@;3btvjAxJVt+Hojx_{`bEr-*AC^vo_p^2jBJ%#ce7OmsM~bOnrYCf7448x3xgrxb1kc z(LVV)WD3M>vEe4x&DWuItHQ>IpiPG-4$0S{gRUDe!*rJ$G6$WH`;Pc9^XWPeB+<@>Fd9?J`cCO zK-_xJ!Mx9AhoAbMD-kGChgO>ooBeHU9^Z63N2 zPj?KNn1@>+-*(W!#GN|0E)O?wbYcCi+lIUO79;X-;|1dO*l;)8Xm}oOTY$4kWRTB)jT_q7>wAoO7srQG zk$f`&j+>jO?tA6Oh?^{O{h`&iuCd|as}>?|sz}@b+%IbKU2D5ne?is-TroBAu_vLlMa?Y8N=LHLnV5jRjIZUA&J=c(_{ThW2I z$s%=#rFgvC8@Rt7du+l(hgVO&NfY!7b6zs;$+yo!Ty|7(d?P#Z zamPGf9Q1m%HSUCqye~chxaN6Q{g%^TM82uP#a+kg0$g)^*dn&h69#U;c*(*=>RZ1D zKW>`1+uCqrMdBtPKW04~G3=UCP>0yF#pTTh&!61fz}@txRff!i0>(?0D3WgsbTH2^ zR_*d)7xGOOi+gC_{V=cfvI9-7UVdc#A`Uv3b$04jTNuL{w+s~d9M1NAc|DjqG_4K~ zMch=8Iz;c_{msnV$3I*-4sqFY#nnS(zdpX(T~-@J+}MAM!)>zV?d^WdTPNhr)c5*1 z@BW5-14WK!SzA3U-M7UW&k{wBXBp7fth3--7wwIFS&`2-YI~+{-Zwb=_TLaUQDi-Y z_viIs&L_(|Hl2&Ofg<_V!*ia@yfw`GTNUDli^PrDo*(u0TAx|tWTHsi*8O<>oA)tI z`D%wtkuN)@xPB3U_U1ZmTk_oDh#M{vw+D1E>+J1y?ua37tVrB$c;2gdod0h1jw!@V z6p5RJ_U1fw{>ZzILEKc4xEbS zX9?IQVH-H9oSDC2_@&Hbe3Q^GHZ>Y7J>ush488&5C5vhDmEp$W^I7Kju~D8Z-s?ovfff0D z+AQ!jasR!f4>w#SZUmmEYtDb~Zk^YPd=o|DX5e!u=K90Ab&(X}24)o3k7Ll@9DlES z{M#jnn0fUZ%0I&d#}Zm$Ar~6?y+;3hv7=&*vBXxYty~ z%@ldR27~+J%)I^M_k(Xo+(2V-c?&~(lkZE1maRnGSdq91Xm8fT$jrIFB5txs+~^*B zerEQI-3M)F-gjlZGVV_;61N3#&Ev)8FZ}i+;%17(jqSqunz*s-4ebVQz<9|LMc#)O zfa_Lfzu4*cuVctJT;%nvH0WTCXR9~A;(EkQ6p5Rx>N_8L5xK84c#I{&-j*6~Mn zyl8^Yii+qzs@{RA=cOJ0rqUXOg-~*1tBs*n%V{qMSN2A@Q7wu$RAL5pY zBClsP!*#OU@oh}vI>b#DiQ5jiX8neLd&oHZ_;s$r&^M|z!+=DjgzxhK3c$xFb zAAaB90p!byT(3?|L6-B470I{W zrmrvh?^47~Jy+cPp~H5a?A_gm_S@&ln&AAxtcS<`d2A*ps)zr$YWWSiY<&M+Am2bf zEK7XC$FmaSZ+8xT`OVw|7#-|nyJUP5w(B@oRxa%~edD%u#9w|L*Kg~;rOW!}XN&L4 z8pll@S!Q{0bruI)bN%dr*$cZq zJm1&|KfVIzJ0W8w*<6P)`^BD}@0`kR6kwHaWOWuZp2TY6n)Unp((8=V0d5(%w>TYI zU>;@8&*naIh;iMC1&m+q9~s{y@ZH!zI`}W&8u|j?SaEz?VcZ#P;GXmNo?mJc1w$F% zF8E#;vwq+BW~jNmA^gM_6!yHq%)vZw>l$dMp0{cg>JWQTTL&}c`9IYh*X$QJC-Y6> z;lhq@9md4LtTPk$*&(J3khdb&H3D#-jX5uA-RFScjg9b=E$}{@kPWxAHUIv;&@qLb zw=~1|lbQ8U(vP3Rj@bC_d|v+jeX#=hhW-z2*8%55@wS&D9H0`ahZL74CsG0yj=uCm z0R#BQfG9x)4-pL26BI&|qZ$O^EMOGDLqQ_-1cX?CLlA;e4it&fPEZI%IQlnlc9zV} z>}HZlzWM!fbCc{odGgHrzVpt^W}}4dOuCV{@ghK6FZY+h^>Ueld;@r#hx~U~&bivC zlF=jTV&=!`#PwX$zhuVF3@3;uQHHxv<_vL>t=EvzcF9CgDPoTb8 z1mDWH+x4J3%qDn0o4m)v`vHxo-vZjYQm{|VkG%xnyDqTT_jv^Q2C%*m&w73P{Q*?T zI>MZWnf^D2%Zyg)|c#P(oFUVJV zIJ_^icm9R15UxyPM{1k(n?lStzdGA4Ve?Jz3Y9O+T^3pT!@dYiVI)tSe(b{bdl$m` z{=A&9`KA}!1LTwK^TsgilfXSvG1J#c*h5ae+03|^D!8s;C;UxH;C_o|r#cUY{eb2# z_Cu>BYQHIQ?#E_g9V#N+VS5j?rM1iy)WK3cJZ=`W|2Sds*STE9h3j{&FPiZFopESy z)awNFM+~)HMbz_Q9p`cP<*MR+&$A3S8_AjXNi`Y1yiTw@6w_6F+ zHwW7T@a7_WC-%LVq6$6iu&36 zN(2RQbBJ;CySLc=pT?X)fz!cR=a%#YKs4&WERR)$+8 zfUe_@t(ft35PaW!HvbTfY8T|2jDM#Xbl9H2e#;>E&N1L?Jtn4a7LE@vZf;4SzHY)V z9Jg-nq4jkM>YGcfPj;!@6V1XC6Mu8Cok3om{P1We&6n3Uv$Jfh1I&+WPdd!3Pi711 z;KBU{e1lc?4B+vjUpM1xN4K(sxez>R9Zfn)pC^4IW@lEM_kjRwCbBwY9T&s(<2VWN z*OtKbR3FiAiw)M5{et}#D5vJt5Pu62xQ-Yk_>L%YFI1!kG;mS4kK4n=K1^E*8 zFe-uTh%(OC!N6W^n7@$LA>*JJ-vVO2`kn;NFVYEnsA7=+1_k+MV|^iixT~%830enU z+sqzZggq24{};H2uB7LQ>6=C1mNCE$2;ycFc~q$c>fj~#W;L`h^ZC4UTpeJjVTxB) z$Dxwwm3C8}h2dUTTE z#y7W97`OWoHs8rwFNT{&tb@D$>(M$G~z=^+`kfO>L^?s1SGF`Oy8Djx1^<3I0xnpV;TU{l&98XmAh2Z6tjqr)+A`0_$k)xr3qPL6LOlDtMo%W5+5ZsZ>m%}=7yIq*LUM`bf3x^t z$NIv2e$=@`KwDSRj*9VB2>V@`!0|%96<$X?zw`mLUQ#I36?f@an>Wn*%})45*-NZn zSOQ`?xCuL(Ui988h?#88j(x?f-yDQr*jBNAVG~{dCDwO(i_K#V$Dwq>&Qb=HVy;(q z39cii;dM_~P(Egty{M8|70sV9vj;DZXQk1pH}@4r-d9LQ|4M;<@r@TwqTdEKo5SP} znJ2{T%ue{*uDV}lBdQ_3z&V;?rh|`|Urao3qH8o*psQBrB4a9a|yq2)~NHM;Xx6eG}FQQyE+em!2A9LHve_y zi}B4S^7UWD?7>jq48o6J?#B9Yn&7&TpUC@0Cs5xUY-gbFH{^8T354r zBY$7m3^xzk1LP%*RwOPj2@r8IAZ8DS@hpqzx20cJW%|upN=%2Odf|PX#`hP>L~_Wn zbex&K88}YD0%Gn}c3sZT=WD2g2kQXqJH>L?{4DEkFAxRaVd9rB5JOWrkBhtzw- z_$o`(xKkSGaB9u)sVF{#y3H{^>i7^kp8n$?#y9JyvlxFX5RB{jgkSt#<}K#>Nty@U zMxV~m9 zi`FBxV=HF*dWpERu+i`$G-|FOUk~ALbrYzsjIaNN{kK0~D~_&e(wCqh-yo5%w@6@K zl1I#2x{39h{sZDx5a$oD-goHFsc4>6NJjrkQuO!9G4wZwKfEu}@6g;0Axz>=dTGAD z6(x?>{&gQ$?HBT$b0;UipgkXLZRT&O*pFeHZ`pLnPpFck#f0O`aIMwVI1Bks$=Nbo z)}<>sQRtvM0XOW5s>5BV-Mz&Vr;Uz@^qiR==U_hu?UTIMZ)=}SDWP6pnq=Yko6-B) z2z}cnP~T)6C*e8}`+y(T(C=*(I;GF$MuQ350SJ~#l0KhS{gL0c}L&MQQvRd z(BBknXW+*Jf2^{S*1;vHLpsrKPwg3&Fu$;2zL1x=#tu%U`DP39O{pICix+?CCgK+~ zl~CKVLd6BXm0I0=2vu_Eg(&}+`I`^>8~E|;7q?!Z;R*zGC_p1SuR4kfI^hhjPy;!5?^`7iKY-Tdr% zZQOK3KW-Z0W)c2&C~JJe{7pg`B-jJk*}ot5O_*OO=t2z*_hJHZy;ui`>&pD8=TIf1 zN7Mz`uVKl>xNv<*%dsW9qe?bB(Bw%o+yJrf-ywnDs|yf(z3baAP844^5zqSU+R;k0 zUj^U4%;e+WdD=_|55|Rj=V;9Z=z2u;NZ-%#%{MLe)qE2Ctxcz6g;6D=N7TiPZ*uK0 zZl?s|reMC1PaZu#Ghu$L5IXellmzLC9JL7OKrV)r+)Vq92H-L||Av(9B%Cx&Z#Th#&fv%b0qF3VIE^R0@{er<#f4M**P z@l98LvEx#6jZ}w2!1G!pf-B=a(^i7LbV4!eDEB41n`6IN3(v*$Ll+x z{Or=8gym;hSYN;mG)l^&`DBg|yU&w{=(m?o*P2e_dZWZGc)w1_547`rM8EaedK}G; zs4`NFui{Ys4dP_E-tQjN>_Luxf0H7jHvM?s5*p_dn6C$jIQji6523iOT8<-5zBzSO z9bh~z`0o<(x7doA{km|T3i;W>1kT^&)~dfkKKWwfm!3vC$mn16rJv~h*o?1&aUrh% z^HfErrmt^oe7H6O_p{%t-NALl$v2tsx89Wky+azr@W)ICUx8{5u&&`YScmZmj`JR@ z1H|9VT1B>L`g-Ej!H369SpWU|hiS_+Twk2HRy=M(-q)|{*4?O*(Ie_&rmvr{-)Fyd zpng-2l%4U}Spgm|Apb2=q0O|YiQ)rI`C@$`Kdb%t50_CT<5Qxl%y4Bi)3zW47>Bx^ zD+S}5j2=-JGh7GOF&QE4S<>jv{-!HVeS^5)z%PpTIElu$LNfYS^2CX2A;z}}g1hI17&_myAe(Z|#KL0^%zYrgq zR@#`b{K1Oj8SH26FImd1@l{5~7k2_UK9oebolbu{1XVE=GrtJpby~dG zuohazo;>>If|2oWc07(SQDQP`NZ`PuRb~UI|LcR1?*^w8DF`A$_sQjyQO$9 zjjtT#{MZcFLiokS1kPiv)m42V-?6m2GB%peP99^%H@HH@g>k-N#nqXplF9RU|C`}v zU>$&Oz2Dxy^ZP?SYt;L^hHtF|RKDOBJGac7p!J*QSbTQo#C{C+@a*(UC|anWED!@< zqw6)4e3dWEv$j+mJrh+i6*GOE*nVMt@yFT1+cdsPoc3!c*4JN7;QG4sRk+{Uznh$a zXv?t(VWxviQE|b}{`%nI5tX*QItbd)V z1FRD?Zad^ZO^3jh`24~}tiw3&`3C7wNJeiVx#HAUx?9~phK-9ZkM==PNMAgs#PVMk z5qGwD|F{!(JaO{PNmJK<%OIM&*P}(>1ldFIfQoBDfXxQ%AE41F$3){nQk98ePzs_r$@s<8o{Q~@WV(FBf zJRJIUGh9F67p^|`m72dPajs8#i1@pq)P=xq-E7xM)jx>P+~U&D1AjL+XJm@nAbLsxd8Wnh(W zU}$`}4(!LUuIx*oJt#H9@QJ%Nr(;*G>g}5{P z$-B|IhN`a;uf9aToss+Q)^O!G*Hc}0sh=0}$!#5bjMH$XtMTa&!0{IX!(bTfV=QL= zW@5{UP*U6{kn!rKQAd^9k$FaK8AUn^Mo0$msppZR-;E7 z4h-|M8LkEM1sNk;jvdZZlZdbO9ZvlaC_7ihSF810N+ua+@ih-Yti-yfhqXo}#z zv=8%z`Fz7KKSzJDV)5=Xpo|Rc4E&q{#8PF=ghH%@zyR;fBbUb3w0i)gx~G6=+(M_Di~3_-s?GX>4(3(4qT$@6BM`rf0S z4}LLW(cfrYF1BK(uZ-;h`mOoUiOV&)4_^$0DW6`y-@#-4srTLiZwiseXy4m?c)@Z(OXEKIPKStap5}X!5{um1>pj$ z7afxc|?5n>u(VDH}|Zm=K(*K zVybVaFmB&`=r{F9C0@RYiVO3h;SCe_{kKf4FZA2j?}x8baKyAM`$+W;Z zvcaoXw1NtGRAKZudh_<}5~v?zDP~+`+;1?yxbmp@{DS6^O5i5Hk~rLK+;1=*_rAIv zjhnF*GacN-x?IlrG6S^U^ToMdE#v$Q^6JkTRrokIwi*leESsXn0l=;0YMC%x7lAu$ z0^q8Od1CYndfwv3xG)bGY-QtbhTy!#Un!iYZp#kO-+XcM^I?C#$46_K^%7^{==7!S*GJgH)n%+bnIYPozdrI?o#J(Xc<`g z+_CpB`t?A2v2{5G-{&9Z7nWW_zN2vq_&U(1gxU@Qw_a}+S3WGJZvpmW(08DLzP6%b z`W6uOaJd%yyK-54zJ@wv7g0Ya*o0iJWDWYDTs~hzJChozb_VhH`Mq;a(YWrr#B}hT zR{a?4A%AD_tu$`FpbiCFi1h~p9g>QP@pTcuD|dIVuJ6!%bAwzvqfZI7J;d){Z2Dyl zS{2uqpdfC5h-ZBb;+b4rOa~=Z{hTlk4=MJ)T6(tVw}XD?>R@PR7HntWZ?72mTb3YS zANC92o0)mzdxr1hVmkPUxO1Z3Dkh#O{QGzt>JY^J2J4gaPyO#(nr~i`7+)vuH`qTe zu_Cyg#!am*hMRFy^*6wMwAqm(G_He>Yp6pqwgI`W_OvMb>L)h;x2KMXi$<^18NAQ(!zfCgew^Tvg9D?sn1HZ`n zl*`x99#RNx_ZnD_FEM?y3EXzK z+A+9RLENOGYW#)VFK6MSkJDl){lxhC2);$iHDLG#_~V74{o06e=<>6hnEUV89b$a5 z28ZX}n+o0~IBy^~M{#|tc2Ys>D;^G?WU?+6AVW2}=T`sPk2yR(_4$p@wHr(?m zeUNV|f4q?ClTbUUq3UliKmPpe_zMzR$B(6$#fNM>AAsM;<~R8H-9j+-wYzIS9^sW-&_sE_*#g3=Y9i!OG*{P^>p=*CWadzboj0`tAmHHgCXAn0(Zfj zYPs}5K|x$gb9H=!dEtxy-R?)@rV7qm&}}B~?CVW#cktixl0rjAY@3Zkxx2&h_t1&Y z(60{aOX_1{{bnWdl8pWz-E1qsSJqPrwUi^O4lo{%dF0GG>2rgFB0L2;$Of<5FfOc5 z?z{R?A1T}5pa@Ty=^Mxm=f8)Fcg&(8tYs>P`jviOYn$Q9__~U_(ShU2|FB5g!FI%Z zUkQA@J*-!+xq4zc!j;j#k`n#(_J(mMw`tgZ7a82g+fr7{&K$&jI5W>zfXiZZC6$kB z$k$2S$9vnpH)iWVQNzo}rB4a9E%;iP4td>GePJCj(7tjT!#9uc zB(gI@9sIc80JqZn=VsCn9znj=E~;NZoP4)q(pegp*EaKuG>i-SUbY2R@o?zZ&2-2k zbSQPE@VoSRN_nw`L z#fLzg@xg=r4dTv>nbXeGpEId~n7$cUUzi76@>V`ahyB04ZO1k8Lyzcnd0$LRy&}}mvGKk-eTJq+#iS&7yg86T94>kV6`tOnsG%CN1_!{aPz;UNIf*8?x0uvt! z1of3M-y#V2B}m$1EN1!!aNI$GL8`gDD}*0iNr`eEKwsyWg89NaSIOS3f;v#t@K+L? z7ZSh2^ht%oRcYL`rebj?kBIBi_?8>A{45aT^}jS9KarQ*Z}59bxq|vyvA!_Q-+k@q zbM*VB_ZHJPAKNeZMRMr(lJv-yW@7rfiQhHKJb2cwM@9D)ixQW%vsA1D_?xY2eHe~( zCHFfq9Rj%DLf7v+p2n=67(Hbvf~>%P}E4BDRy5Uxp#OT>wdS!BQ$Pc6c^W!ZxHtzym+Jh zTbpUz?3P>|=u<*%1=|_;#q-QboifHCMbT>Ee>qor|p zDEL9Yui5x!C;F|wLBHiZ&+RuuJ1f9CK>YPSl)RYcV^iYP;Z3XquF?08L%N9S;3MM0 zfOoFtpfCW}VAEfQw60QQK|8<6EYW)xlSqe|?D&u#3>)-@h9% z^TO1-#p0w)=&*5J4l~cnds$2e3)TVrt!jz)defgN|4lJ_$RqOVnI#%CI#^4K>5xL` z(B}ZFgY^|L9b`g>*Xpr4I6oHC!Ajt|`?I*I9x>c3yblTStny=DI_Q3LuMo3eFUEy^ z^y+`^X7Y#Z=LK>1s__?a>lol>^%KJlV7?U)Zr;>eRcIY@`-|aviTg**xo2m>)|EX( z9`%Gl9%U&nW)Il}?ysZfwV`$3wavyi8I3%!Hw5c2%b#w*tQ%Pd2^<8Tj1x`&XW##Y!6_)^9c<-}!t03qBfG;>?e^`X0vm;@W|0 zQGKPS)bRrH$-1_auuuNj+WK$6t>%NgH!;I?5c-xG@i8+GaC{*a z*Yk+Dv+3`JZFv0X*SY=nL=ujZYVE*n(SCChI+QceA@@r$9b5!%B?Dah3Nc&{#)a#c zMm8^am)0-kb+LR>!Q&=u6)vtVL)xP+PBA|Y5cg~AeK@_lX1`LD`(#{uI9)=u2V6UF zEou)wtS?-DHg3?B(RvZkZv_4%)^851FN_x@4zS}}eviog#?|48lGrcQ+JW1mI!IO2 z_yRikXR2hw(3u?v3h%hFc$3y8lt{gat>Ir)+pUm4>jA>2XP{e3#J zs9~EYmY-P(+_5`Z+|2)p@l`M`^xKpwYnXnMu8ZN?2z~2il^jm%;Co&S*FoU!8K2DJ zmKD2B*HvBh3s|rIW%pu~?_iIQ^Zvh1%opNs(TDpo-w#MBFUXg`JvnK69<6Vnf*7uw zzOSO0n{g~_Y! z%c2|SX&urDeJ}ND$mna2k}r*GPYcJh3-c#2I%G$QOY7jk`#3OeE)Cr`RP{_(l=A@1 zk7>Rh9Cu*c{A2a-7wPvch>|aj>m>BO(xcQY8aJ(5boRjD68l*mgZn|-qP(9YjhjL6 z9XP1?V4ANlO1|`YUaT+7Tb_LFA7p20Psnk`2N&UQb(;3NOuw(?sp#~j&r5zbybg2l z#>BE3UnNGqG_DoT13-rw_icJv!*#@nOZQtgO4PNuzUbz|LHd2Yf;#w!e!Jc1E3_$d`89J)8B_Z>U)#K@QCW9c5YhmT*Vf~3aw8{_X$(fyW( zb%1f``lv0B((juqsDq#AxB8ziMd4EA>x)qbns0#Uw;f%xnYbPlo={f)pkPPX^m_DtLdx6sIP{n)#)u%eIZ|;ROiLlAJATivNq%E zS*hYed?@*R%RPv%jQ*9B-(vF%y5EwCep|A2(QLpZi(9bYoLFDv9@5Dh_cqn^b;PM} zZcSAOm|wKN>Sy8($=&FGOhgY^Ypc3rFRlcujLMtx}=WNZ&$zcaUPIz_*4fUg66N~j%}7S11LE^{F}Q+vV_ zBVQU^!S@k>31O4QKOUoB&lJ3mfSrgtlS{Do=?(Jl(@RqcwPlO?yX|nnN}06AXf;A# zGM^K)2do3c$*C(EGPu^YVz_=H?hO4=8mIM}FUGi||CH#S)db(UYqotyzwQ&ff0Wch z9S=Z<>E-KuPvZvp*CW!WgxY!dK2Lz#`L8_;U-wI5`eqXM%RJGAyzXgf=l+E8; zv6T)KH8Nin!&T0x<0jZch1;{y{8(QCL&b0d#Qow+COentQPG~!|HN=T*dBmy&YrUC zXxwbU`!NLw+@UusGq_Ht7+V`ooU>_2r=9|;=YSFO4aW{H8rNaoUEbinU!Ew(V>(Yw zA?7W)SJRi$e62mATYsQ&EqERP^Q`AGC*;t$_9$`b^V0BoD#Z1XuQx!$RUsMuD+OZA ze`&rl<_r6q-j{|v1DIrSMah@OO~v}cJge%#b*QB;*-_%^&q6I?y!h21uBS$M|2~>; z9tvbI7XqR$>}G}`DXnL8_Q3G%q0U=i9y|5XPv6nA)1Utjx**>~~^;@Sw@0ne;wa8v#l9bfu$ zW)b%V99?lZdtF78_XVVNu;Kk7Scge!y_Mmc5hY(5*MW6_xPIX51?GF$o+xo?9h?O2 zkCisPq{VeP#`wVCV*7=8%^$ZDcl}u|(QmEqWBV=V3$eV!h4~gne4o0WIKG(}7vf~g ziPf3;8?77NHk%g)@pu8aW8V`I*_xPo*Z43{J@T3{v0?ZfU?;mBi&Wr$I z_>vi}hu~YfT8V`5&BnOEcUif_@pTY+RE5qAzCl;KTifD(UIk%bEQw-aBZx zbo})bcGj-t;W0Fh>zU}rAsW|5=zGYz0o++v>`~(CPC^Yo5!Z`VyIo!Dx4;{*<$W}6 z9@YW+ZSj^{BKjKUeVI7#gMRD$&1MEy5u9%ZFkhGleBw#m@44HEdExbWZf3nNiGP24 zTG~)Mfcp(ZT6lgBl3BG#PxO9lsIMFA3p$i|>-1Ur%`=*djhj+?)t=x@FWuZ7<{PJ- z$tZJz`4G&z3%$qcn_r7NpEuMYi_oF8fewKdVmdgmJ;3_!q#f*ivE604*Y_Fn^$>nB z;SB2+zU5+korL`^{$?R#zXj#Q_+}IOe*MW6#?HL0#rOta4co&q1HL(p#O%RK@Lg}f z*Ro2CuMOWfA6wX?pRe)FtSTwFst%fa!X2m&lrlARZ(WOH$8DxtPzh#Jpeycjk1 zIJk$dD9gCGhJ1a*crjw(7AB9%5yZ_Ua7P*7%3q4{^%L=T)}s%e(}@6$A!7FH!}b9A z!;~(&nE0D7$TyGRJJ*13j^KWw6UQ^Khp`6sU|S)kZ-D5xHw^mCwUUbqy}%S3VZUkZ z{$}jg=jGxW+HXF=x8r~x8T++W;o>q};R!!s4~?_#ew;oiZ7mnqkZ+K%2gNloNaMPy zadGKWLTwk3|E3!8-N3~)O5>O2ehK5w6b_FD?c=wHbZ<$Xr9 zbqzR&EEZz^7C0Q9zxkq{Z<26#{?EqyPLTip()P2<+B{Z@b6%K-amypzU2~Sat>MZs z;?nCdHbRGL?Xy3+^Fi=G!6?_)Y1|-Qe}HwwSCm0ZY25T)(XAWN=P5`4m>QoG4>n%e(*(f&;j)Qs@~}@ znb$c_nDI@0P~{8P%l-S|59o3Q^~gY+{^r1T2J@B&3(dZXaAowb$DjP zn6VUj(-Vc^q2PxL)$s7)$6u(1hw`oZn1X6}I5w+~OjN_evqgRQPz?`FU)nE{iGF*n zN#Qy)*CfGp&lHRceo^z+)*ZBdQ^v%%?rF#V2Kz(hZ?fYM&7W>-I?&Hs3BEs-e{3xM zI%e@$FD~}m_kgB@BTgOCiMZ48hVxyTpI@-w{DfbeJJTJevoRGj9ej8{7WPf+ z?fC82m_X6NX1IQgTM8X>`oQOm{qo+&3^zdN(ECUEZ5|H&x*4vG@VB!ct)57qC)>rw zp&-HcM4KMWdI|kLblZ$?8onPi#P*--jon3`7Zm(Gs-)HGx~7Z(8;+SVTEq1%8n$xM zc&%k#oAFI@spAD0ZtAA{TGI%5Yq{&G^eLfsI_@`ANjo0A=elN*p7HU;GbdpWkF_na zO2hTViJOFfpP>xmd+fvenY`NYLlRG#>FdLB3$A-@^Xme{S1roN@%5Y3LDdoB!;p{a z*fiW|Ycsy-*d9QDq{+)h(Rl9lV)o#~@fYmj(B8!DXJui&u9y?~$^mWCnFZ$#Vdm)eNV5!`O=F4lF`9%uxyNJUFyN}Q~ z!LP)0aQvd`0M`{)9PmGeZ}N9y_G=raj*ATu?#4GecGvhSmE(&$-uqR)ut?L~;C|-X z`38$hR~IapTu-dfz%+ zJ8&&}A2<*C<~7(a#P!!lO+e$OB%?>v#Z2D}V%)qk#nL2dKzyJXt~6HF7sj`i{!Mqr zH(#9Nn~ZVM`gEhvrAO&G=>#>oEHgc%7~r1n&6%5{CKo)_lMD*m4a8i+IB zk+D4h-@s0Ev)UMo*$ECD*P-8j>)d!}jIgG0$BA*_dYC`l2O$mC6(@ha&v5_P+Dz>? zSXW+AHV>se>L+uYSMyhg;Pph`*9i>uO(pbIx|{(Q(G@rU`VvFjv_@fnJNw^0#^2IY#QZow=rH!s zA|_J$`8w!6pVsga{r2_fPy1=lYqekSd+r4fh3)sgCWSg`_UrpkwOYGOB+va3@W_(K){QkUy;Je_Hy?@aos zZX@`PX_W-aiMmoSlB_vV7LtSY7L^~!@ZRQsN{C#Oyf0#LO zP&FFEH(rcyfQSzt&l~*;jqCoFd;Jc5N~rA`8O|SmKXPjieNd*0%h%A(>_oo}>3d7{vpdSx^d*yj9h3e9-11@jh4rWx?s+x5ZiHVCPT=x2)WJdM zP+iWePQQ7w;Pp{n+;89zs}_96?8oLz7Ah{9#z_s%d}*Wk<~bs-gQGZU*l$jv-yYnb&e%iJyJ9*> z<<-0d{CN5!qnZ3yJ|(6@3ej)#iao*XZ)UtIhAaJ}=3y{ieEP*x>9oEnZ;R<5V;unZ z<4JFIr*V^~is32*?xt<`_os2)d|X3&@YGOsfEQovJFOdyE4?SiH-+%yzlWT>O5^76 z`O>F^+6rM0Cp)~8OCMw(A!ZK>!8g14I}G0dpRb|5F2di|l&y%ayF#9ciVM$U)8~un zYbW?_KmHTL*P1DaOX$0F-kSZizDWzja2-T^=<@G=w11&5$^744H`F(i(0642=9zj_ zvSVmpJ0X1ym`w4rfb8Df6yB>bXsxy`@RxCQ)vGqf`=5huSmIq4dW>-j*e z-!cilhXVr{zVb9NTo0k|&OxlcS$(+q1N{+0Z4bfs>aspgXq zc>gf?9cV{cuD*u-<|q2C;hXE=`UhRfTFAxK9j`TV2s`s^o4QAPUaNhAIwT!Yb%1^g z9$4N^!_(@tabo@EC;0Z8XJz>23-VR)@72LVbyr6rX5OOlHml9%0Rf`lhK{&&gE{|W zv3|?PI)I%`?A8!20-D!L_AydMs9l@C~A1ei}joIylM|{J?+NK{)-u0K3_w> z2om~QD_U;Rxal4-9g+#YE2px2^Z0yeDxtQY(D%&V8EN!ENuP-EwPLnN@hGqeXw&G0;{@0?uN*3y-f?P5CQ z;`Jz4C#ZD1*S6U|4Z(h7E2XQ^+jb$IueC>id1ik9M9$csJ>XvuVwzt|7 zj-&DI>v{0`ux{j8^nsP;%WIq2gBRyJu-~$~Zt*KT9Qt)`ocsy@K02-)xQ-%D(r*=N z`>+nMj@bP~iN1yhMR?Lw2O^JZ-GcocbKiEc-yf1*QthEM;xw{`(uAhwZzhK8pQ7Tz zbrlb9*^gS1Ok+oCBOMImPI6-v_bznu#F8JJr!n02$m6CNu8eWvdamaTzK@yw7KX$0;%16=p( zk?q$sP7;1`yTe%+Hgv_xUzaoFYr}jYKHPkH2XkF!0UuY#Lu*)x_wO>VWUCx2y1LTwSUVIJhZ(Rzb&iZ#?{Vk7= ztJf8`YztL?gLSzNyopWVgRR#&L_t4h2X&rI}f49$ramymW;)l0)pm9@=ij8kM1a9w}EUv{T z)^C0ScTD44hOg%g*UspVsJ4r#=YhV{*R%RcK{4E9j0^g9U%r{)D;?qHCB}T6;rKA~ zO*TGco)WX)Y;3w6&#&g})bfYGsHpRY5MTQKMpIH zn~QN_9O~nIeIo%G`Zq)H_q%hOsCEz6_pNDcsYT*Q4xGU%aBfA4~kcX`SCsjM1Z_>vx`w93RYd@au zaGeC-Cu^K!_~sN9iw`*jZpX2CHkz-qzZl;XzYpCu(>ELcz6b=! z#dTW$rukbS&hMkA?o-!cVBGxX=aqJvPipb#^rhpO2Y>Gi=JVsLR9!;jN`1KZr83UX z9t+3c)~VANT+bh3{^oo-yubPN8|%<;gnPmjUp(^?-veBDxXwjJ2S;@AjMmqOaUq^L zep~z}jhj46EUxEaJA?hr?4}PQcUE;!;?%)U@LjX77PF3+F32~T_`Tco8Ku6bb+8VI z&W~w*0|ejiy4|;x#?6V6FO3_-xR96JJ=OIIjT?v(mp)G+eph*8yIIZY*ZqPzNF7!C z4{exEEB^|On>1U@&K%gDDkH#4UwD>kcIJxF&S*X!?8mTf^z`Mx%NnjHPFxqE@8qUk zchT>gKQKBwqtBBksQRLSBkh|v>u1DQM*m6<{5d8lFzJWi*_{zlZysirFV{~v262lGP&szl% zeSgX9A2l7MN%7gQjL!#Ld!PBR4lbjAB_&Q==Q{OsR!3On_I{1ru8@rWl^k*6y72iB z9~ulU3Hy37`d9MAiEHbn+5_a)|MgsQTEh**iEG9A1B@5zwtvgGWp0%5fgb16F<*$k zJ0JJdM3t^s1;Au36dh<34dw&lbF3H_=JPKnuY5fUDBU4uxC((=q+SJ> z7R6M|aGe;p6hce8+Ulv8K+(ZwxPiXmakJ9OAak8=p5T2j9C%&`>qcz~A7U8EVtVf-x)&<;ISL{Win{Vn) zLJc3G@5+WF*3qxaPO)(_6@L#K)-~qse4sUrYi|tu0Qw@5{yBxPTT!Trv>!;I!Z>?muC<1>B8!DOt^O7TGSpqU#omkqAtB$Ysfb= zUtZhH-~5+UT)18?)iY`ps$?D(`MMcye)n*{oxk}Fl36{{_j=U*M!wCR|8wzmnJ^yD zeC$5NUd46&86U0}>w7Q4z0&a791YhKB`((<>f-yS;@W|0QF~BUs{ID*Mq~Q*cu(W& zI~1P|N@4YUh?7H~eWnwtVk&0#;3M?ib>P6FJA9+mSHq?AGX-ssX@30Qq8jaKvIRZ3 z>yz{;p>_~oUk&+W>!UwhpbyFryuLcApXwKYYc;_23tnHHj`I?TXYcRX*@ouJYn$oo zCGvG^{{{1C9OpY?>qau6!=Fc3eS?Df$~doqb(oReHvUKR<+U{(=;H!t<_dNOele&< zmCc&{Du2c2Z^@Tbdw_9sT;9T`>G$Qe&G_cxek+3j9{asf6CMuzx*4uCTICDz_vKl` zn0*}S{mA1yH%^|$aT3=KT#Lp@8@4mx+xi`ruZ_dkOot5YZ!ixy)nIxnT0dUf3^$$N zYc=2-_(Ci{ldGzB3iHjy`6u4y@uOci<15V#=MPhV*yYsxLcT}6uL+Gqx6N=}gbqOi zJ4^afOa~V+kNv6H9(8{}>z?{z7u45^?F{m$^2K`P=u!DCZhUy+E;X;lwFB3p@j)SUs9TTK!4;(r zbY4jhoa1pO5!cVJ`@JcTAN{%+Uk{=0E(3p)my5+S z1^XMsoelG@?WOtf+Gczed|wn;|Go5i`71PzQ;=^K))!UMxNe)<(73#|8DB4vPp-}H zx0=Su`Y3W_~xAaK4E-w3BFICs{RnoH(yX+7aqr;-{u5{-I-^3VjSP-cxHJf z>~AB!cW$Tox&+t3eb_I6ufN5wEot23m12GoAoT4#{g{WwRRnRp*dFdefIi2)X#XO% zVrFMjT{TWZK3SsqcCQxCq|5QmFAA^@6%g*4g8N|mNmtSZb;u$7qDrPWVSW+7_5ehe z-ZKTJMY`hqM9`0k{A|I31&ei{Q8Y~Ztz!7T!UyZKeC=K_`}JbJFwVc6Re4(!6m^G~ z@s$a_y+*TqgI`CNPtx(hUps8Sx8=o(jtpw#trye5fyW`(pYOVL^+6gpbCnpbpRfnV z=+wzHF0XB-uY&ajzBU8CDXYc!+K6#}mc3=d_&Nx_UH)P94GQuNV0~d8VA)WoFHcYU zbu)c)aomA8xuj74cJz6?wi&L6(Ba*NYZyDTuNCVz7h%6c|7P_~t0v}eQm62IzRAW1 zAPv@)Jh#}ooR83<BO67-tlt8dFN_!O{#kS+4P}e+dsK8h zOTqaL3_u6YzVQT&n-=B#jmA|lE}FPWGd{XCn#Q#Y=27x}>No^(=if$C>@;rrf6?_D z&DVnM4EBf0ji}0uLm7j_*4I7QFQDIAAAgj&{vl~}>J6h57C{bCS_FQ;@I4q2}wb&oJ@+i^FvyphkX_eChMD z@O281Pd@(HNEC+Ep76yuzo2oYzruXGR%ZF8J|w1Z0P71I=(RK60r$|AY(al>V0);F z(0*>8#;l)Z3i1sS_HfO;vA>QiYS`w8#dR0KH>(57*P9{cZysV^`1Y-pOgzgKPw&JBXC!HS=@}eVs_>y;`-P3_MA<>Z-Jnld7G>80S%wh`PvP9 zG%l}g7ANyDU)Ud-+dXe5jibCPXlL!zyad*x8jLOaF^$V>YkcYB@`(Fr{W|dJ-t_Ak zyTrz~q`_+3fp}JQ(S+SJZjPW1QUz5%*mr7wCNDta^4drTkdP_1nqhsr7x@U%2wm|C zexEmp^@Vi+$ZwflSSyxWkk1M@9`aKAdW?mHb>)X3f)UBA)i!8Z+HoQLaS-u}Tl zKpThTFQQ&AG34tc^ldb^Ff2>yiiPvNTQmDj+N;_bbXa!!>{oQ4sF9J+jXQ>XT?F3; z?>bPE!QCsSueD=%JpL;Gol`V!@-JezDR@5sUA7@T{0aNLX8L{Twwb=ESYOC@+6_Jo z>7TAxf8pA%?s%<{i->}q0pI`CUVdA9KHA!huMP8s_%Px7VlU8m`Nzcc4eV0w9}M?O z#oqmC+`QvrxXLKi9)NGf4&70fqA%%Xx%R6+0k<4Kt9)U9bNBd985?(>6yuwU?W_pG zy@YmoV=ZR==D~bH-!(^$_n~nEf_wvn4*%tKV&-oJr^Iw{2f}f3&4$(}KPx0ls5p*C z9Vg*%w(Jhu+24&HeuO^2nJ>oIxg%_6H%9o5(ztSYF*{QTzCX2?c#Fo({9BB#1LK1I zUb-vSL*v>`i{ZKmzDuvJt4HIy2S%5#)8~2ccmeaFj)NX*OuwFfhRc`nQNYM*rrH_o zi#*+Z5;GsN{=>zksf5~I%oo-lnmtjU@e4m6*O0FV^M&}3dF&Pw*BxiY_y%87`=u7b z-Pv-|lF)}B|C|%U_2BpmV^Og0PR1T`f?Qlf9kQ_wFu!O}x#tBfkCLXS{+*pJ=5INe zFABrb{5qwXb-C16#BlR5F3ej#daD(rmAYcvAm$eqw2}eZf)17P8#DWm>B92>6&Kd4 zcP(APu7lge=2_`Q)$<@BP9;G=oo8W9-*DH*&x6u4D3)922^Z$%pFzu0^k7 zNS@#LrAT(}``+FzYuN+XLjk^4st?wqk~xf^lKI7_fLm;n+~`L@DMpD`98W zPd0624&Xdt##h0(U=NcAK3AOs!@O*UYa?*y4S7CcxK^w$sw8P!;;y@L5PZiuKWF%+ ziQXTE=(q2lD#YN*g19b>3l~oQ@$O6p*I$7xL9p3^^is@j(xTuoON$)xJDo9d#c`;l&ft%*&;i7S!mBnx! z1n!d$f6$)B<+XWnUFrK)D6Ttj?ZUNaT({u34*IUYKK?At&r(H9hjc=RK^v|?daWy| zg1Fun)o}>s7vsC^dQ=CB8d+b8*{_q}Yk9UMGk=q+is|5dEzEb$cOSH-`KING@pTb= zA6&rZeHns$-9()1V*8^m&6n5a*{|GjoO*pVt{u1*wckuahadJnmPYeSuO`-SZUT3b z>q|6?iLLN-kou}R$hcOt_SnV}XrbT-{jP=RCve;KQrOOJ&3h!3J}k&z{|%i&?{~X# zo(k*WA2r&@3`9u}aP>8u7kbgk0OXU9pWXe|EHp3Fmt4Vhn4RiY@9X@Yf&cQ$p=Dd|y_uwT#J4n0c)Aycl0U!FQbjU&{kreGU0~ zalgTUx$ZM|Jt`=3aSi(|5Ay{FF4~H{-(coNt`3HLEhr-cZDB*CRq_Q`F3=VGFz$MZ zA>RPzTNI(SXvWSrgO|kk`Ui*kwm0A#tSzQ*KEb!G0blE7F}^-*51_BjfNxrg7~del zx0?Z9=M^qr!+tBkxDeOvZPs1T83Qz~a&ehc;E4d%0rEau@4iet^YC#E`AUz3$D!v9 z_@-YI=A+L>~ji)+YNChY8ZOV-Y;l9)YMFkjGjX6NUa_>k0G zOy3kj-wztCXX07bOI%z-eQkK$1itSY@J$)W#WmE|O7Qg<@O269x5$LPTjq>l^tJH! zTMYT85`2Gt<7Yq9npyI$;6Yeo}Ge z6Y=3Xh&;7I_14=EyspSY#q2@B`a)ja^XRr2I#AS5%8BWlLGZ0?z}L~2i)&~PX$0Ti z27ImMxw!O447K43F33~C-;T`b&CCl6hKuQIBkcFg8>=tUZ=O1mi%XxPw(&X_~ZTFAr^$(!Mxs+kd`fr+ptFK|d*@=Fuf2v?R{pQ|^TwMB;P}^r$ z`65S?#(maZM*fB#lH__TYJW52>mc|(V!$`|J~6&-9Cx7KTJ(7iO}7fk=wGy088zR~ z;q*F;(q26u;*Nd#?uSAL5r33kV&9W+qYI6|7GPfZ;THBf1>!9X|5c+O`;wPfM||_> zu3GdF86Cvz*YT&y7uKUTZ(SbN_hfAP(tJFtRa`I@`^wS)A5$^Y!AIy&b~< z_zB#}eIKnsllAl0<>*sF?I3|$yUU-|>4RK?xSo<~|G>INUW3c^B2{4+X9-sky%30F9fmFYi~W+v*^KPG~d*n(dj_PGY^iFfIIpA@v~@L>oa2UOeXp*xMo8W8rRn~ zI==LIUSeIj^Tshu{!1TEx6SO=kL?!%&Xz@AFxLg;bra*8i?9C$8~*wJm8WPvIh!Ke znHgUn)&bTDzFTZKw9;>-Yn$QbVO+>lhx98wUUw2|*q##8!B;1I9n<%<+rC5N790@M zK_UF&+r16Ys!VLfOb5R+Jic9h>@G#iA6(bs8{cf0Zz)7`e<#cO*w|{b9QLd{9M8(3 zm$n(`>*M^s-mca4C3v{jst*sU;qfzmNRKQoykvcSNyfE;Ye!Cf2_7!|pqZKJ>mu@~ zlS5v^3|c`gLwxU%gn3>$rB{S~RY^2^}tV{%!M}9v%~&o$>g( z%6t~$>%p}T*P?ubSYK30&WG9`qV+2nCl(*vb=1!b^TPY45ARLmrW_KB4=GQo^A;HA zPmaj9=NX(i(1tCudUqj9Z6#o~JAn(#W}?|-Zy0~r@ zAN-gvtP}kE?=KDS@QpI=@bnE-|01NXR70(0trmZ^Pn_KP<*E=5sO?O|7y_~NfZ#Isjte7c+Fn=v}F zJ#h7Hyj=B*N7P!@YC(N1SYJe2y1(1rOq#DfBQjqzzp&%)HA4=ZG;YBd8aE(|`CEQ% zwck*ONdxXKeVWGQwaxg-gq_{`yHPb7$IsD$*KeLlE7b7<*8yCMju)2K)c8;l5xv~u zrv|8!Y0i<_W;%EmsQN-aS+cbK%$>Ls?`_5ULjL>R(Cv(0SjI%QGoHS#`d@|g z_2AlvYo5Mb+EeqC{{?>I4ESbx~G zwdJFl4l@4UIL)7KYkYkV)d{T&Xs^2n+~2>jGvDj5{wSt{7wZ7)M%SM?zg6SwiBSi7 zpUjQ#-B=A*aKh|{6KEGBwi>UT=H+mwu+Pht~=cBDPTyK57z8-?_)^e8y z(RjI0-Y=6r&qa*$?%fYArC(1L{N7?F#)a|i!!C)t-?kU)0ONe{=*a)ke0gn6U-~#V z!S`HAi0=C05nT7Q5#Ixx+1I^DkBV$$wV0iGFkf_`hIG9W`@I9tb7HvZ1mFHQK2F$v zY&PZ#^W$ZEd)A|M;I+;A&5Lni-*j!Ad~`jczNAFiZ%lkRrsfY|2@6}DdR31qNd+6k z;+c=Iv+7$;UZrsZg7)Ae{9=-)|F<+QuWhDp9?@@>GKuTAe4^i8bF=poQw~O_FWqm> z2i1N9JDXi=c2oLuXKjp(%gsx6uT}FBT>EexZC*n2wH^=KS=)=>wxId?IDF0eEd%>8 z#NYR>ZfE?$9i_fBpCsfEFc$(`r$N8@^CIhO#y6S3eX`D8hOhHbWL$2)&0eSW8?Jr0 zj<(-u9a8XpdXdahr|q^c>DROCiLKKr7#H?0-u=c}i^g>ees3lP>kIn~^ZHqsd93ZX z$oiV~n*|vf*h6{ru#H%sLG$(Tzc)jl5^7s9U-07>DlK@3J}B_J7+*Wq7v=$d2r*8pZ`X z8)vJvoPIq+5I2DD{|oEjvwj%G#7XB3F@0@>4*A)M%TuLfb^Wap;`?LM?Vr&)VwI{si1gC+xTSxq2JugM#;n`Gp6^ zUs#`<)cDFu8aJh>n7%=*FYE_=JZ#2n8kg7B?19cFZ70OswCeS>b$r$Ip!i z(YTod1aaR8`^BM4gIqMOU-bK%1mB%AnvS4xd2P+k=;QoYU&vD(TV8yHe!W1DuNCt} z(?hAoqKp+ZF0XCIHy`tbxU(enSYsL|d68JZDFoj-l{_tJTwdFZZ=j*NjtKh~e~hj2 zG7pD--3-@7elT!ciJfQa%A28#wx3(Cr?}=v+NAl>;X?su% zHyb5pFmHi;r{!#Roq&EHx^1SfY*qUW?Dw|^UYJ0imy{yLHx=2@A>vuhw|XUPpTUj!f*(I|z4$jYUwf2% z>Ac!~Qtda;;Vb!xIW(?+i&$QrP3Z8AC#^1x%WI>416O5=2kQX#`$zAz*XRTMQR+aS zmyfU4fIO=6!-rRE`>{%t`^UiN|D$O3OZS_Xh`+n zUTxU45Ip2Y>O(;_Jci(h@(609N8sk}!Y)*M@WY2{cm(i+ep53$b1hNrs0KR0-Ma?6 zu1o__Z8KcS8McQV?)U$oPUALBac8UfdNM+2@X@ndxj@tbX1G?u9u_6g9#RS1FB6EH zyHT}!8GXLN9lmcweN1lCOa~k03+tY@q&OPY(Jp)U0rcUEFO>xl* zHTW^`EnMN)gW7dhfuL$9JYX~20Okw%!{wj)_;@(<>t?t?j0@L6zfz$Klc&-+blVKq zm!;|ec~rl>S37AsxTeRagM?N(L0`~ea;;e*9mW53kKzPxbw^A+(+vz_oNtZHum_%2;2pvrfMb zxW(f~ziy_ljP(V37}}&2`ddgweTUM=D0q)Z#f+~N>u@hRdHO5g z{1^$t=rvPZLWcu2=N?BogiiOw>2Hprs-510&^ms<7g=2)8T~7{uEb}*>DYc@9{cFJ zjR~8_Dp+4g%zP_*1MQfKnZ8b}1K@6*)PFmwEqjTxvv0%cnX1Ey`7sjCz z&(yD)C|n2O$H!|mte+@c7okJp6|u)NGaWJs+}6DxJeM%Ogq>vvs(BKHn}+jLwA>}7 zH(#ExambDNLY(~c`iZ`Y;_Jb<_aeYat!yX?#a6U_qvu&!xZhwt)aa$_OngY)6y16W zjq4$B8ynzeOo=>?<&B%JvzyfG#BlAyb+qFq%{QCi`-lNw|6#H34|xgPM-6a!y=c~N zIRx%w2DtgZMdpi6|9>ff8{+(BiBSHSs5kll;%laF9-(hj1AT)dBkOC18z69-8Q?0T z#BlR5E{yY*)SXP;=jPz@{7wF;NXXw5Tsv?bt-sNB;KTa?kgvOru6vt)JzH?y(`8Zb zcLmoIH2P)~y6#Ht2{|jiJSsm;UDtqhxuYGrKS%S;5ZsSVX&$~m*BkOUCayakj4uAt ze0jw5Qm4)eF~m)3Dg%M1>R@D%ihZ1B2^!1Z{)=_Iu@ zI4HtXn!nM91n~EdVBIMA za3jBtsxR7pk{Vr3+SdE2e|zH`U)@ z4dTI*OKWTMA;-D+{5U}T-tEkCMRwABllb>RrcVjAlSha74jeqyM<3)H!C$YI>61`9 zP(B=YzJ2J)g;FPjgCabI>=&j|Oz}2T?F{BEpFLEXiNC3W_bawy9l$SME;)j^zAs}7 ze|(b}w&;62SO?f|v5$W3Z;9C{GdPKO%FK_0ggu;pjs3lu0@3RUuB!S%zP>i?I9wK^ zE9v#c{6eaw+CPk&TZ(K!-wV|j|951q0ythe~~OP>R63+4+8 z1SN*E`eu$3!g(+c!2dxEVk4ab?7bE*7*C0^=vxISzTknbe5x_*?#^^6t6&B6C+0Eg&! ztln4}SAIYY*M$rh^o4nBLo`~%TFm044ch|*(I>C9W&GHeD#kahks8+l@WtX6C)0fM z1#vwV_4^Ev?~Hwa#V#7x`>$Qfu)Y$$< zk7XMj6X`iK`^~}QJnUaop1AfrjS&>o!GY};d~RCTt8db{N^`!xGJO(i%QIEKfN_4z z%3;$a#xo2~BAzmfXG#aveqkI+Ki+!~aY|JGn(6B!@~G{lCbXr&a-z_IJ_p)<;(j*c z4D|JH=Z>3(d0#HUcas6%>=yifGve#Q`3{W7_kHke6Z)6}KCU5OKViSM4eZz1QjD+s zdN^ONV`J^t7X_|Ne@N7}Z4KM+g}~JxrKtu7MR>~0&hm(U8*ndcXQ{2kbVwz1sA8al zoGWH$0fKKI1HO5JeC0CX@y*rh(?+zEPM_HL=EUPX-Nct7+-0R8Ydxt__^Zyf71FUwGqRW3EY_tTaTh~vjuTI zgH*m%5n!E%0IHTrbzecs0S`MEsQ5c${@kjgyd=ZJ71MQf-|!5X1V8 zZ1A>j%op;gx!wUkCyK8P=MSJm0vcK6h~)!vOa7T5yap{Q(UyL zqs5)S4emQ*0Hu4%4A+?w=G$<2`~F(LDKk_*)PWc@09Q76-hyVBz!&c%POa~Vp=V89ttI&hFq zY`P?UU~o``r_A^&WyAU8`LC-me6t&f<&(MXRlZ=j%ZE*PiKZ41T$gi|Q~82l3>!Xp z1C8q!{2dS<{yj_J`+;}iVj4F|a9!E^fEpjb9-jYiC$pX!EX}nCa8;(HKN60U>2KBQ zMIR7I=I1-~Inb7g`P-Uh9nk)-Ia}+w(SkjBlbCu1w(W zHNdq^=HtpV8Pv7~!uk$>*19B=q!=7$_LP~vshBTZhgZH+(pmcaq__Ee>2si+j&Wgr zkvXhx7y1}SrWkG(fqQ)iiz{~$^EcSfguD;p_&?F`0aY2?G#LmRX3 zf0V^6o;mP%41PSQ_QmEjoTV$5uc4h~Vmm|2iPG!$biGXDdil7LOrM0>1<1d&`R3#6 z3#AKOcV)=eP58y$$#qB5Z=KssOouE2_n-l8&Qn}mno6kc#Qg^QL+>AA*Zb@?F)sr5XHsg1>mkQz|HE;%DVnzNznX<0O4bsGUQ^hju*z ztLTHgJ-B=g?bnSQ5$qTIV*J~;|CJu6kt4Uw{Mb*#om+L+`e_tTPd;Dz9BAhgxVCOA zZu--FT-gX1T`vhbz<$7`&o|$en3N`1|uReG;_)RP}{*u6iA&wUE%tTr9;*2d7uX zh41TqQgbtUm)HuzHS}W%U)KgN4jTF^^Y+<-_xVqIKD=&UrRZ&DzdP-7vH0M?xaARF z`GHf1Xcd(A#QehNRP}{%{>*a?E=tT5NAx@C+l+AdWf>6#e}nwD!S?oT^k?x~X1D=t z572L~PEY_orUJOK!5KN|1>g(&PEX{beW#%Y2Ss?wjIZk*b$#c4bnbz{b(cqgFnr03 zufL(n7xMM`@65Yf@)(|O`lK0d;7=77^xf0e@knUkFhyZsFvZ1up~GI7R<*5^%AOnP z8Nf9vPGXW~P@=zc+(x2d+iGH)BC7$;l&%dw`moEg1?I>W4@4ASDnx1)$ZY9d<%#?)s>fzb~E(F z6UBbF{tUI{Cawc%{^@x}U!?<=uMw2;~lUxg!Wv6!_=M z%r>*LyV+!>^E~Zlc4ywadFPvNzM0utZ_xklLtrQ0I)RrwC#MF&o%!sG(@bcYo;K4VsZ=CR&FGOdf(7tA z%f~m6i*=}k0C&F8QRmh3U3~T+k#Q65v&m^V3%yHx$*kQHNV|bwKm6>pODt+;A3nbB zGT6>wU9L^u_o&@)OL%VK^X&Vud9!x&QT;8q^Cew>%h}8~50HtzcOW9SKXqr3>1(6< z#il;nb$&9bFQ2~Y-F_<^35at7<@#{*B*b+ z=)I$zGqc}BO5eXH>GgH=(ZYam5FxFtlebNZV<26>^sTFVx;xwYqt=w zGnf~y9p7{di))oP(>J>U_A9XdP-BSqT^2_kz{l4`^sS8mr>#D}k;S#jo9UZG>3ib7 z8oK-Y@;Uk12I9|o7a}&`ky&@J{G7>rc4pg#`vo}k=U(g}v$$4yvv!lnbEd)XT&|M! z6N?kF=4%-5*onR{f4gUA-BB!V#>;&6;G^uJ!L)bKE_Hm#Ooxyi`!kpjmOVSHSA3}E z{>)GLowxql2JTXmvIkk}V5qNyvfl^RJgNKMZPqK6xEda6#+Mg~tLHEBy{Mj#^=PJV zF3|z(cXykmM_9aqW0rA=p$^Js%op0NfAgU)vADT|`E*c-z7VgU?r~igm$2`{=FM~{ zpmg}ItzL)hd`lhJw+iRe(HGp+`Ni19uzD0xDfw# z_^ij|_}H5FH|d^8TwQEOY2AHSR_|k`gF@my;OqVA$aNOS@8;7Xm-3SrizOdoajo)Z zc9ux|I*jwZUn~t_geE0guM=p>s~JC;x4`;CpRu>kQd`0$;rr;+a%M*}zDeZw)Zo6L zN{zIqhB1!jIWK@8LWfP*|L3k9FXCnX1EUOcjaz; zh&H#FWXs~SGnw#(c02mxx&sWXWft)@^be`TenHh?F~jePyhOTI4+4+Cnwri&l4eSA7NsrYQvqTBaq*;wby zbnsE*#lfV~D_JD@J3hX)n^<3n&wf0x0NHP`Fa^WT$-XJdoAH&$N5UnGsThH0RnlD=i@|jO!z7VgUy2|w& z0YiI8C(l~}U%BSP4-MM@-rp>l>EK5Zj_QB=Tpd=x*0;aGr-Sc!MBjvWMtWIXf08w> zkv({bJwU%WU4;F@HwWtgesc6P-=KLRRxG$A=6+$=Zhney{ZmEPkEIh>UzoogZSjI` zeJ9_+r>{E;>j3%|FG9X9!WR}EMtAOqqIYddvUtw4nf-dsV!m)+=KH()J&q2t7CCy( z4A)f&ua`o+^GDvqZ&Z8mEsfnCjNaLEC$10v?6nWP+g03Ph8S*A6RZRHovka2&hG?H zM)dvS+^|oLK2x-FX8KAf5&^#h^S8y%{g4t3!|0kBZs-ZzFJPP>^5okyRec@ri0SJ* ziE&|{q0bfl@5iQnY8{st`7`Aj)&cAxVF=&&W`tWneb4>J_gns9q+zskX8NWPJA>=! zvA0FGe&(g_Gw(BRac!1c@HgxI3nLx8ry}}pEW-Ffq4>URz&F6T?{6QB`NH~di%lbS z>pQ7!E&aM-Y~Z^W<3fCP?uNeIvN`wt17Ak;o$_pn^uqpjU97)(2Vh(nkMsBG??-eG zv+Qq%I%E?az)!Xvrq>~_ou$60rat*7z84JmW?1ic>p{^O7x^7?m|s*}^UV8fp+v8x z4u)|_km?sJ2XpxyLw)^}z8wtoO>A$euOV&@WxwYQ>^H=@@9(GDt?7QfofX{2$5)|r zc*j5oJLmp!r}^?K`fZ-P!n(*?8fg{Mldwf9Cqa(tZu? zAwb!~-8c39*xuQ)-3&jVI~DsK&|%+v>2JeAQBEQq4Eg3!?dBe<=bM+p$2UmXZ_-)4 z{W>17#x)u@-T4u}-jr|LG}IwT>F~CJ4h5Y1{+X2h9{S-BTJ?%Anc1(C*e~2ye0X}l z&MazPH$Hv6L|>Sl%$Egrozcse-~8{JIg0_2K{(t?O$~MOqs^Xm(t;InQmydtW7rSeQ86!1%xlm zhiY%y{(=@2`R6bB_$HLY;{n)%+p}#tiyN$E`CK2iN;oeQT$pDy`f}VDwvfLzA8s;* z+sptr>lwavS|_E$!soYt#q!Ndv&1!QH~9XpI*&bH>#060ZUN`MX*#9D%#Ld}vA78_ z{4NYz2l5^Yca8yW(u;gL*oY3WFFm|mw|Ch0&UuLsR~m@*1@SMf==C#;>-wC}pZSRn zww+e#_U7b1A;d%f7DToBawOUmMXE_;xMU zT*o(as_+yVR9u*U#*)l%17trI{O_DU&pv^0VW=~l>lwWd;2O1C zCe?24KZ~y2GLVqqC&Txxe0_DC$`|snBr_dcWPcMr%diehnjzcKEG(u8dxy4lK5=;URpX10TP7|2l*l4!<3Oxbj}CFW|nv{R8wp6pZT;#Py?Y z0PP0)E~`@8rRv}l#C49veBt}CZ~VLaAr)5<#7!6ziGNEBn~CB++`{tbV(per;co4` zv=G-Lh?_u^^fSVv2*s5st!IuzS+JAuJd21jf$%X;s(k68sHC~~YsR`qoV^0j{-@eiFUY)MyfJu%|KehMV_`lrLco0rQR z@zwbMo9W;ne8K;YaQ1_^Bn7MJ>$;o*y`-D5E>>`OQP11+`_z79dY zF4Q4l+=PCyy-7a$UI*5}MZVukQ8#>PW)DtcXBAK_dGw!X6vZVyf_wv{-C)0a+?dW2 zRa`|7H=p2w{nkz1dtSv23gWsb|L{igeM?ka$38JT^L>fi4dTAHa-YgZ2TjWUhwu3W z$`FhT{-NONWHejWrmS<8_6s4HE@idDxTVpR4KIw%WDCeUt>ENo{GumAo=&9_wCpdhYm5!SIL!ktjI#p5cj zN6=5ACm)CXFX%huM)&S2u4AfLyJbwr_J9IOsq5epg}5F;+z`P9KiQ~R{n;vCMG!aP zE6f*gQ&OfC>KhcqRYqYQ??ku*E)<|yZ7~_Wl!D|uypER4#y6S#E;xMu;*M9mK2-};<4Yvd+y3p)gHU8EnwcyV_8kd`X0PY^eg%->)guJf52 zx6mQ3WM;n}!WZJR#?N#@?x&cHUZRK9irJZu;KID7-hj7XRdrAV{iK8Ns)cZ8m#u*g z#boqSatZQHej3{Y#K1GR)n23GDr3ZSuyw=rVIFHc)Dyz?xRP1B1=nJ};CC*(yBx`k zOS*m*l+-#boC7|9mM=ltGG4)uMUV+P;H zan0b1*WDD~dIo%@nU=WhM-1l!)c5r|bT0N9TgYdPYpAcSA+~?GxN3iDBNjJgjmuUE z=Tph|>Y%@sap?KFms#py$XBNLjys^|o4ni-*N|^M(HF+!P5qzzkS%22WI4|=phUgP5y}wH<8@u2;;>MU2dTH zkT#|7u+&#uf#ke|FIw1<9!>am8CxiobAFsk_(D8c_FBI>EUpx^+>g~&ffE@77x?ZT zAAZuQrd-lGK7Ad;&S3u5bw>r54ro%y8rRT%Gl)Nfv82mir*v^t<{r*=BRar3;^u4R zdTYp{OxAur+=NzWeEnzFRGZ-(bHeHAIkF_b66IXs0<3hVVkuq_r78U)T(nUVL$__lv zCnCVq+)7tj+=P%NuAzT$QGRFqyf@!takH&)*(%|DGSLC-;f1F+>-t*(C$5v=g5Q~% znmm?$bN63-I%E<*3HzJgH&9HAg=v?SYNP*&I_I@T$huaVmhP}To^YymRQ(O<*Nwt4H7$p__vPT zagT}{6vXuszTkgfl^Xd~TZA6WN9uh6|bg18~lZZJ>`*qemHN{ky6#Ff6r?E`#IKfLK(6;~$bfqS%s zS?Ei6NPUQZ+rPebt%~dVSj--h21Vk@#cTg-tm66v`6gAy>u%7G+oeoJ>yzY@-63}0 zm6DA=FZjuu8)u{cq}|AQbRudp(>Lu~tON9m-x?lRqT)((#PszMT&0aB zQgR9EU_&1rFk%0qT=^wv-hw}wN06`kt%wexgX=E=S32d+;ah)j5WcWpJ#KEJ`6^#U zkZ&rvZxF_}zq69jJOJz96V%s5>Dz4UkA>sBd_l|}l3&95f}gxL{(+BZZQ*s|Tt0o> zl)f8(nf!^WgCeLykleQdan$w9v}~5IRo<+>1<5`R1gHz1d=~i1=%wTsE2eMYTx6f& z;`OGeAIF!>_}a>2e+G8e^2?W=V^Qs2@~smDNV`G&u;DS^Cbivyg6)<@_`-ZhDtYA? z%U7As$Jb5amNvlkz0YUASyaC`GT{w0ZfaAa_47Rq*9j6^V|yr#;5v8t{$(vHx~~8| z;vD>_Su(SS9LgSQX1=Z47fCv5sjnelnec`A{Hb0y>ax7De&ge-{DgIYecsTz$s1W* ztGt;G0ZNB~A5YTh5IoCg5BZdxb!**w0n0Car==C%T@{J6UgreK)mz8%Dqe3LjDDO_M1ldmO_Bv&iVTv z7T31dQU|t5IG;-CTYi?l-SVt)4fSHD~WzV-u_xQ3s`N&ExEXMv3s zkt*7h9Ev{9>&A=aMK)d->fk0iz=qRrr}A%U*`jA29pux&Mfu4s27WTg`TU&>!Wa5+ zo|qN9zmIMYI=^$Z$ovjVC7cftJA?Jq zSxbL;!LU%2lV)}nnvLxY{BOl~{z3arxTO4%*g8RweE%5i_w8wIA5d|9bH#977cgI# zXBB_*`$j6R=TnTEzb*QBVWxxhLqvy1mw3Kbaiu%O#(5isJN0Z?G=C%d3gSvNBKBK3 zW1MatklDbpzZqIf)_0Nh$)WcjM`2|#849`t*X6uuzy!Yn^X})XZ2S~3<4I=iCR6(M z&v^8*s;@Lp%+72bFkg7z%SHLTOk%&#j~`wAz!p}6gaDuY$`s!NMab7l^aZ|4XCMAW z)mIkOw}99g*hH_MgZiqtKEZxrn}O{Y*5zEM$`|r=2=Yy$a1UK*S%|9$@>PmsI|V=4 zqt$|gst(cwG5d9sc7t_-$_<~}pyCDv`Fbea2fX77b?^x4>!omaH}!W^`O3B9^S|u< z>p9P0d#H+ZX!pgi6X>8xq0cSvU)PjZGd_y%dtLnPRlYt!9Tb8KT1tX8VEF2wV#jvnur`QHG=_uhsp&#QbDK^+2Ae|zQL>~SitBTjoz+eR=r}-^(e@%BbgKJ(}rYpN_{1@RJi$s->!YJ(tA#u|)g>+-Kfw^@ImiTzS42u4^Xl z7qEYPq#WATQ};Io_01r-wVG>5`3mabdmv)JC;Fe8SBNY49Qr^gV!!i7|Aua_z?Lpw7PB+Y z_Ywd5qjaFRiW?NPGdUacg?YecXUDHpT&Yfc;|1H^eu{7K)zZ(ZxIw{olY$YxkKeNg z&6csgj$>l_rgezudtmLzKiSWd@jRdXdirBturIRm)3 zZOET#Q{W;WU+0vFzHRml?uzu40ofy{uZ!aQ_LIei0VbW?$M|&cQMfyvsISnN@H!by zy>x>#Rmf}{%DIf~0q(PzueyAm<4_zVh~nJ?!f| z6~bUm@^Rui2yRV;mM8n0X+TjXRGH7tTvsq(*f_qnwN{F1XYwofJo`Ru-b`QlUL1eb zLlwGD%xZxSGFvxV-V8U5YPWuO9)af5q_k6yP=Bf6V$=>H@07xzx`dI>^gLi(O=BTOb3N(x8KJ1SXRhaP=`<^ zwlf&Rx=#1hM+Z4(vZ$aLU)Su2{T{se@Na5KMNr?gA0xPxUKzHn5LZx#0GW5gz}8{q zpjNB~@*uu(D3jtlqtv$#seFTiI=IGSJA?W0FU`KlQ*osq#r%$w_%qO9&+F&TsJIS6 zTsze-8V&0CL?P}~F}`lX7uL_JZD{=o!j;iWDJWKZX3jw9{f~{uYF;} zejn{xw$Pus1of5b;`tPOQTq9ZYkO6`9zop9&6qFT@A>k`PO!Y8Nx5#me&I>N;}DE* z)mHTQLgg!y&!Kq}gN&Kq@e#fdK#g2FC%{%MSk1R??|CSq!|}%&9bj?o6)g98*(%|D zHn9irzl*<}J6Y915o|Xv=@+oh^?K;#b1H675Z6cfho7e(ajLk|La~04M|6Pkc*MIY z(2v9VI0WrMq4*wN^y@z=t}Mv6fU@7co$3x&aeab(L*=lJ5J$cGQ&Z&Lu@0URV(TTg z<#@aRdnmK6-8B_AD7Y>cr1br4;zcyOC+#MvZhlaeGw&2zByHrH0uer9Nca&4t;-9|2u;PxA^u0Boz6B&w+9N zLC@kORR>uXw6jIH-Jl=;Iqr+bDsC`N9Z+>mvQd0ro|d&!#dV1C{TS;2{cYlf9#=GP z8biix97^gH(c$d)ZPrsNu0s%4Ci;T?e%`BPs*39p)HnYW z)&bVJRv!rJ))CW=#Ad(jexXd-4fr-IwoNxbr0lt|>8q)PGWOjV7yQn)b4xa|*Igg; z@pVxBxW+K0@ID()jCOYJ?N$=}`7-dIf{yTahWyF1M-(6MZY#+_jxKVP-)kkopM(6d zpU12pyD5KmvBb#nYQK>EV)2f*JgyJ^_XGb#=pLG++{YJB`UqbbH@ED1^DdRIFGhXM zbjT=!?ExL6QXNa}(2zx$q}qJ;kT4$iH<({^8uDV{I#*B;)7MGt4D1*ETr-+2<4@*^ zvE3}~>?*M{a&(a+ubm|>#yY^5yroUWy8-UC z%eDKcxKcf__`yy2hvJp5ex%|C1$D@2g2w~s7wh}fNAE%uBhN=hr=un_eG^e232jyy z{k2=;oWz3oIQxZ%=m7Tn$FK7~Q~5d;i}ee8U(6Q;)Y8uLmo~9{t@36%geW`v_oq9N zD!8OakgvQXG9G_a{j)+`pCE3=!x$Ih)Dvq{rm&wo+08d@I!|NVu>ZZ#p%sgp_z_?H zkVSL=zNf!SF01M*EfKQ^H(5u7^|SPem;P39WkFm&;R}BKWS2YykL|%Bh?`4rLEi(- z2Nv%8y99A1v~vUf82VfHn}cVfLtM$UUkt*ypzp;a`tJcc|Hrp}mPPz8=y2&+&yuRX zK0zJ4{V`vNOG-|;H<=Z|dzz20Li`!%Aieaj+8i1r(T{FEZu163zM77%& z*UzE*cd)*SAZ{Mv3p(6i`IV9H=o}r=!ES7`r8XnzNqLJKWd3k43AHR0nAKX3vLbdp_s zIyebmn7>utdg2w8uS<}xhdg%?;)i*^2U^lx;dS6TA72}}zZ%xLX7@{MuJZK={?4HH ze(cXmA>5U#?mhz?>11omw+@p<^acBEU2gD-LcW6fdMSOoU+bvTH~D?Obv6 zywH?aGr@nboxwnHsoA|d)${7np2&wQ&BeITFO+5*+NnCoE5!U+Ch@=E&zhc@c|+x? z91&&JeXFXgdUVy|k#CdOU4VZvnNKkzMJLi>(3WIWK-(|SCZb)%>zPfIpiPvi#n=w#}ioP>Ymk(ENg!>ir#vL&wJyf7J!XfW4= z{eax6EyuICnX~xXP2Pibfc3r&RrbI-t&Cnuz7t~pAxOnL^V8R&{X%UD*0a<>TY==# znqmJ7e!W%65@>c$)-?p}%trZ#xeqNn%D#DaeLlW+VrS5giywFc&EK>s>n=WAC*^m1 zH_x|Fb&ytywVO955|<>@uJWCVD+}TlQ2uOkpNUPhDoB#U&ZmQm^f!plW+*){9s5-a=bqEoC!5-RqUqg@rh^_gLRNz6|-LtWe@i^d0>@B1jsDpo67nTQ-B`ThNxTUlgp4^y3en9bZ!AD+}`V5q)7DX8-Vgx|Ld`9UouC zhWSE&JMnqwCzY>5kgvQGw-3a>Z#8u{WA(Ky;j;(Z&k=pUa}Qpi@^uOFRfxXOkC)uG zYZ1#=YR{*ygYX4?|9$8Hig$?L5#*b+4eJ2@EOGI<*fJLPFx>lzdawF z{IF^dK|yt>(oe8fzdWVWD3*rVp zj*M@c?w?pss{(r7YhAwm7Dr?Jc_H3ee);=s7B{n_rM`yqi|p2zFB&MM1cT@7C6=(n zWvPVoE}|p&-}!ee{9M)7BdD)}JQ&0eFb=g`ncX@3X4JoeqkQ@n5PN`ixl#Xqy+q~f zi=D5bzJ8)F><4uGt~iR;w8>tQPhT7PUJ__A;LW5tT2y3b*0_dza|mCUZ_d2OKZM0~ zm*V4_K|P=LRRg}B#g_9}L%s^dca8yHe`!9xUW)JHx4P=|b(XQjHRPL1@eSR(O{cFT z!4j8kl5k!jd@G~e;LT@xu!VxwxQ2WKgfHBud*9SI(0w-A6e!EbH;>{w)PQelIZIqa zzIha1hXG$(c|P1A!395Ab>w-S4pId^+>xHlcUXrX0@wSQmwR z!vHtXhi^WVL2$vZ&+oZkw||`dKR#S9g?n?D9ygbB-zl5ItvgqbE6?QP>!+TVdC%@g z8mRuvb5(2}kbHl{9^_(rdyuTx?X?C(avp*U?RNF9-*xSlzKTx=H`U+j81%Pf>v@17 z-ym9{R^#f{C4Wg_3%OVG@%0eC5U<~7fSdd?A8v@UvjJb%f^9=hN}tDvoA4X92WU6@ z|Ma-h8a`Z^;DRBn-*i>)e>rhoWSj>l`up)e`f5aoA%jEvFtA@rcYX#i>6C6AKhVVs zUk8algLb>rt z?N$ci6t8?cT8D{mz0b^kU27u!*n2L!o2suz@b@fzb1`3tCljW9cvHm<#=cIVDyBL5 zDcp}g>sN>?troKfFQtQHa{%pcV#Q=Z+z^HP*TQZ-6<4y0eP1tOZKU09|Fv1+`lL^g zuR`hjRjbACsC*Sc+(guYVcdlEl48rJOwu$e%7nap>rrwE-0o!&MryHBX!ykK<`aD0 zU^=Dm`kB2>sJOCVySdN~0O$bz>{!;Hs8?gYiXh)C!WZ@#Hgg5>POn` z$&0H}R9x2!Vz~Z_c>IF#VsFPLXnIKcTa0|I_Afjy{t({3@R6fJj=cL9ZqjaGXInm) z{Ef;tDA;bfq}^bg-_|eCN5yr-r~_6FRc4awZ|oncq4QJk{{WU_WTr^etQl^A_y?GG zKYeIiVZZPQ@|CIk%=32lDa7>&;yRQ_9QDmJhi0q#DuTE{QXkgsy>n02RdJ;?V*Nro zi}}KS)<1Xt^gY{1X`J`*Cw~+fFCN?7|2LJdEO^JgAXA9Y~q zVAqRNRa~DSZh%@>{&v^X`hA9>eD~7^39ma5-+CXoN2`1#Ma=KWq(0g>mg>~&gN9|S zm_ra(`33U=zW-Zu`YRRJ^}HD0;CfuYCc=GjU!^Bh+@RodB|_BrmMj(fTE+Ek5aXNv zOT_<cfv@@E^=vY} zL0t0il$n<_peU1Oy&ua~3FlpeZ#k6fz3Pz(hJ~V>H1iK>2{=xLb*_5vJ=%+f@RsE3 z$H`P&{pG+d=UH5cie6e@J+b=OEf<&9)|LgafBDwLHNS@L!0sMWn1B}*Uk9a zDEocB#TH>uMuh8NHM|lg0c)0684M1UsAj&#$`m$&5{W{lY57^V<2rK1aMLN=C9S?d%McjXBZ%vy`rC=-W16bCiXd(Q zWxtO!-l?#T#$%SyMh0$y=fYX-nGf`EZ;a3Xcme4hQ2w%q4IT*`**ePqR*M> zAR`NaegS;@)ST9Yt*Pwg^E*zWFZi7@y*JoZzKWo}nM7Z(vs=U0qj)mDWTr!KL1aEO zYHC)(iRVLzZ(Uil*` zUs;fEkkU8Q@X5glUS=pq&6?S7h#H61F8*Het#bP&ass^Lp!eErn;R^^qnGgdh4bu-+=>ezl^zFED) zl|Ksk{w}72Z4<_Yw)^&Lm?jsK(Mw4dvg=Pc@{byHJP=W?MJLH@Ljj)hYVE*-)mwzq>*-map=bm4?cnp zGWv@-nekOfzbJ>0E@amjs`7RGDaO}L@wHW6GF`_le#&BWkhRFsb7p*f zWITp-x%^A7A@I|yGGhuWpQEUR|r5wzce?pO!-JiCkVcQT!XFSOgp+e*KO z4sj(jeLZ=YFU;qE-*6P&x1vpHNqqXcD1Ae|5-%ZCS&JM!XU5k{=Etzl;QyrbaTX>0 zZ9e;TEXO*)xH<37i?a&tLGZpdKhdEg!oBa)=lm+JLonV^2rl%uK%+CqR9ufBuCpZe zv!KJd_fpU@1a1k3;Qh32JH`b&>wiz*QRtvaiOpiOGxqmpvhK$12Ju6|k#@THA#I=K z_aQYr)J%}*3p!LU*Zl`oUx#4aCx3Z7`{D9bB3wHop0Z{X+auGkwR0>gR~{ zsP;EjUu6Q;7yRUJpDo(S;-xK(t=-sq3dMKjU&%gIUq#T)`I3IEe z;<_llU$%O9u-a}uL0mV%y$$hgJjOSt5LXei2QR^eII5aYLaQgZCFCJuxJh?mJA-xb zp9WVrqvE;*aXrNE0NMM@$Dtg~oo#YpoR{N4Hp8{KFkiquI>Oa59!w}}h8sjZ0rUkOmK325t~{&*td}I*v1*ZO zXFhTsosOE!__~Nc13P=YWzpGLuoU(WaKC4>Jt=#lk~6qy#y1ZII-oDi15&>=&Z?sZkmk@t%Aw;<60-WRar zO=f)aDO~6q@g_6e5W$7{{DX^&->>T664W8I9NPooI9#C<8|B31A%a7n5*z;OI z#g#9L;bxNl2Ju7RMHLI<2cMu0ZZxn#zkq(+^7oLTjn zv#5T~=QJdvH-vrx{Vnv1{VM1jPcq}1K|Swv$G5{_KCexk_|_*wWV}FunY86X<$LUH()animpcI_oqU{pg9I1G`Mv9(`-;Yd*NL6^bVw!b2K~6x?$8iekBKLl zwVR7P7ZCKlzV>-ohR~!SFW(LkJDZ%cwj``W#FNbUdWoIE{X0V*8-6c~>F0bNNFMP! z;Lm)X{9CYp8c#Cg>%5M20DWgXoT1Yel7*y71|s5PLx3lr+l#H}?TPTz3v`H?Z66;jcDO{f=B(Y=6^^ zJR|sDSl6iDTw+AT!sFwa1Tz=M1`xTt>IY)<2=wc{a+%9`;_7=hy`v=Jbc zesJ6KEUeOvkFSri-%kbyboQI*;lnMs8@C&Lp1+H5e^Vwpfc@?`|8oJWLy(iN{SC|) z=0Z(p9DNXlKXE0s-E{jRXkwwp)ouI#tDA2obN((@GNnVnKnKq#zIKzEM%pdjSP}$N zbzsGFQha|m;F~&{kFOKGA?OR^(2Xzk&rM=^uz54S0m}dGHsEU;!^hXY8uNv@@#4(g z5LU*O%=mhUzA&zpzN@*;?Iexm<13++E!BQ|-hM-8zgFZ;`4T?~@!8Q9|IW92bc%ln(>Uw>T|Q#&2&g4&zA$g-uvGpm)Uy0d#vvVm)S}v?;?D`Kh)WSTJKGR zLQzhsd|AI9p!|BWfnU!b%C~<}K-vv-X!YPNUEF8OuP;m7g#! z#J>;SdHVe*QW{=T^<^(+5&r;V(Em=}yj4eXutlQg&2VkRpMl@G*=6$Ijv~UfFUS1? z<}Kx~?4G8^zmAv1*87sF=gTesMIWDe?zQe0MnWZ0I?P}4ROc#1q(eI43wHMViSKpa z^O0Ng@y(>{_YVVHg%j6J`~wWcZ*6aQ@y;UB!AJ4^(}1u26TbeILvUdpV3U((v2B~p zi5noeFm66wZJ2J{%xuHgZb>^L^OiI7GGAx;rhdw&Lk4L#@DCl|MRUUZVSLNZy?+J!-We0E^=0co-bHZ1 zPxfl$)GaHAIB_#5+@}n1bK6?>W5ex0|I64OP}n0)H+UXt;tQ5K7~(1f7v@8AnhiRH z4w{tkA|Gym;(K_(_%<3)lu3Pw4>w5Ro-n|5x%hBH6z;hd{o1p9Gy3r1O6j=WV85l2 zTvIpS%<0RAYol_m9)k`EX@|3-M&B zy=@n;?dE!g4>yUzEpLFEIM@=Gr4r8DNxMOu>T4*2ThpY}JNW#Ao$!Tu);AC7*SXw7 z`1m>r-%1F##O^^|HDpmH)P--JCBKI440M=nphNO^mV6UfE|5>AbokythdgUsBUs5s z;wV_(`J?u~zp#ZeyIbmD$k$Eu1^?Tp+DZqDn>dqC2M@u8@uJLBcZkKce{YG)Rte{W z`Zw#GHo!9nZ+_*OLFn>ve+ZyISg@M+rzyrr8TXIbMK^QHYmgBvNV z4#~6m___&S*v}i`TRDlvO?!^dKco`A&|uwPb3Dl6W<76-%T@{JGbz4f4EW~$V5x(l zzD|m7PXoT`*?hQZlz-S+7QCf4$$j{AklomyfuH;$ducZ2 zKA#R=q65Td`RyA#PJP6fUYhCPUWn}haNp0rZ;U!03JTsQ<{`K+UhJy(-msWRQiaU; zdMVto>&||z@|DmXSl~OYk{PbF57&nck+FAw5L9txL0lhcHyAHIKls2F71wh^jIWQZ zBUVJXfl>aC(LqLkF()$}0(W71fPS2u>pvGWASq~u>!;f7?#XqYP<8ML>Z=f3h|iiY z>zu3Nx&(1^cSY6-p1oXWfQsu8#8oJJc;?zF1W4mR39Ry|4P0 z8#`6LQX{eT5}EKVfrx&*_9ogdEGDCuQc&-2SI~Y#q`!ebyZYJek=CDF zTf$5S=>Yz`iKuw3(n(`fzA`zlMbYQXaBU4D_E2*46T01k9; z*4B)kGsAT~jQtMWhqv?4>a(g24nZB{bc_r0!uuu-M*A(rWb{&U3F6wy;C2K1{V{iM z5a9x>C1MyHQd9b|Ie>V3@Y z!9nVSzU_~t%u;b(g19+Ha6g8AQPF?(0>YKiOUWY`KRAhri?;+Co_~ef_Pl{ldJk#|tOW zw6mCuUP_9fz8=CC=CO6231tChJjsl2#v(jlml2rz^KWLTe1n2~)2Q*{@m8*!c(_7Y zGrk_;*I~Tay?qx7BXCLO7S`SBeavt(iT##B0QS2ool$j=4vFDzbsMtdfpe)!Fd}!{KA(zcV+OL|d`Kbo z0Q!FRP+*9P>p{QMV2eQ!GaUl|MB=k4hkD*01C*wS8Llz`>sS|+J~VY33>&hhqD96G z*YN?yt%d5RjjhpFh4FZX3VpvY^=+&J*qQCpAeaYeQo3Tf-=Zn6W-`#k4cZ3+)DN%d z_czsYW=As}vMWXA^UoOU``f*I>yxR0$T4eGuddAInInf=P1h@IVMz}LB)k8d)C+sObomlM}Xa8Z~h zebAvTTG!Af#|l2aeu7&K!F4?JuI@gNv>ZO%Y|`JL?fU2J-L7Se=FN5Z>?}y}eZYWk z;-{ATEi9FAzJO{sTZ1GB|1>F`6F1$4{UofPU9E9sfd&+15+?BRwT+6{ZldjMZYcv?g%ej!!u|mQos?~>QnYNXb7tebi{e|xfN%0zJ{<~D zBKA<;0N2ln>mvRP=2;b|Ki7`^$KXG#Q8hs&JMWUU_PH1 zoc^9Rzmio0rjgi8guH@wJs`I#XCS6XHY20DYJHSklzV_`ycL`_H$Df zB7LhhU$ze96$;m3fScv#>lYGvjy<$nyHCFv%D#8OHa@;G!G->|dB?>!SzPyaK3v}- zJb#0A`$_iCHlTGF8NHMgavoksOJ?m>&?4f06E5z%UN0Jm!8J2nH}MY;_f2k{AT>0o z8|{=CZvJNMe<7w^aJuOT79+>OXAc?n$hyXWg)6>eaUD(geiz2E0_zKLYNsnppHvtn$4@wK}LTuCo{f2e?*5Nm*=7Tu8PS3 z>JeP8&ZEB9+}_}Ow|36&Z~6&e&^PnVJ9+@uc#@e8PGY~%FBU)DqkEy96&LFlZt8n= z_Ub!y`%Vtdd7(mdfQ^7U_t&ha@(l{Mo0r_L0qeiXCkCVSNut={nERXI{Md~mNbr%c zewK1?9|$8fDdgvy#|9{S$VqQLK;DYA zz4n&+ez6|S>{nWZalwA&Pqto%L#&uk&I~u3j6*e0nN2rr0Ix|QCmyFXC#j4XuKyLx z7y5Cz>|?t1U;A0UannY0fN^MhFr-`OqNo|ZG~=s~egQhXvGIi$RmD7l_8=3!(2vjj z@o!s0Qc+Ht@W>|A)pdbdb?s%*hm&vIm#Fmd+j$d-Bqzz{hpcsRxe!vixXyilhFDp*ct5WjX?Kn$VH@Yko2os2=|A!Yc{DZ5fs!R zkGdc6#D-_CskqW8F@2>Vu73yO`}E@HA?}mWU(Cr&-+a<;u%6MpSpA9UAjb@f3Yy^- zJc;8;SXX|mbcKlj9VNDZ?4b@Dg&A5W5wN!ud)K$8Tj>{jn_<3aUFuVF2War zmaX@kM0OTmGUF@l#`;!9a0~w^Gh5~B66EVdD;dz=N}<31UVjDMw-R46<10Uc`NDm= z{oXpLTPLu37c<;sf(tqvcW*tQ>fjU9A&uxz8sRS3`h8C;e(ZHKzS(J!d6w(%NoW+s zC4+)|Gl)GvKQ2?T!G|iYd_>IecnL17pVe(KsL1xEC2F0vdI9ufCUHKe!9hMRtVeym zzkimhgG*3{Y^uLqZr$?(1TQm;qh`(Q!A0y0#lHk2E%&kBdVZiefwi*!DB3L{z5*!0gCS$ z1HKst`S^M$zW*8U&DqDt*Yy>)Ul=!Ec<{!O!hTH7v%0W(T|<)se#*`kE#3MMThG4V zlCNRAWm0yw_Unc)d}>m_8dpyjuLS<|4`{hxqoTm5!15 zMdMmCzGQI|4_opzv@?a+FI=3p{PYtnZjLoBTP2*g6CEHhYi_{T9^~U2p!m)+;2W^U zHRPK|^o6nLO@n@s6trwNLw&O;J6mL6XBpPGhI|WlVtW8PyJ%o%xz@ObeEozk>@)nF z{Lw7-&HYC$+l{Rf&WDJ;!1sy)U&j$XeRC+j>katkaN;Ty?jskz(fPBS<9s?Kbc*!j zgtg9ttXR2!S&o}*m2lpFCm!FRQSWX4ibEaWTqE##!%EaiG`<8-Ay4A7UkCZ! z-)abV|KWA8AD~ITVwSju_8^mXE055cWE?>2M%t86!V*_of#f{palZl`rVZ@qVGAYM zEO8C_+9|&6R}4h!>)KSn%a_<0tXEg8a!w11a+$sO=5JnN53sIW{;wlzS>Vi4mO8Li z!ud2}55V_!1HQqh`S?1BzQDJ#0bfTMOTLEfmP^Kq5(xLYjQ%l6E^CR))WF#+(r(b_ zZf~#bWDB__TaKG-m2h5p6!&8o=W{N+=3@(`RpI07ONgxRWb_O!W^t3B;PYo04KZKP zcg3=z`~F)#**68;cCA>p)_Jpep@;A-g&=kmeAI3E;T z|MjCt1Z)h}cV@rdX{3rP9gR7DF#ddHu|0(6Lt~Z&*h2QF`0OD-_*O)K^QZRwNaZUF z@=YXsL5qPc^!Dp^@$r=oVSRz`^0Sp|s(f97eC-tOC#StPRa}oCu2LJfJJ{Lp8}52a z#q|l|ItgDGkE`GHD2OZ1!F*wT=g8nckz2z(NWMet{xi>jNPp|_&~4~0SZ&H{ z#pfqolnx78M|6;miS;)H1$Sul+INvh^}3|M0tSHQH6zro`5< z*#pbhPw6n^t+hHGl5+TT2vE3BJlO{Al4z5Y6E{fw1L*t1yeFnr0;TQ7)0Y3Og@*XzDtBbU9NRXVoug0%-brNd`y z_vv&)|ueDPdJ?cBa#T;+uFqD@0?$Yda@y zfWq~@xgL%4+LXqL8zi_e&X4QyRE`!E{U*k&*!l%qPd*><59|LKQkT8%yT-Q;BL^`q z_=giUugz5B2Uncq8_Oq^dY;0bifdq4)}-9mV;e6tl~5)~zRv)@r|RK_+tu+{iG#1q zf}*@!2ge_v!<6k$2c&lm3Pm}k`Ukd%>uanp%)5Ubb@MKjuY6oA-f;&bxD`WV3RGN& zC@#7G0sMNeH(x`1<4a~b_<|9>*ON9rqS~29kgq~;Vg9ykd-=log-;OIPx>45;~n?Z z?u`zbl=hExf0H#ea3+(CL(m}>9D8cN^r}IjD5uQymC9jzg7M;7$-1MXKp0*!!wsSl z0{R-*@1hHr(W*gw$qd&!8{@(}>r#zdh3)3JAl5Hj*?5bnVvGU^xFl+XFSMGu90 z$N)Fvk`v=xJ`#|@~gPg2{C;YN{66<4$=-j z9fB0@aRXc*C$8-X)))MGhgVkgRCRC&>L3llI>LS1r>lLXi%Sv%d^*S!->#Kk_#458 zQ*g^`LeJ;&lIIBAj?gyNdUGRzEj*-i@>Q-!_G6!EFuaMXuSZbdY{Iu1V%VqpOOF>4 zB`<=Ud=rmizJS};05@$XU%UC6VmpKR#Y5d&oMHJ|<<0!0o#NZyfUhl=FOG5$I|IL7 zqmpwlYBw3ZloY{sOCJ`|H{F1*{5zk%cH+-~Z}#RV{!sY_1^K2DePO?4?Vm?={ld-3 z*F|uvAlw$8b@&$@G|Bb{pAOP8Y-gZD-#))IQgx6|iuv^{s@?utlY2}<7G*Ma$2Nas z>v@Qs!8lYuqv~muuS1ZpyD|Q}fIF{VIq1&Xw2Mz)AK?q}Z2-Z0>zvCtL3**Iq4ZD2CB852h4WgApHJ^JfmC1K8Q<+OM8d`8ovoDx@C+?z`Xh{*mSy%WJcK;URt!^c{cj@h@4dygWX8 za8WuODpALy>fjO7!F3(m1L&~tqoL2TeEl`~;vF}IyWarUS&I)htvil)z)#+L^xMs< z4od9zpRpe?ocED-104<;@Xh7q>n40*UwTK4chD@nn2cVcAJY=+Z+?pJ5d*%CJNWcX zIEM8FA91zP_4F`T>R*r(*G=pf2B4-VM?9|T;1JZou^a1%7Br-BO`jW0Q4POLxRXx@ z55a}`W{dvw11zqG6W2-NYVZ$rN3ST1Cq05XC=}nn`sw)=aPm#;f$ah8_ua%x6V!I| z3Gxk6d@mXB&8p4UZh<_^7v=#eM=vZ?`6_YpW%orCvfc;n_Ue5%b@t%sVtJn!s;N(o zJ=lK1&I$~4$gIPsgF^fR#1BuVyqv_ob4Fc0+#u=4fZKENhP|r3j?-fPOs4!!*OAlE zJV2XrIr(}Xjrg+}P18|$QcMP9mmuF{if zfUmtCAK!Ee_cjCEY))J|(E-L|Deu$;qyxN?6hR$4gfIBB_pZ&-&12>Id^))HVmqsW zaNk`Fy z?9{eUhcjY26W{!}fLaGXwYVbpIylQW zi_-VSlpXhJ$fAsGb!>cDT<39YXQ1yJZ+z9A#r1RIdI&D)TWRgnLs;BQPFyJ~!uR#- zM}f9B{miF>pYVl!vb$2#kl)cJCns(mX}8h{uG7Y)DOyytuFQ!morvgA`go7oEUu3e zS0=dNf1lYkdmD=@WyjXvJPVtI{g+zbMZPx!@w&fkrM~KU^;pm;ws@VjUpL_kcJ}n) z`MQ0E#5H{OU~i1|1^+w!{OZ;!Pxa{F#PyK*Cd|7(eK~c9il-jEG2;3gYV}np9a>$M z$E$eiF(*b`R^K4O1-?y2)SIf}smCBEuI(h&7y8>C`7w`*rydj5^0k|T;DY`BG`$0w z4{4K~6W2xI_HMlSiWU|9mJ}zhm)HZ$-!{!2g+?W9^2CU%t%a7ep2Yf=L>JmBCD_ZB zd38ONwFf`Z0r;-Ut~Q?q^3I9PKd`t#${t1@J)yhbz92>&SX|pFtONLmDZxcL`;`?w zJM-_0tiuc&q5pnBkXHu^w^4_Wo@4b*o6D!KgXjPQX7IylO<3I27BBVX1Y`~(;LS<ppR(x?Z9P-q#i&aUaAFng0%Ntj=SDg18>S7wl}<*~D`yu5?jse(dRp>jUoW-Ob<- zS5o~iTPZ-|DCozogT-gF*RAqqxCLaqD2)K7y&Gtx>JTgu`+az_!JGTY_eH=S9CgpU zDZOM+D9S0|D;r#w7hwN;JG!=_|6>y+mqDQ@r_6A@|Tv=Kjb!?QO4CxvBCEejIzh zkPY59K=_tH*G_-*Pf}6w4I+;KIuu8Lbvb`0Q$}^!{RQ&{*^p2Lxu~Q@y#dw0{qT_#tpWp{X+UA_I_c+#C96% z3j;;_bz2vyxSlxtgAr~PT3Cm6gBgH-?af<8Wul!k)7Mrl;vcTJ>%LOz91TT(%}n2f zqzK=|Mab7reQ&YrGt*v>D(N{zJ7dPzM)-pNeUo#&Pd0et5aoAvPtL7hRD5&E^Q*yr zUrdVFuP+WeGvb>^`SpM9f2?WP;0!*O*(o!9WvXBN6z&&VgyeO6ajKo*qJdZ%aeR14 zi)x)S>lZTl-YxXwp~L&^mcFsZqDz?RV5j_g)%=t=M|tc`WcrQBYX{*A^NXR4mHN^s zgF;bGnelZIeF66)sUs{y#FfnSwS9s81B@3nx}f{d9C5*ts7qhRL-<0R`b2Jr(fSh6 z&zSL*316_Y)u}Zfllnx*VXvC$>!bQbgFM?mY(1;I8Q%ozcjc}J`j3?2RKg5b%EjYj zO+>7z{f;bYj1@!ebu%3tq+gUp#eaIZZ$E7<>zo;`i^Bb8p1jTe zu{2&=&njoeS2~0H1=#QDS`Rg`!eOtQ;vR_1vzj!Cj2DXFc;O;CBqAc2fp&AHOqNmf zycu5`(E5$oX(&o+hrW5;xb(rsdt=>nSZ_07ZV`c4Ig>xao7yR$Ta~Iu|CK?oqa>|Ua zhvK_-)guT2m-I9jTb~S3^TP38o<1jeqmVPW1T18O^XX)L67Fkz`AX%U(job?Pm10*%a=Tr@k$&;yOZN>l%Iv_w`Dpd@8O>5I68v#Glm~(Fwvo zO-dik_q`5<;(H-C(l0!5@Rc=8aK?Q&5}#G+bN7$Z6oW!hPMO(R=3SBJy}nxY$Y+vn zhcgN&x@2Z&K}v^ju5>}eJuc}Hw6lB)H*sP1OchrV)Hg`Q)#V5N@gLkL6i+hKH~1p9 zf3%S${WLh?w1nmb@gy@`iR}A>pUl6lcU9@Dcu=uwvOyJv*co()3YFUommV-E6y=l| z-!v-jyK#J53OsK)o@9obPu7hfo-Al^C`IZL530EiA)*85JNwsxUxXjv5eKvxUwaVu zW5BIbcH3Ry2O<{%u7{d;r;Ya1l%9_R6csh&n@h$a*q5&U$HO=)vwFP9Wc zm!6G|!(KJR%|sV~FU;SroI>mNajy88;krmahIwq~y~}S&uu&98GQ&-$a3_`e>6X-2 z3+ioVegA{3trE^9bi_Kq`udKNCof2^7!-=6`j5jg+A+q_nZV&r#M^3Fm^r2=2RMuC8H!RLz;dr>}?T5Z3o_!;3uY_C|c| zM8FKL`0^ z-vaExD7kNoJg<1%TfN5`m5FxF%+9jV1?b1%AGW67>yp|;L(yL|<7@u`UdQ*1uuCH87@xuFGx6RQojINpLOZY>Yn3zO>pl|c7s{6H*%Am6M>50BrgUia+|n)*4ES** zGh83K0QL*|b}F-}OLzga2yp#`FZi93(-&Wo(7b?737qYgLvUf-{HhbOU)?uR=y%b- zHq#-S(xJlnJ)cNb^mU`1F~e0TJ8SyS&RbIZXejz?X1FpLH=*5X92}Ej{3|bdJoStj zZZ4(om7z%AMrsXwbaRfIcET6plDyOTx578_P|%)IeB+y+v>W(e=d{kHCAi@+j%22T zgUsI`jBJ^{yqfe{9H6ME8Lsz8#6Qd!_~@_FxAEgPFsS0Ea0f4Z;ezBgC=}(C8Q(l& z51{Y%lju3q1EYW#TmoFfWXJ6dpXJXQN8U6n6Xm2CUxnxZ?bfNw-AARDqktG(GQ&-# z`rGSoS6V6!FsK~ml$j2`?8vxzdUa*AoQO+$&`$$`U$#nSxLLy^>u0b3wGFo6G$}Ei zufGM!JQlcx9-4YadS3%;nK9$*J&XCmu=d{Cs~1_IeDny-XnG*r1hx+3lhM2i>Vf@s zT=V2sI7g?1L3}#olYRl?ThjQB#lvqv0q1f)uh`i)qQkWx#x0~E!!I*PzhTd-dC*r@ zGt|-DIWo?FJSAxwyRH!|$)|&B8pehFp=tlssUdwwy=e?D&G_1mVqBQMK2a%YgES%r zFsg_du7WOrJ;1oRV$bK_OUdLZIy2L5N27-}`S)0V-(S{N3Fpu&)>m~jd{KJA&WX({J zN`V;SYN~kQOMf1=Gr--rOdlcK0^v z_M*X+DZf*7JDObFt;Ka;w~R})71Z2KtS^jjRcfw!SUnxC%9k_QxeLTkx)LKWTu0g{LUZ>sHGie zA3LGLEN`uYt`0ikqsEJz%qEMZ*+!+z&mq3hrF1E;4Q@B^zyHhm6ZL9s%HZVdCw##k zq(2)CmA=>FTIJ02^^@N(1bzQB&^N@%H|WMXKs>qc+s9f+v#c0uubb%`r1YI>ps%+A zr#%q=3w-wvzoRqHzMl3I;9TG}tOML%?Hk!#w~A=5Xvx>m&g{i8F2sG``1C~ztZ|L# zN+D{TzpkVWlx7+hGd*c$XU;(p9cCElkae4-4uGhBem3ZZH!4eO4U3tcG}9qO`Lo#u z{Wzg7A72OI3nCqFw)IJAi77S13ub)t$b269o6;c8%>Y!#3|FDz_4OUw9hR0F(lR}1 zhU=#MWbq0ubmN6QhOb|s+qS}f2jY@aBU)^ga!jciUO?3i?Kh!q#Ggqmz}mDaGlkC{ z?DydNxnSS)^A_6|X;H0nX8O7)JNy3O)6=C@)>w22Gh7ele}i(xRJsnlwvFX$HxI@4 zER4rLvB=T$X6{Q5)No#1{n zDX%-9zHlFf4IzQP54PHWU8<*nwal358#s@3sE!Z{3eb;{F)8OGKE4XoZk-L<&G#8! zySa#+LA?I+*K2P{cQJ%5vPcKRc5_he_NYO-1s~k<9z!1$oenzjfW;qtIN_; zCh_TDJC6Gs=+NdwEI+fKtCSWqwWb7C8;N$4ms4m|C32~c9H6{$kFp= zc9u^0^*O7iPLk?G$6>FU>5xWrfVi)Hse7)m^)g)6I>>A#l$S}nK_~ZaYu!%TsV(Hc z%D0b`ORa;ykvzAn7FCiwd#vrOBwGpP9fWWAd!f_%{K6KowY0=F^k*(g-_8d5=Jc`F z*NCs1+%FeiM?Ci1ZkBJdHD9($IBzHM4&YW9_~65Ap~U@`IvC#4>L&UE?%r39>(&We z)_e{1O(*(7{3}29t!|u8?Z>BYKKVWltVAtpaHpTuA=8>KTP2*&OvU3o_{rZEH)+lm zN;+(+7cFxQ{xQV{tCo8p^AYHi36>5Fyd>=inQAWKE8$@FE|L}f=~$#xw3hid5JoxMjcXUpU^;IlIa(E}Tmya)* z@l7Ip!B6geY?)3fM?-7AMojEyu)bgq|NHyEb+(LSytO^Bbs%3rewP;JoB!*r{~c0$ zH$Ge^#W#C&*%15Q2_N#|I*7i&_ZtJg361#lbyIw&T-$Jz<(tjPH;v-!GvMoqfv?Vp z5V@pHk$zG4=^O{k*D7yjzaC15_sjG=$>OAD^0k|dJWm1I?Rx_qQX5;hn~@IEX6z?n zfnf66<>UNzY~kt(`!OXi(E-NINw+Qkm@SaZx$fzv{MoWaFN|by6;2%-#2(;&f<>;U z(d<6HWM&VUls{`WzD6$=H93i|-BPP#`vrUGHKBZW7S}3o#@G90#7{n-a{O-=$MXgs zUl$qQz#cAhj+-nO$OowYw(O;@nF9LoQeH{hFb#d?3p$nSV5dvFwC+$Wul z*zc>~A~J)}*A*`1ppXdCQt2Y`4tN|Jl3p z_$G??y^R8uGblm@gatXm9T2gK$npiHAWGzrDk?z*$|0tpSWzT$Sr8#8M^V9Wh?O(o zRZ$@vLPd^vVZ9*8RS_hDNCA=GyqTG1GP~PNW>bFuFrQC4oz3nu&pz|cJMYX+l8C}rL_gX*Z>HolE#c(&P% zjlXY&zXr-#L|<4Z*qJ)LD}PRCvY0<}F*+nA(EkQfaJyL$(c`e6AkL&`XC9&h#FM$c z-DtFnPI)n`YiQYno6%wMh{X9Fnb;rHopx@!lurCT*}96^ zZ-}wq4GCOV4l+7y`)|-)NCz1>drf}-q?Z{lMla4?2bgRs5F9T;#2%_5utw|u9K>S6 z|GpU3qqO{kbTks5%}k)aX~a*$bM#F&-37y3R7ziBY!6WvkV5j2NZj|(nc746bFyOC zho_~3%;=CeHgSH^L3AjKi2m=dZK{63^XJQY8B|Uw8q+dXsddJ8A zOyg0LW7wan)i11txZPm=ci{7h>lZnUJuK?eA;j}FD(mTx&-k;o6`xZ1Gq<1)@Vz)N z?}PbJ?ug5pY__JH?>GB$XUBR`+<1v2?l#3YLb{e>;4l%#uWbC0+0@q>O zOuu+(M&LiKdn)Oep1#(j5&xU2p+mtqV;!{W%@`ZOy+Z@n_qws)(ZcmI{bEYzfv_wU zSJKnLMsxuGFz&tmU3t)~*OuKFF^re;y;j4-&17EF+f@C~~=OXofZk;ecsSq6? z-nnCsI^I!wiP=LA(E;W|<&+t5eo6vIpISQjNq++!4m9tFX7}+WJ$p!J`bEy-$*MRi z6vKXSEhb*Z9=z)hp3pj{q+@z~Z8G-1pzp5Vws$HCL+d>~TxT}!$FL55r0fJ6od-y* z%soGLEW&)RLAd?)FB-1Jsib4TSIZtGvcCkzqKxZ%s@CO7!i4wqbg+`=u`s@+H8`(Y zhY`h<2`<>LeQk5a2#0@PkFWAO))#Q^KJk`noq)&T%X+vDf(uV@9(n%Ao&0r1Wj)+v z!}T$^Ro|_u z+Q+X8NZ!!H4KTP>#>{POgu}nDhwEhe+n8T3%KUXkWj*17gzq&7VCUkO(0X-zNe|ab z?5rGu`)N(@=JBEG`-dz$wqKaPxtAtxJ|7}F!2DwTqBE$L_>!IuZo(G=sKI{;^*60< zA!QR>Fx;;-MtS$&V(XI%S&st0^YF%LFUO~Xe!E#~;OD#$_er1bx+_t*GFs8GA~5j3 zdjqo)7N;r%7sMa%XYI*};_D>1FurZ8(r{YBa7nvCKVH0R%%nu&y2!W*e!asd`|BkN z*UPlq()G2QB?>q6N5mfbTJPALDBJ+qcLnFN@^99c7wUz_zxRM^<6yy;A6a3_%oaxDEkR+Mf88+`J5meV^gZ&=U5Buk$pB32YmZ6iwXbd z-H+erkJGZAzNuDx9r*Q*`^Mfz&!>4HPi!0tHpBCt6a=*5$elfD5Ar(A?I$Sci0uL5 zlGP_Z=}dXXn(OHhutq*lmgFk`Myz=BJU!gtHyF1LI`QFdkK^G)a* zH!LYo*@G8-7cRV~m-P7B$T$xj_^l-s&!Bdb(Z7;X*4#X{;9ATFaQ6)S@-d3*G>I#H zhxLW8XSi+N=c;iiv_nka^d8vGV4dLBt-H~D2rK3`$=CiA#s&Y-YMc6VmKnE+tsD8t z^G4`z!7*>3eu4Q0<9rTTG{13_-8hIptAcQ!=#dHCE-Lw!$Hte(brD<`hu-|L!}n33 zs9=3pY#q@}aA7*Dw5NB?I~s@NNBbi*z0*^^Vwd;IH#Cd~=fq{Kvm< zRMz7gXoC4dgWY{|msBGh{(Xv@_EWSygb3gA=zM;MZc5!%IrR zudXPEmvRGsO+h)l_@t+=(kT-6bv~4_t(b2dzvs@^1!WJT!<5RNXDF^R9k*L*ygJM+ zT^+m(-}LfL4pP2B(r$$Y`+`*Mwybpd`We25g4TYNuk<(8H+i|(xEW+{f4pYqeu^s- z+<*bDN{4NwtV3mdzu+HQmVN79%2z=PI*I?4 z*O%OG2p2*yRSMmVaUtHRv2E8Q{0T0D-z`zKTiJ=FI=&T=bpm+ydEJXAF7bSg$~@oS ztCud{>>d$)+az7=#PdtlZ#ohb8?xs@7AT`^EN0SxJ9`xO&*df8XZm`ZpT(H~x}vImqz!zg4uFKPhXI z7_M{@>kE8)REJ+T#fr%$=R=_;7#Gmc&sN9X-}Kte&hUMFR?|h4uVRv~gTb{wHG43{ zb(+L=Gq{%FExx0;67j!$JMv{c9rA9%@jC4PeayQOjTiV#xu&^zC&cibIPCReT(3zT zRZ?w9N@*$f zIbk=$_thV&cBOn}ll{$4#$$Nyv?_t0W0g*0dw}@t;FwAeP`*Jj9;3r0COta~ka++E zZ+riIIG+dc_7aO9WWpD4%hhbY3h|ZEzmnIazPV(-9Qd;vs|8-6I{1g;xESgvDe37T zox#_`^ML6yueqD@4VuK232t44oB!VP@Z4WUub7h_-vVN15bsP&;C>i|;d^*?5n8S# z42GH0x2O${JL)06?;Z3aubCJfLjS}5p#}nM{D~9oUdDW#CdW6I9rrir$Gf)uo3OY< zA^oBf!d=np>YgYIr{K$@)=V5vOZqu!4b=$_f(w4V`uC^Nsx8)6uAONL*F|u_@6-uA zh^#I#?dBl!*vbfSLfOY>({__==He1B;S0FiW>$voETdPnV)PDvE5Ozadk?xc6wnlQgEAq%h~Oz6iKkDMKtD8BC2*nh)#+_vIF$B{+C z&=GUevj>^*t%8uIkF1NL2}zC_6rHGt>v$gP0DkhqS$7MR$>yN_H) zbpZbsOVYzlxfk<=b*^4xZbIy%Q^+M2M|lZf(0ANj6?;>@Xkd;h>G5?ic9t9*0jJ3^ z0g{vSaNX#W9ALk|H+1aKig+;LTs>ST;S2ZOv*zMo6NOvEe2!|q#^+G{1!C(Z%JbMy zRzpPJ)WEe1{w|`6!F^i;*Z;8CdQ>*^`K-a&=jQVI27VFKAwc+|jwbEAboN0W*SSv& z*Z&H(Gq4AL#V-nZT%)p{ok=g?c7uIwa-H`V@Hh_9@6BiQt*3z-62$d0{-IZun>V2z z6rLl?9&_<}9>e!04ZhN#lGlIr^bIh$jWuxdV)#COzD=NCLN{&x3ky}sqOD$EemA&u~@iU2=5{Z4HjH+zg2Unju@f9Cz{qRO8Y3>D*>#o#W| zz|A-;<|nO7v7dx^=bN{0Z&N(N&NAm8tS{nr10CMg;OiMDrf)jIg?`~r&v+GOQ7LV_ z7_Q%s@An3T*7o))C|cvvOJca5C$J6>^Q4SBhQc1~`4p4-<`R2=ap*#`G=*a;<&F@u zGiTGt{vGMZNys{)lmDogo#iq*Z1X?Yo9f^+se_-<;n53sz81|^lAMKNd<$A&9pH1f ze|+5=%`b4fx%-;y7X^eb;7%_;?+nk^|D;&Eg$ORJb4~bd!&V+QIa|dxy3V3? z&-jw=INuoSSP8*-I;Cuk50$ot`l{sLaeo7ScURf~)2*mfFj7okWiR%Vu)g#C@%O)o z0!0PIC59^#zR+%euHCSO#|;YN1{r<-wWe&~aYGZu_Dg}qqr=m0sdaF4E}5?$u4`RHhY1(d zIur?hzg(z2#)XX!ZGPE-hGoLwHFN$fmFaK8t?K@kl_sWxhu8!3x1lH1{Vmu{3^(`# zzTY|scW0ZcK1W$plJ612l?o!bo0jg~9tDaD8TX0dy4|?HLA<$cJIHDJ;>-^$!XFa6h?>UJ=eYkm~1L^80r9&R4Kb1wqJPO(m}O)CP_Jh^8jgB zq`#dx&@!E`*m1}(e$eFWVfc2|;F~Qt53mxx&@XCh{GM7q`r&Qxqk0MTdQHALgs%l% z_>+cn${HqSXO58(ecSw|);IZxp}v~8qEyBG4b~BB=Jgw)c~S`n^>pwu?dH~Kw~XOp zI>?NjrE2KlHr7G2-EtYeQ#AOx1?K^_!I62(pjNl#7LOONn;S3ejQu{SVZS-X^9xNK ze2o3p03+s-OE9i>yCU}6EYK5_fRvNgI?-~;kKzoB_nd`Yig z_!&DJht^j4U>&I z&{xfXw(y|v_gu?6#eB(edY)dcr*A&d_iA+E%q1IC`w8*|<8=qIGw_r59-h{g=att{ zY&;GSzVMK+|E@!S^0@ZNV)l?n{0^*Ze0*K)8>zltllI_bbm*<2L+%B`eyr(t3K$&* zYUp5nSxg5P!}o_X>UK-pg!?(KJ1y(kS&-p-_*ZqiWn~-k)zqPo;KGFa&8kNxQyw%= z7mQO=hD74u?MwdKOzlCM9rHM($v4FCU7*3Y@D)QH=&eQNp>HGp?EPJ9RPkiUc)y$` z-y*^n=5H^((GHetqmu1aF}{IG5q)isom)@!l}+j^-HOLe;QO)$-{hHMd~F>uU+}?? z_kPqLB?2lGJRs)Jk_lh1-$feskmC{K>p?5Yz!m)ZkKMjj`Sr8|hJ4YL>f|Q=0miov zC#%Od&oyH4gZF!^FFYrEI(a`@pG=a`zmnhN_+};gf)4M$s~+EMuZijFCgVJeZ=alh zMK!+pD;Vma+22wKUl`xE|8`h4z9r8VY-e zL?IZP{kHpoZ z{+C%uabwLsgfDdRS`U7nL)*=5a=)^V;DX;-IscV?D3j4E=A_5hPjF#c7wpdwrCQvy7-bFuD2=Pk6RbPWsm;tr}$7y;7fEUj{w*78U*lh zB|W}bts~>x)#I;k5f>;rSr1qK2u@$>(=e4@Dg_m?;35Qh{*~Nhe?Rn_Kgcg0>pDN}z`MC}c!G(VOLS}<56gOy+ zubtVie5m}~@f6qjPt1N@Q>HY6TMfP2XU3hYDX!Nft`*%m_+J<=ZmxK4I$wFd;O{^? zPDaMfI}T5sMfv(o@(qx71HW@!*0*0%+@ML^X_9Xi<9AL^O?e%`%h7~OF41=5&+-slSf^d)OAk`M z!Qtlmn}hTV@M+hV8~858RZQaAiM}wtJ@EUT4vOnEiJMK<*FlHsj}@unk`%$;XUJv7 zA@6I4(KH#iggbV=&{b6_z}T;~Pvai^3BfsH^EaguZg+@N7v4Bf_3?=0xrVqrm2g?U zFEYOE>0kXN{-m@%V*Rae)~t#8`!T$IV^6?4KYG){j5k8kjxW!dCfXd5Ly(`k~gn;GAB z%}ed8QFDoh^!WOj{`Pb5@i8TWXuPS18zSun^MKAP3*M(Xcune%j1&bQ3GvRdF20vF zD3y3fkFTHD1H|hqr$4URe^w$WdQ%TKo3tBpWK!qhk6bD~6Md8j?!zeQ;acCpI)J`O z1L_Vf#+_>pH$Zd%C%X6Aj~5&9#3l_s;4g$_hT>Gd}PKyWH9mM;8p(&r~1mT#)r%6pb#Cvejf;IU%=~-@ndXp z36JYx#}(l*5mNKVwl%_a5=ammmR?`xJQTpz)O3Ad|Gm1Bv*^)q~j zNWo5`xO_kM5`CdxJX>o)Lmt=mYi$03zb>EAA-Jq^!gO#G`-OOY)tkxXsr~v*+HZi- zcjl!x@8s{ts7&pQ*Vo64L-*}@#>M00Zxfqu<}>@Nn^yP(ru9+DVZ2`>>U>&olYP*z zKwx`q(Vz4<%{{%v*10msetYnf?eafY?XS)f-3LPSg?VAi{C*b7GuE888-Ko^(P47s znX3Ml(^pJ~0%B({zqqU6N;JQSFX{1hGy1;XWrZqEO*P(MqDiEH_;oO_>p$%_Q}d(} z4(johe#GM=*x8bU6+h=8as~I<1c|;dzsO&*K-F%1J$zY@Zw{mH+8dgn_$)dp1%~_D zqAwt&P%`fS^-y_Yk4mcfaq7=vxDICi)@RLx|EQmI=9r61d_;#Di0}PBeEvFrQ||Jy z`7_>6hL~}_`>_IW6H&<_=qGc?@A*I+HLJt^uc!`glR9L-gyX*I2zODrnJPc&s~DRO zQ8x*NGPr%fpLKqG;StK$8RtBJ#|<8g^tZ?69#D<*c?$%`d8S{uc3%9JuQwpL-zZ4t z0bmHB!7qP^bdb@%=m)sX*{@VF^4x!7XzKf6Oy*DOF|qzuMEJrw?dmR(?+taEZ8t{W zS&fzrWT=M!wayi5H|sxukz8GsecHX zY&Yw%$ofO?zLn?lI=J2!Yd3{yw`INuk&z|IfbBM^L)L@{-#WYQ9|o9g@_iu2*Gc$7 zfBUCN)p3-s-y~n>VQgo$5bm}zA5LPqhX4OijIWFEg?a2xZ{3Q*)g&4HD+Occ3rl3G zWFz(f@o%4{Pb2>joxFm4oy1Rq4qLBR>)?7#EPn7X?bd%yZ=^5wXY#q2$4yNg6h?<$ zAErk|nq2G?r6Vum6^o8+aPF{u2m?->LbB5nmawgC_arGr#Nk;?@1e7V9uSHapX6Hy3F)h#w|?Ur#mf_I)DO zZeB*;Esv}9wXHYA)wHt^883kEONZ5bL&mt!9I6yx{LZ&27t+uPvg)J~4j_FsQ_83K zKI@}*zqqRmnh!;%4Dx>T(MU-TH%RzaL8neyTILg!$&ss!|3kQ%`ua(`r67pTZ{3#4 zBPD-k*lzqKxO@k;Q+Q5R@6Enw-99>HJs^hbJ%VweAAk4Hb)%zE(LR1rzGX2ki1fdS zNB-e)jmmoM=A4XiAx`Z)KNZab64P$kOh0}t>-JlCe*VwJ^erUoQE)%7CKYd@I`Hcy z!Hf7gI>bBA9Qiee$CX=(#SeC}Ujw+_+y2`Zd0eA1;;Y#&yo|n{Y_-114l#X0L|@>W z`p-8ad^K+=gYW^r^Y4^qEBTXbC&cDMsYG9R?)2ucj;(oIqq3g9QYE~u0e)xfuj=1T z4SXf0uR?GkP7N+u6y*8YPa5i=X%F&5Ja2)xdgT8GLKc;5yT$lgiQj>FOPMFm#_~u$ zs$SaPq7I^hlhI+{`)VBu{xZ~ohYXi}Xhs1fVIEs9C3BtTNhKWAvxhv=-$2+Az0~@q z2gLN18NdGfvy%puKuz;4J$)aDN{LEi2 z8~?7oru_zpzCiT8%6}f^ah>0Y>1$`~ciV)Iz>MQcdOA4wVmkxC&;B<>wGSlgteE{O z4BtaFo`J79iYw{y^Vld+$i^wmmlTu3X&IJpPmjO^1Gfe&R_RnSDDUR3HvAOZGY58aTSxep;~zT9DLfLwoO}7TyH~je1n8nO@y1#<<&kEH`v4+Zs1PL z_d0}Yf4==Pge#+eCFurpxXJ-+XW$>^{<;x)dE62~ll#O98NTgUzRk_?&8UrafPOJ6 zl)I4Xpj0r2n@@0I92$S{Hy72xY0@5?%s5oz;r+sXhmWhR&9I+@`0SUS8Ld$km4aKv zo)2Z;hjGgww9KDh`8^6WhJs!{E+YC~k1(1I3~i?RdQG;Q{VcX$=*P2~?JHiFlggU2 z2PeUWao+aIsX3IdbP><%jHJ-h!CMFO1sz_>nD#Wq4fZ#On?mdX3~cae_`Reg8T~8C zCizMqV|##gxs88q{g(1oOyXJzE{qp>-GA*zah)b{gQUO0I>855-~SQH;!1k$<|F+W z_%=Mz=nu-*Ym#q(;KKO!+b$PcPbL1>ByNcDJ0sHqXg>_bmH#tmXHq$QJ;Y~M?VZt^ z;wmO_T{mKX1^unVp%xB`8#L)3LX3Y1HLo*`;yO+8wWdVI&GkdRDdsEnHK(sk`UT9h z?)rTRS~tS&<~7OJi8?U&NEk0Vta}615?|8m7j|L~!1wzxImoRM`!&f|A-K>lo|u%} zjp9m|%<1c3`1*FwXh(5nlekU>x9+WDkT=FUC?;{;MUnC1h4kAuQe3A=TsyHd(0Ad^ z1@PQ7Y!F_PxIw}fY;DuNmI$8MgGpTLxrh!m{TGp6$GDPYZk*4XhH-)KmuGtwk3+Ia zTo17aSO@=RNL{opN9@5Qu9va1S6a?`gyOnQ#_K6}M|8-%+p!~T49uU@U&ZF#Uea!` zzhp@6DHKl1 zclq~?%6hl~Vh_l@OG6smy^HD)G^s<7;KHKP*HsUqbr`}R$y|R6lHU`C{As%nw`J2}}y(7=JXp7+fk7uhFb(}ABK=aYB`=0mqWaRJSTqEmKzF&&EPM)V!K=3|xp7R?va!TNnf-@g}q zH9VRv`VEgIhW=O6&J@&AH169xvR54*w`i#$E`Le5TtLPPu!r*+e3gg9zV9`S;hV3) z*ZZy*Unv>)V~A5P%ze6$`Ul0NKTBu62X2PO_rN8;C&pJs5hQK5eeFCp%GYUf4@@g?16v7wgLw8mAWeer2#Lky* zl5p8e>`SnqrDhxtX*U+z4EGMUFNsf>E3 zroL{X@73tyAUZEZprzv>A>Uq7~G!@ZGz>EsAMtdioYJesap&|Dxx- z(JB8_YX8{zpM?1O%6ct%GW_xZ_j&5M|WdVVK3GBUn>rlEskG1P&nCGxL}8Q*-p zn}s6p#P%QM%f}_s{)nHHp8H<|9xd%lv3_hVisXM#J?~^S(x}5vtNWU0uTc@%!z8=1;H@*dkpM>?_Dg~=&^4Ap!@=arO_(4O5 zf&qs5YWnp8hVS(ne6z0>(>L%=#2zNqI`R_r>)toat!sFgcFS0?Po&-WCJC1V#6Q3~ zOxvxk6wQ-LIH=bzq^t1w1`em)-#wsv#Fg}L3kl!r5Zc#QRXraUC^}gWH+doUXEo3{ zKiyzMVGlX;Pjl_&C;QjI?@Ya~>gS2#8z8t~+_SfLS3Sousz*VVeA9>GegXY$r#!cKKcck2oW5Cg@VXq# zIa6nqxeaA9dc~ad?AJrqx$7gO9%-wK?ZJt@$^_~%N_x1;d-!_TSG=}LTjY1}nND(C z6u00}tS{_)9rEjzQ#_92J+bvDISK0vabL##pAYf4+5d>G!=y5}kGyl{eje8@_`Fa$ z5$VU@cG`53$CU&>_vIjbLEk@j&A*q&bqL}H-p1_)`abv5l!eqDf+x(`S>b7n3+vUV zpPqp}=M$Y$n~TLIX*Xbf%OSYKAJs&&x%iS^zsT;2?F<%_zr62NG@VV7(Z7j^ z8G<@E86A985~qWU@CAFg-*;j=&o@tyubt=%I#@DqznS_ScP(@M%~uEet?~%BZq{CC zzNqAGCFXbBL|?Gqan+y9E{{Z&8 zddsx6)IS8@GZ&WxERlG!^27r#^8B)r#nx$qLqY}^bHzThBhY%N6A9ADDoD_w>4g*bKF*d=XvRIi}E*2l1)1i!xPg}-b(u2ET! zuaCq#(2uWn!Kz7oNe|a!$9&NOjP%x<8x!_iI`9U@g?RF>FFx-PA6wds)K}#YzGcx{ zpWis~NTjXtxO;HSNyh8kP0*%_V$cp7q<~Et(tQ z@bBy4%ETU^zvVg`tfuWIlXX@ehcD~l+6gX*-|pIxv-#_c%6hmyMu+{=?nZHHd`S=2 z&9vLn-^bk@A1YN%eN_?pToTOZo6H~3pFbmGwAeaK9?=2(S@l~B6Xwsdi4I_AGv57T z5YN}Btf#M!_y-t|*ByN62dbE2(m(hadpKi5g*cNQUxl&X#}{$-^nL@!9P6J zeU6XE&8aSC4<4r7?%3R7D35DY*3-c`68p0X2;kMPzxdP$hksuW*Fp3J+&kh>Q2a3t?y`F#2nP)>m)irTs>#a)|JKm z!leIo5WXAqrrla@`b`y28iDKKItgE}2anRDw-FBiz872EAA|p$v_}0oKvCRW(vQm^fbQ+PA2Y(?-`C??K=^`R|Gn3@()}! zs-m6_*~ITy(G^LPYA@z5%>PO(o^+9Z0V3J!b$gA+H7e`rTgceMtKE-6coLO@e~a<; z6Z-`_8&RWAyC~2Y3VM9qj1I5en!ARFDiYks?;-vH=CPU6KS-E=@DRQ*9~zoB<_OQ% zsH|sa9x|T?JDcTOs+zZm;^vcfgScen+V46U;qdS4@%0fMV0>$9^G@KeGb-!h1{l7p z63DlJ!Cjp|+@k!*bG^FRW1i&i+qy@rzXch-YZAz}kiqqd;cEJITU#7Yf`2&C=VD!6 z2cMu0A;K5Ni^smXFJa@RkN5|;nP)aDBJ*xd9Rf^T^5TP!f}4m+1&ZPNuO_aY(YI~C z8{{ZZR0stO?MxFlMAqeC{P<7V(YY09=2bItJk-yi~JekYcgI}$o<}kaL>J9nMZNmvFm`Y)JPQ~ z&)@E@&v%?LGnS3noB&S=hv-mv3<(u>I>g>&!Bw$vHyOHX1!LT z0~pKIdE@$Oo>am?J-#x7``r01!t>+gdzwb=BeD}*7&kYyuK7QnTHumlKjtsNW#qx2 z&EWe>ayR~WN&6)Iqg02Y8n!6D3gHWm?9SmoALS9!IvV;j{*rLna|e#sVSZ8c`m$e9 zCWqgM@lP?|`HiFaW)b^^=OR<4u-gz{!Af$ z9mcl-@BOX%ULVKzvDpL9*Td-Wc%ce=0cw{9fN? zO~z4vq64fG_~(`XiLWmo=qwi@2ikZey@9wX}7aI|7p+HYgE>= zGnfI<_+c0Yf0aI=XHjS$|-F8?}dyU8YXC?Mk-EO5;Xv_;*SFt|GA`Gw{krZGB< z-y|MK@!%oC_geJE-O4-tDPP$nUnhx6K!-e^^DMDZ0?#KI(4l?>za+|a>nc;h@{p^Q;8BfyV>l%#v8;qNQO>cDM zF|GfK`5k#89&c?3Fm=eQXcr4+;5Dg377BF0KR~>5-OzO5`2~NUIUTS)z=oAUo#!8= z?ItyixgTo=Umhl|&iF_jSLenU|MGlg!VB!|nl8T$;NLeY>)C^cu?OdFwLKIH&a)K4 z7uFw+PR&Hs69xm#?cd2E<1zT1&ZqaI=NA|^c-|bYkLUnHQ2A|@s_}XTI*Y}V!DZNf zVctE~`gtG9*SXvrUwILp55YWk=M6(XqquI9xDJ8~`tGn=(K-y)*KZOx)EM6{#5)(#DsFWhO&pb$Y!Th3N@R(MVuTneaejLSv798aF)L^`LuW^Tu>G9%R@Ov-{$?sf& zPa9b2gKvuQ$Up9Lg6oJjtS{K_x|5f{ETU4{c`@9SKO%Ovcg~(EQJ|=hBZzBd_|}%H ztNNQ&aNnyJMW%GTs9FE7gpC(6;S1wt$E!DY;&qS&=NGwzFU+&3)RY~)V}3G#IizTkha>egWak84!c z<7+4V0t|QaKM()H<0u!!^tGWU3t+!6F`imh;No=23 zh~azbhIi2Cnxj+d4`R5=V(iz!eyz>dqIDx|>CP4A;*wwuj0^2{-#d?8q`1?Y zueT3wAHYprx~CE4>nF#fYf+c<{F#I33(py@e{tC({FVOlVtg~0cKi9r8P#*A`~ori zwN8rIL&4myRpXFN@OzVT7`_MB1ys0sKZ^17F}UT(@+3F77x9bgK089(GPe81E1zgdFc%bKzT_X~*6);3Fffbw;kj7ywky&Bdh z>+ML~_tU15^D0l-(M1)(gmNBSsC2H3tv&;CJW+*NWXyj@rEUH?<#J$mFC6^1x2PXFNF28 z>Q8h$60HJ?1rLb%$t?052e8}Q)|caPm7QYk<|TFtaq4L+v>x^kev|fVC+!CF`DT;6 z^C+%V2G1{Yf?_%-1Q*tKMmFm3B*m2pu2*oseLm^OpzmXsKHfud6@u#!#FcWfJ%F7J zd}V2|oq5grGr|knEzqvpT*}w!F=xLa;(x(E+_w=vzlrU^YqDPiiM|j&44+!5fa1Ez zeW1f7Cd@*8io7&3UTjRh5vfh=*Cby*@xQR%w`%!ozpHC5`G_807t=4QC+~Zl^7We3 z!OGa#m=B&GN^$)r?aV{?!o2(Sw>y5p-*v$bLBB(ApltWRB+f8kP0h%}(qW#?AhzccWU!nXAnCvjAgfUq3tTMI(Ov z`+9s+dte5Tc7MF5}9S~wW}_( z627pmalB@?sj3qU4(Ra>pcQrSub@MNfA@V$8TkJ;*WVn3Z!*GtrpkK;?9^}T@pY28 z8tlwF@7;6iD@#72hpP~O265`(UGtwU8AbiB9Fa$JI#DM<_18 zpEiy79k8<}@&}=H`{Q}1gB6$ypt^XfkkL4<0fegFQ@b z_eqfAx=r$RGIsXHwPOcUT)#uO6qkaVa6fhv9X!V4kS4Cej6)r6hVPNZxL$&rXN;@j3I_^_J%B&UEjMiu#SO;Z-!%EU zi4G7yq)c=a^Ys(H$vws52S4e@Fz@cLy=@(o#g(vX>PtKf-?m;!wVxnYkgxrJ5r6jL z!<80LeWjWv`vqfX<7ZbsroN++kLc-;M(hmix9v-b!e{j{faXgN@kD;Auj>o}UBlCb=L)70ZoKjY7 z9^fQ?rwSsvZ2gl8&$q~!FMmn6>}Gxk@8wP#+VUrP1o^rdKiU72_QQBwS6?xG3yHqa zkLNT|f6m=rPE6kr;~yGi`q3(Abn+YXjlO`CJdD1tYUmpf+{xSY{7GQOo(`)U_|lJgodzR3*V zQ1*Bqk86KYjBm=ah@U)s^7BuqpY+DQA5pX2ayw#uA%2+qO|RE^zP9pWI(V6WeD3Rm zn|a)Tpbk#*dy5c1?7OegFFbC(AYXT9JRa9TfXNF#LOS3Pz~3_FxI|OmBGNCwepl97 zHG}8tsUW7Wn~X!SZd5se`?-9i-6|m52S%=2&+}C>4eeJ`2MI;!5KDp%>ojzbD~ah~ zMLhv<;dxfYJx8~pEUu(C&dWs++@@m>UB`o_J|PzW2Fbh<;!hjFU;p1JKbA&T%)qyc#(!yUZCB;er<25-@O@-zpJjaIfl*@pEt&K;h<676+VCWgYpWur zuS~`_z`fzo#H~LBiT$S_+}#`J{Yv|VbicWNVYTAx!9NVkTMS`vRFX%F>1$>59igGG zQ}B22+{+_==Z24}4W~MIUp1$LgY;wQ7dO_jR*VuMhJv1-^pk!8`d&3%?I#Nabx3Ov znIB*C{(F(lin6${n$?WF~oh%CeC>+>LyVktG?LxVh0#MdDEhR%1@@(5F0mBnYeoDH_xk{ zqX)-`^<$ao$E~L}RryJ~;P13K89Q5EvsWcvUpdQ=FMmn69AxxuqM>gLuC&xL48AvzRSN=+pn{=7~ibP*gwE? z)AF01L*smsjQ*AUCg*Q2WWA8U@A3e#>sX|!9~En+%2 zn10bRH*xW=B;z;%0@N)x{HPi?J%arro$$R1;d;fsr&m+oG{*0IopiHm+>~w=(>KKQ zi&f=seVVt2q8G%*O-B)qt3ltLvo5sfaSNUmn;++raTDf4NeTSEOm{Bk3xUHcgBx$8 z{mpAKo^&w%VnEh|Z}2)~q>8nhwJNq>FqY9f{kMB=4bp_{j?dRAH(|DAEVA5W+Q*KUDNBYwT1M!OXle?C^zeqD?XH*4sS{iv7@e&Tna z-MZI0KAOKzqq3e3In48{?W0pv`!zfV#p3GxU}RlmK)njXjQH{I>)BZr<0s3s@uE*n zM5hd=n7&y|e0I;pH&oAKJ%WC+fEkB&Y3Q3gP>ipe@C85lMYpff=L>NQ%h%xNPK7^+ z`SpBTWc}=Qdy94y*In1#^DH;hZWT1zEmu&7Y-W6`KfQ}L+8WS$)X!q;QFg|!H_`A9 z(owN~;V1sA5+d5+Pzde+jZVS+V(n(DiQ5h4$1{5L9Tkl#N%Ao|ynyGM zQ$M-xEbSNm*!u-fC0q`Yc>wg|+CKH~IQj(l%jGcstiOgob5$0zhXSVE=Km#i;cqG} zUCf_ZuZ_%O8~1MgFOO?f)*IivjGz2I>?e(oqTdHxIr>nzr0mD`0PBbc+jX=^vouaB z;gB9*2l?K7h*KB*eeXgZ!dFGC-MmX9^TI`^j-%(iNityjXPb*BGkmxoUyHCB_FjnM zYI0}O%;AP^$JayL*XV(vkj0hs^v$^&`xSUF|6HFR))e#YZH}+h9$yds;hIjB5N>=) zkFS;BLa_OWT;nv4ntZL8J>(M|U|spp{sjl94zgJtkVk+q2-ZElp;~wHeBFY46~YTX z7y8_TZQPWv(|JBd&SYW_;2(lxzdwSq zsH9XE?ei{b`$`+ILmZLJZeO=Eo5KPR?7>nCI*HP%KU@BKpF* z+@IHNt;^%4HxuJ4-G}`z;P!fS^kE)X7Sz{8^o4==#eve(Jg&E;7+*KjZm#Lmn)A3B zt;BGXi4IpIz=dmfqWN)jDsYJ5S_v-nx5A&FP_6%F-7kjgAv#n7+*@9p6U`QV)^3hi zfAbPtSU1}I%=NW++(1pS`A`a@!;$&*7V)?l#(Xu`&wPwM3~b@Jo5#)VZK$s%uAksS ze75Dog8Pm9H)FqD1EKZ$ zuXC>`P*g~JM9i-%4BwBx|6~Y{TM(lT{OA1@qA%!h&z4`C@wl#rV*S{D29FnD4y$^`lZyIA~7s|})#N!&3_4vw!FX(XFhz@8UX>_um z7xTY%f(sibw_bb8iD*>x+3a*N9Tb8K4OVg5!W($p?1#i~om+6b)j@!sug*0np0|+W zd_8(!z z|1dvxzT0Le#SNOob&__gjBuZ>aQ#aZ*IC}&dTIgT3+t(?hh@7cuG=K8cP(Czu8(j# zfCixoF;!B%^;Nze!vt@ek0hM=o7b#eGmmNlDKhTui(9 zE5GnTNf=u1>EWg_IxHX4>L_hDse(Csa1dPRZ}Qs(Xq6c=kWJ#c8NZYC!cxsxOY8pW zF+Cm9Nk0a@uYPNX`EmFXr%ArnTCZkVhHDlbX18E9MJv^&4L~`|{iZnTELhCE;=* z`P~Qb56_<&`Xzso<0i4^kkX%#@nXhbYTPVAT<^Y!f2dsM+U>O6{3f51r7(Oeu2KK4 zT)rS*JA?c9;Tga1`r6Kl^|v$zH~F9%H?M(MyEz%$`S;CK@eK;%W~W5#;p5ZSpyik( z8MKg1et&gNOYG0Ue(&s|=36BAyPiGbqJDi9-f;%{Kr>M@j6J|#MWVKgfEQ8K6xCP2Sler zLB1&$v7G_#7aF+M#$xvCA#pXV8{NNW&rCXA$gRx9>k6a8&#Q*s7_9>OT^K>Wg~UHV zNBhrZJ4E>^515+=q%(X&8ho9CeDg_v1HL!ikmiZ?i_ma9AA)tyK&6670Ta3_vYrx(04a6S02bVQ`16 zQS0Cl#C2DS%wr$ezV}aF-#kHFFN3>zry4gXh#MsR4c4QQAKLH{wO{x9=K5QR{N4=s zhjWj1ZH;hc^sl7!Glv^wbQoLd2bI3*O~vd%{vGpz`TUV<)wtF-#rlO*IbsjzHTdQV z^0ms?pTTp}<(8^2t&d7_Gcg@fYewRz{ok)b`&N=<0Ct;fH&-&|3-RRZ+ZOu(lTEh! z#Nx>i>BkWF&9Qb;#ZkHFqs~yLUecRi*oeM>`&I=tZdz|K-1HByzR=(D+8yad`uQ9rgK^0F=9y2aJ@`%9LpEa%^EK>2=_zIpL9(s~&rOHD z+4gy=uhiIFydFG++Xu$^4NY#kKyhW0xC*%*{7$NU<69KhX%aW34sJK_5AS?FZUAjJ ziTu7fI$UDX>lcBJIIf2E>P)fEqifci@*(aQ5TCXAX8l^KgWqJo$Rq2iz;{tw&8ka0 zsHcOi7Um23jym=150tNxZmu8u$a4{xZ+dTg>+urFX}qb&S3xr?@PjZPx~9_OD>W`H z@sJ*FHt`P-PqtWhJ;KFjI!)>jWbABl0^7|++70;L`p>*Il&>V4^ACPz-F|$X&mS&P zOpQ17^bJ{XyTOL5fp@ZCfm(P>F>kkj^M460UF(*B~QU}~V5U9`1Jl-K@KysoUZn71R^U&YQ zJ>2>gY7b76>yw4V|H1<8ms0QMiQ;P|I>6`kp7b6={x`m)r$c~zE+6z=5d2X!4=}1l z4>zBUAJA^Oc#|G(i0F&lyOf#0{ZS4w4*+{OlBRxsVe2b450FW_!NcXOGdpidlnw!A z+R1de1=@&niYqL-vLHiv&+7+$h9iaB>ChK3? zXpy6OxJAtR!_VLLSNUJ%0WrVhXX28)f3I3W`36n$bsoe06^J&S8JJ6Py(ahf1xdVA z3*pwBvwv7IE~zh~r1pP$`pV=v8LY!BU;D>xD3i4jw2$iHrV?C;cUCsL^Ih$$^^fY| z2Fd+`4!=*Rik`;dGrcx*^Q@G0__+v51Q0mALK&eNabO6Se_ zbw9aZST_pQn|%yrGJ3_F^z`-L5sCYHKD9S-e!WcuxBLz1zwkth`ib@9gB|W|cq}^cN(lhnWhvGvm zwo3J7J+Zz}@7D>8CzCs1{XpNlthb_e!*}NX!(6{et&ed*hsnRM&84_X6LbE-Qx@Zb zpKQ>rZ}EIyHrbEeL(%nJ2T@$VNgcf8eqmjC!Q(rY zQ(U({cD^#YmQRiY*v=sCOKsi0n-phcf~|)~MSFpWz7Sh?ziut!8(-4JW$Y~Je|Fa(SKOb(3 zuH7(e^A4)7vw^vO;b<1|>!0n|S%>0!0#8=;6=!Pg z1GL+zr?dZ|`npZFTMqG);CHV1=QzZvGWu6?)-&hVy^K9f>U=D}n6F8F^B8+bRu+w> zxRNurc7uDnlCCIlMS&{{Tv6bP0#_8cqQDget|)Ltf!GvygPbNeYZSFlKClh1i^PVa ze-_2hYgM}VMQuwLKj+rc#m{bEy7;*_moC2hzlNo1Kgs<|m%roD(#06IhKINa)$C&>u=>F0j*nVhE^`~}8b2tw6*$llvAL#}B9JwTYMDUvu{NT9K!KeJ4 zqmA)d`>{V3pZ&OFY+uk1^o$js`V(tQKid~{qBf4C0*NF981ToWH1*TVnu6^x&82j)+6`BiOv z1s&JIccSB(_$zeqSLxuRzFWEl)m!vBj(=$GUa>pO-~Kv@uSmWQ z9f$L!diBD7vp8S9TN7Wl{v3|e=zWcL;qgmB$IHNY!{Iy8aTwp}`9b18-RQU$|BC)# z62yn@S8Ip)(A>W%m;~`>&NG?e_><;`(Q&qYv%kRCc{c}>SbT+C_eYfjVf^4yd>+l+ zRS#(5zk`lz;XAKApove{CsUrVVLd@xloB<6L4F*hj6bEtJpT$~7i@^0$0dsYh>H6) z+gGZ*AL$>llc8gO=jHD1REiNe1!xd;2ke`wYyV=F$Nj{^+)f4_U~(PW7y7UuI%e!f$2d3{zTtYF`f5=aKW7i-L38)6 zMPYo~Da?oFOVDwazyA#3zk5*_pRW7RTzLFCUnZ<4XjW1Z#*7<3% ze?SvSD-sBBz<&57tk1P#{9~Q}QvLyh`6-RB^1dyd^;L?W6DnQ&!oNxvKX|%y@Ok@; zb^U>kzg~m*it2AaQ#$-9epXTG;-{S~UHssUr8B>v`lSC`YWU!uq}+?8gU{RNgE6jO z(e*c*!SfNMPndtvf2G5p>YviJY1DX>sQDMg&-tWu=64i7^|R8!pD?C@(Y9f$GJJLbu7+(UE9KXkTq_}_iJV|ae& zScTV#Xs(>-7@ptJd5vuy<~0Q!kBZ->;p?1#c8s3iT^Js|56a(jzI6Cg{Oo^A7r)?Q z>EfsSS-SYnze)%H%L;h?vv}Q{uA^7dS^q@GqvCV&eAbDMhvP%;`RteNF@9=0+>dB3 zchJE{$2IZMaZUXGI{1(1;G^T3_~^J6e&AD#PoG=UT-uDw;N>PSFUsNNC$BkIKWLfyWM7MaBz_%5IlL?`{BoikUQ5YK$?R)^mz%tnp&VXI zN8y(;8oiHRPV(a0bk5)DmZ_`ySp2K;>nO_MW%1#c6Xoz)N?yv^J{EYn$!i(P;k9%f zekt#x_tDEqUVMG=mUDmA{=Im*pVI$Q{it~*i{BL$a%bHXem~oXb176MTuz%w%IpOt z{O|h2`222gJ=u2}T0_paTEq3ZhZtYaR-e2cpI_4bh3jK4LjUJB$MY%fuwl_xJGS~7 zNbt#dw4d?=ydGq~4PV#wg-odl`c{nm2{_KC@3R#vsDQqD>k@k`ZFI?>qv7kbPQ>lq zb$X_Rwm?f+6XUBdE6)1dw7$18rDmu;+obsFOZzmw`wP+fR%S}gQGNEw@zv*v^ZuNZ zu%2n3WlAkjeW_F8tIr>2eF0Km*PWRX+F~vRW@CGe)m{qXtWTLt?B$nCsTHa(^m2Un z7mBk!AFc0rresI;d9&lIPkuT+dy%J*`};RjYK`j4of=<#jyUV{(E2KllF$}@$u}*& z`hwHryFck=a(}f)NjIbV@?MFrKI^OT)#sx1H6JClMfLfo$5)^G;n?a+xq$s=&Lr$V zzq;=?=@V36)&RU;fWFWAN-h7H?uoBHM>f_o@aS*SdQ_jy8DD*_IP3G1`gV`}P5Kno z=Q)7aH)FlO>^SSQPsR7Q=f&To&rp4Zan@(6jK9x@)t&vHjz{@t@OpXR6jWcAw z8qGHkf#;Nw{a*ArWtR+eK6)NWpHI?U8j7D&(&vygm(g)}4iVlghVl`En}q*;V%U?G zTTnTaj^izwHyVzPqk3&C@IEY>OCz4NG(+bX+>7^b(fo;P|GL&PXe@e<i>G9{=NHTgUEm#{ zPLjJx?k9PWB)Qz0)Jt-+^}1igcwUnGNiL1Y$7PZ` zN$#e{P2R8j#r3#-N$w}PG#($9N$w=Mn;ti)w=uLf+Psl|GY}!Lv$SawNi-V8=AY1!}&>4 z>P);Pj|EiLLj!>OdZ|WTAv8f5bO0<35S<(BVf?G1AI&AxreVAVIeKFUf#_=NrT5n#Q z-y=io%^nk7uQTsSsUBM|*`JwA?8l1gRhW9^IPHqoo0cAJ&(4&QQUkVLvad2x_Dt*L zb#`Wrlp3@3lFx%AN@uifGn}le@O(m9jq?JMyVl@x-Z4Bc%6T7`bIJLsYjHV1@{D!3 zERpk)eYor;IjIiY6%-0No$uOesX>DRc%OX#MxyRFtTTdj{2pDeGuu5`9ACk$LGm{I!g3>9FZsR>T5q#N^dnSHZsX{B-Gjcc$ZWmjdpxK;H%0ZjnSKm|=?XuWX1tbZ2Oncq*T z)DBplVe2L9EQzX@LVL)3;d13ie`pq-FSu6XxPs==kIgjq|20I%+5Jhb)p$KHh>kRn&llixCK;>n`K)bU`TvRnrKLc90$ebiJnt;uAUsYT`7+ItRuRpU z(ND=+(K&SgF&&?-O}bjz&WsbW#(8@CqA4!D&wJq?Iaw+KXC;vM{mcRonwOy89fO~~ zktlx7HCV6h&vmnOLwbcyW4*j{NIXPQtY~m!^rD9omBa6$K?-vFxP#fMKci?J?uz0u8b58`Df_C?R9c93ZMO5x%O z$}8nv%qxEp<~4XlH%kx1EA@Z49ZQ=RyG4@AVPqE!^#k|tr!Fu@z++%SdUP@-^Y?szr2eb8-ldq=p!N4y?nk`5m)q`1gHT@9ZCJ1DWtdl^<~=OE5U&u? zOJ!f^dIh}_-5;r6puBvih<#1393H1L-tBK0f_N3py1afu_Fz9sd8MDmyz<_~dUdVw zuq6ZWl3u^Oyz)6-xqo9`j$F)ZYQKjqLlLj^%gig~wP?K@XE3iq%4^=kmSKoj^6bm2 zSH|nnyov}f_j^RI?T=W7BVKuznU`x;G%xQzSg(}jnAcZ7JYpGvcv;)zG8*xc7G55`vPfK~rx#tf|KjXW%hSN?WgJH*svY&# z9r?JB*NZ-P_@dk}%QJ|V?=tbyv@ax!?+9LRrq4lEG#X|ZgLv6DC$>N8>7{933@`fp z=G}I~EYBid*_VlzrhOq^h3AN0CC`b1Im0Z^Aznq3qwUK_{3Fae$}#@S9i!j$NZR`x zJzDDk2tSw1bLn%gLHWZhV-c_1Dbc*B-lFRhdb}tuk|>;byQk0Tww)bjc^>gfemk*# z!aqxUKF9Y*v+)G~Id^)$W^)=(Q2eZwIG(6JVua-dq*v+|+#gl*v{H^IMD@y>kK2R) zT)n7H&KINO8LF470rp?1x%fHn$nk$l=g@QK^w;#(O)QdvNF;h*OYe)$ACvFIyzDD5 zue(1uC$%e&zK^@C4le{y8oZoyqURl{7ov5P$BwX!W9*CCAHAP=UTNp>^CWsc^)sUWE8e(}^0IwQcr6@Z8IO2*-^Ko`w0Y6{ zr7|M>Lf#&&laqGL{{ZuPYWWC@8}TY4yi|SyU8A5^qV1mEzo?%;l){Pseh+#)-aJ%* zzYm>WNBsoF4-xyat{7=~3F&2DgWFN1S1J2d>L={n_m0TxM_MK@yeMyaKk@cQSB(9U z))VfJs4^NC7JiED>+p_|mWha0st@Z$&!=(a<({XxKf}Dr{xZ@s3Gpht9{bhO=0)$9 zwg<0Q%IBEZkz*q*lY!S|(u?;K)UVR{wvX^CSMe#!6vQiM?d54ly*QfMSK0<*U)`Uw zyo`9ItxGH~y?F;87t(fg9>(K#kns9GbZLAx;$P5$)y!DvZax6ocu61p|N48|B^>7zY{GiUJ6x9O3@^&N_`c(Op5~3w z-_v@+!GvU!vf_L$n(_v=2mX7lig}y-hqfcdFUrSyIghz4uOhwDe#GNEy^rGRF4MT3 zaT2#<>edLa84NGVyO>v;?N}INJJNcnzb_*DL+#r!ue&a}EHe==&mla2r03IqQ`&K~ z*|?DZUbA97P5wjei^uoY%(QrrUPZ*ds9wd@T_*c-+oFF@5O~dEc=5dBjSHQm{}$hu z&OfvsYF{*-$k~SNYf|$}%WH^N@`u>3((~y!R@!kPjia4*POs&emNyWu+@G+Y;D5h0 zUcG#6qQ^fSxg=T-uUCNhiOF|lT3$!ItRGz-y=Xg7zI5EC?c~~w+wo}kOv`M<%TIVw zyJ!8x%S@bOcE6ln{6*`{+l6^G_{C+JgLu(I{e6U&l+b;AJTKAl(S9qo7yfsN>3x{Z zssG~fontdCbCF&SV)s<9;`%O=|MIuM{W1M3+>XF&9>a_09dCbh$JiffJ+wd4@lhuB z)oo^`B?s|xeT@4fJwIY!iQOm4+n3q#k@}nB_D#?~)V_FpFY>GNkzUlVQoV|+EoJ+n z?MTO=?44vB`YhA(CgMfMA-EP^nU)2JS9&3i3u!yDc7HkiJ+0TVoA~*|+VzC3-#typ}P%DDPrD;#{8y z{vUf^0v|<@{a;-I3HN{p0R@IL0Tr^Yy73;7Be?4tcRix(x+8K#*CV?M22g20CEoE^ zjk@ZH903)_3xel}9O074WxPk^2&gdL0Tuplrs`E{Dl^^H)01KUpU-bTpGhZ^p7;H} z?|b#Cy1KesbNq!kSicJRb3%L@nO@$*uBUUOygq01_qac{n`oWLl8!r?W&Ib3fb-Fw z4UE^Ep4ZbV;N^RR<$WSva{riaUf3QHw`@J*b==_V={(>S;k=sU7x?0Xce>jnn2f#L zw#Ujp#OEd2b-Ts(i1zDveueM7p3VooJf9xi_UJ2!_dCk#S&0|&7CJa=j}4mb5pmS^ zSo;CXFEZ2`BhTK^t#))fxZB|8Zyia$AQQzd@|4b4;im}hTK4dz^m%5%<6^p9qUB- zDU4So=k@$`H_#V>SMl3Pcs28JE$Wqjs!}Izxq-eU@j~7hf2Z>%p5N=uVFr`|U`Q^?AY%{)?maInnR%b&oY4F6Nz}qb)va=VVx-cjMoYOc={Uf!a9Mx zGF>MSH}omvHR!tW^mX7>9ZJ#=QR_sq zb@jpz{)^K(QGGG16J^^NFLT3q`Zn;wI+2K%Tql}~S51EWa}cBF|CYtB^ka^eEoSSf z#d;?Ac!e}Sk!(Jf%Op0A^aA^JPcvLJ5aqQ(;#IPkty>fIEBb$lS98rrpfoI7}&}5YI*$xx)gX}y~q9K<21QWG}mz&9zPcBV!T4rC(vcU3+sI%UUI!}E?zh; zEUjm}hF46W%YhfxFXWY}`h|4@aqD(4UW1>SKvw{-oF)H%)`_Ca;@gX87cPInI)V0U zd47f8n?P$oueyU=Ckp-Xen)w&lz1U;A%nwlVWDQ7Kpd$;+^Y$2-Kvx4VY>$a}$@MGUys$kYF5$d>e_#S#1H2l(O>$i( z1k?xb<~mM8Ugcw09R0hQUiV*qBV7x;yzgeVPE=gMcp$If8*Ds^c^w_Eu7UAt&CN_N z{9GPKN0*=ry^^f=$L~4a;5$lfl+ov68r@hbn0<$ZX=jkFecVg17W0|(eRO1%z0*}4ef z2meL)xC41%{VM*J*RSx6^nKuk^-J)=`;9mA@esC0#0^ClulzkX()GZrHp6uS^>y1G zbFPlhOSJ2Di|rBZd%x%T)uW7V0KMwB9NhL;a!tJ7Vc@k<;)T404i4L6m1cWH9L#$> zzgGVP(`(KdWpuNY_qe}&9(jgT@0)A=1mYHPUdNwXMn3>vbxSkbKVm#E?^B(h2;UnY zf3)j(8)A8k-^08Y_8(yP<7;#4B>DyDmDhn?hu`G9Rff)smfsiexBtOObc@7G@J5Fm z=6y&r?-3`K_mIDJuQ6Vpy)5tFoi&Mm3A_RuSbpLD@;JIV$Ezx@D&+ObB)S!NHDrhv z`itREdHMD+y_PPWM7II2qK)a*E7?43!gZoR66;r_1-oBI-o{CEJMgMfc)6`#$#~i6 z75H>FpvWaA-~m)rW~eJj2lV}7{ZV*L{K&ukUDpJ>}xZlUek!}ac; zCaL!ss$YSl;^*)E@7_Y&OS}Yc6vAQsifGm^#KC?$Z!U{R?Qbl<0-JB49e|hTcyCNU z+#j$1j*g>8Nd0zBn(w2l@+#TSczJi+LOTMl!p~S7o0}K z2Y3}d6t9=t`vW99?nrn)1&9aos^q*{wwgja0k43fS99^IdMJLr8uh~KtpdL?y@upW zp`C$O*`D|~Vx38KeNM8vs@8ju3SQEQGYqiqwlcmQ>we8{Kd4_ZYM!IH{mZjr?e9;& z1?k6lqws1NEz1~Z<1gY&xPMS4H* zs>v{~;IWKHHcK#4x|s37xNm8(lpY2TfvJ6uGdl3GwYM!7gzh zsk|yE<2Q8iDmoB&Wp8EAhl%?V|HB7cU0x+FdF36#cnw>*iXIKTO17nkm+6of_Ct8R zg83t>U;g9E=%(oSi(jvR$CvWBFbi@3^-A|~E%L(gYI#ehSMJtHbO-Pv%D7PGmCEsU zvbvhE9|CyfRmaEoxj#&z^}wq*&AgJ0SJirt{ZROEHXmJl8q=$Mok^~M`vjV=vwpjJ z18cu-`=R_K;~}&Q62)Fvze`8}ln>EDb+A zTbVw{i!5P!RJUS!)tpdBz5rfD`;yE900$qu)6EOVHOQ;}dd90Li}7kTtdML0US57( zW~TI#*15+je#H%pS3T!7_ku$5WptSFOJ?=L>*i3eg7J)(na%Xtacd#j3cQMw@-mtw zjwN4;`~p#6edBrT@0`|*SKfaL$u{5>Ovk_OHp}*gSgS z{k|}c_&m|VHcYRTuNIOWz{{VMSM%tlw#WP%S$>5%ubQQWq#k&Ae#@+0*zcfT_#D)- zwoI?qn+nNJ;1x>Bt9kTN>qH&b%hQhWD*3UH>;hgn`!lN-o~J^+@cFG(oY%aTBgt35 zt28OE=Fv;7UwIQ*e)-xny=L4xl6(!kYBJ1A)vK2Cs^h%o{bwZk26%Z7B#UFS>lLf3 zWs{g*r5%`FcN}&$*$uqPGR#ZTE5^$^iq-qiPG))qIIrOo z&nFS!73#spg_#;psJv=8uL2L#Yxo`KlW&1nPS4EpQtMagO-!#^Xki}@v7mxhVML|{0zJzhh;X7QeBN5cN9-! zy!?l8z4o3@8h}^e@Po^%YC7Z9zx#p zF1GM+VjujG?s*fme@^rlZ#GGF-DA$^cz@8Y+b!xGM$m&-U zoEC)o;KSz93wQxKjI+4k6^FC@n)d5~Df{3*Wv3>os~NhlPe_SJl-Dm3FXSEdA@*{3 z9@$^2*B%iE;~0FH$C1NEJE!M?SHzbjj?J9+SSPB-viz;@#^N{w^!gQeRkmil&<~uS zjh=s$=gHH(o_qk$ul#QrFRc4fy%qqkhNF|@7yRD`Z{582-fM{V1Yfg#VH{D9BCglC zt{0HsfS1`Tv;8&_MqUk%vivGr$l@6N{|msYY7o2L9rqX8=C2d6@mGC0<5k$5@hTs1 z0of0{>Uw2ZFMb~k)GP29;}zz-qPhfu7dbXbdu)Eaq7+EQ9XyUbm|o*fx_}%2UirN< ztCuvskMRmW#dyX3fFIG|E&^WJgOcdg%=HW7Sa2ufRn?Q}HE-kvgupnb{2=KSOL{l! zCs5!tZ$YmZwJ_JK&dc=bckuDx!>uRH97sG!%gIRuIKOkg* zb!k5ML$}_G?`i&mdX?YBcxCtI?eWSB2nD?g`ee2};&E-P-;RotJ0RA7c@{BV(T`q> zDajnf>-0sx4Ii(7olviI_uHsf{@qNkfV?HQ>qh@;}~yQFS$-6 zTi=2@H zdId79S6sghP9$oNZ%gfw@b$B@UYTf*HC(UAK&IEcM=vC8K(B^_q!-4q^nMmc?=g(m zSMx3;ZGl%&|IFq+#u4)#>R<&HJ1Om|oSW*M}F9cA!^PhV{bZN2`A5 z9VzeYpJ2Q*o%bQGSN*XpzmDB?A!!eKk=)GY7wYADi&M^E-X6PN zL^^<8g=w0X)8&hLAurEEj8|bkkK@3LNJromJVgJE`ewbhQoN&)^EWgSpUPL;9UjBom7x0Q@k?MC;$EEO} z&G52zRTq&% zK`+mM%(h3hu9j4>I0jB&yk=wX`}%1Xwo&pEbc^uL4n@r-DcnRM4e~0S< zeD~#R_(z=w=i1CJx=IhBkBUUka#d~WsfYx2T=JMt0Zm3J!3uhvCV$vEJZ|3;EJ z0lC#2`BlhyATQr1j92;Tj92dTsiXvWm1me2>Vv!*>KHF_SesZswC$9~$)mulq$OL| zk?HmKZu_CaJ=`CNtE*QI(*tc_KZN$H&tP#JcgA+|80b~oIf-5w>W7MFv2kL(kMWv) z`F!#?@X9+h2`_NW2k&&(Rn!ObE5hSpp2>JU^WA*%U*J`FLuRkjL0*_&PS<04?_+fz z*R^6^q-%@$h4yoXFulCXSCc0|FY~k{=aHL#-D9lZ#{2H0ztM5Va`=yb^1+#p#(oIT zcZ9dH`vXLI)x;Pxrg&d|d48ff&v&>Te<5GgIbGYBUO*0?W8i$(k z!2e~v(!H+3tzPNUN410bg~x4?C5?K$C+SuCI_q!5I(INM1DwLTs(b&5WalZ9jlVGO z>xMV-T9<%Vrt%)^7wUm}M&nxxysAs%>x8&3Ec{=dFHCk{3AE>QtL8m^Kg#QUNw3H| zZ2rP+-Y4UqFpfY1+hd@xF^=n-fmgEpLVr;gHSY^XHuBn#fY-sw`&x|jEokrheGJAVr8-0)9Z~slF)98B{d~Z5z$<6HTg>Cfh z<8M33RJ|(y$nt*JfYtO^(5rq%{P_;qo)7-OdM|&T==Wf{^;(#sUhuti>Q(b6rq`b? zUQGvqUcU15=v9+$y_Tn_7kn?BdNrKG^g8Q~)pT$gujdOp)Jx6#ymL9PM_1E);8n3J zJ#lPs$t#4s=B=i`174A@(!*U(4T(9?leUYhEc-zBdw=QVQW8hQrs zilk}$Rpydc*+slg>|H~Bz{~SNdg@n&OJ1I0#%p-%we(EjRq$SV@~g@vuPV-KXxFuL z2=FRNlU^a0ynGk)_BdcIJqvgh?@rJ7tIj2_I^=cIS~?VX1%6HsuZT-trI+yh8o8DZ z171}P>EV@K;I6J_|Bc7-;1mGz zE_oGP%JsTqEiD9IwMV9hSCLCz7^C4M*U{^MSLycj$SI* zJ_fuRzD`em`CRg<;k<^oexE)Lyh?sa53gdEy!?Kq*NCp~)BggmoL|$!tJEd02F`2P zN$=AqfLHkT^zbTo$*baWrq}S1@6#uNS3#QQR|6^XDi1O~wY=WXS@k}B3V5Zfu2#F` z6&l6(&D!-o4FIon)zw;;yo#^jyxOd%PXn)X)zx~Jyds>}%x>%HOyHHSc_!lUerY&g zi1}4Mn(H-iJ$(jvrK{fOxa8#>!+D*(p3VYZ>8khnE_qdRUb8P*PiF(Kbk(mym%NI` zGQH+pwVuuaUg_$G{4ROGQQ6cFMNK0%WS)rooY zH_+!H@6$D37;@MiG4FlfvUOD1*D_wwb&pR<>mG4kBsM?QPCbt!%Ip7WH3>i* z>-hRr)EECxnt%Oj465S0_;uk?UQbKBRNhYWt4K4y5J!z;&NnQMS3I_nE`m6w>-=Md z!}}rQdO5s~j{J-98lAm{%mlrBN3gnzeu(v7%6&U^*FEZ952NZ;a2?P4`5S39=#{SX zqD2n#9@op^bIJm|e))3NkY_-z(tFwQb|Ss9ptHjB$jz-+Nh!~-*EZ6{pjW!i*H)#H zU(g~^58u^{*PQ-q$SlySlIIuJiRQ{Lw2O5}&96$H_gAdiNM8fJ(sdrW#9@A6|A=}N zp2hUK>cllX$*ydN6ZW)poA;+U@W06~Xw#Jn&6AwC{a zz2-`Kp`Ic>4#$O+n*BE7V7h@+`#Bb6=9{3^QC;>nAc^V!+MW;;dnL3s?_Oquly{_C7CNG0t`4=Y9tC{bo5UXF1`89i)-zC!- zufE0?xJzk1iT8bOD`|o zyjOYUl`~#E4Gj@;~;8k-&dU<6(kXjsz?&kID+#O^k z@G2Xh8D7cs!tqx<=au`f9b^^oDx8#FUiq5$m&3fr@t1iI(`#GB4ze0}HDriaLcO5K z;`l3gFXJ`*g&kxK@FF+G>*coJ*1b=ldc0l5=S{|~+C*2t@pihd@9>aUAo}CRzh}rR%yAufzEX)CqPc;X5aS!(`$ZFJy{2OdChpeviGz6^}zAa2x&clmw#>pPaNDIGd6D$+Rl$V z;O1?x6pqZldNW-K`PDE!@jSVaiQ{eHQSv3ztA?*jJI7y7YC*4BMX!n#Os|fhm%M(W zihrJ}UKj`bKF)uY>|lD8KFH$eE!|94NqPxA@rw@U$@4Vp7vcb~oG6s1p79Di#CV0S z{eXS~yaHQUKH~mJi!^f_@whg)EB?4P%Ii~!7xEUo9O_lBsTbk^uV|VJy=wo%^vZkl z1Nu4esz08ccWv_&6$Pj?<5pvf!BCHi9XaycZ`dAXu*;&o;oDG zy*wu;(JMpwRgo26x4q#H=ob<%mAB)06U{gx4)%}vZ5Xf0M_7IZ_IyCM0Iw3R7w%v9 z5UXF&`$x<5i=3u6j&V9~g7^0=d6@AUy8i?ECGZLwwck!Q51<}Ds^gqs3FGzL zqz&{r;FYfXMg<+NzsERweq-&b?pwwyR9a8ohkhu0V|>5eT>VfTIil%!0-80Re{6V^ z@fz;iNj3m4->vby+{Q8J@c1#vpVwFM7~^%@+dIid;MH(jW_Y2$Sov`Lg}m|}=e*YK zB%6R&)$Qr!6;4sF5c2wbC)o_V$c)VJveT>hzg(|9JIM#YE0|_po(B`xIkiq;9I<{y zIIr0qcab{am0g}*y^`@ts279_kGIR8V0sPhxr=-Vys8ymc$}B&`3|2Gy?|FqC)N+; z-^O?aM(iRV0WZ%T@p^gq`2n>b3Tv+0NX85O#r7CGiOe1)g&+M-Y+;-eJ09|MW_ktg zVE2!{`t4ohW6-N0#~Z7|P0qW+IL8Mb=#C4WIt#pFl6giBWcW9-yMdSQzRboE^Bj3q9L4l1oXPci@f)%ScttYI z3-cU#6?A93!kpKI?|efdz^kw#vwC5k<9ZXP&sX5#Ct>an{++HZ=oPE?Xus?k7Dsdc zH{@H;%R4fOUd_Bt6vsLFJy{&7Sxm3GKkp_#126JGlDvn1`QV-I@dTKRy^vQ;AEsA;$8qDR z-J}6{)nxd&fv6AiD%#I@Azy!&14da}=pWBu^IuiJ#sA;wJX7H#iI0O254VW(KRk|( zQT3e4_1MUsn>4m>1NnXQ#sw#5HotJaD#o!IdCg~e-(q6}IUaaby_s2Fc>WA|`A=hd zRdQa#hwddO0I%$~Gs_F-m4H_)#e%0ZUKI=3@zAio`^X=Fmp{Y2@VXr2ReT2HRr4&1 zqRwn|R z7_UHY7RTF8Kg+lrc;WNr@ctB7|DszTywlwe;r&doJr;b#c;zi%ylVb@mN5!=6&ftR zGQ~@Mu5Os~3UOZbx142M0laEDWtLa?DK;-YfRCebeR(uK(U`vnO-5jjqVqH`5p3typPq1njd+c*vIMwDgVS62fXSZN;1y` z$3s5AQ+Y)>q~nF{5qbIUX8AOt<`d(ez{_*bLAxF%=3dUvOs}GsSbm*7c)M{m@QTdK zEHBSk#smAuk_Ps7J?B-kd%JNB@Tz(?v%GxAhSATpQJ^9lH;> z+xDoNb5*(Vy!`tZubfvHuN|d(jq8AyzdEye1qQ_P%KnA%3UXfc=02koczG5d9A4`A z+B$x}jSW!$0}~@PlC_y!{hbN@bL=R33;Xa`bXr2&y$Xv#`Ie7jY-D9 z@pj?IOt0pCo;3Q)RA{^&rslGydJTe|^3GxNU%0>6HuHVlV#SMfkpj}mFY5DBoqX47 zUmWMC`!K%H9$#R3xvi_dm8p%t67iz&VHxM8{y+M+58jyf(Z8);euuooc;fi@{EA{6 z0`KsmBy|G*=YzK{FWA-5%WZx+0&}o4>Q#9`yk1ehE#O`8Qj+!v|MS7Sx%2{FvFfQl zA2-TtCH$x4ruaBU_&S>C|3mNtd4-hqHSlj&uinvbgMGYTTIHLpu10ZN!n>a9g?i%o z@#wuXVaP6crThM0DzE&v8hNz>Y~RZ)j?K*r{RPO_3wh!CoEnK&7VJ@}@WTEgQ~e|I z;&fyEb~N!KY3AkVyh4;rJsTIwyjDx&iRON8GsXe&u};zp#GcbDI%2s@GbnJ>qk)vE8IvzmnAnw2Szd_kmqa>qJM`seIDGjbq_gO?gEZ z=9e9$IHF!fJDc)~#;W!p^GbAI>qCK8-a)#rbu_>E5G?ka(;wI#oPN)4e~cquZ-x6u z`5po9f@=;=ov`B71$fmTWL|i^m8@6v!lDSjp8|d^w#{5uQ7=z|``>p35&?cc1;Gb@ zX?|X@s;)k#J(^#e;6FJR#@E$q%GU2k|1TeRWRKE2-;ZwDZS9_;?t3`3=UmT*@1^rO z*WSOdO`z73i5gKLVo}I^80@={sjYk z@9UYJCodex=1JVHdo2DnejH-g{&oKkdd2D&+Am$h+N1xG{l>pRuL{1NsmXj{Gp~EZ zdQX&fR8d~nOT3V`@Ymt>qWPNZtPm$Qz6UTot}R)|^y*W!-?#yIRc&GUh5O_DMyl6$ zI9iV>@hW(a@#N= z@MG;QuDese;C(s%dVlr*c7J1g6!vR*dxZ6cH-cWczA)465%V7BC;aOfuXpnf7!#$u zN8Wh+nUQtKQBnE)S8WyJwWQ#HF-gk%=H`X|Vtg_05jX#R#%uP71IA?FRkH2>&%AF? z*1e*?MRU`W_h`R?=a+xc0pljn%jaYB_nFRnjAP(HeE%Eeb+g0^d7~aq*ZcZ4`ys@E z_82Q%I6o2D#PaKkl?RMlfEV^dxIgA+2HImBuh2%uYt)Aaj48ki`=RFMh5lkZFph|u z$9c`!alkNv7e2?cNq&I=AH4DW5ZX)E7I~GmWY?>a=^bM0+J-%PIPC@#zjduMyAGzL zxPJ^Ed6i}{UfvH_9LLT(oE{0h^4nyV7g@sAaUidf){Iv*=hb)d;q)lrRi0s9_1DMq z^0#HYit3nN!&V+ny92L+wwcwd;)Zx$!FG&SJ@WeSaM}ZSRb-e~-o$ubRUH^F^FyZB zjGc$mp1{kO;q_m&3a@~N@yhv#$8qoB)C;^SGt4VzH0yUD?_M4g?GpG; z(Zu-k+x5%Yd{T5yI0QS1`lWdvB(!h0744DVpGn@ooBT(D-+l0z;FaM2ZazX@_?*S? z$1ILfn@8Fh_QC&~n-?BGmVMI5>!|+$UO0~SeA>vX`~LthJa1Jc@#+D*iuiqD6H)ZR zhs_;FoR9W>)~Hv{L}aATGQkVachpI|yb^~*zh;6Lo<}bIyiu=SiO5KwWr7!;N6rp6 z@)F0q5*PW`Oz^_>E;!+8+{?K zlFJ#d;`&Bjzk~nRW|&vSMe%xxe(1OM;`&K1EUc|N{@|{I!Rx}xcQ)$P3wUKed2o2) z*bmpil)S{QGn_x-Dq05f0L4$T`JBkl?EXz|@As(tJPP%CtEzu8y+-fbKo`JycRZgK zOGf2~5B}E8`$C7;TdBN?yD(l?oV}601iUJCvGW}YrP!ZNcx9jMY@H0A=S%fIy7(OG zM7-U6rs`FC4byAXog3*w(5tRf{Ctj#5XU836Iq>pi==m_}eNI{ZswBTg9~zaytN5$<@ni}n5`G2s z%JH!IX+OX3@X%mASr1grsjS~l*K?$jJ;wms6OzRIigaT0_d%S$A9)1r1^sqm`^=t) zDXEG--%)=k<5l_{%dft796@^nuZ9fs%DFk7SHa>uaZug z~@yU~HbtL)Is@(SM>&#T;E zd0)eMja}T09u2(m4$CYr^PYHK<{^xizk%od%5L-+;ALi*muFr)ucDI}uLjPm?|>ue zvA`?;-puNicW*qe2F|NuFV}15k#rF7DmWsuyz0y2c?C{pdgbk7ysGXziVg-|zAl;N zRjcS#cnaec;=G0(*`4MCufm+n@+!Y8Uatt}Rs0K&<8$5V?|@gNcV>B&-51ZR@>Hf* zg!5YYTX%X~RIfgn<&}STJTKpAj92-uOs`$1^`O58UJV)MRj2T(=e)eXF)0tk?oL9@kPN63NugW=@<%Q?jkypVPj91Zqrq@}0PN63PFVZiw zyzo3b@(Oca^_+G7m7lw$syS0r2wo zPo`J%@CrBbik)fwiMe`CB}<`AY=5P9`Jjh+m=Jh_?G zt4`rn-Xnf}bo9RI-@!Zp-ZvfZpDdEZ;dMHmhxO)t5eM_W_AI7Xp~2#~^xFedP6542 zlIqnw=ZA2e5b`P;%6OGg#_L7kbt>=*Wtf**zr4d3FV7*2*OS2OG~kt!mn^@UM=!O0 zl@4dTsyMH^fY<53t0u#|)PAV)A$C0EYr*syx&3r{2JrF@$gEztZV%6Qr22e?oDocC z(N5F!3*>!l{VLk8<9db1jG#Wy%U8#)A8E4wK10_Th9BYc0NmdwuQMfH$Xm$auzrYi|%!XSicZAoAVlQ z`v`hgH1GFhIPW=sg8&>0*>~Cz3 zXul+z>9xGFkPZXA>XPY|q33wkzZUOzcy1vbF7ZO%!at|&v19ym6onn-7sSE#h{w4k zz}5o{TUmEhjgs+9*dpQ4q>myV<=xC^`A=b0uXVER<A$tE& zQ_>&rKPv2?<9zGU#pnC~2>4?FKX_hx@VyT4$6Pd#ehB#W?{oZn-T5E3!N=#+nr+#* zhSv8oI>B|vVg6i9@=MED{@Ud~+EL^uf%jn!Nc|B0#{3s?JB-DD*`kT`W7+=-cm79g z{Ks`QCda>H@kIIw;8(8a`g43c|ItnpSC6#Le^s|DmrkUg0)A;b_8beMiLcs09v&Nf zmG{b4lj!HN{}1T3f7K4+du{N|``LBfUB4Yp2*XyU7OkVfh2n)%;_`G4EE$@Ck*7w!LHclmGH_}_3Oo5w}I zE&e%~?w0lE_;&fP+Ch7!uKzi_{Xa69Mr8jh-T5D|@xSgeHa~1~{GE?Yrr!d-X#X7F z&VRIne&aT1gD=``SLXkfvnJE;0AI9!O?+Vof%(?^gmwO@?Pm0%$@F_U{+jrz9i$Pm z@n7iHjrl*Ielmqee>Lj=m|puAb`Y3vBR2Rd@4gL_=})r%n)s?6q~W{XT7S|1@h|k7 zaTDDO_@ezk=`R2MHuyPr#*cr8t+i0sA-b{`568^F7@Iy}Vciv1}$oMC?!;d(`_g#DoZ3Flf zpK$%pbcgS|!8-n)CH>j>um@}ZJFc8U4+VTP!tsZx_=%6dgdGe#ZWmhPS0g^(f5wC< z^f15|{l6x@Y6syc07c)tnaW%#XH8^)Q@=ZUW3R0Y7J*m$l2TOn*E7 zRXeCdz#;y$mDD&}#_#41KV*ZCaWi`}{rlc|i18=DuUW(6f21Bh+Cjf@TdRqW``>!^ zA;vj?Z@$mB0Bu;`d|z-*Hzf<6_zWUM~G#p{Kve z@s~f^%D6=K-zC1!2ESssl7I7B8Gi$Ok$;-_svS&&A{%_n8?!&x|Jf|#@3Q{A-RW;? z;v?VXi?fW&Wc^*@S7_p!xy=8StFsKh?0+A3{s(mNdH>h{!z|-+*?*V#K^uIvZV$~d zjG=&EoTmQ2)TaKbc{{E?%NPatBL6l0SM6Xv)!O*4j$3EUnL=~q@vr9iPql;i{@bnV zj~IUrWcjz_!zr|zJpTN%I{tMw{)||SKVkgSu!0|daKbCLPoYQ3{%hi^cF=z^-r9dL z{y&=e?{96=?tm|jfB&lb?`-_0e}nuj;mi!B=^&m|)W0vj3X+svYz{V1tkOXCBM*?@^QX z1$>cze^dQ;mVZGTeAJ%|V)(gLChaHd-vr;8{-rkcN7Ze`LX-BF_1DB#?V$dq6@GLl zet&SYn)#povq|#+zx-o9|FKlnKe7L42XS#5ve93}e=x&02TY|$1AfEJUUvMqT*Y@5 ze=@N=AeD%D+?B!GG?*KpeIY0h6yiF_*?2i9cJE*^37yme>|D5ep>F)tQ z@B`2P+p=BZ2Xyf{;o0?5>G87vF7Yd@+CPjx#B)1;&-|Y?b{ahq@awj6{fFu4FYKW3 zd>eA;|Co|#^bfNCn)u1$Uu%OecpuOFANun&dXnt_I<@^J&VOM?@!xx+b^Sr!CdY5J zcN#qz@J0S<;-eh}p5$xd+cfZXM?Zm)_3@HdYY{NUt4RnKh+NU6SB#F zRkwcseVU#j`|o$x{wr+!SMgh3HKh+NUUu)yP{~mt+?GG&fSG+xwo)yLa ziPyi=^xD6$gTQC&Lfv;-AFy z-_`ROIzsmUO?T^`NSSs0QRg4FePhsaSbtT%6YopL?uTdB|EhLS&p>;FjpOhGzQy%d zs%~R?KSK*;{ayO+vGKp*+x~I<{K04F9|1qq!1M1j&Gx6*L3e!)@d=$p&yn%N?(j_; z{Hm6G{Cf(^KkqZM=y@{!7Cn4n2Oa0zkPW_Cw};M}MgJ1T|ALP{H1SnCNTb#YA9fPw zzxWqMbeK)g2mJ7GzW%Kh>wi)`|L2)#(f$(PXI(d&UMSpX~f& zz70O=W}eR4-JBgx`mc&IMI;9N?Rucv-*ni5`Bk{PQ}* zUwO+sdZmnia+cQkI~l&uA%5$g^XWfj{8QZF7wO^;VfnxFv-$KI8UHkQ_@!3(3G#ne zcs{)r@atOf{O9 z`p*ky>%q^_>t+9kx${4)iEj?Y{Ckd$m+?os!;e_uC(wU;_&GWO@Ux%d{U66qRe#T9 zz4~Vk!~A=mmdXB~B{&`%l{}pz)AGoQVYMuYM{sZ@))wP2$3-If=bNpM~t$)a0V~vmfwmFjdKl1Yh zbc&pR7r4v6kd6MhZovGS;ZNJu$#@m~7wi9~>gkVmP)FR>PP6bIb`r;bXEXe>zgR#` zIsdu;spfyJmH#q6Cp`Ac1$3&M|1R+(R``(r>TyHKlo#l9!1o*MI(~AoUi?)%sK05| z|0lqo{lyFPHozChpMQ6UUtxnU+TWj8{D(~q(it-T<$CzS4myt8n=JAV{8z6VS$S`e zmIHpMn9o0G;;VKL-eZGLa{2u4In4j1Z@)+%0Q@o!AAgR~^IzCOV7{%;#5Xy9za=ly z2LZp~XFmVv5}0zU(DhDaZdxz5GKvh>KhA&DQNt z#I1(jk|K~5$=VbqX)ocG~2mQcp zktROwKlY24>GQJxF7f>~_?S25g}nasdWF6q`~RDs|7ZvOz-_4}KJGt!&?_`3`|lFp zw86*clA0HB|M$N_Ujlq_{^3Bp|FLHz!nj$z{|(wfKX6-NgOBZx6f^vB4I;MX6@ z+aJeIwfz;9Tht%$qohB({>0??a}Ifxz5@8Z!{YJn&cCA_^c%N+O?=$HUx!!etAJnd zcYge#=-(N3OmzRDWcUFa{V{Il#XSC(y-F9!@u%_YZ=A-z)&^h1{}LX5|EsiGjz7mw zHU42Md^!Fcf6f)J(#3N875|;;AJN1Y@xS&}`kEYnm-u9gMg9Y*i2vVs{NH+&z9GlI zrMvihZ16?=FXizMy-MGdaz1C9l%A0AJjHM)5yc{8c+>FW(9u zb`sCM{5$ji_MQuANY+1_>0iH`-DmoksA1Yzf5{5=xv+!4eCxNtNBvEXpWAC8eMi=x zX@xJfKXMuKfB2w#`pfZCt-q$j`a9-#3+cOnFY2#L{0b|4h>?ifKY0Al zT}YS7@o(!c{y{7K0bj(Q?w&+$`@f5-}7j=!JB|FVU2g&cp5pKAPTb@6$7 z8FTqUS|i8bC4SfnUylFfJpNM_(p7T&JGhH~#0Fo)pX29FT}W5U@#pxd#-ErL{ZE4W z+jsgxx(4t?{pI*}@lRHNJy!Ujzv%x)G5wc+wvfIj>ks$ujo!Zw@tux;d^Y%~Ke>Y8 zj|(rP>ty{oeyaKxS>a3V&*b=XzFbIa0bkT##s6geU$XJ1UlX5ZM{)5J$RkScMnkPW^%Z`I(bp*L}#(KWgHuc92A= zY0>^*Cz1c-c>Z@-L^lDxIQ~1#UH*rx@Iim|z7Z?R4>y*`*FWE>cm7qigZ`UqE&NY_ zpS7=xv0BEj)?5Fb3_oOr4lGb8%N=6W|v;=CyxJl{-uf^HZAbw`p5C-9J+{p z0QjQ*Df#cT{zWwL$(79iemxe^I=~n8&m}&YYVAMPEtBI9?X`%02>7D@Y2u?DNR_yk z#|B@mTP==VL_Y$2QU5gYRXa$+YlROx;rQFUis^s*xr^v0fG_G_7kA^Yd>eex{{PAF zbI)5uKLvb|{~SNn{4cV?H>CM5jz9deMf5Yk7x~Zeas1;n|NWZyCXM_`{!EM7IIH$bXKX zYW{~c@yT^O|DRq&w*$V&f0y_X8+^=LljDzGu!!yee3Ac}_-F_7UTm$_e}VpL-u4YH zqV<3;@?R5QwS)K`8+=?hWtKAihxDwby8vITf9oDU{!Lc@&<^6_)@y^W@?PStre6WR zxc|B)zG?^Y^KI}Wm*%qZ-M^Usql>EPH-PUwlAr(Z>iLg$5Er+88+@^D>)#BY{-c`i zmi5=f7j_VsZzERqFG2oI^HHqxfI( zgvIy|_RYJLuRr788(vXOzXSZdqj>x|zFqxQ?I4YS6+Y-M^5zESf4}#u=?{Qk-ksz3 z*YjW4L14Zude6dtz{k8XIsTH*s_Boi{+jq`M}a3H8~@e384|9hKLNgI|C;!!9pq7K zgO7FF9MAKQET#>z|Ig{^k9H6jw-Fot$;GVxkO@5g9T(HRa{M*%g&hRO?UUB=S9PPE z7SnyQ{+jrz9fbGT;H&+{9ZxN$zXE<`PoDqJ>*=rBL43c}@jv8$`HVbP|8HdamlwT8 z_X9rZ&GBE*!$&)ai`$UZ@ju{`={){r41dNyUZV#9Kj;u&*g;^v&9~8C<-OwC*C^=# z>#zHy$A6yLz`X$!#5>Bs$lh2h)P zf7K4+n-1}(fA%_U71e(epMP594!^=7{=3({LEFgqZ@R+|>f%pk`Ty=`Z_su!e#jku ztrb4BKO8rh9Diu|4cZ>?#rU7&+a3R)9gI6}!#4P8-OSqZ2JHa&b-6tMH1SnCh@Wrs z{2~0Fnbj{=2bbLFHCn*^H$?xtTW|gs?I130ORefJ?4-7vvG>18JA?m~1G)dp-NoPg zRMP%0T7BU_J1^#U?05J6p5B`PTW0uh# zGJe1K`(F$Md=nyv>+kUSXQ~~<57^-2{3q_eW%e@KOU56_@TK)9K0+Ju?be_8HdyCh zU{`$p4ar(g`^xx(;_(j!{}bV>cF>=ojsL!5;*Wop^jkr5W&Gpf@sCY{ui8QUS{r=P zZl<#OKkCD^bR^)5_IDz~x66NF2Z8xEqKnV>pZU>RdN$yf4CeL6B|Zrxi$9!If;_H# zk&pkTG5^VDYw5XwUwElEt}Y4x;cJQNkFcZopX^Uo?VHx$D1H&(hn|ne7vmqmPt^X@ zI-U#{Kab(d{^LIY|1Yxtrz-JJr~gUtFOcz1Z!Uar81Sp+@%GQ3KRD}?UPedgf5rU| zHJ?8y?4XW(YbNdgmHfl+f&Rs^|NQf2$-gA}Un1iVX)gVf`+up7|8(=>m(JnsU()|F zz*k>FfA~kD_TR(~H;^CDt3T##jrHdrvj5zUz)xHIgY1X+n`QC-4}G_U9Mu|p#OrTp zlk2Y&jz3g8oHmKvo6LWPUp^ropH^Q(dIG)}f3;!w+56c#Q*hts1Kv3P@bb@-)j!XD z*7$|R@%=x|xt8>n@jEkoQGWs7l<;xwGwkI#Rc;%@y->3WCw z;QvtBf3G|LLk{ErIN%SL@%y;LuXTujAK*iiZ+!K4hwpJ1|LK5#wv0c-9e&uM|Fq`> z@@K#o>(9oz!}mJ$pPoB`6v_Dic85av{HJat7t8pU zxXVAEL;NDhzrO*#c=_GMzsMo}P{9AYj6cd9zTXNT#!OZ+(ul}3-{u6Bh|KBqHh3@?KSmA^J zMQ_I+|IB)$zi}Ll{|dYC@!xzl{6(sHJ6c{9~-7{wG=cQ|$1sCEZ~CuT;Jl z#h)bOKdOV#HpBobR&7{Bi zWF!7m8UKaM>pxA_U&RMK64l>i`Uf@jH=kwFF|A9vR%Vqt!A%Wjq`Tuky{+%-ZmgbGWs#~=E-zDp> z;)5Pe^p9xjZ_aG={~p=@ZJGD~UfF*Y-=Y8HX}$b2pK0{JLiWEo^ABv}{0oO6(fHpF z_!(P&k)Z#7Q1-vRdE=jG{PD1izpJ_ML2(#?igkpV0 z|Erk)UjY7O8UHeO{+C+eC-DDEz`rR0eyaYPR`|02^O*k|0RI*lzXiMhYO48PVTGT- z|4o2DB>{e_{s*k^W&clLD*~4R{!|&il{^1~n)u{drvDVJ_Hz8wD`kAL-a z@}TU0XLtVlt?(20Kkc>Y zW$^e@iGK$0zmoBP$t-@f{(K|j|CV|D zh>U-rx$q(4Q2*8I??-$@>HV<&Bzq5k{?xSg@%10RmZ<%!b}*l6I~Z&nhad25zvx!R zKbG|fxhJ=xb7lMrcld!$*7z0P`1+Uii%AE-{F@o!*WWH>>mNn?1KNrFSM6{&N$vP# z^^fhL)}L|j&8EeGFP^`CySwp6zRmNWbNcc1AFr|c)Bn}oWFL$_vLEE@pN?escK!=H z=s4dNX|6vuIsWQ}y9qRT;#crfo&P9$&_aL6Kk?k2*O~t#Lc7VYfM0jFGyjDh#ecsQ zKI|Lr9>4x(>C)WAv{<4-DBupyV{Z zy6eSXwSxvqt>O>PsNeJcWe+jn{-@&A(;dEPrN4~-CX2s0Y7aR?#_#P8zrqS1oK)NY z7Qlxozs48GPc{DoR`|029PtYJ9f2t~Qt<-Mf4CVibosXDU)4CG13@c%*a`hN-(vdD z?DQRhDYwS?hh+>uRsTa)_zC=aPabkse|_(MM-G+o z*SN#?I>q1c9XVXaU+WG(-v-~4%lbca32Xm5*MCpC$oTK+;iDZ9H~x#y24CDa?p=o8 zdh_=rCk1?AMtNjFRU z`0)qgt9Fn_sSQ5H&0Nak|K0cGC>ej9yZBew;ET8|ID zug0we;@`s(-&y>FHu$37TF(6U9r^?D%J{W<`U^XX|Fu^5u&?OQ)&4(h zgYW-O{P=e)=nq4##+Ro5svR^CvBH>clvw(W8MFVedq-O6atzkdq&svV@^v%wd6yOQ}IIO_+JC*!Yor@!9{A4nEYWBF%t z{88ZlfE4i24*HGTQX711e`FQ&f99|s$iM{nskT2;7oQUzGW-W}bQUDD~=Mm#nz;9T=kALA|FgoLZ)ed)ucr@|NwJiUZt|Z3kQU6zR z{7y~o|Cez5mki&liI05yt|7)5fM1*@{CpdH^|?J+U0WFE0>1ek_x~t8|5ZEaPsAa9 z?!FerUuAr_8Hi5&li_4R6;%wtez_0m0@juo1Un_iwzZkczXZ}xX-P-sk z;EU%kOxDw1*irm1vcbo3o5}H8v~6u%4fx{u6PoyFM}a4P8+j1yvV;=uo^z=tNh>P2R4Sx92`121{SGP7wqyB&53}3Z_ z_(2=|is9VG0Fg6T>q=-ziJ0%@Y&#t_= zMb>|sp8l#G#1Grxi}-)Y+yB6}hAHFU-%@M*iFObdx1n3C+rK()nQ>BEV=Ca+Z1cu& zi6*{k2l2@&XZX2ywKb;8_*r`EFOuPxPO-)pdHXTbf7<-E#%+Kv#y{8T;R`#$arR4* zL;q(iZfn4jk4F79@ss)Qx4{>A^9l2RX18`mx$OUBJ^zIr#s5+peB^C%{M;Vxj5}oi zHSy7o0#7Pz@YVVEzIpA8I{`oR1t0%3!FM+Q9w@iYKjdwG%Jd&Gxt(#h?Ef8l`lB7y z|Byrfx8B^&xJUNC3BEJ`Yi;nc-I$;A{CljOaUbA|_BTt1glfi8L*|y!S z=mJ=OR=$(3e|t!8{aG^oi#i*ujw-}r>)+rr9RJ|IpXu=i&4%@V;`sly?AZ5H9sdMu zp8p|uhnfDlPqs5EKz~vHHT4&E&=I~3+r+;~`>Sea+z~rAB>cX$|6<&< zg~$KvcE&^Cf9V!p|1|v%N=Ae6{_JKDE8^7~qTc*91Rt{;76Qf4>br zt{XPDGXJ;EZ*Tk;@Wt~7?$R57qaDP>ZG{a!>Sk_Z_%j!@H=Y3e@@+i-HSy67;^H=7 zg%3Na^`Gv4i9Q4Cf5rXZi`~_KVl)0%<2JOqz44?R|0e!Bi+|9{e>ncexS89T{w+Rk zZv^D{Pj?spS{r;dZd-S@H=YLk`t3aan)s?6jDOe$AN?nV%>SirIvCH${@?1(fA1QL z`X}dKJ;Og_Vh3Xm;EVCcZ45uv@rTa}AL5U?nH+!CO&yH6vi=;uvHwfF{s`@$?zkgNf|1R-sb@9Jp z{%7s(WGs~Nr@He$Y=f`XpB4?Bj75Mi>Q57VXZ0sygD>L0oB5yn&(6kT+5ZRJ`5&=q zf2#jWujy>OCi~w6-CWaLGv{ez`mR3WxYvXLm7bWc(g_ z_a9gNK>q_)_^^{W{u#^iZ)QUm11|Y!y#A+}_5Z1kKZCmX-!uGa**V5q8GnvDe2>%o zYn@}jB@d19=lFKxuVng@_blq4tUnLfmXaI;mOMA=e;liSsp{|1#5aFn`Y$=Ds{u=H z8}Z+9r@z+EaShx{7)I*D*qD1pRVd^)XDmv z?k@g5hyJf9=w^H*`+tnP`s264m;L{lxBrrE#wUQEeY%&;+Ye&+spfyF6@G&J+i_(# z<5Ssxj-P7$O&ffi|0E6E|6SdT&jDYIfAaP87j}3Z!A*q~zNEj&@n?S3%?Ja&SbxFs zQ`J9Ug%A4U@h9>fx4WD1g{;4(|Ee9d7qr1g-ORmA|CxU~%J@>&|2TL0*IMCA`jdUU z{$6^Nu~pWeVFv@xw;mh(!spofH!_a5zbm^N^|Jn&_`;5Y@3p~KbsI6UyRl2wUlU)ogEV|L z_^6xtEAzkRuI|Ryvi^T?r@!9@U+DH5!yoc!cjFsbe@%R02OZ~I(+VHD zSa)ML;8$b*ar{)X)DD$7L?qU20_+tFGinV{c@u#qZzQul=JP#Kmoq4Zc{n(vsniY3DWe1HM>)tcfq|ATZzhHStZ3KeLP1H~{$K z_{SxFsSUo`ZpL-<8U*H_#r&rxzG??$Fm3Rw=CSdI*^23Z>p#5)1$+_z-7RD7z%KvL z4&vfAXoD}}#@AmByT)rA0{9~Sn)t#F0`qOi3Lo|n?f-r@{yPEs|10JGpFe*!)%IUe zVNrh)^#9W)d5xCfzo`G3{wIrnt(E_PkNt+3&Ens?T`wa`#{WPs{%A*$pO{wjUkUtQ zk<-h_27HnKn)u25_t>nz!@6a*X8tdIy_eAj@J0R)bXWhpHuxfM+c5mw-t1+x1$>eJ zn)t$w5&)kjzRB^otmtL51AI~cT;dnm;Hz<)yQ-JbUXH&ezG??$D7C>Cx*f{e|CrBu z86H{xU-a@{*g;^vt+2sYd9T>j%jhiouZgePK^j3Dd>l8J?O6WpDCun+CgXec@*nLW zE^b3s_|cu}`SEXihClS5y^X^GzjiO5|Ix%3b`Y3vE3E1d?1S|mzc%;k-o_DtpSLd_ zKh^qQYvq4}@!yQay^S1M|Nidu_pG<>f7H0;w(etelkxN1;rn#)JF@s^eb~o;{S8~jQ+C!n)s?6#E;nEBX6@a^MAx0{f#`?|GDn` z582dTao?On8UE6{`WpiPU$j3>d|?M2=iB@Z7WEJIQR{#1J^hV=fG_Gl$4|BX7g^ya zX#ZJ{^*4@@^{;ZLziESy?bbYu>Azxre`Ao0KTi)I?I`k-fDL~AyYcxyYe9cwFyM>! zuZgePK^{RHe3AbTvHCx5aew1?vj6k-{6{;8i`%d!KJGtmZ-3)>8UI;#_}+~c`JW*F zR^;RwC(8KGxx>$Qh@W**u2CT4Kkp9T=MaC!q+H`<8GnI0{30uS2zp6FeEu&fXhSyx zzPSFSJ6nHPzntBF{McxsP(lvCE0!}W*ypO9*#F>1t4VO*F3`q_+tL$MLm4g4(e~(;H&y)y*AJoF8lwI9=>V^ z@dFO=bK4$m6w3H7yTcFK;0xXU!|HGSV@Dfj1HRwr&F0^C>){JK=s4eoZ17dxvi2Qq zoFn`HtscH=2WfVCC!4JM zpPaS4{&i>LkE+v-HO>e8(nEOsf6~JjcF=LY_1NI6^OiHtKGwJZ@Wu5fn)s?6q~W!} z7xP9vnE%VZZbLrM<5P!ubgN(n+_IImq~jjK9wv ze#i!2Z8!Z+F(};fsPX<6zvklV9=5d3< zC6A5x2i)QNZSb+(ntgcvJ(bcsWqiZk{YSz!__+QK<2CMVO5u|4#^--&;;VMhUc?4p z_}`cLKl{Iw-Xr@@-T7an`}{FZc*J~4@0I=6#82kGS#6#F!v95V{CV42N-JdlHJ`tR zc2IZR25tNo-|NrxANKqq^g$W_R(JY)I$F0sRky6y4xtap`fK8=cF_NP8+_q^F89BE z3;M9^|LyMlFSWr}d1rNNK_8L**Th%tp#K%R_W%-B;rsrpng4kV z|F&yd&_`wc%iZZ;tLr}(Y{aA%^fB3gP5fm3M|9i&0Pg?V7WBWe|986cKYy{c{wnVg zAGM%Q$o^~Mt9CH|iagfsAKRZfko$jZOZt@T|K0BV57^+Vyhohek_Ke|HStwD=zq`# zU-*AC^S|XcE$K|z|9jo}Pi&rlDR>{l@K@|@NuQDZ*Tffg&~d)?TH(V!>iLh`erZW( z0e-{J{QhekKh^Ue`BwNa|A+dMYS#Y_8`O%_5j( z)&HOszU==X7XR5#w4(E6{~vIfe^&Ru1ANRIljDz@--pQ`@(R`|02gL(Vg*NVO%`>%Qb!DRmXt?(20f7`FEXi)Z_sTIDI ze`Y@Of7vxz^d-O-_g{S2UH(uvgjgNe@%R}qsULfR^y)p`Y&6Z zMXP1~Iex18*V_1x^XBI7nf|v8%%-mae(i6(|9ebNf3(xYe;a%;Z+kq$A9GALeI4+{ z{I4dyu%i%&*x=**kIC_O49cc&0KS<2*2G6U3Opf)T8uwo=fHsY^B-FZvgwDz!W;{RWF@z1yNAMkyju=QuicLh9uYMQ+M zyp`Vbk5oHoFLb~4@dxIO$^9R5bv6xw|04f1{YN{9i(8+K{~~Yx!1Uj7Z8m)e@J0S< z;tM+n%(q2W_^?k^ZhZbNDa)oy0AJ)E$H)3J5WZtV-0=K+<$iYlUA2QW{8spK{uS{2 zo1aaW%K7)CyZo!L!N<6n9DmGn*>ss4e@%R}gMQ;SV1qB>b`p>Of^526j=v_pu!F#S z8??fQeF_K0$A8-5Y`Q{@KgY-Q7so{HCRl%=+TrjdWQ8xs|77O>va4Ftm2&(8?&2S@ z!N<6n9DnxJt?4Q`{+jq`2mKaXoAoCmZl^H+M_kvMu9oAki7)I3VD^jG>ii?@;@KO& z{$|v~)^v>=e~xe0{#83j!(-#W=zsYA$Cj;XP2ZE_uX+D5VF!Wv)@Oq+;>Pd4HhWEL zx=xP2Ccdzv;1^lp!@mA~ivAzArti!8EBHslcM|pgsvV?JniSs?yZ$+Q7w>;xV)GB? zlbh*#9iT2;>SgOszG)qQ{TqBO5x%g4z&6`hwnO_@zZZCWGu?wUz4Ye)g&l=J#0DRAGdcdUyW7wYW&Jhr(T)O7 zi0=B6Gr9ivwV@x$`fK7R)8Au-4`j1{iLXCPD%;SH0bh*&6#S#%I|9+EL(1zzQFB7W3~zng7d< zY)7{OzL4*HGTfEB(R|FfC@x8=2` z-^=mm_^HM}Xoa7k{m&ZMp8g=mU(^3&@ekSHi}wFV-v0mIp8h1qKhItK!#4OBHh`oj)?X7}wS)Mii*@}+{mnly{kQ$MJ>4hkKfs;- z`8N1Mw{sZ&jQQ>9FS7oc_`;5Goc-dn!B=(L`doYZtE|5!zG??)1Z?WB(4Vh=TlQ&t zx?k2`bNv_EL0sJW9r{0dZ+lAGN#j3F{AB)@+TaV`=kogZd0 z|Hs~Yz&le^|Nnch0--*khaNy6^w2L&Bkc)2^iYj}c#&c#LI9Ca#ES|B5sd{5NC`bs zFHHhcLXQFxdXN_SMHDXmzsZ?To;&B+**Uw!FTVai9$$Fw+3e1|_j6`uXJ%)2iz@%= zH_bEr6*vEW|6iCt(t+-MzWnr-S^Pmi(cAF{AWfV%qSmQ}tiv z^XWff$-l4L4wV1&m8K2PHdTLN{{3`t;;=FQ_K)lKwe_bBN2cm8%%7)&?4y?ap}(^u zo&Q~@PaB?Ns{X5fKKZaY){Kba#sJZ-A}!u6FR260|8TzHh1~r6@BcbUraw;y`A_)e z?~XtCyzRa#&p#Y<^Y1_Zda^8ko(}SlF5=VvyE|e2rMR0af0u7Nypx;%_^|r^>nW6f z*zs4&FMs#^Gxt-zPL^ziq}jZa2KQn}5Ij z3G?r#gMz1Q%`gA%KCJ!kEdQh7S?6}gUr(v>zrO7K%RHSv#*zN@uTWi{?lY(ZQXBqg zIO66%dAz#+zA?|=`}t>{4)Tv1^2hIA+AkIOe^G%|ZdlD($35}r8dT3<+vBS_3!E_2 zUE=1Pe1iKPw5t!fs%xDa-R-V%o6O$!(zUcb;coAyGr1-8mta#jt>!E^W&iZ`w0}-* zZ>e-)-DNesf2G@~z4)T6!sxe2_xBfNIZw7kJYSUMJVh0+FUo>vftOcs*6Ehh zZ>aZXC|mEW&@0bhaewNT<7W<7v0JpAf4bWdaOQWnSB|3c3R`ry zujlTK{R`8moL1cJ-Ez+Vy?Xb`J)ZocbRC6FHCFblUq`yzyY(o!AU$^g>)gL`k0){X zuDyB)yP3N^GlggL3gU0O+q*odSFosGUsRlsFLat~x_A3iPkXmN?e2E>VCawbXSOXV zoy0e&9fNhY@@{|PYCCj+ooo8)p6y{hy}D<-+THD*Jd{r9YKjM}v(@UJ?O|MP2L~+T zl~?uai?WE9Q;SlY=my{y?#46lLv+60_5)^hoLAjS_Fk`c;YW8KVb3Rq>+XL=Y${*b z`>Xl9+c9(h#kXFzcf?%Xz;^#C&D%?_>vsRm;{JEnDUQ?oy|;z_5Bi{7eNh%j;Q6Ai zTgaF5d{N~F`Enj`eo>b5fb)y8;OUn4ZhPW>dZc%qI{I65o$7Ay)`8@?)c(VExA(3W zM=sr~FG*!-|L*_m|GHan{p$XbTa>O}-R)l2uWgoJ*0Viy63h15LtGbOZV`V(E(U{fnD+shZt#lh;joKxG~L$rU}tgxy#&x)&hw$JhIb~lCY`E{@R zxL$1OZtwCmucG!Dwz$%&eV*?A?Q7KaUu{Rb42$~yMU@-m3z7OfXHx$#{{>mjQ&${c zlm$<>989fWv*z^rmAdfYUjGWVyMMQwI1_3fSlRCOS$d_a`{Rs%-R)EBS8Egh`h|Fv z)b;&~vN!|qjH>a@7iBq5T9uzK%5t7Bs-J;;!Slvf*79r*E3>TS*&f!r+ueh^<#cL$ z_#bzBx17grr1lWD5?RZ$zgkz@6Sq?P2>ZarYkTq(FIl_C(^BIX*h+W12hW4<_AXDn zNj$K{%hvAkly0MZVJm7oIAHIo#)i7%!CH;3kFf1aVnf~ejpoze@6~tM;Y(vfnJGN! zG98z5w|B>b(5>|h9d~|j{~7Znso&84&SkNo1>OBychG*Y)34ZOxXTk?gT{lfxhuCB z?(!i0qt9HecS$_a-9D9Pd^0+(?r!h$6jnLB#}7NpRo(q(@I*IP`@7q_Jmt-4f7sUT z3v2yscb9?u>z+rLe?Q;Nd;FE!-Fy6%>uz^5f^N9J|IFRqEkCJisQkb>dm6@HYCEp$ zu-`c>JKX&*`_5-4Y<75dcz0!IJ0d&W{clg#-}K1r@ZPR{(Y5<1`z>X2%3kz?>~QzL ztB<1poMW=Xz5l|9q|P_wp`M3@jaTN!vHz*^gOdw;J~*D+u<1p1`BERQS{frHNaGvPVif8zB=UJDhF(95vAEb>%nK&;}uq)WWe?i`jiyUoCmHnw7JXEW;{6mp!!sV`pifle+|aEMJv?5 z@~&TA-~EKcd_w*Xs@JXC$&TDfwsbGq$p+c%{bZ|kvdMeMChjAfd5COB+2X_G$C_j# ze zs-NiZcW|D4aClqy{VM%`>(cvG@P32&-ARS1{X<86U#q|W=lmn=`Ixc|o8IU?|6Aq9 zjn`0j;%o9#JzgiR*c?8}jaPFGH4lFoiPmCBhF^5`iEcpgs=MoQx_yD>Su~Cs8d_WHKiALnA73Rm_W!*X zB=`S%JZ@#cduVb$A)d?jX$`;Z@-#NodHUl)#$y`~7DDp0eo5ogD-LZ9zvA-5HyR92 zNyyWEZ%A*L^~>34K199O%6XgWlcU}<<-Du>|0w&uvL7k?fwG?{`b0*C*!@k_xKIC+6ru*HnFVC6M)@zl2s^ULas&`+b@DAPAfZgWG^@h6XV_hb! zQ(MpT{zbgI-QB-?J?P!PewOY(On0|;)4{qZ*wmlb>)og5wz=K?abF{+w&T79>;tQf zc=8mJBc42!?sgBJ``ztbp2}mS8*FOL5pN!~9UQQ8EwzCsPd&bYCr`V(-GgWDr74}t zwTegC`Z61M^0d`<=$t+v-@6Yp{Z=Z^rEgIAfzAEJyF8!hZuh*u<8JpV&$HZSxWD6W zU(h`-+}DA{{fpJz`w-px7fEGt|6)zo@7}*yTivHvN7;3iT~FCT-M@Hjf!&8sTXomr z`fBvw%dYMIS6`j}n>D%XaQDBq`Y*o5uEX8`rmO$zDd)EvNeByZ*QIdEjyH`^&{Ayzehpy4&3o>XwhG>m?p^xA(4J?0Qjr%KQFu zMQz7@W!Qt?^1i;uC%muksqXeEJZ*J-A9c5PdGOo?Z1ElM>w86Q$8{9;^l$FoOK0p@ zx(>poHr?I5o;uD~ln$vQY28%L-M-!wp6bT5-l^zrpSoTmelT4h&r|!OztK+9{%v=A z_xd%PO8?v=D1F!M{R>+^aXhzS)9d!1-P>;NgPC(u|M{T^*+-RKPW6LVQg$_E*Hl)` zGdOCz$hm_0e7w^u{75GwtFBSOzqXG-5lS;m$-)}3a`<+#G-*cPZz-d}<(WdX(%LLejh;nkv(8B8t?HRln+jaeNW1y=XOHQ%z3(=+~+t| zA!mP`nM%OKneRS)=*)&JsO`O{c z^{kw)>&bo2k$6K^KC`drx|ldKLeBJ`bWZMb&Vq%r`&?;vu$^6RB`r?456bU*?%?j5 za^`c~sRZA())S1A`<&C}Bkufr7A8G+6zW;NK-ZJ|oGUsitMAf!w3CoCb)nA5ea@Ma zatiCw&O*)(CoOU8L*Dea}pNHllpignIr~sOQMV zIw$uzQYtst^0}*!v&}fU&p9U!6mkmn+)cb}%IhzN`%BS>tw5O1>sW>N#6eswc4}SXK!E){;SlvYbUd2|25bllu(Q8U4;+<9?8kGjqMJC-*sL zTgWMm`@uraNyf>2&RIM_rl&OShX^?@hZz2nS_4- zB|Q%l>RGy3FAv-YKWyf}VC6G;9+d|?Kgpk$yq=X$kS~02HUe@+kPx$`dGB$T)4eZKw3ScvyUV{){Tn_%@F#Em z8lTehc5P*Wh5FuJP``g<>W5t4T`)Z5z9G`#Hu)F5d~%=fU&sV2pY;pqJnO%r^U9r} zKTmjLFYZJA_Otb--XBE%EybCr6EA$kee5F2C!zA2xX@eQ`gdqM^o%bi)AI(Qo=wFE z?&58_zSs_%+F`JI-b8v@+fV2R4)~u}&xTOX@sN6QeZdbqYS9z-VOx*raWU2R2dKU~ zw)$SUozkoQlgclAa0Rs}pSiE;^}$r%Zxrg8|Eqr9@jG;%b4GUbFQ0hN2--UwZ>sON zQ2Dg#*-%`uJBbfI(&u(Gt=D7zJM@&cpErfnlk3Yll0rSlZq?&r((~4UdV*(AdP>{R zn}vFg-o?&a#UI?D=qa7|epIMu<7xf+=G>?2%ei8Edh6M)(t0*<^73Q4Zr&!W z@9o!h&g{MZoaLSTubbeM>iPG8de%^%Lh1?K!70`AcA=h=`0l34sA}OH+u2{we!q^5 zXH4zVo!#~`ZeL%=zw2olpFl60g`T`Vn#$)LA@$_?a;}}c$1!Yb@ddiSH%1n zzSjvK=?ArlyOi^8Vcfw7p3lpPxJ$1`cM9V^!M>l$eelDM@9JNVz}ebC|1PAdeBLGG z?5KGqaFieNZ$Bfu`E$}&ijdk2YnlgZ^xDrE^R%U=cmA0FYODD$KEH%{Ea^NL^i1p| z)AR0-dUAbdC_;ZFEqbCJ;rwyDslMMUtnbhn-$#Xy^n+UHDIIs*Bh)j=<^x9XU04HP zJnLURgX(#ouw8IUAPyT;P=ULmm|B*%;EV!|}&;Zq8ZRW3YN2A=I`{08uCuQX`EquP? zcp+!*XWu`$;kPpM5^L#yGhTKG@<3 zGCig1X-^VzW}nsdw4Z#MkhAiUpVrbFPfDaJPOR#dLjtMcAL8V4U3NoUxXS)3(k(cMYYp!f-bSdppmccQ3!7>&rQ% z&%aCCrJo7oo_bN|;y&k0MP=7bX@CCbLe3837j+whl0+o+}@Hn|R^3 zJ|Q3Zq;9A6fcTyt!*MD{>FejE?NUXk=S(-@P=|qqkK(n#;|=@BNCocZjc;p!-Ph5&wQZ>U)@@cX_X`b&l5SkyOto0_q99 z!s>~2l|k1hKk0Hx)`MYvaun-*+4|)1fa{Zkay}K1v!==?xS?;R>K$j(I%?i7)t{l` z$A_t0NA}g9lbWk{Vnfz;sk)Yae-l2|35>TXpM=V9;#qI*_71e2vc*}>u%>$Sv`|m< z6Z2cpItKX2p<~c9`WfjGzi&u;k77{HX999o|4sFta~3c0*3Xv{CppEM^n6yxiSn3z zSGD)79>p&8<}{Vhpn5(hJ{GHb;EPJINmXE z{*ySZ?Gm`UXVv`&ADmIeCFSguPdA-LTfbjyiu(%`_oA&|m->Ko>_NK!$9-()wyE9^ z5M$4`;`um!->_DucC4r@(tDBgbjI8besS+GPVOT;SlfB<^4YkS%86+`?Mpq*8S80H z>-(^-u>BF~3LkMtK1r2d{RZ#yS^NQQ56by6aazkKxS$t&a3&Pje~Yuj^aKaD;2JUL zIWbN;h2@OjM8})@A+J*TtlR3**vAy_q#9qshn~o1>_*Bjb2C|fzHLL?alDE1HR80! z9bCv4J~+pf9$`77bviG6f0uu6_jRG37^f#bBVFNx6Zzz>qx>58c^$$! zIgL65*6UI6Q{wB4P(KttIIAyHJ{gr?>;(hoj;Da6co&P)oIHl`;9}?cz=Id0s4?ft2aGk2{zIORJI^PY1aqm2; z$2~vnANS4&gN^$I!nnu2qH}Q{I>NSuahI-7epndy+^jlhopFN?w(@sb`Lx|fC|^P8 zEG~>Yf1mg0S9Nai!4CTU-ggM&9-T$!;y(EL_EMRi();fh3OUCaC-?h&>W`}M{h!iy zsTs0-^76_#Yp==lw3W|}DxXV)ET56t^m4#CrR7r^_ltyauQ4v}bI#7bGCig3(%*z} z&&;9gmyPH?=Nwo42fiIXuAA2TM=#U)ri5{y>3bcs`*TXa-y!YST`Y`ym2q(&I>Bay z?O79_sc>(`8wZ@g)=JD z)7CB(|4e!=Bh<70E<5jO{(7cAmFX$H9^ENymqwyG7xxh#*wme}@+s{vT_)sgGfwV< z4>lrvK2G|6n|}z)XKOxP&#`%RAAGR!$7Fii%4b!T&t*fF&m`jpAFQ-|O5bnuct}0D zzTksR4@l2QhvKrSP)~k6D$eg8cj@&=T92*})}zD%Iv4k$BkcHj{^c{G-Hpdlj$>-) zzw7Q2ai*QvomTGN=PK^0x06Vr$vDT^^P%Yj_3v8ZxY8$df32=8wu{Fd>VTH8eC8L{ z^(-u?`^X=*JfQMfeUsv{jj()1-q&@GFXYeJ5nhj^+==0r+53@5nf9?fi&({%Cn&+73k$jGQD9gp4~c2jGLv4Jhst*HT816!XO_}^qzBs?ke;P!)PC+I)U)!DuIHqMGt;K@!Od;Z z{?fI=dQ^$)`f;CgG%uIccWK<83mJD_4mhXtxQx@*uWMdU>8v7*JD*>gVC9u_O2_Zg z_VYSn+{?@8apykgY;Pj#*Gc2v7RJ53oX(kAR`)q)VnA_^-#~F+HDug77EWp0rTwK_ zg>f%^P1le6T+g;;o&oKWw0vGKA2&CkmZw?SMb4>-}2|=>ysxNs@xdL=Q~tBt?Sa`D^r~7 ztCEF}^}om`r}9hO=e<7J$)OBEG(b=y%7z?4gI*y$7J^nrRDQRVfoCj zqSqVlbIwV1e~NF1kME)I`fhp-JTmx->fbH-Hsk#A5Nw0!x@wOmRKA=$r`n~Uoc|VH-@%1^;e*q; zoAi)!27Qh%;vOLR{$^wiy*zRs{M_O>zU*51^VfKekH6={^t|DFq^DzxdyR2&pYu(e zs=s%E{|-)mpVajH=Ir!bkM()O?3%is+~*uNy?OhYe3HtIiE|F(v_5|{wjpsQHzErk z&-Ij^rhKC6Ii%cEDqnU2MfLnU=d?YiKc|or&*eLKu3SC056=JgbNU~-dqP3gBD zCEHfK)knO!>#F?>%J~U#TE|D=f`0H3_n@4;;^rnMeGYnV_W()U)9aFs;N(8GbBp$K z+|YjVcFFYo<~&r7tnJbSYtXG%R62_JDEZBah? z$Hl(~n%bqW zx(CFad5gB|JNgUp&FMWS@cS7&;T`9iY6o*S>-`XnH>KmahHxA=vVmUTx!>m%{?XIZ zV_%b=vk3LXIHvVY(i1+iDjW37C_P8n^@Z1WTR&u0Dk$Q9h@-CSydQ#m!uCUOys5u5 z8*y6e5xAfqeAJ_c>X%75gO<;mgyplP`g7pqKDNWAPWGQ)3d(u2kh8e4UXQpBKG>F8 z#|59;pq#e|ITK&kIl0d{#{MYNQ+ogCK_O?8adMw?M(&bvO54xB2ssPi(Dmd#=gbM$ zgGu$gO~@Hf>73l>oZ}bC^ptWwB;;%`PVRHgq%iJM&bp8@|4m&_?sLw}jf2(mb|GhM z6P=U$oO9$787IH~@_9w1`>>Fc-#4r?Zlnh*y>BRu`(K5eqnqk_avyxK&ALoaDd$~` zv$>PbgM6c#>D#%F{iGJxBWc|K&Nxl^j4RH`v*~?a@J;*2@0RIld#)Vm-y`JAZLaId zeWWL~&{G=sdxe~lEp$%qbG}jG^ITF+_w|hKKl^)MYmAfooUAo=qVqZ|AwsFrBRM`Yz@Cn~*cJCB;2@9JNdE zIUoF{h12wX*a?T)v%0cKul&{SU-tLDPAX0uH+rM~Uc}K`=sBtA=41<-c|SLW+shUt`kTdt=FTL3lF}ZCJKlGU<4pDaaiN|g+v}X%M?SDE zp`Nz(v!9-jleeF3#*Oq~2i1O7H>7rc17Y0xcO1qty1w9pP0u&j_1;el^-S)db8#Ph zu<`r->pRx5R9Dc~$C%bH9qsBl?Cfn_zr^21!k-fapVXorN!!n7g?biu)b->(=c_$1 zSUn3N_2l|;PMbeRcL!G^KE5`s4|&erSMq%XKCb7!jf?+|xJ$>yZDHICJL_@hKIce0 z=pXk!r{#K7-iX?zjfL$J|BiZm7oD4PO24aaYv=2V^Xnlw8w28$jyGQr#y!8Qt{?Zg zo&{mt`8pHR_5DR5XKXi}llz=AqTZXtx5G#Il(wJ82;<(|TJLw)88`BWjm+-<95meq z#NIQkNzbY~-gMu~(OWLyx84TtvoF6vyzr63_^jUJ%lbWZKRc%^_V01Jj&vQ%yzT*# zbu7`{^|*5%`E!ePEU~rq`|qapb*A@G&!++~=4Rlh=Q!i!KIgNYN6_;5ny?<__R#g@ zKIa^N$iJQE_upHusPzzr?@i24dRp(lNA@Jn>|SKy1m($t};&UBR$ysulzZAJ#yZl@@(pVF5Kgs&svW%`;eaL99j5?d+sgDXY_Tl z$v3_0k+TzRhn~E@ZMq))NO;|xRGiR@``8XU(UQ$C+4^;b7wGyM8SbWRk9#bqj|(f` zV&xTpLK`&hF^apjz9Y`Sfd6^pZX0*hXQSs(CWQ5Ud~I3>2F?jpPT_Og+{=HS!8Cq1 z)uR*K@;T(}<>0xV55rN^!TYr%mlkT$zjLJmBLz zxXnN6e;%msl@)beczus0sUH1H829SKdU_qj&H3OrC;jVtgckB*_r5i)S6s~1Q?mZE zv>)lyR_iNydop>OcR$&*UNLC-EVA<1vXsxp2=(VtUi(4>`~z{f)%Ve3=(;wSu>FiY zL*JJHPFvM0_}rG(@~`hfrs7zuKN}B-Nq8Tzqv%OU9x}YuBEt|qr?Xv*Q5BmluttCH}Q^lKP0F6 zA=A`d2Ck>6{XCJ?qu2)eI300B{ek~^+j+#DmmePY$z!P=%_FQw?Tht#lu){Yo7;&4 z{p(TCxGza@xAsF2XYjxe8+YiLUP&+aT+hbZRFB>h)}u^QPp@#Ge?6MC)T5p}?nz7M zLzZ$6kj#g~zo&C?A3Af3`H+%uKEzbt;}mymKcvApxzG7*=YhCachT!Dk9&GOiu

Rgq(!Nri_1~5AHGB2U3Q$wg5?{%iw{lUz|0QWHmT_^Nv zs{RB?Ev~&)H3(z=QTyvoGu8U8#@rJ%=9ZlPiE8%N)$Zv`d_5Veag{BxF2DwW%v@qy zO~fvu5Bm019ZVGlKnF*&Ym^yjvg~xOfJ5YdNV+&?yoNgvBJD>|peDhOlwQK>%t~LP#odSsZ^bi4LQ+Dtnhap8kzdI|N-_UEeYO({)A97YX zE->N)`lQ-9Oxn>Qq47H6Dj-{vj}3(5HxltX>>GDf+7WiPM@` zr=LR6$z4AHgdI@XiN`s1196&DTv`N#K=J8^`}g#hgILC@gY?IWfEqjeVTzVtWQCx| zhq&PywqOU22M+!sEt&r0*Kd0`_M(q+WdwXds}xiPiVsUM53KK zSFlk;#z6arBS7b4>;Pi|b5F4Kb7=FRic@Ko*A>7CwTx?7Iz!XqCP8?{%TppQPu(+W z1nj9{RVu0i{vVbfDh#)=MmH|XycVKr0YH*{D)&Se z!DK}MlloIQjxGxBn~BB}P}Q)d4wtXAKx0q`=>Nf!>$>%3t*8rUe6mTNklmQ9_yp$ z9)17xbjWQI&UrwVQz&FXkcM&0faijsI$;;*VHhl~^nv~w_D+aOo??;2=a?Lb)KSUI0xT@?z2KfN~*0#B@vyDrBXhu4JhJ z5{@C(aL|H(a%G}>%9`7|vFi3th~UnNY-$vgNe|@cV@CJ^-TuzQ$gPpW{f6*CZrPsb zMfl@hk3JZXkcqR}X?4IKbqbX~m^%3*DTv?|Hq!lRp4w=DsS4_8UHW^Y1li5u4-%BU z9DE=Uy;FYKm_!T9tW;$V{z(dY1heE{T)tAy{HVlNbAq2UesD-+MY?hL2iBJSqwNVE zEdLlAE2s*+G0@)=h|Ymnayy_n89*+>;{%H+KCtNGgE!*g$=mesfZ2ld0&%I)jw4G? za~J<1;PG&9#;k|~<#G;QnGm_JO0XE5>=-UMuUz(Sb`nSCCCko@_5zU>pLAgGmV1{D zUvxW{36X*c{K92}>Xs^yivHDtOa&;i+zK&d_fWnl;p@?H*F zmIkI(o)Vs(@<@YBoChu^53bS?XcC%dwWD)WH6H%)!q(`rOI|#>K0Acuq!0As(gGV< zy6%rpI~)&i(yuhM3U*d-h-4w&Shq729{hxiuxehz$aOi$;s`5qY^K)mcg&wt`B7(& zZvG6xk89Kfh)FUXnB73Y?km>4otoZ*=pKlxx~Up+j6Y~j`Qxssg&X4sbxZ9M0c2Hn zT<{rZu`Ey7mmz_+rQ@@6*(`8Rv@u+g19^aPK=Sm4%ca>e+HgR9k9(p$yos563dLy` zvBXyu;&@oEjfZpi3m0R_O;ZVB)H+7dq7Wn$e(Mz{^XUuKsQ#ix^u|T(g4A%h4jNgM z_M*T^Q-rv{exN*Pxm%N|m_IYl7Dyh?GGGR>pjcYR)oR&7kEM zBg#Ed$>PFza!*e|oeD)X3F2B-0+r#;emYoBd)sL>lBT_KEm%H#>t!)zuT5Y*CwI!w zR`nQAWi~j_qmJ<4Jr(#x0{w@59POTAApj_9Vn%LF2jKNrcw&A*aCAvz4-Y@%UHJWa zZ|7X|*H-x3$x4go+Qk4(=k1(pUXSChwFpMeHE-Swhfa#l#L?gG5Ved zRqYD*&!BHOT{;do)Of%Fi|DKCSJkd-xb2a5Jo08o+~>$!9C>#mZfxW|jl7)^_np-E z?|-^~bU%YXQ~td@KZ(Ks&&1!eZ34gd?zP%~tx(HQe`m^N(EsK7Uo}wH!0+9A@Liw% z8MWH%eSLbL*FEb%=pKjXU8RQ(_ez65#o*W7mvln-HyHfm2LFWOXZaVt+4#TJ;NLX( zcMSeLga5$bKQ{PJ4gPb3|I*;M8T_{f*It>H|5*mVi^1=1@Ov5j-Ui<^xMA>ZgP$~b z+u&Ci?AyUV_l^I7!A}`{*Wh~w`*i*DzVZKLgA0R)22TvWGWgYs{p)J4HTbg({u~qk z^9=q1gTKh&*BSfjp0vykzhT4Sun~ zy9PH6e#+qc27j`_g~5jgcMLu?_@TjlgFnmQ&oTJ(4E_Sep;^Aj;IB9Mn+*PDgTK|_ zZ&w`Vm+vt6I}HvQagOgY{;xCm^#=c#!EZ3wrvFCc|0aWf(%`ok{L==%)!<(@_%{sx zO@n{S;NLa)_YM9-ga63jKQ`Ew|4)qn|7Y-@8vJJl|5t-;`hRZx|H9z^X7FDc{8tA5 zwZU&Q_-_pU?*{*^;*ibRPfq2id4m@XUNQJZ2EWwcn+7)wzO6Wnk4=MLZt#-^ZyVe) zxNUI9;A4YN41QqnnZf6ZLw$}6zA*UO#DA5+uQvEK27kK2uQm8H4E|n&zu({=H28-N z{!xQpZ}1xpev`pJY4BSN{uzUR&fs4#_?Ha+6@!1x;6F3?FAV-Gga5|h|6%Y)d`c=W ze6+zIYw*Vz{J6oh2G1M3Xz+@`FEaS028WL69DByUY4E&27iKyf79TG!M6>5(%@}_U!geUXW!tv2EWqaPciu1;E}->245Te z8pUCL{tV;)r3Qbw!Cz(Ke~rOkXYltJ{Cx)hfWbdx@Q)b$GY0>h!M|YeFB$wR2LGDD zziIIA82oz%|AE1OZ1DRQX@C6y#i2iZu)!Z<@N*5GHF)0OMT1uiev!d1RUG=mO@kW- z-!}M3gSQQC8QeDb#NY=8pBem_27k7}pKI{v8~lX^f3d;eYw-6Q{DTJnu)#lS@aqkJ zqrq=7_$Lj1i^0Ec@NXIXy9WQh!GCD*pBVhiPfPpjvkZPGgWuWUcQg1s4Su%4s|K$d zd`oc{FE2Ovj={Soe$(Km48CvhCmUQCJT!P>@Rh-@Hu$v$e~H0gX7E=U{M813t-;@I z@V_Vx4gL=X|3`y=*5IEv_!kZSWrKg!;6GIy+V{^5{!4@3X7JxC4*ctVT511% ze}g~B;O8g~@Bc94|2*S=)8K}|w+(($ame4c!7YQ^2A>%GKyk?LnZciF!hg2$|6Jq$ z`38TX!C!3fHyZq}4E`2_zfE!2U-?eOA^)#8{%=&wT}k=(CgcB;#{VtG|JRNGZyEpJ zHTd^U_&+rMf1=oDr}oT4>0hBd@2oiF_uY*Ddnyj`pKbi>1}_-AWbg|OezCzXGkDG5 z4TCog-ZFT{;Gw}2#i9IH#{bm@zt-R{G5E_2{z`+t+TgD>_;m)q!QdZP9P;}U#{bO* zzg2MjP#~S=`20w1_%M4yq9P+KJ?vB6(&@HZ$9{o!94{I5;;Z!!Mg zX8gb1;O{W_I}QFWgI{Ox>ka-fgWq8A8x;qB{U+o8pA?7k{*>{5v%zmM_@@nitK!hV z{>=FQg~9*L;J-BZuMGZcgWqQG-x&Pg4gOn$|A*p`-}mXH^7X~TRGzss_}btrgI{Iv zs||jQ!JlsMYYqMkgC_=mror#0~27j5sUvBVM82pt6f0e=i%;2v!_-hRQ=LUbR!Cz59jT92llu0vKX9gGoW`GF; zVPYLScI?=(W7}odve>bs>ngSt``FpFu~ydlKj)s`8D^d##JcL<`Q+uxx#!mN?z`{a z`|f@3MVI`NOMclUzv7Z#b;)s;{F+OC-6g-_lHYX6Z@J{RUGh6FxyL2{(;~v%q4H{l6P>)SuS};m%Nip&UVSeUGfN*Jklla?2<>h zos@k#OJ44h4|U0hyW}HX@}FJu%`W+` zF8Owse3wh^aLM<(e412cX zU@;g58^IQ^9qa;oKxb2lF9Y;|g`gjdf=ys6*a3EfyDc}I-8^Xpa(1j{a_Sq0$afjup8_J)3!kQ!936lR)8_E z8EgYP!8q6lrf-SzgZW@F7zP``7O)-c0<}I`S_@bUSPNJS{Jt#EbgSGa+QB%O_E&ND zfW=@8Yz4c(J}|Rg!WDvHuo>(Cd%*PD#D5;>2OGgQup4x47ysFy7mR`}U?mk(8Fx$l+7{*89#s2>q2CeiBV76) zoBxWtB>jyL@20N!JD}ej?pwL^>CmUceZ(kF%JubQ^Jl|b3;a)80QaZuaDV#Lb$|Mw zwv8>kwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvNwScvN zwScw2@5%yc_saT(-&LV(VXOtL1*`>r2NvkNP1@%NHy&-)g-!c<`1e{L=Dl6Qe{;)8 zCft)v-*0_c#a|@+Kd^4*XYqQCOE&N0@)^gwSOn{TSC9atx``_@2(%~yYxRiXA&~=X35{%N6Pgz zYJm7>;QS4g-uyxI2M(Z*BK_ho#~8af&(x*ZN7Gw8KzP+h2GJirh+g9vh=Y}Xpm2k^ zyU+g(f0p&(VvNB;ue$z=D|TFAl(Adn{O`2?SfgLPO4hk+{p*H)!g|tf9zIL_seaXS zuwtKGIR9Ui9AnZy{^r#BpN;e@o|b&Q?rOg>(SDwe^P9D=)T2cH+N6A^Zkuc3f56o~ z=c9c*4dHuS@i#-?41MnLE53i6Fi8D6V-Wp{t>ZYw$p1!H%K3YF#&M<`=06G)zg5at z{;0HX7rE@$^jFbmBK_+gNxi=Epnu{q34f(4d=KXu- zW2zr0ytZEhg;)K5yZknNYXNHkYXNHkYXNHkYXNHkYXNJ4U(N!4j6Wjl%e?BnJIefw zjxT<>oY<6phy~Jbl<{N3|LtT>S^X|@9(8`Y0{Rc}{9@>VBaA=QcR;^A!cSi;^UJEw z!2I&(2!BDPJO@yHE1r*>^N`HDotZD=R~=s#;`z%5n7^4cCsiLiNAiE^kvS$`Z$%}2 zTmODYZLnc}X$uTie=}~9`u*a`GB5wpr>X6082b01AG;uRezp_(C!k-eEOq{;1J4g1 zub27VS6%bdgW016*XKtF*Z$S_dp4*d)0>{#5rD_w(7u zvwqt6f2{4Icz&(V2mZMKI8*dhE`Nu#U%TS@!k#6m&!3B-_dq`$)cb!M^b_Ge8PwPTzhPM{57O)nu7O)nu7Wj2qpsRjMC!Mm^0y@h?4nxjY_f^b(FT%UMdmAKP zxBFmn(?1-Ozrp-jy|sX~fVIH?ngtqf+3A0}eax7Xol^d`I=Rop!1yU5ci*vz@#nvH zh+$mylf~T&d9eE9AK?C`;qo7n_`|14x*qt?{EN7&zyDcwuPNv28So$A3!ob2C6}!3 z$~g3|gKvUwgFWECKqpPoT@73dTmxJe)cD=}Kj=3c#GgBym8}JS%NAIBeYtMd1Jl8c zKrP!QxGpllEx~Pm;_GE7()|OtCb$FA84lLqx{rX%z~$h@U<-H!cr|z}cmwz+@Gsyk zU^{pRcsF=2_yG7Y_$c@o_&C@FJ_V{>e<^MSJ7$78U@kZw%mXKZyMda|Js{`1+*Lmq zry$(49~gc*!WDvhfiuC`pckAEE(8~W`+~3FeC!YTK+p#Uz)~;>E(R;XC14dem>sO% zTEJSsTEJSsT3}TyP=ou*Qt)!{3h+wsD)4IX8n6|-7Q7C;9=rj(5&R?gC$J6tGk7m} zA9z3b0QeyI5cn|I2|fZo3jPgz4E#IzIQRtE1wI8n1O5Yi4tySb5p4T|^mG3L-VELf zwu85WcY=3=9pHW78{nJZTj1N^J75p^Pw-#hyWpyv``?0}_fVeq!4JR>!Cvs+;K$&n z;OF3fz%RkC!EeDKt7DuGt`4pVt_7|Gt_S`fxB<8kxG}g1xGA_9m;r7MZUJryZUt@) zZUb%$W`f&+!@%vqao{fC1TYVr2u=cb1$P5?2loK?1oOek;1qBwI1O9~E&}%h4*(AW z{a^{W39hRQung|yU)wwulD-!yk#i z=q9P|8gI`%qK{o5Y(GZ)#h%HM{HRATBW;9nZ=RVNU+-5EUcGm3DRTEt;;-YVRR8JE ziQKb(s=J0y-*l%HrmuQs*WoJ;ull?vS6mL&e_uvt%6aQNa^>kZKc1Ry`W7qquleXc zG}WK~*i>2l{o0xRf}H=}yM)bKh~0`eU$yi4YcF5sZc>ieL}AAs!u)KxKKcqo&Rk#0 zot7c;K;>$FC{^E6lqxqDitL}9>h6xOVp!^Rn7+2;NBy;&DD|n&Bk>eJBK5TOQDOY= zqHo+_#r3Z1$yE0|N8-;`_ZL(3olmFAnh!Ud9ut4v>!+5_E%!bm{+e@B{b_ui8>YH< zJRs%D*jn-#yC?O!)NrfH%rzvQ%=;uBW%p*Oc6P^CxbDjB5WiQ>TXCBB>lr8I=vYnU z%;#2~@75Dilf26RG~)`5j1Z$&q-o(^KPDIq$Spi??x%l(%q$mD_Eg zd{}pDf!~t_@`t9j+nEoi%39WrMJv9(+WrpzPY63cm-~)}^FJo;u?JQhullpJ7O)mr zbql0zwc_h>)noX1e0I-Dy+3zg-1hUN)*ox*%+z%IHTExS0c!zk0c!zk0c!zkfm924 zw?w~Ti(gm&q4&WR=ci&5anGJ3>;h9uWhH9?YXNJ4U!Mi^xtu&oKI=`*+ z$2!le&kJ-uUgy_!9$e>{S9L!4*JmMDj__P#pm}(;n=90RP4xU*=KtE?6sChJ``;4x zwzq|8Su!u^{b#EGH0X=p5%)gmHN5II9`&be?U8UAuZGwBXn422btlPB%Wz@g2x0!t z!r1=8=77w1pf}AFJ4dNt_MZ#o-6)49uYZXl*r8|3&Wk_{$D$BKU2ba z#Zs;|oagvxk@G-zvfZ9kJEWf?ayyuDQmWn^elR)xZxY^f|Bs7juyj^cul1?5T=J8d zC-ru~@Ti||ea56g!np(d+T`okGV3nls4q>6ejVrM*JdW0pP$D99T`JY*8Rla`(fX` zjcYvb|FG}_l`bP7-}}uRD;&t5b^nc8;Fh&h>)*ptfBawzmFQG6R`Ac@?cn|3W8e$m+h8yFHMrIq z65mGPrr_q_R^Yba4xk6z4J-ur0R!O4;Mw5C;ML%tz*|AJ!)=gn2k!vy1n&aX|J{)9 z1s??e1^yfS9Q+zwZA~eE8n_O)KDYt6F}NF82rdBqUWzqJ~$Pe4i(F8woSO>ix69dHA1GjMBgTW~v2)87H|PT+8GBsdCG|6?HMfVto<-~@0Y zxGT6jxF4W0`&gBO4;;LYIe;GN*zU!95NHw5k#I0hUK?gq{W z_W}0<4+Q;SDOdqkgLU8`U<^D5Yz8j`F99zDZw7A%JHUs)$H1q+Zt!LB4X_9N5L|sd z-1otC!1cimz++IajskT7 z*bd$eJ^(%nc7gu@UjknTd%zFCPrxaP0nP#!fct@d zupA75wO~CM1rG&}0FMGs1WyOg0WSnwz?;BZz;^Hs@NV!)a4z@~cnjLoJHUIv2fFB+z}iO?hK9r$AZ(rB5)=+2b>Eo0QUz2 z;9{@}jDRPACxNGeP2gGJ72plvE#TeY!{F0k9Q+sf8Mqqy_5TNs1}A~j!3CfXTntu$ z5pX$pBzQb{I@k1C9lA z!ExYtZ~~YIP6Q``yMnucvq3Mo4|o805LgNZ!Np)DxCA^5JQ_S1JPkYpJR3X@ya2oy zYyqzTuLiFL+rXQ^TflbkUhom{G4KiSDezhFpWuh!C*Xg;Z@|^iFJ2p57hE4q2R8&W zz-_=C!6I-DI2T+5?hE?BAXpAof=j?^a4C2kcrth@csh6ncpi8$coq0p@GkIv@DcC{ z@SorZ;3wc0;8)-`po4zI5O65C8n`;R4!8lh5x6&#&jDm-Nhk-|cG4MFB7WHi``n7eCBVawa3~T_S;BxQ~ za4C2=cmmRC1Wy7_1y2Xh0M7!?0j~vb0NcQu!P~&QzD38j=Kt3Kk5nKo1*8|hRjlfO8EO19~Comfv0qzWr0!M=$Fc;hf91l(aCxW|z zyMtcb7x#ob8Jr3hfHS}%aBpxHI0u{y&IcEQi@<%s{lNo49~b~j!63L8tOS>URbUOc z6pVoNU;}svcsO_$cn{bC-UmJaJ_vS#kAjbZPk>K?PlL~b&w6=1D{tt?%yv#eg%w!uY+%bZ-Z|j+&>||3%(Eb zf**q$W1PJSxEZ)PxFxtXxGlIHxILH!?gS18M}nikF<=gu3+@6=0Q0~};BMd^U_Lkn zoCfNB>HBi}j|~5P)3g4q1*`?E1*`?E1*`?E1*`?E1*`>re-2QLOM1Fr!83f=|Y4?Y4u0X_@92)+is1HKP_41Njz{?4Q= zk+p!efVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_N zfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVF_NfVIG?S>P1BU*$}& z8N38M9XtoT5WGy-8P7KFA#8qiN5k-IB6qwl)bD>(ydkoFhhwnsc{n}df1vMqwERo- zh3^Vit+4&Rvi~UWv(|iRe)PK{n!cu^`PT1;xW6}|`DlJm@{|9*um^1VK;-y`!hz!H z_?Khs*!8XCuLpFTO^tg7SO|7KB>q|-7G{7R=$jyS?vp9!2kclVawFnz2M78NidwF9 zq2#}J#BdXzejlZ0XOZ&`5WV{E94GD>I@wGf4cIf!K$oUV8?0;Xv zwH_?)g;l~H=$o$2GVvGhD)BZ~i@tAnksE78ZqA21O&Bc{R?HOUPZq`>k#swYL~frY z%!7MuI@}MHc>S}XpDOHZ5ciI~MNV5y;u|#oUhzLzIa=q6zrpO;^>;~kFuS(Qm-v2c z`F^Z@^Y4}K0w`PWz;zGmb);wYD7598F3^tx5?v1M7 zP~>*V8m}@8eHZj;+0u^nK+c2gTr2TpfU#}Gp9gXw*pB%8kfUG|m~pbilRjL+x5B*x z>_PZ$$j(OMzZbF};qwtb?K;sHLykh93HK(*d5~M+uL5!*;%|oRhun&AUGU$g@j)Ml z+zPn|{yHG{L7#p->^1`S0y_|YHuU*mA@pI$X&X!UM#!0vqwv=P_ja)RWbxkxxfTAL z8^k>i;d|jPbEM=e53B$);J*U?J&>EB_d||?X{Sj1O^{o`4zL?+*7PB_LDu?cX)Rza zU@c%R@cXhr@$Q?M{!Z69((ma5GtU*d5DbIOU*J2iUZ? z*a_xuA@0q+65g{V!b6T80sC(y?&({D{}%t}LebWERhMe&+@-tJ|1i2mb%n|oER}9W8yH?D?hdY#w&UTiK^TU+Cn|CW*p-Fp0YtN_-ieX&DRgJK={9OU1_@Cmp`nO|GS~uaDQsUeaOLm$qzPx9bhl~W#WG1 z)%z6Kg!@nj;dz^u%2)AukK(B zYyw-rHq|412jng=4)%iH7bQOq+QD?NN%IFejPiRR=Yw9*560jxtTNaHYCob0{@Rd! zi^}lV2DuAz9P9<14xDE&6ZC-jV2j!ja);&*atv%z|6pA61G!7xK}Y+wV6VF0i+q8Z zO8E0Y&Ii4qAN0UqJ{X333~U0u(6>PLLvDlI0mfn9F37!*<0^w;gm=(h#vrFd&IFs_ z?tz>SdO<%J24kS}JNPJ(b^e?-&$NGeWZeUGjO zam()KM7edY+ zFY~N^$h}*O9EIEp|9xQQ$C6GV7zT^Cm2e%9d%*Nh#J?YG1pDB>4RSY_y=*&E{%$Zf zE7Qo04dUJu750G5%SHBYvaRvga)`*ShYH&cgZ^+~`Vqp6BZZw{G$wNPQNnJp@o15o zjuG~N&Buydc$_eQeaUAFWbg6fp0=U5JD-XjvOzDHF+uE>4_1IpVEA&;_kb-3*9k^X z7JV<|7RZfXi+gyHu#5@21@?hW zuZer}X+qEEl5Q~=Q@$>G|LMXuu%b-lSWwsn|9xOfg}BEnh2AD%TahrcPtuF-C2|W` z2=|V#xOXoVHp9Ig&u2Oyd+@xa80>+2`hO&TKNy}R@w7qi2Awa&Up5#8TfmA7C0wWK z=ZM@3Ipa$S-wXGOZ$+OE_wX2zyDk$p!95f8r5$n{O#4dW%kUx|uo&)5kkd~Refkx` zM#ycDTj9S8>;ntGmiWD>PhrT-UH01gs+hJ;}=PL;Eu(AndmDn7j|B<;&Qmd{nq5Bi+)}^|JLkb^J^_& zEnqEREnqEREnqG1V=WLL>X>m<;V5Co6rnrbOt|-6A^P6W;1AC~y0?XVr7&He?|>R# z9N|@7RaUGf@p=ZxUpCyMdyBug=4VwC_>K7UZvs32M)GU3X)RzaU@c%RU@c%RU@h=# zw?Hxand!SrKP!y>q&wf?O;_Fz^CKR2xSvYyLH{;yfc|h4`O82#9IOlZsnY+o#MAXV z?dShm>}&I3EnqEREnqG1`?f$D)}8#mOZnd~UFP|jDeHc+FG!VJu|6SscIxx|wj)#h zX-V47S+Tq7qgSq6-*b6tIvP&tIaJmkRGcaP2FgcapJgHNv{WNK1}4o!-b6(3VWMzy)G2_w{lJ@ zkl*-mlJB15h0P}jyN^vRPse$w@^7V_eOTw~&ad8Q-R^F=@XFNtX#8riL(etB_R zy2D%9THx1YfnuyX&^+}{c2fGsF|0FayCT)y>k6mg`*u$Cr|!z$LFNlvw_17lJfxcs z4wR4fy(FFve0Aog5`T;ooR0ff2z~x` zqEE{dwigMbn7@vJam}CWJTz^9_%{-U;opn%7(;&OwYDZ7=>yDHyYn}goc|NWqvakf zy)Klm73FcugN3(xYk}Xh1u}-99r%R`*;pv)^=LZ-IgIuxyt(K*(cY(PJM|0Y@5d&i z`HkXzbn)Y*JWZbpTb>hYI$pH9D*skku}*3^G~arkRe2z~?*oOnFZAhsJ`?dP2a3qL zTMPUOED%ROL$lK9lJk#|`W!}oO#OKV=nq$*-=+TC%pRoO_7Bp}>ZJ&|f7t`JWUTml zj_UR3&H&_!{1t~A!25TciwDVP3+$6NfIVW!cL(xWfqq^)yh2^kIaS*ZY}Vewm@uv_W0*2R4YZy z?Nc7ww>GpZ&B#Zqwnuv1{>s{&!R*q5{I+f(%KWy{J$1`>j3Aa zk21*Tcd%cptK98+|Iv9EtOx8_#ddzM^sHVi(07@<$3ox7)4Dj(8eVW&M7j6G?T~ z_`WaOPC+~^G*IVX?+79Nzbe;t!n6IuTEJQ$2PXKrnKeKV4gvv@U(220@UceL zY;#mMi2DKXo(FndtUPC)!^fE8z2@jRN^S#HmEtiR0wcn}Y~kWyb+ERw)QRSeA2oiQ z<3uVC3D%T5PEC#Im(~l@>!tarEH4X^+6jgtLDp23R~v_#>QW<a-6L>F#Q6ND#Mc6U|)K2sI6g_y5-?uCHZ4={_CqNYbZF!XG%=D3WP$-owDWCfhsC* zAQGuuOdh71)E&p?D+`9|0?y)UDR7{)Cc@W|0=oh96DH^~U#?6{-2A9k29KKH#Le2k^K$G^(zn(^a&Y)Sc*1(zjBj*)}|Xl@l*vOOPtx$r%fqZFyEOz%{RYb0bPe>6n)rXdFo86vgrll-{-3)71jGl zFchQczI+v6`(GZO$vb?IKhU#{7p2Rm}_Ck~8nUy8A zf!gJcxroT6gkC4kzY2jf9qmXZm6?Bh-SdTBQZEh-xSqlxbGbST(4G~UtJrat*T{8V z#*GI3=ycYH=+EY-q+43c5t2LSnSW_#NdA<@aV7uxeC46Q;s}+unwm1liN8=WlnmHDE?%4$8goF3V+Dp*y*f0`fPr}&SKPvyL5IjD})6)b-Ee>xBK)g;$c`+`x5 zaB;9MSdBKZ-xt;2dU2;(ZuC`4B6Yzks_+B+s+N?kR6jtlgmXzG7^p3+p!_Wfa@AfM zG0jOrUsfrZgC5G-A0Y76@>4cAe;a(^p_yGFd&B`rN zGnc}__$P-dx*7AeSyfV3(?Is6^T%)+O6zL)H2HiDr4<3HFX5^{9hKAlBRiXdFQ)oX zNBIrcMd-$ii{Z9I|9 zmYg$(@SzT5SM#UOx71MM@pqg(gb%8{5xR_>l2AcjD2$v81K@t1lNE2krun2Pc5i6BzBA z2sy_@Nb#8ni6%m#iI8X_B$^0`CPJc#fYL|!u?RmF;pC1@dK0ej0~xlLoV%fue3({= zI%H^068AB+pPN!@>Zf>e#(Bohbfi>{BUb6}zo?w(_lOxBmB-~uev{(M^-xK3Cgx3G z3yk%6Ca}z83neknLnSA9qK6VEj)Q)@`a`(!!kk^$vPt0)Z;nZi$}uoaI;5BM@;p=q z&95gq!Q82G<@7tsoUu|umDyi8`Se8jf2M>}JILAmu3r6fpPzq7#>tV>Nklq`NNNY= z&jY)96l7J=_lL~f38O&_)h#%ZJnI)xp|y*>c^U_50)=2 zr}ldj;kfYhOQc^gYT_=_raL(Wqs9}Q+&r;NZk}9k3A&{b{wBGPV!SQ zDmQo9%tX9uU!`2lN$H~gj^AaMT>djBH^(!9JSXyHa`|1E>emF%`2KX<{`ERh_X!?x zQTeB)rl-{MChDQ99O_T=F>Lo~!`REP9D{+&uk~-NSYE@U+Bw5K5?*EHF0k`BBrLU< z9(y2PN_AI%uOBVG#sAY=?{&1SPl^U zYI;h(Kk)fgz1}aFa=(#!rv8;bRem*|NLVsTQ$OZcj(HH(S4PEs)F>g3Mfn%56YBr& z;XidgbqKCr47FbQd~?nCn+CTg2mVeOXP7}Y`K0kP51$j`=k2o=IDC{#H<8E5`xVTa z<6u}!{aG1F7GXdeSuPn3AioX4kSQ5;8_j%|j%Na!l@H}3C6gpjf4i24raUezrHQlt z@nb_IxYTiCdsPhOWAdcM=6G%2ilKaToFs=Cf6=(2938Wej>~BDN5iqikNV-JTVAzf z<-;8_e&K-vewcpZetbR6ps2HqBS-WJ~Wxgt8aEjijxN%VhkE@(c})O76+=P#9co2!rC)Zs(p z3)Ir21O0GWILi?~*}IPCvAT|taPi}W8jfmHIj0a^E)$Niwp6`d-|F8Tz69wE7S0`y z#^)xYbMl`_&Bs9g)W7z}^nN_%T$&G0I@CS)oVgAk!*7v8-Iennoa^whR>3@TxbNTE zA5j0wvkK-qe5kzS(|HabDqnHu{th3QzH%0$ozimA^=#UKDztOzKNQRvUsqG%=)AsC z%Uy|j%;QdWQ#-5P=PT@=Pt?u>DSeBIW-st9pz&#S9XE&?PRH9Cep$e0+9hIXO?bIO z!DcVu@V?SAnyPUE@Mh+LosZ^=-koN_Y>Ft@{EICsn?N~m-^A;J#;ZrcSgs36EObM@t}_X z%s7qw!Cl68I`6LIF^$)=P!cwor9aj5dY!BPep&9XD%bL)3jIuDMpS!gze&?kCfW@e zAF-Qzoa7#lX}gn)3~D^Ppkc~oBXB(Cf671HRj=d1gg=bSG@Xes_(T|7#{o1>GN(x6 zRcbj^*7K#|)O}E*V1xQYx!nHLE@L&{@Td0wPChZ;klat=Aj5XAH9fpxrKN^CuF!Fa zrmOL)tjr!R2`B7;akR}PzM%#5cst!Fwu)p|saT+PpI z|Ac>0|LA;`ElW+O3jHI^r>3X*h}4SzF#MI`IZhB9wTC=-49pjQS?I6r2!`OkC+;!7utd8W-1-TJkH%SY&~qw!!U#`<_{k@mLtWgmyPxTn-TpP6NR4@1 ztzv@OFHncJ{bkux?1_RQd{l-)!Nv4kuRKs`dJG|Y{>*;;drlj|hlca{X6v7Z8n2I^ zXH!VJt4Au#45E0WVa4JcPr1XzXJ>kxP)%MEaU6udu)M$tVBFLApgcd*_y;0Aml;1U zO5>+9-y4#A==0!sfSwD};STRV{mmhKsJn)3+4RmKd}uh8%jYGsZ2r)B>cN;AistFV z^~Q%KI+i8j|NhX zvpxO@*F;Rm-sdZrIi37zxio!xT5A5Jr=^CfS8D%%Rhc|D&wpz?Zu)#)lOA!_0{ZK_ z`UQpa<}9M}&0bJQdc)Z>6aLIYPjXL-N&mgwMeV=(d?lt<8PdhC;}ds!`f#W!BI7L8 zhihxaL8nr#pN!pCr$JlmpqNDj*|Lx_)ZWglp74 ziawuNDPh)5=@^hn^NG|tQhWcP*BoXZh6XyrpY@u9!kMWd9iI(Ep6vT&ZmhsL90 zSq*pcvvVCjRHpoy1u`mYIF+xhpXczQ^3%u7bNEnMIsB@54j=vbk{L7ApLokWhmW(K z#qk!Emkv$u`cLONeB87;&1ci$&iA{U%yanA_`ajxh4gf&Ug`Fy?!Kb=wA9QoV{0BW z7Zyo%nmI?P*Q3^3m1&)V@j&fQg#YSyUoxKCakqb!l{8*Q_y$m}W*xUz)YX*G(A^>O z5IzwHNFqZ|Y5~qh*zg`8<};x*hJwsGZ&EyJeZDj8Ocg0iG+?{AqYOOLU)_ zU$kEV&3E_~n7>3`KqvZV{_%Pho?oG5hvtvk`f4N3UO00mC++i1FPd3E>#NNF{h6Wj zU{(m2^%TY*t*a4nCjT8npV!^q)&ZHD-Y;+0&#<_la^|fu;3H zYB$AO9yVFkc`hoKk$L$G|3Up+?=2yiHeSIT8&vAm3<37 zBaL~sQA=NNl8?qwG>)M|$5T5ahG792hwD6(&PR~R%uoF*bqq8T`cX=Zv#|Wr8HIJt z8cyc{l?diUWSTjVuL$P3%BarrFN6w8r_%iB)S6!op7*-fRpfYNeT$YynRs5M;Xz#o zpz|@gI?rQfrD)zmpD(+@X}L5%Zm#M)mCPUZKTp@@^Saa0P(7U- znw+iV>ybtoX0#d%8PN&La$~01n(W9n2BPkBHVa`Q4ier`lJQM1CY zn$}$LPv@y?YK_{V_1or;ZH$)dcS#^ZEj{%+s%V;)SY6LE*nxV}Eq6+4cy%YW|GXHC z8KN98YpTuiMrs#m#T~T|=nR(C)blcLDv!Bs&^qw2Sr|tbUx0H|jtni9Za=TLLVEw6?Bqw)j49&#&)RA)K zP&-x5EsxHJN9v?SE~RCU*Uly!{NHPyzTbUw^V_fRmv$vNfKnUOF(fHe0} zatYVhn)6;=lew%W9C0G00kdG8*2$Mw(bNL3XXkKCZkP-yoFShta_1Ap>)nk%EOl11uYVvJBqg=>xt73|Y@I$44a5(4+@-W$j3BB<^vWbW4A!$h;4Vx7b zhUCMLd=O1jz%=m?O+3-C#1oYr7^JV_YuQl3SLKk$@_<(=SQ+&%W&XiT zk5RgqCKGbJG;PNAG34}E7I#xWNH+C@$vG#Qo)VLD&V;)u2+1ru$d-`fbD{JFeD#D z(+^{EewbVUqA3Tq?Kn)MC$fT?Df-`#omn>VpcykV{F!*_P@jb5j*#|SP)DB|7(

LYz@z*qUi%`waT5Ki@M1O2abSD4)LoYjXwR02c66Mi zaUi~m9}6k?HM;vnKkRsSJIXIKOYbK@xk{T{i2x8ooHs`^LC-n{Q1iSsWBEA;H7;Y)kj&Us-mih&uOI|7dN} z8xI2eDEiT9B0t?aP~{EdSLH3M;+GKl^_PCJeVuiobX#oi}1T6~8VCKWxvg68)<5%S!a~@6UB$e-rUk_0oE}b3d~9 zo#UQg%kENdez6_ZuM^`qOZ2OXqvU|%>Y&j2OMqV*2gOTk@@tpapcdb6 zSBrL3KMSwLo6hZLDC*@wcfV8@hiq`ExfZr3`G>%h+U zrk`%SY_zv}R_Ukfw^`yB+q0yo3)R`OTk8IO7+v6pT`%HE^KtRO=-f1>IGwF{7m56+ zE``>8rzXFW1D)fr_}wDvO!+0CJ-bP?qxqn5WX^FO52#(+MCa!mTl|)J^Na0t>z*F> zDZlzUXZ@%h`c>h@0Z+v*rD^9oNRMAu5(n~ToubaP4qCtudq}jSbztFLA=W*$qxz*< zoa@EHd%@i=#lv>0e4w2wAI)R+bdG?X3J?9N_;qRe?LJST-;<(#G{4A){mon6y3Tj@ ztD6tY?`tAIRlQ(4mCl)Zo;Q_UaGYL#(XT3RXot_c34hP=sV?o{SH-Va!VmqhXGQ&J ze(V3t{j+C8JC)9f3%%u66-Nqq=&nboboL#rm){WBQNNact?u&@%kD){KdN&F_+ee5 zol57Hi=B10{J!a}Ut&8|KF|)g!L|8(n$~G#eE;^3)FEkG1tI{P3@v3xb zA^c={L%*v2+kUBD98EVVu9v+d>P+*Irwh3*9(jsiZ>-1b{%?tRs=WCkV%}u;DFiOl zi_ z>K{B>S4rS2)#YQ+Z(h7e@NUtL#*1d`Yj-=!58F{)s9n=Ut~-r`+94ipWyg<_Nn-zy zjT=#7hvROZU($c^`Y*NXSir{(dwYIy8^J?e z5RcvGu?~oS7%$Z?*ek|?`dNPOFV3&*J|mhB-}Iq^{_GofzZSpmH0_3Z`@DGkzoIVq z`B2O6kM4e{&NNTZ%&o7zp>gw$KMf8h0Q@@ zw-@S%#^GOw*RxlCc%P~z*DuB8SK5Cq2mA%j5AZo8ZRx{Yzqcj0jK^1cw|Kmi&6`pR zJE|Ye8}<*R9lgihZyp{tgl*;=@p(QyUh&9rTJ||AbW6X_N5&6%pnaYl@!JdEgOFzj zju8iW$n28q?~?0}T}SeMkY`8y%I0-6Z@P9kuBrU$-k+`OS9;$tiMPM)q|YTLes$x; zevWx&!@SL#qMM2LZQ{I1m5<;N&f_U#BA#?SCGq-JIv;=Q*LMEAl@;&Tn(KsP-E~2{ zNIUNj_@18UQC-68I`gA;h)367dhmSuBX8qxgwlb#8(7?0auI`!kBV-%0eV${X^fy3lw_8=d2&c8I6SM>F85 z{3a!S(GOcsjF;-%1MS(mqMfcTsyGrKEAla+L|A8`eyuomD~z8?Kg3tr#Wvynm-aVo z&o&VGQJtf+Vcb|>w3Eg=)ZLEORcwW`&eRV1s^aYhzBFEn*R9fJV=)e@OS}nm*+{gb zx=_ERE1l!T_}EBqc-T&*i*Jr|KgagWC;FxF#-KghRJ2pY+og)P!W$m)RmCf_!~JXv z(JzfR@>j_3=As>q*TSoDx1)7{?Fx;9;`IPuTKDLORg3&+yy0UZ-b&Gq#!LMozG^&e z1$fiv;j>hZR?}3Hksp<;jQq_TPzM>Asiu|Z9F=)@~L_3u($uAV+eZ4n4-FS8FN*5?} zIYi_~b!mq7>|oK3>VkaOcz3(L?;)Qyd-lS{+0zy`Hq4nnW5K*R^Jh0qn>lk~-aNKLfhW_2_Fwed(jl%F(|VEN zVf*m8e7(2_)<*;Pig-Qei}B0wC=Zz(;-kIH4*!lkWp=o}+j|_0x6q)I#6fjI-1G%v zeAJHmO|QeR?|0m=L+-qVwr45#^HucgBf3(*XcxZF8$WEx3^9SnR21cdW{86Mu(99=5*bM}XOyfQppe(1Ls{8BvMQ1O1B?jX5ux8hsN9j{Pb!Y7KnrFB5&O|tq!zSxg?PT=^I zUpL&3PR~EEJv(Dy;*Fl97jMfJVt@0hixtON0~1HDW*oHcb@SE^_%v@;T<}8H-`Y;r z)45Q7^#q@_c+{EHv-EqlAWmARcz;PJd|#GqOZ7|d#g88pkLoJ>J_5^b#rnc=l+Np@ z-=-BjAFB1C=t?nfrRSFle%Qqr#h)O<}rHWUE7r08Xu5!4y>wdKVrk``ZkD{cE*S)I# z(g{(Q%m`;Z>bH5h#18U7>%~gbk>29%1%5P+mNu>{yUD#@T7EBex1;$j35drd*?83f zJSacQ?*rcac1!RmKg5@gYYpCXj-BD$FH5fmoiBHf1NpE{(T=Xe$>N~(LhVY=!M|+K(EMf%a^MXs4^6s{WD^etB^~LTElPPi%T&{3ssv+XMVmafHuv z&WFWsp10#=E8x+*QGQJlJIn8}qAoPQ!Sgw9Hb=Ch`L*zF@z#$LhdTEU3vZUYUm7pA zQ{_$9E^vW!-l*UBKb+^;)UF=zXx@+yTO`Iy^O1t~Y=LMe&Bu#kJ}92=Ldb8IXh-pA z9LTr7bZ!A2s(#b~c2fP07j>cWvWp>8FYp@s&E$UjK+)tJgo80FUxR9oUJY&NROnXwOa%?Pz`rjkn`4=kZDx&x+%` zf#H|FL@yt`U`KVPadb=aX2o%e7zfQqycPP}$)X+2hlTfqW`BEIw4;7$9LdA=@|NCB zJnxPT8Je44WigJoM87l+>KEfu^`n+c_43vMcB;J5^^(k1d*dIbp*Tu5?P~@koQ*4LNNoa%qLivT3>OE%+ z@lTT!e zY}0t7BRM}+9LSgIjQiOo?sZ_C7Szt@O(w4Sj&yVB!vdT%{lBJF&fL_c^P zo9axDGqUT+!RvV4TX?$-bzFa@c+%%gj1ub)pO=xx4;{i*b{~qiU((-n?~_TB_}Tg1 z^43h^#p7k6@%oZtJ_^2X=|cB7EctI0?Nt4vhsF!fNr)luTSPqCKMK{Q^oHVek@>~@ z+`56k%uYHUT*cqN*h$ApGM-`_dHjf-^mqhuV1MfcJt$r(sh8g@#6j~*@n}Bqcx1_XkC+dd-`Fjn z>)oQAZr;+|g`hwS(pxmB+YlEhA02f$AmM}c+F4f^KkLhxkuS8}srJiSlM z8_lmJ|KCKr|J(U3Y1hkJkl0D{M)cF|m!1CU8sJlyyf+`HW5#ybLM#Gb%8v; zRwCW|QT#SBKH2=Ljo9_K&H=!0yPelBd(@jQ7_PEk9wg4klSBFZ9^13Od-L0JBF_gM zcM&hPcVVADQpM4IJI|ZyxXF&cPZ-hRgoXnxfj~Amqk03&hfjsU#vITx_le4>+R;xd!_NFh@EUarFp|~ zh~iN@>HXsnfU53&_vqDq2<)VF|CXpT%|{EgXK#phs(fG`RB?1`#=$zA>ncxYP5mN( zr>f^>iC>J5y)WuQ_3MK6tXs6}Fa3~*Dvr!5=XFeM&#v{xFMO}Jd{BOt-|M~k?YdC> z9I5Pl0r6@5;ePgaZ{JTGy-%;dwSyh)Z-v%rucqI?{m%KY;=R$E&e)FXN8@O{zbDcxv!_Hms$bu8ab`3f8*iA` zIB!P$gogPGrq7>g{BP_7!g+C!`I>57p2mwhux0N2sNdk)&bm-L#HW6#UHV~XJZ#UN z7x_`01D(7*drq{YI#a)hui{sFtn)mZ;>Cf7bliBMfA}Hq*8h4t5A{8w(D@aSAJw@9 z+OwBLyZ+L-TgC4+cfY6$n9CuwEo_9_e=3mPgVbDeN3Utd!k>eO9tArcSSp@i;Q2}3H*Cbkgv>66^H*gy?!2j zToLaF?r|VbcJjc~Y2XP3zmG(IG#|S9#la8zw}_{kH@r^Lv<06x>iVU2ZIXDYo$pD7 zE*}>bhpMjH7xKDN*>y|!(KxVvRCuLNDdN4rTm6+Buh&1iw{|`cK;Ginav z*_j`?c3_vSv=r{?0T~ARK0$QcvKgvbNllg5AE^$I`BQ)b+Bt4P`uQ3-r`l| zH+h;~yj_}h-P=3!v*NwgTOH7KQM|53bwPYpyrDClK;^)BJx zOV)d}^SW~S0cZVayxl>~`-_j_co<*o3unLhcUc_x_qOTc`kL(eG|gLJrL*78=lJ-7 z_+I&8JNAS7eJxbK#B$NE?0P_&*m+$~q<(t|Ua{8=njhx*RgFWa6V9(X;Cc<^7n5A) z?0FByu~*h}9k0+2+g9^_(RJO|SuMQv-H$UEhcCKp=HvXy@l>Vo=hhIr|D zD7BOM#r^D4aXwDZQ~WQ2t}8@4I={+4pN=~(u%Y7}-RoI54r$Pv`6G0l-t~ zBIAeq*#_?8AJrwL>9-B+Xg(;O?-i~ywX^uG67xp;8^yzRDqT8Me!p|~%U*^0_*S%| z{oH)sq4^s=hks9X>TuC4sL>moBiA=Hq)YUYZa8 zYoJSyXh(HH-i*1|pJlg^yB*aJ+o|I11isREH*xoieps&vQzBd_ zD{AN8+u5%5J?PJnsM1ONdlfKm*|4|!1*qT9)1?27caInSCPumYMLRaZ9WSr0$oU(7 zj|AfRN4xu_c)|BY{esJ!&j)*nT{qaF-}*7${8F81-dMz47xc>}x!cirqn|jhD_eM* zxsL}F58Kgk7x$Mg@uo}a1HJK}bh+Mq9C@gYzg_2w>)x{U2;aXH_wplCX{|9j|)yo|7Lw&6{70i|UN~*|zSw(7I~x;`x=vv7I+O-jDD$hrP#9LX#{FOl;5lQ(|4`n3Z;S_hOL`-ff}Y0Y@)cS zyci#Q$=!~|QJ>*)V0-jS?ffr0*E6+499pNipS|FXpYLP6x{84vtrr=;`m@FRuPlC# zc{?7_yy5j<3vY2U&J_6{VhIS>~E+Gt%KxHO@5@Va2&Gu z1-*^C&7V8xjq*!D94h^KNF7M~IS^L$x5(FgKBUTTILqTu*`ZEKJEAk@4coJSd8>m` z`uVp#ock~B=d$sX+7)}eOnf2Mfv#U1pDkT>(7PW5?GyJa=DQENf3AquX}D4BZ%k8X zT|11I`pteR>L3{(Ig z{?etbOw6xrT#L-%`Bue&d{z3jf1{^g8tkZF^uwO_rc3BqKK@~QS-iBr;c=hVOZ;1+ z-)GM2&(UMKeyZbO3h<=yzUUq=#>JvyKce#{Uk~tpLBykWG+xA4<=1ySKYvlh8@+<_ zpz%__@wwu02Cs7>ANJC~#6jx-KSyf$eMR(3`=w(kv$izo7m~bTmQaop*r#mmv9Vd0`ioxgkRrR7<&$|5n$Jto}EPoMP+xd9ebC}+EK{ zi?@f^$&MdQH}msB)IpZFa6&wvk@<}tE%KA$p+7v%M1U_H4?2Gn@ud18ptW`GMsNQ&Z3R84&TYqtx)gg{2>c=9$>#S|KbbCZf+w@n z#Y^=wo^Q1nuP#4X|A-ZcCz}^{6o@CQgVg#wUe$SbDRW-WvAXF#9>-m1NY@1{yv@Ab zKb{1BsyKR7aU3AVLC?==e@o1FUWW@0g7t^}M7;i5FX;q)RlFInqw6J>&Z7o~Uvw?K z^{WKfN%_@@{AfPX(4LJE?WoRHyzs(j+hPCyJeprLqjgH{S{isiqH$2W^lAKfhPXI? zp?3IpmEY9bdOFkbR5o5^0guLkeAvOF&NLsfb)fFYiFPy}g~rQb^E)ahZOU4Q8k1$(%5JC{gHqjL47b9EbMoDABIJbWQ=j zO6RO34mutr?{r>&w(2=HFmbf3uQwiafSt5nW{Ui1KG+6O_tQnY{>n!L@KyO}20LjS zvj&D=k0w9=hKjoXtH_V)+yw1elW3>Xx%3S2c%)iaQOysMs_}WQH-6X;RDS7vL-u`! z(T()#z8&nO^%583p!w*9_H4drr^<(Jyzv>%$3Z&2=;F0)tfxx~?4-IZ7UQM5_%?y@ zV3BC2(j`30`MeS1V@tf@VLMe_bpT&FzF>QHyy%z4%Ql60mx^|(c+(Tbei@K_A2{+* z#nB8rXdJX&l3*vzZ?m^JXup)52Xr0@I$=PX_i1%5cYZEJ?^&XLGQX4`{Tv!Q)O}q5 z>9U{2>+CeYmR)jv;rTn%j^@K^XT9KYQM)Ah+>>k^Pj4pbEL(5tC3d>&iL!Of)bYIk zVi+>NO;?F|!{_kPcxm2r*DKqAfC2G<)q?tWNz~iTu3g4Y}Y}mtVR~>>s$! zia2cJ!3B*k*7Xz;KO5mKZ^5laUA*Rv<|9GyWcg?(cE#pnBTG=m?Db;p-ljO6O9)>! z(p_iEFTB{qw!_Yk>X+TdIUly>xtCtoC;QqvACE$Q(XT9TEyND<)`!nuY4aoZ56O;4 z-NdhqU+K1D9R1Btcie3wc|?6=y5Qg08Q$tjhDYnlzn!Ry*M4sCgBJnY4!3%4C4Oaj z>m+uVHyQ_>M_|2JbRP9MUnBLGcR!}bc##K=&po6b*_rP7rSbaUd1KEha+d7XMZNx9;x33+46}IhgtCtkP^I8Wqj@B4C{=)s#HafYNy8K$FI6udM z`bB)KgEZ)#XGiJ}?>ofy>~Z&cw(Q_V*tWw>XEgI25D?}cDt>rB9JUX<>+yL7BwpEh zPxGI|dX`=9j+5sm%k1ij9e%D7<6u*~^-DSq^?u=e-(h$sF%I-gb&kyt>lEX#_)Yc3 zFPad~-=yDrNb(Wya=tIJmpm^Q@AI(u9qo-D)i3pev)@EO)X(>lvmNqKj*~l!c%3pl zqD#|@&VIXQih0BPHjxjTR-7)fb&xg^M|Y6(v;5BR<~ItTXTtVA_ONPj`}A|pc`Myjtb^v|&UVT;7P#}X;yBLTj>bX#VjWm`H}(%6 z_1i;q@vU?o*JS)CUU-P8bBW~hOc+<>9Le)7Zg!6s+p}BT?I^#NGZZSH<8yE`@Q?$WfoThs0yO}h?FyQeknp3$^h=59ypnbu3*`0|`Po|TW~ns(1? z+I4B#y`X9LlBV6uns%?a+fkjH{wmH7@O~~!zt`OHEW5O(-5Z*AZ|T_uo^_w!Tm0T} z$D_JrRJy$94X@)Gaa@y*e`FlW8~;A=<`?5vUC*QaO*T%}597xV)jT#1cIaP**9La< zd>`Af6UBJ*u7`qQ^IzTTz_%A1_f8P;bg!4G^h+I~xbNnqf$_`WdD5zUl&YRPeTvAB z>f8+N*~y}vO25>)eEy>1hxw*D<9_zW`ocPZ%5RURF5wZpE@=JH@c?;He$=iN@Ko`3 zO8lZ9mJoHO`6w9)^?aIWr_u%SX&kse{Goe4qVaY~p4W$X>~wd2Xczj}o8KPrtI|0T zbj~mOW#@|gsLnLr()rHE%Q*O9XN!1+=7ajp0=_C>rnB#NaRQJ z!OEfTFA(keOXmpStKw(|JJq;R@{8X28`dN3m$VLgH2HNd5bG4@&lJyJ;ao4&E(~_a z6F+B&?_;03_uuffF#oyKTiz0&pDG_sfUmL(RyxOvaj+}B@xykiytRX06~DBK-_;^N z+CKtS&_Avc?fR>K!~vhifjX3a?p_D9uG#>P_9Mh&XShGth2mj5RX#%1Tqha_#Y_FF z*MDPxCynEJF&{K<-O!$0E86u}-s+Fz`O5;cl48N`#y?pe5os{2wB0s8g zI0XIU2GLGeXO(`s_16hJRCujmN8_b+nvvKcA9lZcyq4Xxf$4AUwR-tYgB^|6;`h4V zeUZHn?&5mBVB!5B-j7M^CB8S*%LAJFZQnooS^ReNhL?fkpj5vH_2Ov1+1ogdd{yHv z+NtWkV;{YGVf%7B8ZYf1-GE2!kPmxU)P>eTGx%W-iFS0{u<&Mk%Nw>+>DL21RQmb% z)6*rg$oaT{eCls>uLHDWo$k8Od|*3OyiJlguzkl3?)<3V4B)BsOYaZ;9vsQ$&rz_W zbw&Ns^)-5*rQd5DBgOSZyl#cMB$D2A!FDQL;s@x}Rd_M4E2<0nVe<;>A1Z!{>qK3s z&c5UM{r$*;_Fvt+QM;C~STFQGnZ(lK{30Ipn~~^D?RtqWc>e~qqjie+o2l$%{F0-b zby49-uj^Kb`E6Rkum55`JFoLt_hh|2_Gxj~lUqlN@yf=H^b+y>T&5q*2i}i_@v`^b z=RyH&K4)pOf{BpO?%e&nS-{sVltiklLj*`O!L%#j9%(Cf%JNJ7hWB#r zA58>LW|vq;yx&4r_a%3U{WmM|8(87(e%8{{#rtzq^%5H49B;H<)K6BY*}KI!bn7$- z_rpSuwKi&Mw@Nm3V&ByDBUzskUKa2b#+c@_lT7NQrS>jh$XW8+W`jy$m zNF1_wb@4g~UeR$JEb1)NkMhI&F=_op2%c`dGCWzw6m`D(q++z3Yqf;`lH8x##FN@`t-$iihoF zx?~l2*gmn^-7nht*$}PkDIJ=2^@H5;yvEzSmPb5teva#07%w}*{rfA>&bPKlzf+vY z-Mn}SKUy#C9{q+kbiY3_ypDSu7;m?xUCFw7cughlc2t)rd0qh?KagK~J$F2`Yg^yl zj{3!Rvi_F3S@U}1(Ry_i_@^FT@CH4*)|>R~T5ff>^QsFw%iDFKrme*OQR3t0=cqqB z#~shITi5-03YJ}qCf@m)b{D$aQT;+w#dvWZM(yHPi|fTWf1!3Ug4g}E^ZG`Mrd_wD zosZb*u16$a7O#tRD(arb8#zKxzh+`5(n2r;Bxk*AXc{|E;2(tp3``bFxY#>+Nl4i+Hl{pNX9#+R6N8E)(tWe3iyQb(VeJ zncB&o8`abz`jzpEknphCpJvl#OkBZ|Ey`Q1}XlVb4Xy^5MXtCcPl|mjc zAj`gIs(V|0-bjzXs{F>!a~}Uf@crF*9Kd-*7k*Fpt`{=bU(l^qAe)DF(0 z0{A`G%LgVOo#0p1&of{r?dM$s!%tV|#IZzY$@zXev6J-=>KE7LX}|0xc(Q&Tm@D#= zjT^dt*>~dkmdtMi>{R(p0Y92w8ZT>h9-ouQ=jHyX1MH{GZ+ILJprI<>j(I#EG+y+( zX8XTWfk8&tRmN{%GJoD9Zu$N}tZNeAkK3{lWue-din7Yus*0+b@`|#W>Z)LQS$TCu zsH!4Z5v;8--Zc)ZtgR>?Zz@_gqPD!Mw!F5sva%v%*jJfmRaLb$HMN!HRiVn-@|ueB z#^Du}2bGnF4EvEw7A+h(Xa0=2OJ+8XYz|d7R96n4J7@lq=HavFFBv&~&f-NQ7d6gp zoUwRBlL@b5-#CBfoN4pHJ~$$%_$jL!UR_pMabS)<8*}9$j{1CJ?msPGpN599S!BZK$ssbzt4ZhH-~P#@8KEH(~Oq$>R>4pu_+8X-3qG zr!8Kx$cRBhAJcx;+-b8-bB6itiSj(+R+it|5w)tHIzygHkjKKuy1}gs-<|)W6G(a$ z@tQTUXz`NixlncMVeXvia~423Fy`AVcmDbN+PUV^|JF19V#b7eHaBoRaVv|razt%q zu)3G%s2!;%EgMY<{it6&RpwWRV%F4=vwG~yt z>T=^>O--oG=!s=DRpr&e#^GlF&EcQ<=7wxwr_U8KyjbF=tyl79% zt+$r_2Yel7C+jcHFU)yVF5VuG`KspEkG1hv@^w0G{Ws$A>f&b>@0qKIjUh~?eg^zZ)MSGl=;1>BHZ``6i^2RONqb|5bd&I>p+9MC#qCMi`7VVJ-ZdLZk1Gi|8 zJaCKn$OE@%k34XT_K1sHv`1Xrn)@TCm8@lM&GEhdn?L3H1KRh(d)%t*>u=(p6Tz*@ z9&vH2viJYN`Qg?$p4L=V)*45_pmDG*57kr!Yif<7Z$)*Lao{z6Dve{Yar_M(#QSLV zh{~EOqe)qr(IyluH(ms5%gxDaZIuB~Q*9i=tIXqLb#-pWS~emWsw_9=yfx*Op{lB& zVObdr))+_NP%s#(Hs-x$HD!&%%W88+Q*%CCR%;w~%MCb#NvN#6%3(U%IJ^ev7{_a4 z>QGi|%(lxyq4LU_%4&mCd8jg2Ra;R}ZICRh4H@$XV>(`z^H4sbyxbsB9W-XvRmNf7 zIPe<;YmE81X&x%8HfAG+eOWc14tSV9@cBu_h{|AjsJx=G+MMy1heB1gp)zxtQ5G_0 zAO_WH!>=*l2pv>WZYruj|KWs8{)R9HcF5S22g@o##z{r6yrR6un4cKaq@WRik*{Eg z^U;sDqP*GQqhAl4zjl5(9j4FU5Xc}@X6RW~UK^^ct~7!(=3v1ZqdJVzG|H{QsFK>U z>aq$Wzg3{8 z$?ZMlD>r}kP|vyidg#Bo3>^ED&p59vS*z{1opR$WZezVZV;t_AZ-?RU$*p!}TNt5a zE9d6s-?;tU*l(VncHgu^4hOg4hjtgn^VI3wPbRm25Hsg(<~Z*^1NJu#WqTO=%yHM; z|J|&ie2L6>ZhNWmK6L$IIls8wYIb#QKGQRpuVdl%=Q+lHgHO-*eExu2_w&Kr`TpV) z;*E>uoY3=Wu5JCgJzi)dvnT=i9BD^7_Q>>8x&0nUVLdYdAh``EpJ) z+A!hJhC@eBI&^&9A9D z_zgcgf|o(K3?si8?%9hVZTV+W2Wdg5&nWmhYAS-*Ys#_aEcV$2jWde(*l>b%9UoS^Pfw z=-cAw+^GHf#J-2v?{8F-Sxdq1_YvXhwd|*#u()y2@zdhDCK~t+V;g2Hm_KXIY&9SA`pAr#jk7#m?=Tw8n>J(N z0*(1|?)r<}T%nI?FUZ3Z$9?NK-^dvI&H0J{8d#r!t=HohTgAs811k4p&b916_}*Hd z-;1xuqCG!(>1%=S(cT=p+}68r-3qrJ&X@Ta_JFzJr4v$C1qHh8DTRdl8<3fy1OPBcKriBK}oUFsAEu7J$ zKCbnx^Nck8^|@2z!LH}9VSPtYEuL7PIJ3=_4%TM^>Qi@%?c&f*cWbRL)Q>u>u3^&D zLk=_U5ivHS4;|kyvCdptFm4^0IAy}*afcXxo)U>1I&rc|6#E0-2RxSahYalx=kWfp zHyfOrpSS7;RoL$Sa_#tf%J3Nr=FMAREvsm>Gv|%-7Y{dntyWrfW=xVA8W%2{ zJ7*Ezv}A~*;g8p+F)U4++t(v**JgkoW&fi()OQDBV%|Gz0uDRhfCG>=~2<9Z<8XMkH= z55)CB+~R(`zX7-Xh4a92e*X#U;P)BgHugd_+tRqc?C;_CspB?b>^JYB?q0~R`{Q=) zubuDfxH-2!|2~je-|TO!qYh%NxA5!lxIOnl=leHqdWheTfqLO~^uwlo{<`bfTb%E^ zm~kt=j{@7{cCCM!_W3wUe^LN%EOW2IeV#Yq^zq=S)^EUy%%Z;u1OMmikt}P4)>j&4baf|ha^@m&B zkM)P!8x|g&yZ^_$E@0m86gZGyugDntw=mx0eJ8lxd68jn=xpMd_OT$p-ytuqql=3R z^NL&KkMZCZ_hUS`rF>@pyD&aYzPjA~8|leBPTbzQnX%vKUwA(aZj+nW4H|0G$A4@* zcfZ)#2TaM~bpD0o;C6a=%AoxX9P^lD>e;*_UnkBO`<-yY!G=Lw8g{7v1B?0nHZzU= z_WQV^kHL6Q)-cHI?`R(f`^?4j)~d1X?;6GZvPSA;K|^x$%;Zu&&%|xY*l!+pS{CvBxE*qsGfu|XZ_Zb- zJ#N|I&Nz(+?UCby$5Gsl9=iv#A5Y`Pg;VqXpp>!SJf7lxuDA`o%jeIfJM;TLaT|MI zGJiJqn{na18MkZyCYe9y_B+gv8AZ}5bi&RDOw-F01KzmYGjZ`?j(?swpmcYNQku;Y6k&b)rYIi;U)F6t+o zy9&d>@mY3U(%s)*<4<0`UMVcDJe+Hn_RIO#?0+BMKR90(hO^!$&i9A!x`N*yj{OR^ z&zbv;{)P98W?3@e$4rN=0=#$@6G4yft%nxZufFSfjui1=c9AMu9a7{O?o%&r6zn`RAv6|K;0u*oJ@M?|atapW|v7 z%(vaJKl3yHJF16x@yoeg@(R99U&*)ObKpMX%lS49?_=lk_uZFqJH%VFU8BGn1=c9A zMu9a7tWjW%0&5glqre&k)+n$>fi()OQJ{DQ%;BIT!Zu#bymmqGeNL=sG`K7l|AG6Mt^OW(Mx?UswJKbzr*{$G6_bcbbiFVB6wwvk!B= z=Dj`(Pub-H&HLX_@;g>PTv&7YmPhF3og44 z_01HiLm=G8_ms*z+7UNgWIqnubU4$7%Z3-HZ}@h8U*RT(4!ivPg7MHoUcZ?l`$YtF z*v7zp`lBN&5jR$(4sE;h{$}0_xqI-2mk~EpJb&M_j)Rck6z{O+r1H`X0Q`Ka5Yk@JysM>&&pmOJP<{%oi;oUJvGT>S{iz z`BwO&@y18K_m}=1>w)&SZsUN7b+(Oz4lVHgZxj#To45gdW7~GE&F5#k8v8!|biX(| z&-O=+m&iBIw2I^IZv0_o^uGO3-{jGH{aA(@4)FHoyzlIDKQxXP;!g?v9$)d#kY(dJ zM`S!p87C~Luiru6SSue#37qv-#<$hS$20T%;=T*I+E9l~k#!a^KEP=5HS6s11);n; z>%#9#wit>pkT2CCVC!$&I_MC%q%a-Ycj7vj^VFAzF1W_hp~!mZ3HKf6KVP)pJ7Sc^ z_f~x=ey=3`yG(~tn+}s4bVwDbLu_>4@%W1s``lsapg&J_9Cun_+*#KMaJTa341L9) z68e40;-97cB52cLvV#s;^8LXC*21OxTR{i29!|O8&NS)}7_nBauBknJFUwoTHcn1) z;G4X(u=))HFXQ8?Y()8~Ly>QIJ8iy>d26%fZJ0yelB)`<-;gbDhdJnwzPK=X3UA0f% z@wk3m<=MHBUe3{`_v44lV!b!#!{7o!>+qQu;br9PBSLkMa67 z=VzS`^$;ZAFKusYzLxP#+`w^-(@xfO+#h+zw`hSnL~Qj?z1HD<^`JkVIo3mmtsa&; z)I+SNuzt}BI+*9V<6C0pFf9CZK2cab1V;7Eqr#y*-W5QNH>LP}*z^zZUY57GF(WhQ zsV3h^4t$#mba>(c;c8f)k7%IH$HrE?ap1O18XQw-=wX64|d?o9xse< z{Pw=%<~4Ws{1y48imZpG`}jJG`5jpYJo5T<3s-;L-f?_L+3MjehkD2!r<|8Kl>_Ur z={wFr-$;S_Wo|Y&sn6phH~UFC6pM zWgFLDbQsr57ZsMbw2kjy9Qd|BQdqz6y~X>*Muz&m4?Xe)O+s{^!qyREFix7+$u_}CwoL9D&)!=7=KWZ|fkbiRS^U7h z`Q&zQl;4Rug#V(A>sV)Ls5A5Y;^y*4^Ug0i7Z+A%EjGRZ8{e2d-@KfeI})~j{N0Ju zDyUJ(lEU~l+m6Sfz0Rq|yruN(%u(NNTR&bs{jskp-`)cG2KL~2H|zJhpWbPwxbb}p z>u;%Bct1Ah)v2j3=II+8Q`k6}hI%m9VcrYvv^~~uQokM?_08DyeRb53Z>SF0rG?c) z>}1}L&Fh8jR~&qI9&Um9W_0>%jnmcX`cV{WFOyWhHUgO)^GSR z?eQTW)7aB(>ldfl_@;`?Th^Ah_fMGe6Ls!Cp|HI9>v%g;-y=`B)i}E!l!MOb^QBaB z??blpmQ@>X{UtTZsQEh9Zx85T&e!*R`PzFZZu^Oa=}@v8Z)f(mV{U)aye}wVykvoi z#nnUbJzi(#xmN9_`8vc;DvWP4rWL1et4)WwHXUO6I^=lJ|01^f-O!hxx6)Gz(;)?X%{u$_pyj(^ zoh9`7I_8bl^5c-%FUGx^pSP|8`9`2$nB#iIVSA0jyajgAo=-aREdjpk8MvuePRtw6 zGN%@%um7XII(zox5@UQA6fj({l)k>EdEQUtAkN3k+rFDkdJSYl@44nf+qw{>K}%2L+6mEUC}eQQuOVzAqhj?#(8q{U>{0VSKwl2lM{l zFD~BkXgj9)I&p1bxCt01O&yj^xX98WRiq9<+xYPCkvDHj`F1@}7~dr1ZEFK?kDU%W z66-9Z&zDl+?sl-XR#u2TNm`L zPi}qG=4SeYpV)?lofoEO^_>^)u=T590n~UC*{Cqw{wF)3zJZ_g$A819oukRb6#@Nd1H-rd(I%? zp&kO1jPX9aU*9}x$g(kco5WP-&L<=I>h~bxcB~NedD_6pn!>$ERt_%1g|4= z-7{1Ef^j-KC}6x~sUmSZZ1dl#vw}5{!!=S|F8;4tmHIUYA#XY=|s zuj@tr`0XuI1N%?>h{DF54Cr9$yQ<6R)ND||c*$Z=f97kqA6Y$g?8NhCo)`Yq`oRMh zuD%YAg&De#*O_^o-{HESH)45L_T1QFHu7!!+j3l!?{7A~2@ibpQH|&A1Fos>(#t-u z^i36s>)XArUz}{i%@m0nIGoq1IZu6NtAmYl8x$~JvQ&}vkOCddap$%juiOhWktq_l zWILWWLs<6S+jo76d}9!Y$=&ToR=-i3zDvK#T6s$riJJhvW}W^0njek3HwFcamy8Y3 zKJU(%)Bk*%_w|eUZ$D$*CzdL5-LnJun)Q3KO^4V{#qrJ9ba?cd?H)%RGDYg!8R#2# zQZ`%`)gFJTw7K^I$dB1CE*kZXHLng7i5s@zZoS1NmDn$mMdGHQy~%e68*ZjpT-*Bk z-nZR14f%#2FHYYid`@TwgYW)_Z1FPU28x_VwLrfx>-WWBI~|3%u_F2Ucjk3wj%TZa zmzww62aK02Fts=x>UZG%*qs0VeD5ijBi}@kxPdYo-}=4ZH@Vt>LX-L5?fdMnW#eSX zhWnlaZmdAuCcrhv^@p!MYDYU4^L1oOVSE!d+$XQd$89bUxBmCO zPo@Bm?Ru(l_Q^95fc;b#`d*f|He23yxi7ySx(ejmVZ+_j0k@|>+%6mL4i32f!wRd1 zjIAEt>OL~B&ioG*cHf|{ysy8Fx+h=XrULnf;rM2bJ0l!$TMNW31-|CEv+l3EoK5Q} zQy^{_aLs-^j7{H&;zkcIEN_8L`252>z9k;5HE-Jxei8-ZMuD$+{*q^L+lWTVDxM+;oAsNn76PPX5-sZBF=Uix#GD%*J>9MNN6@;3btvjAxJVt+Hojx_{`bEr-*AC^vo_p^2jBJ%#ce7OmsM~bOnrYCf7448x3xgrxb1kc z(LVV)WD3M>vEe4x&DWuItHQ>IpiPG-4$0S{gRUDe!*rJ$G6$WH`;Pc9^XWPeB+<@>Fd9?J`cCO zK-_xJ!Mx9AhoAbMD-kGChgO>ooBeHU9^Z63N2 zPj?KNn1@>+-*(W!#GN|0E)O?wbYcCi+lIUO79;X-;|1dO*l;)8Xm}oOTY$4kWRTB)jT_q7>wAoO7srQG zk$f`&j+>jO?tA6Oh?^{O{h`&iuCd|as}>?|sz}@b+%IbKU2D5ne?is-TroBAu_vLlMa?Y8N=LHLnV5jRjIZUA&J=c(_{ThW2I z$s%=#rFgvC8@Rt7du+l(hgVO&NfY!7b6zs;$+yo!Ty|7(d?P#Z zamPGf9Q1m%HSUCqye~chxaN6Q{g%^TM82uP#a+kg0$g)^*dn&h69#U;c*(*=>RZ1D zKW>`1+uCqrMdBtPKW04~G3=UCP>0yF#pTTh&!61fz}@txRff!i0>(?0D3WgsbTH2^ zR_*d)7xGOOi+gC_{V=cfvI9-7UVdc#A`Uv3b$04jTNuL{w+s~d9M1NAc|DjqG_4K~ zMch=8Iz;c_{msnV$3I*-4sqFY#nnS(zdpX(T~-@J+}MAM!)>zV?d^WdTPNhr)c5*1 z@BW5-14WK!SzA3U-M7UW&k{wBXBp7fth3--7wwIFS&`2-YI~+{-Zwb=_TLaUQDi-Y z_viIs&L_(|Hl2&Ofg<_V!*ia@yfw`GTNUDli^PrDo*(u0TAx|tWTHsi*8O<>oA)tI z`D%wtkuN)@xPB3U_U1ZmTk_oDh#M{vw+D1E>+J1y?ua37tVrB$c;2gdod0h1jw!@V z6p5RJ_U1fw{>ZzILEKc4xEbS zX9?IQVH-H9oSDC2_@&Hbe3Q^GHZ>Y7J>ush488&5C5vhDmEp$W^I7Kju~D8Z-s?ovfff0D z+AQ!jasR!f4>w#SZUmmEYtDb~Zk^YPd=o|DX5e!u=K90Ab&(X}24)o3k7Ll@9DlES z{M#jnn0fUZ%0I&d#}Zm$Ar~6?y+;3hv7=&*vBXxYty~ z%@ldR27~+J%)I^M_k(Xo+(2V-c?&~(lkZE1maRnGSdq91Xm8fT$jrIFB5txs+~^*B zerEQI-3M)F-gjlZGVV_;61N3#&Ev)8FZ}i+;%17(jqSqunz*s-4ebVQz<9|LMc#)O zfa_Lfzu4*cuVctJT;%nvH0WTCXR9~A;(EkQ6p5Rx>N_8L5xK84c#I{&-j*6~Mn zyl8^Yii+qzs@{RA=cOJ0rqUXOg-~*1tBs*n%V{qMSN2A@Q7wu$RAL5pY zBClsP!*#OU@oh}vI>b#DiQ5jiX8neLd&oHZ_;s$r&^M|z!+=DjgzxhK3c$xFb zAAaB90p!byT(3?|L6-B470I{W zrmrvh?^47~Jy+cPp~H5a?A_gm_S@&ln&AAxtcS<`d2A*ps)zr$YWWSiY<&M+Am2bf zEK7XC$FmaSZ+8xT`OVw|7#-|nyJUP5w(B@oRxa%~edD%u#9w|L*Kg~;rOW!}XN&L4 z8pll@S!Q{0bruI)bN%dr*$cZq zJm1&|KfVIzJ0W8w*<6P)`^BD}@0`kR6kwHaWOWuZp2TY6n)Unp((8=V0d5(%w>TYI zU>;@8&*naIh;iMC1&m+q9~s{y@ZH!zI`}W&8u|j?SaEz?VcZ#P;GXmNo?mJc1w$F% zF8E#;vwq+BW~jNmA^gM_6!yHq%)vZw>l$dMp0{cg>JWQTTL&}c`9IYh*X$QJC-Y6> z;lhq@9md4LtTPk$*&(J3khdb&H3D#-jX5uA-RFScjg9b=E$}{@kPWxAHUIv;&@qLb zw=~1|lbQ8U(vP3Rj@bC_d|v+jeX#=hhW-z2*8%55@wS&D9H0`ahZL74CsG0yj=uCm z0R#BQfG9x)4-pL26BI&|qZ$O^EMOGDLqQ_-1cX?CLlA;e4it&fPEZI%IQlnlc9zV} z>}HZlzWM!fbCc{odGgHrzVpt^W}}4dOuCV{@ghK6FZY+h^>Ueld;@r#hx~U~&bivC zlF=jTV&=!`#PwX$zhuVF3@3;uQHHxv<_vL>t=EvzcF9CgDPoTb8 z1mDWH+x4J3%qDn0o4m)v`vHxo-vZjYQm{|VkG%xnyDqTT_jv^Q2C%*m&w73P{Q*?T zI>MZWnf^D2%Zyg)|c#P(oFUVJV zIJ_^icm9R15UxyPM{1k(n?lStzdGA4Ve?Jz3Y9O+T^3pT!@dYiVI)tSe(b{bdl$m` z{=A&9`KA}!1LTwK^TsgilfXSvG1J#c*h5ae+03|^D!8s;C;UxH;C_o|r#cUY{eb2# z_Cu>BYQHIQ?#E_g9V#N+VS5j?rM1iy)WK3cJZ=`W|2Sds*STE9h3j{&FPiZFopESy z)awNFM+~)HMbz_Q9p`cP<*MR+&$A3S8_AjXNi`Y1yiTw@6w_6F+ zHwW7T@a7_WC-%LVq6$6iu&36 zN(2RQbBJ;CySLc=pT?X)fz!cR=a%#YKs4&WERR)$+8 zfUe_@t(ft35PaW!HvbTfY8T|2jDM#Xbl9H2e#;>E&N1L?Jtn4a7LE@vZf;4SzHY)V z9Jg-nq4jkM>YGcfPj;!@6V1XC6Mu8Cok3om{P1We&6n3Uv$Jfh1I&+WPdd!3Pi711 z;KBU{e1lc?4B+vjUpM1xN4K(sxez>R9Zfn)pC^4IW@lEM_kjRwCbBwY9T&s(<2VWN z*OtKbR3FiAiw)M5{et}#D5vJt5Pu62xQ-Yk_>L%YFI1!kG;mS4kK4n=K1^E*8 zFe-uTh%(OC!N6W^n7@$LA>*JJ-vVO2`kn;NFVYEnsA7=+1_k+MV|^iixT~%830enU z+sqzZggq24{};H2uB7LQ>6=C1mNCE$2;ycFc~q$c>fj~#W;L`h^ZC4UTpeJjVTxB) z$Dxwwm3C8}h2dUTTE z#y7W97`OWoHs8rwFNT{&tb@D$>(M$G~z=^+`kfO>L^?s1SGF`Oy8Djx1^<3I0xnpV;TU{l&98XmAh2Z6tjqr)+A`0_$k)xr3qPL6LOlDtMo%W5+5ZsZ>m%}=7yIq*LUM`bf3x^t z$NIv2e$=@`KwDSRj*9VB2>V@`!0|%96<$X?zw`mLUQ#I36?f@an>Wn*%})45*-NZn zSOQ`?xCuL(Ui988h?#88j(x?f-yDQr*jBNAVG~{dCDwO(i_K#V$Dwq>&Qb=HVy;(q z39cii;dM_~P(Egty{M8|70sV9vj;DZXQk1pH}@4r-d9LQ|4M;<@r@TwqTdEKo5SP} znJ2{T%ue{*uDV}lBdQ_3z&V;?rh|`|Urao3qH8o*psQBrB4a9a|yq2)~NHM;Xx6eG}FQQyE+em!2A9LHve_y zi}B4S^7UWD?7>jq48o6J?#B9Yn&7&TpUC@0Cs5xUY-gbFH{^8T354r zBY$7m3^xzk1LP%*RwOPj2@r8IAZ8DS@hpqzx20cJW%|upN=%2Odf|PX#`hP>L~_Wn zbex&K88}YD0%Gn}c3sZT=WD2g2kQXqJH>L?{4DEkFAxRaVd9rB5JOWrkBhtzw- z_$o`(xKkSGaB9u)sVF{#y3H{^>i7^kp8n$?#y9JyvlxFX5RB{jgkSt#<}K#>Nty@U zMxV~m9 zi`FBxV=HF*dWpERu+i`$G-|FOUk~ALbrYzsjIaNN{kK0~D~_&e(wCqh-yo5%w@6@K zl1I#2x{39h{sZDx5a$oD-goHFsc4>6NJjrkQuO!9G4wZwKfEu}@6g;0Axz>=dTGAD z6(x?>{&gQ$?HBT$b0;UipgkXLZRT&O*pFeHZ`pLnPpFck#f0O`aIMwVI1Bks$=Nbo z)}<>sQRtvM0XOW5s>5BV-Mz&Vr;Uz@^qiR==U_hu?UTIMZ)=}SDWP6pnq=Yko6-B) z2z}cnP~T)6C*e8}`+y(T(C=*(I;GF$MuQ350SJ~#l0KhS{gL0c}L&MQQvRd z(BBknXW+*Jf2^{S*1;vHLpsrKPwg3&Fu$;2zL1x=#tu%U`DP39O{pICix+?CCgK+~ zl~CKVLd6BXm0I0=2vu_Eg(&}+`I`^>8~E|;7q?!Z;R*zGC_p1SuR4kfI^hhjPy;!5?^`7iKY-Tdr% zZQOK3KW-Z0W)c2&C~JJe{7pg`B-jJk*}ot5O_*OO=t2z*_hJHZy;ui`>&pD8=TIf1 zN7Mz`uVKl>xNv<*%dsW9qe?bB(Bw%o+yJrf-ywnDs|yf(z3baAP844^5zqSU+R;k0 zUj^U4%;e+WdD=_|55|Rj=V;9Z=z2u;NZ-%#%{MLe)qE2Ctxcz6g;6D=N7TiPZ*uK0 zZl?s|reMC1PaZu#Ghu$L5IXellmzLC9JL7OKrV)r+)Vq92H-L||Av(9B%Cx&Z#Th#&fv%b0qF3VIE^R0@{er<#f4M**P z@l98LvEx#6jZ}w2!1G!pf-B=a(^i7LbV4!eDEB41n`6IN3(v*$Ll+x z{Or=8gym;hSYN;mG)l^&`DBg|yU&w{=(m?o*P2e_dZWZGc)w1_547`rM8EaedK}G; zs4`NFui{Ys4dP_E-tQjN>_Luxf0H7jHvM?s5*p_dn6C$jIQji6523iOT8<-5zBzSO z9bh~z`0o<(x7doA{km|T3i;W>1kT^&)~dfkKKWwfm!3vC$mn16rJv~h*o?1&aUrh% z^HfErrmt^oe7H6O_p{%t-NALl$v2tsx89Wky+azr@W)ICUx8{5u&&`YScmZmj`JR@ z1H|9VT1B>L`g-Ej!H369SpWU|hiS_+Twk2HRy=M(-q)|{*4?O*(Ie_&rmvr{-)Fyd zpng-2l%4U}Spgm|Apb2=q0O|YiQ)rI`C@$`Kdb%t50_CT<5Qxl%y4Bi)3zW47>Bx^ zD+S}5j2=-JGh7GOF&QE4S<>jv{-!HVeS^5)z%PpTIElu$LNfYS^2CX2A;z}}g1hI17&_myAe(Z|#KL0^%zYrgq zR@#`b{K1Oj8SH26FImd1@l{5~7k2_UK9oebolbu{1XVE=GrtJpby~dG zuohazo;>>If|2oWc07(SQDQP`NZ`PuRb~UI|LcR1?*^w8DF`A$_sQjyQO$9 zjjtT#{MZcFLiokS1kPiv)m42V-?6m2GB%peP99^%H@HH@g>k-N#nqXplF9RU|C`}v zU>$&Oz2Dxy^ZP?SYt;L^hHtF|RKDOBJGac7p!J*QSbTQo#C{C+@a*(UC|anWED!@< zqw6)4e3dWEv$j+mJrh+i6*GOE*nVMt@yFT1+cdsPoc3!c*4JN7;QG4sRk+{Uznh$a zXv?t(VWxviQE|b}{`%nI5tX*QItbd)V z1FRD?Zad^ZO^3jh`24~}tiw3&`3C7wNJeiVx#HAUx?9~phK-9ZkM==PNMAgs#PVMk z5qGwD|F{!(JaO{PNmJK<%OIM&*P}(>1ldFIfQoBDfXxQ%AE41F$3){nQk98ePzs_r$@s<8o{Q~@WV(FBf zJRJIUGh9F67p^|`m72dPajs8#i1@pq)P=xq-E7xM)jx>P+~U&D1AjL+XJm@nAbLsxd8Wnh(W zU}$`}4(!LUuIx*oJt#H9@QJ%Nr(;*G>g}5{P z$-B|IhN`a;uf9aToss+Q)^O!G*Hc}0sh=0}$!#5bjMH$XtMTa&!0{IX!(bTfV=QL= zW@5{UP*U6{kn!rKQAd^9k$FaK8AUn^Mo0$msppZR-;E7 z4h-|M8LkEM1sNk;jvdZZlZdbO9ZvlaC_7ihSF810N+ua+@ih-Yti-yfhqXo}#z zv=8%z`Fz7KKSzJDV)5=Xpo|Rc4E&q{#8PF=ghH%@zyR;fBbUb3w0i)gx~G6=+(M_Di~3_-s?GX>4(3(4qT$@6BM`rf0S z4}LLW(cfrYF1BK(uZ-;h`mOoUiOV&)4_^$0DW6`y-@#-4srTLiZwiseXy4m?c)@Z(OXEKIPKStap5}X!5{um1>pj$ z7afxc|?5n>u(VDH}|Zm=K(*K zVybVaFmB&`=r{F9C0@RYiVO3h;SCe_{kKf4FZA2j?}x8baKyAM`$+W;Z zvcaoXw1NtGRAKZudh_<}5~v?zDP~+`+;1?yxbmp@{DS6^O5i5Hk~rLK+;1=*_rAIv zjhnF*GacN-x?IlrG6S^U^ToMdE#v$Q^6JkTRrokIwi*leESsXn0l=;0YMC%x7lAu$ z0^q8Od1CYndfwv3xG)bGY-QtbhTy!#Un!iYZp#kO-+XcM^I?C#$46_K^%7^{==7!S*GJgH)n%+bnIYPozdrI?o#J(Xc<`g z+_CpB`t?A2v2{5G-{&9Z7nWW_zN2vq_&U(1gxU@Qw_a}+S3WGJZvpmW(08DLzP6%b z`W6uOaJd%yyK-54zJ@wv7g0Ya*o0iJWDWYDTs~hzJChozb_VhH`Mq;a(YWrr#B}hT zR{a?4A%AD_tu$`FpbiCFi1h~p9g>QP@pTcuD|dIVuJ6!%bAwzvqfZI7J;d){Z2Dyl zS{2uqpdfC5h-ZBb;+b4rOa~=Z{hTlk4=MJ)T6(tVw}XD?>R@PR7HntWZ?72mTb3YS zANC92o0)mzdxr1hVmkPUxO1Z3Dkh#O{QGzt>JY^J2J4gaPyO#(nr~i`7+)vuH`qTe zu_Cyg#!am*hMRFy^*6wMwAqm(G_He>Yp6pqwgI`W_OvMb>L)h;x2KMXi$<^18NAQ(!zfCgew^Tvg9D?sn1HZ`n zl*`x99#RNx_ZnD_FEM?y3EXzK z+A+9RLENOGYW#)VFK6MSkJDl){lxhC2);$iHDLG#_~V74{o06e=<>6hnEUV89b$a5 z28ZX}n+o0~IBy^~M{#|tc2Ys>D;^G?WU?+6AVW2}=T`sPk2yR(_4$p@wHr(?m zeUNV|f4q?ClTbUUq3UliKmPpe_zMzR$B(6$#fNM>AAsM;<~R8H-9j+-wYzIS9^sW-&_sE_*#g3=Y9i!OG*{P^>p=*CWadzboj0`tAmHHgCXAn0(Zfj zYPs}5K|x$gb9H=!dEtxy-R?)@rV7qm&}}B~?CVW#cktixl0rjAY@3Zkxx2&h_t1&Y z(60{aOX_1{{bnWdl8pWz-E1qsSJqPrwUi^O4lo{%dF0GG>2rgFB0L2;$Of<5FfOc5 z?z{R?A1T}5pa@Ty=^Mxm=f8)Fcg&(8tYs>P`jviOYn$Q9__~U_(ShU2|FB5g!FI%Z zUkQA@J*-!+xq4zc!j;j#k`n#(_J(mMw`tgZ7a82g+fr7{&K$&jI5W>zfXiZZC6$kB z$k$2S$9vnpH)iWVQNzo}rB4a9E%;iP4td>GePJCj(7tjT!#9uc zB(gI@9sIc80JqZn=VsCn9znj=E~;NZoP4)q(pegp*EaKuG>i-SUbY2R@o?zZ&2-2k zbSQPE@VoSRN_nw`L z#fLzg@xg=r4dTv>nbXeGpEId~n7$cUUzi76@>V`ahyB04ZO1k8Lyzcnd0$LRy&}}mvGKk-eTJq+#iS&7yg86T94>kV6`tOnsG%CN1_!{aPz;UNIf*8?x0uvt! z1of3M-y#V2B}m$1EN1!!aNI$GL8`gDD}*0iNr`eEKwsyWg89NaSIOS3f;v#t@K+L? z7ZSh2^ht%oRcYL`rebj?kBIBi_?8>A{45aT^}jS9KarQ*Z}59bxq|vyvA!_Q-+k@q zbM*VB_ZHJPAKNeZMRMr(lJv-yW@7rfiQhHKJb2cwM@9D)ixQW%vsA1D_?xY2eHe~( zCHFfq9Rj%DLf7v+p2n=67(Hbvf~>%P}E4BDRy5Uxp#OT>wdS!BQ$Pc6c^W!ZxHtzym+Jh zTbpUz?3P>|=u<*%1=|_;#q-QboifHCMbT>Ee>qor|p zDEL9Yui5x!C;F|wLBHiZ&+RuuJ1f9CK>YPSl)RYcV^iYP;Z3XquF?08L%N9S;3MM0 zfOoFtpfCW}VAEfQw60QQK|8<6EYW)xlSqe|?D&u#3>)-@h9% z^TO1-#p0w)=&*5J4l~cnds$2e3)TVrt!jz)defgN|4lJ_$RqOVnI#%CI#^4K>5xL` z(B}ZFgY^|L9b`g>*Xpr4I6oHC!Ajt|`?I*I9x>c3yblTStny=DI_Q3LuMo3eFUEy^ z^y+`^X7Y#Z=LK>1s__?a>lol>^%KJlV7?U)Zr;>eRcIY@`-|aviTg**xo2m>)|EX( z9`%Gl9%U&nW)Il}?ysZfwV`$3wavyi8I3%!Hw5c2%b#w*tQ%Pd2^<8Tj1x`&XW##Y!6_)^9c<-}!t03qBfG;>?e^`X0vm;@W|0 zQGKPS)bRrH$-1_auuuNj+WK$6t>%NgH!;I?5c-xG@i8+GaC{*a z*Yk+Dv+3`JZFv0X*SY=nL=ujZYVE*n(SCChI+QceA@@r$9b5!%B?Dah3Nc&{#)a#c zMm8^am)0-kb+LR>!Q&=u6)vtVL)xP+PBA|Y5cg~AeK@_lX1`LD`(#{uI9)=u2V6UF zEou)wtS?-DHg3?B(RvZkZv_4%)^851FN_x@4zS}}eviog#?|48lGrcQ+JW1mI!IO2 z_yRikXR2hw(3u?v3h%hFc$3y8lt{gat>Ir)+pUm4>jA>2XP{e3#J zs9~EYmY-P(+_5`Z+|2)p@l`M`^xKpwYnXnMu8ZN?2z~2il^jm%;Co&S*FoU!8K2DJ zmKD2B*HvBh3s|rIW%pu~?_iIQ^Zvh1%opNs(TDpo-w#MBFUXg`JvnK69<6Vnf*7uw zzOSO0n{g~_Y! z%c2|SX&urDeJ}ND$mna2k}r*GPYcJh3-c#2I%G$QOY7jk`#3OeE)Cr`RP{_(l=A@1 zk7>Rh9Cu*c{A2a-7wPvch>|aj>m>BO(xcQY8aJ(5boRjD68l*mgZn|-qP(9YjhjL6 z9XP1?V4ANlO1|`YUaT+7Tb_LFA7p20Psnk`2N&UQb(;3NOuw(?sp#~j&r5zbybg2l z#>BE3UnNGqG_DoT13-rw_icJv!*#@nOZQtgO4PNuzUbz|LHd2Yf;#w!e!Jc1E3_$d`89J)8B_Z>U)#K@QCW9c5YhmT*Vf~3aw8{_X$(fyW( zb%1f``lv0B((juqsDq#AxB8ziMd4EA>x)qbns0#Uw;f%xnYbPlo={f)pkPPX^m_DtLdx6sIP{n)#)u%eIZ|;ROiLlAJATivNq%E zS*hYed?@*R%RPv%jQ*9B-(vF%y5EwCep|A2(QLpZi(9bYoLFDv9@5Dh_cqn^b;PM} zZcSAOm|wKN>Sy8($=&FGOhgY^Ypc3rFRlcujLMtx}=WNZ&$zcaUPIz_*4fUg66N~j%}7S11LE^{F}Q+vV_ zBVQU^!S@k>31O4QKOUoB&lJ3mfSrgtlS{Do=?(Jl(@RqcwPlO?yX|nnN}06AXf;A# zGM^K)2do3c$*C(EGPu^YVz_=H?hO4=8mIM}FUGi||CH#S)db(UYqotyzwQ&ff0Wch z9S=Z<>E-KuPvZvp*CW!WgxY!dK2Lz#`L8_;U-wI5`eqXM%RJGAyzXgf=l+E8; zv6T)KH8Nin!&T0x<0jZch1;{y{8(QCL&b0d#Qow+COentQPG~!|HN=T*dBmy&YrUC zXxwbU`!NLw+@UusGq_Ht7+V`ooU>_2r=9|;=YSFO4aW{H8rNaoUEbinU!Ew(V>(Yw zA?7W)SJRi$e62mATYsQ&EqERP^Q`AGC*;t$_9$`b^V0BoD#Z1XuQx!$RUsMuD+OZA ze`&rl<_r6q-j{|v1DIrSMah@OO~v}cJge%#b*QB;*-_%^&q6I?y!h21uBS$M|2~>; z9tvbI7XqR$>}G}`DXnL8_Q3G%q0U=i9y|5XPv6nA)1Utjx**>~~^;@Sw@0ne;wa8v#l9bfu$ zW)b%V99?lZdtF78_XVVNu;Kk7Scge!y_Mmc5hY(5*MW6_xPIX51?GF$o+xo?9h?O2 zkCisPq{VeP#`wVCV*7=8%^$ZDcl}u|(QmEqWBV=V3$eV!h4~gne4o0WIKG(}7vf~g ziPf3;8?77NHk%g)@pu8aW8V`I*_xPo*Z43{J@T3{v0?ZfU?;mBi&Wr$I z_>vi}hu~YfT8V`5&BnOEcUif_@pTY+RE5qAzCl;KTifD(UIk%bEQw-aBZx zbo})bcGj-t;W0Fh>zU}rAsW|5=zGYz0o++v>`~(CPC^Yo5!Z`VyIo!Dx4;{*<$W}6 z9@YW+ZSj^{BKjKUeVI7#gMRD$&1MEy5u9%ZFkhGleBw#m@44HEdExbWZf3nNiGP24 zTG~)Mfcp(ZT6lgBl3BG#PxO9lsIMFA3p$i|>-1Ur%`=*djhj+?)t=x@FWuZ7<{PJ- z$tZJz`4G&z3%$qcn_r7NpEuMYi_oF8fewKdVmdgmJ;3_!q#f*ivE604*Y_Fn^$>nB z;SB2+zU5+korL`^{$?R#zXj#Q_+}IOe*MW6#?HL0#rOta4co&q1HL(p#O%RK@Lg}f z*Ro2CuMOWfA6wX?pRe)FtSTwFst%fa!X2m&lrlARZ(WOH$8DxtPzh#Jpeycjk1 zIJk$dD9gCGhJ1a*crjw(7AB9%5yZ_Ua7P*7%3q4{^%L=T)}s%e(}@6$A!7FH!}b9A z!;~(&nE0D7$TyGRJJ*13j^KWw6UQ^Khp`6sU|S)kZ-D5xHw^mCwUUbqy}%S3VZUkZ z{$}jg=jGxW+HXF=x8r~x8T++W;o>q};R!!s4~?_#ew;oiZ7mnqkZ+K%2gNloNaMPy zadGKWLTwk3|E3!8-N3~)O5>O2ehK5w6b_FD?c=wHbZ<$Xr9 zbqzR&EEZz^7C0Q9zxkq{Z<26#{?EqyPLTip()P2<+B{Z@b6%K-amypzU2~Sat>MZs z;?nCdHbRGL?Xy3+^Fi=G!6?_)Y1|-Qe}HwwSCm0ZY25T)(XAWN=P5`4m>QoG4>n%e(*(f&;j)Qs@~}@ znb$c_nDI@0P~{8P%l-S|59o3Q^~gY+{^r1T2J@B&3(dZXaAowb$DjP zn6VUj(-Vc^q2PxL)$s7)$6u(1hw`oZn1X6}I5w+~OjN_evqgRQPz?`FU)nE{iGF*n zN#Qy)*CfGp&lHRceo^z+)*ZBdQ^v%%?rF#V2Kz(hZ?fYM&7W>-I?&Hs3BEs-e{3xM zI%e@$FD~}m_kgB@BTgOCiMZ48hVxyTpI@-w{DfbeJJTJevoRGj9ej8{7WPf+ z?fC82m_X6NX1IQgTM8X>`oQOm{qo+&3^zdN(ECUEZ5|H&x*4vG@VB!ct)57qC)>rw zp&-HcM4KMWdI|kLblZ$?8onPi#P*--jon3`7Zm(Gs-)HGx~7Z(8;+SVTEq1%8n$xM zc&%k#oAFI@spAD0ZtAA{TGI%5Yq{&G^eLfsI_@`ANjo0A=elN*p7HU;GbdpWkF_na zO2hTViJOFfpP>xmd+fvenY`NYLlRG#>FdLB3$A-@^Xme{S1roN@%5Y3LDdoB!;p{a z*fiW|Ycsy-*d9QDq{+)h(Rl9lV)o#~@fYmj(B8!DXJui&u9y?~$^mWCnFZ$#Vdm)eNV5!`O=F4lF`9%uxyNJUFyN}Q~ z!LP)0aQvd`0M`{)9PmGeZ}N9y_G=raj*ATu?#4GecGvhSmE(&$-uqR)ut?L~;C|-X z`38$hR~IapTu-dfz%+ zJ8&&}A2<*C<~7(a#P!!lO+e$OB%?>v#Z2D}V%)qk#nL2dKzyJXt~6HF7sj`i{!Mqr zH(#9Nn~ZVM`gEhvrAO&G=>#>oEHgc%7~r1n&6%5{CKo)_lMD*m4a8i+IB zk+D4h-@s0Ev)UMo*$ECD*P-8j>)d!}jIgG0$BA*_dYC`l2O$mC6(@ha&v5_P+Dz>? zSXW+AHV>se>L+uYSMyhg;Pph`*9i>uO(pbIx|{(Q(G@rU`VvFjv_@fnJNw^0#^2IY#QZow=rH!s zA|_J$`8w!6pVsga{r2_fPy1=lYqekSd+r4fh3)sgCWSg`_UrpkwOYGOB+va3@W_(K){QkUy;Je_Hy?@aos zZX@`PX_W-aiMmoSlB_vV7LtSY7L^~!@ZRQsN{C#Oyf0#LO zP&FFEH(rcyfQSzt&l~*;jqCoFd;Jc5N~rA`8O|SmKXPjieNd*0%h%A(>_oo}>3d7{vpdSx^d*yj9h3e9-11@jh4rWx?s+x5ZiHVCPT=x2)WJdM zP+iWePQQ7w;Pp{n+;89zs}_96?8oLz7Ah{9#z_s%d}*Wk<~bs-gQGZU*l$jv-yYnb&e%iJyJ9*> z<<-0d{CN5!qnZ3yJ|(6@3ej)#iao*XZ)UtIhAaJ}=3y{ieEP*x>9oEnZ;R<5V;unZ z<4JFIr*V^~is32*?xt<`_os2)d|X3&@YGOsfEQovJFOdyE4?SiH-+%yzlWT>O5^76 z`O>F^+6rM0Cp)~8OCMw(A!ZK>!8g14I}G0dpRb|5F2di|l&y%ayF#9ciVM$U)8~un zYbW?_KmHTL*P1DaOX$0F-kSZizDWzja2-T^=<@G=w11&5$^744H`F(i(0642=9zj_ zvSVmpJ0X1ym`w4rfb8Df6yB>bXsxy`@RxCQ)vGqf`=5huSmIq4dW>-j*e z-!cilhXVr{zVb9NTo0k|&OxlcS$(+q1N{+0Z4bfs>aspgXq zc>gf?9cV{cuD*u-<|q2C;hXE=`UhRfTFAxK9j`TV2s`s^o4QAPUaNhAIwT!Yb%1^g z9$4N^!_(@tabo@EC;0Z8XJz>23-VR)@72LVbyr6rX5OOlHml9%0Rf`lhK{&&gE{|W zv3|?PI)I%`?A8!20-D!L_AydMs9l@C~A1ei}joIylM|{J?+NK{)-u0K3_w> z2om~QD_U;Rxal4-9g+#YE2px2^Z0yeDxtQY(D%&V8EN!ENuP-EwPLnN@hGqeXw&G0;{@0?uN*3y-f?P5CQ z;`Jz4C#ZD1*S6U|4Z(h7E2XQ^+jb$IueC>id1ik9M9$csJ>XvuVwzt|7 zj-&DI>v{0`ux{j8^nsP;%WIq2gBRyJu-~$~Zt*KT9Qt)`ocsy@K02-)xQ-%D(r*=N z`>+nMj@bP~iN1yhMR?Lw2O^JZ-GcocbKiEc-yf1*QthEM;xw{`(uAhwZzhK8pQ7Tz zbrlb9*^gS1Ok+oCBOMImPI6-v_bznu#F8JJr!n02$m6CNu8eWvdamaTzK@yw7KX$0;%16=p( zk?q$sP7;1`yTe%+Hgv_xUzaoFYr}jYKHPkH2XkF!0UuY#Lu*)x_wO>VWUCx2y1LTwSUVIJhZ(Rzb&iZ#?{Vk7= ztJf8`YztL?gLSzNyopWVgRR#&L_t4h2X&rI}f49$ramymW;)l0)pm9@=ij8kM1a9w}EUv{T z)^C0ScTD44hOg%g*UspVsJ4r#=YhV{*R%RcK{4E9j0^g9U%r{)D;?qHCB}T6;rKA~ zO*TGco)WX)Y;3w6&#&g})bfYGsHpRY5MTQKMpIH zn~QN_9O~nIeIo%G`Zq)H_q%hOsCEz6_pNDcsYT*Q4xGU%aBfA4~kcX`SCsjM1Z_>vx`w93RYd@au zaGeC-Cu^K!_~sN9iw`*jZpX2CHkz-qzZl;XzYpCu(>ELcz6b=! z#dTW$rukbS&hMkA?o-!cVBGxX=aqJvPipb#^rhpO2Y>Gi=JVsLR9!;jN`1KZr83UX z9t+3c)~VANT+bh3{^oo-yubPN8|%<;gnPmjUp(^?-veBDxXwjJ2S;@AjMmqOaUq^L zep~z}jhj46EUxEaJA?hr?4}PQcUE;!;?%)U@LjX77PF3+F32~T_`Tco8Ku6bb+8VI z&W~w*0|ejiy4|;x#?6V6FO3_-xR96JJ=OIIjT?v(mp)G+eph*8yIIZY*ZqPzNF7!C z4{exEEB^|On>1U@&K%gDDkH#4UwD>kcIJxF&S*X!?8mTf^z`Mx%NnjHPFxqE@8qUk zchT>gKQKBwqtBBksQRLSBkh|v>u1DQM*m6<{5d8lFzJWi*_{zlZysirFV{~v262lGP&szl% zeSgX9A2l7MN%7gQjL!#Ld!PBR4lbjAB_&Q==Q{OsR!3On_I{1ru8@rWl^k*6y72iB z9~ulU3Hy37`d9MAiEHbn+5_a)|MgsQTEh**iEG9A1B@5zwtvgGWp0%5fgb16F<*$k zJ0JJdM3t^s1;Au36dh<34dw&lbF3H_=JPKnuY5fUDBU4uxC((=q+SJ> z7R6M|aGe;p6hce8+Ulv8K+(ZwxPiXmakJ9OAak8=p5T2j9C%&`>qcz~A7U8EVtVf-x)&<;ISL{Win{Vn) zLJc3G@5+WF*3qxaPO)(_6@L#K)-~qse4sUrYi|tu0Qw@5{yBxPTT!Trv>!;I!Z>?muC<1>B8!DOt^O7TGSpqU#omkqAtB$Ysfb= zUtZhH-~5+UT)18?)iY`ps$?D(`MMcye)n*{oxk}Fl36{{_j=U*M!wCR|8wzmnJ^yD zeC$5NUd46&86U0}>w7Q4z0&a791YhKB`((<>f-yS;@W|0QF~BUs{ID*Mq~Q*cu(W& zI~1P|N@4YUh?7H~eWnwtVk&0#;3M?ib>P6FJA9+mSHq?AGX-ssX@30Qq8jaKvIRZ3 z>yz{;p>_~oUk&+W>!UwhpbyFryuLcApXwKYYc;_23tnHHj`I?TXYcRX*@ouJYn$oo zCGvG^{{{1C9OpY?>qau6!=Fc3eS?Df$~doqb(oReHvUKR<+U{(=;H!t<_dNOele&< zmCc&{Du2c2Z^@Tbdw_9sT;9T`>G$Qe&G_cxek+3j9{asf6CMuzx*4uCTICDz_vKl` zn0*}S{mA1yH%^|$aT3=KT#Lp@8@4mx+xi`ruZ_dkOot5YZ!ixy)nIxnT0dUf3^$$N zYc=2-_(Ci{ldGzB3iHjy`6u4y@uOci<15V#=MPhV*yYsxLcT}6uL+Gqx6N=}gbqOi zJ4^afOa~V+kNv6H9(8{}>z?{z7u45^?F{m$^2K`P=u!DCZhUy+E;X;lwFB3p@j)SUs9TTK!4;(r zbY4jhoa1pO5!cVJ`@JcTAN{%+Uk{=0E(3p)my5+S z1^XMsoelG@?WOtf+Gczed|wn;|Go5i`71PzQ;=^K))!UMxNe)<(73#|8DB4vPp-}H zx0=Su`Y3W_~xAaK4E-w3BFICs{RnoH(yX+7aqr;-{u5{-I-^3VjSP-cxHJf z>~AB!cW$Tox&+t3eb_I6ufN5wEot23m12GoAoT4#{g{WwRRnRp*dFdefIi2)X#XO% zVrFMjT{TWZK3SsqcCQxCq|5QmFAA^@6%g*4g8N|mNmtSZb;u$7qDrPWVSW+7_5ehe z-ZKTJMY`hqM9`0k{A|I31&ei{Q8Y~Ztz!7T!UyZKeC=K_`}JbJFwVc6Re4(!6m^G~ z@s$a_y+*TqgI`CNPtx(hUps8Sx8=o(jtpw#trye5fyW`(pYOVL^+6gpbCnpbpRfnV z=+wzHF0XB-uY&ajzBU8CDXYc!+K6#}mc3=d_&Nx_UH)P94GQuNV0~d8VA)WoFHcYU zbu)c)aomA8xuj74cJz6?wi&L6(Ba*NYZyDTuNCVz7h%6c|7P_~t0v}eQm62IzRAW1 zAPv@)Jh#}ooR83<BO67-tlt8dFN_!O{#kS+4P}e+dsK8h zOTqaL3_u6YzVQT&n-=B#jmA|lE}FPWGd{XCn#Q#Y=27x}>No^(=if$C>@;rrf6?_D z&DVnM4EBf0ji}0uLm7j_*4I7QFQDIAAAgj&{vl~}>J6h57C{bCS_FQ;@I4q2}wb&oJ@+i^FvyphkX_eChMD z@O281Pd@(HNEC+Ep76yuzo2oYzruXGR%ZF8J|w1Z0P71I=(RK60r$|AY(al>V0);F z(0*>8#;l)Z3i1sS_HfO;vA>QiYS`w8#dR0KH>(57*P9{cZysV^`1Y-pOgzgKPw&JBXC!HS=@}eVs_>y;`-P3_MA<>Z-Jnld7G>80S%wh`PvP9 zG%l}g7ANyDU)Ud-+dXe5jibCPXlL!zyad*x8jLOaF^$V>YkcYB@`(Fr{W|dJ-t_Ak zyTrz~q`_+3fp}JQ(S+SJZjPW1QUz5%*mr7wCNDta^4drTkdP_1nqhsr7x@U%2wm|C zexEmp^@Vi+$ZwflSSyxWkk1M@9`aKAdW?mHb>)X3f)UBA)i!8Z+HoQLaS-u}Tl zKpThTFQQ&AG34tc^ldb^Ff2>yiiPvNTQmDj+N;_bbXa!!>{oQ4sF9J+jXQ>XT?F3; z?>bPE!QCsSueD=%JpL;Gol`V!@-JezDR@5sUA7@T{0aNLX8L{Twwb=ESYOC@+6_Jo z>7TAxf8pA%?s%<{i->}q0pI`CUVdA9KHA!huMP8s_%Px7VlU8m`Nzcc4eV0w9}M?O z#oqmC+`QvrxXLKi9)NGf4&70fqA%%Xx%R6+0k<4Kt9)U9bNBd985?(>6yuwU?W_pG zy@YmoV=ZR==D~bH-!(^$_n~nEf_wvn4*%tKV&-oJr^Iw{2f}f3&4$(}KPx0ls5p*C z9Vg*%w(Jhu+24&HeuO^2nJ>oIxg%_6H%9o5(ztSYF*{QTzCX2?c#Fo({9BB#1LK1I zUb-vSL*v>`i{ZKmzDuvJt4HIy2S%5#)8~2ccmeaFj)NX*OuwFfhRc`nQNYM*rrH_o zi#*+Z5;GsN{=>zksf5~I%oo-lnmtjU@e4m6*O0FV^M&}3dF&Pw*BxiY_y%87`=u7b z-Pv-|lF)}B|C|%U_2BpmV^Og0PR1T`f?Qlf9kQ_wFu!O}x#tBfkCLXS{+*pJ=5INe zFABrb{5qwXb-C16#BlR5F3ej#daD(rmAYcvAm$eqw2}eZf)17P8#DWm>B92>6&Kd4 zcP(APu7lge=2_`Q)$<@BP9;G=oo8W9-*DH*&x6u4D3)922^Z$%pFzu0^k7 zNS@#LrAT(}``+FzYuN+XLjk^4st?wqk~xf^lKI7_fLm;n+~`L@DMpD`98W zPd0624&Xdt##h0(U=NcAK3AOs!@O*UYa?*y4S7CcxK^w$sw8P!;;y@L5PZiuKWF%+ ziQXTE=(q2lD#YN*g19b>3l~oQ@$O6p*I$7xL9p3^^is@j(xTuoON$)xJDo9d#c`;l&ft%*&;i7S!mBnx! z1n!d$f6$)B<+XWnUFrK)D6Ttj?ZUNaT({u34*IUYKK?At&r(H9hjc=RK^v|?daWy| zg1Fun)o}>s7vsC^dQ=CB8d+b8*{_q}Yk9UMGk=q+is|5dEzEb$cOSH-`KING@pTb= zA6&rZeHns$-9()1V*8^m&6n5a*{|GjoO*pVt{u1*wckuahadJnmPYeSuO`-SZUT3b z>q|6?iLLN-kou}R$hcOt_SnV}XrbT-{jP=RCve;KQrOOJ&3h!3J}k&z{|%i&?{~X# zo(k*WA2r&@3`9u}aP>8u7kbgk0OXU9pWXe|EHp3Fmt4Vhn4RiY@9X@Yf&cQ$p=Dd|y_uwT#J4n0c)Aycl0U!FQbjU&{kreGU0~ zalgTUx$ZM|Jt`=3aSi(|5Ay{FF4~H{-(coNt`3HLEhr-cZDB*CRq_Q`F3=VGFz$MZ zA>RPzTNI(SXvWSrgO|kk`Ui*kwm0A#tSzQ*KEb!G0blE7F}^-*51_BjfNxrg7~del zx0?Z9=M^qr!+tBkxDeOvZPs1T83Qz~a&ehc;E4d%0rEau@4iet^YC#E`AUz3$D!v9 z_@-YI=A+L>~ji)+YNChY8ZOV-Y;l9)YMFkjGjX6NUa_>k0G zOy3kj-wztCXX07bOI%z-eQkK$1itSY@J$)W#WmE|O7Qg<@O269x5$LPTjq>l^tJH! zTMYT85`2Gt<7Yq9npyI$;6Yeo}Ge z6Y=3Xh&;7I_14=EyspSY#q2@B`a)ja^XRr2I#AS5%8BWlLGZ0?z}L~2i)&~PX$0Ti z27ImMxw!O447K43F33~C-;T`b&CCl6hKuQIBkcFg8>=tUZ=O1mi%XxPw(&X_~ZTFAr^$(!Mxs+kd`fr+ptFK|d*@=Fuf2v?R{pQ|^TwMB;P}^r$ z`65S?#(maZM*fB#lH__TYJW52>mc|(V!$`|J~6&-9Cx7KTJ(7iO}7fk=wGy088zR~ z;q*F;(q26u;*Nd#?uSAL5r33kV&9W+qYI6|7GPfZ;THBf1>!9X|5c+O`;wPfM||_> zu3GdF86Cvz*YT&y7uKUTZ(SbN_hfAP(tJFtRa`I@`^wS)A5$^Y!AIy&b~< z_zB#}eIKnsllAl0<>*sF?I3|$yUU-|>4RK?xSo<~|G>INUW3c^B2{4+X9-sky%30F9fmFYi~W+v*^KPG~d*n(dj_PGY^iFfIIpA@v~@L>oa2UOeXp*xMo8W8rRn~ zI==LIUSeIj^Tshu{!1TEx6SO=kL?!%&Xz@AFxLg;bra*8i?9C$8~*wJm8WPvIh!Ke znHgUn)&bTDzFTZKw9;>-Yn$QbVO+>lhx98wUUw2|*q##8!B;1I9n<%<+rC5N790@M zK_UF&+r16Ys!VLfOb5R+Jic9h>@G#iA6(bs8{cf0Zz)7`e<#cO*w|{b9QLd{9M8(3 zm$n(`>*M^s-mca4C3v{jst*sU;qfzmNRKQoykvcSNyfE;Ye!Cf2_7!|pqZKJ>mu@~ zlS5v^3|c`gLwxU%gn3>$rB{S~RY^2^}tV{%!M}9v%~&o$>g( z%6t~$>%p}T*P?ubSYK30&WG9`qV+2nCl(*vb=1!b^TPY45ARLmrW_KB4=GQo^A;HA zPmaj9=NX(i(1tCudUqj9Z6#o~JAn(#W}?|-Zy0~r@ zAN-gvtP}kE?=KDS@QpI=@bnE-|01NXR70(0trmZ^Pn_KP<*E=5sO?O|7y_~NfZ#Isjte7c+Fn=v}F zJ#h7Hyj=B*N7P!@YC(N1SYJe2y1(1rOq#DfBQjqzzp&%)HA4=ZG;YBd8aE(|`CEQ% zwck*ONdxXKeVWGQwaxg-gq_{`yHPb7$IsD$*KeLlE7b7<*8yCMju)2K)c8;l5xv~u zrv|8!Y0i<_W;%EmsQN-aS+cbK%$>Ls?`_5ULjL>R(Cv(0SjI%QGoHS#`d@|g z_2AlvYo5Mb+EeqC{{?>I4ESbx~G zwdJFl4l@4UIL)7KYkYkV)d{T&Xs^2n+~2>jGvDj5{wSt{7wZ7)M%SM?zg6SwiBSi7 zpUjQ#-B=A*aKh|{6KEGBwi>UT=H+mwu+Pht~=cBDPTyK57z8-?_)^e8y z(RjI0-Y=6r&qa*$?%fYArC(1L{N7?F#)a|i!!C)t-?kU)0ONe{=*a)ke0gn6U-~#V z!S`HAi0=C05nT7Q5#Ixx+1I^DkBV$$wV0iGFkf_`hIG9W`@I9tb7HvZ1mFHQK2F$v zY&PZ#^W$ZEd)A|M;I+;A&5Lni-*j!Ad~`jczNAFiZ%lkRrsfY|2@6}DdR31qNd+6k z;+c=Iv+7$;UZrsZg7)Ae{9=-)|F<+QuWhDp9?@@>GKuTAe4^i8bF=poQw~O_FWqm> z2i1N9JDXi=c2oLuXKjp(%gsx6uT}FBT>EexZC*n2wH^=KS=)=>wxId?IDF0eEd%>8 z#NYR>ZfE?$9i_fBpCsfEFc$(`r$N8@^CIhO#y6S3eX`D8hOhHbWL$2)&0eSW8?Jr0 zj<(-u9a8XpdXdahr|q^c>DROCiLKKr7#H?0-u=c}i^g>ees3lP>kIn~^ZHqsd93ZX z$oiV~n*|vf*h6{ru#H%sLG$(Tzc)jl5^7s9U-07>DlK@3J}B_J7+*Wq7v=$d2r*8pZ`X z8)vJvoPIq+5I2DD{|oEjvwj%G#7XB3F@0@>4*A)M%TuLfb^Wap;`?LM?Vr&)VwI{si1gC+xTSxq2JugM#;n`Gp6^ zUs#`<)cDFu8aJh>n7%=*FYE_=JZ#2n8kg7B?19cFZ70OswCeS>b$r$Ip!i z(YTod1aaR8`^BM4gIqMOU-bK%1mB%AnvS4xd2P+k=;QoYU&vD(TV8yHe!W1DuNCt} z(?hAoqKp+ZF0XCIHy`tbxU(enSYsL|d68JZDFoj-l{_tJTwdFZZ=j*NjtKh~e~hj2 zG7pD--3-@7elT!ciJfQa%A28#wx3(Cr?}=v+NAl>;X?su% zHyb5pFmHi;r{!#Roq&EHx^1SfY*qUW?Dw|^UYJ0imy{yLHx=2@A>vuhw|XUPpTUj!f*(I|z4$jYUwf2% z>Ac!~Qtda;;Vb!xIW(?+i&$QrP3Z8AC#^1x%WI>416O5=2kQX#`$zAz*XRTMQR+aS zmyfU4fIO=6!-rRE`>{%t`^UiN|D$O3OZS_Xh`+n zUTxU45Ip2Y>O(;_Jci(h@(609N8sk}!Y)*M@WY2{cm(i+ep53$b1hNrs0KR0-Ma?6 zu1o__Z8KcS8McQV?)U$oPUALBac8UfdNM+2@X@ndxj@tbX1G?u9u_6g9#RS1FB6EH zyHT}!8GXLN9lmcweN1lCOa~k03+tY@q&OPY(Jp)U0rcUEFO>xl* zHTW^`EnMN)gW7dhfuL$9JYX~20Okw%!{wj)_;@(<>t?t?j0@L6zfz$Klc&-+blVKq zm!;|ec~rl>S37AsxTeRagM?N(L0`~ea;;e*9mW53kKzPxbw^A+(+vz_oNtZHum_%2;2pvrfMb zxW(f~ziy_ljP(V37}}&2`ddgweTUM=D0q)Z#f+~N>u@hRdHO5g z{1^$t=rvPZLWcu2=N?BogiiOw>2Hprs-510&^ms<7g=2)8T~7{uEb}*>DYc@9{cFJ zjR~8_Dp+4g%zP_*1MQfKnZ8b}1K@6*)PFmwEqjTxvv0%cnX1Ey`7sjCz z&(yD)C|n2O$H!|mte+@c7okJp6|u)NGaWJs+}6DxJeM%Ogq>vvs(BKHn}+jLwA>}7 zH(#ExambDNLY(~c`iZ`Y;_Jb<_aeYat!yX?#a6U_qvu&!xZhwt)aa$_OngY)6y16W zjq4$B8ynzeOo=>?<&B%JvzyfG#BlAyb+qFq%{QCi`-lNw|6#H34|xgPM-6a!y=c~N zIRx%w2DtgZMdpi6|9>ff8{+(BiBSHSs5kll;%laF9-(hj1AT)dBkOC18z69-8Q?0T z#BlR5E{yY*)SXP;=jPz@{7wF;NXXw5Tsv?bt-sNB;KTa?kgvOru6vt)JzH?y(`8Zb zcLmoIH2P)~y6#Ht2{|jiJSsm;UDtqhxuYGrKS%S;5ZsSVX&$~m*BkOUCayakj4uAt ze0jw5Qm4)eF~m)3Dg%M1>R@D%ihZ1B2^!1Z{)=_Iu@ zI4HtXn!nM91n~EdVBIMA za3jBtsxR7pk{Vr3+SdE2e|zH`U)@ z4dTI*OKWTMA;-D+{5U}T-tEkCMRwABllb>RrcVjAlSha74jeqyM<3)H!C$YI>61`9 zP(B=YzJ2J)g;FPjgCabI>=&j|Oz}2T?F{BEpFLEXiNC3W_bawy9l$SME;)j^zAs}7 ze|(b}w&;62SO?f|v5$W3Z;9C{GdPKO%FK_0ggu;pjs3lu0@3RUuB!S%zP>i?I9wK^ zE9v#c{6eaw+CPk&TZ(K!-wV|j|951q0ythe~~OP>R63+4+8 z1SN*E`eu$3!g(+c!2dxEVk4ab?7bE*7*C0^=vxISzTknbe5x_*?#^^6t6&B6C+0Eg&! ztln4}SAIYY*M$rh^o4nBLo`~%TFm044ch|*(I>C9W&GHeD#kahks8+l@WtX6C)0fM z1#vwV_4^Ev?~Hwa#V#7x`>$Qfu)Y$$< zk7XMj6X`iK`^~}QJnUaop1AfrjS&>o!GY};d~RCTt8db{N^`!xGJO(i%QIEKfN_4z z%3;$a#xo2~BAzmfXG#aveqkI+Ki+!~aY|JGn(6B!@~G{lCbXr&a-z_IJ_p)<;(j*c z4D|JH=Z>3(d0#HUcas6%>=yifGve#Q`3{W7_kHke6Z)6}KCU5OKViSM4eZz1QjD+s zdN^ONV`J^t7X_|Ne@N7}Z4KM+g}~JxrKtu7MR>~0&hm(U8*ndcXQ{2kbVwz1sA8al zoGWH$0fKKI1HO5JeC0CX@y*rh(?+zEPM_HL=EUPX-Nct7+-0R8Ydxt__^Zyf71FUwGqRW3EY_tTaTh~vjuTI zgH*m%5n!E%0IHTrbzecs0S`MEsQ5c${@kjgyd=ZJ71MQf-|!5X1V8 zZ1A>j%op;gx!wUkCyK8P=MSJm0vcK6h~)!vOa7T5yap{Q(UyL zqs5)S4emQ*0Hu4%4A+?w=G$<2`~F(LDKk_*)PWc@09Q76-hyVBz!&c%POa~Vp=V89ttI&hFq zY`P?UU~o``r_A^&WyAU8`LC-me6t&f<&(MXRlZ=j%ZE*PiKZ41T$gi|Q~82l3>!Xp z1C8q!{2dS<{yj_J`+;}iVj4F|a9!E^fEpjb9-jYiC$pX!EX}nCa8;(HKN60U>2KBQ zMIR7I=I1-~Inb7g`P-Uh9nk)-Ia}+w(SkjBlbCu1w(W zHNdq^=HtpV8Pv7~!uk$>*19B=q!=7$_LP~vshBTZhgZH+(pmcaq__Ee>2si+j&Wgr zkvXhx7y1}SrWkG(fqQ)iiz{~$^EcSfguD;p_&?F`0aY2?G#LmRX3 zf0V^6o;mP%41PSQ_QmEjoTV$5uc4h~Vmm|2iPG!$biGXDdil7LOrM0>1<1d&`R3#6 z3#AKOcV)=eP58y$$#qB5Z=KssOouE2_n-l8&Qn}mno6kc#Qg^QL+>AA*Zb@?F)sr5XHsg1>mkQz|HE;%DVnzNznX<0O4bsGUQ^hju*z ztLTHgJ-B=g?bnSQ5$qTIV*J~;|CJu6kt4Uw{Mb*#om+L+`e_tTPd;Dz9BAhgxVCOA zZu--FT-gX1T`vhbz<$7`&o|$en3N`1|uReG;_)RP}{*u6iA&wUE%tTr9;*2d7uX zh41TqQgbtUm)HuzHS}W%U)KgN4jTF^^Y+<-_xVqIKD=&UrRZ&DzdP-7vH0M?xaARF z`GHf1Xcd(A#QehNRP}{%{>*a?E=tT5NAx@C+l+AdWf>6#e}nwD!S?oT^k?x~X1D=t z572L~PEY_orUJOK!5KN|1>g(&PEX{beW#%Y2Ss?wjIZk*b$#c4bnbz{b(cqgFnr03 zufL(n7xMM`@65Yf@)(|O`lK0d;7=77^xf0e@knUkFhyZsFvZ1up~GI7R<*5^%AOnP z8Nf9vPGXW~P@=zc+(x2d+iGH)BC7$;l&%dw`moEg1?I>W4@4ASDnx1)$ZY9d<%#?)s>fzb~E(F z6UBbF{tUI{Cawc%{^@x}U!?<=uMw2;~lUxg!Wv6!_=M z%r>*LyV+!>^E~Zlc4ywadFPvNzM0utZ_xklLtrQ0I)RrwC#MF&o%!sG(@bcYo;K4VsZ=CR&FGOdf(7tA z%f~m6i*=}k0C&F8QRmh3U3~T+k#Q65v&m^V3%yHx$*kQHNV|bwKm6>pODt+;A3nbB zGT6>wU9L^u_o&@)OL%VK^X&Vud9!x&QT;8q^Cew>%h}8~50HtzcOW9SKXqr3>1(6< z#il;nb$&9bFQ2~Y-F_<^35at7<@#{*B*b+ z=)I$zGqc}BO5eXH>GgH=(ZYam5FxFtlebNZV<26>^sTFVx;xwYqt=w zGnf~y9p7{di))oP(>J>U_A9XdP-BSqT^2_kz{l4`^sS8mr>#D}k;S#jo9UZG>3ib7 z8oK-Y@;Uk12I9|o7a}&`ky&@J{G7>rc4pg#`vo}k=U(g}v$$4yvv!lnbEd)XT&|M! z6N?kF=4%-5*onR{f4gUA-BB!V#>;&6;G^uJ!L)bKE_Hm#Ooxyi`!kpjmOVSHSA3}E z{>)GLowxql2JTXmvIkk}V5qNyvfl^RJgNKMZPqK6xEda6#+Mg~tLHEBy{Mj#^=PJV zF3|z(cXykmM_9aqW0rA=p$^Js%op0NfAgU)vADT|`E*c-z7VgU?r~igm$2`{=FM~{ zpmg}ItzL)hd`lhJw+iRe(HGp+`Ni19uzD0xDfw# z_^ij|_}H5FH|d^8TwQEOY2AHSR_|k`gF@my;OqVA$aNOS@8;7Xm-3SrizOdoajo)Z zc9ux|I*jwZUn~t_geE0guM=p>s~JC;x4`;CpRu>kQd`0$;rr;+a%M*}zDeZw)Zo6L zN{zIqhB1!jIWK@8LWfP*|L3k9FXCnX1EUOcjaz; zh&H#FWXs~SGnw#(c02mxx&sWXWft)@^be`TenHh?F~jePyhOTI4+4+Cnwri&l4eSA7NsrYQvqTBaq*;wby zbnsE*#lfV~D_JD@J3hX)n^<3n&wf0x0NHP`Fa^WT$-XJdoAH&$N5UnGsThH0RnlD=i@|jO!z7VgUy2|w& z0YiI8C(l~}U%BSP4-MM@-rp>l>EK5Zj_QB=Tpd=x*0;aGr-Sc!MBjvWMtWIXf08w> zkv({bJwU%WU4;F@HwWtgesc6P-=KLRRxG$A=6+$=Zhney{ZmEPkEIh>UzoogZSjI` zeJ9_+r>{E;>j3%|FG9X9!WR}EMtAOqqIYddvUtw4nf-dsV!m)+=KH()J&q2t7CCy( z4A)f&ua`o+^GDvqZ&Z8mEsfnCjNaLEC$10v?6nWP+g03Ph8S*A6RZRHovka2&hG?H zM)dvS+^|oLK2x-FX8KAf5&^#h^S8y%{g4t3!|0kBZs-ZzFJPP>^5okyRec@ri0SJ* ziE&|{q0bfl@5iQnY8{st`7`Aj)&cAxVF=&&W`tWneb4>J_gns9q+zskX8NWPJA>=! zvA0FGe&(g_Gw(BRac!1c@HgxI3nLx8ry}}pEW-Ffq4>URz&F6T?{6QB`NH~di%lbS z>pQ7!E&aM-Y~Z^W<3fCP?uNeIvN`wt17Ak;o$_pn^uqpjU97)(2Vh(nkMsBG??-eG zv+Qq%I%E?az)!Xvrq>~_ou$60rat*7z84JmW?1ic>p{^O7x^7?m|s*}^UV8fp+v8x z4u)|_km?sJ2XpxyLw)^}z8wtoO>A$euOV&@WxwYQ>^H=@@9(GDt?7QfofX{2$5)|r zc*j5oJLmp!r}^?K`fZ-P!n(*?8fg{Mldwf9Cqa(tZu? zAwb!~-8c39*xuQ)-3&jVI~DsK&|%+v>2JeAQBEQq4Eg3!?dBe<=bM+p$2UmXZ_-)4 z{W>17#x)u@-T4u}-jr|LG}IwT>F~CJ4h5Y1{+X2h9{S-BTJ?%Anc1(C*e~2ye0X}l z&MazPH$Hv6L|>Sl%$Egrozcse-~8{JIg0_2K{(t?O$~MOqs^Xm(t;InQmydtW7rSeQ86!1%xlm zhiY%y{(=@2`R6bB_$HLY;{n)%+p}#tiyN$E`CK2iN;oeQT$pDy`f}VDwvfLzA8s;* z+sptr>lwavS|_E$!soYt#q!Ndv&1!QH~9XpI*&bH>#060ZUN`MX*#9D%#Ld}vA78_ z{4NYz2l5^Yca8yW(u;gL*oY3WFFm|mw|Ch0&UuLsR~m@*1@SMf==C#;>-wC}pZSRn zww+e#_U7b1A;d%f7DToBawOUmMXE_;xMU zT*o(as_+yVR9u*U#*)l%17trI{O_DU&pv^0VW=~l>lwWd;2O1C zCe?24KZ~y2GLVqqC&Txxe0_DC$`|snBr_dcWPcMr%diehnjzcKEG(u8dxy4lK5=;URpX10TP7|2l*l4!<3Oxbj}CFW|nv{R8wp6pZT;#Py?Y z0PP0)E~`@8rRv}l#C49veBt}CZ~VLaAr)5<#7!6ziGNEBn~CB++`{tbV(per;co4` zv=G-Lh?_u^^fSVv2*s5st!IuzS+JAuJd21jf$%X;s(k68sHC~~YsR`qoV^0j{-@eiFUY)MyfJu%|KehMV_`lrLco0rQR z@zwbMo9W;ne8K;YaQ1_^Bn7MJ>$;o*y`-D5E>>`OQP11+`_z79dY zF4Q4l+=PCyy-7a$UI*5}MZVukQ8#>PW)DtcXBAK_dGw!X6vZVyf_wv{-C)0a+?dW2 zRa`|7H=p2w{nkz1dtSv23gWsb|L{igeM?ka$38JT^L>fi4dTAHa-YgZ2TjWUhwu3W z$`FhT{-NONWHejWrmS<8_6s4HE@idDxTVpR4KIw%WDCeUt>ENo{GumAo=&9_wCpdhYm5!SIL!ktjI#p5cj zN6=5ACm)CXFX%huM)&S2u4AfLyJbwr_J9IOsq5epg}5F;+z`P9KiQ~R{n;vCMG!aP zE6f*gQ&OfC>KhcqRYqYQ??ku*E)<|yZ7~_Wl!D|uypER4#y6S#E;xMu;*M9mK2-};<4Yvd+y3p)gHU8EnwcyV_8kd`X0PY^eg%->)guJf52 zx6mQ3WM;n}!WZJR#?N#@?x&cHUZRK9irJZu;KID7-hj7XRdrAV{iK8Ns)cZ8m#u*g z#boqSatZQHej3{Y#K1GR)n23GDr3ZSuyw=rVIFHc)Dyz?xRP1B1=nJ};CC*(yBx`k zOS*m*l+-#boC7|9mM=ltGG4)uMUV+P;H zan0b1*WDD~dIo%@nU=WhM-1l!)c5r|bT0N9TgYdPYpAcSA+~?GxN3iDBNjJgjmuUE z=Tph|>Y%@sap?KFms#py$XBNLjys^|o4ni-*N|^M(HF+!P5qzzkS%22WI4|=phUgP5y}wH<8@u2;;>MU2dTH zkT#|7u+&#uf#ke|FIw1<9!>am8CxiobAFsk_(D8c_FBI>EUpx^+>g~&ffE@77x?ZT zAAZuQrd-lGK7Ad;&S3u5bw>r54ro%y8rRT%Gl)Nfv82mir*v^t<{r*=BRar3;^u4R zdTYp{OxAur+=NzWeEnzFRGZ-(bHeHAIkF_b66IXs0<3hVVkuq_r78U)T(nUVL$__lv zCnCVq+)7tj+=P%NuAzT$QGRFqyf@!takH&)*(%|DGSLC-;f1F+>-t*(C$5v=g5Q~% znmm?$bN63-I%E<*3HzJgH&9HAg=v?SYNP*&I_I@T$huaVmhP}To^YymRQ(O<*Nwt4H7$p__vPT zagT}{6vXuszTkgfl^Xd~TZA6WN9uh6|bg18~lZZJ>`*qemHN{ky6#Ff6r?E`#IKfLK(6;~$bfqS%s zS?Ei6NPUQZ+rPebt%~dVSj--h21Vk@#cTg-tm66v`6gAy>u%7G+oeoJ>yzY@-63}0 zm6DA=FZjuu8)u{cq}|AQbRudp(>Lu~tON9m-x?lRqT)((#PszMT&0aB zQgR9EU_&1rFk%0qT=^wv-hw}wN06`kt%wexgX=E=S32d+;ah)j5WcWpJ#KEJ`6^#U zkZ&rvZxF_}zq69jJOJz96V%s5>Dz4UkA>sBd_l|}l3&95f}gxL{(+BZZQ*s|Tt0o> zl)f8(nf!^WgCeLykleQdan$w9v}~5IRo<+>1<5`R1gHz1d=~i1=%wTsE2eMYTx6f& z;`OGeAIF!>_}a>2e+G8e^2?W=V^Qs2@~smDNV`G&u;DS^Cbivyg6)<@_`-ZhDtYA? z%U7As$Jb5amNvlkz0YUASyaC`GT{w0ZfaAa_47Rq*9j6^V|yr#;5v8t{$(vHx~~8| z;vD>_Su(SS9LgSQX1=Z47fCv5sjnelnec`A{Hb0y>ax7De&ge-{DgIYecsTz$s1W* ztGt;G0ZNB~A5YTh5IoCg5BZdxb!**w0n0Car==C%T@{J6UgreK)mz8%Dqe3LjDDO_M1ldmO_Bv&iVTv z7T31dQU|t5IG;-CTYi?l-SVt)4fSHD~WzV-u_xQ3s`N&ExEXMv3s zkt*7h9Ev{9>&A=aMK)d->fk0iz=qRrr}A%U*`jA29pux&Mfu4s27WTg`TU&>!Wa5+ zo|qN9zmIMYI=^$Z$ovjVC7cftJA?Jq zSxbL;!LU%2lV)}nnvLxY{BOl~{z3arxTO4%*g8RweE%5i_w8wIA5d|9bH#977cgI# zXBB_*`$j6R=TnTEzb*QBVWxxhLqvy1mw3Kbaiu%O#(5isJN0Z?G=C%d3gSvNBKBK3 zW1MatklDbpzZqIf)_0Nh$)WcjM`2|#849`t*X6uuzy!Yn^X})XZ2S~3<4I=iCR6(M z&v^8*s;@Lp%+72bFkg7z%SHLTOk%&#j~`wAz!p}6gaDuY$`s!NMab7l^aZ|4XCMAW z)mIkOw}99g*hH_MgZiqtKEZxrn}O{Y*5zEM$`|r=2=Yy$a1UK*S%|9$@>PmsI|V=4 zqt$|gst(cwG5d9sc7t_-$_<~}pyCDv`Fbea2fX77b?^x4>!omaH}!W^`O3B9^S|u< z>p9P0d#H+ZX!pgi6X>8xq0cSvU)PjZGd_y%dtLnPRlYt!9Tb8KT1tX8VEF2wV#jvnur`QHG=_uhsp&#QbDK^+2Ae|zQL>~SitBTjoz+eR=r}-^(e@%BbgKJ(}rYpN_{1@RJi$s->!YJ(tA#u|)g>+-Kfw^@ImiTzS42u4^Xl z7qEYPq#WATQ};Io_01r-wVG>5`3mabdmv)JC;Fe8SBNY49Qr^gV!!i7|Aua_z?Lpw7PB+Y z_Ywd5qjaFRiW?NPGdUacg?YecXUDHpT&Yfc;|1H^eu{7K)zZ(ZxIw{olY$YxkKeNg z&6csgj$>l_rgezudtmLzKiSWd@jRdXdirBturIRm)3 zZOET#Q{W;WU+0vFzHRml?uzu40ofy{uZ!aQ_LIei0VbW?$M|&cQMfyvsISnN@H!by zy>x>#Rmf}{%DIf~0q(PzueyAm<4_zVh~nJ?!f| z6~bUm@^Rui2yRV;mM8n0X+TjXRGH7tTvsq(*f_qnwN{F1XYwofJo`Ru-b`QlUL1eb zLlwGD%xZxSGFvxV-V8U5YPWuO9)af5q_k6yP=Bf6V$=>H@07xzx`dI>^gLi(O=BTOb3N(x8KJ1SXRhaP=`<^ zwlf&Rx=#1hM+Z4(vZ$aLU)Su2{T{se@Na5KMNr?gA0xPxUKzHn5LZx#0GW5gz}8{q zpjNB~@*uu(D3jtlqtv$#seFTiI=IGSJA?W0FU`KlQ*osq#r%$w_%qO9&+F&TsJIS6 zTsze-8V&0CL?P}~F}`lX7uL_JZD{=o!j;iWDJWKZX3jw9{f~{uYF;} zejn{xw$Pus1of5b;`tPOQTq9ZYkO6`9zop9&6qFT@A>k`PO!Y8Nx5#me&I>N;}DE* z)mHTQLgg!y&!Kq}gN&Kq@e#fdK#g2FC%{%MSk1R??|CSq!|}%&9bj?o6)g98*(%|D zHn9irzl*<}J6Y915o|Xv=@+oh^?K;#b1H675Z6cfho7e(ajLk|La~04M|6Pkc*MIY z(2v9VI0WrMq4*wN^y@z=t}Mv6fU@7co$3x&aeab(L*=lJ5J$cGQ&Z&Lu@0URV(TTg z<#@aRdnmK6-8B_AD7Y>cr1br4;zcyOC+#MvZhlaeGw&2zByHrH0uer9Nca&4t;-9|2u;PxA^u0Boz6B&w+9N zLC@kORR>uXw6jIH-Jl=;Iqr+bDsC`N9Z+>mvQd0ro|d&!#dV1C{TS;2{cYlf9#=GP z8biix97^gH(c$d)ZPrsNu0s%4Ci;T?e%`BPs*39p)HnYW z)&bVJRv!rJ))CW=#Ad(jexXd-4fr-IwoNxbr0lt|>8q)PGWOjV7yQn)b4xa|*Igg; z@pVxBxW+K0@ID()jCOYJ?N$=}`7-dIf{yTahWyF1M-(6MZY#+_jxKVP-)kkopM(6d zpU12pyD5KmvBb#nYQK>EV)2f*JgyJ^_XGb#=pLG++{YJB`UqbbH@ED1^DdRIFGhXM zbjT=!?ExL6QXNa}(2zx$q}qJ;kT4$iH<({^8uDV{I#*B;)7MGt4D1*ETr-+2<4@*^ zvE3}~>?*M{a&(a+ubm|>#yY^5yroUWy8-UC z%eDKcxKcf__`yy2hvJp5ex%|C1$D@2g2w~s7wh}fNAE%uBhN=hr=un_eG^e232jyy z{k2=;oWz3oIQxZ%=m7Tn$FK7~Q~5d;i}ee8U(6Q;)Y8uLmo~9{t@36%geW`v_oq9N zD!8OakgvQXG9G_a{j)+`pCE3=!x$Ih)Dvq{rm&wo+08d@I!|NVu>ZZ#p%sgp_z_?H zkVSL=zNf!SF01M*EfKQ^H(5u7^|SPem;P39WkFm&;R}BKWS2YykL|%Bh?`4rLEi(- z2Nv%8y99A1v~vUf82VfHn}cVfLtM$UUkt*ypzp;a`tJcc|Hrp}mPPz8=y2&+&yuRX zK0zJ4{V`vNOG-|;H<=Z|dzz20Li`!%Aieaj+8i1r(T{FEZu163zM77%& z*UzE*cd)*SAZ{Mv3p(6i`IV9H=o}r=!ES7`r8XnzNqLJKWd3k43AHR0nAKX3vLbdp_s zIyebmn7>utdg2w8uS<}xhdg%?;)i*^2U^lx;dS6TA72}}zZ%xLX7@{MuJZK={?4HH ze(cXmA>5U#?mhz?>11omw+@p<^acBEU2gD-LcW6fdMSOoU+bvTH~D?Obv6 zywH?aGr@nboxwnHsoA|d)${7np2&wQ&BeITFO+5*+NnCoE5!U+Ch@=E&zhc@c|+x? z91&&JeXFXgdUVy|k#CdOU4VZvnNKkzMJLi>(3WIWK-(|SCZb)%>zPfIpiPvi#n=w#}ioP>Ymk(ENg!>ir#vL&wJyf7J!XfW4= z{eax6EyuICnX~xXP2Pibfc3r&RrbI-t&Cnuz7t~pAxOnL^V8R&{X%UD*0a<>TY==# znqmJ7e!W%65@>c$)-?p}%trZ#xeqNn%D#DaeLlW+VrS5giywFc&EK>s>n=WAC*^m1 zH_x|Fb&ytywVO955|<>@uJWCVD+}TlQ2uOkpNUPhDoB#U&ZmQm^f!plW+*){9s5-a=bqEoC!5-RqUqg@rh^_gLRNz6|-LtWe@i^d0>@B1jsDpo67nTQ-B`ThNxTUlgp4^y3en9bZ!AD+}`V5q)7DX8-Vgx|Ld`9UouC zhWSE&JMnqwCzY>5kgvQGw-3a>Z#8u{WA(Ky;j;(Z&k=pUa}Qpi@^uOFRfxXOkC)uG zYZ1#=YR{*ygYX4?|9$8Hig$?L5#*b+4eJ2@EOGI<*fJLPFx>lzdawF z{IF^dK|yt>(oe8fzdWVWD3*rVp zj*M@c?w?pss{(r7YhAwm7Dr?Jc_H3ee);=s7B{n_rM`yqi|p2zFB&MM1cT@7C6=(n zWvPVoE}|p&-}!ee{9M)7BdD)}JQ&0eFb=g`ncX@3X4JoeqkQ@n5PN`ixl#Xqy+q~f zi=D5bzJ8)F><4uGt~iR;w8>tQPhT7PUJ__A;LW5tT2y3b*0_dza|mCUZ_d2OKZM0~ zm*V4_K|P=LRRg}B#g_9}L%s^dca8yHe`!9xUW)JHx4P=|b(XQjHRPL1@eSR(O{cFT z!4j8kl5k!jd@G~e;LT@xu!VxwxQ2WKgfHBud*9SI(0w-A6e!EbH;>{w)PQelIZIqa zzIha1hXG$(c|P1A!395Ab>w-S4pId^+>xHlcUXrX0@wSQmwR z!vHtXhi^WVL2$vZ&+oZkw||`dKR#S9g?n?D9ygbB-zl5ItvgqbE6?QP>!+TVdC%@g z8mRuvb5(2}kbHl{9^_(rdyuTx?X?C(avp*U?RNF9-*xSlzKTx=H`U+j81%Pf>v@17 z-ym9{R^#f{C4Wg_3%OVG@%0eC5U<~7fSdd?A8v@UvjJb%f^9=hN}tDvoA4X92WU6@ z|Ma-h8a`Z^;DRBn-*i>)e>rhoWSj>l`up)e`f5aoA%jEvFtA@rcYX#i>6C6AKhVVs zUk8algLb>rt z?N$ci6t8?cT8D{mz0b^kU27u!*n2L!o2suz@b@fzb1`3tCljW9cvHm<#=cIVDyBL5 zDcp}g>sN>?troKfFQtQHa{%pcV#Q=Z+z^HP*TQZ-6<4y0eP1tOZKU09|Fv1+`lL^g zuR`hjRjbACsC*Sc+(guYVcdlEl48rJOwu$e%7nap>rrwE-0o!&MryHBX!ykK<`aD0 zU^=Dm`kB2>sJOCVySdN~0O$bz>{!;Hs8?gYiXh)C!WZ@#Hgg5>POn` z$&0H}R9x2!Vz~Z_c>IF#VsFPLXnIKcTa0|I_Afjy{t({3@R6fJj=cL9ZqjaGXInm) z{Ef;tDA;bfq}^bg-_|eCN5yr-r~_6FRc4awZ|oncq4QJk{{WU_WTr^etQl^A_y?GG zKYeIiVZZPQ@|CIk%=32lDa7>&;yRQ_9QDmJhi0q#DuTE{QXkgsy>n02RdJ;?V*Nro zi}}KS)<1Xt^gY{1X`J`*Cw~+fFCN?7|2LJdEO^JgAXA9Y~q zVAqRNRa~DSZh%@>{&v^X`hA9>eD~7^39ma5-+CXoN2`1#Ma=KWq(0g>mg>~&gN9|S zm_ra(`33U=zW-Zu`YRRJ^}HD0;CfuYCc=GjU!^Bh+@RodB|_BrmMj(fTE+Ek5aXNv zOT_<cfv@@E^=vY} zL0t0il$n<_peU1Oy&ua~3FlpeZ#k6fz3Pz(hJ~V>H1iK>2{=xLb*_5vJ=%+f@RsE3 z$H`P&{pG+d=UH5cie6e@J+b=OEf<&9)|LgafBDwLHNS@L!0sMWn1B}*Uk9a zDEocB#TH>uMuh8NHM|lg0c)0684M1UsAj&#$`m$&5{W{lY57^V<2rK1aMLN=C9S?d%McjXBZ%vy`rC=-W16bCiXd(Q zWxtO!-l?#T#$%SyMh0$y=fYX-nGf`EZ;a3Xcme4hQ2w%q4IT*`**ePqR*M> zAR`NaegS;@)ST9Yt*Pwg^E*zWFZi7@y*JoZzKWo}nM7Z(vs=U0qj)mDWTr!KL1aEO zYHC)(iRVLzZ(Uil*` zUs;fEkkU8Q@X5glUS=pq&6?S7h#H61F8*Het#bP&ass^Lp!eErn;R^^qnGgdh4bu-+=>ezl^zFED) zl|Ksk{w}72Z4<_Yw)^&Lm?jsK(Mw4dvg=Pc@{byHJP=W?MJLH@Ljj)hYVE*-)mwzq>*-map=bm4?cnp zGWv@-nekOfzbJ>0E@amjs`7RGDaO}L@wHW6GF`_le#&BWkhRFsb7p*f zWITp-x%^A7A@I|yGGhuWpQEUR|r5wzce?pO!-JiCkVcQT!XFSOgp+e*KO z4sj(jeLZ=YFU;qE-*6P&x1vpHNqqXcD1Ae|5-%ZCS&JM!XU5k{=Etzl;QyrbaTX>0 zZ9e;TEXO*)xH<37i?a&tLGZpdKhdEg!oBa)=lm+JLonV^2rl%uK%+CqR9ufBuCpZe zv!KJd_fpU@1a1k3;Qh32JH`b&>wiz*QRtvaiOpiOGxqmpvhK$12Ju6|k#@THA#I=K z_aQYr)J%}*3p!LU*Zl`oUx#4aCx3Z7`{D9bB3wHop0Z{X+auGkwR0>gR~{ zsP;EjUu6Q;7yRUJpDo(S;-xK(t=-sq3dMKjU&%gIUq#T)`I3IEe z;<_llU$%O9u-a}uL0mV%y$$hgJjOSt5LXei2QR^eII5aYLaQgZCFCJuxJh?mJA-xb zp9WVrqvE;*aXrNE0NMM@$Dtg~oo#YpoR{N4Hp8{KFkiquI>Oa59!w}}h8sjZ0rUkOmK325t~{&*td}I*v1*ZO zXFhTsosOE!__~Nc13P=YWzpGLuoU(WaKC4>Jt=#lk~6qy#y1ZII-oDi15&>=&Z?sZkmk@t%Aw;<60-WRar zO=f)aDO~6q@g_6e5W$7{{DX^&->>T664W8I9NPooI9#C<8|B31A%a7n5*z;OI z#g#9L;bxNl2Ju7RMHLI<2cMu0ZZxn#zkq(+^7oLTjn zv#5T~=QJdvH-vrx{Vnv1{VM1jPcq}1K|Swv$G5{_KCexk_|_*wWV}FunY86X<$LUH()animpcI_oqU{pg9I1G`Mv9(`-;Yd*NL6^bVw!b2K~6x?$8iekBKLl zwVR7P7ZCKlzV>-ohR~!SFW(LkJDZ%cwj``W#FNbUdWoIE{X0V*8-6c~>F0bNNFMP! z;Lm)X{9CYp8c#Cg>%5M20DWgXoT1Yel7*y71|s5PLx3lr+l#H}?TPTz3v`H?Z66;jcDO{f=B(Y=6^^ zJR|sDSl6iDTw+AT!sFwa1Tz=M1`xTt>IY)<2=wc{a+%9`;_7=hy`v=Jbc zesJ6KEUeOvkFSri-%kbyboQI*;lnMs8@C&Lp1+H5e^Vwpfc@?`|8oJWLy(iN{SC|) z=0Z(p9DNXlKXE0s-E{jRXkwwp)ouI#tDA2obN((@GNnVnKnKq#zIKzEM%pdjSP}$N zbzsGFQha|m;F~&{kFOKGA?OR^(2Xzk&rM=^uz54S0m}dGHsEU;!^hXY8uNv@@#4(g z5LU*O%=mhUzA&zpzN@*;?Iexm<13++E!BQ|-hM-8zgFZ;`4T?~@!8Q9|IW92bc%ln(>Uw>T|Q#&2&g4&zA$g-uvGpm)Uy0d#vvVm)S}v?;?D`Kh)WSTJKGR zLQzhsd|AI9p!|BWfnU!b%C~<}K-vv-X!YPNUEF8OuP;m7g#! z#J>;SdHVe*QW{=T^<^(+5&r;V(Em=}yj4eXutlQg&2VkRpMl@G*=6$Ijv~UfFUS1? z<}Kx~?4G8^zmAv1*87sF=gTesMIWDe?zQe0MnWZ0I?P}4ROc#1q(eI43wHMViSKpa z^O0Ng@y(>{_YVVHg%j6J`~wWcZ*6aQ@y;UB!AJ4^(}1u26TbeILvUdpV3U((v2B~p zi5noeFm66wZJ2J{%xuHgZb>^L^OiI7GGAx;rhdw&Lk4L#@DCl|MRUUZVSLNZy?+J!-We0E^=0co-bHZ1 zPxfl$)GaHAIB_#5+@}n1bK6?>W5ex0|I64OP}n0)H+UXt;tQ5K7~(1f7v@8AnhiRH z4w{tkA|Gym;(K_(_%<3)lu3Pw4>w5Ro-n|5x%hBH6z;hd{o1p9Gy3r1O6j=WV85l2 zTvIpS%<0RAYol_m9)k`EX@|3-M&B zy=@n;?dE!g4>yUzEpLFEIM@=Gr4r8DNxMOu>T4*2ThpY}JNW#Ao$!Tu);AC7*SXw7 z`1m>r-%1F##O^^|HDpmH)P--JCBKI440M=nphNO^mV6UfE|5>AbokythdgUsBUs5s z;wV_(`J?u~zp#ZeyIbmD$k$Eu1^?Tp+DZqDn>dqC2M@u8@uJLBcZkKce{YG)Rte{W z`Zw#GHo!9nZ+_*OLFn>ve+ZyISg@M+rzyrr8TXIbMK^QHYmgBvNV z4#~6m___&S*v}i`TRDlvO?!^dKco`A&|uwPb3Dl6W<76-%T@{JGbz4f4EW~$V5x(l zzD|m7PXoT`*?hQZlz-S+7QCf4$$j{AklomyfuH;$ducZ2 zKA#R=q65Td`RyA#PJP6fUYhCPUWn}haNp0rZ;U!03JTsQ<{`K+UhJy(-msWRQiaU; zdMVto>&||z@|DmXSl~OYk{PbF57&nck+FAw5L9txL0lhcHyAHIKls2F71wh^jIWQZ zBUVJXfl>aC(LqLkF()$}0(W71fPS2u>pvGWASq~u>!;f7?#XqYP<8ML>Z=f3h|iiY z>zu3Nx&(1^cSY6-p1oXWfQsu8#8oJJc;?zF1W4mR39Ry|4P0 z8#`6LQX{eT5}EKVfrx&*_9ogdEGDCuQc&-2SI~Y#q`!ebyZYJek=CDF zTf$5S=>Yz`iKuw3(n(`fzA`zlMbYQXaBU4D_E2*46T01k9; z*4B)kGsAT~jQtMWhqv?4>a(g24nZB{bc_r0!uuu-M*A(rWb{&U3F6wy;C2K1{V{iM z5a9x>C1MyHQd9b|Ie>V3@Y z!9nVSzU_~t%u;b(g19+Ha6g8AQPF?(0>YKiOUWY`KRAhri?;+Co_~ef_Pl{ldJk#|tOW zw6mCuUP_9fz8=CC=CO6231tChJjsl2#v(jlml2rz^KWLTe1n2~)2Q*{@m8*!c(_7Y zGrk_;*I~Tay?qx7BXCLO7S`SBeavt(iT##B0QS2ool$j=4vFDzbsMtdfpe)!Fd}!{KA(zcV+OL|d`Kbo z0Q!FRP+*9P>p{QMV2eQ!GaUl|MB=k4hkD*01C*wS8Llz`>sS|+J~VY33>&hhqD96G z*YN?yt%d5RjjhpFh4FZX3VpvY^=+&J*qQCpAeaYeQo3Tf-=Zn6W-`#k4cZ3+)DN%d z_czsYW=As}vMWXA^UoOU``f*I>yxR0$T4eGuddAInInf=P1h@IVMz}LB)k8d)C+sObomlM}Xa8Z~h zebAvTTG!Af#|l2aeu7&K!F4?JuI@gNv>ZO%Y|`JL?fU2J-L7Se=FN5Z>?}y}eZYWk z;-{ATEi9FAzJO{sTZ1GB|1>F`6F1$4{UofPU9E9sfd&+15+?BRwT+6{ZldjMZYcv?g%ej!!u|mQos?~>QnYNXb7tebi{e|xfN%0zJ{<~D zBKA<;0N2ln>mvRP=2;b|Ki7`^$KXG#Q8hs&JMWUU_PH1 zoc^9Rzmio0rjgi8guH@wJs`I#XCS6XHY20DYJHSklzV_`ycL`_H$Df zB7LhhU$ze96$;m3fScv#>lYGvjy<$nyHCFv%D#8OHa@;G!G->|dB?>!SzPyaK3v}- zJb#0A`$_iCHlTGF8NHMgavoksOJ?m>&?4f06E5z%UN0Jm!8J2nH}MY;_f2k{AT>0o z8|{=CZvJNMe<7w^aJuOT79+>OXAc?n$hyXWg)6>eaUD(geiz2E0_zKLYNsnppHvtn$4@wK}LTuCo{f2e?*5Nm*=7Tu8PS3 z>JeP8&ZEB9+}_}Ow|36&Z~6&e&^PnVJ9+@uc#@e8PGY~%FBU)DqkEy96&LFlZt8n= z_Ub!y`%Vtdd7(mdfQ^7U_t&ha@(l{Mo0r_L0qeiXCkCVSNut={nERXI{Md~mNbr%c zewK1?9|$8fDdgvy#|9{S$VqQLK;DYA zz4n&+ez6|S>{nWZalwA&Pqto%L#&uk&I~u3j6*e0nN2rr0Ix|QCmyFXC#j4XuKyLx z7y5Cz>|?t1U;A0UannY0fN^MhFr-`OqNo|ZG~=s~egQhXvGIi$RmD7l_8=3!(2vjj z@o!s0Qc+Ht@W>|A)pdbdb?s%*hm&vIm#Fmd+j$d-Bqzz{hpcsRxe!vixXyilhFDp*ct5WjX?Kn$VH@Yko2os2=|A!Yc{DZ5fs!R zkGdc6#D-_CskqW8F@2>Vu73yO`}E@HA?}mWU(Cr&-+a<;u%6MpSpA9UAjb@f3Yy^- zJc;8;SXX|mbcKlj9VNDZ?4b@Dg&A5W5wN!ud)K$8Tj>{jn_<3aUFuVF2War zmaX@kM0OTmGUF@l#`;!9a0~w^Gh5~B66EVdD;dz=N}<31UVjDMw-R46<10Uc`NDm= z{oXpLTPLu37c<;sf(tqvcW*tQ>fjU9A&uxz8sRS3`h8C;e(ZHKzS(J!d6w(%NoW+s zC4+)|Gl)GvKQ2?T!G|iYd_>IecnL17pVe(KsL1xEC2F0vdI9ufCUHKe!9hMRtVeym zzkimhgG*3{Y^uLqZr$?(1TQm;qh`(Q!A0y0#lHk2E%&kBdVZiefwi*!DB3L{z5*!0gCS$ z1HKst`S^M$zW*8U&DqDt*Yy>)Ul=!Ec<{!O!hTH7v%0W(T|<)se#*`kE#3MMThG4V zlCNRAWm0yw_Unc)d}>m_8dpyjuLS<|4`{hxqoTm5!15 zMdMmCzGQI|4_opzv@?a+FI=3p{PYtnZjLoBTP2*g6CEHhYi_{T9^~U2p!m)+;2W^U zHRPK|^o6nLO@n@s6trwNLw&O;J6mL6XBpPGhI|WlVtW8PyJ%o%xz@ObeEozk>@)nF z{Lw7-&HYC$+l{Rf&WDJ;!1sy)U&j$XeRC+j>katkaN;Ty?jskz(fPBS<9s?Kbc*!j zgtg9ttXR2!S&o}*m2lpFCm!FRQSWX4ibEaWTqE##!%EaiG`<8-Ay4A7UkCZ! z-)abV|KWA8AD~ITVwSju_8^mXE055cWE?>2M%t86!V*_of#f{palZl`rVZ@qVGAYM zEO8C_+9|&6R}4h!>)KSn%a_<0tXEg8a!w11a+$sO=5JnN53sIW{;wlzS>Vi4mO8Li z!ud2}55V_!1HQqh`S?1BzQDJ#0bfTMOTLEfmP^Kq5(xLYjQ%l6E^CR))WF#+(r(b_ zZf~#bWDB__TaKG-m2h5p6!&8o=W{N+=3@(`RpI07ONgxRWb_O!W^t3B;PYo04KZKP zcg3=z`~F)#**68;cCA>p)_Jpep@;A-g&=kmeAI3E;T z|MjCt1Z)h}cV@rdX{3rP9gR7DF#ddHu|0(6Lt~Z&*h2QF`0OD-_*O)K^QZRwNaZUF z@=YXsL5qPc^!Dp^@$r=oVSRz`^0Sp|s(f97eC-tOC#StPRa}oCu2LJfJJ{Lp8}52a z#q|l|ItgDGkE`GHD2OZ1!F*wT=g8nckz2z(NWMet{xi>jNPp|_&~4~0SZ&H{ z#pfqolnx78M|6;miS;)H1$Sul+INvh^}3|M0tSHQH6zro`5< z*#pbhPw6n^t+hHGl5+TT2vE3BJlO{Al4z5Y6E{fw1L*t1yeFnr0;TQ7)0Y3Og@*XzDtBbU9NRXVoug0%-brNd`y z_vv&)|ueDPdJ?cBa#T;+uFqD@0?$Yda@y zfWq~@xgL%4+LXqL8zi_e&X4QyRE`!E{U*k&*!l%qPd*><59|LKQkT8%yT-Q;BL^`q z_=giUugz5B2Uncq8_Oq^dY;0bifdq4)}-9mV;e6tl~5)~zRv)@r|RK_+tu+{iG#1q zf}*@!2ge_v!<6k$2c&lm3Pm}k`Ukd%>uanp%)5Ubb@MKjuY6oA-f;&bxD`WV3RGN& zC@#7G0sMNeH(x`1<4a~b_<|9>*ON9rqS~29kgq~;Vg9ykd-=log-;OIPx>45;~n?Z z?u`zbl=hExf0H#ea3+(CL(m}>9D8cN^r}IjD5uQymC9jzg7M;7$-1MXKp0*!!wsSl z0{R-*@1hHr(W*gw$qd&!8{@(}>r#zdh3)3JAl5Hj*?5bnVvGU^xFl+XFSMGu90 z$N)Fvk`v=xJ`#|@~gPg2{C;YN{66<4$=-j z9fB0@aRXc*C$8-X)))MGhgVkgRCRC&>L3llI>LS1r>lLXi%Sv%d^*S!->#Kk_#458 zQ*g^`LeJ;&lIIBAj?gyNdUGRzEj*-i@>Q-!_G6!EFuaMXuSZbdY{Iu1V%VqpOOF>4 zB`<=Ud=rmizJS};05@$XU%UC6VmpKR#Y5d&oMHJ|<<0!0o#NZyfUhl=FOG5$I|IL7 zqmpwlYBw3ZloY{sOCJ`|H{F1*{5zk%cH+-~Z}#RV{!sY_1^K2DePO?4?Vm?={ld-3 z*F|uvAlw$8b@&$@G|Bb{pAOP8Y-gZD-#))IQgx6|iuv^{s@?utlY2}<7G*Ma$2Nas z>v@Qs!8lYuqv~muuS1ZpyD|Q}fIF{VIq1&Xw2Mz)AK?q}Z2-Z0>zvCtL3**Iq4ZD2CB852h4WgApHJ^JfmC1K8Q<+OM8d`8ovoDx@C+?z`Xh{*mSy%WJcK;URt!^c{cj@h@4dygWX8 za8WuODpALy>fjO7!F3(m1L&~tqoL2TeEl`~;vF}IyWarUS&I)htvil)z)#+L^xMs< z4od9zpRpe?ocED-104<;@Xh7q>n40*UwTK4chD@nn2cVcAJY=+Z+?pJ5d*%CJNWcX zIEM8FA91zP_4F`T>R*r(*G=pf2B4-VM?9|T;1JZou^a1%7Br-BO`jW0Q4POLxRXx@ z55a}`W{dvw11zqG6W2-NYVZ$rN3ST1Cq05XC=}nn`sw)=aPm#;f$ah8_ua%x6V!I| z3Gxk6d@mXB&8p4UZh<_^7v=#eM=vZ?`6_YpW%orCvfc;n_Ue5%b@t%sVtJn!s;N(o zJ=lK1&I$~4$gIPsgF^fR#1BuVyqv_ob4Fc0+#u=4fZKENhP|r3j?-fPOs4!!*OAlE zJV2XrIr(}Xjrg+}P18|$QcMP9mmuF{if zfUmtCAK!Ee_cjCEY))J|(E-L|Deu$;qyxN?6hR$4gfIBB_pZ&-&12>Id^))HVmqsW zaNk`Fy z?9{eUhcjY26W{!}fLaGXwYVbpIylQW zi_-VSlpXhJ$fAsGb!>cDT<39YXQ1yJZ+z9A#r1RIdI&D)TWRgnLs;BQPFyJ~!uR#- zM}f9B{miF>pYVl!vb$2#kl)cJCns(mX}8h{uG7Y)DOyytuFQ!morvgA`go7oEUu3e zS0=dNf1lYkdmD=@WyjXvJPVtI{g+zbMZPx!@w&fkrM~KU^;pm;ws@VjUpL_kcJ}n) z`MQ0E#5H{OU~i1|1^+w!{OZ;!Pxa{F#PyK*Cd|7(eK~c9il-jEG2;3gYV}np9a>$M z$E$eiF(*b`R^K4O1-?y2)SIf}smCBEuI(h&7y8>C`7w`*rydj5^0k|T;DY`BG`$0w z4{4K~6W2xI_HMlSiWU|9mJ}zhm)HZ$-!{!2g+?W9^2CU%t%a7ep2Yf=L>JmBCD_ZB zd38ONwFf`Z0r;-Ut~Q?q^3I9PKd`t#${t1@J)yhbz92>&SX|pFtONLmDZxcL`;`?w zJM-_0tiuc&q5pnBkXHu^w^4_Wo@4b*o6D!KgXjPQX7IylO<3I27BBVX1Y`~(;LS<ppR(x?Z9P-q#i&aUaAFng0%Ntj=SDg18>S7wl}<*~D`yu5?jse(dRp>jUoW-Ob<- zS5o~iTPZ-|DCozogT-gF*RAqqxCLaqD2)K7y&Gtx>JTgu`+az_!JGTY_eH=S9CgpU zDZOM+D9S0|D;r#w7hwN;JG!=_|6>y+mqDQ@r_6A@|Tv=Kjb!?QO4CxvBCEejIzh zkPY59K=_tH*G_-*Pf}6w4I+;KIuu8Lbvb`0Q$}^!{RQ&{*^p2Lxu~Q@y#dw0{qT_#tpWp{X+UA_I_c+#C96% z3j;;_bz2vyxSlxtgAr~PT3Cm6gBgH-?af<8Wul!k)7Mrl;vcTJ>%LOz91TT(%}n2f zqzK=|Mab7reQ&YrGt*v>D(N{zJ7dPzM)-pNeUo#&Pd0et5aoAvPtL7hRD5&E^Q*yr zUrdVFuP+WeGvb>^`SpM9f2?WP;0!*O*(o!9WvXBN6z&&VgyeO6ajKo*qJdZ%aeR14 zi)x)S>lZTl-YxXwp~L&^mcFsZqDz?RV5j_g)%=t=M|tc`WcrQBYX{*A^NXR4mHN^s zgF;bGnelZIeF66)sUs{y#FfnSwS9s81B@3nx}f{d9C5*ts7qhRL-<0R`b2Jr(fSh6 z&zSL*316_Y)u}Zfllnx*VXvC$>!bQbgFM?mY(1;I8Q%ozcjc}J`j3?2RKg5b%EjYj zO+>7z{f;bYj1@!ebu%3tq+gUp#eaIZZ$E7<>zo;`i^Bb8p1jTe zu{2&=&njoeS2~0H1=#QDS`Rg`!eOtQ;vR_1vzj!Cj2DXFc;O;CBqAc2fp&AHOqNmf zycu5`(E5$oX(&o+hrW5;xb(rsdt=>nSZ_07ZV`c4Ig>xao7yR$Ta~Iu|CK?oqa>|Ua zhvK_-)guT2m-I9jTb~S3^TP38o<1jeqmVPW1T18O^XX)L67Fkz`AX%U(job?Pm10*%a=Tr@k$&;yOZN>l%Iv_w`Dpd@8O>5I68v#Glm~(Fwvo zO-dik_q`5<;(H-C(l0!5@Rc=8aK?Q&5}#G+bN7$Z6oW!hPMO(R=3SBJy}nxY$Y+vn zhcgN&x@2Z&K}v^ju5>}eJuc}Hw6lB)H*sP1OchrV)Hg`Q)#V5N@gLkL6i+hKH~1p9 zf3%S${WLh?w1nmb@gy@`iR}A>pUl6lcU9@Dcu=uwvOyJv*co()3YFUommV-E6y=l| z-!v-jyK#J53OsK)o@9obPu7hfo-Al^C`IZL530EiA)*85JNwsxUxXjv5eKvxUwaVu zW5BIbcH3Ry2O<{%u7{d;r;Ya1l%9_R6csh&n@h$a*q5&U$HO=)vwFP9Wc zm!6G|!(KJR%|sV~FU;SroI>mNajy88;krmahIwq~y~}S&uu&98GQ&-$a3_`e>6X-2 z3+ioVegA{3trE^9bi_Kq`udKNCof2^7!-=6`j5jg+A+q_nZV&r#M^3Fm^r2=2RMuC8H!RLz;dr>}?T5Z3o_!;3uY_C|c| zM8FKL`0^ z-vaExD7kNoJg<1%TfN5`m5FxF%+9jV1?b1%AGW67>yp|;L(yL|<7@u`UdQ*1uuCH87@xuFGx6RQojINpLOZY>Yn3zO>pl|c7s{6H*%Am6M>50BrgUia+|n)*4ES** zGh83K0QL*|b}F-}OLzga2yp#`FZi93(-&Wo(7b?737qYgLvUf-{HhbOU)?uR=y%b- zHq#-S(xJlnJ)cNb^mU`1F~e0TJ8SyS&RbIZXejz?X1FpLH=*5X92}Ej{3|bdJoStj zZZ4(om7z%AMrsXwbaRfIcET6plDyOTx578_P|%)IeB+y+v>W(e=d{kHCAi@+j%22T zgUsI`jBJ^{yqfe{9H6ME8Lsz8#6Qd!_~@_FxAEgPFsS0Ea0f4Z;ezBgC=}(C8Q(l& z51{Y%lju3q1EYW#TmoFfWXJ6dpXJXQN8U6n6Xm2CUxnxZ?bfNw-AARDqktG(GQ&-# z`rGSoS6V6!FsK~ml$j2`?8vxzdUa*AoQO+$&`$$`U$#nSxLLy^>u0b3wGFo6G$}Ei zufGM!JQlcx9-4YadS3%;nK9$*J&XCmu=d{Cs~1_IeDny-XnG*r1hx+3lhM2i>Vf@s zT=V2sI7g?1L3}#olYRl?ThjQB#lvqv0q1f)uh`i)qQkWx#x0~E!!I*PzhTd-dC*r@ zGt|-DIWo?FJSAxwyRH!|$)|&B8pehFp=tlssUdwwy=e?D&G_1mVqBQMK2a%YgES%r zFsg_du7WOrJ;1oRV$bK_OUdLZIy2L5N27-}`S)0V-(S{N3Fpu&)>m~jd{KJA&WX({J zN`V;SYN~kQOMf1=Gr--rOdlcK0^v z_M*X+DZf*7JDObFt;Ka;w~R})71Z2KtS^jjRcfw!SUnxC%9k_QxeLTkx)LKWTu0g{LUZ>sHGie zA3LGLEN`uYt`0ikqsEJz%qEMZ*+!+z&mq3hrF1E;4Q@B^zyHhm6ZL9s%HZVdCw##k zq(2)CmA=>FTIJ02^^@N(1bzQB&^N@%H|WMXKs>qc+s9f+v#c0uubb%`r1YI>ps%+A zr#%q=3w-wvzoRqHzMl3I;9TG}tOML%?Hk!#w~A=5Xvx>m&g{i8F2sG``1C~ztZ|L# zN+D{TzpkVWlx7+hGd*c$XU;(p9cCElkae4-4uGhBem3ZZH!4eO4U3tcG}9qO`Lo#u z{Wzg7A72OI3nCqFw)IJAi77S13ub)t$b269o6;c8%>Y!#3|FDz_4OUw9hR0F(lR}1 zhU=#MWbq0ubmN6QhOb|s+qS}f2jY@aBU)^ga!jciUO?3i?Kh!q#Ggqmz}mDaGlkC{ z?DydNxnSS)^A_6|X;H0nX8O7)JNy3O)6=C@)>w22Gh7ele}i(xRJsnlwvFX$HxI@4 zER4rLvB=T$X6{Q5)No#1{n zDX%-9zHlFf4IzQP54PHWU8<*nwal358#s@3sE!Z{3eb;{F)8OGKE4XoZk-L<&G#8! zySa#+LA?I+*K2P{cQJ%5vPcKRc5_he_NYO-1s~k<9z!1$oenzjfW;qtIN_; zCh_TDJC6Gs=+NdwEI+fKtCSWqwWb7C8;N$4ms4m|C32~c9H6{$kFp= zc9u^0^*O7iPLk?G$6>FU>5xWrfVi)Hse7)m^)g)6I>>A#l$S}nK_~ZaYu!%TsV(Hc z%D0b`ORa;ykvzAn7FCiwd#vrOBwGpP9fWWAd!f_%{K6KowY0=F^k*(g-_8d5=Jc`F z*NCs1+%FeiM?Ci1ZkBJdHD9($IBzHM4&YW9_~65Ap~U@`IvC#4>L&UE?%r39>(&We z)_e{1O(*(7{3}29t!|u8?Z>BYKKVWltVAtpaHpTuA=8>KTP2*&OvU3o_{rZEH)+lm zN;+(+7cFxQ{xQV{tCo8p^AYHi36>5Fyd>=inQAWKE8$@FE|L}f=~$#xw3hid5JoxMjcXUpU^;IlIa(E}Tmya)* z@l7Ip!B6geY?)3fM?-7AMojEyu)bgq|NHyEb+(LSytO^Bbs%3rewP;JoB!*r{~c0$ zH$Ge^#W#C&*%15Q2_N#|I*7i&_ZtJg361#lbyIw&T-$Jz<(tjPH;v-!GvMoqfv?Vp z5V@pHk$zG4=^O{k*D7yjzaC15_sjG=$>OAD^0k|dJWm1I?Rx_qQX5;hn~@IEX6z?n zfnf66<>UNzY~kt(`!OXi(E-NINw+Qkm@SaZx$fzv{MoWaFN|by6;2%-#2(;&f<>;U z(d<6HWM&VUls{`WzD6$=H93i|-BPP#`vrUGHKBZW7S}3o#@G90#7{n-a{O-=$MXgs zUl$qQz#cAhj+-nO$OowYw(O;@nF9LoQeH{hFb#d?3p$nSV5dvFwC+$Wul z*zc>~A~J)}*A*`1ppXdCQt2Y`4tN|Jl3p z_$G??y^R8uGblm@gatXm9T2gK$npiHAWGzrDk?z*$|0tpSWzT$Sr8#8M^V9Wh?O(o zRZ$@vLPd^vVZ9*8RS_hDNCA=GyqTG1GP~PNW>bFuFrQC4oz3nu&pz|cJMYX+l8C}rL_gX*Z>HolE#c(&P% zjlXY&zXr-#L|<4Z*qJ)LD}PRCvY0<}F*+nA(EkQfaJyL$(c`e6AkL&`XC9&h#FM$c z-DtFnPI)n`YiQYno6%wMh{X9Fnb;rHopx@!lurCT*}96^ zZ-}wq4GCOV4l+7y`)|-)NCz1>drf}-q?Z{lMla4?2bgRs5F9T;#2%_5utw|u9K>S6 z|GpU3qqO{kbTks5%}k)aX~a*$bM#F&-37y3R7ziBY!6WvkV5j2NZj|(nc746bFyOC zho_~3%;=CeHgSH^L3AjKi2m=dZK{63^XJQY8B|Uw8q+dXsddJ8A zOyg0LW7wan)i11txZPm=ci{7h>lZnUJuK?eA;j}FD(mTx&-k;o6`xZ1Gq<1)@Vz)N z?}PbJ?ug5pY__JH?>GB$XUBR`+<1v2?l#3YLb{e>;4l%#uWbC0+0@q>O zOuu+(M&LiKdn)Oep1#(j5&xU2p+mtqV;!{W%@`ZOy+Z@n_qws)(ZcmI{bEYzfv_wU zSJKnLMsxuGFz&tmU3t)~*OuKFF^re;y;j4-&17EF+f@C~~=OXofZk;ecsSq6? z-nnCsI^I!wiP=LA(E;W|<&+t5eo6vIpISQjNq++!4m9tFX7}+WJ$p!J`bEy-$*MRi z6vKXSEhb*Z9=z)hp3pj{q+@z~Z8G-1pzp5Vws$HCL+d>~TxT}!$FL55r0fJ6od-y* z%soGLEW&)RLAd?)FB-1Jsib4TSIZtGvcCkzqKxZ%s@CO7!i4wqbg+`=u`s@+H8`(Y zhY`h<2`<>LeQk5a2#0@PkFWAO))#Q^KJk`noq)&T%X+vDf(uV@9(n%Ao&0r1Wj)+v z!}T$^Ro|_u z+Q+X8NZ!!H4KTP>#>{POgu}nDhwEhe+n8T3%KUXkWj*17gzq&7VCUkO(0X-zNe|ab z?5rGu`)N(@=JBEG`-dz$wqKaPxtAtxJ|7}F!2DwTqBE$L_>!IuZo(G=sKI{;^*60< zA!QR>Fx;;-MtS$&V(XI%S&st0^YF%LFUO~Xe!E#~;OD#$_er1bx+_t*GFs8GA~5j3 zdjqo)7N;r%7sMa%XYI*};_D>1FurZ8(r{YBa7nvCKVH0R%%nu&y2!W*e!asd`|BkN z*UPlq()G2QB?>q6N5mfbTJPALDBJ+qcLnFN@^99c7wUz_zxRM^<6yy;A6a3_%oaxDEkR+Mf88+`J5meV^gZ&=U5Buk$pB32YmZ6iwXbd z-H+erkJGZAzNuDx9r*Q*`^Mfz&!>4HPi!0tHpBCt6a=*5$elfD5Ar(A?I$Sci0uL5 zlGP_Z=}dXXn(OHhutq*lmgFk`Myz=BJU!gtHyF1LI`QFdkK^G)a* zH!LYo*@G8-7cRV~m-P7B$T$xj_^l-s&!Bdb(Z7;X*4#X{;9ATFaQ6)S@-d3*G>I#H zhxLW8XSi+N=c;iiv_nka^d8vGV4dLBt-H~D2rK3`$=CiA#s&Y-YMc6VmKnE+tsD8t z^G4`z!7*>3eu4Q0<9rTTG{13_-8hIptAcQ!=#dHCE-Lw!$Hte(brD<`hu-|L!}n33 zs9=3pY#q@}aA7*Dw5NB?I~s@NNBbi*z0*^^Vwd;IH#Cd~=fq{Kvm< zRMz7gXoC4dgWY{|msBGh{(Xv@_EWSygb3gA=zM;MZc5!%IrR zudXPEmvRGsO+h)l_@t+=(kT-6bv~4_t(b2dzvs@^1!WJT!<5RNXDF^R9k*L*ygJM+ zT^+m(-}LfL4pP2B(r$$Y`+`*Mwybpd`We25g4TYNuk<(8H+i|(xEW+{f4pYqeu^s- z+<*bDN{4NwtV3mdzu+HQmVN79%2z=PI*I?4 z*O%OG2p2*yRSMmVaUtHRv2E8Q{0T0D-z`zKTiJ=FI=&T=bpm+ydEJXAF7bSg$~@oS ztCud{>>d$)+az7=#PdtlZ#ohb8?xs@7AT`^EN0SxJ9`xO&*df8XZm`ZpT(H~x}vImqz!zg4uFKPhXI z7_M{@>kE8)REJ+T#fr%$=R=_;7#Gmc&sN9X-}Kte&hUMFR?|h4uVRv~gTb{wHG43{ zb(+L=Gq{%FExx0;67j!$JMv{c9rA9%@jC4PeayQOjTiV#xu&^zC&cibIPCReT(3zT zRZ?w9N@*$f zIbk=$_thV&cBOn}ll{$4#$$Nyv?_t0W0g*0dw}@t;FwAeP`*Jj9;3r0COta~ka++E zZ+riIIG+dc_7aO9WWpD4%hhbY3h|ZEzmnIazPV(-9Qd;vs|8-6I{1g;xESgvDe37T zox#_`^ML6yueqD@4VuK232t44oB!VP@Z4WUub7h_-vVN15bsP&;C>i|;d^*?5n8S# z42GH0x2O${JL)06?;Z3aubCJfLjS}5p#}nM{D~9oUdDW#CdW6I9rrir$Gf)uo3OY< zA^oBf!d=np>YgYIr{K$@)=V5vOZqu!4b=$_f(w4V`uC^Nsx8)6uAONL*F|u_@6-uA zh^#I#?dBl!*vbfSLfOY>({__==He1B;S0FiW>$voETdPnV)PDvE5Ozadk?xc6wnlQgEAq%h~Oz6iKkDMKtD8BC2*nh)#+_vIF$B{+C z&=GUevj>^*t%8uIkF1NL2}zC_6rHGt>v$gP0DkhqS$7MR$>yN_H) zbpZbsOVYzlxfk<=b*^4xZbIy%Q^+M2M|lZf(0ANj6?;>@Xkd;h>G5?ic9t9*0jJ3^ z0g{vSaNX#W9ALk|H+1aKig+;LTs>ST;S2ZOv*zMo6NOvEe2!|q#^+G{1!C(Z%JbMy zRzpPJ)WEe1{w|`6!F^i;*Z;8CdQ>*^`K-a&=jQVI27VFKAwc+|jwbEAboN0W*SSv& z*Z&H(Gq4AL#V-nZT%)p{ok=g?c7uIwa-H`V@Hh_9@6BiQt*3z-62$d0{-IZun>V2z z6rLl?9&_<}9>e!04ZhN#lGlIr^bIh$jWuxdV)#COzD=NCLN{&x3ky}sqOD$EemA&u~@iU2=5{Z4HjH+zg2Unju@f9Cz{qRO8Y3>D*>#o#W| zz|A-;<|nO7v7dx^=bN{0Z&N(N&NAm8tS{nr10CMg;OiMDrf)jIg?`~r&v+GOQ7LV_ z7_Q%s@An3T*7o))C|cvvOJca5C$J6>^Q4SBhQc1~`4p4-<`R2=ap*#`G=*a;<&F@u zGiTGt{vGMZNys{)lmDogo#iq*Z1X?Yo9f^+se_-<;n53sz81|^lAMKNd<$A&9pH1f ze|+5=%`b4fx%-;y7X^eb;7%_;?+nk^|D;&Eg$ORJb4~bd!&V+QIa|dxy3V3? z&-jw=INuoSSP8*-I;Cuk50$ot`l{sLaeo7ScURf~)2*mfFj7okWiR%Vu)g#C@%O)o z0!0PIC59^#zR+%euHCSO#|;YN1{r<-wWe&~aYGZu_Dg}qqr=m0sdaF4E}5?$u4`RHhY1(d zIur?hzg(z2#)XX!ZGPE-hGoLwHFN$fmFaK8t?K@kl_sWxhu8!3x1lH1{Vmu{3^(`# zzTY|scW0ZcK1W$plJ612l?o!bo0jg~9tDaD8TX0dy4|?HLA<$cJIHDJ;>-^$!XFa6h?>UJ=eYkm~1L^80r9&R4Kb1wqJPO(m}O)CP_Jh^8jgB zq`#dx&@!E`*m1}(e$eFWVfc2|;F~Qt53mxx&@XCh{GM7q`r&Qxqk0MTdQHALgs%l% z_>+cn${HqSXO58(ecSw|);IZxp}v~8qEyBG4b~BB=Jgw)c~S`n^>pwu?dH~Kw~XOp zI>?NjrE2KlHr7G2-EtYeQ#AOx1?K^_!I62(pjNl#7LOONn;S3ejQu{SVZS-X^9xNK ze2o3p03+s-OE9i>yCU}6EYK5_fRvNgI?-~;kKzoB_nd`Yig z_!&DJht^j4U>&I z&{xfXw(y|v_gu?6#eB(edY)dcr*A&d_iA+E%q1IC`w8*|<8=qIGw_r59-h{g=att{ zY&;GSzVMK+|E@!S^0@ZNV)l?n{0^*Ze0*K)8>zltllI_bbm*<2L+%B`eyr(t3K$&* zYUp5nSxg5P!}o_X>UK-pg!?(KJ1y(kS&-p-_*ZqiWn~-k)zqPo;KGFa&8kNxQyw%= z7mQO=hD74u?MwdKOzlCM9rHM($v4FCU7*3Y@D)QH=&eQNp>HGp?EPJ9RPkiUc)y$` z-y*^n=5H^((GHetqmu1aF}{IG5q)isom)@!l}+j^-HOLe;QO)$-{hHMd~F>uU+}?? z_kPqLB?2lGJRs)Jk_lh1-$feskmC{K>p?5Yz!m)ZkKMjj`Sr8|hJ4YL>f|Q=0miov zC#%Od&oyH4gZF!^FFYrEI(a`@pG=a`zmnhN_+};gf)4M$s~+EMuZijFCgVJeZ=alh zMK!+pD;Vma+22wKUl`xE|8`h4z9r8VY-e zL?IZP{kHpoZ z{+C%uabwLsgfDdRS`U7nL)*=5a=)^V;DX;-IscV?D3j4E=A_5hPjF#c7wpdwrCQvy7-bFuD2=Pk6RbPWsm;tr}$7y;7fEUj{w*78U*lh zB|W}bts~>x)#I;k5f>;rSr1qK2u@$>(=e4@Dg_m?;35Qh{*~Nhe?Rn_Kgcg0>pDN}z`MC}c!G(VOLS}<56gOy+ zubtVie5m}~@f6qjPt1N@Q>HY6TMfP2XU3hYDX!Nft`*%m_+J<=ZmxK4I$wFd;O{^? zPDaMfI}T5sMfv(o@(qx71HW@!*0*0%+@ML^X_9Xi<9AL^O?e%`%h7~OF41=5&+-slSf^d)OAk`M z!Qtlmn}hTV@M+hV8~858RZQaAiM}wtJ@EUT4vOnEiJMK<*FlHsj}@unk`%$;XUJv7 zA@6I4(KH#iggbV=&{b6_z}T;~Pvai^3BfsH^EaguZg+@N7v4Bf_3?=0xrVqrm2g?U zFEYOE>0kXN{-m@%V*Rae)~t#8`!T$IV^6?4KYG){j5k8kjxW!dCfXd5Ly(`k~gn;GAB z%}ed8QFDoh^!WOj{`Pb5@i8TWXuPS18zSun^MKAP3*M(Xcune%j1&bQ3GvRdF20vF zD3y3fkFTHD1H|hqr$4URe^w$WdQ%TKo3tBpWK!qhk6bD~6Md8j?!zeQ;acCpI)J`O z1L_Vf#+_>pH$Zd%C%X6Aj~5&9#3l_s;4g$_hT>Gd}PKyWH9mM;8p(&r~1mT#)r%6pb#Cvejf;IU%=~-@ndXp z36JYx#}(l*5mNKVwl%_a5=ammmR?`xJQTpz)O3Ad|Gm1Bv*^)q~j zNWo5`xO_kM5`CdxJX>o)Lmt=mYi$03zb>EAA-Jq^!gO#G`-OOY)tkxXsr~v*+HZi- zcjl!x@8s{ts7&pQ*Vo64L-*}@#>M00Zxfqu<}>@Nn^yP(ru9+DVZ2`>>U>&olYP*z zKwx`q(Vz4<%{{%v*10msetYnf?eafY?XS)f-3LPSg?VAi{C*b7GuE888-Ko^(P47s znX3Ml(^pJ~0%B({zqqU6N;JQSFX{1hGy1;XWrZqEO*P(MqDiEH_;oO_>p$%_Q}d(} z4(johe#GM=*x8bU6+h=8as~I<1c|;dzsO&*K-F%1J$zY@Zw{mH+8dgn_$)dp1%~_D zqAwt&P%`fS^-y_Yk4mcfaq7=vxDICi)@RLx|EQmI=9r61d_;#Di0}PBeEvFrQ||Jy z`7_>6hL~}_`>_IW6H&<_=qGc?@A*I+HLJt^uc!`glR9L-gyX*I2zODrnJPc&s~DRO zQ8x*NGPr%fpLKqG;StK$8RtBJ#|<8g^tZ?69#D<*c?$%`d8S{uc3%9JuQwpL-zZ4t z0bmHB!7qP^bdb@%=m)sX*{@VF^4x!7XzKf6Oy*DOF|qzuMEJrw?dmR(?+taEZ8t{W zS&fzrWT=M!wayi5H|sxukz8GsecHX zY&Yw%$ofO?zLn?lI=J2!Yd3{yw`INuk&z|IfbBM^L)L@{-#WYQ9|o9g@_iu2*Gc$7 zfBUCN)p3-s-y~n>VQgo$5bm}zA5LPqhX4OijIWFEg?a2xZ{3Q*)g&4HD+Occ3rl3G zWFz(f@o%4{Pb2>joxFm4oy1Rq4qLBR>)?7#EPn7X?bd%yZ=^5wXY#q2$4yNg6h?<$ zAErk|nq2G?r6Vum6^o8+aPF{u2m?->LbB5nmawgC_arGr#Nk;?@1e7V9uSHapX6Hy3F)h#w|?Ur#mf_I)DO zZeB*;Esv}9wXHYA)wHt^883kEONZ5bL&mt!9I6yx{LZ&27t+uPvg)J~4j_FsQ_83K zKI@}*zqqRmnh!;%4Dx>T(MU-TH%RzaL8neyTILg!$&ss!|3kQ%`ua(`r67pTZ{3#4 zBPD-k*lzqKxO@k;Q+Q5R@6Enw-99>HJs^hbJ%VweAAk4Hb)%zE(LR1rzGX2ki1fdS zNB-e)jmmoM=A4XiAx`Z)KNZab64P$kOh0}t>-JlCe*VwJ^erUoQE)%7CKYd@I`Hcy z!Hf7gI>bBA9Qiee$CX=(#SeC}Ujw+_+y2`Zd0eA1;;Y#&yo|n{Y_-114l#X0L|@>W z`p-8ad^K+=gYW^r^Y4^qEBTXbC&cDMsYG9R?)2ucj;(oIqq3g9QYE~u0e)xfuj=1T z4SXf0uR?GkP7N+u6y*8YPa5i=X%F&5Ja2)xdgT8GLKc;5yT$lgiQj>FOPMFm#_~u$ zs$SaPq7I^hlhI+{`)VBu{xZ~ohYXi}Xhs1fVIEs9C3BtTNhKWAvxhv=-$2+Az0~@q z2gLN18NdGfvy%puKuz;4J$)aDN{LEi2 z8~?7oru_zpzCiT8%6}f^ah>0Y>1$`~ciV)Iz>MQcdOA4wVmkxC&;B<>wGSlgteE{O z4BtaFo`J79iYw{y^Vld+$i^wmmlTu3X&IJpPmjO^1Gfe&R_RnSDDUR3HvAOZGY58aTSxep;~zT9DLfLwoO}7TyH~je1n8nO@y1#<<&kEH`v4+Zs1PL z_d0}Yf4==Pge#+eCFurpxXJ-+XW$>^{<;x)dE62~ll#O98NTgUzRk_?&8UrafPOJ6 zl)I4Xpj0r2n@@0I92$S{Hy72xY0@5?%s5oz;r+sXhmWhR&9I+@`0SUS8Ld$km4aKv zo)2Z;hjGgww9KDh`8^6WhJs!{E+YC~k1(1I3~i?RdQG;Q{VcX$=*P2~?JHiFlggU2 z2PeUWao+aIsX3IdbP><%jHJ-h!CMFO1sz_>nD#Wq4fZ#On?mdX3~cae_`Reg8T~8C zCizMqV|##gxs88q{g(1oOyXJzE{qp>-GA*zah)b{gQUO0I>855-~SQH;!1k$<|F+W z_%=Mz=nu-*Ym#q(;KKO!+b$PcPbL1>ByNcDJ0sHqXg>_bmH#tmXHq$QJ;Y~M?VZt^ z;wmO_T{mKX1^unVp%xB`8#L)3LX3Y1HLo*`;yO+8wWdVI&GkdRDdsEnHK(sk`UT9h z?)rTRS~tS&<~7OJi8?U&NEk0Vta}615?|8m7j|L~!1wzxImoRM`!&f|A-K>lo|u%} zjp9m|%<1c3`1*FwXh(5nlekU>x9+WDkT=FUC?;{;MUnC1h4kAuQe3A=TsyHd(0Ad^ z1@PQ7Y!F_PxIw}fY;DuNmI$8MgGpTLxrh!m{TGp6$GDPYZk*4XhH-)KmuGtwk3+Ia zTo17aSO@=RNL{opN9@5Qu9va1S6a?`gyOnQ#_K6}M|8-%+p!~T49uU@U&ZF#Uea!` zzhp@6DHKl1 zclq~?%6hl~Vh_l@OG6smy^HD)G^s<7;KHKP*HsUqbr`}R$y|R6lHU`C{As%nw`J2}}y(7=JXp7+fk7uhFb(}ABK=aYB`=0mqWaRJSTqEmKzF&&EPM)V!K=3|xp7R?va!TNnf-@g}q zH9VRv`VEgIhW=O6&J@&AH169xvR54*w`i#$E`Le5TtLPPu!r*+e3gg9zV9`S;hV3) z*ZZy*Unv>)V~A5P%ze6$`Ul0NKTBu62X2PO_rN8;C&pJs5hQK5eeFCp%GYUf4@@g?16v7wgLw8mAWeer2#Lky* zl5p8e>`SnqrDhxtX*U+z4EGMUFNsf>E3 zroL{X@73tyAUZEZprzv>A>Uq7~G!@ZGz>EsAMtdioYJesap&|Dxx- z(JB8_YX8{zpM?1O%6ct%GW_xZ_j&5M|WdVVK3GBUn>rlEskG1P&nCGxL}8Q*-p zn}s6p#P%QM%f}_s{)nHHp8H<|9xd%lv3_hVisXM#J?~^S(x}5vtNWU0uTc@%!z8=1;H@*dkpM>?_Dg~=&^4Ap!@=arO_(4O5 zf&qs5YWnp8hVS(ne6z0>(>L%=#2zNqI`R_r>)toat!sFgcFS0?Po&-WCJC1V#6Q3~ zOxvxk6wQ-LIH=bzq^t1w1`em)-#wsv#Fg}L3kl!r5Zc#QRXraUC^}gWH+doUXEo3{ zKiyzMVGlX;Pjl_&C;QjI?@Ya~>gS2#8z8t~+_SfLS3Sousz*VVeA9>GegXY$r#!cKKcck2oW5Cg@VXq# zIa6nqxeaA9dc~ad?AJrqx$7gO9%-wK?ZJt@$^_~%N_x1;d-!_TSG=}LTjY1}nND(C z6u00}tS{_)9rEjzQ#_92J+bvDISK0vabL##pAYf4+5d>G!=y5}kGyl{eje8@_`Fa$ z5$VU@cG`53$CU&>_vIjbLEk@j&A*q&bqL}H-p1_)`abv5l!eqDf+x(`S>b7n3+vUV zpPqp}=M$Y$n~TLIX*Xbf%OSYKAJs&&x%iS^zsT;2?F<%_zr62NG@VV7(Z7j^ z8G<@E86A985~qWU@CAFg-*;j=&o@tyubt=%I#@DqznS_ScP(@M%~uEet?~%BZq{CC zzNqAGCFXbBL|?Gqan+y9E{{Z&8 zddsx6)IS8@GZ&WxERlG!^27r#^8B)r#nx$qLqY}^bHzThBhY%N6A9ADDoD_w>4g*bKF*d=XvRIi}E*2l1)1i!xPg}-b(u2ET! zuaCq#(2uWn!Kz7oNe|a!$9&NOjP%x<8x!_iI`9U@g?RF>FFx-PA6wds)K}#YzGcx{ zpWis~NTjXtxO;HSNyh8kP0*%_V$cp7q<~Et(tQ z@bBy4%ETU^zvVg`tfuWIlXX@ehcD~l+6gX*-|pIxv-#_c%6hmyMu+{=?nZHHd`S=2 z&9vLn-^bk@A1YN%eN_?pToTOZo6H~3pFbmGwAeaK9?=2(S@l~B6Xwsdi4I_AGv57T z5YN}Btf#M!_y-t|*ByN62dbE2(m(hadpKi5g*cNQUxl&X#}{$-^nL@!9P6J zeU6XE&8aSC4<4r7?%3R7D35DY*3-c`68p0X2;kMPzxdP$hksuW*Fp3J+&kh>Q2a3t?y`F#2nP)>m)irTs>#a)|JKm z!leIo5WXAqrrla@`b`y28iDKKItgE}2anRDw-FBiz872EAA|p$v_}0oKvCRW(vQm^fbQ+PA2Y(?-`C??K=^`R|Gn3@()}! zs-m6_*~ITy(G^LPYA@z5%>PO(o^+9Z0V3J!b$gA+H7e`rTgceMtKE-6coLO@e~a<; z6Z-`_8&RWAyC~2Y3VM9qj1I5en!ARFDiYks?;-vH=CPU6KS-E=@DRQ*9~zoB<_OQ% zsH|sa9x|T?JDcTOs+zZm;^vcfgScen+V46U;qdS4@%0fMV0>$9^G@KeGb-!h1{l7p z63DlJ!Cjp|+@k!*bG^FRW1i&i+qy@rzXch-YZAz}kiqqd;cEJITU#7Yf`2&C=VD!6 z2cMu0A;K5Ni^smXFJa@RkN5|;nP)aDBJ*xd9Rf^T^5TP!f}4m+1&ZPNuO_aY(YI~C z8{{ZZR0stO?MxFlMAqeC{P<7V(YY09=2bItJk-yi~JekYcgI}$o<}kaL>J9nMZNmvFm`Y)JPQ~ z&)@E@&v%?LGnS3noB&S=hv-mv3<(u>I>g>&!Bw$vHyOHX1!LT z0~pKIdE@$Oo>am?J-#x7``r01!t>+gdzwb=BeD}*7&kYyuK7QnTHumlKjtsNW#qx2 z&EWe>ayR~WN&6)Iqg02Y8n!6D3gHWm?9SmoALS9!IvV;j{*rLna|e#sVSZ8c`m$e9 zCWqgM@lP?|`HiFaW)b^^=OR<4u-gz{!Af$ z9mcl-@BOX%ULVKzvDpL9*Td-Wc%ce=0cw{9fN? zO~z4vq64fG_~(`XiLWmo=qwi@2ikZey@9wX}7aI|7p+HYgE>= zGnfI<_+c0Yf0aI=XHjS$|-F8?}dyU8YXC?Mk-EO5;Xv_;*SFt|GA`Gw{krZGB< z-y|MK@!%oC_geJE-O4-tDPP$nUnhx6K!-e^^DMDZ0?#KI(4l?>za+|a>nc;h@{p^Q;8BfyV>l%#v8;qNQO>cDM zF|GfK`5k#89&c?3Fm=eQXcr4+;5Dg377BF0KR~>5-OzO5`2~NUIUTS)z=oAUo#!8= z?ItyixgTo=Umhl|&iF_jSLenU|MGlg!VB!|nl8T$;NLeY>)C^cu?OdFwLKIH&a)K4 z7uFw+PR&Hs69xm#?cd2E<1zT1&ZqaI=NA|^c-|bYkLUnHQ2A|@s_}XTI*Y}V!DZNf zVctE~`gtG9*SXvrUwILp55YWk=M6(XqquI9xDJ8~`tGn=(K-y)*KZOx)EM6{#5)(#DsFWhO&pb$Y!Th3N@R(MVuTneaejLSv798aF)L^`LuW^Tu>G9%R@Ov-{$?sf& zPa9b2gKvuQ$Up9Lg6oJjtS{K_x|5f{ETU4{c`@9SKO%Ovcg~(EQJ|=hBZzBd_|}%H ztNNQ&aNnyJMW%GTs9FE7gpC(6;S1wt$E!DY;&qS&=NGwzFU+&3)RY~)V}3G#IizTkha>egWak84!c z<7+4V0t|QaKM()H<0u!!^tGWU3t+!6F`imh;No=23 zh~azbhIi2Cnxj+d4`R5=V(iz!eyz>dqIDx|>CP4A;*wwuj0^2{-#d?8q`1?Y zueT3wAHYprx~CE4>nF#fYf+c<{F#I33(py@e{tC({FVOlVtg~0cKi9r8P#*A`~ori zwN8rIL&4myRpXFN@OzVT7`_MB1ys0sKZ^17F}UT(@+3F77x9bgK089(GPe81E1zgdFc%bKzT_X~*6);3Fffbw;kj7ywky&Bdh z>+ML~_tU15^D0l-(M1)(gmNBSsC2H3tv&;CJW+*NWXyj@rEUH?<#J$mFC6^1x2PXFNF28 z>Q8h$60HJ?1rLb%$t?052e8}Q)|caPm7QYk<|TFtaq4L+v>x^kev|fVC+!CF`DT;6 z^C+%V2G1{Yf?_%-1Q*tKMmFm3B*m2pu2*oseLm^OpzmXsKHfud6@u#!#FcWfJ%F7J zd}V2|oq5grGr|knEzqvpT*}w!F=xLa;(x(E+_w=vzlrU^YqDPiiM|j&44+!5fa1Ez zeW1f7Cd@*8io7&3UTjRh5vfh=*Cby*@xQR%w`%!ozpHC5`G_807t=4QC+~Zl^7We3 z!OGa#m=B&GN^$)r?aV{?!o2(Sw>y5p-*v$bLBB(ApltWRB+f8kP0h%}(qW#?AhzccWU!nXAnCvjAgfUq3tTMI(Ov z`+9s+dte5Tc7MF5}9S~wW}_( z627pmalB@?sj3qU4(Ra>pcQrSub@MNfA@V$8TkJ;*WVn3Z!*GtrpkK;?9^}T@pY28 z8tlwF@7;6iD@#72hpP~O265`(UGtwU8AbiB9Fa$JI#DM<_18 zpEiy79k8<}@&}=H`{Q}1gB6$ypt^XfkkL4<0fegFQ@b z_eqfAx=r$RGIsXHwPOcUT)#uO6qkaVa6fhv9X!V4kS4Cej6)r6hVPNZxL$&rXN;@j3I_^_J%B&UEjMiu#SO;Z-!%EU zi4G7yq)c=a^Ys(H$vws52S4e@Fz@cLy=@(o#g(vX>PtKf-?m;!wVxnYkgxrJ5r6jL z!<80LeWjWv`vqfX<7ZbsroN++kLc-;M(hmix9v-b!e{j{faXgN@kD;Auj>o}UBlCb=L)70ZoKjY7 z9^fQ?rwSsvZ2gl8&$q~!FMmn6>}Gxk@8wP#+VUrP1o^rdKiU72_QQBwS6?xG3yHqa zkLNT|f6m=rPE6kr;~yGi`q3(Abn+YXjlO`CJdD1tYUmpf+{xSY{7GQOo(`)U_|lJgodzR3*V zQ1*Bqk86KYjBm=ah@U)s^7BuqpY+DQA5pX2ayw#uA%2+qO|RE^zP9pWI(V6WeD3Rm zn|a)Tpbk#*dy5c1?7OegFFbC(AYXT9JRa9TfXNF#LOS3Pz~3_FxI|OmBGNCwepl97 zHG}8tsUW7Wn~X!SZd5se`?-9i-6|m52S%=2&+}C>4eeJ`2MI;!5KDp%>ojzbD~ah~ zMLhv<;dxfYJx8~pEUu(C&dWs++@@m>UB`o_J|PzW2Fbh<;!hjFU;p1JKbA&T%)qyc#(!yUZCB;er<25-@O@-zpJjaIfl*@pEt&K;h<676+VCWgYpWur zuS~`_z`fzo#H~LBiT$S_+}#`J{Yv|VbicWNVYTAx!9NVkTMS`vRFX%F>1$>59igGG zQ}B22+{+_==Z24}4W~MIUp1$LgY;wQ7dO_jR*VuMhJv1-^pk!8`d&3%?I#Nabx3Ov znIB*C{(F(lin6${n$?WF~oh%CeC>+>LyVktG?LxVh0#MdDEhR%1@@(5F0mBnYeoDH_xk{ zqX)-`^<$ao$E~L}RryJ~;P13K89Q5EvsWcvUpdQ=FMmn69AxxuqM>gLuC&xL48AvzRSN=+pn{=7~ibP*gwE? z)AF01L*smsjQ*AUCg*Q2WWA8U@A3e#>sX|!9~En+%2 zn10bRH*xW=B;z;%0@N)x{HPi?J%arro$$R1;d;fsr&m+oG{*0IopiHm+>~w=(>KKQ zi&f=seVVt2q8G%*O-B)qt3ltLvo5sfaSNUmn;++raTDf4NeTSEOm{Bk3xUHcgBx$8 z{mpAKo^&w%VnEh|Z}2)~q>8nhwJNq>FqY9f{kMB=4bp_{j?dRAH(|DAEVA5W+Q*KUDNBYwT1M!OXle?C^zeqD?XH*4sS{iv7@e&Tna z-MZI0KAOKzqq3e3In48{?W0pv`!zfV#p3GxU}RlmK)njXjQH{I>)BZr<0s3s@uE*n zM5hd=n7&y|e0I;pH&oAKJ%WC+fEkB&Y3Q3gP>ipe@C85lMYpff=L>NQ%h%xNPK7^+ z`SpBTWc}=Qdy94y*In1#^DH;hZWT1zEmu&7Y-W6`KfQ}L+8WS$)X!q;QFg|!H_`A9 z(owN~;V1sA5+d5+Pzde+jZVS+V(n(DiQ5h4$1{5L9Tkl#N%Ao|ynyGM zQ$M-xEbSNm*!u-fC0q`Yc>wg|+CKH~IQj(l%jGcstiOgob5$0zhXSVE=Km#i;cqG} zUCf_ZuZ_%O8~1MgFOO?f)*IivjGz2I>?e(oqTdHxIr>nzr0mD`0PBbc+jX=^vouaB z;gB9*2l?K7h*KB*eeXgZ!dFGC-MmX9^TI`^j-%(iNityjXPb*BGkmxoUyHCB_FjnM zYI0}O%;AP^$JayL*XV(vkj0hs^v$^&`xSUF|6HFR))e#YZH}+h9$yds;hIjB5N>=) zkFS;BLa_OWT;nv4ntZL8J>(M|U|spp{sjl94zgJtkVk+q2-ZElp;~wHeBFY46~YTX z7y8_TZQPWv(|JBd&SYW_;2(lxzdwSq zsH9XE?ei{b`$`+ILmZLJZeO=Eo5KPR?7>nCI*HP%KU@BKpF* z+@IHNt;^%4HxuJ4-G}`z;P!fS^kE)X7Sz{8^o4==#eve(Jg&E;7+*KjZm#Lmn)A3B zt;BGXi4IpIz=dmfqWN)jDsYJ5S_v-nx5A&FP_6%F-7kjgAv#n7+*@9p6U`QV)^3hi zfAbPtSU1}I%=NW++(1pS`A`a@!;$&*7V)?l#(Xu`&wPwM3~b@Jo5#)VZK$s%uAksS ze75Dog8Pm9H)FqD1EKZ$ zuXC>`P*g~JM9i-%4BwBx|6~Y{TM(lT{OA1@qA%!h&z4`C@wl#rV*S{D29FnD4y$^`lZyIA~7s|})#N!&3_4vw!FX(XFhz@8UX>_um z7xTY%f(sibw_bb8iD*>x+3a*N9Tb8K4OVg5!W($p?1#i~om+6b)j@!sug*0np0|+W zd_8(!z z|1dvxzT0Le#SNOob&__gjBuZ>aQ#aZ*IC}&dTIgT3+t(?hh@7cuG=K8cP(Czu8(j# zfCixoF;!B%^;Nze!vt@ek0hM=o7b#eGmmNlDKhTui(9 zE5GnTNf=u1>EWg_IxHX4>L_hDse(Csa1dPRZ}Qs(Xq6c=kWJ#c8NZYC!cxsxOY8pW zF+Cm9Nk0a@uYPNX`EmFXr%ArnTCZkVhHDlbX18E9MJv^&4L~`|{iZnTELhCE;=* z`P~Qb56_<&`Xzso<0i4^kkX%#@nXhbYTPVAT<^Y!f2dsM+U>O6{3f51r7(Oeu2KK4 zT)rS*JA?c9;Tga1`r6Kl^|v$zH~F9%H?M(MyEz%$`S;CK@eK;%W~W5#;p5ZSpyik( z8MKg1et&gNOYG0Ue(&s|=36BAyPiGbqJDi9-f;%{Kr>M@j6J|#MWVKgfEQ8K6xCP2Sler zLB1&$v7G_#7aF+M#$xvCA#pXV8{NNW&rCXA$gRx9>k6a8&#Q*s7_9>OT^K>Wg~UHV zNBhrZJ4E>^515+=q%(X&8ho9CeDg_v1HL!ikmiZ?i_ma9AA)tyK&6670Ta3_vYrx(04a6S02bVQ`16 zQS0Cl#C2DS%wr$ezV}aF-#kHFFN3>zry4gXh#MsR4c4QQAKLH{wO{x9=K5QR{N4=s zhjWj1ZH;hc^sl7!Glv^wbQoLd2bI3*O~vd%{vGpz`TUV<)wtF-#rlO*IbsjzHTdQV z^0ms?pTTp}<(8^2t&d7_Gcg@fYewRz{ok)b`&N=<0Ct;fH&-&|3-RRZ+ZOu(lTEh! z#Nx>i>BkWF&9Qb;#ZkHFqs~yLUecRi*oeM>`&I=tZdz|K-1HByzR=(D+8yad`uQ9rgK^0F=9y2aJ@`%9LpEa%^EK>2=_zIpL9(s~&rOHD z+4gy=uhiIFydFG++Xu$^4NY#kKyhW0xC*%*{7$NU<69KhX%aW34sJK_5AS?FZUAjJ ziTu7fI$UDX>lcBJIIf2E>P)fEqifci@*(aQ5TCXAX8l^KgWqJo$Rq2iz;{tw&8ka0 zsHcOi7Um23jym=150tNxZmu8u$a4{xZ+dTg>+urFX}qb&S3xr?@PjZPx~9_OD>W`H z@sJ*FHt`P-PqtWhJ;KFjI!)>jWbABl0^7|++70;L`p>*Il&>V4^ACPz-F|$X&mS&P zOpQ17^bJ{XyTOL5fp@ZCfm(P>F>kkj^M460UF(*B~QU}~V5U9`1Jl-K@KysoUZn71R^U&YQ zJ>2>gY7b76>yw4V|H1<8ms0QMiQ;P|I>6`kp7b6={x`m)r$c~zE+6z=5d2X!4=}1l z4>zBUAJA^Oc#|G(i0F&lyOf#0{ZS4w4*+{OlBRxsVe2b450FW_!NcXOGdpidlnw!A z+R1de1=@&niYqL-vLHiv&+7+$h9iaB>ChK3? zXpy6OxJAtR!_VLLSNUJ%0WrVhXX28)f3I3W`36n$bsoe06^J&S8JJ6Py(ahf1xdVA z3*pwBvwv7IE~zh~r1pP$`pV=v8LY!BU;D>xD3i4jw2$iHrV?C;cUCsL^Ih$$^^fY| z2Fd+`4!=*Rik`;dGrcx*^Q@G0__+v51Q0mALK&eNabO6Se_ zbw9aZST_pQn|%yrGJ3_F^z`-L5sCYHKD9S-e!WcuxBLz1zwkth`ib@9gB|W|cq}^cN(lhnWhvGvm zwo3J7J+Zz}@7D>8CzCs1{XpNlthb_e!*}NX!(6{et&ed*hsnRM&84_X6LbE-Qx@Zb zpKQ>rZ}EIyHrbEeL(%nJ2T@$VNgcf8eqmjC!Q(rY zQ(U({cD^#YmQRiY*v=sCOKsi0n-phcf~|)~MSFpWz7Sh?ziut!8(-4JW$Y~Je|Fa(SKOb(3 zuH7(e^A4)7vw^vO;b<1|>!0n|S%>0!0#8=;6=!Pg z1GL+zr?dZ|`npZFTMqG);CHV1=QzZvGWu6?)-&hVy^K9f>U=D}n6F8F^B8+bRu+w> zxRNurc7uDnlCCIlMS&{{Tv6bP0#_8cqQDget|)Ltf!GvygPbNeYZSFlKClh1i^PVa ze-_2hYgM}VMQuwLKj+rc#m{bEy7;*_moC2hzlNo1Kgs<|m%roD(#06IhKINa)$C&>u=>F0j*nVhE^`~}8b2tw6*$llvAL#}B9JwTYMDUvu{NT9K!KeJ4 zqmA)d`>{V3pZ&OFY+uk1^o$js`V(tQKid~{qBf4C0*NF981ToWH1*TVnu6^x&82j)+6`BiOv z1s&JIccSB(_$zeqSLxuRzFWEl)m!vBj(=$GUa>pO-~Kv@uSmWQ z9f$L!diBD7vp8S9TN7Wl{v3|e=zWcL;qgmB$IHNY!{Iy8aTwp}`9b18-RQU$|BC)# z62yn@S8Ip)(A>W%m;~`>&NG?e_><;`(Q&qYv%kRCc{c}>SbT+C_eYfjVf^4yd>+l+ zRS#(5zk`lz;XAKApove{CsUrVVLd@xloB<6L4F*hj6bEtJpT$~7i@^0$0dsYh>H6) z+gGZ*AL$>llc8gO=jHD1REiNe1!xd;2ke`wYyV=F$Nj{^+)f4_U~(PW7y7UuI%e!f$2d3{zTtYF`f5=aKW7i-L38)6 zMPYo~Da?oFOVDwazyA#3zk5*_pRW7RTzLFCUnZ<4XjW1Z#*7<3% ze?SvSD-sBBz<&57tk1P#{9~Q}QvLyh`6-RB^1dyd^;L?W6DnQ&!oNxvKX|%y@Ok@; zb^U>kzg~m*it2AaQ#$-9epXTG;-{S~UHssUr8B>v`lSC`YWU!uq}+?8gU{RNgE6jO z(e*c*!SfNMPndtvf2G5p>YviJY1DX>sQDMg&-tWu=64i7^|R8!pD?C@(Y9f$GJJLbu7+(UE9KXkTq_}_iJV|ae& zScTV#Xs(>-7@ptJd5vuy<~0Q!kBZ->;p?1#c8s3iT^Js|56a(jzI6Cg{Oo^A7r)?Q z>EfsSS-SYnze)%H%L;h?vv}Q{uA^7dS^q@GqvCV&eAbDMhvP%;`RteNF@9=0+>dB3 zchJE{$2IZMaZUXGI{1(1;G^T3_~^J6e&AD#PoG=UT-uDw;N>PSFUsNNC$BkIKWLfyWM7MaBz_%5IlL?`{BoikUQ5YK$?R)^mz%tnp&VXI zN8y(;8oiHRPV(a0bk5)DmZ_`ySp2K;>nO_MW%1#c6Xoz)N?yv^J{EYn$!i(P;k9%f zekt#x_tDEqUVMG=mUDmA{=Im*pVI$Q{it~*i{BL$a%bHXem~oXb176MTuz%w%IpOt z{O|h2`222gJ=u2}T0_paTEq3ZhZtYaR-e2cpI_4bh3jK4LjUJB$MY%fuwl_xJGS~7 zNbt#dw4d?=ydGq~4PV#wg-odl`c{nm2{_KC@3R#vsDQqD>k@k`ZFI?>qv7kbPQ>lq zb$X_Rwm?f+6XUBdE6)1dw7$18rDmu;+obsFOZzmw`wP+fR%S}gQGNEw@zv*v^ZuNZ zu%2n3WlAkjeW_F8tIr>2eF0Km*PWRX+F~vRW@CGe)m{qXtWTLt?B$nCsTHa(^m2Un z7mBk!AFc0rresI;d9&lIPkuT+dy%J*`};RjYK`j4of=<#jyUV{(E2KllF$}@$u}*& z`hwHryFck=a(}f)NjIbV@?MFrKI^OT)#sx1H6JClMfLfo$5)^G;n?a+xq$s=&Lr$V zzq;=?=@V36)&RU;fWFWAN-h7H?uoBHM>f_o@aS*SdQ_jy8DD*_IP3G1`gV`}P5Kno z=Q)7aH)FlO>^SSQPsR7Q=f&To&rp4Zan@(6jK9x@)t&vHjz{@t@OpXR6jWcAw z8qGHkf#;Nw{a*ArWtR+eK6)NWpHI?U8j7D&(&vygm(g)}4iVlghVl`En}q*;V%U?G zTTnTaj^izwHyVzPqk3&C@IEY>OCz4NG(+bX+>7^b(fo;P|GL&PXe@e<i>G9{=NHTgUEm#{ zPLjJx?k9PWB)Qz0)Jt-+^}1igcwUnGNiL1Y$7PZ` zN$#e{P2R8j#r3#-N$w}PG#($9N$w=Mn;ti)w=uLf+Psl|GY}!Lv$SawNi-V8=AY1!}&>4 z>P);Pj|EiLLj!>OdZ|WTAv8f5bO0<35S<(BVf?G1AI&AxreVAVIeKFUf#_=NrT5n#Q z-y=io%^nk7uQTsSsUBM|*`JwA?8l1gRhW9^IPHqoo0cAJ&(4&QQUkVLvad2x_Dt*L zb#`Wrlp3@3lFx%AN@uifGn}le@O(m9jq?JMyVl@x-Z4Bc%6T7`bIJLsYjHV1@{D!3 zERpk)eYor;IjIiY6%-0No$uOesX>DRc%OX#MxyRFtTTdj{2pDeGuu5`9ACk$LGm{I!g3>9FZsR>T5q#N^dnSHZsX{B-Gjcc$ZWmjdpxK;H%0ZjnSKm|=?XuWX1tbZ2Oncq*T z)DBplVe2L9EQzX@LVL)3;d13ie`pq-FSu6XxPs==kIgjq|20I%+5Jhb)p$KHh>kRn&llixCK;>n`K)bU`TvRnrKLc90$ebiJnt;uAUsYT`7+ItRuRpU z(ND=+(K&SgF&&?-O}bjz&WsbW#(8@CqA4!D&wJq?Iaw+KXC;vM{mcRonwOy89fO~~ zktlx7HCV6h&vmnOLwbcyW4*j{NIXPQtY~m!^rD9omBa6$K?-vFxP#fMKci?J?uz0u8b58`Df_C?R9c93ZMO5x%O z$}8nv%qxEp<~4XlH%kx1EA@Z49ZQ=RyG4@AVPqE!^#k|tr!Fu@z++%SdUP@-^Y?szr2eb8-ldq=p!N4y?nk`5m)q`1gHT@9ZCJ1DWtdl^<~=OE5U&u? zOJ!f^dIh}_-5;r6puBvih<#1393H1L-tBK0f_N3py1afu_Fz9sd8MDmyz<_~dUdVw zuq6ZWl3u^Oyz)6-xqo9`j$F)ZYQKjqLlLj^%gig~wP?K@XE3iq%4^=kmSKoj^6bm2 zSH|nnyov}f_j^RI?T=W7BVKuznU`x;G%xQzSg(}jnAcZ7JYpGvcv;)zG8*xc7G55`vPfK~rx#tf|KjXW%hSN?WgJH*svY&# z9r?JB*NZ-P_@dk}%QJ|V?=tbyv@ax!?+9LRrq4lEG#X|ZgLv6DC$>N8>7{933@`fp z=G}I~EYBid*_VlzrhOq^h3AN0CC`b1Im0Z^Aznq3qwUK_{3Fae$}#@S9i!j$NZR`x zJzDDk2tSw1bLn%gLHWZhV-c_1Dbc*B-lFRhdb}tuk|>;byQk0Tww)bjc^>gfemk*# z!aqxUKF9Y*v+)G~Id^)$W^)=(Q2eZwIG(6JVua-dq*v+|+#gl*v{H^IMD@y>kK2R) zT)n7H&KINO8LF470rp?1x%fHn$nk$l=g@QK^w;#(O)QdvNF;h*OYe)$ACvFIyzDD5 zue(1uC$%e&zK^@C4le{y8oZoyqURl{7ov5P$BwX!W9*CCAHAP=UTNp>^CWsc^)sUWE8e(}^0IwQcr6@Z8IO2*-^Ko`w0Y6{ zr7|M>Lf#&&laqGL{{ZuPYWWC@8}TY4yi|SyU8A5^qV1mEzo?%;l){Pseh+#)-aJ%* zzYm>WNBsoF4-xyat{7=~3F&2DgWFN1S1J2d>L={n_m0TxM_MK@yeMyaKk@cQSB(9U z))VfJs4^NC7JiED>+p_|mWha0st@Z$&!=(a<({XxKf}Dr{xZ@s3Gpht9{bhO=0)$9 zwg<0Q%IBEZkz*q*lY!S|(u?;K)UVR{wvX^CSMe#!6vQiM?d54ly*QfMSK0<*U)`Uw zyo`9ItxGH~y?F;87t(fg9>(K#kns9GbZLAx;$P5$)y!DvZax6ocu61p|N48|B^>7zY{GiUJ6x9O3@^&N_`c(Op5~3w z-_v@+!GvU!vf_L$n(_v=2mX7lig}y-hqfcdFUrSyIghz4uOhwDe#GNEy^rGRF4MT3 zaT2#<>edLa84NGVyO>v;?N}INJJNcnzb_*DL+#r!ue&a}EHe==&mla2r03IqQ`&K~ z*|?DZUbA97P5wjei^uoY%(QrrUPZ*ds9wd@T_*c-+oFF@5O~dEc=5dBjSHQm{}$hu z&OfvsYF{*-$k~SNYf|$}%WH^N@`u>3((~y!R@!kPjia4*POs&emNyWu+@G+Y;D5h0 zUcG#6qQ^fSxg=T-uUCNhiOF|lT3$!ItRGz-y=Xg7zI5EC?c~~w+wo}kOv`M<%TIVw zyJ!8x%S@bOcE6ln{6*`{+l6^G_{C+JgLu(I{e6U&l+b;AJTKAl(S9qo7yfsN>3x{Z zssG~fontdCbCF&SV)s<9;`%O=|MIuM{W1M3+>XF&9>a_09dCbh$JiffJ+wd4@lhuB z)oo^`B?s|xeT@4fJwIY!iQOm4+n3q#k@}nB_D#?~)V_FpFY>GNkzUlVQoV|+EoJ+n z?MTO=?44vB`YhA(CgMfMA-EP^nU)2JS9&3i3u!yDc7HkiJ+0TVoA~*|+VzC3-#typ}P%DDPrD;#{8y z{vUf^0v|<@{a;-I3HN{p0R@IL0Tr^Yy73;7Be?4tcRix(x+8K#*CV?M22g20CEoE^ zjk@ZH903)_3xel}9O074WxPk^2&gdL0Tuplrs`E{Dl^^H)01KUpU-bTpGhZ^p7;H} z?|b#Cy1KesbNq!kSicJRb3%L@nO@$*uBUUOygq01_qac{n`oWLl8!r?W&Ib3fb-Fw z4UE^Ep4ZbV;N^RR<$WSva{riaUf3QHw`@J*b==_V={(>S;k=sU7x?0Xce>jnn2f#L zw#Ujp#OEd2b-Ts(i1zDveueM7p3VooJf9xi_UJ2!_dCk#S&0|&7CJa=j}4mb5pmS^ zSo;CXFEZ2`BhTK^t#))fxZB|8Zyia$AQQzd@|4b4;im}hTK4dz^m%5%<6^p9qUB- zDU4So=k@$`H_#V>SMl3Pcs28JE$Wqjs!}Izxq-eU@j~7hf2Z>%p5N=uVFr`|U`Q^?AY%{)?maInnR%b&oY4F6Nz}qb)va=VVx-cjMoYOc={Uf!a9Mx zGF>MSH}omvHR!tW^mX7>9ZJ#=QR_sq zb@jpz{)^K(QGGG16J^^NFLT3q`Zn;wI+2K%Tql}~S51EWa}cBF|CYtB^ka^eEoSSf z#d;?Ac!e}Sk!(Jf%Op0A^aA^JPcvLJ5aqQ(;#IPkty>fIEBb$lS98rrpfoI7}&}5YI*$xx)gX}y~q9K<21QWG}mz&9zPcBV!T4rC(vcU3+sI%UUI!}E?zh; zEUjm}hF46W%YhfxFXWY}`h|4@aqD(4UW1>SKvw{-oF)H%)`_Ca;@gX87cPInI)V0U zd47f8n?P$oueyU=Ckp-Xen)w&lz1U;A%nwlVWDQ7Kpd$;+^Y$2-Kvx4VY>$a}$@MGUys$kYF5$d>e_#S#1H2l(O>$i( z1k?xb<~mM8Ugcw09R0hQUiV*qBV7x;yzgeVPE=gMcp$If8*Ds^c^w_Eu7UAt&CN_N z{9GPKN0*=ry^^f=$L~4a;5$lfl+ov68r@hbn0<$ZX=jkFecVg17W0|(eRO1%z0*}4ef z2meL)xC41%{VM*J*RSx6^nKuk^-J)=`;9mA@esC0#0^ClulzkX()GZrHp6uS^>y1G zbFPlhOSJ2Di|rBZd%x%T)uW7V0KMwB9NhL;a!tJ7Vc@k<;)T404i4L6m1cWH9L#$> zzgGVP(`(KdWpuNY_qe}&9(jgT@0)A=1mYHPUdNwXMn3>vbxSkbKVm#E?^B(h2;UnY zf3)j(8)A8k-^08Y_8(yP<7;#4B>DyDmDhn?hu`G9Rff)smfsiexBtOObc@7G@J5Fm z=6y&r?-3`K_mIDJuQ6Vpy)5tFoi&Mm3A_RuSbpLD@;JIV$Ezx@D&+ObB)S!NHDrhv z`itREdHMD+y_PPWM7II2qK)a*E7?43!gZoR66;r_1-oBI-o{CEJMgMfc)6`#$#~i6 z75H>FpvWaA-~m)rW~eJj2lV}7{ZV*L{K&ukUDpJ>}xZlUek!}ac; zCaL!ss$YSl;^*)E@7_Y&OS}Yc6vAQsifGm^#KC?$Z!U{R?Qbl<0-JB49e|hTcyCNU z+#j$1j*g>8Nd0zBn(w2l@+#TSczJi+LOTMl!p~S7o0}K z2Y3}d6t9=t`vW99?nrn)1&9aos^q*{wwgja0k43fS99^IdMJLr8uh~KtpdL?y@upW zp`C$O*`D|~Vx38KeNM8vs@8ju3SQEQGYqiqwlcmQ>we8{Kd4_ZYM!IH{mZjr?e9;& z1?k6lqws1NEz1~Z<1gY&xPMS4H* zs>v{~;IWKHHcK#4x|s37xNm8(lpY2TfvJ6uGdl3GwYM!7gzh zsk|yE<2Q8iDmoB&Wp8EAhl%?V|HB7cU0x+FdF36#cnw>*iXIKTO17nkm+6of_Ct8R zg83t>U;g9E=%(oSi(jvR$CvWBFbi@3^-A|~E%L(gYI#ehSMJtHbO-Pv%D7PGmCEsU zvbvhE9|CyfRmaEoxj#&z^}wq*&AgJ0SJirt{ZROEHXmJl8q=$Mok^~M`vjV=vwpjJ z18cu-`=R_K;~}&Q62)Fvze`8}ln>EDb+A zTbVw{i!5P!RJUS!)tpdBz5rfD`;yE900$qu)6EOVHOQ;}dd90Li}7kTtdML0US57( zW~TI#*15+je#H%pS3T!7_ku$5WptSFOJ?=L>*i3eg7J)(na%Xtacd#j3cQMw@-mtw zjwN4;`~p#6edBrT@0`|*SKfaL$u{5>Ovk_OHp}*gSgS z{k|}c_&m|VHcYRTuNIOWz{{VMSM%tlw#WP%S$>5%ubQQWq#k&Ae#@+0*zcfT_#D)- zwoI?qn+nNJ;1x>Bt9kTN>qH&b%hQhWD*3UH>;hgn`!lN-o~J^+@cFG(oY%aTBgt35 zt28OE=Fv;7UwIQ*e)-xny=L4xl6(!kYBJ1A)vK2Cs^h%o{bwZk26%Z7B#UFS>lLf3 zWs{g*r5%`FcN}&$*$uqPGR#ZTE5^$^iq-qiPG))qIIrOo z&nFS!73#spg_#;psJv=8uL2L#Yxo`KlW&1nPS4EpQtMagO-!#^Xki}@v7mxhVML|{0zJzhh;X7QeBN5cN9-! zy!?l8z4o3@8h}^e@Po^%YC7Z9zx#p zF1GM+VjujG?s*fme@^rlZ#GGF-DA$^cz@8Y+b!xGM$m&-U zoEC)o;KSz93wQxKjI+4k6^FC@n)d5~Df{3*Wv3>os~NhlPe_SJl-Dm3FXSEdA@*{3 z9@$^2*B%iE;~0FH$C1NEJE!M?SHzbjj?J9+SSPB-viz;@#^N{w^!gQeRkmil&<~uS zjh=s$=gHH(o_qk$ul#QrFRc4fy%qqkhNF|@7yRD`Z{582-fM{V1Yfg#VH{D9BCglC zt{0HsfS1`Tv;8&_MqUk%vivGr$l@6N{|msYY7o2L9rqX8=C2d6@mGC0<5k$5@hTs1 z0of0{>Uw2ZFMb~k)GP29;}zz-qPhfu7dbXbdu)Eaq7+EQ9XyUbm|o*fx_}%2UirN< ztCuvskMRmW#dyX3fFIG|E&^WJgOcdg%=HW7Sa2ufRn?Q}HE-kvgupnb{2=KSOL{l! zCs5!tZ$YmZwJ_JK&dc=bckuDx!>uRH97sG!%gIRuIKOkg* zb!k5ML$}_G?`i&mdX?YBcxCtI?eWSB2nD?g`ee2};&E-P-;RotJ0RA7c@{BV(T`q> zDajnf>-0sx4Ii(7olviI_uHsf{@qNkfV?HQ>qh@;}~yQFS$-6 zTi=2@H zdId79S6sghP9$oNZ%gfw@b$B@UYTf*HC(UAK&IEcM=vC8K(B^_q!-4q^nMmc?=g(m zSMx3;ZGl%&|IFq+#u4)#>R<&HJ1Om|oSW*M}F9cA!^PhV{bZN2`A5 z9VzeYpJ2Q*o%bQGSN*XpzmDB?A!!eKk=)GY7wYADi&M^E-X6PN zL^^<8g=w0X)8&hLAurEEj8|bkkK@3LNJromJVgJE`ewbhQoN&)^EWgSpUPL;9UjBom7x0Q@k?MC;$EEO} z&G52zRTq&% zK`+mM%(h3hu9j4>I0jB&yk=wX`}%1Xwo&pEbc^uL4n@r-DcnRM4e~0S< zeD~#R_(z=w=i1CJx=IhBkBUUka#d~WsfYx2T=JMt0Zm3J!3uhvCV$vEJZ|3;EJ z0lC#2`BlhyATQr1j92;Tj92dTsiXvWm1me2>Vv!*>KHF_SesZswC$9~$)mulq$OL| zk?HmKZu_CaJ=`CNtE*QI(*tc_KZN$H&tP#JcgA+|80b~oIf-5w>W7MFv2kL(kMWv) z`F!#?@X9+h2`_NW2k&&(Rn!ObE5hSpp2>JU^WA*%U*J`FLuRkjL0*_&PS<04?_+fz z*R^6^q-%@$h4yoXFulCXSCc0|FY~k{=aHL#-D9lZ#{2H0ztM5Va`=yb^1+#p#(oIT zcZ9dH`vXLI)x;Pxrg&d|d48ff&v&>Te<5GgIbGYBUO*0?W8i$(k z!2e~v(!H+3tzPNUN410bg~x4?C5?K$C+SuCI_q!5I(INM1DwLTs(b&5WalZ9jlVGO z>xMV-T9<%Vrt%)^7wUm}M&nxxysAs%>x8&3Ec{=dFHCk{3AE>QtL8m^Kg#QUNw3H| zZ2rP+-Y4UqFpfY1+hd@xF^=n-fmgEpLVr;gHSY^XHuBn#fY-sw`&x|jEokrheGJAVr8-0)9Z~slF)98B{d~Z5z$<6HTg>Cfh z<8M33RJ|(y$nt*JfYtO^(5rq%{P_;qo)7-OdM|&T==Wf{^;(#sUhuti>Q(b6rq`b? zUQGvqUcU15=v9+$y_Tn_7kn?BdNrKG^g8Q~)pT$gujdOp)Jx6#ymL9PM_1E);8n3J zJ#lPs$t#4s=B=i`174A@(!*U(4T(9?leUYhEc-zBdw=QVQW8hQrs zilk}$Rpydc*+slg>|H~Bz{~SNdg@n&OJ1I0#%p-%we(EjRq$SV@~g@vuPV-KXxFuL z2=FRNlU^a0ynGk)_BdcIJqvgh?@rJ7tIj2_I^=cIS~?VX1%6HsuZT-trI+yh8o8DZ z171}P>EV@K;I6J_|Bc7-;1mGz zE_oGP%JsTqEiD9IwMV9hSCLCz7^C4M*U{^MSLycj$SI* zJ_fuRzD`em`CRg<;k<^oexE)Lyh?sa53gdEy!?Kq*NCp~)BggmoL|$!tJEd02F`2P zN$=AqfLHkT^zbTo$*baWrq}S1@6#uNS3#QQR|6^XDi1O~wY=WXS@k}B3V5Zfu2#F` z6&l6(&D!-o4FIon)zw;;yo#^jyxOd%PXn)X)zx~Jyds>}%x>%HOyHHSc_!lUerY&g zi1}4Mn(H-iJ$(jvrK{fOxa8#>!+D*(p3VYZ>8khnE_qdRUb8P*PiF(Kbk(mym%NI` zGQH+pwVuuaUg_$G{4ROGQQ6cFMNK0%WS)rooY zH_+!H@6$D37;@MiG4FlfvUOD1*D_wwb&pR<>mG4kBsM?QPCbt!%Ip7WH3>i* z>-hRr)EECxnt%Oj465S0_;uk?UQbKBRNhYWt4K4y5J!z;&NnQMS3I_nE`m6w>-=Md z!}}rQdO5s~j{J-98lAm{%mlrBN3gnzeu(v7%6&U^*FEZ952NZ;a2?P4`5S39=#{SX zqD2n#9@op^bIJm|e))3NkY_-z(tFwQb|Ss9ptHjB$jz-+Nh!~-*EZ6{pjW!i*H)#H zU(g~^58u^{*PQ-q$SlySlIIuJiRQ{Lw2O5}&96$H_gAdiNM8fJ(sdrW#9@A6|A=}N zp2hUK>cllX$*ydN6ZW)poA;+U@W06~Xw#Jn&6AwC{a zz2-`Kp`Ic>4#$O+n*BE7V7h@+`#Bb6=9{3^QC;>nAc^V!+MW;;dnL3s?_Oquly{_C7CNG0t`4=Y9tC{bo5UXF1`89i)-zC!- zufE0?xJzk1iT8bOD`|o zyjOYUl`~#E4Gj@;~;8k-&dU<6(kXjsz?&kID+#O^k z@G2Xh8D7cs!tqx<=au`f9b^^oDx8#FUiq5$m&3fr@t1iI(`#GB4ze0}HDriaLcO5K z;`l3gFXJ`*g&kxK@FF+G>*coJ*1b=ldc0l5=S{|~+C*2t@pihd@9>aUAo}CRzh}rR%yAufzEX)CqPc;X5aS!(`$ZFJy{2OdChpeviGz6^}zAa2x&clmw#>pPaNDIGd6D$+Rl$V z;O1?x6pqZldNW-K`PDE!@jSVaiQ{eHQSv3ztA?*jJI7y7YC*4BMX!n#Os|fhm%M(W zihrJ}UKj`bKF)uY>|lD8KFH$eE!|94NqPxA@rw@U$@4Vp7vcb~oG6s1p79Di#CV0S z{eXS~yaHQUKH~mJi!^f_@whg)EB?4P%Ii~!7xEUo9O_lBsTbk^uV|VJy=wo%^vZkl z1Nu4esz08ccWv_&6$Pj?<5pvf!BCHi9XaycZ`dAXu*;&o;oDG zy*wu;(JMpwRgo26x4q#H=ob<%mAB)06U{gx4)%}vZ5Xf0M_7IZ_IyCM0Iw3R7w%v9 z5UXF&`$x<5i=3u6j&V9~g7^0=d6@AUy8i?ECGZLwwck!Q51<}Ds^gqs3FGzL zqz&{r;FYfXMg<+NzsERweq-&b?pwwyR9a8ohkhu0V|>5eT>VfTIil%!0-80Re{6V^ z@fz;iNj3m4->vby+{Q8J@c1#vpVwFM7~^%@+dIid;MH(jW_Y2$Sov`Lg}m|}=e*YK zB%6R&)$Qr!6;4sF5c2wbC)o_V$c)VJveT>hzg(|9JIM#YE0|_po(B`xIkiq;9I<{y zIIr0qcab{am0g}*y^`@ts279_kGIR8V0sPhxr=-Vys8ymc$}B&`3|2Gy?|FqC)N+; z-^O?aM(iRV0WZ%T@p^gq`2n>b3Tv+0NX85O#r7CGiOe1)g&+M-Y+;-eJ09|MW_ktg zVE2!{`t4ohW6-N0#~Z7|P0qW+IL8Mb=#C4WIt#pFl6giBWcW9-yMdSQzRboE^Bj3q9L4l1oXPci@f)%ScttYI z3-cU#6?A93!kpKI?|efdz^kw#vwC5k<9ZXP&sX5#Ct>an{++HZ=oPE?Xus?k7Dsdc zH{@H;%R4fOUd_Bt6vsLFJy{&7Sxm3GKkp_#126JGlDvn1`QV-I@dTKRy^vQ;AEsA;$8qDR z-J}6{)nxd&fv6AiD%#I@Azy!&14da}=pWBu^IuiJ#sA;wJX7H#iI0O254VW(KRk|( zQT3e4_1MUsn>4m>1NnXQ#sw#5HotJaD#o!IdCg~e-(q6}IUaaby_s2Fc>WA|`A=hd zRdQa#hwddO0I%$~Gs_F-m4H_)#e%0ZUKI=3@zAio`^X=Fmp{Y2@VXr2ReT2HRr4&1 zqRwn|R z7_UHY7RTF8Kg+lrc;WNr@ctB7|DszTywlwe;r&doJr;b#c;zi%ylVb@mN5!=6&ftR zGQ~@Mu5Os~3UOZbx142M0laEDWtLa?DK;-YfRCebeR(uK(U`vnO-5jjqVqH`5p3typPq1njd+c*vIMwDgVS62fXSZN;1y` z$3s5AQ+Y)>q~nF{5qbIUX8AOt<`d(ez{_*bLAxF%=3dUvOs}GsSbm*7c)M{m@QTdK zEHBSk#smAuk_Ps7J?B-kd%JNB@Tz(?v%GxAhSATpQJ^9lH;> z+xDoNb5*(Vy!`tZubfvHuN|d(jq8AyzdEye1qQ_P%KnA%3UXfc=02koczG5d9A4`A z+B$x}jSW!$0}~@PlC_y!{hbN@bL=R33;Xa`bXr2&y$Xv#`Ie7jY-D9 z@pj?IOt0pCo;3Q)RA{^&rslGydJTe|^3GxNU%0>6HuHVlV#SMfkpj}mFY5DBoqX47 zUmWMC`!K%H9$#R3xvi_dm8p%t67iz&VHxM8{y+M+58jyf(Z8);euuooc;fi@{EA{6 z0`KsmBy|G*=YzK{FWA-5%WZx+0&}o4>Q#9`yk1ehE#O`8Qj+!v|MS7Sx%2{FvFfQl zA2-TtCH$x4ruaBU_&S>C|3mNtd4-hqHSlj&uinvbgMGYTTIHLpu10ZN!n>a9g?i%o z@#wuXVaP6crThM0DzE&v8hNz>Y~RZ)j?K*r{RPO_3wh!CoEnK&7VJ@}@WTEgQ~e|I z;&fyEb~N!KY3AkVyh4;rJsTIwyjDx&iRON8GsXe&u};zp#GcbDI%2s@GbnJ>qk)vE8IvzmnAnw2Szd_kmqa>qJM`seIDGjbq_gO?gEZ z=9e9$IHF!fJDc)~#;W!p^GbAI>qCK8-a)#rbu_>E5G?ka(;wI#oPN)4e~cquZ-x6u z`5po9f@=;=ov`B71$fmTWL|i^m8@6v!lDSjp8|d^w#{5uQ7=z|``>p35&?cc1;Gb@ zX?|X@s;)k#J(^#e;6FJR#@E$q%GU2k|1TeRWRKE2-;ZwDZS9_;?t3`3=UmT*@1^rO z*WSOdO`z73i5gKLVo}I^80@={sjYk z@9UYJCodex=1JVHdo2DnejH-g{&oKkdd2D&+Am$h+N1xG{l>pRuL{1NsmXj{Gp~EZ zdQX&fR8d~nOT3V`@Ymt>qWPNZtPm$Qz6UTot}R)|^y*W!-?#yIRc&GUh5O_DMyl6$ zI9iV>@hW(a@#N= z@MG;QuDese;C(s%dVlr*c7J1g6!vR*dxZ6cH-cWczA)465%V7BC;aOfuXpnf7!#$u zN8Wh+nUQtKQBnE)S8WyJwWQ#HF-gk%=H`X|Vtg_05jX#R#%uP71IA?FRkH2>&%AF? z*1e*?MRU`W_h`R?=a+xc0pljn%jaYB_nFRnjAP(HeE%Eeb+g0^d7~aq*ZcZ4`ys@E z_82Q%I6o2D#PaKkl?RMlfEV^dxIgA+2HImBuh2%uYt)Aaj48ki`=RFMh5lkZFph|u z$9c`!alkNv7e2?cNq&I=AH4DW5ZX)E7I~GmWY?>a=^bM0+J-%PIPC@#zjduMyAGzL zxPJ^Ed6i}{UfvH_9LLT(oE{0h^4nyV7g@sAaUidf){Iv*=hb)d;q)lrRi0s9_1DMq z^0#HYit3nN!&V+ny92L+wwcwd;)Zx$!FG&SJ@WeSaM}ZSRb-e~-o$ubRUH^F^FyZB zjGc$mp1{kO;q_m&3a@~N@yhv#$8qoB)C;^SGt4VzH0yUD?_M4g?GpG; z(Zu-k+x5%Yd{T5yI0QS1`lWdvB(!h0744DVpGn@ooBT(D-+l0z;FaM2ZazX@_?*S? z$1ILfn@8Fh_QC&~n-?BGmVMI5>!|+$UO0~SeA>vX`~LthJa1Jc@#+D*iuiqD6H)ZR zhs_;FoR9W>)~Hv{L}aATGQkVachpI|yb^~*zh;6Lo<}bIyiu=SiO5KwWr7!;N6rp6 z@)F0q5*PW`Oz^_>E;!+8+{?K zlFJ#d;`&Bjzk~nRW|&vSMe%xxe(1OM;`&K1EUc|N{@|{I!Rx}xcQ)$P3wUKed2o2) z*bmpil)S{QGn_x-Dq05f0L4$T`JBkl?EXz|@As(tJPP%CtEzu8y+-fbKo`JycRZgK zOGf2~5B}E8`$C7;TdBN?yD(l?oV}601iUJCvGW}YrP!ZNcx9jMY@H0A=S%fIy7(OG zM7-U6rs`FC4byAXog3*w(5tRf{Ctj#5XU836Iq>pi==m_}eNI{ZswBTg9~zaytN5$<@ni}n5`G2s z%JH!IX+OX3@X%mASr1grsjS~l*K?$jJ;wms6OzRIigaT0_d%S$A9)1r1^sqm`^=t) zDXEG--%)=k<5l_{%dft796@^nuZ9fs%DFk7SHa>uaZug z~@yU~HbtL)Is@(SM>&#T;E zd0)eMja}T09u2(m4$CYr^PYHK<{^xizk%od%5L-+;ALi*muFr)ucDI}uLjPm?|>ue zvA`?;-puNicW*qe2F|NuFV}15k#rF7DmWsuyz0y2c?C{pdgbk7ysGXziVg-|zAl;N zRjcS#cnaec;=G0(*`4MCufm+n@+!Y8Uatt}Rs0K&<8$5V?|@gNcV>B&-51ZR@>Hf* zg!5YYTX%X~RIfgn<&}STJTKpAj92-uOs`$1^`O58UJV)MRj2T(=e)eXF)0tk?oL9@kPN63NugW=@<%Q?jkypVPj91Zqrq@}0PN63PFVZiw zyzo3b@(Oca^_+G7m7lw$syS0r2wo zPo`J%@CrBbik)fwiMe`CB}<`AY=5P9`Jjh+m=Jh_?G zt4`rn-Xnf}bo9RI-@!Zp-ZvfZpDdEZ;dMHmhxO)t5eM_W_AI7Xp~2#~^xFedP6542 zlIqnw=ZA2e5b`P;%6OGg#_L7kbt>=*Wtf**zr4d3FV7*2*OS2OG~kt!mn^@UM=!O0 zl@4dTsyMH^fY<53t0u#|)PAV)A$C0EYr*syx&3r{2JrF@$gEztZV%6Qr22e?oDocC z(N5F!3*>!l{VLk8<9db1jG#Wy%U8#)A8E4wK10_Th9BYc0NmdwuQMfH$Xm$auzrYi|%!XSicZAoAVlQ z`v`hgH1GFhIPW=sg8&>0*>~Cz3 zXul+z>9xGFkPZXA>XPY|q33wkzZUOzcy1vbF7ZO%!at|&v19ym6onn-7sSE#h{w4k zz}5o{TUmEhjgs+9*dpQ4q>myV<=xC^`A=b0uXVER<A$tE& zQ_>&rKPv2?<9zGU#pnC~2>4?FKX_hx@VyT4$6Pd#ehB#W?{oZn-T5E3!N=#+nr+#* zhSv8oI>B|vVg6i9@=MED{@Ud~+EL^uf%jn!Nc|B0#{3s?JB-DD*`kT`W7+=-cm79g z{Ks`QCda>H@kIIw;8(8a`g43c|ItnpSC6#Le^s|DmrkUg0)A;b_8beMiLcs09v&Nf zmG{b4lj!HN{}1T3f7K4+du{N|``LBfUB4Yp2*XyU7OkVfh2n)%;_`G4EE$@Ck*7w!LHclmGH_}_3Oo5w}I zE&e%~?w0lE_;&fP+Ch7!uKzi_{Xa69Mr8jh-T5D|@xSgeHa~1~{GE?Yrr!d-X#X7F z&VRIne&aT1gD=``SLXkfvnJE;0AI9!O?+Vof%(?^gmwO@?Pm0%$@F_U{+jrz9i$Pm z@n7iHjrl*Ielmqee>Lj=m|puAb`Y3vBR2Rd@4gL_=})r%n)s?6q~W{XT7S|1@h|k7 zaTDDO_@ezk=`R2MHuyPr#*cr8t+i0sA-b{`568^F7@Iy}Vciv1}$oMC?!;d(`_g#DoZ3Flf zpK$%pbcgS|!8-n)CH>j>um@}ZJFc8U4+VTP!tsZx_=%6dgdGe#ZWmhPS0g^(f5wC< z^f15|{l6x@Y6syc07c)tnaW%#XH8^)Q@=ZUW3R0Y7J*m$l2TOn*E7 zRXeCdz#;y$mDD&}#_#41KV*ZCaWi`}{rlc|i18=DuUW(6f21Bh+Cjf@TdRqW``>!^ zA;vj?Z@$mB0Bu;`d|z-*Hzf<6_zWUM~G#p{Kve z@s~f^%D6=K-zC1!2ESssl7I7B8Gi$Ok$;-_svS&&A{%_n8?!&x|Jf|#@3Q{A-RW;? z;v?VXi?fW&Wc^*@S7_p!xy=8StFsKh?0+A3{s(mNdH>h{!z|-+*?*V#K^uIvZV$~d zjG=&EoTmQ2)TaKbc{{E?%NPatBL6l0SM6Xv)!O*4j$3EUnL=~q@vr9iPql;i{@bnV zj~IUrWcjz_!zr|zJpTN%I{tMw{)||SKVkgSu!0|daKbCLPoYQ3{%hi^cF=z^-r9dL z{y&=e?{96=?tm|jfB&lb?`-_0e}nuj;mi!B=^&m|)W0vj3X+svYz{V1tkOXCBM*?@^QX z1$>cze^dQ;mVZGTeAJ%|V)(gLChaHd-vr;8{-rkcN7Ze`LX-BF_1DB#?V$dq6@GLl zet&SYn)#povq|#+zx-o9|FKlnKe7L42XS#5ve93}e=x&02TY|$1AfEJUUvMqT*Y@5 ze=@N=AeD%D+?B!GG?*KpeIY0h6yiF_*?2i9cJE*^37yme>|D5ep>F)tQ z@B`2P+p=BZ2Xyf{;o0?5>G87vF7Yd@+CPjx#B)1;&-|Y?b{ahq@awj6{fFu4FYKW3 zd>eA;|Co|#^bfNCn)u1$Uu%OecpuOFANun&dXnt_I<@^J&VOM?@!xx+b^Sr!CdY5J zcN#qz@J0S<;-eh}p5$xd+cfZXM?Zm)_3@HdYY{NUt4RnKh+NU6SB#F zRkwcseVU#j`|o$x{wr+!SMgh3HKh+NUUu)yP{~mt+?GG&fSG+xwo)yLa ziPyi=^xD6$gTQC&Lfv;-AFy z-_`ROIzsmUO?T^`NSSs0QRg4FePhsaSbtT%6YopL?uTdB|EhLS&p>;FjpOhGzQy%d zs%~R?KSK*;{ayO+vGKp*+x~I<{K04F9|1qq!1M1j&Gx6*L3e!)@d=$p&yn%N?(j_; z{Hm6G{Cf(^KkqZM=y@{!7Cn4n2Oa0zkPW_Cw};M}MgJ1T|ALP{H1SnCNTb#YA9fPw zzxWqMbeK)g2mJ7GzW%Kh>wi)`|L2)#(f$(PXI(d&UMSpX~f& zz70O=W}eR4-JBgx`mc&IMI;9N?Rucv-*ni5`Bk{PQ}* zUwO+sdZmnia+cQkI~l&uA%5$g^XWfj{8QZF7wO^;VfnxFv-$KI8UHkQ_@!3(3G#ne zcs{)r@atOf{O9 z`p*ky>%q^_>t+9kx${4)iEj?Y{Ckd$m+?os!;e_uC(wU;_&GWO@Ux%d{U66qRe#T9 zz4~Vk!~A=mmdXB~B{&`%l{}pz)AGoQVYMuYM{sZ@))wP2$3-If=bNpM~t$)a0V~vmfwmFjdKl1Yh zbc&pR7r4v6kd6MhZovGS;ZNJu$#@m~7wi9~>gkVmP)FR>PP6bIb`r;bXEXe>zgR#` zIsdu;spfyJmH#q6Cp`Ac1$3&M|1R+(R``(r>TyHKlo#l9!1o*MI(~AoUi?)%sK05| z|0lqo{lyFPHozChpMQ6UUtxnU+TWj8{D(~q(it-T<$CzS4myt8n=JAV{8z6VS$S`e zmIHpMn9o0G;;VKL-eZGLa{2u4In4j1Z@)+%0Q@o!AAgR~^IzCOV7{%;#5Xy9za=ly z2LZp~XFmVv5}0zU(DhDaZdxz5GKvh>KhA&DQNt z#I1(jk|K~5$=VbqX)ocG~2mQcp zktROwKlY24>GQJxF7f>~_?S25g}nasdWF6q`~RDs|7ZvOz-_4}KJGt!&?_`3`|lFp zw86*clA0HB|M$N_Ujlq_{^3Bp|FLHz!nj$z{|(wfKX6-NgOBZx6f^vB4I;MX6@ z+aJeIwfz;9Tht%$qohB({>0??a}Ifxz5@8Z!{YJn&cCA_^c%N+O?=$HUx!!etAJnd zcYge#=-(N3OmzRDWcUFa{V{Il#XSC(y-F9!@u%_YZ=A-z)&^h1{}LX5|EsiGjz7mw zHU42Md^!Fcf6f)J(#3N875|;;AJN1Y@xS&}`kEYnm-u9gMg9Y*i2vVs{NH+&z9GlI zrMvihZ16?=FXizMy-MGdaz1C9l%A0AJjHM)5yc{8c+>FW(9u zb`sCM{5$ji_MQuANY+1_>0iH`-DmoksA1Yzf5{5=xv+!4eCxNtNBvEXpWAC8eMi=x zX@xJfKXMuKfB2w#`pfZCt-q$j`a9-#3+cOnFY2#L{0b|4h>?ifKY0Al zT}YS7@o(!c{y{7K0bj(Q?w&+$`@f5-}7j=!JB|FVU2g&cp5pKAPTb@6$7 z8FTqUS|i8bC4SfnUylFfJpNM_(p7T&JGhH~#0Fo)pX29FT}W5U@#pxd#-ErL{ZE4W z+jsgxx(4t?{pI*}@lRHNJy!Ujzv%x)G5wc+wvfIj>ks$ujo!Zw@tux;d^Y%~Ke>Y8 zj|(rP>ty{oeyaKxS>a3V&*b=XzFbIa0bkT##s6geU$XJ1UlX5ZM{)5J$RkScMnkPW^%Z`I(bp*L}#(KWgHuc92A= zY0>^*Cz1c-c>Z@-L^lDxIQ~1#UH*rx@Iim|z7Z?R4>y*`*FWE>cm7qigZ`UqE&NY_ zpS7=xv0BEj)?5Fb3_oOr4lGb8%N=6W|v;=CyxJl{-uf^HZAbw`p5C-9J+{p z0QjQ*Df#cT{zWwL$(79iemxe^I=~n8&m}&YYVAMPEtBI9?X`%02>7D@Y2u?DNR_yk z#|B@mTP==VL_Y$2QU5gYRXa$+YlROx;rQFUis^s*xr^v0fG_G_7kA^Yd>eex{{PAF zbI)5uKLvb|{~SNn{4cV?H>CM5jz9deMf5Yk7x~Zeas1;n|NWZyCXM_`{!EM7IIH$bXKX zYW{~c@yT^O|DRq&w*$V&f0y_X8+^=LljDzGu!!yee3Ac}_-F_7UTm$_e}VpL-u4YH zqV<3;@?R5QwS)K`8+=?hWtKAihxDwby8vITf9oDU{!Lc@&<^6_)@y^W@?PStre6WR zxc|B)zG?^Y^KI}Wm*%qZ-M^Usql>EPH-PUwlAr(Z>iLg$5Er+88+@^D>)#BY{-c`i zmi5=f7j_VsZzERqFG2oI^HHqxfI( zgvIy|_RYJLuRr788(vXOzXSZdqj>x|zFqxQ?I4YS6+Y-M^5zESf4}#u=?{Qk-ksz3 z*YjW4L14Zude6dtz{k8XIsTH*s_Boi{+jq`M}a3H8~@e384|9hKLNgI|C;!!9pq7K zgO7FF9MAKQET#>z|Ig{^k9H6jw-Fot$;GVxkO@5g9T(HRa{M*%g&hRO?UUB=S9PPE z7SnyQ{+jrz9fbGT;H&+{9ZxN$zXE<`PoDqJ>*=rBL43c}@jv8$`HVbP|8HdamlwT8 z_X9rZ&GBE*!$&)ai`$UZ@ju{`={){r41dNyUZV#9Kj;u&*g;^v&9~8C<-OwC*C^=# z>#zHy$A6yLz`X$!#5>Bs$lh2h)P zf7K4+n-1}(fA%_U71e(epMP594!^=7{=3({LEFgqZ@R+|>f%pk`Ty=`Z_su!e#jku ztrb4BKO8rh9Diu|4cZ>?#rU7&+a3R)9gI6}!#4P8-OSqZ2JHa&b-6tMH1SnCh@Wrs z{2~0Fnbj{=2bbLFHCn*^H$?xtTW|gs?I130ORefJ?4-7vvG>18JA?m~1G)dp-NoPg zRMP%0T7BU_J1^#U?05J6p5B`PTW0uh# zGJe1K`(F$Md=nyv>+kUSXQ~~<57^-2{3q_eW%e@KOU56_@TK)9K0+Ju?be_8HdyCh zU{`$p4ar(g`^xx(;_(j!{}bV>cF>=ojsL!5;*Wop^jkr5W&Gpf@sCY{ui8QUS{r=P zZl<#OKkCD^bR^)5_IDz~x66NF2Z8xEqKnV>pZU>RdN$yf4CeL6B|Zrxi$9!If;_H# zk&pkTG5^VDYw5XwUwElEt}Y4x;cJQNkFcZopX^Uo?VHx$D1H&(hn|ne7vmqmPt^X@ zI-U#{Kab(d{^LIY|1Yxtrz-JJr~gUtFOcz1Z!Uar81Sp+@%GQ3KRD}?UPedgf5rU| zHJ?8y?4XW(YbNdgmHfl+f&Rs^|NQf2$-gA}Un1iVX)gVf`+up7|8(=>m(JnsU()|F zz*k>FfA~kD_TR(~H;^CDt3T##jrHdrvj5zUz)xHIgY1X+n`QC-4}G_U9Mu|p#OrTp zlk2Y&jz3g8oHmKvo6LWPUp^ropH^Q(dIG)}f3;!w+56c#Q*hts1Kv3P@bb@-)j!XD z*7$|R@%=x|xt8>n@jEkoQGWs7l<;xwGwkI#Rc;%@y->3WCw z;QvtBf3G|LLk{ErIN%SL@%y;LuXTujAK*iiZ+!K4hwpJ1|LK5#wv0c-9e&uM|Fq`> z@@K#o>(9oz!}mJ$pPoB`6v_Dic85av{HJat7t8pU zxXVAEL;NDhzrO*#c=_GMzsMo}P{9AYj6cd9zTXNT#!OZ+(ul}3-{u6Bh|KBqHh3@?KSmA^J zMQ_I+|IB)$zi}Ll{|dYC@!xzl{6(sHJ6c{9~-7{wG=cQ|$1sCEZ~CuT;Jl z#h)bOKdOV#HpBobR&7{Bi zWF!7m8UKaM>pxA_U&RMK64l>i`Uf@jH=kwFF|A9vR%Vqt!A%Wjq`Tuky{+%-ZmgbGWs#~=E-zDp> z;)5Pe^p9xjZ_aG={~p=@ZJGD~UfF*Y-=Y8HX}$b2pK0{JLiWEo^ABv}{0oO6(fHpF z_!(P&k)Z#7Q1-vRdE=jG{PD1izpJ_ML2(#?igkpV0 z|Erk)UjY7O8UHeO{+C+eC-DDEz`rR0eyaYPR`|02^O*k|0RI*lzXiMhYO48PVTGT- z|4o2DB>{e_{s*k^W&clLD*~4R{!|&il{^1~n)u{drvDVJ_Hz8wD`kAL-a z@}TU0XLtVlt?(20Kkc>Y zW$^e@iGK$0zmoBP$t-@f{(K|j|CV|D zh>U-rx$q(4Q2*8I??-$@>HV<&Bzq5k{?xSg@%10RmZ<%!b}*l6I~Z&nhad25zvx!R zKbG|fxhJ=xb7lMrcld!$*7z0P`1+Uii%AE-{F@o!*WWH>>mNn?1KNrFSM6{&N$vP# z^^fhL)}L|j&8EeGFP^`CySwp6zRmNWbNcc1AFr|c)Bn}oWFL$_vLEE@pN?escK!=H z=s4dNX|6vuIsWQ}y9qRT;#crfo&P9$&_aL6Kk?k2*O~t#Lc7VYfM0jFGyjDh#ecsQ zKI|Lr9>4x(>C)WAv{<4-DBupyV{Z zy6eSXwSxvqt>O>PsNeJcWe+jn{-@&A(;dEPrN4~-CX2s0Y7aR?#_#P8zrqS1oK)NY z7Qlxozs48GPc{DoR`|029PtYJ9f2t~Qt<-Mf4CVibosXDU)4CG13@c%*a`hN-(vdD z?DQRhDYwS?hh+>uRsTa)_zC=aPabkse|_(MM-G+o z*SN#?I>q1c9XVXaU+WG(-v-~4%lbca32Xm5*MCpC$oTK+;iDZ9H~x#y24CDa?p=o8 zdh_=rCk1?AMtNjFRU z`0)qgt9Fn_sSQ5H&0Nak|K0cGC>ej9yZBew;ET8|ID zug0we;@`s(-&y>FHu$37TF(6U9r^?D%J{W<`U^XX|Fu^5u&?OQ)&4(h zgYW-O{P=e)=nq4##+Ro5svR^CvBH>clvw(W8MFVedq-O6atzkdq&svV@^v%wd6yOQ}IIO_+JC*!Yor@!9{A4nEYWBF%t z{88ZlfE4i24*HGTQX711e`FQ&f99|s$iM{nskT2;7oQUzGW-W}bQUDD~=Mm#nz;9T=kALA|FgoLZ)ed)ucr@|NwJiUZt|Z3kQU6zR z{7y~o|Cez5mki&liI05yt|7)5fM1*@{CpdH^|?J+U0WFE0>1ek_x~t8|5ZEaPsAa9 z?!FerUuAr_8Hi5&li_4R6;%wtez_0m0@juo1Un_iwzZkczXZ}xX-P-sk z;EU%kOxDw1*irm1vcbo3o5}H8v~6u%4fx{u6PoyFM}a4P8+j1yvV;=uo^z=tNh>P2R4Sx92`121{SGP7wqyB&53}3Z_ z_(2=|is9VG0Fg6T>q=-ziJ0%@Y&#t_= zMb>|sp8l#G#1Grxi}-)Y+yB6}hAHFU-%@M*iFObdx1n3C+rK()nQ>BEV=Ca+Z1cu& zi6*{k2l2@&XZX2ywKb;8_*r`EFOuPxPO-)pdHXTbf7<-E#%+Kv#y{8T;R`#$arR4* zL;q(iZfn4jk4F79@ss)Qx4{>A^9l2RX18`mx$OUBJ^zIr#s5+peB^C%{M;Vxj5}oi zHSy7o0#7Pz@YVVEzIpA8I{`oR1t0%3!FM+Q9w@iYKjdwG%Jd&Gxt(#h?Ef8l`lB7y z|Byrfx8B^&xJUNC3BEJ`Yi;nc-I$;A{CljOaUbA|_BTt1glfi8L*|y!S z=mJ=OR=$(3e|t!8{aG^oi#i*ujw-}r>)+rr9RJ|IpXu=i&4%@V;`sly?AZ5H9sdMu zp8p|uhnfDlPqs5EKz~vHHT4&E&=I~3+r+;~`>Sea+z~rAB>cX$|6<&< zg~$KvcE&^Cf9V!p|1|v%N=Ae6{_JKDE8^7~qTc*91Rt{;76Qf4>br zt{XPDGXJ;EZ*Tk;@Wt~7?$R57qaDP>ZG{a!>Sk_Z_%j!@H=Y3e@@+i-HSy67;^H=7 zg%3Na^`Gv4i9Q4Cf5rXZi`~_KVl)0%<2JOqz44?R|0e!Bi+|9{e>ncexS89T{w+Rk zZv^D{Pj?spS{r;dZd-S@H=YLk`t3aan)s?6jDOe$AN?nV%>SirIvCH${@?1(fA1QL z`X}dKJ;Og_Vh3Xm;EVCcZ45uv@rTa}AL5U?nH+!CO&yH6vi=;uvHwfF{s`@$?zkgNf|1R-sb@9Jp z{%7s(WGs~Nr@He$Y=f`XpB4?Bj75Mi>Q57VXZ0sygD>L0oB5yn&(6kT+5ZRJ`5&=q zf2#jWujy>OCi~w6-CWaLGv{ez`mR3WxYvXLm7bWc(g_ z_a9gNK>q_)_^^{W{u#^iZ)QUm11|Y!y#A+}_5Z1kKZCmX-!uGa**V5q8GnvDe2>%o zYn@}jB@d19=lFKxuVng@_blq4tUnLfmXaI;mOMA=e;liSsp{|1#5aFn`Y$=Ds{u=H z8}Z+9r@z+EaShx{7)I*D*qD1pRVd^)XDmv z?k@g5hyJf9=w^H*`+tnP`s264m;L{lxBrrE#wUQEeY%&;+Ye&+spfyF6@G&J+i_(# z<5Ssxj-P7$O&ffi|0E6E|6SdT&jDYIfAaP87j}3Z!A*q~zNEj&@n?S3%?Ja&SbxFs zQ`J9Ug%A4U@h9>fx4WD1g{;4(|Ee9d7qr1g-ORmA|CxU~%J@>&|2TL0*IMCA`jdUU z{$6^Nu~pWeVFv@xw;mh(!spofH!_a5zbm^N^|Jn&_`;5Y@3p~KbsI6UyRl2wUlU)ogEV|L z_^6xtEAzkRuI|Ryvi^T?r@!9@U+DH5!yoc!cjFsbe@%R02OZ~I(+VHD zSa)ML;8$b*ar{)X)DD$7L?qU20_+tFGinV{c@u#qZzQul=JP#Kmoq4Zc{n(vsniY3DWe1HM>)tcfq|ATZzhHStZ3KeLP1H~{$K z_{SxFsSUo`ZpL-<8U*H_#r&rxzG??$Fm3Rw=CSdI*^23Z>p#5)1$+_z-7RD7z%KvL z4&vfAXoD}}#@AmByT)rA0{9~Sn)t#F0`qOi3Lo|n?f-r@{yPEs|10JGpFe*!)%IUe zVNrh)^#9W)d5xCfzo`G3{wIrnt(E_PkNt+3&Ens?T`wa`#{WPs{%A*$pO{wjUkUtQ zk<-h_27HnKn)u25_t>nz!@6a*X8tdIy_eAj@J0R)bXWhpHuxfM+c5mw-t1+x1$>eJ zn)t$w5&)kjzRB^otmtL51AI~cT;dnm;Hz<)yQ-JbUXH&ezG??$D7C>Cx*f{e|CrBu z86H{xU-a@{*g;^vt+2sYd9T>j%jhiouZgePK^j3Dd>l8J?O6WpDCun+CgXec@*nLW zE^b3s_|cu}`SEXihClS5y^X^GzjiO5|Ix%3b`Y3vE3E1d?1S|mzc%;k-o_DtpSLd_ zKh^qQYvq4}@!yQay^S1M|Nidu_pG<>f7H0;w(etelkxN1;rn#)JF@s^eb~o;{S8~jQ+C!n)s?6#E;nEBX6@a^MAx0{f#`?|GDn` z582dTao?On8UE6{`WpiPU$j3>d|?M2=iB@Z7WEJIQR{#1J^hV=fG_Gl$4|BX7g^ya zX#ZJ{^*4@@^{;ZLziESy?bbYu>Azxre`Ao0KTi)I?I`k-fDL~AyYcxyYe9cwFyM>! zuZgePK^{RHe3AbTvHCx5aew1?vj6k-{6{;8i`%d!KJGtmZ-3)>8UI;#_}+~c`JW*F zR^;RwC(8KGxx>$Qh@W**u2CT4Kkp9T=MaC!q+H`<8GnI0{30uS2zp6FeEu&fXhSyx zzPSFSJ6nHPzntBF{McxsP(lvCE0!}W*ypO9*#F>1t4VO*F3`q_+tL$MLm4g4(e~(;H&y)y*AJoF8lwI9=>V^ z@dFO=bK4$m6w3H7yTcFK;0xXU!|HGSV@Dfj1HRwr&F0^C>){JK=s4eoZ17dxvi2Qq zoFn`HtscH=2WfVCC!4JM zpPaS4{&i>LkE+v-HO>e8(nEOsf6~JjcF=LY_1NI6^OiHtKGwJZ@Wu5fn)s?6q~W!} z7xP9vnE%VZZbLrM<5P!ubgN(n+_IImq~jjK9wv ze#i!2Z8!Z+F(};fsPX<6zvklV9=5d3< zC6A5x2i)QNZSb+(ntgcvJ(bcsWqiZk{YSz!__+QK<2CMVO5u|4#^--&;;VMhUc?4p z_}`cLKl{Iw-Xr@@-T7an`}{FZc*J~4@0I=6#82kGS#6#F!v95V{CV42N-JdlHJ`tR zc2IZR25tNo-|NrxANKqq^g$W_R(JY)I$F0sRky6y4xtap`fK8=cF_NP8+_q^F89BE z3;M9^|LyMlFSWr}d1rNNK_8L**Th%tp#K%R_W%-B;rsrpng4kV z|F&yd&_`wc%iZZ;tLr}(Y{aA%^fB3gP5fm3M|9i&0Pg?V7WBWe|986cKYy{c{wnVg zAGM%Q$o^~Mt9CH|iagfsAKRZfko$jZOZt@T|K0BV57^+Vyhohek_Ke|HStwD=zq`# zU-*AC^S|XcE$K|z|9jo}Pi&rlDR>{l@K@|@NuQDZ*Tffg&~d)?TH(V!>iLh`erZW( z0e-{J{QhekKh^Ue`BwNa|A+dMYS#Y_8`O%_5j( z)&HOszU==X7XR5#w4(E6{~vIfe^&Ru1ANRIljDz@--pQ`@(R`|02gL(Vg*NVO%`>%Qb!DRmXt?(20f7`FEXi)Z_sTIDI ze`Y@Of7vxz^d-O-_g{S2UH(uvgjgNe@%R}qsULfR^y)p`Y&6Z zMXP1~Iex18*V_1x^XBI7nf|v8%%-mae(i6(|9ebNf3(xYe;a%;Z+kq$A9GALeI4+{ z{I4dyu%i%&*x=**kIC_O49cc&0KS<2*2G6U3Opf)T8uwo=fHsY^B-FZvgwDz!W;{RWF@z1yNAMkyju=QuicLh9uYMQ+M zyp`Vbk5oHoFLb~4@dxIO$^9R5bv6xw|04f1{YN{9i(8+K{~~Yx!1Uj7Z8m)e@J0S< z;tM+n%(q2W_^?k^ZhZbNDa)oy0AJ)E$H)3J5WZtV-0=K+<$iYlUA2QW{8spK{uS{2 zo1aaW%K7)CyZo!L!N<6n9DmGn*>ss4e@%R}gMQ;SV1qB>b`p>Of^526j=v_pu!F#S z8??fQeF_K0$A8-5Y`Q{@KgY-Q7so{HCRl%=+TrjdWQ8xs|77O>va4Ftm2&(8?&2S@ z!N<6n9DnxJt?4Q`{+jq`2mKaXoAoCmZl^H+M_kvMu9oAki7)I3VD^jG>ii?@;@KO& z{$|v~)^v>=e~xe0{#83j!(-#W=zsYA$Cj;XP2ZE_uX+D5VF!Wv)@Oq+;>Pd4HhWEL zx=xP2Ccdzv;1^lp!@mA~ivAzArti!8EBHslcM|pgsvV?JniSs?yZ$+Q7w>;xV)GB? zlbh*#9iT2;>SgOszG)qQ{TqBO5x%g4z&6`hwnO_@zZZCWGu?wUz4Ye)g&l=J#0DRAGdcdUyW7wYW&Jhr(T)O7 zi0=B6Gr9ivwV@x$`fK7R)8Au-4`j1{iLXCPD%;SH0bh*&6#S#%I|9+EL(1zzQFB7W3~zng7d< zY)7{OzL4*HGTfEB(R|FfC@x8=2` z-^=mm_^HM}Xoa7k{m&ZMp8g=mU(^3&@ekSHi}wFV-v0mIp8h1qKhItK!#4OBHh`oj)?X7}wS)Mii*@}+{mnly{kQ$MJ>4hkKfs;- z`8N1Mw{sZ&jQQ>9FS7oc_`;5Goc-dn!B=(L`doYZtE|5!zG??)1Z?WB(4Vh=TlQ&t zx?k2`bNv_EL0sJW9r{0dZ+lAGN#j3F{AB)@+TaV`=kogZd0 z|Hs~Yz&le^|Nnch0--*khaNy6^w2L&Bkc)2^iYj}c#&c#LI9Ca#ES|B5sd{5NC`bs zFHHhcLXQFxdXN_SMHDXmzsZ?To;&B+**Uw!FTVai9$$Fw+3e1|_j6`uXJ%)2iz@%= zH_bEr6*vEW|6iCt(t+-MzWnr-S^Pmi(cAF{AWfV%qSmQ}tiv z^XWff$-l4L4wV1&m8K2PHdTLN{{3`t;;=FQ_K)lKwe_bBN2cm8%%7)&?4y?ap}(^u zo&Q~@PaB?Ns{X5fKKZaY){Kba#sJZ-A}!u6FR260|8TzHh1~r6@BcbUraw;y`A_)e z?~XtCyzRa#&p#Y<^Y1_Zda^8ko(}SlF5=VvyE|e2rMR0af0u7Nypx;%_^|r^>nW6f z*zs4&FMs#^Gxt-zPL^ziq}jZa2KQn}5Ij z3G?r#gMz1Q%`gA%KCJ!kEdQh7S?6}gUr(v>zrO7K%RHSv#*zN@uTWi{?lY(ZQXBqg zIO66%dAz#+zA?|=`}t>{4)Tv1^2hIA+AkIOe^G%|ZdlD($35}r8dT3<+vBS_3!E_2 zUE=1Pe1iKPw5t!fs%xDa-R-V%o6O$!(zUcb;coAyGr1-8mta#jt>!E^W&iZ`w0}-* zZ>e-)-DNesf2G@~z4)T6!sxe2_xBfNIZw7kJYSUMJVh0+FUo>vftOcs*6Ehh zZ>aZXC|mEW&@0bhaewNT<7W<7v0JpAf4bWdaOQWnSB|3c3R`ry zujlTK{R`8moL1cJ-Ez+Vy?Xb`J)ZocbRC6FHCFblUq`yzyY(o!AU$^g>)gL`k0){X zuDyB)yP3N^GlggL3gU0O+q*odSFosGUsRlsFLat~x_A3iPkXmN?e2E>VCawbXSOXV zoy0e&9fNhY@@{|PYCCj+ooo8)p6y{hy}D<-+THD*Jd{r9YKjM}v(@UJ?O|MP2L~+T zl~?uai?WE9Q;SlY=my{y?#46lLv+60_5)^hoLAjS_Fk`c;YW8KVb3Rq>+XL=Y${*b z`>Xl9+c9(h#kXFzcf?%Xz;^#C&D%?_>vsRm;{JEnDUQ?oy|;z_5Bi{7eNh%j;Q6Ai zTgaF5d{N~F`Enj`eo>b5fb)y8;OUn4ZhPW>dZc%qI{I65o$7Ay)`8@?)c(VExA(3W zM=sr~FG*!-|L*_m|GHan{p$XbTa>O}-R)l2uWgoJ*0Viy63h15LtGbOZV`V(E(U{fnD+shZt#lh;joKxG~L$rU}tgxy#&x)&hw$JhIb~lCY`E{@R zxL$1OZtwCmucG!Dwz$%&eV*?A?Q7KaUu{Rb42$~yMU@-m3z7OfXHx$#{{>mjQ&${c zlm$<>989fWv*z^rmAdfYUjGWVyMMQwI1_3fSlRCOS$d_a`{Rs%-R)EBS8Egh`h|Fv z)b;&~vN!|qjH>a@7iBq5T9uzK%5t7Bs-J;;!Slvf*79r*E3>TS*&f!r+ueh^<#cL$ z_#bzBx17grr1lWD5?RZ$zgkz@6Sq?P2>ZarYkTq(FIl_C(^BIX*h+W12hW4<_AXDn zNj$K{%hvAkly0MZVJm7oIAHIo#)i7%!CH;3kFf1aVnf~ejpoze@6~tM;Y(vfnJGN! zG98z5w|B>b(5>|h9d~|j{~7Znso&84&SkNo1>OBychG*Y)34ZOxXTk?gT{lfxhuCB z?(!i0qt9HecS$_a-9D9Pd^0+(?r!h$6jnLB#}7NpRo(q(@I*IP`@7q_Jmt-4f7sUT z3v2yscb9?u>z+rLe?Q;Nd;FE!-Fy6%>uz^5f^N9J|IFRqEkCJisQkb>dm6@HYCEp$ zu-`c>JKX&*`_5-4Y<75dcz0!IJ0d&W{clg#-}K1r@ZPR{(Y5<1`z>X2%3kz?>~QzL ztB<1poMW=Xz5l|9q|P_wp`M3@jaTN!vHz*^gOdw;J~*D+u<1p1`BERQS{frHNaGvPVif8zB=UJDhF(95vAEb>%nK&;}uq)WWe?i`jiyUoCmHnw7JXEW;{6mp!!sV`pifle+|aEMJv?5 z@~&TA-~EKcd_w*Xs@JXC$&TDfwsbGq$p+c%{bZ|kvdMeMChjAfd5COB+2X_G$C_j# ze zs-NiZcW|D4aClqy{VM%`>(cvG@P32&-ARS1{X<86U#q|W=lmn=`Ixc|o8IU?|6Aq9 zjn`0j;%o9#JzgiR*c?8}jaPFGH4lFoiPmCBhF^5`iEcpgs=MoQx_yD>Su~Cs8d_WHKiALnA73Rm_W!*X zB=`S%JZ@#cduVb$A)d?jX$`;Z@-#NodHUl)#$y`~7DDp0eo5ogD-LZ9zvA-5HyR92 zNyyWEZ%A*L^~>34K199O%6XgWlcU}<<-Du>|0w&uvL7k?fwG?{`b0*C*!@k_xKIC+6ru*HnFVC6M)@zl2s^ULas&`+b@DAPAfZgWG^@h6XV_hb! zQ(MpT{zbgI-QB-?J?P!PewOY(On0|;)4{qZ*wmlb>)og5wz=K?abF{+w&T79>;tQf zc=8mJBc42!?sgBJ``ztbp2}mS8*FOL5pN!~9UQQ8EwzCsPd&bYCr`V(-GgWDr74}t zwTegC`Z61M^0d`<=$t+v-@6Yp{Z=Z^rEgIAfzAEJyF8!hZuh*u<8JpV&$HZSxWD6W zU(h`-+}DA{{fpJz`w-px7fEGt|6)zo@7}*yTivHvN7;3iT~FCT-M@Hjf!&8sTXomr z`fBvw%dYMIS6`j}n>D%XaQDBq`Y*o5uEX8`rmO$zDd)EvNeByZ*QIdEjyH`^&{Ayzehpy4&3o>XwhG>m?p^xA(4J?0Qjr%KQFu zMQz7@W!Qt?^1i;uC%muksqXeEJZ*J-A9c5PdGOo?Z1ElM>w86Q$8{9;^l$FoOK0p@ zx(>poHr?I5o;uD~ln$vQY28%L-M-!wp6bT5-l^zrpSoTmelT4h&r|!OztK+9{%v=A z_xd%PO8?v=D1F!M{R>+^aXhzS)9d!1-P>;NgPC(u|M{T^*+-RKPW6LVQg$_E*Hl)` zGdOCz$hm_0e7w^u{75GwtFBSOzqXG-5lS;m$-)}3a`<+#G-*cPZz-d}<(WdX(%LLejh;nkv(8B8t?HRln+jaeNW1y=XOHQ%z3(=+~+t| zA!mP`nM%OKneRS)=*)&JsO`O{c z^{kw)>&bo2k$6K^KC`drx|ldKLeBJ`bWZMb&Vq%r`&?;vu$^6RB`r?456bU*?%?j5 za^`c~sRZA())S1A`<&C}Bkufr7A8G+6zW;NK-ZJ|oGUsitMAf!w3CoCb)nA5ea@Ma zatiCw&O*)(CoOU8L*Dea}pNHllpignIr~sOQMV zIw$uzQYtst^0}*!v&}fU&p9U!6mkmn+)cb}%IhzN`%BS>tw5O1>sW>N#6eswc4}SXK!E){;SlvYbUd2|25bllu(Q8U4;+<9?8kGjqMJC-*sL zTgWMm`@uraNyf>2&RIM_rl&OShX^?@hZz2nS_4- zB|Q%l>RGy3FAv-YKWyf}VC6G;9+d|?Kgpk$yq=X$kS~02HUe@+kPx$`dGB$T)4eZKw3ScvyUV{){Tn_%@F#Em z8lTehc5P*Wh5FuJP``g<>W5t4T`)Z5z9G`#Hu)F5d~%=fU&sV2pY;pqJnO%r^U9r} zKTmjLFYZJA_Otb--XBE%EybCr6EA$kee5F2C!zA2xX@eQ`gdqM^o%bi)AI(Qo=wFE z?&58_zSs_%+F`JI-b8v@+fV2R4)~u}&xTOX@sN6QeZdbqYS9z-VOx*raWU2R2dKU~ zw)$SUozkoQlgclAa0Rs}pSiE;^}$r%Zxrg8|Eqr9@jG;%b4GUbFQ0hN2--UwZ>sON zQ2Dg#*-%`uJBbfI(&u(Gt=D7zJM@&cpErfnlk3Yll0rSlZq?&r((~4UdV*(AdP>{R zn}vFg-o?&a#UI?D=qa7|epIMu<7xf+=G>?2%ei8Edh6M)(t0*<^73Q4Zr&!W z@9o!h&g{MZoaLSTubbeM>iPG8de%^%Lh1?K!70`AcA=h=`0l34sA}OH+u2{we!q^5 zXH4zVo!#~`ZeL%=zw2olpFl60g`T`Vn#$)LA@$_?a;}}c$1!Yb@ddiSH%1n zzSjvK=?ArlyOi^8Vcfw7p3lpPxJ$1`cM9V^!M>l$eelDM@9JNVz}ebC|1PAdeBLGG z?5KGqaFieNZ$Bfu`E$}&ijdk2YnlgZ^xDrE^R%U=cmA0FYODD$KEH%{Ea^NL^i1p| z)AR0-dUAbdC_;ZFEqbCJ;rwyDslMMUtnbhn-$#Xy^n+UHDIIs*Bh)j=<^x9XU04HP zJnLURgX(#ouw8IUAPyT;P=ULmm|B*%;EV!|}&;Zq8ZRW3YN2A=I`{08uCuQX`EquP? zcp+!*XWu`$;kPpM5^L#yGhTKG@<3 zGCig1X-^VzW}nsdw4Z#MkhAiUpVrbFPfDaJPOR#dLjtMcAL8V4U3NoUxXS)3(k(cMYYp!f-bSdppmccQ3!7>&rQ% z&%aCCrJo7oo_bN|;y&k0MP=7bX@CCbLe3837j+whl0+o+}@Hn|R^3 zJ|Q3Zq;9A6fcTyt!*MD{>FejE?NUXk=S(-@P=|qqkK(n#;|=@BNCocZjc;p!-Ph5&wQZ>U)@@cX_X`b&l5SkyOto0_q99 z!s>~2l|k1hKk0Hx)`MYvaun-*+4|)1fa{Zkay}K1v!==?xS?;R>K$j(I%?i7)t{l` z$A_t0NA}g9lbWk{Vnfz;sk)Yae-l2|35>TXpM=V9;#qI*_71e2vc*}>u%>$Sv`|m< z6Z2cpItKX2p<~c9`WfjGzi&u;k77{HX999o|4sFta~3c0*3Xv{CppEM^n6yxiSn3z zSGD)79>p&8<}{Vhpn5(hJ{GHb;EPJINmXE z{*ySZ?Gm`UXVv`&ADmIeCFSguPdA-LTfbjyiu(%`_oA&|m->Ko>_NK!$9-()wyE9^ z5M$4`;`um!->_DucC4r@(tDBgbjI8besS+GPVOT;SlfB<^4YkS%86+`?Mpq*8S80H z>-(^-u>BF~3LkMtK1r2d{RZ#yS^NQQ56by6aazkKxS$t&a3&Pje~Yuj^aKaD;2JUL zIWbN;h2@OjM8})@A+J*TtlR3**vAy_q#9qshn~o1>_*Bjb2C|fzHLL?alDE1HR80! z9bCv4J~+pf9$`77bviG6f0uu6_jRG37^f#bBVFNx6Zzz>qx>58c^$$! zIgL65*6UI6Q{wB4P(KttIIAyHJ{gr?>;(hoj;Da6co&P)oIHl`;9}?cz=Id0s4?ft2aGk2{zIORJI^PY1aqm2; z$2~vnANS4&gN^$I!nnu2qH}Q{I>NSuahI-7epndy+^jlhopFN?w(@sb`Lx|fC|^P8 zEG~>Yf1mg0S9Nai!4CTU-ggM&9-T$!;y(EL_EMRi();fh3OUCaC-?h&>W`}M{h!iy zsTs0-^76_#Yp==lw3W|}DxXV)ET56t^m4#CrR7r^_ltyauQ4v}bI#7bGCig3(%*z} z&&;9gmyPH?=Nwo42fiIXuAA2TM=#U)ri5{y>3bcs`*TXa-y!YST`Y`ym2q(&I>Bay z?O79_sc>(`8wZ@g)=JD z)7CB(|4e!=Bh<70E<5jO{(7cAmFX$H9^ENymqwyG7xxh#*wme}@+s{vT_)sgGfwV< z4>lrvK2G|6n|}z)XKOxP&#`%RAAGR!$7Fii%4b!T&t*fF&m`jpAFQ-|O5bnuct}0D zzTksR4@l2QhvKrSP)~k6D$eg8cj@&=T92*})}zD%Iv4k$BkcHj{^c{G-Hpdlj$>-) zzw7Q2ai*QvomTGN=PK^0x06Vr$vDT^^P%Yj_3v8ZxY8$df32=8wu{Fd>VTH8eC8L{ z^(-u?`^X=*JfQMfeUsv{jj()1-q&@GFXYeJ5nhj^+==0r+53@5nf9?fi&({%Cn&+73k$jGQD9gp4~c2jGLv4Jhst*HT816!XO_}^qzBs?ke;P!)PC+I)U)!DuIHqMGt;K@!Od;Z z{?fI=dQ^$)`f;CgG%uIccWK<83mJD_4mhXtxQx@*uWMdU>8v7*JD*>gVC9u_O2_Zg z_VYSn+{?@8apykgY;Pj#*Gc2v7RJ53oX(kAR`)q)VnA_^-#~F+HDug77EWp0rTwK_ zg>f%^P1le6T+g;;o&oKWw0vGKA2&CkmZw?SMb4>-}2|=>ysxNs@xdL=Q~tBt?Sa`D^r~7 ztCEF}^}om`r}9hO=e<7J$)OBEG(b=y%7z?4gI*y$7J^nrRDQRVfoCj zqSqVlbIwV1e~NF1kME)I`fhp-JTmx->fbH-Hsk#A5Nw0!x@wOmRKA=$r`n~Uoc|VH-@%1^;e*q; zoAi)!27Qh%;vOLR{$^wiy*zRs{M_O>zU*51^VfKekH6={^t|DFq^DzxdyR2&pYu(e zs=s%E{|-)mpVajH=Ir!bkM()O?3%is+~*uNy?OhYe3HtIiE|F(v_5|{wjpsQHzErk z&-Ij^rhKC6Ii%cEDqnU2MfLnU=d?YiKc|or&*eLKu3SC056=JgbNU~-dqP3gBD zCEHfK)knO!>#F?>%J~U#TE|D=f`0H3_n@4;;^rnMeGYnV_W()U)9aFs;N(8GbBp$K z+|YjVcFFYo<~&r7tnJbSYtXG%R62_JDEZBah? z$Hl(~n%bqW zx(CFad5gB|JNgUp&FMWS@cS7&;T`9iY6o*S>-`XnH>KmahHxA=vVmUTx!>m%{?XIZ zV_%b=vk3LXIHvVY(i1+iDjW37C_P8n^@Z1WTR&u0Dk$Q9h@-CSydQ#m!uCUOys5u5 z8*y6e5xAfqeAJ_c>X%75gO<;mgyplP`g7pqKDNWAPWGQ)3d(u2kh8e4UXQpBKG>F8 z#|59;pq#e|ITK&kIl0d{#{MYNQ+ogCK_O?8adMw?M(&bvO54xB2ssPi(Dmd#=gbM$ zgGu$gO~@Hf>73l>oZ}bC^ptWwB;;%`PVRHgq%iJM&bp8@|4m&_?sLw}jf2(mb|GhM z6P=U$oO9$787IH~@_9w1`>>Fc-#4r?Zlnh*y>BRu`(K5eqnqk_avyxK&ALoaDd$~` zv$>PbgM6c#>D#%F{iGJxBWc|K&Nxl^j4RH`v*~?a@J;*2@0RIld#)Vm-y`JAZLaId zeWWL~&{G=sdxe~lEp$%qbG}jG^ITF+_w|hKKl^)MYmAfooUAo=qVqZ|AwsFrBRM`Yz@Cn~*cJCB;2@9JNdE zIUoF{h12wX*a?T)v%0cKul&{SU-tLDPAX0uH+rM~Uc}K`=sBtA=41<-c|SLW+shUt`kTdt=FTL3lF}ZCJKlGU<4pDaaiN|g+v}X%M?SDE zp`Nz(v!9-jleeF3#*Oq~2i1O7H>7rc17Y0xcO1qty1w9pP0u&j_1;el^-S)db8#Ph zu<`r->pRx5R9Dc~$C%bH9qsBl?Cfn_zr^21!k-fapVXorN!!n7g?biu)b->(=c_$1 zSUn3N_2l|;PMbeRcL!G^KE5`s4|&erSMq%XKCb7!jf?+|xJ$>yZDHICJL_@hKIce0 z=pXk!r{#K7-iX?zjfL$J|BiZm7oD4PO24aaYv=2V^Xnlw8w28$jyGQr#y!8Qt{?Zg zo&{mt`8pHR_5DR5XKXi}llz=AqTZXtx5G#Il(wJ82;<(|TJLw)88`BWjm+-<95meq z#NIQkNzbY~-gMu~(OWLyx84TtvoF6vyzr63_^jUJ%lbWZKRc%^_V01Jj&vQ%yzT*# zbu7`{^|*5%`E!ePEU~rq`|qapb*A@G&!++~=4Rlh=Q!i!KIgNYN6_;5ny?<__R#g@ zKIa^N$iJQE_upHusPzzr?@i24dRp(lNA@Jn>|SKy1m($t};&UBR$ysulzZAJ#yZl@@(pVF5Kgs&svW%`;eaL99j5?d+sgDXY_Tl z$v3_0k+TzRhn~E@ZMq))NO;|xRGiR@``8XU(UQ$C+4^;b7wGyM8SbWRk9#bqj|(f` zV&xTpLK`&hF^apjz9Y`Sfd6^pZX0*hXQSs(CWQ5Ud~I3>2F?jpPT_Og+{=HS!8Cq1 z)uR*K@;T(}<>0xV55rN^!TYr%mlkT$zjLJmBLz zxXnN6e;%msl@)beczus0sUH1H829SKdU_qj&H3OrC;jVtgckB*_r5i)S6s~1Q?mZE zv>)lyR_iNydop>OcR$&*UNLC-EVA<1vXsxp2=(VtUi(4>`~z{f)%Ve3=(;wSu>FiY zL*JJHPFvM0_}rG(@~`hfrs7zuKN}B-Nq8Tzqv%OU9x}YuBEt|qr?Xv*Q5BmluttCH}Q^lKP0F6 zA=A`d2Ck>6{XCJ?qu2)eI300B{ek~^+j+#DmmePY$z!P=%_FQw?Tht#lu){Yo7;&4 z{p(TCxGza@xAsF2XYjxe8+YiLUP&+aT+hbZRFB>h)}u^QPp@#Ge?6MC)T5p}?nz7M zLzZ$6kj#g~zo&C?A3Af3`H+%uKEzbt;}mymKcvApxzG7*=YhCachT!Dk9&GOiu