From 87b13c9e8babae3a4cd04cd18be75a902b1a617f Mon Sep 17 00:00:00 2001 From: zoeyuchao Date: Thu, 23 May 2019 09:47:10 +0800 Subject: [PATCH] bow off --- Examples/Monocular/mono_euroc.cc | 2 +- Examples/Monocular/mono_kitti.cc | 2 +- Examples/Monocular/mono_tum.cc | 2 +- Examples/RGB-D/rgbd_tum.cc | 2 +- Examples/Stereo/stereo_euroc.cc | 2 +- Examples/Stereo/stereo_kitti.cc | 2 +- eval_script/png/1_room_ATE_SP_1.png | Bin 0 -> 59551 bytes eval_script/png/1_room_RPE_SP_1.png | Bin 0 -> 140498 bytes eval_script/txt/ATE.txt | 13 + eval_script/txt/rpe.txt | 13 + include/Frame.h | 7 +- include/KeyFrame.h | 1 + include/ORBmatcher.h | 3 + include/System.h | 4 +- include/Tracking.h | 8 +- src/Frame.cc | 153 +++++++- src/KeyFrame.cc | 30 +- src/ORBmatcher.cc | 215 ++++++++++- src/System.cc | 69 ++-- src/Tracking.cc | 546 +++++++++++++++++++++------- 20 files changed, 898 insertions(+), 176 deletions(-) create mode 100644 eval_script/png/1_room_ATE_SP_1.png create mode 100644 eval_script/png/1_room_RPE_SP_1.png create mode 100644 eval_script/txt/ATE.txt create mode 100644 eval_script/txt/rpe.txt diff --git a/Examples/Monocular/mono_euroc.cc b/Examples/Monocular/mono_euroc.cc index eea5617..86fdf89 100644 --- a/Examples/Monocular/mono_euroc.cc +++ b/Examples/Monocular/mono_euroc.cc @@ -55,7 +55,7 @@ int main(int argc, char **argv) } // Create SLAM system. It initializes all system threads and gets ready to process frames. - ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true, true, false, false); + ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true, true, false, false, false); // Vector for tracking time statistics vector vTimesTrack; diff --git a/Examples/Monocular/mono_kitti.cc b/Examples/Monocular/mono_kitti.cc index 97fa83f..c02a553 100644 --- a/Examples/Monocular/mono_kitti.cc +++ b/Examples/Monocular/mono_kitti.cc @@ -50,7 +50,7 @@ int main(int argc, char **argv) int nImages = vstrImageFilenames.size(); // Create SLAM system. It initializes all system threads and gets ready to process frames. - ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true, true, true, false); + ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true, true, true, false, false); // Vector for tracking time statistics vector vTimesTrack; diff --git a/Examples/Monocular/mono_tum.cc b/Examples/Monocular/mono_tum.cc index 09d7e72..7c4190c 100644 --- a/Examples/Monocular/mono_tum.cc +++ b/Examples/Monocular/mono_tum.cc @@ -50,7 +50,7 @@ int main(int argc, char **argv) int nImages = vstrImageFilenames.size(); // Create SLAM system. It initializes all system threads and gets ready to process frames. - ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true, true, true, false); + ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true, true, true, false, false); // Vector for tracking time statistics vector vTimesTrack; diff --git a/Examples/RGB-D/rgbd_tum.cc b/Examples/RGB-D/rgbd_tum.cc index 0c9671b..1ed1110 100644 --- a/Examples/RGB-D/rgbd_tum.cc +++ b/Examples/RGB-D/rgbd_tum.cc @@ -62,7 +62,7 @@ int main(int argc, char **argv) } // Create SLAM system. It initializes all system threads and gets ready to process frames. - ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::RGBD, true, true, false, false); //viewer localmap, loop,trackonly + ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::RGBD, true, false, false, false, false); //viewer, localmap, loop, bow, trackonly // Vector for tracking time statistics vector vTimesTrack; diff --git a/Examples/Stereo/stereo_euroc.cc b/Examples/Stereo/stereo_euroc.cc index 425ed7b..9f4bbd8 100644 --- a/Examples/Stereo/stereo_euroc.cc +++ b/Examples/Stereo/stereo_euroc.cc @@ -101,7 +101,7 @@ int main(int argc, char **argv) const int nImages = vstrImageLeft.size(); // Create SLAM system. It initializes all system threads and gets ready to process frames. - ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::STEREO,true,true,true,false); + ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::STEREO,true,true,true,false,false); // Vector for tracking time statistics vector vTimesTrack; diff --git a/Examples/Stereo/stereo_kitti.cc b/Examples/Stereo/stereo_kitti.cc index 2e293d6..29d8603 100644 --- a/Examples/Stereo/stereo_kitti.cc +++ b/Examples/Stereo/stereo_kitti.cc @@ -51,7 +51,7 @@ int main(int argc, char **argv) const int nImages = vstrImageLeft.size(); // Create SLAM system. It initializes all system threads and gets ready to process frames. - ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::STEREO,true,true,true,false); + ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::STEREO,true,true,true,false,false); // Vector for tracking time statistics vector vTimesTrack; diff --git a/eval_script/png/1_room_ATE_SP_1.png b/eval_script/png/1_room_ATE_SP_1.png new file mode 100644 index 0000000000000000000000000000000000000000..bdf7eb39116060d6219d7f228f495f956a077f97 GIT binary patch literal 59551 zcmeFYWm8;D^e;NNOCZ4DmH@%s-3cBvxVt+HE`v)TxI=JvcMIqwCL=BW0|0;)1^}R{5#b?cM7CCHAs?{L zqB5$8ke4^2Nf_i9$wB(3GvxZk|K3odH0d6YlRPdGnl38#W-jiAPNo1`Ll*}ddlwr^ zBQiHrCud80J2F;ARz@~@G7A?M2VN$o|L+1udna=y%Fp6(000?4MqEVIBja@4-CKM9 z>G5iE{yr|$hFUK?bNf^t-Y}%&o6=*=2u;DQ)Hlj5Xj4CY(?t1iN-OrcO6sYm$@pYQ zCKtBUjyv3r?a3zEyBnLNL$x+TVp-u82kXgJQmye5IM*GMJ`+5X)2MySn4*Z}!C_>D zLF)kWU`)}lcPgm3|ISgwzzYA*SKL?tB*-@uJJNtJ|6LG9`F}6?KlU7wg4X@TG7Bvc z+K?cFBi_Y|x@*9dJ1GPB43>VRfQ%$2CJ)~G3>?+}k1Z@N4eWYDLqT}4&!M=ghx2kTrSl~v^NP#Eha89*;IDwoEyL{o@ zssZvdLH6QF(6}^UE?neAVyOY8whnZQ1-}L3k`Nx);*5WFRHV7H3(9weJRkIU5zvOU z#2`Q-&vev_=+%D&c^ME|$>w!s1RWmku~2bxb%IRZFTAz-do(5^Vfk*yJm&A;ct~A0=sFG}*&XfLvxwezIF8gAQ|1?tPKO5GEt|7?E*8m)!5wFQ(^O{|;^jTb zX)G&(U-zscj)#i)42HrGTq^3p5RNi5$nfO_Pc9Z+PzGZnXdf$6PAe}vpoNuw>xoZ@ zuC%;7%*R9|`iC14BMo1S9Yle3|Fosi6}YH(GTX$$j#hD1x8n467xi+J{c`&jjJacg z^jkfr=#K&U6#K7!f7~vZxgry+#4en?{Fkm@>+CcWAj3G+DFY2csfWGO^ zuYk*|A=(p21P8^n^z;o?(phHhPHVkYLMeX*kx@yG{~jMb*_4bxmjSS+oGn4InRUks z-JhRWjlYlO=d0x;#7!9`l&`ma1z?Gy>fz&OXg|9z5V^v^rCw}MicR11U6oAimFG-UKA~}3u{m;~l z_I(yNp*K?6uoEpw=|z?pUSzS^V*b0iPOCf%3Fw@jyj&>8E~4|6qESWL6O0BDy0p#6 zPu}gGzpCge{qIiH@Y0vp&Q%qieLJIIutddwpAt?M9v4+GoTD7j0EyT$F9+~o*`s}` zx;F5}vB&?iKPsRGANfnld|NHb7(L9B06ap;Hcy6dE<&$bjF77^Q3aIZ#wO~$gLE!B z!}e{3wQFG~1PPH*R=v+M-S{YvPugnfL=jnN*vI&gUNH3CU!LHrxu`>L8MLS5-qOo} zhzA`TWcWEEIfggrU_1u6oCwW!ZuF(XJB^l(DmP{_g8YM>t_vs^i{sgM|LmIAdHEE6 zI})VV0P6`F|6b8!tl1TBhPFwBmwQ*^*kDW}1G<(=-uso>;=YZB^J+C7wCqHs_()FHbOT(|r$V_azF!ffF^7K&NpH+zSjvx4r$ioY;mA@WpB9bw$G!|u9lHv&Zq~Bi-&a1=2?R-dJS2|t*4gr=2 zuykg%ri8E%OFH>aK0QqjJ6-vgm*X@gF@lXU&Hk^4w z=#-{sO}6@u;u5X|uK?85R*rgI=Es0S(XeS2f|VUo0HVWI@-V-J)1jdO~NAmGl(CeKgbGRtUDjV=pXkLNIrx%z<+4PMq`oR|R`6I}dgN)|CN~ zjDew~U~Gj$-edpKMVnklNrx`_CaPoSy+tO#YJ{b(jg2f8|qSZ0DcxJOTKXmLoUk5 zqsL*d$)`S>L4-dZ9UioFprW%+-ywgK`?a6V?yRdMLjA;zp*j`IZ<7f54b@(l6 zYR5+GoQ)DS{ccCRoHRq-EQ2Kui_Gt<-6L%n8VqRgnXWz+sBptMQ^an?Mx{USfW@s|_Q{c)E zU)*@#eU(x{RSe8weH6x0TIhL{pXPzgf~aLHqy5iJxX_PsjhsbYTrzUO&t5K}Fl+{N z-z=R$=Cu{$LN>(3)9eJDn%yxVee#b&^WxR!{3bUENWSw;ze`^uO{hmr zqbCsV^X3(MtTQ&$3aOKWzgbX5`T|Cs79_D?GkCjS-B=Gmq>RjUGh${$Zrc8xo^rdF zV9ThtVzR`n)igh48%^_YnoaXQn4Nan0pr z>-S$`QnsPjyJ^9_2O0EP~8+!($qsA+XBDi-->^^v+L)t7j|1!!iZZBwK zEU|kCU{7SgW9PJ3_t~{VGKg!`po>Y*i1aejL1RZOpT0Y*Pjh_d{xd%skm6*>lPgj% zKtHxI{QMP#LZS)z{5m=G|Zh?>Qa9Tqf=edLAaY)|$>J(Mx>$9afykq3Ci-z+^ zQ%2*3>3wry98W)rc4IL@rUH-+p3^q4l^3-v@oVSNpJm#=_l?-i{X;>c za6KHK8IqFlqVlE6b{Ygpak^Ux?F=^9CU2j8(dKUSG-Ti{Flqg6r^PrQExSj$s08JD zg3jnGAXzeuuunzy%vg!Z*-JRGGgj)}iRxuS8~~e2*hipTr^Gh~Kd91r%oP9UhE58v z8XRwhnp(*gH5L5MPWQ!7WSYD+Dj~e5=hlPDu}eH+N~Mqhnk=^wU$WBYz*bB&SeIp4+lJ zFw+b_^J>>{2;IWm^ucRR?kh^M$ovo~2B|Nisi{Z6Yf+Zb*y~eAr#;MB`=aiD_@vwW z6Kc@T!=_Z*rRWddlG8Oh`$dmg4iq475{#9|tc&76`Oh!%8HhDChb%1ox8~G@$C5XT zuPQQs!;XI7dyofnFWq}LAe{^kvHTvidd7`J_6j_Rh(g7gW1j%bR&dI7qFYs>kye^* zG&)u~rpt*>W=1x8)U@t4?|QiJN}A!~8L!rd-(Ky4oEQC}TsBU~ksyOi)`=)cT6WPE zJB%U7y>(1rqmUtcy!kG@^F&Q_S_nahn(8Eu#G!AuM0&EH8^?01-R+B|%jXG74{aJm zwFm;%LCj5#zdQiRC?lg#=;dXc#$e=Pw~Il9_8iOC$~1j!0L>vQ z5SlZJWW3%N(Kqk}1jn4KU13m{YrS7M)N1TKpjiGfdB0(mhbel?BPEXnQ1{C`zP|RF z*U}RUZPb|%T{L{KYXHz1Eb-xIOaWhEZ5ov>u}`(M8<5>DBuRy`;I|H_u=gjDSh0u+ zERbM6nE?MW>P5Xh?xxNup7dD2R!O^DmXzVE)D7{P))dp_4Q`dRFMK!c$b`@C-xduE z=+oDd0aRT1MW<%2tSD7vFKJG(7neYh`GfIc2#)7>r>B)P7R{3J{99PkRe8O+huaA0 zz84h*O@>C72IXar~qTfwtg>v%TpbAUMAVo5^1ZU*Onmr0@p-x_C_}$LWD``cP z`I1r&4@oTd*rj5M29NVwLc>$ZMfb!`w^BIU+NxaUi)N@Nhmpi0`^pufYxpaUO@O&J zRb4~w&qLy|N@r)k!CSGhs>Xe7m50uOD$M;8oID|roWJ39V!&0P0qp*FvQK+ICL}9BJ5qisih5aTo#^G_G}_?vNyhvu-Lmob&C#ZxgStzDM-OdXJ}c!b!&}Im z_8%faXV<^gglr$SX@h^Hsto$p?O`egh2dccUuF1k_w7^bgQAi~PuMhg-s(=g6r3$4#$r2K>fr$7y^ zH2$4*?+I%IAn9f?f;CH)?eKG97nf487QdO+Ko`8u_NnKxfB_ZY}@*OtRe7HQCyY z9)6=I6bC5A4(-J=934rFO6RGwR;<-htIj>KW$F!m7PIaK2caLU+}5GxPa4jwEULvp zP;n@8AE`l+G11R}Gpjh~lOZJMKxysO$uzi<5~~3Z-OzIS?`LlDO}56a>bSEvH=wom zdm`k6j(0L$gV5&JRXgK@wH6QFmA`gE)qEodDnZeFnppWHe6kbX{&`DFc8bOqwh7no zedoJX-2byoDR?GVnVOI(!U;J#p4s6|T+L6h6ZrFzF}u;z>!XwUp-PdI*tNO+YPTh{ z_P<79JS-3hvw>j+Tt9j1xUai@p`zMxYH5CdKDla|<+vTyf5%E6m$b35nLR7Y_B}qp zbq}hndp~b0@j7KuxOoaIj826YK|^!l4x^&|EumhN+oDj5DGG`DS`bsiWTTsYJg|2B;ZgOHOto?_nur{^hw=Bw9? ziOU2wjx{YBALKUZo%GvCZ~IgOZvwdOhQX+|n5N*gUFjc;Cj8m#K#n1BtJJot4?1g@ zTUg*+-=D}_jjcEX3;Q$ad;cm&AThA2>y|vB`D$5H3^ig4C*$f$i)~UPED8UTng5ME z@b@g#bL2ghaBo&}g7kDB@cjr-NUwClj z&Z)%$WPer7FQN;Gqr~*r{~#do0GzjBWcjG$Xuh8Fv3BSQ#zucVyX*rwGEpr0qx$Q4 z9eq7-Jz<=gnUR*2-JRgO_(%HjIMidOUiI_!vMSID0avHE-n2SNI-fODTCf?CTnWB)uS;s(i)3 zRwi!|IRwav-9MWFrN-jMRL*GSb+Z%n)zIPS>P|crD0S1wsFQAbik8!F z7iu}HI=E^QSkJyx4Fy?lAMHE0x%^+!te?FmDMDGgPd7SN0a5Ys@r5rDk&$TKG&D5a z1}}+p8UzCa1K`aIF5l-PYU8D9!@&ea!R7OlP3K90o{))jySKd|MInwX=JaR)5Q4|R zzp^UrkdVN+mf&0`VT27E&OT{5cGToiW+UU(&B`lvGX<9K?y9aUSrv->h911074Mxs ziO$j6>%UhqJ~$xBAI$u`WCd=1jJ$f8VSj&cjG9Uz5X~&q&_6fSQ3r)xsIyH6?6@5Q z{)AWbp84AZNGZiBpm*7W;L~Xh!_0n|1jU8cnU@EhJSw55N0KiY4NbFX7iD#mjP|?kr$_Hxwb0c(%hGhYMYSeP zI>oGKxW#sNC(XLCu8()n`)1A1b@}+#B@#hj@)E|X`y#jSHq)J^^OThU(9yxhh~o<|Hn<$)0?()FJn!e$uO2W%&2`^^mtJw zF44aGl>FNj9F@>33g_FYy7#IZ$>}~sh4@uj*X#Q^r(|o$NLi??jKzi%+9G$WsN+VV zjFDMi9oPFqfXEruW;rh~J3l6moHED~-1AA@dMLqAJekOAS{PW_e*K-q`%)w#B7%mN zb|*KKWM{GK-8Fr+6M}wJH8hNY@O0|sTfd}8w%czeP7ZLJswyjEq|Tdz@;mfS{c(va z2Jik9i8-+@*)U{pJ(Nk@2iE27?EaVWD@RWvn3`HhyhvXs$6@Xs95*Rg@X)kk%O*3z zZB=6{n!K84=bmj&j^xMmt_QuH$%m@>MuK*1lHTsWj+h9jk&F99#G1ET(y4pHo+=-A z3Jb%D>gg9V=M^^S7yh|=2hak(f81+xzu0h}(0iP5a7;K)Q_#OW+z4E*hg08=V2O+3 zJLnqZ90SI)g|fLeJYf7~nL2(KWqBb-4)k(F!}PyDFLpsYjIj(=+pY7y`U>IWYTe}V;nTor%pyMIOXIoEi1@RtE!#()carfu?VL}pxVaVjq8`QBj z2EAuO#;|+{8z2%uaTMb@f2t%_LZL~ z^uSkfsUYh5zrWy_E#r~B8|~DFo`PXDyRuIF;e-{OoPAxvAH7?m$t;MY?1S#g5`1woRWAi+;k1;kmx*B87D+6E+QU%hd z%hZ+ibjAjkA#6!m9F14Akq^e24&?2IQD&drQ_GSZ&movb>B|z>e4{96VG9up1R+#5 z9|MovO@;q_TlZezHx+|Bt9s#_n-C?!AW}+3^omw3+b+YP5kNFP3?Y~3Pkc!?PPnJ1 zs5$od!I-m9fk+}O05NR3f>5U8-Pu?PGHlxS5*XSF0z3p3mfXNl!R%6QEsY{ycs5Br zdld&01lEA4pGQm7t{qN?wWgzh6#RYK+e&gVhrNTF>6(Y@x{HgG>zBL6qe0q2dtEr~ z+}pBkhxf{$^)KZ8WO>m<0beO`t_d$_m_iF=Sx(*Bm#Swak1*x=3{ryBb)(U3A|s5} zI2OBaCd;;pSYZCxZcaEDl+4PgpUAM}Nqqqvo4>z$-$RxqN&psC^3OUDBQ4kYx)8q8>8nrw&9NiB74^AlUO6x(y^R_D7V?rgSK&P!KDBz(Ayb_J{gnav%b zHg#umOeI}E4h~%}KO^IwJyF^3y&1py-Gy3;xtzGy4zHPM$b%23iknFCc=vF2qNZ5o zdJ33Y>#_Kc1E<@q@y4<-W{djt-=XchqIW|{r4g=8Ulpqo9BQ+F@}>1!)Rovsfy}M? zl-3Qx!%Mq(s0#OX^_V{6e9~x5P(J0=0 zC?TqjOSL7xg;18*s9|$LF0Y~?Wyb}fuOLkQ&FrGi-_cyL?6{?spZV7lg&*5aBxbyme0D!NCq5|FWJzwW$g}>w8-(G+g%<3r=>IeZ!bU@DYqk43QZL8 zX#5SyNp+e(1bSK@9)&`k5zY3QK#yc7K;*C?w>DikQGM^878JZ%RG{O(Umepr(@~Jd z7GJhq0PztqVTh~tcJ4}rsWSu#BPHacCr1LO^S?z94`@-{%nfHJI8Pg{+m$Vz3>Y10 zVH~BEWm8fq1;v1I5xdd2x+9qa$HAO7z~SyqsKvcxXBRyZ&y$6kZ-QBFR(~2Njg%3> z7#k;pMZh4!ql=GJMX-*{m9vk&k{lvSbBjXC1lGP%Y$^Qux-d;ip``8_iDPhU3LVps zv`j8MHwuu&OwOL;CwshTSmxn)pwbCs8yl|bBJtji8M^TwITx1-U3i6%34kMoEOWq1 z5^kJe+sW)^5EvC-R9+slUe6y#-Ui5NyiM;CNQM@mqyk8jB+z7|gBu+bhOaK!y30^e~6w=T+ zzMogsIlp2mrDmoPa1`@seo)bto`vZz&NrHxT2<@lX09w81s__t$Z?kxT#oR8<`#ZY zNi4<6UdcW0 z6XLdc6|l)6!REAT`RFw?$h*HVpd-tef9!GPUoaeZJYb886D_hNAQ~JmJZ2kA{W;>z za0HLs3tb~F+3;tl4&xg9ZCJcFvX+R0gdB*YoWoCIm9L^XNPql8>b|(*{{;(7Y2v@FpRg7KXHSC22 zEO3!F%>{gtD!kEP+!`c}{jpq(guV50v0XoFu=kyY{*TSA1>?x5@hC*=r^|5bmrLp9 zv2X7ICny;G5EFZ`+%teXBe^uDFguI=UAZK4J@!e!i-BDHpXDWNO3mZXj5z}!6$iZ2 zhwq(%>hF=6P;x*@C|Z!|Xtzn8)65roLQaR$zJP^kP337@EWjP5wXuV7Syiadi82z+6g(IFJrerQAYj6(ZBh1z00f8NvoMNa~TgVU@ojo#K(@%}&5#mX> zG;S)3Y(R%54;mB=gM+hzma$_*BIHy;I_293O1iUis=B1R1l&=EPA>Y6ryC3w{ShBG zqGeR~=>g}m3iaGo^BVRjV(rb*udd}cnwgvLy72yNvLp5a_K3$fq?Hz{3U0d)Y&=Ov zceH%?HrF}Q&$N3k(b8(7sdB=LW)8O;QFTrZ=Mr45*ldpnBI1hMFf{vWYAaffu|${Y zkB*^LU3PJms{|Bbin=F9pA{kXfU zHn?_S?yN(kKz7!T{o+PVkpc;Yzh_R{Ft29Lk3Ri9iJK=U^GIt)sXZmO;_*xB~?nVp_f&Pbi4Us zq*);ccdlC}d8P;~AQr-&X9k%EqK{ zI*Jt%p$d7FKi--9*{K~pWYcK{s&1FEt>8s(a3m+>fB$T1@}GA1_!d=FX_j5cvh#ZL z;=x3b{9iaT8^gPGWAWp!p3&ABH@SP60*WiE4H~9uSzXJ@VPmE4QVb2FcO85`MA4}< zL}OR^T#r@BUhS&&i8?b^Jz=ZNR8XD;uEZ@yI)`AQtpf${b+!diDJOYCcVYqu!0@it zk%g}BEsa^67?0D^-lypNqg>#5Npf+M=i7L$$6tNZQR;Z+$v9>_#Htb+jIU#dsPAWb(V|(b|iDq#;DLA+9}0CDycT!+X5g zhDC~vjvB`~fM#Y_eRJya;=m&AxNo%vaYySt@5W5sZPxk+ikPC}e~cFd zM?cZ$_I$$N;SuJmQ-^`#=#*NVujxSJ-Gb6=h{)hO&%xBZTiv{u?}H!IV`<k94Wf72x?^i<_c{3sgwX!!W01TG5bYEMtx zK7z=CkN)M(6G&ymEeh26*4BMxwN{*=BPg)YhOr!0v3PWxl`7ba zW4>_`(9$wvVObQH_lX!UdUKx$<{kHWqQUSfA<$2Z{p)9@yL#aKi6VC!UW&rljrzzT zKaOlszD1<2p`rSlHY(*;uHCn92=pO_rB!`6G^VVCJo{yBG+w)_c1`mptd47rL)&*= zPuroSy*Fe)M{Etjw1=f(c(?i@HGkv>;rC z%UKyNt)DjPnrELy#gle$+QRQkY-0AUm5kX!(Iv{t`$b?#@>Jb5Qv!k)fUkfh|9-Ys z{Xy|yDag*xd4DzJIIDSA*VtGR$d-mnfVsXQ(^854T~>{=pjt^j)xB-?4W@2dc)PFa zwz$JQ%aaOl(e>f0xfN;OqXfnV{i={^1#l{58qxA zXbYersf`wY5%GNgj^F7~Wk(h!1x5MC2?eh6XTH!0bv%o-LMuS(_?FWrc@H?u)!oDM z)-Vd28MuY;PH8wh1x0i36VWhT)4Gz9+a3wwRs2)!=!CqIB385U)pf7*>uV=4I`MZ= zQRtWZvp%fB+c%WS;=R;K$%GMKAPcnHx$53}GDAMCVAf+PZ6_o>;ocj-p+0c&Gz*>+`lPFUnJB5HXtPCaS=IkB;bBjtWM&IqW%E)WG&U0 zcsX4S^cxGDus6h6iixQtCzB-mtLrXT!2N(y?;m6}9zvHhG#dpaxCDd?8n;~y-jmjA ziRl^>N4FqV;;U;cZp#&MTS>1x`ZTQ`JGF3c2V>JPFqlI81%?9Vo$p^tPK(H#E0KMv z6xH|ERaC;ON{wKunZK3vEz)eZCPG+rsR=kUeE1kNLW6l)2othUrLkPVpsnimO^EdV zR9QoRZ;!TaL2o^W**nSMQ;UXRfByq-nFd2}n0Vr-v&{WzZzN7+8}f!1irGZ)(d@iL zNugn>`ns{*oFo6514Z-t*oqeJrnBM&mmd2sR3+-?FIWq%oK)0oHFU~%euGbM}r1&`Jt)Ycj-G6H$9 z+)i_#G}*klov&|JPtRvvGcUjx2agkG5teCbNDI%nI_Q*-Acxg^S`k9{29B-!)nYeP z)4wrazx;6(+|ow;l!}{q0}S=^;G=SBfcJJ7uSx-OZ^J%b_{~eCEPHRkl@839y|Lt2 z7Wf;O<&jK1oRafW=2y8D$j3ur`3#v*-0!C&m5Iu8D@Sft)k^k(dzNY-wy;*LRNh45 z7$l3<*!2sB3pZz`<}GMeR@TRV35va1L>xX=$lAcF!0d2rwM#Zn*3+ec&Anc98{78p zR--#S&SA9lCfNglSy`3v-bF=aM;8#C>-$?Ad2TIWdOG*GR4|(tbAGOPz?6<|z9LW5 zG<2oe5(kI-4d>L|B%v8p0V^aLhOV}kh}r!I;y@51b`G@m^SS*+@WO401q%%vA8`d@ zBKvB|d$TA}|0~=YvMB^SKJ;O@``F|oMnWtK)5*Ua&Zlz!ea3TdS62Pa+k>#!iwrxL z7_z$V3-^z+JnI8_HoLWb)z)V})jUPWPp~M{jUe0i`I{C(z|S*Zu7;9)V6U&7LeX(N z0SEH+HM1NQtxKjcE9+9V`6Se&&(mHq&xb}=@A6qvBW1G*c)e0kwvD*YD!;n_yK+nP z%k2Be=4O=XVY_3;+k|LXPydCv?5m9=XuyNM@yuRFZ({Vw-9fz1J<60W z!v)LxF0s@>SADRorlws*d$i5fbt#=8yym{7sQF|+J=G5Qdb|@kte~hNlC?}n1b@wk0TyxV`DO$eT+*TU89o&ORkqvcbETHAu&W#4DUswRcF!Z}SDb;4D zf^9VUt@E4J{F(=Rhy%2$Lg@W5-;gymDkTMI{B*rXYzNv{x&xCYdTMXTB)x8X2!Ig%6C<+o{cl#r70cZk$)45ADy@4H2^GHw-jTqwD%FiAhZ zx;D5-NWkg16Tj{;l|$eA-hMLAa>YG|$X9+$ohkTVznY*Ck6do|%}276Hm|jgRy=iS z+s`gM<_-G2cvo9u(^uj5b(T{$Z(k&Y3t74qy)Xo0rjvero~(FqO6i2|Gm)Hyp~beZ zD?yDLEr{tzOg!$~$}5hB$zB)7jy~`&xq`26w|{hS)!D4cx4fE5OrUbq1R67gf=v8_ z4S{cXNQ*c)__CoGTyFQy@LxP$?t>9}t%@p72G5!{?Ev7uZDu{cw>!?Jm%jPE!Syxk zIaFdCuj~w>z7)=J=I*};yZJX0Y_GmuS6#bTF~B_!9n&FH(M{DJw zF`4BvyGkBXh zjH%V^YD}XzEw($S!ipC>UMjgmE3?u8=r;E<7NH*2FDxup@!uV`k9T$&i#oL{fP(ro zH`v4#tb605e(a+ZaQ>zVR4h%TwZgyRq2eJ11ccqlxR)uh&jPoYQf=$R_J=N|Lbc7@ z9B6`^>JX``Z7@*QddVi2v3ASfC>DXAB&wCS^Q}KiJZjj22dNK+-NYnL^9R;3t23{fW$fTCB+#dGPQ3Fh$JRSDqdrkSySPK@ z0lIr$DCRC8c2MUD!?Oq+o!R+szXj^G(kEs>AEWk_4F=!cT$^o8O~3j*&t`i(9~G5U zRSoSqIrgD(U9!1T&62)w+$8~te7V*?4(_D z&zrXEukSE^oEz<~P@S)1lS2(Rz=tWOCqKVxaMNWugzeILStONtK7%uvNy$Wl=j|C& z(8)+cOG;j3<&KC^$4j4{w(_3J5`bkkw4?W2GCEb1LzT-cHTzZZ6MKYaU?Ai;9g1); z#&jl$!KbwgQueg91u0BPVl3EMbFMjCm2y+mFL!nQCkZw*ID}8jZ32chIh_s=HSR@M z>v>IP39Lcn=l1InI#_6^)5d(yHNKD&5A+y5^oR(98#4&B7*)TmW2&p%|C8yLFcyoM zC+kv`jddUm_CmSj%~(36QZt#ivL(n_Gx;Yyzo({6h#W(Yi$jkOZ(?rz`CQ`0Gd(aH zxh=DQRw0O~6VWt!W=54|ARbGzsq$#A%)iQpb7HOe)6n6xPb0*f-@d31;rRP=uO*gV z`ms;FkH1Oc;j-3q>2q@j^;oHKMZ#6tnfZl>XG(I$$of`(M^8*v+98s0+0z4WdNAS_ z$ywd(xt*^KLxlC=uJ^{kyA1(UV~p&Hta1F&q>_`>hL+ly>sSoe@HDBIU^`fAcqVE<}H?VNG*wLq=<#LQnh5Zj<$?-rC{3@Yy)noRD!6(ew%5M6_&;5~msoP#jiv`35ZC*>G+&Z6Y|ArJn3>S_ z`MP4wo^yAMmya}3ZyJorcWuGM7*n7CVLlfY{Hn3n?`nFu(TLzVyMEVK{)xy^J%3u# z3lz-Y&L`+I5uLqL>c++?Xf3+Guy5JdxO~VJQxjHIUvR>7F&0*pW99YT@pFb!-t;Yl z&dB*isTS8@ovfwQdgV$-t?;kS_2hALIN{0TYz3X}`k_D9ZR3Ov;w;=zdZhq@d-6g_ z&6YYIjP9NeBTcWP3bP9bKZGvXH2Z&@#*&WyRT*MF8`s7_4E7atLd$pe9nN1HaWcRy zEiEBN>>n_!tSpq9bs%<@JH%+I7?9RFCgi95o0Z;!uRpHwb|Q*64YxVj zk?1K)QqV&bEwE*Ye+WDDj7nJ8`sgFbar7rQch8N7CvH^}u9XFol|HF(k0q+vqaHg( zBQ-0H;PD;A0Z(J`7jyn=BdDpg0DO#0*YaW~x#{PZefp5=v2lX(KmB>9czpBie0{q} zy zFz7aJ00;iw8c44U9Yh-F7xv~qU0QE+B~PT5gSj)KQqnjIi(R_s$gL?pDsq zG>n7u%cF`E1yhB*uOzZhUvj-SPUQcydXjm6va+^*I)-?Y-`^gVQN+{bzO?Fa6Qi>? zX`?Nj&~(>mi9sn4o|teTDYRfzZq85nSG5zAwITZ>V?FvDrxOYB$F`^lXi~*|1-eliEDLR|?vx^apr@a%Ov@{gOVxTwEKEwZ=-U3AUERrh)Md?56C zR&o7TLQ9BDv?Ehsu5j^_XmP$& zU!(0YT+q*)!EEqwznw0%K_fG}!B=qWRJyr&-?S9Oj`2IG^t^h@z*=eOI)mui{bEpA zcRa#xn7S>ZG3&h{Fy#&i}JE!rVpXym*(t4lrrnPfNX4x)R{dk=ly}mXfTe z^yC&6?nX_TbVZ`)3lU-TCGB6(@wgR@E+RT?xd(Qk8G0F~0KRr}w=7 z>844qqpBNC$xWY|jQT&`amWM=c$c8jZcj<X95VxmNO#^T+cF0z|Bw{kH@c5cNI}4qb zd$~*hEh`EB<-Ww&!21MZzhcyq5t*5%l zt*#HX-LSwPKUArFH#?_(;0qht&|fSrutKVCc#h8@I!Ybz@Swv%2GY@)PLUm&E$2iF^D5okEn1jP zqqbd!DZ#`iY==?Kp;iaOs(l%zE z?yb>csm^(UUb-wjRb-CD&IlB;`V6^^9ocpuN?3TT`BSM{xn@f|fZ259bBy3VkbeB2 zmJr^w0REz@?55>`+xIQhM4`)G!NM&KA}NSWUqheP6~#$^4R{nEQ;XJphVT;$xW)K- zAtA?0aK}bddsbT2zaKp~g2@E+;AkZz7|a6aQ^&>OpvyCO68e&uhKkE~S{?P-ygn#= z`D~G5qUp3r{3_JBPnjE*N{9bI=Sf6rMGcH0B=KbGR67^(;y%RpK%Dhq5I7HX(T9x< zmH&9c81;MLtF*{6gG)Su1h9~?k*Ed_CUP7<$vl&;@-(YFA$+#kfED`*sl5&j^W%|Q zQQ=WGllBB!)x_x_TL>of+JIe>TxS|~#O5Dbs!R`e;|h`@72;ip<_CsY#67I6RCBNh z%UHL~>Uh)_eDwQh%NTY%mKoZ-! zB`c#W5@uMuDf@j6J7{*!mh;ZON&`-ggX4I!rv_q0gLNUk>GYX{;yRl}(7CX?(*+u%c0ZMh86zI5bL0!1fv;J?tX7>Ap z+PAe@R%LcA^d10HtwqmGgkCQ!th?=^%2u4+0>#Bx>QKXV032j^MGynIs%b)0&~I;c z0**t(U^G%M9sa@^V}mEBI|GO6y5;iLW9%0|&( z{Mi9M`;I#*g`zr*6^h_6Ih5Fr1j85_O) zKISER1@mI%KYD!MWIB8u!1%?x#&S_!Z~H@fp)h8XWi# z0`{$h@*f+a%Z5|JOM+}Mp~-mspO=U3AfTk)06un=5BIdP&(WKIIx6GOC?Bq+T7zF4- zvYsE8D$H);u>H;TUZgCI{NaDNhUp_6l~?H#q$;cEj5=!Rh84}jef3n*u$^iko70(f>F73q0S_=;5{VFTObdvE#rcAsH1pZR;&9&RP6< zj14UR`$H?lTUw!h<`rVcEaUt>0WRBiFX zM?j0*)~{Y`r{?bq3`Y)p_g2m8{m7K*!tb6N?w^_$&o6>PNef1nsR))UyTeIJ^g=?r zTePd0RoUcpOMl2}YPw3)mEe+-;Ov)?j}{6oBM4+uh5LGgZ1V96v=AZ2hUnd+qfCD{ znVrX#p$E`%ba?Nr?H%d{Sv1$m3XK%nOk9(QN#v>wXGHCsIy4ik>KW8p{X?>oPXXaR z4vc+h!^qJSx_5EmX9Fak*ZK*KgK6dOo-W7Ffwc$TlI%~->!F7m@0OOp9w)l|OClv7 zk-bM#yF$?LBVwvJypeXcYs^MR=8;U78kI=2w6yZ0ok8;B5^*P=+tiP*r(YH1oL_$? zoGf7{eNKD7_n0qz07FjRHId)d6%efj=!tP?F4|;3Yo~E$-@m`(Pv;aBAZ&$#imzhI zhr|S6%HV!*gPAv<8XXu(x#7=MoV`9FBX_+o730qFM00ZGav&y1|FOM5FP6Ep*(`v!SteMpgGz3R&)fRtg+)zDlOAe;G#kCm35g>W~e zwTBMMH^X!IJP-JcdA*!_k#(B(A};$q9y7AD5A9wnn)@L?#9aC3|(~m0_u0(oys@u4ds;Oa3FQ5c5s8oma4k8hWlM->mtG1uPibh6p ztwwx8`9XcV3}1rTJOU{}u?t1-o@X=ovB!r6%jxaCS)^G!KUyrlODY=9Wi~*`!h(j& zpwc(>T`_;|@KAgb19;y;q%E8Hea}za3bJtM&TnKOZazC-JY^CbTrkv(a)fP4EP`==yzU#{sDcF~%qi9{KNs z8h`(gy=v)#@K1n{mPiQZzrV9+y7=5~wd1Rn5S_O#6*B%M3R4G!&nCJeVKRP7(+QE) zz-=x^?9jIq09?)P&ejFJZ&*XIC}M$Qt7~cLr_;4NfZY8s@OiYs-k@kfaWc`zCr?3D z*Sb7Dd;j-K4u!gT@a~00BL_3;JB5$x6)P*?$VfF*lgGVDq84|DY&Xu7VZkjCut56j zN0Gpw0FuwdHMB0zV)N)a9vR53|uF-q{2m$<&_R5bP)IyxlQiU=?b zdy{V|==}ZtQIV1J2Fbmn$1Ll52X(^i>Z7tElVzhAaVgU$35q$mAz#icItvRUKpCKk zf9oM@t(NBIYKDfSFnLDpUg|0;D!5nSK-4&~Z8~;_m3KtxH_=boE;Q2CxIsV$cDyoP zVoR8)8sqzam)w=OAl|+{L-yP=UworNtfhPEk^|ofpZ-lRaWJ6H{$ZO93mYDaNe8Iy z!&iKgD#I`5zJAEe9a%sze$I?T+> zRP=qgq5}Q-u1GjCGGZHO^bbw_A)A~lENfF>e0^Hj1u0lFY5au}*C{~*0VU+-D#ZIN zyv<}1{5lJl3^!3)X>i!)w;n5_zp#;8kK0~m)cHZAfJ!=CE|#|ST&@B0CMuU=5(*>J zw5pQkeO-_Qa#?{eOwnBjU35%=51geg0AnRzo811)* zv=G`FS-c4NZd2v>_hu$b290U~DsKs(shtnDg$ExD4V7r*qA5Xt@}-d!R8>8k$AOAT zGDoabtfHQgrh9x!ElFuR1JIG1#Cau*Zn*_aiEwZZyOmyN-Ci^6XUPK0)}5tpb_G8^ zL{L+g%@*3}7W_P=_j+Sqw7tDe#mNaSR?U^G z;MP0=ME8>&zTR8AyS?M%RqBJY@M$$6v(R3^U*q9IQ6`GoC;aP=BK|-4`1FxujqLJ_ zObDPr!f3`2BvDiNA{C3$En{ztOqhyKGpMK8!U&S(4vv3EM@BfmT$ooFwG-FW)XcYi z;VCFABr%Nr7h=aj?8b8X_N)b8W_J!ITKO`g%IlLYyjA2)PkGhNJEF)$U>Q`oC8+%U zDJ3ZALB(RC6E)S~0y#}@x{J#iD;KU>dhx*Zc~E;Xd`-Q~vvIN6q%k=;>jf)~^s_1$ zdgo~}LFpb%yMBu$4!teaJOh?Rt~}3W!yX37*=cSw(){^InV6X1q3j=8&6m=$vz0-N ze0&X)gU(~wB55EkJwtq*@)W$+0IRb9h{3MApKb zi1o5AQ&fzY_3(>ir-_d(z44-0J5mvr4%cq&qFn&9Gy?x;pvDUf?(zX`@USN>8n8tS5_d_ zjPWTU&;xqK8SAe)VdJmbWV8{oYW24LI9_gtp_+>-oRU#e)sI&JPlB_5ukqD1U`?;A zgVTS_!>oxRSqjbWyWRmJ7RTLe4{9NyH@%@4(v7~nA^)E6Z=qv1tPC@5@@zUiA48Z$ zz{w=s(74t5iKL_w%hqf{^w zcoPd3AGgDSk#(hZYLIJnVa2^RG4kG;J;X8Oud(nC3I!-owtQBbvg$@lL^ba`{V8iwe~ z`5zFqqrRW?ROqB~^u|IObZ7Oyng#?9XBdNBPDm@_DGkR$ktq%F&R6kS;#=$psl9GL zX^HR>W2Caahb^28*DlvF-5N@mZ*(B>@%1Iq&iVHa9P%9}sd@Ko(r8Uq#pP5~a?HPl zk0V!2!&ve>-5zxdgTBX!h3YhHkuEi3>-jHz_FVcJP6CQoLF%KcmWe7>;o?c7AA@kD<=RG4M}Y%D$Ku(DS@CcT_~WIIMJyyOsAmybUwA19$<}0=I>9B;;}KMk+HFF zz&_&~(ZWo;S$QwtqAX^i=c!SvR#e7($=tLo^nx~G3ko7Q@28=&)t5;iD-=|5(XL0} zlL=>13D||ncNY#O%aor;I-ZfXKE;aJKol28YGG z)fSg`SzK^%uaCxIOR1@;p}@IJMMDFZ>wEKt+-r|2Y}EDNS5hH8n#K5wi%a63DA((Q zk40g5Dn?CkKhwnFxCTA_MY9 z!lb}d${PA{KFZOhYh0S1)7zuRzjtK6^V-YhNU6Y})OCqQkmumc?bSb6nD%^ht`hv8 zR@zK`_cyY#LQkIG^IFwpbr_dWOV1OJF07@s8Xk5~*O-gvSt!X_|M{j$`myis?`$GL zM@m}x9%KLKklzgen@!j8L1b%pyZiOR;)t9V zxxMjI1KB5WKg3)g*gjuwTRSB5G z+0tpJtAl>h@3*H`*B~|2wS{2#woVs@`j~fE8Whcu%PzQi!fVWM`P@@iUNY%Q_#R$g zxQ^qR1V*DwxdSdPAPZxrEv1ywkc7N$Np6~_>$%DG5W*~t6M%09_Ka1j`1uKtu*hBC zY5=k322b6y5{|s=dj4?}bxma)5pHdN7*^B##p^@UZb~U;17E}&{V<~h;mEM8ql|QQdT55u0(J9FQdPO0>P)v)uF%E-)f=SSj zpWi%eUUeSGw_e|~=zF&S@1GjXGKBwhuhC}W;>aBAa(RFWLZkc*JWOpjXwn+~^n2)@ zl{s=Al{6JfaN-!OC*83$ifG>Dl$3!6a^VUV`8Gl|BoI-jje-QIMcK}g1mWTTQ~^&9 zhgDzs9f%1yjE)@B|1YHiJ`}#C0oElwg*3vSSW8UrY82RR^5BljZrD1Dd)>+x~%bqL5gwh;Dx3F-QxJ`eK zvSC?`1gg*CL8@xIh@2kD5q4uvW&aQfw49rl;}RbFE&rk{C5UzO>uMc?C52#@(#6Q* z&&g976+c>(YJJlb*Z4~A`szGVeLVO5h%NNksx=UqK)4TCB? zA?lJAfGK*pJ~ySx2Mn{MPeDo()Jx!?5^qGF%EU0Fwf%_RVzK!9zn0N`UTWre!B@P= zJ)msb!c4g?GVrh z`>we4^=2A2j6^L543g;W(KNHEZ}R`f5y!hT(>+(=;^adBTi_MLq3|Pui6WpvgfcOs zw$}58jnZ=dsw0?1eS`<;fC?xfYZsEmX0gApu_5}zXkT`x;bmn&W&@lWu2+mS3L{A0 zwDFv#Odwu1OkS{pc-R4X5-$+LG=JF`$^cz^z<_v**!aFYXVtL zR+li@MUz8NaxNAbDEnEl2ZeL6K7fClGzTvJY~26jMNfzdQ(8Eu?H|Sp<4*F=9ryG( z-X}u;|8HkgVf_%f@pvMQ^%8sV2j!iDv;KW8qhxZW_6;tGia*t6P*Vf+D1@`rXn~ut zv&HE`RAu1Gdx3;CV9dnCxY&T!J2HxmzE+vaHu+cw@NMEbbkg>6|2bah@$m4vaPZ(c z%JC6^@_fAfCNM3H4GVm6`F_umji+ya~l3KM3 z65SyPxAX7a1^tFc{0KxTa%_Z?!U9Lz8SKt@Zk&7)z3D=&g$mR3KU7B?waLDl0++t4 zFb~wk_&79;D`jI-c#+75XDJ`(er3J0o0K~6a_VsT}6-hP{` zb|_C-=)=EA{uU8*k|Tc>cLo{BT-}hPEjT)V4;I%4@zlrj;-E{t>4=HyZAZd1F|cNQ zure3yrzrXM4W3NIUB=dydA7V5{3V0X@Q0z znHSc`^Gw4j!SxX?k-SaRyXbL0rc6ueZni*c^ZY0cI)$;GtEF4SB#*wy^~a2no9=6{ z7X{j3z6?;MenXkjpnPI*joBdo4vsDYP?`Q9Sz(dOERlScfdN_bo}FI>>*<#XKP*Ut zzZ$DW5ikyq$=rvaogwDA1xkRi!p2eepg?t)D%B)H&Rgw#jR68eM2mkg5}$?BX+x&| z^D2257Dea_YG__7kjV|bANkE3idCAg$KHUT%e8cUXoO$o0B;uEVtH)RvD6Ayw;oN9 z6=)g8q&^Po1Pv?fR$!H~)#H@Kph>Prd&{U0C7xD3yfkc>N<@T&j*c#-rBC}Gc6lv3 zo6d9h)8q5<52YQeo6Dd^X(T?Of`u`S!Q!G?^b*V)vd0k|N+<**Q*v|bbJtCQ!051w z%~m^gu3}2Hk>icozB}$A=oJ{w>2+oObUsMod9z@3K5Ot^W=Lt+=sMmo8^?ftL zi|H!d2rDj1HZc zcW9maUuq5jILAPldLiY>YMhf#ZWTvxj}#v4SvyV&IGCBjT?o_&OGJyT=ey)Ubat~8 z9uuv_vtw-be?L@nziHLaplTD~QZfgOdSc4)LV;%XZt3&av$Y^=nAG~if+m42ok~3^ z&e$x{wWlwQTiXGFLF#%RK9MCw$SNl%b6ylqRx6c>i;oo#Vd@}r%6qL{&%uBOCt=2m z#UodKdcc9ilPpLNXVB6~1OPiJ0JrkF7-pcPUiMh^1*~Npo0Wj%Ep&?K;jZ@SfsbD8 zq(Gs@{jhb6A&DZkyHz~g&yPK%(wl{tXP6lOu;R_RwY%AEF$yLj@&1)ap&Ph_(u&!P ziu(yKTJC7!C*hkyxpjUEc1|34WJ$^BES|#@q9$^o!0*5j?Q+8k3kyqXLlus!S)|k*C-D+qs#*MTIFSxBW%u7{L^?2C zT;u%YsU+k_+7D_=dDfAHx`wQb&sYTU!+N%xy&YRiONjr?HvGFV`sqTFkcs*}{N#H?6_l=GPDgwb*bPlh|7!6)Ffv#~t;G@9hWI<3;?OoE+QrKxcJ&TC9+!zsT7)BG2bdhJzCO-e@+gF6SCnSQfbEx3 zbc-BLaLp^pM*_{+`=z+9&#n~7Dan*jWL0esLg4m+|J@OwniDPHcLx&~lwb+~vAxMm znv}?}|2&bDzH)ZwU;N{94gkcwy3^ku{^V~I35Zr!u0YdEc^kdm^(-scf^mde^_u;q584s~()OK_XLbezh4R&*kB!NsgZ7-^pgelKk zK6L|38o{r=B^FjR6wtw3e<=wQs7uvk^uN%?gS|Se>ijrUrtSH1zl*JJ!;ZUZx6CyL z{Mb5E{>&PuA@J354O}`1R!SQC4KXT}K-w>|*?94p{jXl{!C!TTK9=Gze-103fcdbt{$c2cvJ#@q{CX?TmG=b9DACUb#LY zuVuwyE#l$BNJ_@LI8)~BKYJg*{rCb4ts^Ht<0THDc?(_-{zIaRW+-=(fLrZ$r~~*H zQLE!QL{TEsMi%fye%28zjWWcw?eU7tU;8w^M zP1iVzv)THHFT*XV2tQE+!xPR+%zghb#Zd4Leqtq^CwrF@vb;j$bRfQ)a%o_QroMhT=bxP^6{jQiT%$Jx|4$CWFn13xDrs3r!oX|hDT-iz; zZ;>7gEJIZuO@%BTx?UAd5tjG%zG?X?ntnZVw4g;m_Ca=2Bi2?tmA14SegOMIYYSiL zPc7Z!@xD#D@s7YMugC5G`xI|@EGI@%ShCgsXd?kVjV^30>$EX0{RFyX-ZKcF(O6yg zBbRi+k%%P@Og$OpXDqD6dZ$9o#RlI;cT_Aa2GF0vw^*%?>w%ghZkq?v2hv!4N>Jva zxdV77cE}QZ0KeO@!uzGh4^71R$;o(&;veCkiNTOl=Hu6}Zb-TJ^~dM)vtD~KKT&Lm zP^H0=Qn=2a=K#%Bto#91XSXFu$)g};DhVslNXPG-FaL^?Qy{s(CsKaSIL=47vcES z{Os;i_Yq+Q6fa^&u(A4OaJ`m?hldMbZ;s|`;3Op_{}BP4_Vb)!qrfwD_rE@4?K{-=@zIFgfL8sBlSz`q-j8Pa}e3z+=y^e&9F z6ax{G?ucI~m+$#k_#Nm%P|W)*k8$Iss-vgb`_!%3zHTAzVit_2ASnA?3cl`$_(SF~kxMP-yVq(K3lL@k1ZumWQA6FT%O)$7P z`1>km*68R5bQtO+Ttbb3u!DEH_D=L@uJ?4f?fE+4yZ3JWI|A|A*URFlm9dwG$$U9tNacP}n313D%VX&ip&Y*}M=u9_5w=vNYK4#bpSHe-!@=i&q4~U)`|5rZ%vjSLM!aB=efhxMkv{avXd6W%~=vuD%La~r`hQKrpeO&gKD+Jz#F#$niXuUT9TWH*__9cX2L-*ei2pbA6~B<6wz zd$;}aIJr&n3i$~GH%|(%F|cvssAK7H_Vb{lWt1#&jHeqC;2HrW!2Ij*unMl94h#yX z90Ef?w1Q`T*Jq$3U~eY~8~Ro(s`Q5Z@eUMuR11N_U>$qi%@2dllm|qko5M6;J>Q1^ zJp3^*^UC~xxr3XxNSb?`KWWYBeRDKmxKRdZx`N9Q2H=n!9edzui@xPWF&0SMvr4tK zLEA*vHu{N;-GBGIT{Jjrz8Cnm@0!PB^*?}#jR0-M`&8`T8?>;n2#<;B2Zn$sr_F(u z>~B>B;Pr{i@xtq+&%J3w^x$j-=uu&KS&$su5VwJTJ&2o|NC*`j-r3nCCT=jKgt7j8 z9U@Cmpre5b<}7Frh7uWq2YmsFgJpdd3J?Hhm5Y}HOK~t(_B0xOFTA?kO0_RbEDBRz zUT?0I5Ak>b&Q}tqqgwB*Wiq@8G=^BM%XHiQJNq0Ek1<9^1YBKBpLrcHtu0suG_8De zYjZ`JZ+k-|2nL+ot)~(1?#$N0D4=eoMZ8$f9Z z-oJ`{TKU&b3Rtj!(sam>TTvE>iB5a)Ct`c;D|g6VY4Olqod3kI-!tRea_wg%QoS*g zgJW*%JvST9O8+ak+KlY9-0iL5BwougB3SRHsfm1PCN8c?o9&;I$N(Mt)cLAj8;AA& zzz)-?XurHwwosi6YEW--s8c!rP+m1J%pO~jpHCY_O}0NBhMX6t-%v1|Kc>5l1@%)K z`AI^F3n7HTf$@@Fkbuk69J%@BC58=Qcz)X3PBSh_25g$=?oUKgpH#u&H%F$A&8uhv zzQ@bMN}l=o{QkMMgA~P;9}xd^{z42|bVqvl87-25gjnnS{%tH}l#a1SdVz*OW$HEz z>>e`Yw#i|sLb|CGNbGTSmOzqEf@Fb|YaL%M9oJ@bx%vi?#9-QHYU$X2WuYv)U`;e} zfU#kcQ@TyK^L=IDVc$kWzk7S&Jw6m@;gM8o%|Q@Bd#2rJvz0_I!hPfOaK#hnLbJrTFJzob8Acn`kke#EYbVEON%oX{O&-X6e0ew zM}vxvP7B&PJXHML`OKe^oGkd=N1*KOLW_&*$1V^z^KE0~PIbcijGL`1^Xm_Jp6)7+ zNSR2T(Bv;QLra-9p+?>@&mFtujh~iMOAG`W+x;abl~S*>#9#E>6#P!b8c&U1sR0v( zNvrjBnbEYm=i61)t2qDaV+ub?VgDQl2HKL{-d8DMytwV4hFDd77! zm>$ot-~3*IE@DMmejku66aQGz4 zNm^C(99}+A1_U5n;s5-t0lk>B!u=<3X8Uv9_@0asdU| zH2a%?E!^)Z;W(2&h71=FAvQVDEJ=JKoh12OeeAJ9CF~T4oEJ#I#%RDfe_((t2QmM^ zw^fkvtar3)MI(wod$WBmz8S2JqFcqY7mA|%@J`|cdnn*+;EaQG6V;n$j3MT^4jA4doj_k5na872OHZ6o?d~X zVovu%*jvYoA^bKr6M}lVS`H+hbT2Vov8HYmhFGK$exz0HH^ixI28iV|sO?5^-ly$^ zsuItvZOYg+-Z8-|9U1;{5sjr~l2 zw=yw7MpMVkuZJ1BqTc`-Vo(@n4ILB8-G$;>wg+@v-0Xe2$0_2=3(4LbR(Q0z1)yaZ zdD_HUOEvgg}Hkog%=`74xWa&qr!Jq!%= zM>vzXyKq05TOM5YwW~tE-S(!;XFMP>c03^9s68k#=o@UEQ9 zVHN()4O0P|+?+x4Cc8#$`$M`Q$p)-@eiyX0Zo;0asRa&x;y3Sb=<)C+VJTr4VNG%; z@&cjd(Ic=4Z^3+=)TJu(VePs!!47AaX2D3Hf&yqgZ=NQDoXO4@jFB%s5mz8KVL3jL zDAC=shn)WG4~rhJb*Z(|Vj`F?M_eW=q9!jsJ9RFjY-3eF-0T|tyJ1cCHB83I*Y2DM z241TCYc~B~-pn^)U99&4yQ$&tP;9EgnV&}wNeGG_c=oTy!b*hyOi^qDnB4BJuD{>+ zFSE84s%~>NOFOjXTDwT9nlL|g4rc-47vd?1i9sAZ3&6q2schIDCx+L4hI4`dL?k2~ z19U{I!1fQ#zxie$jzX11_ea~O+7;o_sAWg`$S9jRnz#uwBcm%mNNJ+X_kaM}u&_GD zfbggd*M7f<)~AMc$PMXbTToS#T5Z5I+7A0DR8x*#JkQOPxdvJ}`5c~G`m z<7Kj&5JV1|%G{~Sd}ucEAPtQKF>A)M>D(~DxvDMjGg*KkNXZTO?tau5EvG4Q+u|%8 z9kFpKBOQ<%3!Rto6#-d1Z5KmtI-9i;^|3)&y!TqP5MDDx1K>&P{lu2Yc|y~FfOc@< ztI>bm-ybcPFcz>G%)c0XqRJ4(+O^GGBy_nb$n`+R!ZQE|iC zn}S0sw@#4i)IH*Fjs89nKRP+PRG-IyiH@g?phh2Ha%tm6kd$w*DvU zL|QM@Jp5e$718lEeCR(MsF9nEEoKF{p66g9A1)*$WU}IY-QIkS+3&VK{4k&!wZkUl zF#5KwFtALFkWR}5Q#4mc_$`ePSNP>+Y@eGpn2|MlgjcvYSo{=)Se{|m=kQNUz{u#R z4S@RNQBbI6Ap_!$SOPYE8K5tXHHIefzo&2YOi-f7{a#!=9l_E0jm_9!S&@LFsQvkI zdO4lP#-{00{rF(mA|k@1fkLJ(qa6)|Y2=0;dc)L5^%i@JE)uHXu$p5oNtsl;`c3f1 zPNUu1ZGb$vm8xPWr>$v_litUr2eijTWXkYr2^-59{H~1H5KB6isu>fL+XS=^(3pS+ zVg5OpcWMSkA8QEKO&EQt?$>D{*#ay6{5kzQbDg4{>YI~Z zpYNblKgb*7KMmzE$=gp?Nt@#<+NeM|Q=S?De8DxEKK*@%Cwp;oQxpJ)G}Rr1l)0gy zj0qrMbF7h()|a&w^}pX3@5bnr(I{_E)YyQs(BG%p{B3pP^*l4#kYNPYRsQ7$Gb3Y( zm(=_8nB`;!dX16u&3eGnS-;(j?>L(?K-_odO$Lvza5gGx!QiL1gq;vTT}wFu5AEr$ z=TC#tuc&81DAU;qr=0LrS5GcSPOhJ=lqY~sluck2{j7YtA|o0Yhl}Hvi-=`u7cwyq zzntw+>!yTmu<8hBfJIh@>i_w3$~-YTD+5N?J9ZDoljZcv27PT#omlZQo6_O)bUX8c z0$aih3?_B8Ro{9_RlY&gGzMgzV3oV#2O+ateAjFPk4I6eho7U+DBT}6iY!Dp7UiRiOg z!rHG!1j+W!zpbU4yp&Kz?nGqP2fLKGIL(H3T@rx#6{<`b9v;3LVX0DEYIG>I7)|8` z3Ydb5O3~DmhS%jUfl}p6{@<;C@I(IP3R!A0-ot&v+}=CikSvwKj%0%-%S-m_1KHV? z_VO68?Vhtda>3K}&&>MvpN;nUOMoGoD+mK_Xu3BDxSK#O7r3DA*k&%4oP;kjRZdpD zz(}>}i`SGolpEwllsBm$7Gsh@%)act)UZCcX7UijumZQIAp?&MA;^v$X~~O;q<*;8 zC13)KLb?$I892|+ZK);LgX{I>V4LGLsomb;EpTPEoq;X=#0ht@@SL3clg__**YRNm z>|Dcs9Tm6DxHRffMaH_oA&0k-cU!$UG z41?ofH+QN}{zmw{W;?`@6yHoQeXhHnuQ_^wk-7c*_Uh%)-upLcW@@3NqJwW4_&faN(u>+0)C}?gyq-ao&zuVP?BGdCsz$GBk1}x8H%oC^m*pL&^W!j7Eo4 zph`$c3(ABWsJPzwY^{51e_tNBNQUqkV4Z1oc{mS5z8uUT{tJIJ1=ZZ5(;UBy96S0L zurVglM(I_2(3>2fdI6tGK|!GaxCde)hs$g)N#yjKjoE-&2kqppm)NsnixD;C7VawZ zVhLW()6erYftc?+~OY6KUUerFZA1?kBf9!o{>Mn8RRgjFQ<35@y^EMVJex$2mDh+#w zcP?tueq=8R31!P@c5dr0H8ls~;+S{sbqsY`dQ9J%h!8EF=Hm6cPDp7K)8B1-ede?8 z@c5ikaw!}fg57>saNO1os`R>49yHd`<@%Ql-&4>CSo5;7vh?F>_ygqE6aaFq=Q?z1 z%Y4yqknAccDO}C$DM%qNAA_Sq?-&Ut?0a>5txjcugF(|&VhGy)yJD5An_mLcdzqgK zG@vi=*31yGqY*Kfne{nTwft<#aae0I$h~2+0?zQw3+GKn@Tb4b!iCN_a3$01*1Tg% zQw=PSWZ*noJ;Cm^o|H_?Pz+7w4?f1Dsmxrke;l@>G8XGi?bv-Dm|?&AN4Qktj@wK( zvKhEIsHL%&RT1VT@~aRWRnZ~iqsUrpXlSZXdON@~Ncuj`uGZ^V_z>;k1n$)mDIp23 zC?m+1CO3T|tTfJ0wvzJJCi6~tj`O6TrLBIsI;U#A)@l5Fpw;O2V51!bT-;p2W@;+q z@wflx`H5%v!<&T1!c)VM)ShAVh#Si8b1OM2){vC&q6AzD75(E=8j7H{oN5~Cr%9!M_EtbOP`GQiIU(;zL z##Y=j5MBazVUy8F+KuR_Bqhrx_UGcPr)V45BFi{q!%aF70_b)(rOf+~XX^VS-g{ZQXebBB+NmSY;eFT$;qi^q<3eJ@)|4YR4wwUU!Sv+$5^ zHScw1k|N{CGk161D4w`GMhCm6H$?eRb>d{uvW((6T0KX+d#Q=BUowT1h4*+@vY2(g zIdeW3r%Af(aNFYCLhP>USu16S@%$mXXdG4c(#*IcEv;-JI$TY;WaKWn&$G<8@W1_5SNKg+tw3IPdyL1Z#3FhcS8R?}g`FItt}Lm97ruSx(v^H~o3l^_HSO=5DE_iz*KOMzRZV{4?!2t4g4U5G<0pgxQA`Gbg@0De z(jxsv?2PI?)%+Nr&MP$1VRJ|7WR=I0^UzL`l9)UA*q}y=?+cTk_+ig!(+mqzbnq5J zgL?0;doiaT9*CM!`Ao`E9fQH;nfoJGPlH~Hd|9ozVsyPO*P9Fb1^3%2ag4xUEe7B} zTz&GbDsOom^A-nvjv78WD3+g1?@gXqcOm{iEr9ZKqpkZtxmb*jFbF8)KSIZVV)D`j z=Ss<)$en3&QaoZ@kWy$fmNIj9yvSvxg{rUq)nXr)b6d z`|R>>rwp7LIz1t^jEO1!Uk+Ul2wU6F&d=2m=GdA_=vh?AY2_;c53;gvfLWEcbnoHs z!@kE4V6DXN1`*)E>+WliG1Tl=b{1v86xeo>v{ha6%yq2oX`o9vRJ#{nOoH)7IvJ5l zfAyIAU>;-Pz}9dnJ3JXYHQ6k(-{U`r!$<9}`LXz?H5y_90yREl=F>1ac}1+~9R4W_ z`8MAdZi7`PBo}8yMxlD7_f%@a)O#fz-ZM2L4c2aBaoS6sRp57BkEKOtZsZpDc;8m) zPAZIU@-JrC-XNFiA$cS1Dts$#t5uEHF_wiGf({yC!2ytkWrGti`yx zbpzrJyZR{@V71fH!qBKL6qV$x_Vbv=w4qFGu~mN--&2VFYk$SGHmx`yK_$9@73Qrk znAj*{^6U7^r{uo-A@o313sWxCz9$7Y;~*Ru@XOAothG#ghLu-4nB|GNq@I~~i+I@c zjv|mcF&X%vw$$tTj4Bm(X+o!IXO21om5l|txK&sTI)Pmefsc6Sbl(a%D<|fBGLyts zW^Lb16wOZC2zX6lGv#20VH8dqJ1{V_x!FTAez`vIPM*wqOi@fRwxYXpp!ra<;DoIA zE<8jq*l)hOxnwA(oGR|-(6Px(K?7WuN;{r?3T6;vU0Pa)Do4z+Zp)wBH?~qlJRa}n zf16!8Yd@)(5~mA4H60Pu$?2ZMNtbK;Uv?m)s7o*wDb@Tvi3Iy#4d87(+(G$;fZe@+rTJzbWfuvdY;-8Of2&jaXyL!{ z_<2M)@%ZW7mOG(e%5|+jmx&ODf0a-%c}l{4hq#4fG{#kJx;K_H+#H{l`OsZ+re;`K za=J*HRMm}@FLYG*t;}6>Nmf$Ws@;j1<=e;$VJ;Udp)%o&xt*%PL3@58r^btiJy-l( zib@?ahBmCH=NYS=6>o=~0Upq^*W8ESomIM2Ko`&=$3pgR_gpu~&`9O6WmN`_pk?YK zjOIO|H+&LG1~Yu|k2Lp&!3%TyzHYEWMb132wYiUkwO7T-ry4v#3Ezx?;`@iUry zVQ-$LhMAeE`rM5t`;GkgJ7Y9{K3i6H1e#Dm=)|3z$_65hSH(w0bKuX#n*_48+2hh| zUOQEa>G`fM%?7=^xN$ZPNBw~EP8*sTbcFE3*I6bgzLNq!766ZxC3wMtP=@_lm`Bm9GJrsL# zB-j9K?g`_o|v@uQ#XMSb!&722uA$E!1+31%WcDZes z=U+gttV60utSswLs#8825J&R)Ghg9VGE*`&vN^)ulv~#G0y)4X8WyHt{?jF~PK5sz_p#vAyZvp*S>ExU=4CxhNj57s%HylyovmfOJ*c0$eaF=6jq z>QKfl#~S38t7P!f)lz9wwgBJ32Zr;I%mHQ;*Og8kU`>)OMcR(1vjT5mT2@&w8{<$p zO~tUoc~daW+Eg@i<0Hv~Zpml-TtcYzm30c}%(u-yxm4~*de8#uS9MyawqUbtwApjZ zvZd8H{q!CoVI*0oc_hD3!@`FyAf*5Qqv{>Q>-wU0?<9>Hr?J&EX2ZsfZQHipHnwfs zw(Z8Y?dY#hYSxX@r7&FT$^I0L?1Vah=(YYJ{P< zd~WpTa+RFPR_rGVv)P^7yQMs4a!G4S9Hu+&19|#aDl`)1hVX>GZgTMm!a6eK0yvUn z2)V*qUrm1g^%4?lOJ587?1SB}$l+>Q^=(~{)8;X#D|1_J)QIw8XRe#d*plVxE2m01 zlj(ccX8eRul%W_C)wmI*Z*J1I*7m^odN}w_1x=rkquJdS6f)6 zwNaH0;^j!(w!8{-PN3lv0p{!LuV7eUhcNmpe;&9H>a>}h94$$e*q`@|MO3EuLJw`O z>k$T&yG{2a^JhHQEebDxiYuOr-a7fs-DQC`rffwdQk&C&?ggJGqphK4*oY`Q4U%ia7g)6*v%Ix!`09H$Fpn|J(%fP685Ncc0d;Ls{9r#7bFGAzgn6YsOcH zNqyrYtgEHL)#~Vpb zA}@b7Cp;l#0Qfg8eijW<3>eg?3o#*FQq%yaukQE!MX}yu$1HF&Lm$7Ew?1XmpwuR@ z_s1IWmnpwUCxX}EB<7ISRONs2xYW?IJRpbkBko2kpj>#`br_E@YrBVcgTw}7U`T!> z{PR$F@oS)WP!!D%wz=94aY09_JG86sdTJt$F(%QF-GdbFI9LdpO9owj&h#t24kUeH zVxBOFvtEGt1sUusA~D#X0Rx&gEp+`DW4C4P%lSwGrd(;fJDob{y87N+8V7QeXTCYT|wU-_}DY2EPvB)%f>r zOPlAA`k{-r{FOW%=b9AVe80*a5mVSh?WmD84oJp)= znC|q6n(bsjD^td=c)!B;j_^D#=S>AV+AsVc7mHD~E*Dm*9-Mdp@lRXZfiJi9MJ+KT zTqJkLfYoTts_?FAVKysFb|&U!qcDq4EXOY|GtYKYs(>f&aJpPRh)VXVNE%xzMeiUi zt4Hd`VRt>hiI~xsrA43Gs2zs9@h)e0p8_DAi5yv{1}O9B=CtSErLNAPM;kL|iWPo0 z4Q{lq`PjTt6G8{C!%DqdDLohcQf zkw&;=nI46g<0z+@FJnI2z##f=JkILI`sG~-|3nh%_bAxP zM=!jp4ZarCzs)e*3MVi?dsvAzOimuZk|*j{yQBgBBV5MG;7)Nu<1ruVw5(!NMm!fd zsTHTCwp4!Kma5N_1Poh;>vv-c>P=ohjwS##jNIz#@p&f=r687I*KZIsMqeB=stD8- z3EJ1%pV`Lix#>$kvi7n3UVh|ErYiXWkgP8uZsB1h&(2Y|3}GAV^w zwjO&tINBG+<5?U&0rz#Jd}g+GIq2k#_L^LAYFrglKC*)~FEXc#xDv2`D_F)OVI zlx~dnZON;a&A=|;#@c^~_uAN5()dMM;PTC($HQ&fPGY*sG6qm`Cp=ID~AST>K6On;znQ1%8}K>K>RPb+6a9a*Uv zG^bdE@|hnA?&sA;hZ!&iuA9G3^&j}NQ}1O|u>nstOw0 zNJvgzZGrgf?gOA&y2UF$4DnsY-$_7-!*&GF>wznwV9==5Wak^7-ua0W? zRCeTsVboM;qeDTO|Ap`;B+mKz`%b4YeUr#_V_ZsXK(2Rf>b70hWW(b!&Go?NFx_#g z#z0B=W-OPu@O@wu=C}`M@)D8oTVM{UsnicA;GE1?3YfgYLC@!G;y?IEtQ3f9FzDcU zzlT;E4ExkgnLOsyMCdjqOPj}@=;#93G4HmuD|bmdzr`vrA4}N&6(O_3f87r4(K<+Cyx9di%A}t+JJJWoLr~Z@782tyUzZFBF8- ze}4j1Qv;L9z>uZoiVyn!E~;bX+Dm;~5^5#uvc{jAG)cl?2w&2{V7e3~Yj@Jhj${>W z`-;G?g}--Lwz%FZAQI?dJ-GENv}SBF&~frNk+1*tuKoshLq#q`AW{K!4IT;KYm~!J z*djO>m9u6$!{5^=v&?#4#U zf7o1Llj#k1kePb@-~has*m1bss)23cQNUA=LNbxo+-?)tFNP!D-rjB)d%E7$bn0Mp z3xf!)C6~<44G2N7tQLDXMjPlbztvA`nbqR$d~sF()AZ9bf>q50p+(JMP>Vi+x6V@L zbVd1KJZ1KXmL&oiDTt%4*62l+Z=|TsWF*QolPc@sn2fJ~V1zzRIB_(ij3YhZN(>xvO-_vcxI&=7TK@Ax|u2k_`4O2ydsKvLis&GU>UK!fO#n#5z41Edj^-a%!S@*#+SX<*rWJiLsAQ zXMcbHaGGr=6~KhNIY_gWXmdHwudc4%c#{U7n|?Szp+x?vnePE|D6u)<-|3IeaEh5L zE0lB>A3J3t0Q4fOv=Fr+=q-L9V)!q{$kZ*`7y`BJmkBqIzfFhFi5&$N28YH%3nZg{ zkhlujbM&7(j8u+GsdJgfwmU2v$6}y=C31&u^Y!o-#u)aRx|K&#u*P;c7N;0l>}Yq7 zE#>}XVJ;SIb#DY$$##qH{$T$*-g5zTkZqocE$TpvIntm}FlP`mo=v=LTQ_oYWTw7W zlQ)jTAx8-KNrLWDEsa1=*Ea))S!0E=d*)$ZRWbasDhfVnb>G8fKOF(FsE2% z@bSt|TmQP>Rgrjqy2fl8IlO8c=H>e?d1KN(>*J_7CYLkYM1xur+BFEUbXjej@Udh(|8uO$oA1F7B(b@Dtu#z ze9=>|d{e$K9b~U`w6WVp+Nz^+5Fbh__6`vcR$Al%(|<7yjnyxei#nRVT_+|}4-JqY zOo50yOb1rUTBR({->}1rJ!tv5TYi4|yfTWwAhJy{54?=XA1;QR%&;EzB3+qnZT? znGsUBoQn4<)E)EFo`Wctbcpe)o{E(6FYh%k?SieAwh|w+v>3`fGwCEnA`=V5wf9?& zGGl)$Ke*FEw`6|Y<8H=c@OXy4?8SBL6nJ~aJS7_Q3kB~hu#tPh1Um4R_MWJHv&A-~aom0ADwOnZ&t1T}-o>E)?i)#XHqRXBv zo3kk;sY*pI1s9TN`c$?y@jbQ|`f?7`FJ$Wucgr!`ppx~(oV3w_M;ES9#lf0|5zXUx zNO;`lE%Z6w{<8RZzuA5l(##GJffcQ}?M67PS~r0R*a1~b%W+}a36H6{c?qpyL8@MWb4vA-tP7lGjS&lFLcTbH4#O--|JfPNQ zOK!!&v9UKtG6Hy(JDl&Qo+*F&X;}@M!XTkQ%E1f>3JXND4KEk=Q({QxSFTY5~aMTRjkg5N`rVs}gD;yxrT62nv zKU)T(^F&rU!e}+2dMWH#xhu{z}yDG1bX*%X9`LW2Yz^Vy4<>yM(*b$yiaOZ}lRzm9R}IL-|_NO3cu zL3x-!Egw2ABEjYR@uY@e2p2dA6F zb;@tKY>gB=#aZPZzJ9bvj*iym2&M+2F^G6`4L(mjmIKF|x-EE!eQA9~Bv{Q=`$Oed zI-3eZxfH}SU(k@XQQYxJhH~OE{4rBb=P?34|r4(NJ%YV$gl#9mcJOOY9WK(3O&Di4oKLy zX^|Eb>};fL^VFDjr*ds$um{=-9*@!K5X$t?Fxuq(VEf_w zHo-to@i?Sh>%LWR)Ay-MV*7?}$EkUs!#VBo*V$Pks2iV_?{)ePIl{=-a!oCHRMwnItp16Ocy=G4Z%s$4Rc@gDt(JkBlp{#zPY5cOl0}<9-6w{hWm}l zB}pw&8?CVMgR?=5xBtk_u$cNrMOwT2<2v(Yg6dbpN&FF?9clHKJNyzVO6!?>w#*#3 za!e67n60TPH}%+9A)9?;)aZ2*9-t6jaiN@yDa_%&{Fz4WD{mri)9+pEmaPjT6H}2@ zevOux@}Wsi29n0d-hm!Dclq-p3a1GJr(`XWl=N}^up^R!%drB3l35{S{dvdROIU85 z>X|nTtslJh`TZqo9FYeONRU+%_YO0;!pvsV#GgNZjsY|=V><(3mQBVcCK7IL%|<3B zp~1tVMBZO{Jno{as~JP0qLKh<{K)hDDNy6_yQ8d7V}xOjM2eKk5}n=P`zEN`Y*Nl! zvN!tVA=eD(^_{}+4=9?B1tp4;5|mIPWm=BD8mZ$S z51OF+ov{7)YgI7|If{~!xQ{`64tBMdkrzcB+Zp7TgX--(rIe8dh2I{83(R7)90LZZ zEqC?YpyQ3Ke3ShZl@1eP1>v`z0nYlWh!JWsC56?9n9ZUN1_ce#VVg~Q_xiYryHaPS zR)M`a#rc-;DM!2NVfIbRZKnZ@4NFAA^7m95wyE%154z4y(qY#hol$xYe&v^Ipy9Rg zym)?`N2hN`-(Zu&ldY3OH+=*FIQ>;%Z8sYlJM{c{teu7+?Bu#Iip(0nikWO^SMt;^ zM=tiYKmtyyu6?RMHXSLvWV?)C(7GAz7CDw()_48ae7Yo`|G{`!g4D zvar&!L+V=N*Q~62hI#BVr8TJG&$?&1Xp%TRRE?X<>0aM*C=hn?A3y%^)ZdpCb7j~? zz438RX~Qyd8siAs;7s<1P=l%qoufJVcDOIS&YDYzlPfv~QFZGxPJFpVv^J5@S9gw` z6hzBo^zXB>o0IDwioQ?R1X7>*Z(Z4Ny*VZGZKmn3nE1JF28_}B0e~Chu{j^_m)?U3 z6r2*~0@t%*>V>o+kckhQq%IgFOj#_}uT{qCV7brDvwvZU7`LX^s@cT4!#zb+d)6JbU3?l9v8LD#mJYS!QK7MO({kd7aIqll z+BjmWA?gG~HP^M`pJ^rML&LE}n8T9IF4M7=I=pv_@Olqb1jcchb@5`LEX^}A8Tn%G5rfwB12RA2Wq)<@Q6mczCpp|;al-WILNjbqp{Vbu7 zePX=#`zk@ZpcOVC8A6FLe1HL|4IgdqP;v!yC>b(^bqcOqIf25}AW0DCfyky#R0_d% ziQlP~nBkMfVJ&d)6T*&8u?=0)%cp4FKv(VpSJ`L!O{pPg@{P=NL~mhOHHuE$%` z_Y7Wb^1hphLnh%U95f@DICd;Y?~DOjhFYJKIWlj_NC^nzwORV=Z?M>kTTDU=<0-Tm zycwT0n;J(!ke@zXe&6c-lQYW9R_)7!QFdBhN{IKI%hpa@gZBk(q9jnH`O?(hl6jWq9E;=8_3dOTRQ%39iZglt7^ z8g@9tTJCYE%pq+1rw(urc$b^N_K6uYh&vG{$+mfv$!+Q~-;j*rzI z#+o~k$5j$gA3M!lPqbvDf|(d@N*;CXOJ0U1V^dQ9s5ap0z8>luj40(VSw}*G0gyU? z!ZzK#&;xk`qWpk2C+7q^E*hn{wA5Sk6C}8%$rcyv|7rn%Y=mA1TQ(R44w6!r&YI0ueqyXCe3HK7&ul9=9 zQxui2Ek@p$|3D3CeyVabTV%{GoOiANe4qAo>sf>%n&VmkYEOe0OzQMj-hbLLP_F1G zgtlpclHr7^Y@2M$I)wQYn6u-1G6KZzikj7lvV!G>Dam+>UaT#;wz%02+S1!^5v>7 za5Q~3GSXw&6&1(^n*U5perce!@2!b6GOl^gi?RbugWev_a-f4b|3=(^90pDNT+Zi` zUQ3Efap>LMr%U3#@X{xFbeJOd5BB1ib{}TZfZxw4+C8pUyU+ndYp)V51SCmDm!{O~ z8{()qw3Rp*QXS&mc_M6Yd0H2)c&oKffV4Klbu^|GJ{64Q?Qhr2sqfTQcVLExiIs@3 zfOyCv>7Hbpi^Sa7#<{b31YXgC_f5#+9}8>?`!>rdQw=FZVpghVYhowMq?S z5OeT3NFaegewobRQjg1wybqy(1?|{-Kgg)z8sinfE)C2kK0MGp-Y(gri2U&wIbByW|sVf6SSNQDNoEn}&an%cndGYzfKA3r85HsjvQMOp6{+jY1O&obR% zfGGn8_*Mt7Z~9ktsZdxi${<1)6i7g7d)0iANQ=L+kHi<&*hzt$_=tHImgG5SbmQF9 z>8$wSC+ZfTIf!)db)!4@ChJ(MGeuc;imb(fhJdg$A)Xh27d0LBw(=+4xWWoX>m6g31 zdbRn#O=Apy+ToE_`&)+PcXJa=OWm6h`^WgjWuLii3xYhf^F!x6IXc^iz|^StF;7%b zCi06k7)1so6&0gvrN(6rHQVRIO+wXEBW~?o+$9@gyzfp9M+glWqMiP%%fFK(< z|F|C+9BFbIm!<#JHGlE^kWi{qL>jF6<;A%_0#5)t0UePqEx7|Pfol;<7d{dPUP%=) z<>l_O$|N|&o{z`#r%mPaZ?J|MXPIv3SEucObZZSUR_Xuu9RDc{NWO+XD91>v04=9# z)7!Ph{8gx>rl#~cXI%*JpLTq(>V!u+SeR4#*0#O|p@mQm1D*4S!_mOt=qx14j)GkO zc;*u(gUaFgjNsdPjo{n)rtW|ut@a6l8h=ZzO^5R5Z?hhIaU_fRq~!$U{n2VUlaD*o zuFZxMh~dWcvp>9hrg=6|M0s&xSeP{=6#;pW@)71c#Gk}<71Mf$$3X~JgqJ&~SCK7<%7sf=y*wsBg{BR*cQp~2_j z+A!h&y)#%ukri|%H+p|AFlYr|U$nid=}cyfCE90=4Fq-D=wUKKVGL{Q*KH#pQpsr8ercn{yoTU8hS~adSqtI$_z}Jp-9|8UYupIF^bS}lsb}M zxc}tV>I{Kl~pi@mDw>VkJEvc;49rKbSfj2a~@s0>n5e8IN=5 z`$2Th$4%rZ-c#=fFH^^P41oh$CN#x%*YnaH-|_e_nd%1a-G9UAcm6PR3C%M9t8^fW zKSS&bOxFugQx8{_8yy0Yal>1a0{{;Z$M@R(V#A&V!S{)TA9s4}c16F*Z$5NAeVf&Z zl2$zz8X5Io(qoCy7<8Rc_^};yg7u{PuJFOK?>H5}>4f~|!`T8sMSepl|L>Jz7Kw_F6goO4E-gLqwiA}W ze-K+|jrXzC6eaunl&8%b!U-OJH$M~(pM+#7UB<435zs1s9~y6lZ_`E;x;-pg6U=-n zSSgkGW`c1ET|6jLEjw?^ZULPN&o#!SHJp27zgBmS*||qLxns&KqBBrUUWFgZmCyO} z^^uOE@Hn6Qd)!<){+TRy4}Ms{-2ExY?9s*rT)f!)-JA{YQ-)0FN)ttHA+)7A zRp4rcgoBYusXDv&vzuuWh}i&=R&zlQ4Ii~;X$-$A_}eidtIRVHxhdq&Og9&R_{mjd@8#Iw}u?0&7L9ep-M zgWK7}9LalcFEvN$d@#cQN$TB(o8{`X)C?5Ypu>^jiT&`m7phOZp9sMkHEHjh+LqUg zkTaTWgaM9)nDl)sffr0+kDvZ}>mb9CX4;6~(m8gf?ybXxJGP@w@kERg8m6F}P9i%_ zUZFH8#0PfPXx}FCkOAz2X<;AFqnj(^y5=Y7Zu6p&6<6mb(9UVzHRf5HF)d+JuZ(}j+P-AZp!RhMa}?Gm=KIGc<*YSbsYm+|P}Mcr(3gX_Fm z6#4SbQ`bvap-P83%vReAre!8if4g_3r`%(F8FK2Q#`(E~lXSfE-LtTrJ+`agtJ_d` zR%tR5Xe(Vet}l!xmGHld3?ze~>0fw>3ipRpr9A&+N^iH@Z1F=^>G~#nxLW;ZjYW2Y zVD~{FE3ZqQ(60AXR?i2!{fBcQh?-1om%xCT^>iH~qAH6dkO8zxT2_{RpWgk+bCoHQ znMxV;V@yg(D)?FZwSBBjOYn4@6QiZ3;p}eK%;okNXutvUdaP@=*;hNKe_}tW@A;lO zDk?<1ac7i9c{yoLscP#Q$O3gcyU=By;Yf=M1GUm3l5i?OrWb45RLB1so_e>A%pT7Z8R`c z8Z%vy{kk$D^=FO?S0U)J!ts)OzNazhp_o%&P8mk^M3YooCc$}R@~-oN7g7DWXocVK z)m6uqzTSNqpF<;xhe!8$B=80ZNY#(`YGgoxp5ZT;H^UNE{p1$;ajJ{cY79Su1cN%o zGgMot4PM={epZ54wynuMZ=(1~MJ?H5Gx`aflBx$-)+#eAO8Ur`Z7P+)tiA)=CWUDE zpCeI{nsuJ3DhH32nWhT|Ipb%K=m37E{k4{QgUd3pc8B{u-j^1I@)`{jdWxqAGH$)H zUslN9!(`lQ5-BJY5v>OyV1vh_9+NK>Gl%Y94KAUU$4MzPEG^!x0vwvSjXFF5?u`k5!i%FgI)QCwdkm z0#zZw8w9Gr(!_JVF-Nv!*zV+d+tz}XZ8=Y4VgKX_A~kZQ^6?L%5lx@xST5tuW$dM9 zOji*BGQ%(CgM+2dPP2tnOf2SK#?xTb)i=1F1TZ$mytpl&*! zLw&Gx+@82R{+s4RW-WrN_eUtivpC~!|IS(pOLWdlXl0mR!R$Gj!)`7cbtd)F1cQx! zCQp}WoQA1UqintM5P7}q^g9nZAO@ZLw%oPU^AQZ+PQK%@!bS2CX8P*Pr@TB{vf|NF zh#LF(+=$=%vSkJNLoPMRCRl_-JsxD;K(4jPf4me32HM@EvWk|L4SfYd{urAW@Dgps zhNc4Ogw6M-%j~8|VWQ#PpN$q#`7k>Dv<;W6?n8;Lf{FTQe)pF28^eh~u- z)?GJ;oPm6_{SK$=d1q*R3O~6wBb0sNTW{;j6|VMV563Gqaev!qxVmUN`FPw3yE^16 zJM4M&y;v9XGfy|4{$|iFW1%iz2Ea<=PZ_cct%muGf738LjXm)jSlCB7QEgmk&ta>Eg_+n z?geFR+=~-}S95qKe`;tr|B;^!cF~4xGA`GWr{fOA`>v)Q{7qJcw4`2%z|h3|VjZv1 z+Asg>@Z?~`=#y594^Pb}m_{EWi1c4Lk3zGQ&zR;cLEufAZ_AC+jlNgE$6GFbsHa8~ zYa$4iwjZMl^RGE?u$x}<6sDu7uRb~~fA>8_y>L2>i6gt&@Fb1<7V`CL@T=btQZr0T z|Hynh&8A}|te8s^>P_#trm^JIZN8nM$|-AMHh&|o_nddv0dCB+9BQB3`O%7U2TV*5 z5oXP*uoYX(a-Hx>gW~CBtK?h5>b!24@cC>(7_6AHT{Y}50~J-pqDchNzr+j=$W+3= zESN?9v;fY%0=D|tACJEHNeRL@(;(t0Wp=$4sPZFEo<5aMVY%jx-+7T>q@xN7>Lmuc z28PPjZUi?j@zJdBvfO(<;Z;rfbCpfYdUsbA8|yxB84fC-EL>;gTJf(T_zT~o1@dFe zFGq4IeDj!p#5{##AXKUgPf^&&!9c+@mA@$~mq!r{{3=x*MRcE)1{_y)EGM^mq7w_X zv|QJ~r+CYrIlO;JrR4s}l;zV_|Kk-$G}vGK*wTUy-u7`z1ikKVI<``1jtTz#fwOoaxAu$$8AVmT`fV=Y`}l(Y)dTQmY`d zA&evxiGrW93S!6cuXT2*4~d6qdC0F(*r4#R{f$oDu_WD4bSzJol{(R{yqyALDSfzS zk3M)j1vFgwzpzoGf0AkZJ*T?aKa`bb5XmYzL z^&<)+i0QFTH+|Bazne1aA1g@w^8XfPfzMw3?S@5yp)Dp(x2tj{`E;R>v@JQ~(@>m3 zH9B6U$72c+OCnO#YXJCTnHIYyv@|jKIsCtwd1<(gI3sdaOZ;p8@ASB9Xey=`Y^Sji zHHOY^O^$jb2t74Mp@3|x<(&}wgYCg?e#T#$oH0%w%=xCAZ%sbxRji{)r4u;uk6gd) zMqzst4@jxu0+9lAeU&i_PAoW1X_L8B2k!4qiyXis2+9onRjLBxkjbmPykjvM1MGCKdwmZ~S@dQOOKeG9tgvP)Y#7X3VttGfq zlAFJh(wkvdS1XJ3v@rE~xEN7&hI`7jh6~L0T) z&x&!4!nJhbwc&C3rINC?eB~(=Lj0X!p`)R53*=vy44pJuV!>HivGJ4d zq&VzKy|qW%kcqwae_|wi!rB#94lz41V%G8GFc$1S}0u?d+*=N*; z@OsQBeLQd}tHo4SrtWs{fw1kU%Kr+em$V=2XZ5ZPoNFB?<%gmO0TVKQAKv-yl^8Nk zz-9n*olJV{-|wLKIcLT)gr2x(B*S@#KdIZEEP#Pw)c#DJrR7czaG9SbP5B)8ZNslJ z@a&u}3Zb_If6Zcs`em;?$f+M!xNS%c9(DztcX}ptU+HajVTIv5#w8Z|Phsg68`MX{ zq?Y=}4(zBZHCD>ig9%JZSkSjhg^(jl@~!pINEMJ$%TMgI?!ft8qv68c9`-Gp()_FM zmX|HEF4mR9r-6RL8aOJk9esX$ zT>ErZXRI<5xdUO(GD~m(VefroUdCQxaZv@cpIPSWz6}+VjQ!!{0K^N93y3anZl1gN7QDuz4s(!lWRQjL!WSIl2qzC4e&F;rs1Jvc158RCO`sz3Z9U zWjU*(W)vYQ3CT{Q#=c?n)JhW;6@%^lhu>h<|1X;P$y{ehK^K!;#`-T0wb?ijeTWKf zllu+gc$#5z!-^WBU^s!pK}4Zn$>+Pg=c%20uyn09Kr$RXT-F_tus51#F3Z<*RwLPA z++h?U`iGOGvON0{yT^;N9gWL#Ewq^A{?Ct(SORh1N}7pLaF~VO2pIVxzoPB!4-s0< zdsdbFyBa41;N=v`pp^I7=)q=lGBeG#&};&Cl9s-Zi9$(Oi&@|E@0*qkjI=sV0F!oz zGsf$+<8KFb?>APUlsqv5{cUS1EvAQHU(1Gzc_vidR03u4kkG(W)1YP@-#Al69r3#@ z`-EEC3u&`J1H23UepuFyHvp1dBYb=;r&5R%94uG0+Mqas_;{{(Q5_1W{1wnGCE!&W ziVlw(wM~e?6vd53@fG$Zs5VY^{ACdXy4N4jVtF%=+#@`m%wF$alT?&?FGX3kW>!BASRo$Ds^HmaVd{s5bz-GMg6gY;}D6pAHuW;v6CHYz7F{REdR5B&2nP60l!)O$8 z9{^)MnKdovd|paT-ml|{c+swC{A+S*2o+U8wkR&D&1q&wbhgwCJb%WFlOp?Pm`e-rwP!f!{Vr7NReq*FHXds{4Z}pAe2wlWn{I=4!2TI~jNx7%%1M%Z2NMo}oDplE3 z26VZG<8rCO+PhGpm`lrm>~Y60650QBCD;fqpT-t5-E>LRLY8Xs-*!9CJe97hW3V0P z`_t{oyqfnyo8ORo9vvnT&1h1zTuLI5hZqJ8D-#0i?U+rKZ*+0x1DewPAashokgj(@ES`x`cO(I$7l+kGd8Mj$ zg_g7DWA86;34aVs>M%JMHc(&>M)!V)Cy~`9Ybx~r*FWTOa+FeQTZQ3{^B)eboc%5M z{2B11VO8gR0}~p)V2aHTSBZpyz%b+X;_$la`MvtX#lLA&B{BQet6`F{n-QgHwF)6n z*YQ+cm0^3Eddq$GTk{F9BmRQ|=J`R{fRY+cLP9CNiv{SokWs!^kZ%X6@1cI86hLXPB|=Jzh@D8&bYbozHa}#hp2FQ+nc=r^ zQL&)z@5gVZqk*q%|8mi#8^ZRTaQIy0k5Xsev%ievXb9M-bz)MHh0jE4L8Wn1*&6@# zwZtnVRL@$A1mymqB08oBC8I(2FTcw=ky%&`Fmo2%38MVIrJg;86%n@24X0u|BcPZ;Wqp6e|L5Yi-Z^+Bb$^I3aj^7AzF_{s9gv=K#W5FVwXZUZ6)hh=#qR@Hi zVII0wn;VphE@5O$hP0M6;^+B!CmI^E!qU*IR9tGnPNjlpbV=<30Ey(?FCy<@Ib)6miPx%OY(G|8lrLsWm?m>KH~uG#NopCrGV1XuW)gYy(-$Z{kgPBwqZ z-YcsL?!4+9ls!l>(1}SLe3#|z=`cYQzP?_%y|w4UkH5Q+_Ut1rcD3!5<&JUr1g(dR zXzchQd6agTwK=@GVyMTmC~u0%&FWVUtQh)}Btw907gQ5o5p1)T7q<_0Tqmf|{cyhi zKl`(0EU62olg>_zzW=KQDC6QdZ|wBnxzhabT&zS`t%cGwOvxiaaxi#_RqOP#kYwz+ zIPq{rBL*0N;+-!SDpoBpNnvk|LO-GpT{}e1D{m4%XS@9_&ql7%gC6&5!V0uk) zZ&U1c2INcH>)CkYU=m0Mh3a+H8dN^71)nMxkEYd3w^%lpg_P_UUcHo&`qJ-}wJS_Q zCo-ikhGT?6qcKnglJIQICNj-fV6vg20jqR;>T(qkT8}_o8SkfG(qzEdG{EyaGBz+Q z45`DF_O!|iLO?m&R?O{gV$|R;9H(OT;K$wjkWlSQ_>Jb`+AoVuZ>ab-8d@pokf?Aa zywcLSA4y@;2{a(oB_8WkUttg6w`6PU0kgwG{sS?F_heUv+@cL`fSS2R8SOw5LaAfZo9BpXt zL&6~eUn50Wz2AOY|1^V-Sq}y{&8PP9yX6Pm*dEkH=)hQ=Dyj|J0`~IS^75B8nw=|B zu=9JGE9@Q-lu2Pc+HH+yrQV889(S_w+8*ly1gB{c0E~-~)rD=2t@mF!S^A z;4WMBo)_i;DwaSN`Jbiv_ME=zmrG+);<|d==33WcC`x^TDp0fU2?W4oMp)n9;c=#H zM;Eq|B<%(2bEs~{;HN9Zg!bx!pdAc>h4a}?38O-jTqa9gY`8hHo%5vOG6ZdF|yEz;Z*JHTh3Zjx@4HP^}O3! zi@-xpChfZ3jyigLVjabp?^bd|19$0oW!AQBtGLJQu*5>Z&9?|_K-on28;Sl*Bq zXg_HUaF0A&Z%fke3k1O52+t4at7n#Mcf=eSG7b(7l&pSFEJL)w!UIwYG+f-3yGdN> z@9J*Pec>8cZXGqO$Jf_)!y`Qg4GWd4Z=P%ceN!fk<{JdwLPFXWU?U?W93(j#=P(29 z?sf+$zGwJ7J=EYkkpy5Iw3uf$>|I2@+!PgB%Wx5Muk!U^Kj4;|Y>Bdb-#IDL?I8Ms zkZl#fte0y8{#}~qgVkUp!5F~C9swLxm#g(ZvDN*wN1J;j4u%DAE@~AjU%q^)UOo3M z)=kYzYj5WUoI{V++nO37%{35{6qg8=lWdeVk(a)8%aV!MO~#Tp%=RpHHH3Hi@+O=W z`#4cuqY6Z*`7y`F9wjEsw<7vJn?Jp5YB~jj1x^&g<^B1>4+4ofvj)Pt2MSzOY74oX z%(Yt2(z5yl(lhoI@ckL6y$ez z2L$GkfSqBA7V8isD=VwjW@iR~5jC$VGgm(F(h|xli_C**J6Z1pJlh7xQ=z&~sB9Vc zA~b7=OI=iKDploJdMm>i3dcU)7d;{{f5S5<70}?WB4%L|_jRMlFA&Mzh~jXdkkLgr z=F`ZPC{>@%f^B=7(U+G+AGP8Qx?x!fRmst}36BEssP{UhD<2uDSY-R3 zuRqF*;w5EgZ|W(KO!|Zt%qlD-1PNe;d`?5d!a}U}RAyt(WeTI0m$8CPR9fN zt_#5Nxdk|;gZ$#mn%erciz}n5CA;U`Tlk3iKx*>U`-iZQp{oiA9@+7SJJ}u3;@!qm zRm>X+Pi0;$n@+4Q9xH*b5~3b3B3N~g3iye&+>9<*Cjs?&BrZ6h+ZOin^70EC_q#-yEFsov3CBfY(w~zH&~Ay% zZu~`g5U$d9<*OT{)|8e|)w%K<;d{Y(v{;zD61k}{9@z`zh>+9qBK0s4n z$;o5lj5G4Zx%s;DFn0_T~uj>Ksn_)7aRnzfg0f31c5*D^=>-&w29_+MAir@E{5i&}Hol!(TcUwDeI+@Rcf+{*)-W zcX-f{B;r<}M1#X)I&GG8=7F6Yu+yu+p5kS(UapY!gw;Uc?zn|~mw5JI%H4=cMjUG7bMyq3PcK0U7J7hgv$B zW`G-(zQcA`E;pY(wvzft!h<{06s+zX&hNIyB^Z7m&IS$JRo<~;FEAWh<@<2m{@^8b z|3TV?{h6qZFmHDEWft|_(K;V7m}>Jg7w2Lb85vMEION*?CAsNm>xJlIz+VkZ$Lybj zLy8&{0_zF#&CPkGrx#Cmdtl1l0P+IME*wE2p$?~PWQDR@ zyTBF5Ms)us`n6C|G;NGQog0`*6<&rjG??3Hv+FkAc!}tG$%V|tlkT@Zw1StIywdxO zJtCOY4~pw=3XhD~7~VEJ3?zbsmG4!mFZ)?NdPGV_CJ(T)QGIOPe^k`j-JSE{Lu-%v zFu37-%FplUv=hG{%CDuR<(J7WDOoGJAq%5Z_?1Z4Dl;C79TEogSu47xuQg-S0g>*tpW`1QlqG3ois%;q_py~9`5=R?NKq@;8A zxgw)Dy(h|X3JvMHV`QVQv~j`J;N>?u8gnmjnc!1n9VW_m;4ZA_vxx5& zb8Gp<%YaPT>FEKdr_Y(ZW-*HD{u=U75%?bOeRHhXg(H-6u2t_u?5OO93!Zo+6;-cs zOP_8lKv`l9b#=lhslNse0q(x+?CjAgDeACTvsM^I?P=~N@IBgH?$*`Q+kxuZhgVD0 zZr^4R5+Z+WhwE=ET&UK+=yqG`s1bjYumcA}K!#aP?gt$O?JxJ2@6)iDsmrn3?YjGE z+)E8ziVWo34QPfuZXH!j%Ii8heh$nQNo)@FLq?gSE6#(>o1DBnCOM~uRe$y!^vp~3dmc%D6-lfW=wUDsE(zk=uLzbJY`uSxzWA@y)zM#r*LK#>jjb!!B z&DSfYLej}KSSo9iXA|k>!L>ZvPjCuU$MG_{%l<@Y}hD!m7O$DaR6b$ynU_Cr5_pQ2I2}GV4cPyOkvZxu0&D z=|6}WQdKiI|7;uj1e4hKir&ET1E`XlB<7^7h_+J$9~ZI&Q@^7a$F~q*2dr)RXHZYX zA3hn;2&K^+3m^Zn<}T3CGUZV-GH=O&SD1Tmo|7AY+c4gqkGjllC1WE(+3ighcJB=} zM@PPu6i+6&dk!XeFJ#VsX-+;JP*mSTioJ02GRYSC)e+1ZzkA zk1dY;!@_&onBTt9FnPWMO+mpBD{Uj}fGtIMPP3fs_S5|1dHlz|FSJ*JcbomMeyOEP z`2K20ZIYHD!kj~@AjHtc3g=iwF~GY(;_9^9^OxPqB?EU_i;P$0DH3Is|C6z@`6iH? zEJ=yTpJ228?U7qlo!a)9MT`LIKc@<3}ZCOQ^; zjSLG((GU$4C!{tk4_S2`pZRcXjc5*B$+)vM4A3qU(fkGcgPIJ9QgYt;jqm(7v#+nzk9EwwB;AqKg&+)W68_Q z^IPHc^L`MmY;1;mPdoEc^!u~P-6N88spv1}3hTo9Sx>Sc4<-@N z5y$BUqkCL<0tQ|0Zo03rR!xIl60M+BJF7&6@_>FRJI6iccQe&Nv4=`ZwjA%fW!CQ~ z`kj9h)5wy*`L{Pk6;~^k*^qfQ?}yqXYd7&j6nLRf0rH2Q&TiXyZr>Ld2%B23UBA8n zZc!frI>0*f#d=ZAYq;SG$X>P6N)PwmIB(ue1oA1f_>OP#d`AflLMFcZdLUzH1k4Z! z%hrgwqm{IO^bqI*xK&Xco1Cm>Z_m>sb0G<{-uiHRPEkq8W#>EfiQcm`IGF$*x zaB#e;_dO|do@;7$zblfc5M@sC_d6~H>5$pwh-K$Sm((7st0ea&#=mBN{HUX=+XCU1oP`B);Dh=CTrxLb8_WZpQJV2W z`~_4378Dd5t#ac`10T8r@Hj#LPV@asTjROKAtjX}Htm(=aUs+r83%QpW75)kT0+UI zewTG}@$x=e?ain?KVAplSX5b=AUdq<&mjPl6Df2XLXUr<@&9D2A&r2qGT?dCnBVx9 zC!q3UVq(74dhdFHP$23&8?+%JK)x~ZW4rO@o|)ZN;qi1=Gkqs5yDXQ0?Yh2`A4?<$ zq7O4S9*%H)r(;^nxk@hP>gIL?`TzvgeN<>DtE6Od8(3P5eSU2D)$kfT7Q7}3511yy zZRIEL+Af4Ss^Hye+4efexW>cC`5X3AsIa}dY6Az}p6eHz7}sop+q3M`r@|gJDQLrp ziiz%O_jNkSgX_h$O?3y;o!~N7V!&hc>{rg-#zewa!v#}9=XZ#;y+Pr?6J$Ws=v)D> zZH==MFR`C zUwyzsg^u4LvU)H02!Cg1M=e$IeQj;6b=oaK!Pws3-thwvMZkrJb^N=7NY|PvNsw=Q zn^Q@-xm*?&7F>LMj(g8&X=x?58?i2Crl)X~^tSvF{##{|yq#svT6hNf+MTn3Vat1p zUhnh88)QpcwS`J?ag|vwY=s8~`!hQ?ZW`@Q*S@5(e7dV4r*HjeP;pq;ghYfn*Y1Z9 zUPsV%zM9{D{{GQPD7+e;n$FY%JL|_DJx7}fJ$`>nPR88oS9}Uw?1brnmq90DI5;>6 z&_(td>kzJasq%Z%yj0#lVM_kMu|8(hd@b;mka;F?Ka)A@{ue1z%P z_koJaOv@`lTB`=eYP#R}J0pBGTJ$gKi7(cctraB%9W!qP`vgcDczKD#>Hzl@%c+U} z$;pV=STa~R8J|Ak*VWbG;o$|Or7=@9q;SwvQN04v`)-&Xp?m*6HRwqaIy(HUJ`^0n z!${yWE-NA?AW+cJAulqjvM?@xwr{(*vXYgVi7Aiw)YEeT3gYG#7l$MyP&4@*noC}s z?yjz`%34~o{n_1RB)c9nFdfEnWGmprGxV;@tWK}1Oi!W<+{6Uwr^ zt4q*K2@Ya!ukp{s zRE*jMEjW7M%EwuC1ZVjz`*6Ki6E)LB_1Uz*3cdlh--m~Xm0W_ZRP{59_WKu;QMq~q z$Nb5{mn%1qje{65>21%3mg*2)oSIEyq8{vXu_0A`2dSL%On|LoLYta9HgQqw4d6^h z@2qr~@%Q{n`T3eFRzRBc*@E6SGw9{Qb<&L@(Spt1w8Nl0VpW3QdXI3K17Fy;mJ zb&j0-y)q~kd4JD$Hel+EJW`JbRLSJKp02#@8^##=g|3IwEVReVSb`3dtFx)0lgtG0 zu%4W87`Hs-hX*f3FmG*da;8WGO}8qC9Nb;}X@DRljij8Llf6q|)^_QY*o4m_@oZN( z|2QL6pFs;I3T0E!@dNV;4vVzks3xuL@akVp8EigNCKnq;OKbv`P(Z=&!I#Mq2p1QZ z!^4HB!gaKv#iVN|@4Y--@n?Hnh7TXc#KvNNHH-w8)haFvWHqa)DHxs1t{0yW#Sk`| z#UU{pQ$$2oiwd6VK2>y#qE?76ff&E~eKF!spL?_gGY4+X4~Lie9ZY!+uXLqK(f3H7 z@M!DkkkZhgT3Qs7#a)`J>+|yoBqStye?7gIKU4`RF|GUeaS>oD+}_b42V4T)Em2FI z30a>%yY0o^S={_GUSBHLBW*V_z*%0=?0WnqC|6d~NO5FVc@1DP&SoQhca( z(K~nUSRDOXn*X!ZIS)a%MN{x)`HusaS%cxTGPAQ4@mO1+6D}e8rl%c!9j&cDKyEd1 zf2Y*4Em%2=6ksSvAgMdEw$>oilE$t5X7WG}()W zL&~IYe4IO&!~*IJpbgD4>*|bG_n(z|?O2rBj|qmXIP=uaDC$p5$p^o}@2k*!JX-Op z;jDWoCNBI=j_@oKi%Q=wM5Ohe)6J<81(0J3-rf>`b{V?dHy-_;*87_e4b#0 zSgu~hcCBK7!C>z1?=Nwhk+w^M4nT^CP{Kc}=8)a;+-w1X5(GojzT}D~$9F)aL`Fip zzoA5g091wHqQHlu2apWIMD+Ie2LgtMcK|k@=|z z`Nv=OTSxApb)VWobC6cJSN>8S3q5(KXNb}TL_Ir&V6 zg$41fjtOy3M+eK)bOyuMWMjml6kz+qjBAzA>t*01W##cB?oi3DtSHR834c=r{kubn zM`~_L-|ib+Os+&3MPNr~4Gvb`48#EGY9>Gf@)6sPRQKUSJ5PUbtAsFH&ctLo-JytC zpm4}GCMn5oB$YEoBP2DIX>e#rE`Nw<^*&!hR%t1zYEJ)heJHyU2Nob+Zb9(78(B_$ zEb8$LDk@~(6wH{Q*7-bGD}D!w}WT5KT->G%Gc5-doi= zg(M~(F|mrWG7fCB^bQZ>q;IK}!}>Y+LsleR^48-txi4QDXBP&FNd$jb z;rXvHCVW>~R1;(s|J4jYCTNs~1Q7tqSPRH*LfLf}EvrSI=M5ck#z*r6t1#VZWSGAB zU)&-gn_r7=|L(X~w-PFjgF@YII$h~{agi)hL=@Ei%L^|8a;oehz&oU*cZks3fsAE9 zlawO61W&+kmbiU&R*siifA(tfw{8J*_(~FV5#hhYgfBGJ6A%PdR8-_EWNHmUXY%v& zb5WdnvLgRbB;(rP1$Bq?PE3Tu90L>W4s5L$A#ZPQm=8@eGc!XOB&3ly^SZEFFm3P@ z9Pp^Zv8_KpAfpeb=&%xmHN|v}M0P~0Vzl@kv#}?1;u;~|z=KZGH&j8WbK4coVx%#P zB?x$4WXBv$y7?@^0KV;Mg61q;*lTr_x1*?*ovhw9#F(G|ZkvpZ82rw!Nof9$z4K2i28c)( zb#?W3GXB!=`7CiA_w@8c7Tr|u-bI^5bH%Gp!ZZ7bzq3Lrhd zI6DX`m-0WCv=XG%<&NKfo0_`WVq@H6CCJLjiTmx_H?))j(fQ2BM`cnU-@cs`Le00sg;%01l{}_Ty1qTP-o40OlI9|v8yO@=miw7)< z3J-4v1jG;jK40M6_GN9&mL{?lqw4M2O0rbB<5XC5GzsL(rz{VWOA)S?Po6x9?yw4) z{+TA@(c0D_C6 z!E|dvM`lI2xs$&k0?;WlCkGo=eS3Ge(w#e@`OU84RI-i*fT)Fqg+bHM-wvBPIogDW zU%{<3w6RfE<>iLxt2mj5yBXSf0(QeZUOql>Uu?G6|Li*Wn8D$bTaRnm6Lj))5xxA6 z?{Ar=2|XNFeNlLXb~gqbo?TjcSp%2QV57Ae!sZq9qs6Pf+}zysv!s{WcXJe;^gWou z!^aP-s1O6$6%!x76f?m@z#{fRKcAG2?&hjGU&YzR-P^ZUJwLqbuxbLcY!YVXt@hrj zCg(q%zS4;FPoHc@k1DIh?r;YN1(8xx4)H$*Mbm5h6y(!U;0(Eye77%d7C<0WA@OcmQxFY#R{* ze^*|dpQO;1O&Gwo+}irOmVp5t%<85ld0`O|xXSoa%>DwT}*ybmRejy zP2F{J;=h7}1yEyNY5>n?CQOI>MTa}yYcWQp#AQMGsfWk>N}4~U6K=8BZ4ioiGBPrX zJI^AjYidCJ?SOgiJnSWS>9 zr>8BD$6?b*limo-ol^1ku0lmcQTzG%!TD%82I=Rc)kPmZC||mC36+>g#~MrmG5I`% zpOmUO+E7C@4427E7A=(ZGHQbRY$)>e3&|j%X(LP*6Boy(#t}y%k18nOfuR*CDA%^S zy9pbAiudkCLr_gpG3AkjhLGSfdk?);M{`(eSkmi|HGfGW-<2e$37y|PUjF&B4v$H# zK`y|w|C%h0?QzSfQ?zImQL~?jv#*Vzlq5l z0|-Ykwi&{z{|C$d%Oj*Q4@Yagg(&c`A?Ecv{>52y44JT(syTs1d@4|NFo=yEso4Zg zO)482(gAup)@+E@q^8BhV8H5wq!X@+vSRA1|Dkd^N{}shgoLoW_Z$NOi4*i90Rz)l zQ*F!LNoeqfZn}hx%?d$0B=tqmob{xi9daHERV%6Vg$c5XOcBsrBz~cOIOMm?A#|v8 zp2Hk2G7g6xupce?_Q6m3;?yns!-sjO0_OF*w5B0QVaw|5m5k2as*^%x^`X(oZ3O#B|}wOxkrz#0uSda zupvViAn2!~#3g2GnQ&@|tn)dL=SyG%Rz~m1LYB~&k&cwqN*-@+jRl25qc7}C&;rnl zyDs8!Xr|h`F`s}tDa2WQ0|P<6Cx2O`qn9*v7l; znP@)A?>DcBF9N1eE9p`&awlZoznU@-<;h^2Wx?!JeIhG z4@+sUi3sDxdGjx~ZX_6JFCYI!ETg@;v5I~N?UmBOe}C}b+e6C2zlGx8SK;4R;onyQ zcHsXLt5B5=25o5U4S#t4P;_i7bm$*4Bgvhe(YHw%{rd5`26a!sC8@pF%gDU?JSk#_X*;6+o-Dan#HUo z?+@*^%S+h`Z*1IqFo~V~n81pj>X?#Arh@9`sMl3W#1+0Hsg{iig?q0o^Zxw$YM_}o zZ8l*#p5e@@4E|JfMBryX6Wu!6s|}mw=raywPxWWUpa1y0Hp|(zw=q-FWu%*R?^R~s zqmNYfoj7sgSs)|r(*Yal(n`1MrS0$-O$;x15tmcf(IfBj-Rs%$s6va>#H12OmAAGwlEwf)A2ceNww2>mt zPA|H+-t7GOYujSeTB+mpFny`^fa6B_UM$uP)GNeazkB0T$#L#NlVbyh-REe7DZQzs(_7S^J=Ua^WOlSVe!z2X%DN{eRf4fBGBOh1 zI~1-U-`&&0$NMloUNrL1{Z&>u6CHGaq}853fBxZv2cKVdrhj|2v@N|etYj(!zB3-2 zI}sc$ekfE%JWhIYw2#AIan{M8Cd9gMy>sXa+EWj#qN?@2UZLnC+n>hQQ!C;zcs*^R zBRJ9T#L1I|=K}TDnua->gxHo#$Det9#mfuNwZXC3U6fKC{V--QfAwLXjEoGa;Zm_j zv9ZG4-QBH$xzp#aW|`)C%se#A^>8*!J^SWX^msiSLfX*VZNov2oG4Du)@Dty}3YH?;p`TGrg`RNG`voPSfct7BK4 z$I$KYe8rjfiUoOpFv!|9`RxEPh#vflY4yXy;R;W*=N-TRrd&F`J?iS}qHx&J#;MI7 zu9}*fNv@4))@`i~wiOoK1GVvdVJ_Xzm<^kYZ}OGwob{Oe8Wn%>^Q&m%35D79wE4Z; zPY6F?-F7m6w68w6C@Re5ybqVGL=*_mXkD~*&xRnA!}24Vy>-biob_~dIRf=;4!{ki zeYbr#d{=S$^9t>@!L}kEo3R15ikXM!O75PU*@huj;*>sXsH|&{H0=wE^EQ94 zqr{!_RrO`RGn_m#HRk{KpNx|JWBrXBFHXhvKYem1#<9tn|75h*P5aWeaN5mp5u?Az z6r-KEg(7#M_GMPAmAgmJ#JjF4Rh}|-&pwLb_4kJrXI^$pxBR)HHMz#%y5j7h{~$c3 zAW}V;_x2mk>X7-PSP~Yj%bV%YcWrWVGTInaQ7Of*x-(8cbM$4+iSnSJpjN}V5yM13 zeYkB4D^e}$Q`Sjb&KT;Z(AWR8JjiqHf?&SP#T%>2&3u2aT@~#O-=P&#r2pHC*Jv^`;>#Q6V-5IbD0>t7>c4 z%}wRbacnyo?FEXuNKGXBgIn3`%v9SI4oj~b_o>3voROH<6H%Nk53X`w(@r$8@0#Cw z&QQ1opFq5;(qd=Z-=DC1Z@H^8>#a9D%Mv_%POg9?SI z3)LDug@uJ_ZGN&t9)|NraS4v%oy?w;CYF%vFq-Z1VAY_Jo*GkmKk0|xiWED0q7%!n zaad)E_OO&4mK#)-`tr=oSEeNDlaH@Al~Od2!nMa|zmW_I?Zjrwjc&MiI# zwB648hv4phkyG8fcW=VT99{(b&Bxmc zpSX6)zKxdT+I15$LMKLO8#}Zp&$NxF`U(HkmmE?sa+3q&THI zN!F0P^u8EB#qH~pK$U@}?A3;AnBV~GexI%Ty z?KfZRHmlt|>sz5XH{DhBNcCz=4Ci#eWA61USFUsndh>^^W7D@g+S*f_XnJ_M({t9e zI=%!NBbW?Wmympgh* zhngD6@cLZOx$(~{JhcLn`D9t0=H}s4k^{S|J&!+kHDfz=UQ#K z?F~9;dr$4>{@F%6lJ8N9zM$hoawf{G3flt>xlKduPY!oZ?SpS$m$vQ5|8s@Hx^Rz4 z^J>cbNcHPC`Bb^9b!Zcg&=TBv)un02zM2mo)~x2&@Bw?jrN=2sBh;ueVmCT51+D|x zY~gN02daBMe*8EHhO_;$h8@zKr^t6@k|@yd+H|XWYnV zy;vl91!`dnIX$Nb7sh=)J$DzZxT=MP1**(=PO5i{ z2bxg)Ls|!Jnv{n~Yqx=}{g3+I`wq zS-CmKz3mT1Zm$Ekx9o%0wiza{ccQi(rCM-?(~ZqDq2n~rO6k+^;;x;^U~#n4ZO&Z) zF&qWMF7G<(^Ik(%NX4I<3!eSNpozr_PA=Y|ukLAFoc{`i@eOcW9>G>sfv$KO6XOd$ zmxL!znx4~NG&$!i9_wsjsXRw1zOhmCZ1Ig_B7Dh{BRy<0lOx+kcFv#lUgrh7=B4!i z9T406(pWWrg~v)!JG1=pL6+-mfiARwCAdUo*LLr@C3mMcg(ps4h!_qR>^$A|uh`|%%ULlGgazb41$WQNtg^`h-?-sk`Oli&sM zf*;x@2L&mcDMhNhM z1m*p$9$dZ3laJS7z;C=dm3MSNq%jC4`_>o5B9UPo5wRn8Zsw07g-LlRhmVKr8fK! z>kXbL&PtZ>E;%oy`UZX&^9!t$`qw8q7*kOeH_nFd|9n7FXl~?=(qG)S&!z{aCE$pc zv9zC+piU<{u4wn~f;V-@so+C~I>|T4N3Dkm6LlR5Oa!q(lKd9PIdvLmMBL!`vDIG= zql^~go}E*Mmu9-IbZHNH)6oV8$o`PBN{L@fpp9E?Ksc-bg;}`=mbtUFM2(=P{2H1R z%}R-}12771T!hcK(P|>Xg47n|&g_J{Pb9@;6M9E)HlQ!{HuUEdg2{_Y`yNW51$oDR zTNJ68ej7&pKdd2mYSa7)9Z_+MXCnS}`v2_+Fd5n|%`XLZVtyOh@cFq<8+OB+N@sov<_4H=#E!m3 zeo}USJ$l`*bG*dN>a-9fBITEO)1DleJtgoTX8ilt;35B*?SJ}Yc$0P|ey;d7Ik{hx zKjb=gwEqF@3n{%3d)=kKl0rlpR`NFOzk%z!jABgKya#A6!U8-_OGK|EteQB%HT5;f zb}6WQu-Ev*)1ybh+IP1OjeI;+@0P9V&n;@-{UNO{r5+t|@93=%@_}c{_2OjAwG%H+ z7QDT)t<6`m$qN7}@$li$0XKdKl8;wTm)sS)K3t)g+cL78eV2g5h1wfq_81W{ayxC9 z9psr4O}X&tU57M(sNFHdpJH=oC%Yh8|C_R4JVXSP#u88wq~`d)#?-c626(d|-+Ogi z?rcwPoxByebAyj~W(30AhTb6VwQSvv4G&o9&Ch{(RXS6b>2E{c;#XEg;2!{UrL|t$ z#_W|FDr0}`xQ6s*6`yr1MO==0)f5P}{I84TNX>$O%xa;JKmwbA(?)DA; zo|T?2Uc4|K|MuCs&OD0i+r2);xrqw=OA(-fH@+PEW6cjazD3HdP%k0O02rgycAX@F zp4u_c)oCNux{tv1WEs@nWbogEbPoh6gi zf_3Z=l;=Nv@#4Bzg`5~n>LH+c9up;oYy0E@-TE+ID4BCKAU$xq_9{dGhSSsng$D=b zW(OGM4rWG1Zm~@Jd?l?^lhP%vs{1=m>P;i7d6K8p%t2hgSLE1+%J5|k{!7X9>e1e0e&+qWK%%oi=< zv@P!OlkT{8PtMtG%_kvSyvg=V*)Zy^)cY!%;OvBwB5TOk%UzdW7b@q(3I*5VBGc5_3p$<- z=>pZA*#Jn@=D52W)I{s1#_nz6*x&RZC**>eSK8dH7tfs3{SokRw}L7hS_9z_*w>5R zNq$$soH$n;)z@$A4^a&g@ti0TJ@e`>se!CvBT#Wi0i4DF9))HzS(gYBESbZNr=C zI8e^+*jFb$Ae~{~b630x0IxGK&om(k!wE{lH{Q4?Wnz+vKV&6;$i+QA-10J(khHj` z;O;U#S(9t&;oes0OG1DH9%Gq*=3K4d5MWDplm67r-%3X;COw!_9t?oV4k$HdI$AZ^ z0=f{@DDA)IPsSArX44iikWQGL2%nRVJRBZoKm9c-+z(K{CyhNhU1qacf4m!N-}KYT zfcy$C$agV&YSV)tfGLmYR@^s1Z4MBjn0D^vDL}D{5a3RA_K@~$s?m4UKNKb>9Y?8- z(Pg{6MZNpR7~`$>k^|sNB#p`D_Q%sa0RTR^LAF)EieI~SEu_;7egH)6X-K!#^PCy6 zo*Ai;hzBvq z>ZnaPr&c{~cHIm1s)RjvxLo$8baD7!AT8iigp5sb^@U4Tiq_Sq(?fuf%;wx^4Bki5 zN~+r9j0_nKg^4fG#&C@)AMCx#J(}US388)VxpomxZ^#LymD%P3xPI1G(xNV4 zY$`dY!)z++55F^xOJM7M9`&9WhE`A*!xSc6v>>Jo}LKgh;LDT*MGksIsAl_(Sc@4lJ;^25x%JqX| zv5Z3^`q5nnWv98BvBW}vnW{jW8IXi`Ir_+j}U5ea{Pv zP{&|-sBBx9Yrpgt*G9O_Rh5;MatZ*o`(+eaFmM$G-Ug4+d_Y04=&CtL1Scyd+P+2x zCvZ1rLGCyWT#gkkvjBRxW;V}QR-+a^*SE=1ZQs6q)t>47yM$AmhdT;j*F%RN#qsf? zJI0{!CkvlSKBNL1iYcCx@54=e2QqqM$J==3oGORwC!5m zqeb!FL0;Iv)c}Zkfh)6%C$s&o?n6*HfY7bSESHxTCONa5tPcT<4@u5o0EKcrr@viQ z-2S%CVW7!9Z=l!167VeTHuMF+V{Pt8e|>d@zsJmE@2Gc{^C`0)U*? zIX2p#avN}Mz79^8sa7FlL| zjno3UMx|0#15XgA~tIi0vlQF9~ zFz5S|dyqmeA7H3lYp6m0`(gl#H-_YsH3S(&SLC{qYW45e4z&Iu%@ZdIZXZ@yk9HE|j`MpK*v_>6j2@$r?vJ8yx4x{^+H^ef zkhiX7`sQ+lsa{CgDSVlLtLKN=NSuWeIETZ2x#1kU%#L6f)}J%g-%)fS^$Gaw))n$& z`4AYPzqc@(Esu?+N%|U9C+BXOLt3ep`q6snJ0Tugg%TAe?^+2>lBPu;=9M{b`Vf@Npz-zy%0!S?}Hb;n{J}q}w4`akp#g5|Rz%&9RpM=pX;WuI4! z5Y!9Qi1536GZ8lcGvGUX7}N~7tng{{@E!m-B_rH`owb-DB6dlRo*f2HZ(vJzr1{i8-{Yo(bH2d?Bdq#@jG2i~ zsRNarX}>;3u7kumCP^+3i-ve7?yh2Fy*B;84u2V${aS^w$#S6rD74Y zSQpCzI+i5O$9E>*f3vZsUww7o6P5EXbWg3S$+#C336Cmf zkcsToIMP>m{C*V#)yb&|Z2XUtgfHMcKftF6a<3W`^^^)qSG}LZ%`8x&dm-++VuOUU>)Q#=BMz$&FWCbAK)C|+KC&u%!9>Z zuohhVk2&l_dBcbNW8Szr15;Rak|XT%{K-_2!45f$Kr_c}%hUA4hx#n(+&(=;_#`fD z{@=Q>m zrZ+FArdkSVfX*WBDE}Hw!b&408wHdc1b9^Fg4vIK5_04b!K`-ru8M&!B6kx~Z(ST+Xz%K)@1`kNg6 zw(0nC;y@H%$_4XDaZ(B_Q3^Ja2J!Z`Y2Rl^E`w{M|W~N?SI3FpDyHsHf zG^Oo9jw%F7eqO*8%NCOQl=!j*-y=_xhX#C-A0mYYzfV-6sUWX>+fq8}`I=iSm3Ug@ zVl{KP@+K@9iAn>DPq(JT$vaW3j!)f$qTo-;I_;@LFjeYw(qjfK9F*Kx@}c1!GSo~5 z3zuy2v-qfIZnCZm^9ZHnl8K@*cqzz9)6|2aP#+tLp$ro=OzN zqtG(5?_~cfI-TtYUIuHZK0a3PVj&SBG)$iPT^1r$bcN#dMT9NFJZC4i7!Cjr?GR9X zkeJs6fcSy)2czDT+&^&VjheEY2YVAM3V|W9MmJ?jW)$gcK;5&b8kB_D`OA-L$qg0r zA=^_c?c$koi{sBUeSmueEHL$(rEyCuywQhSOIwTx&d{>wa;z-w=L@b ze$7r$1wX!HsU#JIrflk+dMY3tQW}ag-??5j`*Fz@LLkNk!(Z%8C=u3 zj{Bz9PS!xIZ(JR%y>BVxY7Ly*?}U7|0>Gg4efX>$r%TrZ(bIWUE(6d0^iCs4;~-Jw z;YY?JW(P1+_52P^z#lQBEeBYf!wBMD?H&wH#+$}+*pT1tHF?7c-nDLW?%W4{xw0~d zz(x((z9gsiJEt5LdtHx#bWS`(wwJgQ0bN%ZORp%vC=K_u!_n#+Qa2%#;(@Jt6Rn%= zVjptx6%)>)3#c^@hermQ6%qU2RM#2tC-cE1c_m{INb2-DRD5uATXyOuny3Rns#vV! z*q2;W_$1IEC^;5*+Q{L_KXa99ttzLr@^kf>8~WgIBn2N_9z-BcAlSBv*?ebEfHXr3bK*3;>m)EIiYN9$)wB)WY# zs#>r)Q16!Q6d=e2`i_lvlKb!KT6zO`vL-79iJ}k}12c{lh{QffMQuZFYNJDa%;`=k zVD%UewiXP|40z^#`sV0rI8|5Enl)TrqT>ic$rinZYILBk>ILYPrzdZ3Y4@-&tstt= zL(`O{ySUzcday{l&4-USHlzFb{wK%E`o}(1cu4rc6)7F6OQy5|5lzI&{VJ!;{$<>9 zX)Q&KO)RRMED!*zXEo!TM-+sBw1)Du=kB5-7x7R+>ode#bEa%^o6-|WxhZ2I0;@n- z8G|CY-|jy8i62AknjGL}mFjqmf4;g@TPL^%2xGNYxibmX;&L48BVtf7_cl=C_PKrA z-Cu)do7hz$MlI>OsmlFEhg;U6S0mFiwb{Wn(X_%3D0(1X@=Hz{>Ymco4NjikZR@z0 zsG~mqBNk2hN25YuK#K7ld*XWv%PBkA+IjpX(eAT4i1YH*D`6$2-BrF@!UW-v6C=cmc=bH*>Y>lq| zsVDa!;dXMrYaShAK4^i^u65f^#rnV;B-e)wq|{qlf4QkzcnbK&>l8iQ?0ReCKZ-Np z-ML{gJMA^nbGz?-y6w!*g`N^x#~ zduQRZm>69Egc@9WVzhg<9J+U7Tnf<9(of_Qyw<9bic;}!UAnGo=TuVm5WujVfVAO^_Oqh^gF z44O|KOG@G8>C;!EZ@J=Mk$%N2{R%yre^VmxK$~APEJdC1;#E$^U5Ac> zaeN-i+_KZ0bB{#-;&N4Zirb%M2Zw=xDh`k`8z|A@XxXlaKU;xNTgI$kd07HLAgn1# zRM|B*6qxH%Z<#41^ChGHMkRhiYUIQ5)qRPOXhdzd)W##ij@(qzS&I0!An)8espv+S z(Bt=C_qR_jsQ(M}fh0&!3$g=9gc7pCr5W&#B$A+O0qZ?@>@@(-twEGnZ%9b&Q_cq( zEr%y?t=nF{X5LmjI5kf-ERLt9sAG(iVq`~T(smB+_`6iA=IED>z%+=rX@9F+q(!O+ z*QG4Ya3iEfYmM7tQk&jJbI3Vel!N?T6)3k`A2D5pnzT9tbbt2QPR6B>!}ukEt`FL4+|6>xVh*`}R<6;rsP{R1p@z=+uD44or?6+;2v8+qB%SF>3))Cre(( z%Qep$7G4<0V_4w>$=D8r3d61ZGLFKD_B)ip>Vr* z2lhRS*G#c&WRD7U(7{8#Zx1bj(h$YbJz&44TiJ4JAE;$~z&f*Wpu7hs_d{g^qW*!;cq49Y z&R)M2rcjqzZAWxY*7jma{!<4FqXl;2nO|~Ba}){YiRCieD2;Gi z9zvF&EG+6wsl)4V@WE4`_wSJb&j@UNf64Z!W6zN1v4s76oK`$9`sSo-+hhvn)cO?@ zKi0VQGdjLe+tnrBB-uOF+&sv0N=vb!B8WRL}t2+oprTX5>w zv%~I!iFRs~l<6!@zrNGlqhR`(uu-OWA}mxkZDtu>!~-7%CPyZHhN~chj4l#;^@_#ndW* zXpZ#NDH9C){_+i$4}d#BrW7Fq#erZgjb`V0SHV))GVE6die0xFAI7M%DX zcwDA^H4sWbUVO?JGPXho^}#Q4z!I%E3n&X)52AlzC>iY!)Q1JR^+CNx!=+A z$bD04vX{W}49B|AOfakCkh)k8QH=51XshFEa- zpytms|IR6c^+*Y~zH{dVra$T}QpxlR5=X!bmX&QZ1p@gXRwiPJUcgKVlhV|U?&!f-Hq%T(y+J2OiF+5?iv0aiKwe#5+6IE*+g=h_)KM0U2jR=WEVY4Iar#>q zc*d=5k-FcQoVqF>2-S&r!*yUA8D9>3fwfTfXBpz!pU!f0uCx^ty*xVapu4f!unWB4 z57pHw5O`rh+>;T-&ThhCIRL(znVijm3yCE(gZ21K-?_k<#Nir@IjE5cZz+=yjqbai zN1k#Y`FTk-Uc3)+jE9Kb=-windTV>nA?`v1k$}k{!WkD1#5&5@zcnDCfC%$YhnxfT zkX9BUYnDW^zU_fDOuB~;eJr~hIJAp`s~CPp|5588@CZkuBjHfv-J|pR9`fg zW;*+l%5q@aP%xS_1zDlyH1!)B^%_F+8-mG5>GCNSx^LigizyC3$?M?#3b#m~kAzam zrk^@{LEgNqvd~=wt`XnE*@;|+Mau+i#UTtP{V+9~?Dz4;qX~%AQ6o<%6Io!!&w0#( zs(PyhenAK+J=a9(>%`Zfh7#l@6k5IbFjaR`Bg(ky;l4em3Bg-{4*fQ%i%>Dv3hCwZ z5ZFWZ4vW$P(|L*g<)l|%(Dg(9t}UiQED1$=U6ATlR@Srscw#U$cP6Hkl}>3VcqZKj zK!%njHB$+3Zi)9)qIFRxIt~GyEOny?8V}b^hy%=z=U~0(Ix@m z_kx0ipBLsd<-l9RysOsB)4Q=Iau6by)Nv;eVKDAGc}wUb%yG*TSRXOe&hMDX0=qx4 zcxJTObIu9S2Hrad_sN7>j_?oy3uzvm978R#m?G*<9AdmE6Y3Y|*1pXe=pU-^`h%jv zSMk5{h{|d(#a}x%gAB9s5f0Z0w8N~ciDsuZ-@zWkIT_xBz0FYhR}`f%@~rE9)M21c zW`}I1S4t$Wlo$y%e}m(j?Rw$BTlR= zL`9gqY?J5Q48;034?Z!P9v>thCANs25ZwJvsisT~)Z#xysC_)`LrNC-q%17=P3M}x z!F^>&2>K!Zdw~?jC2_p;EkJnPr#zGBsW|cGa3K^1mgun%n*u@6f*_dKSt&=Ax|MMn}E-9#b!1Jf>4EIDhy8AVg!JdP^%HtlMr3`(uNU*Nrk#kG*=~MT{e( z$ruPaD6n7OJsIo>wz`|SiP(P#J$3T5335{4P~}4ic}F`3I3jPgmJ>;smO?$3W?aqk2$)EeOTUSpzW+I?M> z3-xxbKqvEs`4<39i@SNI-?0st5!)Tji5qOBr>wJ@_@$juf-S};Dm=MaSg@WA*@Sn2 zfC{!nANj4Mdk=2B&0(dGu7!NgobJ>;c^m)vrV|=ZO?gAq7aBa5`SPlF*Wy&t_ z;1gbmmBIKRFeeHnplf+_iDgP#fBL$=F5DteajO?ZvAfr)@s9`8tlS`}u!vZr_T%J# z2$djVx!CFUf^1pYwM4)*n!Q<&$0chbGVia!7DOGof2<#9UMENshPRba`h4OL;Rbd& zAaem>#!Bu0YMQ_<&_(A1+uBwUN6bh?N)sG1+j{GVCWjkFg60qhL4v`H6fjUNqnjZI zhOs-?FLD!Z{gwP{CcE&n``-oM%s2)4wb*rh5&C=4$dH)^npG23QKCg|`kxqDet3N2 z`TPnj;3fFz5N4^j93G{SF%#6x=2`&QANv3&Tw~rDyr$;XW;G}`zH_huVpmWmnItm* zD;(7SBunM%W~fPdC9{7jO(tM? zlw5yacAfWhB!;B)9+%HcUfvjSE?ORD7nwF8cj-4bnf#!|X2N6WjhBdrXlu)#eC3LY zMtyayA&kUnQ!-LoV-RJ-1}FPa$cO6D{mg5%2J~)7_n0VP;T?P|h56`WimAEG>*;?T#Je^Ju4w36<*{pfVs(ZD#3mnbJn!{mwO=-f1PzzAclM6cFB9;)-kTw09hd0b4qu~TW^c|(h%sVPUpd$}% zGLNXgYiVHMpq;*rAnN$$RS2BsG%|-FTd}hQ3Mx)Rq9n;}A)V4v&AP>1eHLRCpn?A; zVR_QtD2})MIT&N*zAX`OYmvZs5WxEfx#+l9;w^OlIk1XSE(AQF(fL4^0ZhXJR5%gG z1H=uj%}7rXxMJi(wNxYBHG!*OBBp?QN1_9Zma}VioF^jA!C?@ehO!m98=Q;mNf`(_ z3H}rqBQZsYdvbj4fGc%^tn=BUw(3Lmhu$<{@ET#YXn0u&9stv-fKCefKOVxBT4)TC zu0~JIf7?jcYa&2Y-rbZgabA!p|47%XW`}nIOpz1ttVDr@34KHW#ly@}yU=1nXM;JR z+m%;cb_C>N>q(+l&1(MhQoOBD`&=J~cLkk!s{bBG0 zKE{H7WZhO+Al(_V8npK8>{xCQbbK%Z{FU^NPWH1@)~B$JIuS(7%`bINk4JIUkOs<3 z2fSGp7RLr_RXrevqMe7LVXQb#gYX;MWo!cj_3}6>Vo$-7KXyRf?P`jJ3}6>K6~`cq zI~k+HiiJLyc*82@Y?l$_A}WIu@+k7z;VaUQk3G95PB|%ha1nKTJ2zcp9pNdN+5+xv$ zAuU;QZ%xegT8q?IALxl21Icgl{$QEvOKo!@MKI{(QND=aTL+&c%o0kvcfOmP)#aee zcCa|pO%Ptiio|S(WH7VqyvJQ&N2pFG*0T|UN7H4gm~7R3*N}WvT|NK7RTXf_Sm4I1 zTN#sg`8`#LBAaRfonj|;_`<&LW|~alA7X<0=*9WdSrh=H!W}e;~V4+uDrYE z=XR0S?$)9V3n3E36WBy9{@SDC=}XOg?PRzB1MtBz_;9EM!Xg*!5(Ld0IPjDJ$y&Gb z?0z3k>79NGlU?g%9WJD+EsD5?Uf{RG1?+S&ps!Hm*Ar3izhc*mRwye#Mx#lL)i(t2 z5e&V~CgR5*?zS@)ylCvf5dz6q>vHK%Wx<+Lm+2z*zm=!Y__0i6E)Wq?f|d)u17xyZ zmCIfeKOPT6Ww=cDTO{us?EA*gyR#k<4s3`a1=S91P{*^qGmcJ)RnU=$h7ruvphk3z zOmtK4zIaNEL-6MZq{1SInn5W@t{;j#_6+lZAbDF}e}-K^$cNLmRCExsbOFOPbP;b+ z^L#sO8g_q5oZK-TyhZRyEcU{OgAcpI5fjfP!kOCvoM46Wb3dftLP&3n73!Fp0jYKy z%WU?AJ~gKFtzKT3w+4_!uiTJ{DtP=W&5~VCxS$OM2kjpE#kehQGj!TW4caJi``LY7I=Fqq<)bL<(92=-q0VtIB@NGCeWo7rV0ZhJO-s0mRgk=7;uoYtZ zdCQ9!sYcJgvs8jYr|yCF0%H^|8D+cvtYKsHP%x}skjDc_!j4YNh;Arqn3cke(QZE` zqHL=p<3$QX`*IE)9$p4Qc^3~cmpjK+mE2SAfAhu9-CRuNcvS~7g5gH7=&2Z;I}_;+ zrYm^psr2A)CB*nr{VEqOBa)gR8#!I%`Nd-bIZ%@ z*~uPV`>ZQ7@4woCq$82y1!Vy>bnDpSu00F#C^adw>j zyNOkIMVRkq8F|o$)s&bSyzXa@qKUsAijV{7sTSb&rCLIO?a7mf0=0VlV_cAD_VK7` zfAnt&rS}k6`gx@RBD|9;6U+~?9H1J_zzuM0=e}I1V*>WV(pHF5U6emCzF}bjI=Xq) z`9;*eJFW}tHu@n`%goo8BiJ*0{7_s|T@o2jZNa8*K#dT!TU!WR7e08!o2`R&mRa z3ZCNj{pfI9&4(|Z(Z9kw&;ec~VhPDBE*xyj0t4VaH-Ly)!^TKtTJ0^edhLPS2_Wmo ztU1S^q`YZ`UA+;3j%+2n>{3#Ai6nypAF7`hBByK)Kf>I9V_ugpe&32&njR-e(6~t`C-1b8^fB_YC49wf&KftN$Mx&T230!;3 z?;?pE)2>c{Y?I+JA}g?K4^1n=@R3NWM&1o>1|$-oPc(OtaCte#talA%R$_9y^} zNr$$oD5-uh)D<6ts7=YWqirQP;jtKRpRG^Td_do_oMVYCClN78^AX)Z@)f~rvIgYl z>@03-yD$^6s>Gge=P9D$q%1Y{!q!r2SYe{I@o*g5^Z84gcx@fs4CWItea^yyO?M#f z&O(^UCSAtGwy|sbci)md_G_#fb?&u+WscIUAcVhf0!)T_@EBlcMV?72PmVpSg&M|( zkexXf`*a)-%QdKiLDLlg;`<27nSg7)7RUkDplQ|J%&c38WKR$Jd-|Y3fD9b)t z&^qjXIOKIs6dt@bfYq^YZu1vmNywKTER0}Uy@iCjAt@zvKpn0l7FHwc3i}R)K}_oe z{gsSL9GLRv=}tn$69!-uu#mVF05}V`2Ia{rxG?J^E%nf&V}^EBYr{<;fk{H4qq7|D4VYp{K^<;|%ox}Y1o2+J2Vs6^;QF+p-z09nizqh4j^3YwSzGc9bm zabFUo1h8=xJ2nq1|0c<61jj;FJwq0d8(PO~Jx?;Bu(21?zo3AROmhKB-v*U^YA45a z_op^G=(=@?g?nQ~&H7mt5^cn`Lsz+7%n%|GlBqxsV{S-fZWVTLBA@dq;T%~)i^bLw znOsT=;G2+smgQx)MHrJM?c?##>R&=c?4fT#$;a>lHu0{AAvd@=!j1jm- zK;rSnqHT&h^rLJ&9zLnbc`=Vp*5}hKkOx-bUm@+tFT<8MS_f(!0(d303ym4WMA{LO zxuf(0aapT?4skx(Ae$_e zjNUK~ogiI9oICCdO)sajY4$1=&v{uXDZG?bU@2JnyHJtL$Vm1A{uXbe9DA@R?4Vzi9jJcIjaeQ}m29_z4 z{S`3~>;a!-B?>536;U>gLfvsIpohZeeSsLD>IS&BKi)hn-Nf6DuGB*LqJ7Zzr#^+E zJ_Q6m9;6Urx=*{_9VPX?m?<{m+u4J;U=&G%&im4~CRopVza6MEP5{Xoy?cBBQxBz+ zz-`IL%00vm6T)Vuf}5weU=><^E|1b*AgN0Bx|t5YEgq`1iz?pgrYI-f)~zKpBf#~e zP$+Fcg7QY}9Hk2>Cwd+e?eW6laVt~Lki4?S{^Q?{s&cVn>&Egv#^vm5u==Yy1B;5l zpdSBL2i-ldVc>uz-+;ikLUitr>3`@7mU=0y6KsPox{7jw zVmOR>zC=riDzPh{M^xt|@BjmovB_H@Job+56!fZdxjHA0x!ce%#t1M9K*QP|Zpyos zRN+cnp>x{%p17Qh$L9zol}r97p{lt&#LEkl-fh^63|m5C=z;AYj2hCct!vL*{lUX2 z@2)LXwWT{Piu5(nb8iEp?XeTvG+zC;D6r4ZO+$1Jq)Kv1ZD z*ajg?txn|0NKAkMFLr0iRBz&8EFz9`hsw))Oprg}22R{1#=IvlL7}4bBviLgg*0Lt zgKdNd6mMhIm9*?t4n@-mtP6+k8-3s9Fz~}XE;Muu(jJ4BU`wfgS*MzPHGtNz4NO&k0g6HkQrfGYXJ`8H!CDoSLa`o|PDIr(+KQ7w`ei1@zwINJvVO z>XF5a|_;7@q@9$Do&pvuMITV>cyY` zQ~F&1dku66cHL5^*gO`I+NkVf?O$5x*v{@P4BQwm?E zxRct)rog4}fu6`28;a=b5FMwUKl%1Y{DdGKS`&<9A>e^v*c)QmyP1zqPC;fX;Vvkh zknwfDQRM`$R_Cmk$YE@pqCVE5lIAok@dF5b7_yObM&0BCZ~Y?7&$% zg?&>?agNL%$|l@aS)M)qXhK`)>v^HnUxNvZiIKOtUGps&a0=Yn<6gapy63qUa|<2A zB50%sVF&o)J5L>72X0xZj%CAxApb(Hr@pXQq%|S6Z9Bg^4{T}O(9{g76%A-MLT=~| ztXsbn!Xps+7=2N2Pq_}`v{yahL_~&q%=~W)6+$2b(_i2*lvV&aL(q8h<@Zu@4fEtS z@iC^9n>2FU!Ac;$VrK)B^ud87G1v{?8h-i1w`@0mM2-jWHFx_hOtQeJncQj+i6`$G zj<*I)r7j_^J>#8ak^zneNo#-&!oCJz2?Aixdw^1ZvNjXE;OGszc)%&F(231o8E;(% zzM@)^XU@QGO2zFjdPI6sAc<|k{Ao^Bz(HHOi?=*$h=>~yJA%2et@dg_dca_?+oQ4v#c3t?Wv=G>RBJ4zS<=PE-To>I{^?nWEU1W`YeBpLm+N+6@h@c&MT0? zxPhn2F2uWorE3AV(P31DjWfFrkRUe{*`oHw z1t7g)wT9G2sMd|O3H&IC@nZE5EOfZZ5&NS6+*N7=OoL@S3Ry><+&M&P`qRq``Dm!Z zKyrYh^O96y@M1^Ra1b5u+h#hwr%ITThHdP{+fO|PlTgyt6s5ZeJo;W}@eH*0XrJgo)gu{_8 z<`xjBsRVYo6naE&GavEx2`EaA3(Xs8d=biQfEq+MSaq*Wa_~Z{cR|Sr(EMj_X!nCx z8{$xBULX*^32>2n$ra|I}2Vm#=U6_{kKIVs92c>7bBwo9ijI z<;DgArRg(3r)z@_#BX&Z0Zzp-n8Z%=#U&iGrD5`!C+ykYVWt2XYwb`)kPn6G#&CVr zEpvg^eoxBU2s6)#{l$F#KH&4A{|3p0@MJe^TpS{83s(KZ9CrdD^gs2OKI_o{0(NGbXj%1w4#>?rx7QU`jd@53M!m%)qlvkJBC+l>`C!) zi|`CN0iEs@$(M8+1tYxn?E8DUGxeoN!huapEBBWV_}>$~T`Fx`UaD={6xY-JQM zb!~5NXR462Y*L!O`j!$wJ2O|BI}F}h0_e~U^~2`9EgR6?i4WMb@9fkuR5W1%P#jx zJNvH6zi&GOFZICx;_A!eYTVwppS`m~$y`w)4x%*Bs89$E3eB@Jlr+*vs(s9akfhRp z2F+=n+j7WIqBNH>H7S+m`MuV5&hP!b@8@&=_@48v-Lu!T*1GTey07cHQTJR=a%h3M zl;_iiPx!Eq%sj`F@J`ADXebMQ?x-DtN(~eqkAQf@BPcYaT3vwRpsqWe)Wy3Pr$iy8 zszz~;6ewn>5x*c0mhmRdu2otfEd|Ycaq!HUTzC1-mP+{AYzJ36YlMTkx%~2(NWqtU zAN0@=p<Rr% z<6dGQZwtPMk9M^#Qq*ePpOJi8cW;A_e*&+eyrc!-%?T7)$x0@_D>f#wPye!P5 zI!K=GFM8|k6V>s7xWs)sP`DWy8wYo~zkK;J4{7QU%7iZ1Q1>~V-;s;0FocEaL`tq3 z{-*w%g+(~B%ttV_>%!A(*(n1wtVLjQB}instD-U`soRN? zyY@c&^Y>XBvpFouQ(37nq$uGVYpUpqhQt(#aBeXu<8*n1^5LJgDTZ2FH&N6^!plhy zjvPA38dmt*MV%UML=lp)BPb3=X@ww!HsrY_U^GO+@87546%v<|V}vbQ16hThj?UeF zA1-cgS@&+Eo6Dv5g5mlJoaf9l1J>#~wzhF^-@cWxWKmVZ0@TA)F6PupT95U*c^;eD zuhWs{;1*95&wbojHKx=WYJS`f@A0P~o9;aD*THq`)+vInwY}v4)&rhbPoc6oTO>*4 zip`@*iARz($7bhWTDPhqp8kLj#KvMH21{qkWAV^B{O{v?r~>Z^cX8u1Ra|j~d-hyH zZY^V9C*=m$?T$DaCHzLQZ0M)zZStGKYL13f6#(^xoN@G4?}@0AUA}E}O69_9PFASA zQw44|@;kr;iY(eiZviWw`g4s1Nm% z4r*JFgLq^d=~8Has%fx$*KNRHe`g=#%(vs-j*&Rkt923Lco9b@6bWqz8pzjj*24&5*(miiJ{QH&JyJhE9 zJ!%r>H`*YC-?mzI{pFD@^LB%qnL{p(eJjtbwUu?&MS5OCz%JiuY|S%UkK>c0`KkPy z4R(lWJ9Fl8N;i2a2I>sh%c44dQZ{pL%KkDk&EU=>D zW;q85r4dRpQT5??CSl;J-?dtH7PL40qa*v5QcRg=5TR4AkGqR8!y@Te%nZHi;>GP1 z6w^`_nU=CoLDcvMOfkp`k+!)-^5%?J~Vh-{vThi=DR?`E$3-xig0elWjrdNnZV3EhH2W-9^JUAt(;I&=s2;10DRwD;XLk z^-=(5T{tM3i@8AA3{1|4H*I;@o2Yd*`|$Bzqdbwz#wR5OS}l9~?p+mp;kT?z&&ZIO zM!UOwx&Lg68E9|H@nDG&%sDRVb9V$;+?^g+6{joG{w?GZi`;sX>=T^0W)bC7m%3AD zYP<;5x(?C{d=P?Ve<>=QGS6)km3XXCfR(`{8^%bVLUKCIbIQ8(5c@Myt+l!wa{k8d zzNiKc9gHBAKZ6%;w%p~wlSY4TE-tg>ODIa(>I6*-_XRcQx<14C-Th8~O>%pv1qQ}t zKO##`e%V6rr<~)2nU2oaw+|@l!J91V0eSOydWN%=)i_vMSj-GBkN@@e5DJUezLA=j zWKn41wtV=sNxpj$0>d(2;*NIX6$d38=xU-ev2}K=!ru%${sRW<%o!aYpYd-YLi-Lm zFsQx@`d9oo&%s{v{K9Kg4p8y_QiNu*JER2&+tp9m@#Eu5w-mdcvOkVDL3C*iIXd<4 zyXj}vR~O&?6tDlgwny(6jk>+@zgIK5PkHL95DaFrjP5QvzN|7=q1Q+T5{IUcu2wc`Oe09&VtQ|wPwuri=Er5(5a#>X$> zTNp2zeu_q=Uckz#812FKmbSj3p{dF1_wv}X%gBSHNp_Jb=ky4HB*pdXHIXhNkv5!} z?%1bXiKM=xzl=tyNm9cu^R-XWxp5mwaUUxe_3U{}UgKJ{kyMO+%-&ARzwYNZ1VJd7 zN1LyeO=)Iroh&nu@ zDuLdAb%>@>eRuUoyJ`hkgiIs6!J3w8%t$fEzc7VAl557`&Rpg?TX5IULQ(kDA(ZFE z2ZVmoU0iQ(v+S}XdhFIIvKI>(3`WS761`+sQ*Qd&m%E!UGqb<=@>Cb`@D}r=;MO;uL8|Ho z9ntJzX&BP_>pu{DDa+jYXVd9Z*|q`oIo707(!E)JU5<8)qI|&}C0OVQ=t2n9esgbpm+&mAC<7A&P%`dM;-u-*z1h@rP z<3j|z8c%V^Qo?iYoTN1yVL8cipM<8;q`>nTT5a3e(JITK3QdGh7z7Y_@7_~%-UPNB zy9!;c+K={q!=(&L)$D_KWOMTRqV|=Y$@x*e0;eb(#k}7dw#|9pdx`VPR1JSF~Q!!zC%oa}4p{K7XROsZ<(FNblmwx3liU1=w@t9Zng)+!J_Q^Jvc5j`;Dq+kbvst-6y~c`VfT8m?=+Mb5=S!cOknnI|53fr}}) ztMe~^nU6Yny)erxn<5!BtUX6RF&@JP3 z%;Kb2V*lTQ{B2By2H6Nv`7dp6H|2;16NXyUlVph;F3W3jc!N%dNNOrgI?3lOc_~wJ zu~Vx0$B%a%U6@is-AA2K_6ncNWryc2A(UroRg@`>n9op;PnO>L)JV?7RZ;dWN^&>m zf--ttYBJ3}mLbE=>%_>3xBuVE{=ts2(V;zzh&U(s>jyJWU!Z+ zGSFeLyeIO~BjgAu+>!@J2on!|q3P0Af}iCfu+snR2xlOS39u$7|H zBJ?Tyb@Rj{2efYS<@hb9D5K3v1|8L!XFFDp{6D|lM|nbUNwTY^ypo=SW&UYml*)T) zZp)*a$&O`qA9GJUsQ3MsPnjr_>^F-vuW%BVh3EV|o5gc}&XEgTVKgeYv|CK1S(Yhp zf7`;haJmGDy2fmwV})#=m{$4pZwu0o`nj?%-dXuU_t|ye>OLw5vp)2`(5WCr>w!vb>qEtA_Mau~lu|NqR{A$Fa<51a3kOxL^)id26^d!b zb_DBfLB9l8Z_Lj882OT-cewfV*pJG}==UQ|m$8o#YvuiY6WRADot@yjjAbAgt^H=e z=*x4fe7vVT8}p$OW+JMlLZ2<6(r+!IsMKBLn}(9p^6!So;iXcHj~4a34aDchoI0*u zq+YyG`v|ToUa|@6%YL1aYk!X*Lyl@INBWW%MrFp7z1!Cl`dYiW(Isz{XaC%d|9!NU z?2hG?B6p6k=p@&l;Qic@>K;6|f}-UAd{DNDifNca-f~KQJ`q4sDvIYF+4<4`vt99Y z_$d?f{X>uGo-I3Uj^c51rL9;kXG6G~9L+Am=178iVfNB$UkM<}p)fh)PKJc#> zc#aJ=g6we0o@Q>``Kt(=GvWd@M>^<0egXJ232aqP|FFrbAE`5r0z(mAPCFKdy@XU@DAWhR|BLkvh@1}!nBUa!2o+Iu)S!+G^g z(O=%~@m^Do*e^`}?r<9yGY0Cewe(hKeT|6Er<<1(+WHx<-k=--isSmvqJ6KW=6S;% z^eiC9riY>wr5+r%Op%9~q`e|Zdk2F3&FFZ%HPx2d!lFJ`9`F^N>bs(I=FErm zT}v5p%+xp~&Y~I--U~}*K(JwhhYT&yWKq9=+_>_3h2N$SH z2U_#J!@Mk<{M$o_mPn9yO?zoYJ zQcFD>JyorOyB-+Kc>fz_SMCBT;}1pZK!y1O01j=5cq#qQ~5Is+rl(w%=?8<|_z@JyNxEo^H%pYI(>a*;*C|IDxylx>CVIQM7SuQ2 z6)u%tOHeyMFhA!iO%2C0Tz!hh+#kNCs|*@@FE|xHEB1UmB_|kg6s3qE*)7tGNp1>) z{BVz$I*J&;)*nHd4Rxpj95yNkgwMduEwj@T!v7B-3kWUn(bUk`_CS`RTG9dSeE*tP zeeEw?QaA3OZ;p(sD(Dw^oBR>=butUQ`&9q)?fMSl2+v3VSiGEV+*bE$O8id zZbZQrQH(Q*Pv3Da2PMe>0AF9bmfe-czDoA|i6L&uLtTlh}7p~-4QoQVx*h*yur zcBC?fO($t#QFAYMX1NbL*=$Pi%a|D6D#%YQ+%ai7U!H*{>Gr&YKiJAkN~j0e;P<15 z{m-gm7*LdduBfP}g*ENQ7gE@hsMNr1DUJhX2nXSlnCJydBN-qaQqw-0_^N>ToSWPT zYfjN-z7JXlHY7<@68P!%e7a@MHL~^0tVWbB4_G77#l;i>Ml|l8OY>fQ01QZ6Vyqhp zZv(gEv29I(T?u~+&PdjDh)zHqZhCXY*2?S%l)CxANtKK_>bll!Cz()Z>bT>n-$D$v z=lWFW%{R}ukUauU$z47drTt{2h@~Om(v0Kp_^N$8h7HWj9=hhEml_W=E)Qh>3|w*6 zy@Hn?0c7a{J*OIa%WYwZTRiN2|A?;8^7X{ue(}^o?@kFxYArioGGyaR)}-)@0|8)T z_O+Ks^1#Y)t=2cRg-ygb$Oc33ZhD8y9z-UhAaJcQwy`aq8XmBE1;@vMqde?0-xAn8nV;1bc7r2d-v~mVIJlOUPH4*gL;TY`3%=(?6gTZKRUkv28suHS=L8? zD=ZL&cn&M?J3SYB?=oRI(9afnX@dIM^?kowIW!a9N5( zXl85pA%S2nPx!$|{LFFp*^*x*Qs3t3_9^W%pY>lc(1+(u5oHdD^W6{*8k@f#C*jYG z08VB{dS32T?FG)F_PneW2^3Yp&UF5*Oi;!U1i|wrwahVX2|HDN%}Ekzsr09v*DiN; zolH7hYytmow5NjR<+l{vTmg;7$}())USr&y69O!r)oyA1TkkNK9e+`mL%UbhvJ($M zlFXEBx=ZVW7HyE!`cS?G!Nw{kZ{GWkBhMZTpVCL#v>9JgOk0#$$i<8v=gxdHTyD65 zQjMrC{()*ZwtIz(=OXMGbrP$u2govcUeuSjP}DI|9UA1(H(%WnN&r5n3Tp*h{Ruj< zbLARx-DDhFNx6tflMnLXmLF$rR4V2Cv%Dff?3~JngnXx#9bpLEXJMK2?YUETzLVB@ zoUXd)M!MotuGW~c_>(y4!sB@9@(g`;CDIofpjnxj`MHT=P|V=hvslD^WeBrUH?V;l zU`@a*&?zH_FFHC}R6=6@*$^b2$8my_WSNDD6q2MP#9)uTRwV|sGWKcEexGh<7k!@I z+Xm=Y7ncfn*{-1Czr1i*T>uvf>?5LxT}f*_PFILNBQ>C6OrO@|>V-5y*b4|{6T9X% zR7k?RWF5cV(>7qZubTuDZMt|SqfRLef#-h0;U z0eRAH@)UZtpWqfx*`TIyF#uvWBmu@Rfo zv+eMw{zQU5ITn;sNa~OW2UsmL$vqtntLXFLm>+#Bs*&EH{s-b_pY>zyb>wQl&GYYB zpT#0DBBlV%Q?Eos8UhV**0#TZY^i6{bK)XNdiQkQGU~t0@8bFKf2|BJ>)a|DHOY64 zGP;YA(&QYe-*qe;G9a&}bvcc)jQHEY%g!sFHPQ z+mFWDPSPvEM3*JaXsVfHoVYVjB-@NewWi}e&n64+ouHba&b`0v@a#mAFv}e z8(s;1^P{P+6W!#=XI9G)s_~ujfLRkbEj}_*1*)eAlgyJpPBh`Af}WAH-JGHpBh7NR z`_q@GBu_|InUqCxI17KiCJH-1pEyA;k8FNflyCC+;24x5PY}Adu9R>496S(Q$nkNqn<8y3L)Dp@jj-=JjL_;(9aHs= z-55|APUAY0ROG=tb{_v(Zase!G8!vjN7zv7sb4iog4KBx^R-4c!xi^8dqJNIu$%+J zj?O0~avF_Y+4BXnE9sr^*=A-$o6?$=lI`5Im-|G{Mr2APRJ4#J!K&@KcQ!>uZX~zT z7M%Uu<2M3~sH-~=Yd8MSZOq=ze{OtI`ek;`d(4n|j!?1ce>U-@0Iok@j?`PM*_~NT z$8)=k4Q;$D)$rSWpOvRqhn-7v9sF1+PEejn3x_z;rHW5<;=8`v&-oV`hk)(sfS#q+-&8uA^XeR zcjILR1_n0doO%L3`U~M)6m`lmk@m1_%{BzM)}%K9p~Z4;@fpYcW?W7!;bl25A&ZrJ zUY4u`Unk{>fw<#f+r@y*91mWX=%!721d05xb9NlkT=K8*s>4KQ{?2EmEB{&wT>I5c zz7KIVR)bq8$NDW}?)v)gUon_Z;}Zh-Bps*EIwTDaR!vuwYW?3+^9LrmD;|k~Qf?Ud z+5u9DVYP>0_|3H~Irw9`Xwibt9On!6g8;y7FiN?m&?eP8bm&eC8%6z}%g!}c`%QLZ zR(X96&_9D2&Y++P`2~_lq2 zGrYcB8lO=gdR~)Wq0t`xv!b90?H>{wviZd$%Xj_w@$RR8Z1-npG>(L{OAZrn=houa zdQ@+7zM;*-Q}Xw#xZ)pSL2)`8+unsPWAejoMn*Lw=3?W_tQuE zh9Xn#$|%u7oL=Bql8i=BPOUj#bJe-l=^fZ?ek3b*N7}dQ%=bkY4ZLaPBp%HG#wUr8 zN5o?IQXF7yb>&*rKIX_{Nh?Pdd;^qh64RfFaX}|&%KbkP&%UQ(D|nd`$J&9~;g-XS zUoQSrTSjl~X+*AbTkv6%TDnJyj7yA%%c&O)nK~^+m3Q`;IF(MNIg8>BNZ4GP9C&$t zAVAZpDLQpJpei)c_%1M^Y?3t)V)_>{Ty_W?!wwX39x|`cPD+3yOWf0^8+P!K+j{{y zscq=>6^{qXoJn(K(S|B!&wF~fH0|S*&fPK&%NMOjL;*PuS_dtcE(pG2Dp6!)k|#6d zK8xl2_I(SlvKUiP&p^Ye@W-?dmgX9{Z|hJxKs*-=6@f&Yk5CI~B0$DrdsE-QAchDw zYI!gW<`UAhwg$umwO9VK%&NJ}f!|Sf$#G8pMu%35n{9wi$3RaR-SV0nllGl6mcNIK zyD<2Qpr~k+M@we5I4+Jf-7nug7|s_$9Z&lf1D7JE-*fU2?J>ak8fnS#E?wFI_IAaI z0`f{CBZa5W0pVDFb2hMXWDH3P#vBS^d>?rDHIF`P(=Wd1)^%)pB~6NH);jpu{N4S} zWiNPs{1|Rr_^bKnBwggRsgW2i8RsP=)_1Qtb)6L7>O zJ%)Ys1U7x7nr^aX!TG7DRMr!>pW`#@cH=DYAJb)|>Lwb`&hNIEH?oGxl8$LUE|2v7 zWoQ2)c1T5TC5H3u-)I~tvXwM`M=>r=)bQ0TighE5t4Z(V$;!qnVN;D(HJs3-t4O?# zq3Sw27dS*(1vM9o?EC}G=e)FKNXdWtlN#iF&lh`t+3Ezye#tj-;kY#VP20d*9N&i= z2weut!hq6jbBF{M`2D;+`ZpcZCZ=f;MS=#|N*!s)E;BE99{xhKoS8dF5#BnxBwfq}Y#n_M#0k`hDLugrF#T>O| znZOcK&mb8l@DG{zmr{;%WCKgw!*KpNc*8WFCLE{7%W|i;ZuhEe+*frv+H;_^@hbbRXf`tD}Jua}(4<9cV2b`fKWZ>HuniIG+gF#p?{7k)5-JqM)}h0C(&r z7Z;cP%?ViYb-~2(rrm%UQbnMER^vWMYBL~_%P5VIwY#s4Q7IY93xqvL@HhIv3zw1g zzJ-rV*iWBpMrwup?&@lP&|)s$;Qj>vQeH0 zhGK^Eo$LcRu*Je}w*w4hcZVeFSgsf6qIp!bHRYLZ3G}*~R9$z3k;w)6YexN2%20o6 zV>q?U{Zb)=*paZrwUOmFucVm!_dKQ>#ix8K#5kV8GUB#Q63DcJqO+xg2bp5UC>wzPa4ralM*zBx39i98sWLi}&Q6o2Y^Lw4OQf%0Q(D82kp*+=jAVlHRe52zc8rD@8`hXC}Jz{Wem*Na}M%6ly)@A2hwYrGaK=*LgS< z=#ZkH+){j-F88K0J|Tes<%=ysVVP7AUtb2nK+yy86qB@L*XC~@JXqUiaOlt@s1(;0v}H_5Q={cbuXh?! zp|bB$hTY~)i=*cp`b)@k)MKT4{Z!$|nyZ;hLqCBw-xpzRTpwtTrAl;>*DdhXRyFwc9T>Qx#tOtkottC z!^F<6zSvGgac{d?UNy?e!KdS*?5XDPMkw+fe6u>6;P1_A*!C&XcA^~x$K@lq9a6uR z{-G-MBFv*gE?E4%w=nEzh`;iEi9EH2oR1S|;-?|#qF~uat%w9gecd)?V1xF)SwJDX zfDuog0qj&X`CHSl?fA0GWcXc1yWEKnkr&$`%GA!)PDgekUInL_#THMdq?sGk0F=CM z*U_iEn(6F(02Q1L_wTP+%|}CuXUqk*sKzG`yYE2rmEE}Rp2Oro@8#~rc2q=egJUs` z@(?Vd0Lq8kaRVkJ>Xt?r>g(HLU_o+O4@_V+JfS?gk^pVk@|(GC zKMla|RRe&U44!EeB1Imb5r@hJd-M`Xq62_bO`Hp~A#roj^6;K|V3=Fkm^RW!T0Ou% zoY#Q9h6O%-9Q%&SH2a|JSY9Dkub|x?*e&f?mXw^VO`I%B>|l26RJoE&3+`&nPJz9g zuMi%CSTVSfr$O6SbmPX4!8YM>@U~63|CbCUp{7r>7ooJVG(XW-aGXGJJiU`-B<5Q$ z`?gyd)|slvyT9Q1T*iSx+7CJZ+j=a1Z3lt#8X6`JA@)ky3UQ8Z@306<;`f6{re|W( zb>armD0~@1+%OL|tvWSdu|v4@DADH6eUu{Tg28?UCA~YXtR6`e^p#|k!csfPwt5is zV*-qj`<#$V5#JsWO<|8WjVbttQ~4ZR1vT;4Efaj=4;_lFF31m{I^ZNkuZ!lbG-qT6 zOYK~%l|bA&d{=CqRY7GhbB)?SlB}220HySq)wPhzee`Bnqz^(diGg#G|O7|Ns zYtM3N*Pg;mv;Ceuh&ftziO|H^;us6a**}0>BL&mc;=w>C@eDe08K=+Nw1T(nA=cr( zG2nCpk_=Py_?1Xz-3F|R4kjk8Bp4(drO#OLXW8qafPd~1Y9 zI6LjAM+S^v<0x-vwYC~J=ri}PEbPEdxi|pG_7cYR2i)(yVN?9_A zG&yQ}xGvb*H9{Uuj~aS!eadobNd~1~4S0N%*tekj_v14%J_SCbE(Vb*MxUCEdMjQz zSnCP+N2+_X5=oLQSwB`dQ(sX~FOQ;xQa;{5KU+G#Gw)~AR+lJ_1&O}rhU7^#O}G|5Z=>ir$=bM<&;C}o z{h?v|%M6X+C_{@=Zr3U1iqefbDmY7@z(u}TiwpAGi5oGEtDvi1UZHuH*f3sfN1Slm zwzsMxN+}y&M@VY)``a&Fx|D};qE!N7OO!{SFIXJzRG;>8WGi)5P9B}0f0La1+~Sek z++n_)C(62BUAZqFZI^uK)s24Z7Tk_ln#EK_sED}9y-^?Yu)(^c!4=#Tlk<*kjVA!t z(p85+@+9G@;V4Ov$;CW52LEU2V3UUVTfZ+vx}i8d3E!$u(33m(`hY=D{>o)H^r1jy zmL4w625Llt4E}?Iw-1beaRJ;?mXwfi!*st9?V4glx7+VdKceTP9z5x~%;~4J%29)2vBqr8BvY?!r&yX4!63JM zfjPrDdq{eIJ769tVa|Qf1JX_K2h;TnP+UHta*%#n6-3foi4p*f)&6z_m?})~IPxe57&q9 zVhhde$IDfI0f){2^qY{fFuku%ow7&V4XON3C}m(9xwf! zK|1Lj0bS+-NGIuOD}W%~;bKH;OdTZ-ms2cj)AsY(W?v<5Pu>;hSxfQ<9>E&#d z4TCN9+=>WHuq80iWD~%{A>6^aTmHNB&L#Yo_TL88_gwKLLaM;bm$4lSsE_y2YQvc_ zZT{PSxc>5?%E@KixONQ897{X_8*|nq$8~3L#Bsn zK5f|E_4G;QNiC$EC(ALG za}pb)uebiT*S52AP z{cOXz?!W`eHlx!wBmgydi5)IN?Wb$C*Yo+Uo2<}|?gx!0yl)b^zmKpbv&-{N%WVPo zWaCIc8F<-&3oouZ_0OVl;LZsFumS zc|RpU%e8C+uo_gw)tb6e5ac^UZB7<3gICt(eRwu0DoT~O_?OtpH@gN9rh)?oAWfT~ zREPTV5!o~l=3FlZUEYvr0K>~1NU8v>*yI>mVX~-K5rVcpS_g4XAf|e(=2^AF%u8?` zMM9t(xXW8Vr&uiuftOQ>U9iCn+I9N~YJ=t#X#sRWN@i2y+wuxnB%wU*0eTKL@~ILp z5>=Qqjx8bF%%*$sbOrDmm&NTiNcSe3H@7b^gS_of=`htKoX9_h77+H=1o`S8>3PZ8 zd98HYPa8Vlh(s$-?i7$wGbvOYct)eX+;`+Yp@`=9-D1@ zm&-doB=|69mam&`K%?4lJ0OUz&xQG<)PZaa1XQ895n|w+!$qR{(eBw5ZE|j1dO~3M zkZ$5yTil#^up4%((vpueOtC;;44b;4(95Hw9kWlG?RgI86Co2CV*f<&^YL||jktfp z=0svznhwZ4RbaBORYy8Vq)RAi+1VT*8-*vZ)rA}{}6Co_doT}TWJ2U1#Sh8VJFvwAVxB%SOQj(1S z+CG`;Ix{t0F`I(Vxv7fN=k94U0G#XfXnog2!cW-cL-c7Oq~xBlJ=tm*Nd)2ekb$ye z)b0;iOw%sek!VT)Ys8W<+hK z9f{jGW@_K{i9v&0vT*P&aih){u9s0Dl~g87zoTUhL%w5$ z*;X2^_1Eq|)14Z=|Ic^DRV&Vsby?O5flascsJz92EUQ)M*(dAYx5hU%7%x?xeuVF6 z2)e@+R8aR^^HF}8L(@ulB&6JU*F@Bd3~oMvD=RC%zX{MX6@hL~pP)iWF z&(QEEkbO;0@v7kp9q-%Q&-^}y!R=^R^!;4~`Q5#UPV6$Dsh@{`#wR4}V1cB=Ihaj> z>ge&a6)w&PVrY&=yLHnA-Ayutsl9E9j#7Ol3u%3gP7}okC>4b$LCUGA^e*(KjT`|&B-#*FNhodWkvgbUj4LDC&u9h4b;i?ye#b+N;{U} z`tE*QsY6+}s!UbnEUIKZzZi2s%W=W`%arGYd*{<9QLAQ*#yby0e=dx!P+oA>pk4$) zOnDd700P(=h6dhC?@VGhO27 zo`{J}3K;Pky?a66t6PB>mEK`Ya~9-fwY;7 zB+W&=2N%uwQtpl(**spyFw{gEH^M*(Iwf;j;>R=oIUyJLnm<3UL`Oi#syt zb)DnIi^;k1T{SINm#GO-g=HHDODUI+GS#OvE6e3Ii>EW?U4A$GYOc&~S?}BXl7A{p zGs_SA05y_Y_P-ii=j*d5X6Y6%ZATNs0$9}v0mVf&2Y%P0PgZWSw_SsRB>l}{-|vfj z+i5JX45s6+nJH!4a)FWd@3INXe&VK+p;vS@@2drf)XsR!w1r069QChn5mXi}WwWgV z3~A0r{;O%!M>M4HhsaxcuipCmN9Ce@YJzfWiyYaCt**_XTk@HqVjde)On3+9QKRcj z0ekyMC;`&Z3hVlHZqjndW_b1gx*{bt28)8lL;(=u2Yiy+Kdiv)x{0Zy#$dG)IAWcdi$v+26yQr(JA|-_mG5j={ z39As4#LEiiWF?vAE3HyiO`?xR2i^7cP#)Ot%F$|XPjhfT$Dm&GXmhk)KDwLzEw7nT z+ic#iFh^ISq0ih`^F?QNj|YfokbvK~1VZ`BcTw~@b?%N=7QW^{6UIv&lSz##3`AYT z(5xFPN>m><buJKseEM386&BgFJy2Hog79ap`G_OMHZ0KicfjDoT>E;Gg54<=QmYpoZFd(o9=N*@tL~gLsMqD0iSuyeCC2~ zMfx%aK=v4pr;i34h~l?+y5K>D(gCm)2Vc>sWBzC*lO_gcHi=c&)V$(ohOH9H)%Uu1 zdqc$6XnLGSz9|y9njJbVB=X8&0dOfxO#6@~5`3^M#EsU@fqFrSP1DNR`OWVIAq}-Z zrL-j)q4k+AR)3()W16|eHzi&)gyy^q!uPWW6lhX?g&2u<{Dhn%Il^5KHZP}r))b*W z=gSY}x+uyodjD`^nD6vR`*eVarf#eTzxnrbn<$mxtNW=*VBqnf4X^wP@v?^hw%=E| zij)E-dz^d)Tijtk@Q3vdksd}3%37B#3k(XfL&16$BSB@3zM2Q%=Y7knS=4Qp?hK|} zzDYQ#-%%68;2G_umCndz@{>+WbVd&reWud}@x z(b@7*Pkh_YuE`V)&hx3>`7*9gGn}oa2F}wv$J(Q%-_LQkVAfWW8$EybX`gu~msQ@B zUmrdqczJN5MU&s+wZ|grdz#ug#eZ_2TDISf#*>mFzr7_CO>XNna-54W5f4~ZQUBY)D`1(dV67r`+6z^Y$rBO^^Q8>`X`rDK0whmth~A z{tOXv9qu|LV#yfPxW34-7d|x)YZOq&glu(*0p$J{Xz+x5;5*&!%Vyt~Uv%TK#GaJe zM?ExKI#YOHNGQ)MTX`T=4EkUx?lk1#hJi6#cuo|WyjXNKypD*NBDQIdNJ07+>wcZe!0_JFF>UbaTM^~-){aVPGtq|nm z{q9?2Ftg&N(xe@a9-4=4x<*zOQ*I(RZ7ZccWMf;i@vjYslBxNpc`RcK<}+W6J5jAc z!O|DPX{|}FbW0^fOaGnk-j%nAiJq3@qlEKS*HE8_n|m~nv=SD8)!n<%Mo+}r^WA&W zR`lYYF$6ZdP961)#vCZ}oI}Ajh}$7}AAlKG_y$h8_By)+hOpNm+P`aIvpg%S#-Nnb zY60_tJ+0?nE#b}XP4@d5($8FCkwohrY-&LoYQ2_v?Es2^$FHX4zD@9Di)viT&tGb) z>I;|#g0N+v-TsA@f_I=zP_QkKqhH5KsuijZfXGToUV+KhE zN#v@EiUlO+?7~>wbZ=8M@+ItPsnzFRtfXew(;MRUOJ0vPX}Rb3>$Tg?S*+e-Nv($) zrg~>;Qhd2QH*Vr(i5VF6EL}V)N0k)&JqqLZ;_vZM6nC@zr16 zq2b<_d3YB=xBzj1z7lz2og@wlcTv#c`wC{%X}`nbk+q3;IC<{MIVJlRc|IGgF|9n$ zK)qt^;=DyNpXOXwqNDV<27rpk6{>D~u*K2?Lu2;ETj#62?4?G3(l`%qQMfc`J1QlKPf`Z4nL=N>oo6^|D)gS0&KItKTo7lPi9W0%$?iNBg@onep*JZ$t=)* zz{L6l^93Q_Y2?eYjcqri-ycMk2VMEs)x9w1i@m;g-#v)a1Br1|2h2VF3};q?mydis zazuF+C2V7SiE`&?1+bN$%Zbh%(`=C|)yr<8z|~K=AGl|tq8ZE}oXx};@35`u zMGYfG6CqC7XEO(Tee>o0^~?h)$tagZoAwxKtXsZ&?tklcKdMSwNqpK9)P(ZSlBn^C z$vd0Fpa%wOsAHZwu(K|h@Svn}g{5OB47&oOM%}SBb;Ikc?J3I4l6{5oS*1{I|14I? z>IW6MWeWr}rkROCdenr-N%2VOF)wX~)a~(@$mP;eK^7X*pI1${e%_Xoctto$muBCd z|Gb=_H2!pIa#8T^DAHoFXjbwXwudx3s$LGfr9v`uZ-EETi-QghNpcPiQJ@->n(mO- zo4JK%5-Gk?lxGv&7rPR%0K(2l^)}O^pY})kp6_0Lc+#hp*7?N0 zsTG-gACT4a2#GfPcy-OdVMs%=K=`JR*wj>ST%+gdk3zY^0lgQsLYqQo^RnigH>45f zVAG9RRIYebtW~)X+G~VFe6mPMNpj;x+bk^~pCZCLFvlD%g8fVmU1mX32QCos0rr2C zvAwGtFq`@=gPn&Pwka(-eRFgZ57RVjzxQc}WoGB-Y3ecjW$r!Dh981bqxZ0&vPFo( z$ItCmx$332%*;3xsy$BB(Mg)uV@Pc~c@O%6;p_;xr0JQKvk65)J*H0UX7aN=QU((a zSI=g-pJIQBmVw7>M%td2hs@cfh~n|v29gyzUfWM?QYQnTbR4U|)*$UJQov)bZ8E(5 z4j%TM%7plZHhV=R!NcH{dIvbaR|9@CkolRfn{NzyI8TXL6C`y6;$?GveCJ02K`-)<`pD4MJsvuW`* zJUioU`}%fUZ{b)>dY_@jw1>mc$xgT;%p`}MjsKLHFmQ%$b@z?OE=Bn#Az#+-pS3#7 z#Zt-F=HbOGk|&D+>w^UO`x(uoZ`6)cXFTQX?-6S&EN(dwd+Oe*g%-K&!lH(;Ydia zWA^FdXEDCF(yi71+Iw!srmm=PaJUh|ysmTh!ke~?X`iTmTX^Om?S}A0&{qkRn&^C$ zluIzo3GF8-ZK}8XwCO1i+1us?d6w{%YEhnVO4+xszn^+3+Fcc{6bx7E>wZ5k)FdRI zp03~Hcei*tVn$(ALVv^)D>Xy2JIh)P_0%w(ZQ#@kmQ)n4SX7wOh48uO@4xYg4kee> zoL$T4Y~_vtAuabk06c92+_d}1DaD_TKTcBi+4N;9!+oOEuTPy5r3S>%r#V1NJhFJY zq4-SHUmbiOf`3(&e+zy!BM#E&4k?GOZ~oEcq0No4tN0}EpB=h8K6nRM156KY{e9Zl zh)8}GU4%!6wmz+_xPrRPR)_T&t;c~+f*->`*A4fchc`DaqD;Sh7kDj!ZrVi8$kfpU zN+B%Nwfpr;N};;Af~@^`vuVCT-uJtG<+(dQ;J2G?6sygw1!g{ro1ZK)zejHk5$OCL z5Urok717%$GS%Z$SvbO}C_ZaLK<_O1;`S4?o5E28VOH(EH*h}L%=K5RA#hlkUPW(6 zkY#%G$|-l+HP+NWfL92wcJkldi(MJ1hVp^mkFf86xHcuXcp1ls$}XowAto2R7)P(` z>eX5}<4_60TLvZ|)Y_Ew`AW>WvcE{IXT{;hJq)Sytq?P@PZ1FXqTCi`>Uzt8nAGB9 zS9BAPF%wZZF+b>WUJEt->&N*Ki?fCc58k-Gkdbe>Gga*Atmh{-t^N2<#NL<#T<`!EzzTza{7~fl^Cp@g+KUMBu+YdDioh zF4g@*R-cmQX1sHfk8Ui{vS37TzSvHsG zEIJj!p>Vvj^7}K3?0EV2v;xhx-jYtIlRy*l!wyQABjf1dc55=!*;Xececi8TB zgR56dmX1Y}DU-LacI+=pOMGn+di5&Tl?c8M796dg>=gB>bVh~(CrkB`$kWKbq*dIw zm={2~=k925<<8ub4F{L0_ob?D^;avz;=S(sEc+8PUN6C;9X{USQ0Q zv~tR5)#K77LNk1dpd&=n>!PR!?TYu_RrshKZ?ulJi_1A2d(gFexJA2kl>xP6(V+(! zbC}}qu76ivv*xi>9gpHwnMZv}vs2BvJJPl|U3ivAWtIBbJ@#DG+>0x>>9pH?=AK*J zikELWHVs#-&tl#`WA&h!jkQoK_! zubo=IW{v(Dr}H{TE34-(T6AZ&`<1-1zpqEOQCSJpu+9|sQb($c%kpu_Uy7sa1-BgM zWGT6i`g$8DQpsA`T$Ue;3vc;ySDC6L41V@vwMTFynQ|l;)GNP_a@oMi!WWc#bh^=o zA+^Vcj9hWV!4pnLYnL|{)+%jol%<~J{qXF`)RfhGS{a2c z_fU!~AJ+plMrxx=Jzddc9&@9FoD*kq!Qzglkfws`-wJ zi-n}@>UA7*^Rk!{5_}85y)K_yON~sW$MLfAc)AoF(y@tbbQIPtrU0XEd!KQVvBH^Z z+*KMjmzT9|pGcs^xkV3@YR5L))3j7o^EO=NYDGsl(Ik_LH_yBtTXbh1?#JF0EPGlK zrx4)cSPGV$q^s8nUU#RNMUD!_X z9k1MauQA9VMw{W@BGggM-BG#Dc%9A2anc*(?wyInhA41xOv;A5OF$6#7^k{h-S}-x61`c+sNeT2W9TxsU@dkVwTS$oXk?J%^JeYNGO!Z(H6qJMI(BqD(hCnu7)-RekpoZQpM~O3WSJ%$tH9&BJ5u ztfAW3#THA2*iWNtwl(ZPoFlErfR@;pOJB6;(mPC^h3DppmZI(Gb@^lZq$MoUZ~4yv zKe~+m2S3_VyWQMmH@!Q5-1vd49Un-*H-Ix)g*G0#d-bXs?GE1ucUSy%kIjPZR8F3W zz4QGGno;=?zPHZul&#rfSrbV+Xd;SRkuq{^`Ac&Tm1z1hQLsvs`AuQAlo+!o*meGo zLHX(LODuaD8nVG$aQ?abV^uUmMvSR0a_!<&<_vWv;@%>zzKEb-&vdyd^=ad023#o`V8|^>}rdy08Z_g{o2{GCp z>o71>`@(cV<&}u3gGSOw)9J-Py;KEb1$spT_l!kltfRCGFZFJ*NOA7|+7 z3*xejJ$mY4imuv$YZr?tqrvnq22Ll>U~+yz@uLc;V0;>b5@bf@Ra8|O{jH!jbev(nF1uW?cio@GgDC#MOny|^`2|ns*1wgmHh@Bs}CWI@a>GC*tbU z)a8pPN%Op=DrwO!KufEt^T*CXr(~S;m=FhlZuW)IUgZo}UeMA?e@c;AwCJN`H|Ov% z)G)yub!pw?A^1v3j3HXpF1Op!Yp5E4Fjgkiic+rD4JCEL%AumcgFjZpx(LN`?KhxG zgZ^Y3iv5jrlfi9~1!m1@SFdge$Lm6KEo9mQ1*XF)d2s3z&2qO)4S+)#JaP((WfAxU z2TY#lU=YhpHg`LMFjVm#D1>juEJ?84jUi}p_o{N|o2u}yM{0uL<+`|L1>og)Q@%xu zUIt+N%%#@aXJDz(h3luc-cgH$jw;K)d>&K&`ijlC(YGx|AMKwNEN%Xvp{_ULl9zZ{ z!=9(K@{UrQB!<=r$RnI*nOdJZb&kXG&XhDd)Kw1iEmJ;w^LKojyFrX2&z-SjY;9ew zv~5cn--mmeL3|$)sr6wBnM}U=m3x#8=iv@`ee?ft^(Np@_U-%lJ;P9lBuix}71^b- zm8H^3JhJao63Ln+yHOD;DrL)-vJ2UF6BSaH?8Y(`#!mKi=6Btm=llKte*fcm-{U=w z=RKa9`@TP)YdNp;I#2e3-zUG1>6C#E4XGY@+dEbB^%kKwdtS2Ta#j0lXQO6(^$f)M zkB1>eh9xQx;u#9|Ax|uE(%Qe+2huogAyz)PB$rx58096lt^aUz-*T{Srq@(ag1>o$ z_nSoeZBP^Z`M<%ZMruc9Hqte18UTfvl^QBeD1kX5=FKf-{&d>2TG`f!3nVI|5(HMk zkvMpA z-$JO6Fsh&!D3OictL^U*bps~+s5K4dpwYNDgt{9*#v9)#vFm*R1_bZ@a}09%QBpr? z1cDD6P=~J2Dq$IqKCcT3nJa$KFF-&17`?fvk609U52T%P;LU|Zk@vIEzOfLIcaTWB zmPvi~K!oy-!=W4>QA`O^cS`9R)3sA~7t89Cd%Q(oz;M#37LP;{g`qqfuZ-X%{@rc?q`KyL<7*=?uTJhh zT>e7_E&JpkufpH=8MfTRfgP7B7ND~ygkHSqoVGSQP=JGAu-@XX04qvFP!9Ro0t=t_ z$&;GsG1OwV(HTX;76Ol=hdb_E5TgKnr1(xpGgsj~!NPk~A2NK(c|1XAxuc?&rg=}m z!g!*ZR|lK5H$s$P6?U}zQI|;gnU}QXa<@9OaE*F?W}iiNC$I$k@bG|6HKC3P|E=DU zdF-`VKx0IFi2yqq4OZR4j{|AiH z;y^ty`sAHGlI~^s-Vn&Ojf{3qMrl8(_T32jIH9JdOWf2&(i+T5_4F_nJ~#YfUGmFE zZ1nG1k;00<7s z0nYWt^`cpEDaK|+X2WV;*x914X(8ew%wDqt_r?wZVnT zpr8_UNkxYs21ZX|8=HB0$^NhYXe&&~JUWg!HtG7ud&iK_Fy5JPz% zfe6-S_^Fhe#{)4=;ON;xtv&|B#`zNhmd`bIq(OmQ?BM3df+ncf8*f9I$Uo!)RA@%j zGR^v^j=GWEJWF#Apb z;TU?oKQEowPyeFDrFDUZ{Z&F}?kJXkV??cwEtUw`RC3#?^Y2*&-?*49-*Wog^6X2J z9LielsbwlbP!UB;_)=Qm4kke2|9M64HO;a)^;%5q@YT&J5CbLE&O;9+naZ&85jx$B5qVg74|fYLAE zP=G{I6~|7eUTnE^#^8M~rD|x_;#WcIYU%frB1clC(Nx*L1r(YggR!YMS@EyA9iR@% z!=2Rr^khD;{0RijE zg+TDc?Jw;s2`ThvDBa><=Ty8V1z|DxcO6{E4*yJPBoZ!XD06$J?7Jfe5Vn1LzI&*|p`t04W1HAYR%{Uwql)P3_B5JT4O zq`G6D>!EqiW)?#DnLRx6yLl9@PkW6SW9<5hKQocZF-|PEm~Cd&&MBu!KS0Bvm&&lL zL>M15W}3A-2p7Wn`l%toOmCbqbAYfvLl+vNW$lf-rt?2JUag(%JqlpLLHJ~Z^?=vF zMlLlsg%b~bJxk^(o99~#pBU?!rpAID@=TYBAw9G8GS>^F>W= z`vxB2wJ4u@4A6jLTL#uJYT*DJyrAQlIar(xP?s#D2N7dvlK$`-1~50Fpc>Xu3$y44yOg_O!eFWyNvsriuL zyo+$x_A@o1oaK2efMSo(>Y!?&LdrN_?T6QMKi6J1_|>k-I>`6Cx_~;}2GiN;qVCi> z3kcNu`a!7G8aNI}q9nL?^1M>i3KUXrVW6)P??`hfX^|5_xCZ3lBXHGowLWBgT*9wuh?$BXBKQxUAy>>2 z=-6}%l;5-ccL=vp4>O(@v6AMMJYW%U?QsoEM!$f0!c){QYC`X@;B}C}Ul^j6)Eq}- zV?b&nEr!K46LBwp{_HLaCxtS%J^z#+w{j)$U=GOB4o1Pi<;sS4+tAyAKjO^M3LJ)| zyX8lDk}fd2O$rt8`w1L4nPxfig&X~0uDb}=R?lRl&sG0sBDZU8Nj+Y?c@D9wg{mec z`CKAm_-|TBOpQ|Qg=J-yg9_G;f-i`$p7d!hD){D|k#CzNjy=0)yq+5i!mdXi&UF#K zxAP$mgj?~&meIS5y()~yThqMoWGO>ro#z+`&6gj@eqrRLrtgQp@|6nm9`o z2;R#YRH`cgnS&WUU8x$!-|5LWwjDLSiD)QhWHM3JFTs@+6l8}YM(o6%7obIy1p0UE zIlJI$@YYBq?L#g-;UwzXluA_0woG(j))yPAC4%?eNp`^S!6;Y@H&?ZS74XTMq)gb7 zHx~jrvpTcijCrMd*tJeQs2Z%QGh-7j*GJyWd0uDl*Vj8*qkHym^7@lw<|=Fe+9>W! z#<|YOHgDe>8?T+O>|yy4AwX#dowT6#n9_J~aKkYu0HKq!K+orHKHX=N)?JrRh#(;TGC8<{um~D@Wx>j!j`cK)>OEF6@D(ps%0k(EPYs}BrS4aVd=7UM{4(cH zOn7I_nuoMa#&nCCpmTG8ekSY+^ z3E>3*_WSVi;0-7%+E>6)8Aw+ih2+D|?)i57=s))8QtkQ>YV7{#?m0EJBlQlghfat) z?Z0JFGw9drJtI=1jAkorG}ARxl_r@u<(3-^MC}qnv3D-|?lx}647oku@Q#5San_6j zi#LNGG#ALEw;>o`U8qVOcNNFuqyx|1_Wz)c%bT(UsL1^3PD0D+*)yn}HvmCEWwqJ? zZP3@e3i2LU@*z4b138(HV>Z(L7?Z~fMZnu%#Z#3k1tbf`HthNr?tt8CEOoKE z@M1Eo=-QZvFhX-ifO&cR5I`V#_u-&{@RB<`G*2=Mp-La2cuTUgbA};7A`cdT+ntn} z$^bSa`@!;A^Lv~E2e_uFpk~+U2G8KQMh@Vj0Mc%X9I0_^QHpe9n5i3TGh#9xoChh$xk&Hb%cB^A#%St52?LK>Y%0bkH4*x2g)aA3wu z{suC|2T=c|G#86vLaKDbRIXbll9Ty!(gU9T*Kr}F8kEy92$0Or0h#?H{u34){PqLa z{%Zgue=vH=J{T9BgSGy}{1YT~4tDm8QGjU7a84EOgA6B(FyfEVI%Q0De|JkhOT|z? zyRvlla=r@%8?M6I?-IW0qE|!+vqZz9zeYOR{LJdwLy`CALfQfj-ZA=~pgL7kGv@)l zQ@@Sr%eS6}3GdlySQGaPb}u=Gd{^QrRwp3RBp+OZnWa8v>ZD2@pUMzb;xn31L?n5T zC+!Ld1HpTC0F-$x665x$9nqxz*9N9BYtIX3_&6EIiRqH*jFiHW`WSMJlu7}X_B()Teh&QWGQV)(I?(^+h z#J7*JKi<$u7$eJ)k@YN ztqC9-@#yr3DdM<95_mH5EQ#)Bzwj-;GSGLg5+qJBQNnAng`pBkg4YiWZ}%rowDb*j zc-J4fX9AQ_8rH_eRro54{ua6L0b(klCoG~iOV}3f9~XI2s3N+AE&*l2CdM` z=4w(t!i5JeUM@fsf`aq4(MTz3)SQcD*M1)>#~8$llPo_raq5tfpRuZxg@a1cCnmBJ zjMPGz0VJawMOZ;DQMo-;VJJ5fz&ZOzoWxHqikdQryLBxk1S37d@wvb`U+kyp3m5#gT@*ymecIA_b{25+y5?Kfj;T(iA zGZ24Qe#d0r_3qVxNK11jD031s&neVs>?F8tJ)NL>=8L<1lAt4dw2k`&peN>q{df%x zclGLGEM4@5Ig~43AVfAu=T`4u+W%Z!%H>L`-9RjD`S;BvXUi&M)q1Gk(dY=-CvGQv znqz=~x(BdH);O3I z<;HvSOSw!pPNMZu%67BT3r@4?-Gp0k7wlo5m*mjg;sX6ymk2p{k{mjQw=x}4`N9Z2 ztLNJ9Fjg31r^nL4n>^ACJY0NxD!%J{P&;>uE*oLv?Oh~$gIiQrKem8L!rWDn3xYGm z%QxK+yAv`0`xkC^M;}bk3+(OeOWVs9`2{hAkx0bve=xi&h{vC=@MkiZsBXO5P&TmY zltkaz9TIvR4t+zSU0~ez0^nD)2N@MciVy6#jqvirDdTl|ewmemXo|i^426b&TCw5@ zm^>CUF@l?lKLqaH|9S7|yzs>x78~7B2Y`?aE8Hc(sv|f)-{3of%1R(zp~1)GO^T6S z2QF4|9r>ny)F^ZSf6-R;)D&DBtn~n+bk%QO;$B7>k~JDTAz=G>LywNe1Efb_Kt+oM zDsfE;GhB0NNH)R28kTm*CP+Aw!MB14+Z!Ljo~We>Vnq6Hy&dfPZhv8dqTnwubA&UQ z@COwLv9k|OkdM^-+jd&nC!`@ zldiNg8IX+c8SPbyFE&GCAXI2-YN^NZ(SjtfEOP=!2(V5D8DjO7+@?M3IQ$nTe9cy} zIrAR9V;Cn>DRBsx&cy9TCxR&h%Ah~VnL-gCkion|(M!)E?fbh9QJ^208Y`TJ|EWFb zqP%?{e+Fn{=D;l`5S`Ni&kB-Y$W!)^@BWma+K{*x%t2q(Zk2P2C7aW|Jaqkv(1GEL zKouE3^EWWe5LAOQ|=jH){Lq$Q&q48+g5CEl5J7L4}Mm)XvYPc zM(-25K^q7)M9yD1r#8$DJ{ul8_w=ioVdAuS84WVCz6=@g{(IU-JTf5Zjpf%V5T-}` zdLe(yR}k{dl^iJ|XLnAj?_U{WJ86SFJ-`SU%*G$LAxfql31Y4JgC6%Pev2M#Z0*5< zA6W@lxaw$V#?Wr?BD zN-Ml*MhCxCb`aR41Ir}gGq7BGO!mh6px|SS@WVfUguqtLhW9#jVyuz*?$4O-%Z>KE zBwk{mF2?RBH30%$!D;=84(h%gx!BV59r7#v!~Ucay4;$XO^<<^f8e9$ziVH^LTk(7 zK>9fnHM=gijUh6|Hb2lI!S*1anwX~iJV>Fxz}x!j;~EE8-Vgrtkns|1>LXCrMDhO`QCbn+R`ja4Z@(b~Hr z`*6gRlr_ihLrC#y{mdM{c{uFy3obg>e^XbdNda2Qm{iS9m*?hINOpc~baLAN{>;sz zQB&)3+mV@%haDD`<=DVdkp8*dUmwuRNltj&HVOM&zroAuGw2qvHswp-{Ji5Sufp}E z2{`pLltjP@ULFF-{w_|Mg0OO-eSHtsI4r7bOXwum^4u56Y}@*dL;Q-ECLMh zzi(EP^mCUS!YEKVX$@2gwfA&TXM;Kg9r7>k*$g&N_4VEIyf{FtLx8U=wzUB2?`)^U zuBh!z{_*C&pKBZm!8R+CP%psPtiV`0qe!k7*s3yrb&Eksp;S!~CLe%oUvaOG_MX8k z_t43&+km3TuxVQP&obQNYXhP1*ILRkyzaJC2$jMH9DBDd+m zm3{#~M6ya36d}HFwch%llpj~THks2zjX^Q^%Z$*L0g)H?JexY*`j!ruowKX(wMtG8 z`p=Y6k|6@X?ME*g$l<*HAjbZ}KxTTcg2&Cs(rwsZLQH`&0KX+Gmfr{MRUyf4Ro&Kw zNASFHP4S5dVycbNNMyAe*#CWAfzjz@!|~gb`sAsC01L_9!o#rCvtTMd*78Y91*3K5 zh3^}kku)V`6sk!Tysr1k^WlYXS6RGVl^1!J97>0@!S+**IpxC4p-}?m`Ck6G9C@ zj=|zs<3`)hzvcO|5V9 zPXk&8iRA4b^oDAqWh3;)Qt%Aw>gw&ZV!P%E*a&__T>+DJ)2Ln`@+{W)kKT$^dyk2U zmn6~Jp{VmdoAOvN_!29zx(l1d}@si*hR$%57+mIT{sWD0-Ba?Vey?74{qY5 z(Vnf%DzNH%<`7VJhkd`pWakBS1-7`%qRMXnh+V7^(=~6~&F*=``?}wtr!Av416#90 ziV;ZhyBjS&40R@_yiPxmE0Of%$rhWaB92JgNUX7%yf}K|D;f)7sP}|>QZJAJIec+= zC{3AG+1JfJ-v4}7S;}mmuFL-2ESXrIR$-*&Xu-7g%)&!f7WbJ~-j!zPAuRn)*elOK zoXOQGk#y?N{#99R3q`5BE0aFjg#DLTfdk!L>s+HP1(9>t?jtp)%(2IHT;&6aJ&E&`3T=QK%TW-^&C<*oEkC&-q0L*{EXX_y1 zr;|RMMyurpUP~?sEUPk4&t0h`PnRSM6+EdpsY|2T?EXlN?{}V}+&@cCPAfi2(gyNf z2b*hVG61ZZFrkojTrQFH>-9CdT4FDl-I6vyxhO>F5;IKioZ`pB5vSO}}T8CnK-3)YXPVq9W!& z6>gy~%YZZ#WgVsd($yBj=Zf%_q@ui$(&xR(v{@Qq--(yB;_Tu6oQI5z1?J`Rpd#M- z?k*H~1&#EYH}sL&oUxJe4 z2Gni;{aV<7m!Hb3`>Em&N_$28pw{m{RZMdD7g>xlbKiF{j5p?#^&Bi$JAy>E|_8LR!&QHAckMKMO_sh zFkO;~Csn8Cg$HNf$Z{ zpc6Yf!r~uPajT=<{+^(q=wy*)6jbiDr>fQk5pmo{9G|?5DmyYT)`wMe zz~liSsQD1DR<_A+39!?%1D)AVc0TBFe0($$a7>uJFOU0WRau2c{dhwfN`v#_Kzeiq z%B}s`2EAD0k^Ey`iuP&$SH())eetI!C7$u%zJ5TzWM@r@uuy**1y0lI%%CU$Q%H?? zMb7p#t$NUKXkWn)!51~)jbpV!$I4l?Tf*NQKc6;}ek0uzKfY4KXzndxWK>|uDD5Nf z)N9q2qXWGq5CWJzS@GtE5zV^1mdR9^YtfbZ$mBuzz2$n|sSQ(atiUpFfYQV-)%5Kp zZ3IRE$AyXrT^ZLSIf;;=@UPJ(>c3*1r}lCmp!$Cy>EG-~*XB8XliqfocO1MqrJaAP zEl%~G7+6=}To&3BvREV0R0|M)nDd{nZ=nJBRkc%4kP+T+eF|=|>jRPG*j?>Ad>I;> zxo+X3!H7KP@PsU59_xZd=4Z6c7K2fK%aFZX zlJ>jJm5*4%r~kg(5@te$TLkUE2_%fW875|5@0ffWsL$ee0Co!+0(DNn zRw{r@V=z1gH;U(gHU;elXu3d7g=*_GNJ9oZku2XK9PfI4$6XDzBVm|4f0xl=f%lo| zi1G%@SiA718}>mAogp-%CHAGMU!P8tX`qMspO3y?J7WMORyqKqwXrrjn^q#t>k)+O zD}h~D<5aBt)WIzCs^JbUF@vsZsR^WK=Kfof>`vjFZ0mhX>o(~`BuL^T*^5(`ceaz%{}G( zKU{z^2-FVTZ(qNzcyLz-dZXXxz9d!HHRzhN#(4?>=G2%7pW1A{=9xBHxqL?Eyvo>D z1wsUq1QMBnu)0XL11Z{{xq^wD4!exL=1fI6*SESz_XlQEf2F*Q8R8f2ClXIEPL=e| zGm~yH5VUUu%b+|Wc+)qCyBXNEZv@{{{XG7F_#WM8-q_I3-r=ZpkMk#RNpzbJadV-; zH@!#M>U^q+;{YcWODwi08d)Eu2|R)-fI}0R=w@6V67cwin{B#@bJ|0PKh?A(=JwsO zN1C>!Z2O!%e@9ODVQaoi1BLX$k-s zUZeSdyCG`V&7K1=w-=nm)4OCom~anzt?HRO_z(U5vi&MeRGV0DXO`|>f<7@eNtAGZ z>M~WrH7hK6H8dHwc%H4Z+MXm!j=xVBqIS{NhbMYn3`!ouFj!?1W7D@+e#36f3MP~k z(n6b?zfi$+Qz3zMA$pVxxddVCK7Yo4ADm%wx_C(!5kJwAqWMX74bGD2$?dwMoo9~E z9p7K-Tsj(i*XhTpZon+J#GnQgSQ2Gt7Xg+1Gd8V??QALY)b=O6O&fN#$wHpz>aSp1RRI%G!r&#w)%Bv-e{nA|ZBF z;!U+6w*iW#EGTILX$1vM*Xce^kp0@RM`$T@>jLi(N6eLO$gyxQZ`qu3vz4Fx^I8Yl zY}eZUIt&-9fbn#E^-jrPi^}Zg84mbdL0zX#HP`&1Zrv~XJW$2~3ZF^u={@Go&Q4xF z0_WblLodi2q%2D)p7C_6_iO0*eLF~ZGiwzH1>^FJdF`(_*IvCoN^61M8wO$rO1N5C z2+Rh%KiL9Wwa@Q`s0`oD?OFs*(@XIhAS+@Kpi=-}i{oz}{oTc}wo>qNlm=CT$`v`A zRs?|PTKkfLAP|^%RBR6VHXdM6DeXG;kGMtknORFvLepa5Kf_~S=Ega3buj=m9ru6` z>WJq6I6xAB8E{2Ks$oTK_`)kXLBU)ld*ge4U&8nvS_tIEVacz>A|#UE*$BRc&%*gI z(Y-19RMVQLb1uRVM@Qxq%cq>bw(mIBgN!K{B?&EzL4S(Pg$=bK7L91+d%_35cs2Ah ze_!itj<29jFUS0K87y|o>i_fRgH6fB!n@YF>gF&R+=kLHQ0)?|eadk?>lYWsl(q!0r46 zjLr)nn!+cL_E5fBSjJ-akUQ5=MV=G)-qX67UbgcRRb4q{fP&5nfT7L~Sp7`=({0h> zztN)7^cbU-ugkKT-uF0D-U0Vxl9%|w_-MuLN~)q0ZL87$u|%cjR|UmKr17|LL2sP0~c3!>FDS@L>aSnE%>lTCuwp)Ez7n-@0Tij1#=(oQ$}|8?b<9T+S3s{_^D>7Cyzj zP^f8P;y{4lK>1RI%;!xGXj+P#M^d_x>BcI46tik>^w z)(vy-XWdt2goOaD(?^<`+s9lF&A9&h@#G#;tR}F>R%;)^?9Yt|7r4=GLk5$V=)%-H zd!hgsv=P9d-utS&h|s)M!Vy2ny=HwCCryXHezXDc_|8MlNF%WF%@4s<2ZZ}v!R&C~ z0hwDnP_tBo2qf93K=f5olFMrZ4a&!;4~$U>D)n0mVr2ympcHftG|8O6<%}F{8Fr<` zv%;=d<_v6<0#Wevt6UODCIkc7A=N(zw(&tYjt;feF$xFqPUW1k(fz!jDJMVvKH{IX zCeGhbX*>a;_Ny(kq>q-D;yiwbP={3cwX1{$+0C`SiHUBu+-*YS4bK)6x&XMBLtlem z{kOXfP3SuaJ$qkIFKD)sj@Oyq>30ZGq6D$BvW?7onFt9xBO8${gvt)olW2X7C^HE9RJ`cLV2C4D4=qiKG&{ zkY$%!K-ufSIK_z(F3`FZtEA>z98^Ts1Cbc3av&B29%?}3i&!eQG7_2aehe^Ei9!Xp zOyOGc$lCG14yg3qE^(Ad$aB(WH$a|`L96RhmDf*OTU$7#Qnv=&Vb}ZcFPWeBYIh2g zfzN-9Rte@-DBd+*4jspRlwh(>ft&FMjD1~v2f>Fbe0^U^aD=c{mr!~*Jg-N{Jyv|% zr|5JOmU8F289Xq;Piw{EflVUk@XGrPFyjr%aYPXgA!Nuu*RRYEz9YXhagCZR2%RZB zaEL7{ejrmx=K(n1^S0|U5<5GIQoE7`!P=`!0tqX}x%P_^P5^_ur6z>(;1>G)eS6L% z!rZHCd_nCt^I@de`@c|Ui6uj;kqk9aDJW!XZ#K2%B`0G+4V($}#3{7v-2>t6BCOT_ z4Ch>P1k!!TloF_d?E?q5D>T@Ezr+iz;klNrKLWJqr3GlI^m2?pD16ZB3uEshvcg!`e*yEguB2eqUyu0K$YIy=BAdfhtI4XBdgJ21lpTkV~vwbHnHY%=d$Lu{;xV$kL z9;C@-y<&ZzxRxGr={RFv_mb?#iSxxUHkTg1`bAanvX6|pf>aA*{4%~YB46w($ zwdFREzDo-LH`y5bWBY8(Ry!Z#RYb(HcJgmmzm9w%C~ z+}PEaZJOq}df;v_oqq+3G3Xel5(=&F=BSYT4tu?C@s~j1w)uJsn69|!;}#$a5dd}W zU-1GFD;|=}^;dA~-a#&^ZJ7nI6dKW=O~<69>H#fEi3Hr7OVTtLTq53;m+yykT?c(@ zSZW5<`lYLfmYM?(vXKT`OUXc+d|Z0_N2L-Q8R(Z#^Ekh~**cK_l2m#*Sg_z4oLBDw zn!+w56Bgzm>v--W3>4o`sW0R^J*MtRiWH4>Gyjmu?pjM$B-KUCfbbn0f^{t@dz(JZS6fc@D4l8R*Je;q7) z*GeNZtg_fNurEbn(zIGw{W17jdVG&G^e)eC$7_5A*|S~$_6v$Oza948kzM{6fZ+WgP2PTHx7Z8y?tntO$092F74aNQpl?Kpov7i5&CWCN6wLGSyg@XyUL-|hm zO(&>g`V-&5ODB3tS8DPVy$;bvr+ZV!z+XvQ4~dG*G|3TlPvkbss(q**44Ekd@f&`z zSuzBEr<3g5;ET&pX~yjWN0x58c07smy24fULBYxu^bUVYwAtIdJU!Um$fg5oT6;>E$gqUrH}ZP3MBO~BU23XW zhZAnV?PmIFs`0>l@YMFAtjsPta`14_P=qfUnVzc7rnpqIt--GJ!y|jAK z3#1Z;my;QjgoHaTNR|!8{yI8na9m-}NOHkB87|yQeab&g3o$4MZce!9DmdaLv(C;ro}zqi#vnY~EWRLX9CTdnmU@zP()E_+dq9n9KZkID^h!OYss_3no8J7RVW1S$@A2mu&lwNt z1n7bnw?IAqD}bY6pvT$1e9D#T%aP*2H>S;wG|{`fk)ylzX5If$+jn1w4dTKCA^ zEuI{L>7Bf}C}AHGkyFb`uqwV2{~&BHT)$#MvrvVv{h&A(V(lZW7psADatN$Mv9GOK zeCt&6I6zRv;zbfk0mEw^%_*n$iKZhSL%14-oh>YI-7wG=EV2FefcqeZqQ}sIGTc`9?0u+lY)o4l?0<-{;A~%QRNNCnq5HcZ4PftXLj0q8;Og(NcfFr$y7c?G}a^^6v#%C7p-1=BM^Doa^4Rk4df!upS%FfVkx#fM)YJ4Fwr|m@if) znBtsfih->dH*>9g)w> zligAF>lYw4@9DRXYVLa0ac?vAXr(eXJGcaTB6{?eaZMC9Z*wh1r3d( zO@ak6dl2u8P?m=c^@>lC{7k0OF+u$29V_)-_L%s6NYf+s8X5`?{thqEIVO=r+Zfs` zk+Zk0sq*}Qj9yT{UF($Piee&%GEwx)GZ~ARZ?FRI&+ePUhDq@eS}ss)s-@Uoy&40< z>uDe%SU)KTb}MU=KW%t3Q^dd&b7nn#t6U+z!V_K9Sv%OPvt=dHYZc7@?g90|&vb2~ z02SD%_Xjb4o9wGp?=q%;ep>LLB_gmhL`CdmZ?lU1nUc!JpZq zooS?!#l-FsRRG=GxD|boLkwyKl$}WV@g{1i#LdgsY>0zXHkVEbhCp2}BsszGN|1|+ zwH-ycd7}a2tvk(jUK~A zEd;sH$zl*Ux-4;c|8?%pU*j?oaG+3xRU$_F6vhAI#>gKWT_^3US{**KL)f5-Jr> zLBeis+&|6#NQu#j7gm^oNEv66Qhcc-ptI<1RieS_F2ZzXH|&ryLV5JCM+$oEHAg51 zHz>itcZWqinG~%27}OQ&@1T9m%T@oyEQ4s;w`?O7ubE_!1O=Dd>qB6@^2|=@9^GdE z7u1z#(0MzVCK&K3x~ks!ntsmHQ-Mp$TzqpAB2`gZ%# zJe5S)DzJv#XVHh#QfBwhhQ*fT79E8hq`bE!l$d`orbaticz5*s*KAoD7Z=vFjJr%N z_WnXoG6n7tY{C3C#)u!Vo8$-Ya8}T|BPwqomv}K}Xgs*fu?bfYZwF&0K;xfS9%*A3>)*?rNom5%mi+zSV8ok;op`8mhr;u z%s^l{a%ll5O@WCOU~4aKTzG8D1^VpQRZ&2je#olWuuzU#VH>FkxVD}RDC{$jIq_Ft z@P+EacikftWsX4(&f;TY1S^IiH@-sleZ!p+ghg1duTg0QX^q4Sj2s}KaV^%vJ0XXp z`E8*^nDNA=XZQU2LxlT=C;+}JQh^h(F+&G4=dnJ{(hUb+O8b!$z>AU1#W=w}yESzv z_gp5TO!FbXeM|rhA9{D{>Lqe9$$enfigYzzEZDBjoTLgnc#3f9D_jhroP6TNikAZZ zP8@*sypKV4V*W1&^a%e}!p6SBD=1FX`iCFj%u29BsBJ0|X9ng|U2PyUiXVdvZ(Y9l zkv%(MH>qiIV!bO(OQ0WyI^&7L8qv?qrQ`(sR&R8*fRgw*i2bi}NF7gis)M~)IB;gQ z#>)QGhqtVk0qgx+msmT9>Ln~Kz+^n&=Hmh}^lhOR{zeI*OG51$dl~Z6o+z?#PTLjv zGm%vwZ~#bv-H2hgJtKhBD&&{ypZPaPLs);R3v~l9x*;dJxj*3*ehIKFP{R*6^hY;X zSF$Bva#bidKq{(IC(cg$97-6n>JxdTK=7yT<54PKp1wbTES)J-HVKg_=fL5lHTeQ_wpj%ik_W_L4RB04 z_R0_VCHa2Jli3CEzF;>wq{dpqP{y|7*cs>=a}F&4_$@7(=6ZFhJY|^53UQLYzW&V| z1PZABRRn8P2C$cV1KNPK-moFGP*n0zar25RDE#!h!-*hvSk3hVL21Hi=! zpkov@D}j5q17eNGIt9wv-+pO3+5MdX4SNSFSX&EV^u&4j%`|ZIIKdkf{vfCw+QwI~$NV6*KRV$%NIcMo8XC(luU$Yxz@!2Zs zcR{OgvK`P4(F$14upk%V$!VeQ|@TF4Bd zF5fm18!Y>&D9{P+?Z9R+_(O86`Qqre@FsY0L{hHb>AXH}0t)z-om`6D^CL~pS2V-F zWdV;CY>AwF;&oT!*QMmn{Gfmc<@fb9RPaA7(a&~c)n}3#?!Q_0_Y@S7rz*h@E$8k1 zR4}{mSm#5*bkx_u*MVm?q(Mv{+2EictD$03QuF|ol!iWu@E5D7iE0ll)%aq-B-M3= zGah6Jz+AkT0KF`}^Ys;AzPN$dMsRf2f75W@L2$8H066%gWr5=xX^i}`A-?hDT-TFI=1iRH=)$zJ3QBx! zVE%w52QqVyZaD(e1on8N!PTL}*RGld3Faxtmfi%E0#(r9hgdTOpe}n2={*d7$f<7} zzLncIJU>(lTNi)9w=vBzD~~_~AH%tZ15lPImTZ zk+ir6V7NjLp-z3s+}u3u?fJ*Q!6)Z})mP5n&|A&)MXo_dtVW}5eMA|9qi-C)f~i=3 zroE1+s3^>K1^#3gG}nSVS9tuscS7hX2bY&eqnfOLl-NDL0M@e|&;~A0kY-+dlht+R zF^k)0q>XK*Ni!?sMKE=!5S0=%vctq*OJl-!VnEO%0<6>qi>IhUGAI+dSLS1VN&`Rh zd^{acYWni07$ZSz@LFeFYEx8}QP_@(=~FKns2k9Y-H^$^%7@CfmgOq=`B3X6Od_Gj zUS}3Xn)@T;tA}5ER$8G_JA#GlnhxOU`G~(8#(}@;W641W98mu5aquiywAWHv+MD1x zy3cj26$8NJSBU=~fm4u8c^w&f6V*BS?RLbR2u>(Z!Ai#RS8X5|+MagD&yhdz0JyK{ zKD7gA6cFO38ukT%ubS^1L`J5XW+2Zw19JNZ5TT2(7>%M1C-3~EN1Is~?ZHRXojipk z0Y<^2>?0qhIB{%xkmH3os8ZA~GU0_axx<8T#0X)~6vD7KSCdU9R&4IS$b~#k=B08p z{&Q-s4wkRXTSR!Z`Qo^~@e&>M3P(noNq6svAce znlCT-9R%c3cpYJ1xE1&kU8OK};bVui#5J$gOwi+8mx$Uhd;RJa{&O%pwCi%MA57#(^_{sE0%+$4BH7PStFTvYlK>{d z@_Z2Z46@nx6@K(Jg$oM<#}!L3B(mwwiEqtE0dJ5*Nb+8pIrquW+4*>w(y}3J1<^jC zbFcGkO1i7Qx0vS9TZeAYfEYXFh1>pH2HKeHd%M4kCwDwEn>?ZOo~^#lw-B0HZWI#S%e$J-Pyk)7s73{Z1jC`PMV|o`h=G97 z`u++BFH9-rA;W9my#HmEIPdw|FxOlOosN`(|HWUJWo+jGz~?Xsx=;j4CQc299w%L% z*Qfz#7DS9HKtUsc@;&Au%n0$|fZ0>&c>?{jq2M@a-?!I$wn~mwWz)%ulYACNT)D~F z=rjIm;@f))rduja#wD5qUTU8t;2W}9WmWe_UOIA~f-WFeNJ*=AY(q!`>1pSTi4tl9(@PUE{%lhj+ob0T!r| zw#%YM(N=Ytt*r@znp)7;&Pq3U7nz(a$P3nX@|$yYuca!0sW8@Gb^^6S^Xb)m;G?C6 zE**s50dS1Y3WS5E>if&Ia|2W|hAa)yCCLa;h>}01J@EIC??9jV))XI}2vatgWQBp> zJN!y9IJH9bM2AEWar>JW^fInm7aSX?ShBo6a+>);K56099r1BBkI0qZg#-80@#oMFB)GSWzUV~EK%L9(05F7^D@#enh=mE=2MgL=(^h^H3uV2C-13Q|4I#83VTOeUih_p_%^{Zt1MVC{i0B$0ZM4Dw|Bh5^5i8l z{`-TTV5He!2*JRoOGNF*k$c+jbmoq6ps*oq2}&PSG2~}x`*sUTDDx5}2IBkBW*1}< zegd46cE31?FTvk2Qz_V0=ubp+76EUPNLsqRQWheEEU&K>p0;k<1)FQ2iWcBL-5<5D zv*;1YIvkUC=7nto>;+wWGb}6Ee$zzni%%#kx|iDHa|4Et=uQ&wwIeUqeL~eUCNE@! zp4}T`HMTeT_MWw^@xA6vEZDCZSe^z4vlQkwM1IM;aATv_{&7AXRix5TSkIM}pum_{ zV&!FI{v6bnA5Qv#VK1Lai~RY@SXm%SqV<0m@HG?YNWPyAb#}?=P?{S>TO4a}k>VIl z`9m}pH^5dDqAHVWrB$aE1YI<`(A8-YW!ajcm-TqEMA8K@LN7KpI2g2(gam&+>W-Mt z6C(_HGOqr;M9a;Hh33MsdMB^%$-H`g;;bJd_c!_35(VgvX+|xq zXI6H2F6IP+CdG+q}h7wgz-a2vDNynM#GR0<$___iR`p{o^ zbF_N7sGDG3_0nPoR5#?|hyd%vYlFfC)3H!hO;+mySjH(fKjd%|nc{K>l}K*xtX;xZ zSUe{{ra+Y0m?bii`*eL0;yik-OQ#psmr=Po`6XR^U!hqEDZXIjE+$^R1SM@vGzQ%O znZIhg7cEa_z+z#;GB^IxWvP5p<;1oolc1mxdXP{4T1xJi>`#uVWbx275YD>g_Uk?? zx$WJ;kY9_^U|0P!Alh7rdRLAuy}%6n?Nv(M!$5&V-zBUO3g0@@HDy0QTPUd3yKy(((q$BHPO$ijZf9NmX1|Hz| zR*1+~MP`opu9&&2cl!Vg#S8aS6a0J=-^6rb%e4f^ATcL&?Sc0$pvO_b+-R7_yuH<3 znN9&ll+YzUq{4ospZfj(ccACIwD()#oDR_w&+6q4n-42|cmtv=2hTAdmM4K`!$1p>gCgnDBIjBoG~Be zbNx6Ntq&fV04`7I=iS=bnh~)+@&*WZnm~Snq^{I!neyGQ`xQJ$;-wg_*8k_%U6X1A z(ndIhFTT?+xfA>{nJPiuxa9=pGsrx;KiFUSosZ}5ez^WZ6S^4j6aUO~E{+q$a*t%~ zg+0^KxpNyW!BL2OHdiYeb#maQA8-7y#CSMem>4<+4N2KE65H1=B`cCS2O+N{j9CiZtv_=K7;}rC2a*{Ri|9r zaseegq=)z~8_6tQ(>wc&=LO57$E-hS9x(w89YfcO(Q-oMDik`kWgXSuL~dnfzY?&? z%w~~8+?mf$DHoibQh%60=P`bLh4R^r6<;y^5Ac38#zapyNP(HufM|(NO`P(iA|p}c zY_?@9B*_PYQWz(zl&vUV7GFV; zFk6x9&iwrnKSn>ddHYcy`#{;mB${>gdegm3kL>j4D#ee?)_yO>_>3Le*nlCHd11qr z0t|{O;y1u0t~=x1@~UJ(RaQD8DN#ftK?7muh46m1Rs@jvZnW54+Sc^!30Me%`5`wv zF)L_xM85GfH7)+`sem3Kede*{>1lzATOkYOJ-^(J0yP;#Fd$&42oL*>VwPP#-Z4h( zjMfAwCl9_q4@_(^g7-?Kzh*0D&U<#GW-E|;ekcb<#TC=7lh%RU6YtM~PuJIH%i$U6 z&xhPEC_fgZyI6tTY~ms>lcp27)sj-yT@u#3jjI%UC0n0`VDd;;O*`Lag>Vw>K4m2g{B4?X;jBlX?pqy+8i=Zs zIv9NjE?LMUUrr$12@1aaw4KS}YZ~ZZlnahfUtEcDY!!!?(*L9~3DyEd5lK-j_yo=< zX#NVd(8N3%2rT=qYCEw4`(L+Smg*u|n`egogj!StcusuX@`UsqvvIcVlXAN#K|+11 z$q{yrYLvb);bEA7*%BjMv!Ss>??b#5(&qN;KMlk$%qQ4QS4bV>N7800HXK$)47pl1 zuI<*xNfS|(j1IIrf}_Cg0|WpTWU_n1yIM4P_V7?rL?h_z(g~a`zOmV4G2epoX;xSh z5Ev#Vw!7p14^{6SPv!sqf#3Hzj+qfknT1GMl`WyD%t9o)A!YA94jQB=k{MEw5kmGj zNRrvG*O5Ywz31_}PVdk6_xSz(=%4bbNS%xYL%^VKt=fK*0=k@I)0IZOlqN-D527xLGD zh&Z*T<{)3@zYgscN-4Xmlzs<&S>ZIK@WI-J>!+nL)XuBu{P(x*q#F+hIR1a9_ZWW1 zVo!ucCpBekTP9-u2XPTHbVDNU?N#k)=&6vFv}JehRBcY>lE&}`aj(xfEh(S*60DqQ z4VOum@eYJ?ZB}5iXHnF{sf=qkS(|7G7fcx+TEIg>h6+;$P_0Kv7 z2^~CI4;UL)8NsXOSQ|Q#N+aXMWMlq|A7(fGUVqzgLK8+X9Hn;OWXQou5hylG{m}o; zsx4}M2dY`>CmwfDo?AF)me8c~NJXaj69U&XN?in;8~3eZgR%!$9*HM`@AzH%J47Z6 zs05eXPLPpaVtX%5upK(6dmc7IX46vyK5No2rhm4~Mib#4_x=19V|kpYGI%`(3?8Elg}ymY_knUkBuOD{mQ5x@U@dI$3QY=EE8OR9`!fB&`jS2>T689BLxlUO|{$Ilyt?g*Xm4S@K}-Gw4h& zVf0?VzR|Pr6{g?7SeFFIvo+A*OH;|~a?;L-JTP73%ZRr8pEliwHw}z^g$h0)tA?VO;PTj_q~5)^eOxC#IwD`%F*k( zanP*zd2kLEaS1|~aH1O$6It(wnqSM>#J@b--=Mg7(XvWSZtn09T*F zFV=Si0SJG70@8QHP}(>eS@F;NchLheGsM{s+3p?ymGm_f#N%?~!lD(E>D#5sTegpoq0V|86d~n}Ko<%C{xP4c3koJ2fnr<4hjL$8(MR{(^V%-(o7;o8i_l`Y16RVsLrPWcvgH}kE2;iB zf>IwLa*%)xG&MhgSlOYHdIoygHcf>Mx_%1QvadBMW4s1Y(QB+LoLw1^Y6%1ER{!5$ zZ}xn=gt1*vU-fy^2m@-4vHAgS-hsb=SPyFdgu$|eLCE;<-U~ud$*eR5WVr0x#tC>C z4NQ0gRTUk^0{`;$rEMy?fKB9*60X=bcH3unCz$yRvf6uYh6E|x3kpRVd8gMsfCLL# zW~-CFLqDD;Q3%cnbW5p7UC*7|u()EGEEPULwt(@zfQI-dgwmI8W1GhYzB~i_=`AcZ z612%Szr945DW$Zbi<%u+F|lUI#u#Tnxchf_7Jj~<1QIOqkY!K!UAVySk($;1?I^`j zs);}G&_Wo7^cLb3=Zb4B|B0P38dsRsuNcaA>@s-gP=f99cpKqJoZz`)G1E_}6S4=& zrcXk}Yt_aHKDgl7p{`oT@wsMzy)ZuA=md?kF&IKS1g0ZLb-^ApkCCCgvi|vJ|LW48@f6ZY91x$yk*`WKsLOJv~YU?1?M?nIpJ!X&vVt%AEk6xI~+F>oG9+m zfay;^7MfdpU|8z^8yNY8f5SGaKnW_N_ut2E)GyN$VUis*DfUNIuHX3Ia|QpkNkNBw zn#h5bBe4((D@Q~?h~oKxDJ%J^Ni3iEP19L*#q77HAb!7??Fc!?vQPP;SX$9v7zG}`&~Iw~)udqjpxk77=rj~QF1t3wQMT>6w!w;ih-fN2 zxl0=V<1v&{d;3YE$3nw@7uyIi%Vd(gj_J&|EYvZcXa`F?;Xa3g1hCVURh!vMJD#KW z;JNw$28~Ea{M5j8p#`Qm0MXkeT%NFaL$xI0W6rwIwhNfGU{bWv!OIE(pZAODuPG$B zJ3&Vku^+xlE^sN1E4py#TDM70 zg`JD48OuH|b?d!xA?fM%^+;hW($G3M!ne^_zNXur=oTIGd*?KBl&+&|v|mhe@>1YZ zfMrF-x|)0-ZAAO2C|iV$N|nXsEJjk5<=*w#ikwk37-fg|S%RSix1EGf`4m6PX#b>U zHEWh;Abg1y`m|t5(T7uwQW{z)k5u!L9$i@s)|l65zVQtfHlS4po!OekRxL-@{5axR z7jcnBPZ1yU6l3ymVXSM@#t_CPW$0jG3PZd!!{iSdfMC@e58hEbAI^J=A2+XUdGWVY z(fQEUsU9AJh6egljmBAgV&%iJu}V2^Leule#$%S&>~Ju zj|j2!Z@1Z4yc5|*l}ifi;cGEl%ZB!XmUz|6Bj;JDp6Rfj6ceBgxyS_2xyt{STHqs- z1hkw{IJ3EVK0?BGH{;S;;KQS#L4|CIX?QjXTI-wj!x>NH^<=Uz&fHm@+H!bxX?(=S z`c2|zu4YvGQ$#a9Di>>Pxa_KgTZTCs6Df8<%3>x6I5gHI_+lr5$XYsgJ&?*5m_)Cr z`|{mCbbmO>!j9eFumHDtKWLOH%Ys-i*n8gD0<=&NUvf z?0hND1`VGQT5J+_IEl8RC#=TTt<2-9ToNAxxTcoOXI7dz>XOv>zvqL$QDsq6%Qb7> zHM_l7c0DxVW^>bLHRwiH>T!E6*o=z$GML~Ji2nQaRUT^8-aZNZ1e?%PMEjH0PbQ+g zTb282_ROO&QedyADe+gtSYK(BW~$qt*cJW&6CANXB<;03(z3c+I!ynVm(l(2ueW4! zPc8n$&0f-6F|PHR{3vxlRfwCo9-}kyF`MM z(Gx)GuIp%xW|dzsevxbT5N?#(;s1M{&ZA4`GcF?CbT$3HY|G^n@Id_9^po#+2vzLH z*=5rRb#IK(4@|*huGV|l-U}uF1@q-%oNH<<9vD3rq999Sw~x#HsnxxFqKuvAzE)XhJj$M zZ})ocVU2Ae$<-*;PIOvT+8Zyq)#E55FgE3%#P z4xG*-0louY&jz=sLt%Fgq49^pw2K0jBwgRcMSE4w;A^*!4E}y9Th2fNuwer6VVyKd zwRKDQO`JLPbZxDFWmWiN#^~ROjQq10I-zK6uYfL%bNuEIhs7P6dh*xfgpMF4DLd-r zIcC^lz7fE(u=Mr#?SYnP?E0l3OkSmUe?Vd9Ow*5JNahK!nI9S|cbi{48Zs_XMIg7j z&zv>A)ri`=4!&JX`tUhekAZM(>?kYgQ`s-X$Y=J`A4KSz&Ypbbi;s|2(g+-$E0_Yi z+9RqgRC^gIhvwPc^N*1ff7afzy~ZEv8I~bFIU1YxBjxkPo`DtKM6)_|ayAA`% zWk;5|d50<%%n33)gzGq>v>jd*#_x{7ES!~O!*dUPe^t`ezrjcLqq(edY@-!mkYA2x z+P<%WzIPMNuD#n!SNhKL#j#6DUGo(q1*rGxwW6)VzcTHv7R~fQkfK^k-}8nI=$-%V z2>2rF#5+`Tt8*W|p&K!BK`!_NYQMpIzNapjT_{K?(xdYAQQi9Xn)28}O}F^9Z{I3k zI4`Z&^9D)&#NL^`hAqc$gauye-WG=?y(MaD-%hCQ6rN+ zwP9?AZmd(xg?RSPDveB%NSbxXl6VGQh9}-r3FmICeW^FUT*!NaZ}*O;vf8%$-y0>> z?@edq@YX5ndi0O=9-TdTnSS!D8Kmk=tXww7`w**_4+GY46<(#aL2QCu=pHHVt4m)h zkX&EoGC{fWF9w$ulx?hi9vL8!EhzWu{kNirrkKrK^9u7`ONyk?Fy9W!7(;G9`D?bx zL%Dd9|1MtZjfR!xq^dA#a$yXeg`z^JZ{M7WN%sDE5y!RdrO+NOS=}0)*qskYnUFuO z(0nz$Vtxq~6QI9Le+TA3rM)KW{C(n3zpupp1DlE~Om2L8R4_CWF*DV|NJbQ%ED}l6 z`HASJW8+t*X9jx6H9C9$R6B0|`H+2V!^2z))nOw3b{z>ID3j|fo1SCk=tR=gXU+$_ zZ^Ak4IpkXt9w-nuu9{mD+*7-hx5dPRAFl38C7ph4Qp#j8`+e>rd=)hsIs%pIt^LD- zM{EIbG@VKL)l4-fb~%oRkh>##jekUl*_>uxM>gT^Rh%m#tc-L2Su0ZgL1!|ZpXC!B z9l_syGkMB38*Sy+q$#l9eff!#kh?_e-)RtNhB@VK$!aw7igVsspO}@{*SAI*p71oI z_K{qUEcr!C?R70bCJ`aDH*`&@fu11V77B^6YEIc(GAQ@$(qr4MW8URjwE~pTz(bu` z4SD6Ss@M1YDk*b>J#2utI}gX6RJAaooF$8viMeDQ531Pagir%Tcv(JCVwYhXyu> zOm~pyX~^U&1}br}Xj>vK===`nzZ*{j=p>=>2#utZtLffJ8o!}IZ5x0XBRLuJfB8Vr%q*GEAqD711RLsVCcUa8liuyP9IW#LtuyV|hnVfF8sd}xJj61+}j^(_MT-wA*& zvkTmMWx0M{E@BQUL#Q?dom1)Up`23|bW(TIhwb$6y`JaTUQhZvv2eA5`*C@L%Y=wzt* zxs$4RA?kJW&;+i;4tt6}-u;1}RJhSaUI{lqN>&~h{y}sTjpO#wNRkrSyO6-myTnMq z^}35@i%!)zcaqR>Y9!oGzaRe5hiLheE;CZ19KcGe;Wv0$7g47Dv9UhsmYoYWeW>V` z(j(#cCtOQGvHB zyPt=Em)l9-Q+1}_lacsNQ;bSgB(3XW1Xd2tf~fobYp!6~a35CNG3GQ-8OTPbqbEf| z9Z;aw($3NB#J$z7tB6z^EB^c>xTs^5oTb7%em7}9{v6>8f(n>Lv>Or6My^F@n2cP%u=)TLbj-}6tjWP ztl)cU=kK2sQV?z#oz)aSjClnDMMRI;%{jBLX=4ZzRvy1nHpXOCI)ry9K_iv+8-F}D zE5J`162{Dmr~Kxs@UXneCI<0&p<~B@60$G2KcQ`Yp(z1J6NsvptG#`%Bip2JQOnYo6 zV()>8C}e_wWfL?aDhJef=|4y@q~vWd-#lIbviSm%oe56*5RVTS=uCOlfTibwWAnK{JnK zmNJuZN?D77a~=W36N}pI4~LNmAz4vxRqCt2L5Za0mz~{#Gvk7^_D67YV> zOvHEk1`jA8rB+x3w+w9AfFpzZH0|;a!KPk#4y8t%y&jo zsv{#XP}y71-x)44UOgBC8T0N%)PXf&&Ou)=tO3p4WPKe8iA~;w<(kXaELIs@@e~7x z5Dx)rH@tQ)L%w=*qF3*XfgJ7FLXb>pn|Yb0{)rBaRm zL~xITZxx{S5@X_V^1A*N0~aKR>U}y>@+82d(yW}At=Yoh`|of>(Vqy@7}8ztlup+1 zXp9t2wJ)>Z*>r9?EBNrun;_~zHz?-oyNi*krS@Uvn5`#M+}%I#jl|_4gX!w?0kMsc z4b2qvRW9hjN-+f}ACvE{*h;KS$5}#_q1waOP7Z*)|Db@$%1~`W_0KgGY5dshlI|@I zsUZ5KZvv?ar`kU5Q`6@ryuhnBa(;Qg@-yyeK_~&@qaabs(C#nAuK&0ctT;zy z;hR;%C$(3!dmp~(34=wuZ_RJl#SX=x2~9JMWPU);EMMHk3eX(Tc-b>+sr$6zFj#7D zX%*p1)KHPMpN<(~)?>6fRVIW~KE)*3A}w{BXRe>}Wxu&(T?_;b1Q~9Z+v<=;!`PX_hfdFG8INay`WP~%mTnZa`M zZp<&F`}*&TaGhTd@Li7*e5>FFHbY9JigN0!4-{`M;mAZzyYNFdKS6#1somTsd4~nM zOKxwT<3XW%QHs0HQf@ZyB&Ha6RHDZ#o-4U$owO8(XPx|6jgmF@K zW-%T#lK&9nzW+TXmDP~@Z4GCnQXI+Ap4z#o6^aEzkk#a6vVw~O{OcZs8*18xf0MVd=XZtv2orL_`T9)M zedIW5#vjSv>ESVM(RpXc#38^GBgycBOK&CcONBwCI?z&rw1jj|kEZz&%U^UYuw#-h zNVGPPlZyC84qqgSG#&m9lu;RzN6-{?PBO5XCqsEH)w*ipZfCEar`ZcNG+tkYbp0eE<`=2+C_!;9x8#f+ z_kj{>Nf@;e5|`PB!bs1m#YbzF18Or!27Bl1;wLs+(uE_4Q?FG?wf_~%e%WAMMxtmY zetc!F#UvoxUGVrUoN2X4=;efbW z^86@agiOutrhQKK5FJ5{)k+?3T0H;V-_m_=!9)r{B8cuZ*}E#epqY@HZOTszk=PuS z%aX?X1kb^p4NUD|nExD$QOM(j`)d*ff8|0?kbxqk=D`sp^CR`VbPudkK+ioucoZ=` z<~CkIK-B_^(d+w7G)E+@cH_Lm&O2MA=?~(01n1rjq}BwDJO!B?`?<51>e;pWHyk&g z-Tnuq4TYDXs~x+IPmh4u=Zs)iChlx|FH}?=GWv;eelCpaj>;fmw#%W{%r2 zS#iN7*Zx^(J-;ZWfVXJ{P+nCqx6@*Y@3ANTE zF`^@qM)@fJp)E7`FYja5BP6OyS0C;{DNT&uu*Ss~15Z}nxDSo0y@w*Qk!eL5ZGau2 zBS7Jg`41Qh&u50_o}=*L)<=|y8Z3>_m}TbYFmJQ5lDhGnV}%c-3qo<8KpoZc>|s5GR}Q_lIds_9FA$0)Uq%d4k*ijHvC9T{=EG{4xyi~Ssl z+b z{0QYK0g_XxO5Lkarf@7y`uhN-58E7r)37W2@^^UI8Lbz{>kBPGJt;~vbcE|eY1tEY z4b&fJv=#6>%{6z;bl{~R$t`_*;ck!tOCiwpJh`SJ81vpV_;utBMSo-XlEHgpe!U7` zZi8FU{kJK`3`=?1i{Yt3f!2Yh37nL2j}oR?e*x=}(K7ytt(rr?;Vsk3-XXtZV-a%t zDy2^OlrRzB@}X(;I%IqH&b#l?)?eMG!B}Rh7vd}A6h)5pm3&hEoEZ}!{~A*{TD{cU z70=aJA{Y;oB5BhHVgtl}CKc+hx{nO=w; zgk7>tjgCdF73scRm!}4DJLo(URGo$N|0M%Jo8~&GQV`^M^@!fo4egX^obwesAj&V* z>z=@PXy#V36?hcny`>EI6`mn zc@I6r%2F^USHAO$W=~x0K}8j7{&wrkcrUt$;fn2MeR?j2VB0Jw3TzfMh~V0MMzNB>~#D6l@0sT($&vaZOres!^A6Et32#;Ibb~A z|9n<4un!lWi=?5aZr;CfrKlu92`D1bDdt+Z zwj_euC<5KM#57uoqb>bw^P?$llX&b@T-KgMLjWFjh_E^A>2$a{ye2I@T6zSjG{PRZ z7$tDOAmUwqWCJ=_@o~+v`$PF}WOh)##xME)-$1jH>N0(mB`Z2YVfxF+vbmnNVm<77 zZc$Z#a>b`3ylbANpvj1GQpg~coPl&x8GsDhQ)c4pn7 z`Lf<%v)A$hrbEP$7bDwe}L zJb7i<6!iQ5e{|nOztswco)D9d7|#Jl7^L}tG%sYRCkO7wl}J+65`K64VfD*L2>6CA z+mz3LbJ@7}@)O`mQcuhK9fK*f=om8<9;t54u^wb(Nkx!nX^4fBiz8+m!Mfo*pKosork^$33XJ!MsZK zAH}9@%rBxdJ)1lVKU;?9D@VH4Mzi1f^I6i;$6ykvh!5s#BC@~S;m5gagkOCf_(xOX zW^Ofb6LRU%QU& zogD>DO+8|>!~@FS!L8F@TY~joR}qTsZmA)kG=_MN*+Mym%bs|op3U+Sz4N1uX_`#(F@s`bU%+hOO50S z4rN{?r+QeKpM!=yz zZ0))}(!IeuS34K(zq=8Ygn98da8MofuEPW@aL@vGH2^jZ-5XAB#Ngo|owxX5Pt#Ms zBnUyg3G}OHRu5RZw=^|wU3dt2%&mQ4^In9+>ZfDK`X7mE-?EKj`@iM4tR)jL{TbL^ z_G1nkJB)MQrH+3rBXU0k^xGmiVWB`I2;qqS#%t=F5THgxfu;`1DxkF1idKYJ!OlRI zjt_fh53$Z9$}(Fx=H!3jfLkd9ITrIOJF@A!ewveI>HQoaCj!YnI}SBGxi>&HRdahLFArO) zl5`7{MDqIjnAL?m9keVRGdb92=9kxl%y!oKQUAM|Z}IYtGQ?Z>gx?geJFStt@4aymqr$Q_lh6I7OMS>^Cd%b=2vF>Da43OFA+= z?0iOpufAU0Bn4k9qW@t^9%Wu}G&iJ?w9CD_c(8tJxU0*8e)VWLY2&~V9tFf}IIC1l z9^d!n4W4@aug#AX%x3IWXnpT08Ev~{=7lUpntM1p0umvX?l>1gb1q=RBX%1_@xucKn1ydo$XIJMhYZ{G z_p(}yqc(G3Ae5VxP!Vr{MnrX(b;cMYDe>i&DKfs2nq9};wNg4{CN$*63VIl!;}IUZk=@CWm=orU0=+Q>%JJaMIT>3$4GvYo2(J)`LB| ze@9FAt@m}{LAK4S-VcpuD^j;qfmrFuT_7jD0eKknI!^)bqr0DtjSQOoSIv!;7;(hr z`Y+vkO%EVc%NkQBfY3`eSgE)gAav^+%6)+mJdULTWDIl%pDb8qb01QF1`rf0XL}JD z7pTa*lJ}(eEq-Fz_nO;vaX`f?h$y}e>LKN)R4zKb@N831sABa zt_U-q_{ir9kL?aaAbkoNm!I!o8NTkjtVcuKq^4??c10MhMn;Ik$X9W~1cF-S3~kAbjtU zf!Hj2Cmd2iWGNhK8qQ@|A11?1@gQ!oO^d3z2F{|K_I)LeD;C}XzvzHtBX(WwD)FNG zwsG~Zuo`KKUi6wfvbCmg+%&ocQ_#F|5m>42@{$ey63qd{*~y)_74EF8a9ME{oJ`?1 z5X6_SZPWdq7eJ7QqN!ZusZw1WZ(G^TXFJWZHx}_H1}{3mSF{%95(-hPa;r;XKmP~F z*Wb|y_nzYg*KgE2X(4cmTE0$K|7{Bu$|EE>VT6+rZf8U?uqx2xmsE@zO@Rg~_k_vn zM@OU_74cfp?*aWr91TBJGF zCGTdUpaR}ao=D0MR*$GJUHQyKczW34Sl`;nn*KLtKHgpF6e)K*gcLoZ{DDdxG<_T=ua4ccLNlJ|rm{T??(0{yQv z_*utr@{0oA9O`u}nL+%i-A&MG*Ib6sR;}yrlQ0!|?F`P~!{L_AB~a55rq-MI8o649 zJ|$bX;K2jo+1HrES2Gew_!_%8Gvsoifpq)x9%9U;dLEm8791nE%_eAw>A+s+rBcy2 zn@Qt!pkn-WmZFD9b|LNJ*MQ1e9BJkoxJUPWfEE9v6+m%brSIRH10}e2MTzybuYaOn zV*0yJX_lHpfJv&q1ERKB7y}cLl$Wy`WWks6DK6X)@-TqebN_f)k9eSvqcJ8@L_WF8 zgAW{_DjS8}4yy(#B=FP9d`Y$GLz1+SLlKyQwtgd*E`<8mUi^-o%p=)&9qs6#EmPuH z6ls?{f6i+8&dzFz|4HwSC$dwe3Fj9rJ?TS^j4y8PNHP(tSF?9_k3y61+67i_LdI4S za1sNb?z49ulg7UWn~F4kD3qIEZx0&w1V>T>GfmC*_pM#PcdG-zNshK zRq?O{|I`IgEOLwz96Gu<2}*vLhur$Rvhw)Qf3;igKUZm1D95b=coVl0kEw{(m)sR_ zyt(6BJ;(VL8!ub;@fn5_Id=R{sA{3~d2=_N0~{iFtE@=;8}^-#s*S26k3-Od}p zgKwEUY>a3tiM!=0{{ew>qVO0CvnfftsYi}3Zi;kS8G`Oxw5ewfR=W$0Xz~Ma=Qun? zS}#a3T{$QmjSRAYHa7a|A*cA(!i5FT3W(27jhLst6In-4ImlJA%N$|l~?Pc!c%MGj#8=Axp0x#Dtoos^Df z*45tnd$6~OdJ*1q)TDw#pMK5zH*dhqA?MSYI^vvgQO@BzmE5#s^$uhVPUQTP#gr|E z{qLOY7Ul4_7zlb4mKY(Ey*grt%Zq#mVq>Q|Bzbd5C%~fGNP3EuJ221@Y{n!9YukRQ zSq-1Inz{nhYgvQoLc;j|FGvykkh`!WClaZ%WX{l(-Q2~(KXQh+ePprwX?X5(Z!nq z9dv9}cC#Hpt0^u{HCa96NBcILjP{WHnr6V4QJC*%H|R(a+5pl@C`5((Ua0Wuzt z0cyU|)D&KEmL_g_=SD$dHa^|z7+G`Bz!>g5k$+X-yq>R zjtb8He195UFKmIpAE??+u$i6(8TBlcP6v3Xd8#zRmFrj-{XK+a%DICu z2d*+&f%PFt8m~@av&DKG2P1JWz|v4qS9wNLE3~6&sRPCWg%5akp~-@%_aDtw8!p)g zc9jQM@ztaqF#W|@?$2-8toGiay@U+kWR{rUO5OFISbg^zT#e@)MxYvD<{B>#($d85 zl6%6y#u_v3$et>isgFSE6Xy%?rdtyZVpsA+AiHvRS%)s-rvi zEk05cVe&O9b!+qEdi?gv!cN&9xB~WefX~jsTS;HMa>)YtI0y1clRi|AdTc zfBCIbKPYdI5mck(^_I|{sQJ7#83%kQ(;_)sat5&|V~JN9aC@{oV>%KTBb3761NzB{ zBPbBgP0Z{Uo?#L{M#&kd#30GsYGW$9DFfFZ`hJUx-IR)3`ix7LG0ew;>ml6qX^hB% z726ABu*6}#eKJGrrF?;w|sA2cV*JQ+BBOQ63CIzd*OtJ7qT_8^lSfb zggURrWIN;o5X#GEPpY!yo&9$YXe7RjUP@NST5@3u+J9e`N_a|lBhNB*kdu(kUQ6am z$)hCz-D=KM2HIj98=i&{s6g)zWe!(yR<%xrO2N_}m@V4GG*O3?EQ5y9I#Q}P=C{ni zm$`;wtoOuA;8(!4@O_6L0lt{c8WM1($)HHu*gJH3(fbolZOx*ynpY-1m7S&_JZ>;> z9hKX0Cl32D44gRO_{j9BRuPh`Z#pELi`Y*kSi{*U9ZSN^C0D_4*za144hyqcX*C5N zb{i!D+Vq56H;@2YA^#B~Bp&sA0M%~eC_HBLFG)I8mTT&tQF{TLJ20LJNV+4?955)o zRPHq^#TPD@z8{|?jm@iyt{!4m4jTXy-stMWSd>MD!+r&*C&=k^vh(u|qXTl|@x(t4 z{fK!*L8*but%CO0Jgi(>x)b=q;x7f#-`T4Nk}aXPtpk20A-@yG8TIk1@aGBnV;_ zPaLlCn4#ZupwoH7r3pCOB6va&qkL|?+&cfHkj*|khuT?RUj;-8?~Q{t_wvj0rjW?7 zzIZ{kwJV(~&0HN{sg}m}v zKi4_;Jssy4@B*>_HN2+r2rFj?E)=B$HuRHHneMUu=m=V#G$c32Ew2NO>7Yxn183Ls0HGr4qxC?#q$@52T532})Vg)ObP3`H;M z;Xp3qk6$aj0!ncbX_?WO#1;F|6@y&2)FZD%?n>k1#IQ_f%4)_pTN4&%CW)4*E*W^H zsZ*4@;K!@9mOO!R?9FxE_fX)K91=d%csB&dt7uk-|)Iz91B_3*gg zbG!u|%rjpP_$!BRXm`@4J6Xa_z{_5BeSc{mu$GZmyUtaTKSf;4wfp>$ zlW>gN&55=2YV77fgDL0_vKLmA1FCbhGkExXb{5thJ508|AJx>{m=c$N= zCs&>BDBzZh?+#NL+-Bzl^14lG;in_8Oon^Ayw&IAVWiZyk*wV#HtI`1S?>0y z`_v55u1`PNV}aE@Q%+W}sNt4dGuxQSuhey{j^tr5m|38@$R>^VFi^3%4(y`uI?4o4JDeH@tDI8k?- zeiGC-2YP}_WqT-#Jl-J#KmJ5xb?}t8k2z0)^Q-L>3sx^lAS5-W#yu|x%8{Zc6n2yW z>T!u<0sqm!t)ph=S=5X!8ZcV1VI&XfHf6(jNEiXUHUe%LEv=1@n-DhHgui~Y)|4}S5PqG~7%M`8ZH@Xhq$(H0x307~9-udEYn)Rl&t!XYPJ-&*x99pIDVIv+` z_I)(YI!}aGr&4x@tAl@B>KS+;oR~$m1x{$-5&%bfh!RsT42YyggrCF}KQd^8TBU02 zDKx4S&3_KgwTtlz1QTMfHI1`A6)|XAU^C#n2qIigUGSd06Q2YIQ}8;}u5<*o*F=uD z#V8B$f<$Ww1oifTi~UanZhzVsGOvmQZJg;J@1bxDe7J{Bh=A3eM^ypiJSbu-V^2GW zMCv1fOFHEx_T;>)=3NCc-#vQnGkZR4l%^@z1CrKh5c7@4eHpF#(wM;?G0}Ck+HN*N zVtF85o^7&I)yZ^t>HOQM!!!lFP?2NDwU`QQ%Q?nE5N`LE6;Cmov}>*4aD=q`d+W-FgXTY4}9{ zF>#@?dadByRJmjyuK0GU%4bm;f2}s)ZWa(r*>#tAWpKn`EKsCXQZ9Bqm91! zkyHCV@Ybx9#JoqRIU$JWYCCAZJBAcdSp@Bz3BYeGaRt6`r&uujqn~2>8{_1`OU5L^ z90$=${X4i+q-UZuqH1Dn*>5U@&GMVl|lHU#FjGp|2T6n zgRo!p0tbx|oJ>Np{46cu7r$XQk6c%O?K;GQ9S=1KF5Pkr2!n9$x8PD0_@&(BY$9BjZa zNOwMRPia7m5J5v&+AQ$9#0`}k3|x@m;FPFw z@JyOZ$Z-gsn`Qu>+UmJz3P1D0Q9KWzUnH$)KcR!~$AX1WJD(Sc^#UVUW=V&^?yyQ_ zMQCwdnG3?!lBHqlG=Y?lg>IwNg|EAlpUyoBZ=o3V_`u=|0tQ^S@TWnq0pvEYi)ZCwiJ;38f;1*O2T`YUI^95-CEBh{6? zzGKSHW;_61*i50b*77*_1O25mFrJOLKGsm`G2mcvd2XSpdSrWj3>v(C_FKI?4#}`- z+3VxVV_6ZzYtCX_c20JF%l_NktzYuuB&7XMx)v&Cdr4~c&#Pl9xBk}rtOKeh!RF)C zX~MGn^Xg#@#4}?11kYS@ytit&N1HWB=9SwQSm40qmLHl+JSKwbDzr@G5KqC2nX|H7&1;6lM+<=B%q?=-ye0z6>#5GVm|T!xZK&kw8y zE}6`_Tp0!`EoG04^7rQpR4VhB<)OJJc_U8YN6K85x8nBUb<89bZWx;AtH|2^e)1%w zCMqIbZ;;7~_cYpj4>}lzK&-2RHa$S^l)HJPl~T@q0kfeHLel0P^F*BbsdCLkEF{2p zNnVHtDo#>Mn{g>=v80V--Gb*b!uaGL36qj*DG zBfJKGk;y7R`_Tgp7JNi){$olDPdvwTgaUkhO3b_c%>`D}OuqfH0=sakbkDc|Sp%X$ zh~5d7J?)B6EWJhYRvBU>JTXb#Dh12hPfXiC9tbn~qQwAF2ZiTT?72;k4O* zd5vA1@)Yqbcn|8&GE`Q2Djn{~3BG;7Q@>+oxEo|g!g|6rfv7DwlY0m@LvPk`4GSJq zzQdAFb-ZF1qJOkr!>Yb$+@>pwyTuA}o7paluDbxpZg=c&jIxsVp|gh+1m4 zCOJMbF1+E>0Z}HJ0+ACJy~Ja#pz(3keYN{Fr1ZD5HUlk3r+4T`DDf zQrfR50Bx9f49qU-s!~aHPO;&wb3slQ?yRqxE+`lp`lIptegiG0V62L-P}pgHYHy_k zy`DbhSM8=6IfD6umN5mgBdz&5V*FxYxmi)!GiP$*uYxw4IQ@y-GYQ;;8xU%uc#hZR z1xZZR_{UsYSZN{2TH7HPfazLGe$M|RM+2Z z15n@v`Ogb_E=ZHeXZ4LFs+k|FZgP>Fgp+P-9m+K09TQQf9H5kf;JbTJ>{L{C7CP*I zYW@GA>AK^o?BD-=?2#i83Q2>qMMqeN7sx+rbc-W#C~N+Z#uW&a*5R!j9h1H(GpN-78~fvwl=f)i$m9;9vmI}p}46A zbd1-?FWIyUR1)g=Ohj-D2_^>N0cKeo426{8+8ush4z{{<4Rr;=9SS_N=2C0Kp##4^ z3jwRzYN&;RP~^)c97+gaan+5tV06!hXll}CNYnZQvB-*N44k@Aq+KW@DA|LUHl6>0}C z4G>~(cNpkv#ntC9zq-n}e!##n`M6#iv_gZCQxv$;$Alk7#T33XX9=|mV8R&5RXtH0 z>SfCIS{;8GI9jJ1L9@e4fWi+D|1S1lqM=bF+C(k4QmP_1q`>d6j6|`O;F@2zf0Ip@ z_xIg=q&`ETByT-c)I`S2_oR2V%_@rZ{sOi3K;&evkH~kT0{kSd&*XhmZz8MJS@<*A zV23|wK-s8K?jNUO0x522MiH#urXfm!D_2-ZJ@{ zTvO)!)&vCzo8HVq`WDlMt>x{sk~9}k$-W?yF}t^WEtODfP4Bwa0nXpOA{-ZJk|aNk z_&)ou%J`4KP>sq^T+)gnXD?*K_a6PwD%~*e_UO?Kpslv+y0Jd~v$oQC$3p%j%g3;)@451Pt)H-pE#XD*=khc?8w#MCsx620xMR_>moEBM!1~(mwAJUIny8nKl%vf zhKfs=G^2O(?(dqB_$=m*)ro@apz6*S1mtfbAhrV9!js>{>;ZEr;-pzsy_9` zNd=>{dXNVff7rO31LDen;tIxvZu)6l`G`MXsxFb})`R4K zJb!5E%QQk2MtSH2>8x<3n-&CUECcq*F>EXj^=oG_yH#ke79T_q9XpMY4*}<$n!1+) z6F8>l!!EW(RHCt2-6SU9@~Pca&&6)Hu`m!%-)gX~K4|{`D*0az!|#5{Z6R97cs>im z%5W|o?ylOOMz_gQLTdk7jWE3=m%fgq$sDa%l-ZWVI06WO#-F{3`CGyvOkBB1NT&xF z_wv=D{alXH8}TGD;RFq{t2fBpfgTXnk{QO}J0%fK=IX|6bbIuR=)*(H3J$|3D%Nh} z+d>i)HIvV0gnnIq=Wr1dM8&u zUXClX4oR~?NjI~!=hI>hf%E%)eK&@;v6amcXs*(mxHrS=XSy2az&Jn<=+XKGtlT|)bu5cAM=M5_ib$DZS5%4 zs=VQWKTv|#`eEK(0<-nIzCkxy67KgtnUyf}4kF6+yCPE!v$(ge$SMVXZ}}aR!a-(! zjR9Z4?)||343Zq-6KzvN<;n>c7LgEweH%;Gl1LuOjeg2rpH}ki`N6Rt+2lzVMV4tR zsbDzht$pD}4(vmc5V9#sgSznJ*uPn(TimlH5){r^3_S67zVh9uyZxZopm_-|u!rY- zU9Q@V8-2`v2{8OqEBI(ht$h3<|DlX`z#ZRo(^elMbybhTp39lAkmjxNE17ZUeNi1~ zu1>%KYy+7i$fZHV+U+?gK0P$2C4bf|5>Nm*KmY|nM{~4nUd;Yh5vxG9vq_y_Ne8Js zkW3p|w--?pY(nOG5bOkMTxraMGPauQ*3BrBl+O>=1AU69T#dM}Z3^_9-pjs>j{oBV zu#?0SDr}S-RB-(R_@Mxbyw#ob42Kv04%8dpzw$!i!S#xE<$JU{P+)(0lOB_zN6KZA z9-Bva!;cggHn0lZ0kHp2A^BuOB)NpGq)Dx}P}Qesj=%9AMtAFBw0#D_RY*ZUxV6t4 zEn2S#yt$H{doV$H=%auu*Gfn7PTzm>jRuFt@41o9U9ui)JTw@PnmGIC{~sI5RPS>_ zlt!h`jC*wvV!uPE*Bo6U+|RePnW}?LT8s9AQ@joV_U>h#J^oq9f2LKJ0Y6G`Xh2ol zFf8?1nQ4rT&Iuh77a&x))P1um*&yE@V1XBWlv?i)U)R-{wM+^$`ZHODtR$z{?xx)VI zDx~P{HzKh$KKIfk!Yrhx#w<{gM5-WTgr8S(4zY#NP#H_R;D|OK=JgA}S!rDt zkZDa2T8}x)ZAe`>A9aJby{6at8zppgN8nD4IF1!IXSTLpAuIfd97wcXFiB`Zfvr__ zFnHYX!Q|hwZszHXHKoO1Vk}sElSW40n1RYqwzGzsZ0mK%P09jtPJyk9gr9qZb=P}x zdNx+!x5u&0cLgZdRwm}#WV~+6qDf~D6W=lVWT?Bm)q4|zr&r09aUH$y3X%ZUs4-*isEDxbawP(S2JoMZmxu;^89XkmV8g&2 z`z3dnKIDnL`RI}S;y5;&6WdtFktj{Va@b4wj~kG;1s32AY9pV&3|D@SHg<(^_bMKFC0Xt??xZ`}i5^L-^~8%u%G4Kv@6;{@*huteBEX zMDh-K#g@-p7oTrUtitV(v;#s&8s7Mq&oFB2`$v#SvY_#zxLi7{fL64_)f#meL zEbMv?c|{KYRtojw2?f(imIF}eNzVbg?;}2gp!@j>3V>$=E?%Qcx8!gTg+^0i^ZRSu z*_*daO`{>$Fw?dzja}3NdHs+}BjRLYi{-}r-y~TdVZD44T7;DEu(LMvAb5Z0jq=6U zEZCeoxuPKlfuuhJiS;VNiB}S6Oq1Xiw0%p5bpOi&Nss+9EzQdpjmb01B;0Y2L$(!4G}!gMEw=;-zr|DWgvvO zMcrN{<=SI-->FKSbaP37A_u?T+uh%66w=ILgJZ?S10ok~s;>FQpsh6P9VTJMTsMvK z?AgBoVpoq2m8kck_P)Zg-qhVDb|SEy!>TPcSIYZh5E>YacL1ft?r)M?eV-=8_DWUG zBQ{)DQ_%QAk-aZ3$SPgT3FU`&YD;WT0rNb=8?lPTimNTt;eP0%d`o=_e9x!9=}rTE zqJtad!^OQWe~Xt06(mG@70$ueo8l_%1nA?#PMS21yz!Ovn|x(Uiifg-HyfH>4uRp2 zqFH}b-y{^xC8O+ZVqEUr2vP50$u70WZXUaItIBKcA-!+~0x@d}%||m2cXxODZcikN zIrU#4CA)3S<`yK)B|s+2aL{I>-&ATOv!*mEn#GoLu*#?D?vOw*89=38obEq(`ftdzFyRGx~LMD=-F)HoUA6YJIv6!We_wb%D8{CsYxcDE8HA2yazF+it>P66CV z14Ha&#XS`J#pXGyPRu#>pQqK}4Eg~t{$_IiYciQn0Gv13ulODQj+%#A#rj<1+y^;& z6V@G*`iIC~LCD1v^IxFTTYflHGH_3kp(4oiMM6%EAiEw=$wIi8{_p}jBPUu7}M|x0P@yOSS}ndWiS_x-&(pX&~$N2OuZQY1bt68{t=4LI-`QHwKu&K<4il z$Iv#38XZC?*+J<{CGhDL1-D#yhoS1T&tMb0)r$VqgWEkze6=qst$La;q;HEECQh7kEyRnoIMb`cSj8v!bMoI|zZH zY-wq3F6`2jeFMpWb~J z`P$t@hTFG8AP|ZDg56;Vz6oCl*_nB7(DG=-XZ8>v)7Oq@xnBqrS?$Jr+mcn!MUawAGB-t~;`jg_sm&vYkNOC^P@it;Zs|rD)a+{n> z`x~?U8Bdh(%vLJf5QxG<1v$h@~{9J9L27Od+_s(BitaYLvG3+FDp}%b2 z7Z13*kiz|q`neoB+iI3}glH{(46X{7l4vPjx>G+Czj`3hl)X{n{KwXDHRW>M_zTh) zY&!7}rxy!c9{zzE%1%N{>BJ9QiOu`XbBs?2@5~UgHIhdm z0Zmm!g;HUEO(*bRd+GyZ-e;-B(}m+9-TBD-H2<8=+UAxPvAf@BNT1lC((^n-{!j-( z;@Z~q+t@&x#pEYX=ty}$A3E99JQoL!6#z4(vrZvs=NuvO5$h{j@k^MA z>i}Tt19-YSO@rkn6E$QO47?ZKx3~Jnm~`Ioi}*+^85q&2C*3;t^+jSpKGR9yo1i`i z>rMD7*B6{&QbkD3App4Z6n85&-{h&+@D6#JMg9@TV zQY#+j!+#F9Vxr>EQ^Dlv?Z!E&W7N#;@uaV~@g}|LFW4$=+hFeI{f5eQ*=-#7^D((p zqSyl=nB0Iu8CfbxrxanlA^n3Hqqutrq^}_5BDjD#*zyJrt4K7gn1>jWfJLz??$qtH z=B*dK+$_YH%-w&L|F_2tSC<_NA*ez!E)?$Zvi)2 zc3#wRpU5}-=cCT@&Rl^NBt{MFlQPBGOk7c|m!>%3E4=z*24UlFumSJFzh;;Bzu-mR%<;~8kmIv3}KlFqy32NFRBDUg7|!EK_7#;=`brs=Ef z-VKs;8jUg|dB@!BKCd%%E3)(UKJsU}1KTP~uBEuZwFyiPMdFvuS1@_@B8$n{eAKLP z9nou25rg6Q&U}p&HWwMY!C;|Nuac;v1lg1W{<%YC!h?yY-YBh`R0^(r35y1Up8NNq zIn69(d3N38`@P9u_)AtQ5qu{WKI@OT!z8C%M~69ZA39~B;~tcQE>OsGNiV?9 zf{(P7F|u+O`~b(^LlZtsEbYPwn*xL*C^g7Zz1J)dy4osH&Yh}|k*^ti$PtFb^deR; zD>N0~7^)5+MUeMB+ms<*rsfL2Df}h;OEBd6E)znCRTh6CQm+U;ThdGF&1cPTE(iBQf2IGzO=Yh*? z7Q-RIvpFQZ5p}A2?6x0=k@cuLSz+YOEAg>F76q!8^Hs%C#B7o|79K5)kdK{OpS>eUE813h93ztAAA}Jwd2u zCthiX!UFK?coFiKFQ%&uOpairTv%nV-*GjZ_K0BCq%j+MOHF)jYbte$N%7ZB$!J-R0*6$XNvRBk0EGXt2Vv7>!ipA&G~dUG(oG$uOSVfm22ioFjn1WX^f(V?njI z(9%d`eY!T?v~Rm#?Z<%vUH~rt|EiT%9fHi7yymF;6GMj1lK!*QSC6o8z|>TWCY>YW;>TO8_(3AMYeTfvXUnckBd*oc1Q2UQKN zX+A1&sUGH+0WJZxTc;p_yngOEk`jDRM~Qq-CJ|%AV1Wggw{k8lu>>M|9^D@K!jIrQ zk=(#3(e*u(2S*3&aC+5FV7LW%*ngBufdWy_bEKiDu?uQ7C+EcpYhzs zjmMhm?%pQt{RaQ+@Sq+FCy^r*z)peo&tUDyJp&ZU*UPfpmKG$=*p-R(kX#z9+~~h? z2qj7yCOB^C=Z=f~uV#@}g?mqLY11;2i`SDlS&-cJ>y?D|G08;wslJEjem!{-y8!v0 zQts-Fr9w{v^O=7KKURO%2pAxkKJqw!-A%c+fGDiBKfL^K zWo3!X^)?A*@0ZKNU#;>UbutBXN};4U0h&V-v9a$cks68tFShn_mwj6p<5U9ggl%5< z#^jj@uvcx0!5-|+IkhBTd5$p$c%pk|Qtws^LgETP0bho50r6}~A=?tsGmAkkEax1ThzM2$dAOrW#m0f<`=96YX z_b1))N5PVW^rnQH(7sfZ*Y6Y*2%C=gI`#kYz^A&BwSUe{T-p0;E58}QZsH2o0J#c= zUX3U~L^!+{8*ZC2u++qFGK-TH!f*vlkr6DwTnIeJRSm<%*{y1Kr1zgZ_fCaCpzoo;?TN-|Buxw!anM<1VgtQuTrxQ3Qx z`@3y(izZxZ(Qu+#Uaf8#=ujCmL$B&WjSq>Esuf}cT5S&x!HExKvTfUt}oYlXNqaF!E4*8xx zddKx0)HGTSuPOKiY8>nj_V8`EQYLyT;U{9_NLi!+JnOnvHWya183lD&*g#X=hGTR9{HUhrL=$Gigl#x6?NRiSnXe z_m@aUMh)5TBtbv+8ECzE2q@AUj_ASg&OQTzmk)>BPF4!`1T;74)Rhl4^%L^Y)=(kH|$NZi;*d>S@wugJcXTG#c z^M+HN$(JLfsB#EdEZQ6j7{fnc{0;%i(OlkrD9E*k^k&Wnd}+R9pY8osgvsF&o}`TZ zs;&xUpUs;&$TbTk=|Cp^<1|nVg%Lk99MmR^4z}AuEgQyr%OlQFdg{hzKcV})4pc~n zGpB`kV@dW{0nz(@@w}sJlfoqNk@tf$f4~nc7^FZxbJ+*R{VXd+{LXhGiNk8_<_4|S7NU8DZd%`*(tqPc9Z@}FEGHV+;iSv<5%Up@RVMsT2`eZf za*eOi6{X8{mGI z%vM0|yYGL{Vkg{#4B2pe398hC^4=H_flL^W`jVzbTEJ#~{EvUD5`{S(yH@;6Sq+e! z(cs4++@Mbn?FCVwZtRTewdlX-4de;`}9ae;+!jmo$wp=H7q+E1$>Gqa|A z)2h)Fk5;kH;KR@`eSH&o;>lxXzPs~%Mc;Ae(9G(cSM957=Kg$ylC-7fYtvDW zBbtg;i~MHSR1h1lb0pL-)w`b-qTf~T+&P*cWc(1eFB=qw+(Qt8oL=_v)2Bvm;?^}%$Ul_5!0Rh#Py{4t6S=Uf-$D^l>Rr z7@0~h=>-PD@7MPt;MVhWRt9JJQ-}_oUC?o<$@duVJ0$*!ydyM@`){8hj;AC1{-FOU zgMA6|+v{&xR_+b_1Ww|EEPAZ9HCCt`d7pB(c42QWAKV}>rTjjQWmE(&qfb7uTmgcx zQud0}Z+Rz!M0ciZB6i`!+v@$-8D)9{j8)T!bN7u!6$IGdNHwu`(`DNolFcFN)(_^L z^|!;pncvY)m=2T(myVIVKGr5_oN#cCvSjaY-hruE{>KrbUe5UpHIn0kCMTVjP1J9d znh>k#W2W(^BJRe&>FqUY>0q?lo z`4Yzd&km8Q(Z}C-&Gk(GE#cFYU)Lo?$tQ_h)0O>f;eG*&zTf`6W#f~hZ|dkRV`1A@ z5zzA`S`8ELQ!*8gJwE-x*=qD&KPrVA)BbAS_Ep>wk(!lI>f+wzkYUk}KfnGV!Sb45 z{;^&QnB2}Y^1e?2J(O{i2rF%|%#;)wRbj3O2k1@Ir?}Bu;ko;o$FDcI1g!i7^Uqf< zQp8&Qnl_+!Os>BxAEZ)GrK{c(CsmNc2if{O~BR{7Kj&^ z$`n9$_g2$~K3f88yLv_i@vfm-s`i`2y#RKzoi^^@ z%=^qa$0N**`Th5!^%Kij#|btHhJNAPO$aE7ppXAnM=TJi&>;ON#^?6sBz zp?5u8Vs|Ob0O}x<@_+@LU$bHKF6cz2#zlH)NsoaH;)yU~-o7LR6_VCY~RudO_yDVDx!CUUlqyAgb?9Ir}Bd z!t>JOSjioeA-Db`nB7f%W5pXhpo^QS?^ZB<3G$YBO>vw}5xD_nUE8fM-m6!+_*W}` z#&=JF0{#BPZ*s5_N|F{cF}`?llx^L_6G?pO_pwlg!l~fM%@44|F3K3b(FLq~Wy~6P zK0|Tu@Yc>8zRiRqez{p;>)-`6QQ%$dGtd#3EDl5UPtYS|VI)%*VnENu`Z}{wxroMa zzVhXpzB>W}j!#?{`XIqW;t+@Ap*wyh?*QqsfM{%nl<(Oyke2;DnnV9tCO9Xbs3*bM zx36mFmb58wkh+piN%NrfqcN8z*-!6kab(X{AkJX0`9OXFM-K5z408LP&6tBMuo9ei z3d}r$@4PAG?&A2ZF;$ zEf!sLx?VzV@OhYY{n#^MPz9`oYF}xv2NG)Uw0_mu>h4s5WkI4@oVj@*c$v3r`AX5LQ!;#-fw2mT!A~t|!0ylEwuUlIz3?>a3&Jw(_d=;wmX~Oswt-NVz0@Aej@kz zJi`(y?w~cM4V;VO=>-x%nkwTZ-pTsBmPFcK7=5fC$BC6BGnPXo@!>(mlepquOCn|r z!dZ9*$qk+=yx3~O_Yo>SP+3*lnqomg-Fk$!daTq->(TvVY(Pz>yZ+>nw4m@&Rj+_* zNA5nskJ;m7U4H1f(t%-`V%DNCTq3+H)goX?nZQ$Z3wo=u3oPqdMs^fak|^npZr zqvRO-eiXJHb>VMh!JNonmk*AB;3^)PE3!TfHe&|8D3j_>4EOF2H{UiEP#7X9q0eV< zT#Vc0S}8BcAv5z+sn!sin0TAvn*2X5K*t{>flCCmkgKkrhvA=&xDtN(g)&5zNe>j4|{$95_Z@No7P*xH5JgTC`y zUyg38T!3W(rCatg3w;hj>z3c29%BeDKi3C$C;fq$^=`N66^2VXij z%mbGx%jHeI2i&e*XwgyR7Z4~ic$3jE+89MYyIyA3kr|3IFc{_B*eq^U)Z|0)4sz;avtW#Pk>Q&0YSj=T2aiWxX}EsgAXf!Uwwf={Q?YruZS zKJ6Vq;er1ZO zF8j!gP#i=((Z>3J#Ia%ai4V`VkS!$$Ez>5u0mwuYQruFiRv-~mzeQYq(>mW#?lK%! z2a`P08K*=M^B9-9{f+l^EiEmifz|1zJGXC#4b=oVaN}eN)jCT)grS;u4jlS=dUyK@ zEtBK}Hndud${Zg9e#QhrSkD!xy7CN)GVz2MF4^y%XToXXAMn3Yb6MUw1rM!iGn%!k zr|7Vv^WtMIrp)ObC1(us}L1rcS#Imywq` z;mCT;Ma)EI16C{NFwTR0>B%gZ(|MiomrNGAyl(lSIej=qeG3Bv_yMGy>PQg6x`fb! zN5xQ?q}qK33o~O-S>?<}o_cjZ0r@@6_cX&Y_}rUD-#;3uve6IVYC zTXGa(UB3gAc_PFdn}^Bg7E15f!^|G$QO=F}gOkSbE@mUi3aK;{7GaQnkUipAM7}OkZ z{~))-Y!6kZY{Dnw_0B&t_$rfo;1}M(a|G7VThdDU|HD=jTD|l~UsIcNFR@R!jd$fH zPHEcES^?14^dj#(^SwKWa~D;T0v9lnzN{xpb}OR)j_r(4#1m5hsIT2-)r2-H_eYkyB=BLkDaa2YZX;jZ=tlJN; zPxrsv-_E(y!4*YEf-|5*2V#-mZp>XrxNDkt#=WNTmslT&&LE2&SDk{coQM}eCj~NH zqkehtzIs4*D3ijPay$eO6<4=9UR;~}erd3xtt^b0=CZPR2hn)7c#Ql80uFo91i3F( zf;Ou*8-1H89@Q&I^!+qbm zPvyZoRd;gr*e|(fby&>}R!MCP`V6NZ3{|+DcCKDl9r2a|tuOzoyUzw;*gWZVCBW?@ zK7mJ@{AO1%{7JdB_NxpjKeS8kHqx1R|Fx!Ud3fkp*ks=GGfc8jd2K;#(R?{~q5C^u z(_goLD^IGOw`Z4wCT+$Nzy6tLyqtD1yrS{Wr&%! z<)W`T7(@j?&CgL%bYEa&&NhT7zSvNak^-$|_b+~L|!|LJ)W+dG~#ltpd;#70b;;-=Y_S)r2i{$1bm89x0#nUh;( z=-Fjhq_^+2G3+ii)b}1I9G5Z#g7RskYU{Qc2sNq%k*PZbi5n`E&!!l69`mK=5tu#A zKWtCG#h0yWGhwV%TuFu$kLc-=zx_I!Xma~mCD@(}!K`ZlYZ5Zk`A&L&tqX7wF4;1y z8mF?Fnp(Z$vG>b&h)s~pXskUzAYLl($TG>v&}CxM1+&PLk1U>2()L(1#2Kh5&&%`Q zKXX?@IeI7h_)B(U!J-VRA`6iW?OWQn>{ZXxnN-v%PWn_&rIkp?mdIAgR!#ZUnN?T# z_;~v)UaBgQSpBuSZQ^hLc9>5q?P;Q!znald?qbMR19xD72Mk-sVCUKE_5u^(cg_bG z@tTj3I0`;gZ$Gyw5;@Vty?CCP^s5=PxiwIfc4!oSGX>6b1;er9Rb6?rEpa-hjge#Glqxe z!Vg|{UoAJY{Eh(S)hTWrYSLQ~n0&}3#vQ7dV8wrYk0I_VK4;YT7Qum&4J(-pO&zf& zbrk_eUDMyFYFC~m+;G3FIggh7#9+bxqAWO|d~360{bS<&%D+yH#%^%;5t%5@ne&{7 zI zmt--dGh4Yo4qQaoqH<*Q1OOqi}oFyx1{q5$i&c(LEiwEWbC_5pUM zsa@lEGMrTI%1)n@okA7ECY(iT2?_yI;ygsTaC1a*9*cqUo`fJeZ1}UR3}hZ5 zu@s=iiGVI}Z_25Bz@6T?W?j#dFvJDO(02ec9uki>zO(~w$O&IOs#NTb@}Y{|#VRqo z_LG5tPa>G~;2m0KUUl&EPkBIk-L(TXd&JFhnuXFgHfBzV?JKbfu1!C7*@@)1nz4%Ru%Z|S8A>r#< zvC47wlr6Olhqf?sk`JzGcC8izT);6_7r@j!@VP=kI8j)b@BDo+}{B3?6=$9 zS)UUFl3z8@rp}JKRCzBfePhy6SDH{}*M}=g`ugOt3jE6W zb44>iVIEI^?;LVTjoOtR<$Dmw)59I)x#ZzH!iV78h4{G0`se;WzKTFbXTTJ{Dj%PB z-y=H8zXvx&X;B)eq{E{!F&bV8A|wJv(B@#|OxJrWm~nTy3mKJyhBcK$ld^#BxaiNP zfXzi;IP=}Q@96tIRB!EicazN|XuaEa;d5{MXNO*c*=(?FOBMB+)g{foG5Y@}yyNcU%-kTffzgJ`%1uI?KHoHmg zX+*d&8|>YsMU;Jn)w@rOM+_H|E#X{t&972YT3oqqWI<1zHTs)3&dGNESXxQ!nbRSgB&#h zo0^r!&%%jf(ZuERE#^G;gbzUcfZo9W{Y_lk=fj>%5-G|p3F+8AP;c<1{EZUiaBW99 zQg`hZI~kAAC12{Qb7ZG3bO=3R0{ZJy4%EpPnYVqTIvDKV8|NpvyCPCfbaKn#G+q0P zRoD$2IW;GKao=k7(#_p_HBMBFR44qe7dYyI6=KTi1(1Gu(@dX4TNoPa-Z>j?KDi&w zW_;K9I2TqJQYoJI8|^+o)WTM@l9_hszG41r#T}8LcJ=jyM;yLaf0Lc8pCh%d{FY#D zK2`9(16WQepU_NPOufqvS4)h{4dQAvKZWO?Dc4kYH-t~RWTg79 z4K_&(eEA=zJFU!@9E`y(QRgWeV#=4UlJ&lz$omv=?40U071Volqq=gXd3sfdnn!@F z&>Z(79OMXB3k!!Ud-bCu9BHvR1asTVlw5Fymp=O{EX)(`8&5^;8YB;LH&2^G(S z0&nTzM3a`z-n8z@_K%;{caueJTPl07T-B{8{}d7c{Gv*6LF-B ztAjw|*m;EcO6Qg4%8KyAr}$>kFU_fS-b?IuT$?$Jfu<)pZpXj-N%C({nh}*d&3_WII)<( z`o2sRtT~ZxAW&jydx`;P?IBe8cLXhs4cP4~@^7Mshmww&YF9x?Kicgb-^mFGo;Sdc zL^g;hY5yh!tvn_!XOk_3QTk8N@O+bmTjj`=>#m)6L}67Oze`y7b1gE1Sp__pj7vpj z-!B|)2VnybKZz!5kqD1=#R=T>-03081l2d`G1)IMM|bt%R-&627~X#Pu*4P`f5Zva z-2RKV|BJ2(-r$x3u&>fTRPHh*JUWf7uf!jpl5x%&;3vA-pu|K-m?r)JS2 z6beP??ma87!R2OPwmOwxlzaO-nY?@$Jzrg7Sfg=^7Q4Rg{e5+UAEEw9bZ`%x70R^@aYD1bhm zjw35f{w4&wsPIJ2QfTF7)kg>hBRy^vH5azyZCAppU`EN>a`)}pz5Yc(7{RcnHNVUQ z;+Rut40%OikT`754Nk0DNNo9_&1RrsGm7)fp2T5Ik2j-&-KcgpqPQ zJZx*Auz#V?txAJ6orE|pFT^6Q^u)MxL<7R602y&)L1daB9NA*GDpU`C(OA&(X8BnP` zDDMQeB&bN_fmGsjOL#bOHt1#6Qnvevmj1hjI4zX)vEoq#eF~X7VdcIEy3zPN!elZ| z(KZ1vFtkN#u%!WNE4N^L;$YW20Q`O^ypX9n>Qu_J_HdoGTEXD1KGsVONjN6wxk4nH z0n}quMuChBIC}Q);4J2pMAX0ph_T>}0ZQG-g6rMm@vtutTmBG~QOU@iurly3i zwrvt;M`)hdz5RJm?V+>2P)7XcMp(Qm&O{wUkZi@2PP`l? zf}z({#*2!)QKGQPU}*5g#1j~AJQ>g=4i%!LXUP8y?PZ$6F_n8^oT0Lz*`Y z0S%gVBnDt!NQeDaCwP_GbxoAowfIB-Vrc{>;d70e?DdwH?ofVxvCFJDK{^QM%d>%2 zntixkZ4xp2a@$lm8mfR@gLS_ztYrPM6_of4dQSEH)O$2`@yqtl8ov{29fA+>golSZ z_|Wpa;<^7`{|^Wf4L)9NkMX$Oih)*q1IL&o&oSLaJ>B`PRQ(0WIT1~-Uk@2Zt7RS} z;#`1Ggh>AVChsPu20xsU?Wz)Sjd^J@S&1-o%EVtRKjPodZQ0frsla^)O{w`r+qUTdf0y#SZvVOu_Bv19T0hSRcIe#;$ z>ip{D=6b0)9E1%|nKam+Xk)t4sq)`Guc` zKWRkm8Z3U*7Mmq;4%Strx5jYz?LX~M>He&7CRapl6*XbJ7chg~3=VtRZxuL0xdZl-aTXE@o%g2SkC;-&S8B)arP!Kq@)hP<`Bz($nzn za61T{t-fDy*2&f&KiHf4KB3M9_ZRk+?T!}Jizvhd-51zu60CogmJ9nc)2KQ=Ye|*b zb>}B=lCBTS#rQux#vEOE?5HK~&+s1aRuNEwquQ8#h_%^NeKyG!O;lb;$TFp<)x+&| zI!ZioU&~B$0%>)pu}f{NaI5JxE>9ptLD@N(jBk2vB0E3OZf!cmw8d>YF04OXmQ(JtZOslR zA`xND zYW`ur?~t}hA`r@wWXqQc5t?CF_G;^@2zup3o`}>#vO?^H&z(4Edle?xSFPyIvvu5> z*t@YJ-*C8n26S2Y4_B3Th4^*4t;Vm5JwE{Xplv#eQPDAYzk+5LeaM5mVjj^Hr&vo8 z8#TXmFFo`I61=S9RzOvMhQbq?ip!K1utTd(AtC#pH@ycp&Y@9T!$j7ZCwtG&EThX9e=rP9T1;X8kWcBWd;-<;c+^cYmS<%-3^Y%wpZW)zYa2Ggt zsn)j5rAZtGY#0bBOwvnA7R@YvbxM<9!=(`{U*{0OPZM{b7c=A^@tGWEU#$!8<`u zTjEQ_Lw`m+p_8D_cubxIrs55pSpOs$jDtgHuQ_9I%}F%=if&tW>+mSskT8us3^oq+ z0867{FaJi|IS(Y=m2Bx?SE(go68L|c-C&Gn9(QS2H$JntwluHy^Jni_KHVTS~tP&A{pub)DH8 z_Ngh-mbtt`?)K(5E=vQ^gN~FA>oN7jb+gw@;441e?cw3Dn(yA?)JxgPv+F`{TTug9 zYFFiX)o&$6%TRa%tvX0@=RvQzdF4WjNT|L!Lx}U0>t(KvIq`?D{Ce(%4%qnP(>~+5 z2r2PY-!jHQ2gs;MVdh5(8B6;G6D#*3)qZ3?p|gnBSZnD*aWZC;%b3CwiEHGN_vs>w zeN27cID9X?0Fs-gky@v6(f$@1rZSb4-UY8MN){(hoqK)c9l|-e1=VvWJ6flw$+Y-e zKtR&Kn={g7J5!bvr#X_Usp)n*<9S~$7UWT&73KQ8Iw7(`h@w=8ry~Jex+~Vcs?M@@ zsmLf*Yyh{S`u@wny~$$a(2wDO9Ll}z099Mz^ZCocxq3De8Wi|sXMP4X=<$X+Ufo0E zTT|B+=m#73plXf?Dx_rw_t(=Xe!Y(DTRuk_lY@%SVKkqPiq z)m8ognw5Dfs5f06+-VDM9XFAhdrrJb(O zsL6|?Dk_cYuAYGMlhph1$-?D@`C&MHO}KaI3l!Bt**sk^at=_n7O3vxN7#nqWpwXE zFnhUwv1kjf-Pidv-Sf&(FX+G$+Ksd2&aVfWEi=fa{XG@N3Wv!lEiRT1jMnUDJQ)3S zO{_Q=Cc{YGp7q$qN+kEVlL#gLUg7#7hU539ZT`(sVd zC!X|wRK0gR)$jiY{66-`UX@WtLUzN>RwyIM$`&bm?{NwVg;G&wC}r=x5=jb?y;t@g z$2hoOr_b+uKkoaV{-_-9>wT{Ax}LA+AnX@>C&om0N{*-8e#RGyjRyPM=p`cMPTEc% z1vz`N2R*ZA-04&6Mg__pUjl>`71@zP*@;TL3c3%IYO&GYIvMBb7p;GIqHmPEy+{ZV z#81YoSIjU_LH94{Ggm!`l`j`ut1{!~Q?7~xBky_|hY$>Pm4py=W7%hTSv)ChOZ`_M zmPZoYUbQ|y7#sDgzJa_6o$f&k2ln)ldLao_)lXKWH!m+?blQOL{wVvn&wg%J4yLTu}YQBYY!|q@587B&o2RI{2o&}Jj*Z(_d z!-r5yGu$^5ki`3>YnsyYae_GY!=|r|exU%BoRS&L@i)C%vuo)gIWU_mt?)N3-pZ9G zG{7!iB!SU|s}EaKo3OZPg^v1I-NLMl@Y>;SdR6}6h}TAdJCe|Mfp@AU zvaVTIKb*{FwT{2;p75RJH+dCz1(2YP@R}uNqlyV+=d@eaV76s!SnK4(_Tmip3!G@M zz(S|Rk^i17zL#ammWV%^FHh2A#)8b$hfAGkK(AY1dF^W*7#ibikO~_LIi31e_%1}; z5YkL9C-ZUn!;QU1!w|64arK!*ts(@^gn^S}Ie4+d;*>FY1-8kJK^j3e87no{Ht8@G4lKQ<&ho%<7I ztjqMv5=kI}n~aK06z|IVQP~ja4p9(HV_#EPlbB^%HEFxvug-i_3EN9e#aYB}Bswef zdoyLI#E^gz>>&zg#47nRO~dj^UM0eTLqbHq!$ed_+Z?mv`q zit^P`zfoXmjxcb~y%xktAChoYL9uNPJ)H4rS8#TOUV>2Ij$0V>%9x$-cq8S_wi6sD zwwC4t{NE9q$J+dULMZVJ$)T6_;HJ>+xC0fAheyL|5RLna0QbhX=st$`^N8k-vEgG$ zO!$fVvWfyNK?aPp`*?92quBnekiQpL%vT+{>$hAhJILk!efI~N$h{@%{!BU}2KA!a zuRZa}n9Z--k*et`gqg`%QIB7*Rv&B^TN6O{&#~kJpA|u={n0l#OFn*DVETi?jUD^O z4f(qrs@?|XtjFdtK`TW=)}D$KTv3}PBzn}y(D$2W5TU;VHjjks8Rg*Q71sGU_xds& z9{x9#@*;s&e~8@vkso*`&R9p1y0Vz^>dBTn@Yj_eVo5oClmlVd;}S~pv#wvbFFv7W zioNYMj26~0oR>2^c^wb&?bU%LGXoDn(0=Uq7uzFVlWvj=yvI{>h?tz#JGn64_k{7^ zfuSF3_5DVD7Zb_=yXn5|RzC9a9a)3+Q&WebLCI)ARE70T^VQnzwjo-~;b7llzSFKx zuYkwEW;?@i_DXC`!z>S37DQ)~PvM#BUJ})Oh`!#B1KZHC@*6RNqxvV$XT;z*35^KW z+Jp(CW&WDAQv&dbpCC;-z>Mk5%f0(S_z6p~XYT&n4}gtd`1ao{IS1mri(X@bM_T{3 z7m>3hmy7(xLjjh_K05MOF|nD+$tF~c`yN@5#nju(!1ww!C-!&O2jJk7t?SR6<^}vx zEfhn70ZB}|q)MG!4wBUS_+O<7DE3LKj2`;>|dpNzd#r~S;u)^>?3qD)b~+@2g_$pXLou@bCZ zXZ?K8R%|1VTf%zHv|P`cmG?4E0D~}~95##*L&ShtuP0OBSeDD}Lir1Bxt^;+N9AZ_ z%r(+Sb3?JFZWTNUJUos75%Hluoi!l5e^yDJK`~Za*mD6N8{G!{I3F5myuVKIq_xy)BQ$(?;>nZ~A1JbqL7R>v??} zV`_7wDR%uKp`k;)q`JEn1H1)vB#?;cT|R=*H>GnNycew-2jhU7qDZGxZ4XG|zsGuU zWR3P!p;N6Nns%K<5~MJZDPD4*!*rf2i;?MYsw2O;{c88b9sKTmG~zWnV{6yb$FD3p zdN9vJH^YD8BW!SwqMApbj9`#S*A1r@h8jEZ@9jOLA5;z*{r3D!LN=Hoo5 z08qM8llfAyrM7{sVFushemiyZyk^V;@`GfWs_`DN6DWr;-oZN~#P_vJXT=6t5(q>P z`%#5f*; zh=1>j9OU-@WN=sHl8e6q>tKhr6H`gp?+HkwHYk~7K}9Qr;SlA+6>AF-I2+t8dAc%? z|LG|=k^9kR>&$fU0W=Jw<#tj+2yv^zCYi1YVh!J4_*$EUz)Nls9+qgJ?VO1SM+6p! z%51IkWt*NAtUh2}xxqSDMyyTQP_^ysVVt3J{7YP1Ix`Pp>#?B+>oj$;Imh`YZCz_2F7swXbpyl$Y7L?V45dk}ug~i%(mgrjCsE@;7eBT8j+_x9mdMK4Mf@5X^ zy@RwET}n0z_7#P7dR%tabcYR46-&?Rs~|#wE4?`=Q$HX|-46eH0;NHAF;s^qB<4># zJ&C(M-6BPEGgM4$QiRW-PKF&oCCA01@%uHPn>p4LuG@^gCv^TLI?<7PU|-40`&Jc zE*tXNx5;EP5LB&ICWzBOlFK@dhLvP%4&}e4J+*^Iv8TX+uc&&FS`)fAPftM$ zL0rqQpSIINsRwa{>_gZQETy5a%lNcVZB8~f2f5#mfEanSt1>Pegc=Rd4>5_Pq-bab z+?*d#nMX`ZZyfC{Xugx#AQSN^@~_uSaNQZObj4Kc)xhONqLB-qXwYa9i;okOm`hWm z=ScF}>eeC*W7n&ywQjqu&3l0t8B$OQVZTTKee7>TVxtBt``t{KbYIdTgYo<4h}>hj zM_ZcFNc2hcm_F~)CuYB-K;Nk`Yixug*pfb^#b^w@m|VXBhjxM+UAA89YHSUpAIaWO z1hoz&3KETU_hM$bF2og|BW=voYR$1s$k5-RQ61=0eq|VeNLx09U;HLz1 zE^Jfi-!Hj-&~{cP;x0o!rF%`X>RYc7p-mzx5ro8*ZZ&+1;T1ff0&d=I&iX5*;Zzxnk^2U;t_Z#yAzS#!C z!#03ZDx57Nxq@Nc*v0Z9JYi;I)07s%xSUwhw0=&!uEhfi0xfO!*@XAKo;z@0|&kNI$^&Pa;K)gsLKyy$%(|e zTkw0uX@E4IaB`ri)>XnD4ARi48te_gzVp(|1Q$5BcDj{U44M!69lMwXj7WYaQ=Q;2 zuF{&l`Y`@MB&9yjv`Okcm5Y!3j}JF4SqxR54R|BL-5!3r-YX&sU$(|7iNDhjA~kj; zcV4NqwDjrLNY76ohf~djon<~S3dm1!CLi_nz^Z5CkTn!x%cv{DzFycY6pfl2Gb7v9 z$$YcI&-mSnU@iXQhaouXGIxEj4Bo{;5K_vsw$Zk5X|Llf9P$))d6Az9cWHtUZVlUt zxL9YTe*HTT8ws&=5WG8q9(Asxkb0f7rF_@1YKdpG(a~1Pe^# z!?sTJyTDt~UZEbZLD;U%xdJ$v<%uT(#oBnR7(1<(#~iHK;i^A3)R;fQdM06?@~;T8 zIIsJ7gad}Ss>MmP^@TL7nwvZtj?^a@PnuYFZcIF+8RCeyhE@v>U*v!#_p`n^g!#KH zX%9hsZn;=})U)5|wdH+1qEE{%75=;#V+9`H`1|I1&VG2kd@zUzyze~6z7g)rj-?n8 z*$D+X)YpzO01L4ObsZqC*to>R)X*4uzwaZykb3fO^PFNi{YRJv3KSH-9#OStAif7aHz@l6mBf5_Uw`JGQ}S5NH{uz5U>MY;j0lC%c543x zBE|60i8O;hM(Ue?sZt6lAtq_O{=o}e{P9uwgbj4+dJfJV`#@*A=I4*swvP-vOclvm zr~W%H(F{}@?51+0YmU`>kxiF2*!xp0VkrQGewKl+uPi$?NS${ez11Eb(E)_}(0=cb zqxqSTS?38P+TZ;8PahgV+6)$Qc?#NM)m^40Hy2K4*+{OiHPBo|w&v(o-f>;6T4mI& z{zlu`3I*Z`qYF;PhsNMMSkWICh;0?%038}4UV zyuaP`DY+8DTfpLKsXnM;kxqJ!%oeDCYaIyaWh_ts`ljnXe_p6fhd?R6U#1Hj zasc2il-j(yPpukJhu#=eMM!5ZtMiWwz%xY%N#aw+XnOqImhbxP+MG2Yn@feVa_i>T zzldIVO&;aAONmJ+K>^I+0j!K;;(mpw9VYBd8Bg-xF|$DGagRkvDVed>%e&$QO}H!Q zjFWf-;m;J$iBC-fBVKUP>f!>n<)g3Egi+F(>X>=sAwAMIkS+FvM=8GiiBd;NBq(2e z#P9}wEA;>Nx9Ea9EWTn`%(kMR#6YPSOxhML?3f9XpNj3?Z$rsG*G=S3K?fdSo}ipX z1`V;bAGx!kZD_2q!nQ!m1w<#ui0ySeNrm( zsCRL0+b1QS67DXSKUywh_`GsGis*WDZ^95)h!u-Ubx{ayS~Pgo-nE8@eI9h&liwtV z>>l}{iLwo<#gYgL#!97N5ujUj7~RT+tXq5PK$C(TSuz7|i;ir`sKLOe%% zN%}o{2Q$8;%DZ5bi51cx1|oGyl@ND)8L3k(F`QdV75BcDc`R<})nvLe0Xb&>ebF^E_#|y? zM&!K~#mRP5&Q$X2x0l^H(etUkp3xEnz-HfGFN1*BNxwCz)hdsMBI|`sfKpD7(N)Cc znf&Td0DLhjU!OCCHV8*#ZrI-)#STu7)3ZG;5;;aJ{tb6dztDzm?W(mwd7djRoc0qtBfOl+n>+m_FW6%ema=5c8q>oFkSm5(8!SN>6 zkack^l`yOY9rvvrOg8(r0F5(8`t3K*{uEv%`2;fLp}`$Jp*afMpu=qcGti%W5qbn5 zc0aQr+=9{rE|8)OxZkukG982h=9nr&b=U>>&uUFJ0_TZY27H_y?s96Nrw6k@Kfcyp zeGgyu1nIWVzlrVl;z{%AkeIntJnu~=kYLT!&nF+Z)kb*RWLd6Z+YQ|HszA2e4d3l6 z!iu~o>hT}uMZwSj6Y{%A6%gTy&PnafAg}M>vH<>Y-+RRPMi&s& zCHNxc;&MVUrp4D+@C}$5HiE%FD0_N>K@U=AHV1u+Am>;OTw5EFxe=T?*xcdGAxU@uB9TdyGiE1FC;65utyRD9U6EWW$hhO)op z?S6r%B%6UfG@haXV71Y$#o5}!$CS#WPWl(=FuHr~sAIJV+@|Hh-s*29oD&~1<{o=o ztcTnCE}K8;d6(%>A*^wen2D1`*paN`13wa$bV7?#YE`N1>ya`{kS02%FP-d-Rgbzv z22!klXdu*n_4iGXc4(ZkGS-hhep;y}jnU=o9W33b%glKm1qbFdiJE*T^^85+YqYU7 z6ROtwea@Vx$EWedjizhaG(q<-Yh)Xce3{ zA&Dff{dg5$8Wk!~nD)VbbKML1lgBP{|Afecm_QqY7F5pNi;G~A%Lc7o4Nj&phO8*5 z(6B9+{rLt3Qc--v#n*&+%NzEPW+T{_qT%^(pEHAZ*J7;G+;eXsnmiW7rB^Cyi_|Nj*>@yU##~di zUwI#hb&Nz{eNBxr(MH#=g4_ab0l^ZOZcg4%4}_5O{Bsrto_Bpbnv+mHq~t@>7qU8l zgkvgu16AQ+m#Qzk7YK)VU{HDPMa~1KkXPdWj?or(#Om?bct;0*CO&g>{o*v)?Eb-? z9wwupQ5KIt1Zh~2=Eee4b=|5O&z~Y9UP9pOZ7Jf>M5osG<4mllJ-s#I4xAg#fQ$XG9JOsQf~XfOw7Sj;f)2^ zoO>()jO7|+r{9Rtus8g@g)no01@`peUs1aycm-gTGjjNj#~vyaFfi+KC@pO;^&`&K zF>Xo%0*dbr5r+@a?u>A4n+lLOcFGq5HE%;(A_*9|O7d+R0SS#qtmql4OntZ&^4vi6 z=f^$(#%zMvzV+8hap#USsPoBLDxOU$l;y zD+>EAkTGnaj~sQ_5%kU^eb=d%38SBTsXA)G-(oOWOOELnu8=3-KyqWj=kxk-<<;KvPnp!Wln-OYG{dbjXSiF37&uU`lR}fEv1Ig86 z{|!wSxk>n{pYkQWVF5saKkwG67c@m7B8~Z>k109&cf&jr5E|6}CI3PaS-rghoWx>K zvVYo?Wl7OGkA%74=qw+P1q4op1EUu;n`E>4u8eypVu%i|D`$f2J)fr%6!7EE%+Xs& z8KD~zizf+>K%hAk4_CEIv!(7ed>Yz17e)4W@U^zKg-~F{*`?M&J6)nn0~hgg@2cHH zx>xqo2ne+DDz8^utlw2sUOOexsd<=|kw`S29<^b{nBE<>xAxU}`};lE>L_={$SycZ z)IwKLbbGrs45O!UlyHK>&ThNyNwd>9hv#DvYIU&BWN+XK*e$&W&FZDP>JhuacXI-s zTDztE3fw6XAbb%8Vv?{Ci9a?8`~sM5;;5h$d4x_?y9g>X$N!Zj?t@Q1$wfoh+o{VK z?ewLj?mM?Up%hjIoygp6^;yw7Sg-Dn^5u@dD^}CbhC?e3XFS^sC3m&^x^Vir$90>U z6~5B|g40gYCz_%|GEN(k(m&-P+5)5+YA0-_HjkKN*u^*-GE)}F8y*_O-=m~>;^}-IE<%%Pm5o3c;pPWo z<>IMQBx%knQ>(t+=tSYvy`E5`YV@Z>#k9#B|_xc9)x;F6v&3*wF~dM}mS2rX9rqnur}c zt?xBPwC30Gb)DMP*8C?40@(hxdcS8Av35pcYXmI#`RC%)GFOH@z_fQtk!+4vHJ#94 z=UI-)kT=>A{gHayZw19HbS0lPCK*~bZmbV$>aAbJBE!|?L2n`IsPUR+7Sy|v7~qEA z9(DE&rG04&>AYXv>9ezck~eRn5oM-BNAe_= zLk1IsBRnZl@LnBQkQ(b!DflPHxxtfDKrOTI`sU3cdqU7M{ojLEBo3lk;K5Jqj@^X7 z4ELpzE2je;paCNhPJGvp2IY_dshSE94tFoD!mNvv_jNI$M3mR#CE1u#h9W<}PaV6I zr_F^v>hj~M=TotuDtAUMKc@WOw)hRQEj>yD*!qFp{41<2)h zaGuv#{&YtBSWxip_aVap8LtkR(X`AcS}98+kQ2{~c1UYE{l0#i^AoUV!VqKa7s-;c zimF#K3Kp-Ep{Xha5PjWwni!*Ucmr1!smDn<){dm_F!Yuw;eCFCPATGUmEN-;EiC#( z2o^833#ZBnE9y85in(!n?iEW#-g#35QgAU_Ve1R;!f%C1Ar4{PT`E8M48cosrTK8D z_;OSvcrWFVKnjT12;=Sof34e-^I4vvAVN>N!x~yqK&t_h$?%>KqOy+7Xx4tPKYCL~ zdO-zPo3?bAtfY$d>*I-Tr=2z#6w4vmW{Ua+Yn=|yc-=u$B8cA_=6?HbYh=-!JK*Te zDZDJSoqjEH?J!VLwaO*cNQn&nrS%5coWxf-!T}bHbtA^MvC5!{oF8GKu_Yr{WCUog z?+O|?9!gF8oAvBT0<&xkJ@wyujniwuk~4z7wM)@`z(BK4)Dz zIG9Izc|IZjLk=H?0D!ZOL%ID$ift&@S!nO2J?sXevW6Ls_$7ma_1IUlBl?c*?jnO= zT6*?>#m7vq(Y0j#Q&4~cbqCBO%y`HQ$xylU80(;5zT<8hxhqE|=aG(t%)Ft(mN#(* zN@?c+EqDg5hHjEC&J>)4CLt5Sen#vKCClvgOt3Oh5?ig}U;D;-G%NTqi=rPY?GJH3 z+Sao!KRjMEYtf0j!e9*`-BdR(vlY`5jHWmUpQLhu(cPi)l6qW%<@7UlyVy{Iu+|?NDNF*S_i#IGuQ^Gr}FlU|3Xr)Wk*jXEZ(7pCdrx|JosU$W@l^j06Hr=lZ= z>xHJDa}LP&L|qg8eNva~fe}L$c9>8-X`xn24_hS#SuM({a?sH}{+R%_L8Q*zA1&z% zZ?dfWT?;kfN&|V~3{TngkY>G@`_%LF{F}^AFTn=H=9OqF35`hFvH-xt3~|Zlp@M#o zADtv7jE1ybB7I$K#7hg!jZWgxbiXGs>q~8}%O%z);v-gE(ja0xp?$u6zm!3^et4~z z?-=qH$01bPW$Luk&HWK|IER`ZIZ^?~H(i5u`zS+6USGG8AF=rYeDUv}>kjZ7NXy74 zW8$MHK{VOr`jLG`u$;(q=-1Lo*jGm2g)F4IB15!^&`S;pe3Nu@`|VN@r8C4KO^j|% zgSatN4*U)Bv08O z1rOod$PP~{Xd&x@-6TQM1sKeu>Q!d#c*oiv+*Rq-CA0h4xlN)G#IqR%aN{d`F!nii z)MkN#do{0-QRpGhg4g38#4CN*Yxixxc7PuWDZ3TcA8()gVd!O`xDIp`@twttHxlqG zLNO~n{JS2HV~9~;)m~eUolj4;Ul}z~=cw7wBJ0C7v&h#6ewb00{&BF{q2_3r0xWo_ zD$|~FkBgI!_x&Ap38Q^f`<=30YB^9A`!0pB0+1`)jo533u9fH2{-9G2c9>Rg_jv4@ zR9-WnJ1ZE_B#=(e)3sI83CY){>h|Aej3jWO2K7e1NHu)O1%nA@kYp84A8d4hT$;rP~XI^+U(ktlO5CoS$<=wBHiEY-Qe{e z@2`4tO{)RP_x~y0yWLY}<_DQT>ELlHR^+!!Dm`YCk}eXj^X*Q-ESD8~)k$e3T#UYhqX-xJ9!@pP`ZqorURSG}-T-ihU_bXY)Ggbekh%0L2DT2Jg-y5HQ3o ziK#yt^b4x?9Q6RC0hpk|2~6&8NT$n%BzYQuR&MNor*UcoH04|ZQy#N-$>lIZK&Bph z0=3*2&|99rcTs$ljLq$te^9(j5F_AM0@C09dcFBZ+gjCe{|#tiep5z&ebS1ZFVS}U z`}Ej)s(NAJ!63xSVZhKtFOLX(PKC#c&Wi-r1XXIM*OcR@A{P}NBykP;&w_`tqeVHIhRS=ZWm1|k+1e%7_!Jj+R>onD(VI*fyFtlYQs zczsW#b1Y!CR&K$0n28C({*Gp#TTMbmpee0k;yA6kx~%=&$g$pJS_K=7PW`_f^cql| zC?**17i26Vnw%lGnHA+(ZtL8WGuE;GFkqvAidR;khkbdvh`hN&3%fG9SEdn@o72v4 zKkeRFK=ZLwM^OqP?BccMi<(yM%XgDGd5F!cKP87%N%`SnEZL00=y*|}Ig}6b)%k{8 z>j_iKMvR3(#_LT=bH-HaiR0L)oVuO$c_^u-T<&R5IX5%yES`MxQKPmT6cCX2`lAOf z42FV^S_eD2(QQ^~j%XhgL~Pb#y_P=dmy4V@Id1m1P54@Z%ZLXALK5nHe9G${`iw)6 z=JJ{5>WTayre%|{x`zC~4?;Kp?W%dKu&bVn`l1s5r8Ex#BgrrMbgyzGFzFw!Q5H_> zkWv7K_R<-_F7r1H3fGZ&apad-{a_5D)4zUvbQC*eAsd?>MSo0ligWNgubfsnFu9c3c+q&>4-30KPk@U!-DK-2WYQR9#ih^OcZ;B)C0okOTq;B|CQB96T$ zyjLXAf7{=kXFi$idAgvP`KX1%PoT59{3&NoMmVjO@z00+k*b?N_&4rZ9hxVMy|tyQ z%Lb}zG916)D5?DJf#t+ z>I{#n#X3GL2ajXHnhB9oe@BHhV{6G-nei89jL;<%du6?Sf$*cF| zCFQyfexm!gc#$|7SkWXb#z@VY;?z@>b1EMpj2b1urd^s_nRv`8q0ekl`tTgl_}Qhx zu-(~93a<3P8j6woM+HxZ{!OTbjW<*Fgp1?uhGM=u+U|xUtm_2(DSgBqS^gU-|V*RK->6J3a zeseZx3b^B-`szIiDfNjU>VfGz%}=?CQF5jg(s0GBx9{A^-Zhk4zA`?a36^@)s3Z^4 zwGi?Tu@`0&yJ|4@FJO%Nv$_d8FS5%D1{LS*K#S| zS}BR84awBf>YI$uARaf?Jl@=}YuVWT1y0zzK}Ys|Q|PC5!qi}$F}`JPmvhqUeRUKe z9*(?=MRT3Tk1;#VK^^mbP^{bLgPs0ik;0I0e$`5Cxqm|k zZRf4FGkZvLkbi=PnW7B>T8>%v2YS$#ed75^T6gF(K_4n2{ zOBvL!-(_z|G`*sk%EY5J|y0VPPFx{n6oBI3ed;Mxni>s%IUv zxpcEJtM%AXEkNa;i_uF4b;uf#oeIq}txI1j-1`g6{03GhRk{pC>;M#J`XmGpf!_XNedw@u6-&yr)j6qv|v5n@KXm{F>fu8m#&U_+GxPIfI z`!a*#k|G#yC|-Hc)pT__186Ezn2}KYk<+coKjQiG;_oM4Kr1Hp7Ac-b^pc!Lq_%CL z$eMtHJMPB~^MmC_M~CU;DIj$>xuZ`A_VWHmmGS+5$h+gi2t*36LAya$(lN4iM)?Y{ z@NeJ#f+s1(|NNE2ox%Fy-jP|VKTwMPdVrTpzk~SZRM`+U=wgmtp; zV1`*RWDP8D8YqRmGjCtKhE4M9)=10w3>sp+jNheNWQCNOx5&`S!C8EO0K5ph%@POH zfJf3ieXP)YF&@u|Z8G0lsebgDAD^JyF2z4+cO9C1H%Og3)zoxI*Cv}AbhKJKShz`@ zi|?;%cvn!2Y0oQeC#@a0#(`f$W3c!`f*ixCpcBANG~xn%n2zM!C3D1iETDl-1%Z1+ zna47PdeY!6ZhpL?-_aZb-8||ubP;;9uMud- zEt{->^7b&gf(vJ!xiK;=oT*zrFpX1I_yE`UM~*TE;j?74qAKS;tmhwjlrx;6d5I z^-<5ck_$4v%2QqH4E`z~0GR030{0&L6E`sfCZ!-TchPKxv@q&{j_v8T$0lP z;~*_yt(ZeJ?RX7Gy!5L*fA^kqd|dJYxWKVILzRJWwr;d?hB*$Ejathd-U;-lr?gBz z89YzXu!ju?NCm%q{(U>KAZ{EDWUZLxKnnq>`L+I!wnd;#SCW59J5n1cVcQ0;sI&u3 z;B94Rv(_u&53AiTY+&?b*}!as#F_GijJ-J5V-02v?_w9J<~-kYSDk)G%Ve>Mv~hcB z@K6VnHGGW!i@f<=F9#{78;4So@w`YkDp3sf-V`whT-%k0jdMgz;PC#<8f9=T@!lsc zH)KY?}d11LU;$4T6!+oaN{(GSn@fraU0r~9^7jM&dVD1m!R2HQt(1P^)Qc!3P6$qLPk zXie$1wT>q4tb^8G11?Cb1Qd22@gxN0U8b&T7u*$@k4`zOAS6F$Zx&stPm}ii{R?F* zfE>KmYIIg4a{<;|NX#9#y_wM=;VRyJy919X6KYhgMX>)FSX7RHCN~_( zTtp9@W%GaAfZZSdq_VTQK?xCOJ8bVz+NiV8G}U5wZU9;yh|LDW0=srk#ix@0uIBgq z3%Z;WWPFhpc9z4^!;qmYJ}+48xOlcd;;GWNTJP4KRm4oQH$WRjiRLZM-B|DjQ2wyi zc8WvKyMrJr+yQ2f(sq*a{Oxl)bAMXvq0`*N?E*29haTSA{MAKp0A$MUiJN5W!8*L~f^Lv|@ICe?;sry&cMWogA6xU<6UI(+7t{ zldc%*argK8nhT3l*`(xfPv&w2y71kR8#9m*M&Nw)j(%i^@1gJEJ*(xCcFP>WG9<4; z@#)QTD!y@Qi^ZRdF&84iI>bhl4^@!}!t#4@#zLS4NE|vBg5Y1?snmx$<6iYQ|5ow2 zE6MXrd;=mI;{E^I2@@Ur>Ljl&HPK%Md7a_&@sUciqw*!+a_Nu6nd2Nm6Z z*!NjSX~-5L$tz_P$$)wrLQ4Tx5*#Lv(W&7M>YGRy*i!^?>nfUn@+b+bugBuP3KklB zVh(AaRlp*^W0cCI>Ix2@hCU}4LW_ZhbqLWnC;7jw)Swo@5Yh;Y)Qtr)UZ#Xz$g9iR zGikaSis#|#0=ZCm_D(~3b@@dv9YjFY<^Y{bJhq|9NuTiPo18mx5DNq#82;Bg$eRFh zDNt)1CS3dX+B1`F^^&R050nLg%$&+*tqCAU^iWQJ=~kPTbX-i_`Bk@b4gy=l@u!kt9YlO=sn%)8VW#DC6DOjw5r}AO3F+9o)8LO5huk1P6;hGH z@T?@QY=muA+3zL3Td{7ziDVBxNLm#L@)sg~#$i$wRQwB*Ti%-=eRHm+erJ$>-3Faqg)U zbWj8)XF-p_Xfahj@X>utTctJHO&f{oM&&>s24#@yD}EdCr0Hq8L_F>es#SLBthS0y zoAUz-Gpav;XWHV`pbK$ z?9u4{hdg_AM~8>{x4JbZWI@n`AI9ycd?(xkFMU>_0i8Jp0v;evq`3XIR@x`-_x9?1 zB!;y@tnv8nN@fCcMfG$C~OBHgrMD;i| zp7vChNN00wbfxjG&6g()v`vy+)s7S9!!+=;ZOsAWVSt$YP1s#f*up<8PVxC|guASA zGNS8XVIg}tBH_|S!|i192-}x1Ww+Y3wNa4O7jzsfiD?Tye{-vC@C3?4(@O2ZABF9_ zXjjK9!^?%{25|zC`X0%-;K%lbG|tg(sLX}e3#8nQrGBspK879q?@tt1O`3WuNR00c zkbj!5y6S&~4GEsHk#8;XD0XE%bzT3QfrOBPgUVm2il4Zco=bCbe zb=x27Vy>Ty{&}Hpnn1Dy4hXXl5kw;Cy9)vV7xR)AYblE+%YpnJz zsWY;H1OvPdYD`J}(E-zxxUs3=8@O)($S2nhmWygyJL9|7OsI zH{^FLYJlTa=SvG0TN}c9a+MuJHAaZ8E1A#_qauuwqNrHRd*a}?O7)D@=J;-sRCt}d zOaEvD1=>*#?9arFREzI7kn_Bf4a%w`z-vAlwdCgGbi>sZl;mxQb=^}-{<6_T*cR%u zVdWuHbTYEBP|7B%#`q2Mz(MKfO5>>x*{9G@Ma3BtBnH*d_KA=7*Cd1ALSyP{7$Lec z(KiOjkq7_IcwQoNB>w6ti5bRJ4c6b(9Nu`i;7fEbNA_2@I5~2h;0iezHd6E zpj$=+ytWi`9aa1d1K3&SeES&m({dy^tf2^SPX`QxJo(leh}j;&fN z?;3t~6i*OyNF@2b>ZJc%GCTXi5xwG#f6JUM{j{=;PwH!?IfQ#goe_iqzlBDf2@BjW ztkoZ*j&Yg3lRt(g;V7fcrF5O%gc!((UhaT2mzPHGc|GH{s)7 z)@mYg>EG}9a>Xn5Ov@Rws@#V<7cXiMWhPG6CZ)Xa!+$?;(2#3sP_50%MG`y8;Sk)i z)AJUJB!bzJfBqmevb>x#Y@YE|IX^@-Q3jpaEY1s` z)%rLM?~sI4jBRF>aoM>Efa+O3L&bN3cpV4oUsabYo;fG+rU4i5Coh*}JfXx0eE0>M zvH|Y-(@nut<&ojuLzS1;7P1>6g$W{=$w?LSP4`>k2rJo~0n32=Q!sRBCgbLm4yVz* z0(C}ra0-$rDo%|Sn&RodR%!l>+PwS$wD8}^Zrz%&3|POm>T01R@1}0V@oA8`r*Vw; z)<~S;q8o6wkb=d$$ur;;6p9C$xh$b9g65x^dgdOG1bHt=Ld<)JPUn=SPhKsTW%pEtTiX zA}GecpPR}JTd4av$aa$!kB!&^UQMgWd0q6WP}r@T5AmX;t`=>T0jhg{XFUhJ@0HDl zcq^bJWZ*{LBxn`cofg$T**E(hNo31vp0XesPnJ1kQF^%q=42nRU7s@v*rl3`phhCb zzff(Zf1mvX3V$V1kqcgq6<_=g)+W|_zlH#8Fq=Y3a)LINa>#*Y#XpQKZB)+FzG9Q% zCDe+U04ax5G>7x}I?1ipJjh?1#gl)gZv}`$C5~M>l_SfQbb^&zF&y$wPfp>s^BYo* z7=vVfs3CfSjCd|!`00P!^u;WNOVWNT_?7oIIFgp-qYic>9nJe}eoM(BsvY{lV2@JTs<3$!8$Dqk;@?bEN#(DhFZ__w*>c~vX znVAD%39I=Oc5CA0=|RWRK-F!PfYydtov_{VvmYpR9WpeRExy&G+VqL!w@LLkeH!`` za;SL1`!78pD~`jLZ0?U5&QzB;(KW(AG?~O+LRV~1H782gzQd@TnmdD5i%kEff!aS1j`RK(0{jE6OqKtr^IG*@P*CjxRL#i#g}dO( z4@TlJGh_3J(esaBCgV3a)E~V6&EZG}mlV*$b=&U%8wWH2q-#C;4L{$?gQXX>wAJMf z34G7#9D`EDb`{R`?`%ZjI>!i4^7kn>;Vi8Y^g!!E4J=gz3MlAz$`@PD=(Vurzve zTRXVJUa)Q=bK;p;4a}6)WFn}#r&6{WqD+P7ZgIWel82up3W+@%LJL9`fHJ`iAGiRo_XZQqu6?a7 z2XBO$ZTyEBXL#7HE(7h>Nk-LK0;LA8DH6&Do(@Q522V+F<}JPtLf~ED8?X#ii}0Vu z1!e(?Wa07mqSi+PmrL=VX)|2$kBo^9YcgZOzbMgmscd&6AyV9a-+EstQ7}VH2(A1w za)0Zb_*^IIq%`x%E2@V9GuojT{KsxVL+zsmyaIH_)&Gv#%Yj!5=083!cc_;sI6i9q z1E$cnjLz5*V0>HZ;vg;>pgKV#Zj;OK%eZ`?yD}bEZ@*icMgS#F*Aa~iOV2bHI>Y}K zc|_3znkEN0vAGQ44|w*=d$h2E+!sl3vvLiPlm7E9;Zgyih)de2t;r*3SC5nb#|Cx!l6SLs=?)ZLq^Qm152gGH(N_QDefQBlqi z4m8)*O16USUi^+7Wu61{je|xRVx+o-Ci}kvJpldVwL<$oHW^= z9`vAe6i$n|q4!)GFd240d>^O@0^Ra3W|@(z(0NXY5av3{*$WVmsTPCFORvs zurPf98*8jFwfE9RFak71t+sf z3vYt)Gm9Azga}JZIYn;}3o3*(5&WC7YaZY*_}@>wk|ZScbxM)A2!)g4%XT zA&044%EFu0=L_0|0EN7TJI|%rn;*AoH+Th#U&S8`bsPVl7XO@=Y;fMI%PnjSPWYv! zZN%S5$a2|VqO&dlw+;VX0(K>MOjDUkNnZL#jnC#97&1>~=hrnt;+?jUQDj}ffn}eG z*R^ho}7q<)glBZpYVI9YWHhWlyu1xYG@` zRN!18<|tmugAX4RFJN5JS^V>3f@1{u-H(Iew33I1$GBZBv<52H8Y$NynC@P%N?OQ| zA2*h&SL=Z8)>Z%x_(XM@i9rni_x3B)p`;rRZa7#a1S(fB2};J7%Y$)#^*W|rc9o(zJ>PCq*%$AKMoi`LttW|uODD4qU$(K4KQ zr`BfT%qB5})D1&U^|`tbK~>&zF8b9DE3!wpyB~FkN)^C#%u=ayLU-@o1e6#l;{6v86 zMuMo_6Zj4H+62o5$kh)2COBEbKQuvb`13qb>mQ5|l=xm5w>(^V86PSJ$&;18cdDwS z5g*U?R3aAhs;Tj5 zjriArcYKEw5=dpdaqjn4td{JT!WNF~fF#4>`xadpYR}84*rgajkk8F5csB%cUkLH3 zq)P+E7p=a>T%T!|m^x7d&)t5g@!#V6w`O5I#hQ2#OL+>61U8bxW=?xM5V*dL0!C#g zATX*af{8zH)N|&w{^U||$Bsa~^MoQk0Tv(p95m_)p68P`;saI;!(h|?yzFpZE2yyu$J)fnV(hGtKGq?7 zU~k<%fmV9*>dzsJ30vC^?{z>G=Kv89j`fG0TI(!`t*tG6 zru=#J;s5sz|2>_mPw`i3{Hgl$Z9~f$!prwz=L%^eBpxRkD6k+r+V86u8}x(`otuqC z%pr=iA8h@DjshT569{IcIlaq=*fA$Yy~=Bm%o3YFF9$>?TzN)lLS_R z-0>(xg`HrRy0h57KGh<=e+YX{nPKV6#3qu0`G|#n<*l0p>i2U z%OpldA2&;N`UTl8+WYnBE#6t|T*xgpwPP=^H7YG9rqeF`#4CY08zaL1{j3f~e&gV4 z^93_*dV1H!37_5{cWVxoCS(lrmiO8doPrPpiGf7rhb7CG?ay&SR8i4Lbx`?obuR3J zO|Y6g?>Z`lQRnXT7gg5oPDZ}o5lq0M0W8|v+v~ZT2`|hAu&2yPQM=wddu-q)s|6qU zzt6nlvG7NEINz+^HripR%mM8EFETj|mi#~MeRoil`L=DVGdgAwkPHrp2r7tzM}LVystCjIz_qz&HBaX*3=J0Nef`i7JOQ%+ z+DKQMN9f=Oqwf4c`_whMF6;Ic7LaJqltj{&Y3M9qQOk>hFvW}vT2b6Sg=hi&M zylGvyaN(?tjiFa4`T!X!oVVyV`ZgeF#}R<0l%tbq~3@CoGWA=06t`u6st zsgs?e+7TM3PoI`>d{ab4PoBrRU+U`Wf?`#?MlU%c?VJ-Hef{YCgQoqN4P)^M`E`wj zhCbzD-wwr^HbsOFc4iT^FCi~4&(s<(*6`cLIB<0(0^V+HT`m;>6x)yq)5K9DV)Did9Bk73FW)za5>ddR|PDlxeh4Jj$js;%YL$z;D4@BD~1EoSV?5M#IvpZ~5o4=Ir zysLZcS9aZi?MI^w{{0L#=g-rh-4tPWKtG@b+Sqbmk`}R)kJWgM7N3vyo&Dq%W!4m{ z(ib2S`g4taM`nnb(_^>NKJ+kZKZzliSo|PYQQVW5qJHEJ{OW5hJL&xdA;&Oy8g}N%*8yo~>Rq&K6h@ELpOHDn`}J&CT7c z)>hmyjqX#L!sY1PZq29;44=%}F~#Rtbh>mX+V$08W`mROK29mCa%FUR=B%lK1F#nh z^g6GsM1+)8teq0fGNhMr@2Kg-MC`W<*b3)vKDjEhb~OoxxTV(??U0vP$ z(f1i+|6H6CyVG2~2G&1n3BPlvI{Wm~&6*7XS!?bg&^PDW)bH4_BLJ5!YUzaaeqBIm z|LoLQMUN~QEGFPTFZ#B;87(4^Bvf%Q8K2%!NW;2G%*&HO8zMfw{TF{Ody8#NI_xE2 z$9G#;r(rT>$%Htw?smln`K?=|Ecvw~c8O2Tj^ObQwVCI~QXlL3lqbdXljho4ehWh> z(*W>62r>7iMOef7vs!Q5RV9DEUx$Z>(S}AR`tpZA0w;Hy6;va?_W=P&8PB7GpHCk^ zbfyura6dZvR(N0r645y5Yz#F2XR|8O(x-n++_s1+89 zRzt=^8{U@Oh>H_Khfx|?dd=vhdt@%(p?g1B&1iz=jDX>Lt$h}Nig&Dh&XFv$K#@NS z!((Cu08yNE{@5!jSw77WFileJ{l`9S<``kKT-o)JFw-MpD0Q!am1nhU{(!dq=Wk21JmS(+xiD6G#?C})58{?xaB^k4TUW!<-5Z{XR8Z`q5o_gB0VjP;}b`*F%Y z54!1p_@D`TCF~SC$G+N-K#$4c*B9!(g>2r?+}_B@1yunW7}4ytrrD^5j1-lr{EQk0XM*3!Q|}8|kR^p--}C zL0m1}Nj5*f>&pWdUi=V0JAAq_^M&Bb;lW{R)-RmhMO15sbP&+Z#rOUF52Qts{bHA` zD~&HJE92gO@nlJhZT1GmkMSRy6SYcOD4jn}?m1HUsLoy zJ(_=;cbOyZ%PIM7fRbP&?b)R(GplfCb>tQsRaw7K47R5sf64Sfuwnfi_xitbrT6QsVc2c<~22*{+}l_F%_wc#S=FcOB`HMfBxrh?3QI_oTSlJ^g*XG*H$wnz5eg zuM2O!fA}`K-C6LXOl>Z98E{QnHGBrRHZePUkLvvArzZhU(oORvqV_xRlH>7ve||!( zX47h&8At($CJnK8uxW!(!V<72qNb)sPKR`m(UR}~qToWyLvpGF91g&XgJfL>gVBjq zbp~CGLx3F)6*~3^i-{%aws)6ZcF~DdR#2V&n0T_>`||tu@2l~SmQ8>#fry~3&v_|I z!S;v!d%~9Q$=3EHwPz&WAY6vj$yxpu(FFD9S<*7DIn^-DvvEVG#V*sl9VoX)NVp>X z>6oLXW3^GT_9wD{y|sWSGCE9tj7)CuBH$BtjCy1d+oA6ZsU|Q^K zQ${!yzojWZY2W#2L?0=M5iIgPQhqV;f1zML3XF!faBx(U57GBEDYK(`mzeT2GBV;v zS6eFjv(f#Rt+31Aa-%rbXYw_-oTGUek~Ncb$oDl@aV`(MT%LBTe}IfRsWc17j3-jRsOch(VhQXp#~j5 z$kwgNdQ9Y7gEWwz8KgL$&=fv?{;l`dh9ZoL^_Tb0b3B*~iMe*oWgb<(u9o(m{wxtJ z(>?oSqwl7T%AeI`uwsmcmj5w8S6ieiPrtj$x#d*hz$&%r1M`!G6(Nr&yV7c{AVz*hlyq14J03idYgDFW7_PsalwL5N6O69&kbt+O10Hk-O z(Vfxcx9F0fA|@t=l6Vu+=yeMZ?W}Y&*gy_>T}UZgES|H zwUtijj!V!*P*Bk3k;|7aH>c<)oy1J@mum_QLy&c838N8VmyO{%pEcg(_Z>Grp$c*>}m> zvf@D(o9e=M_Ms8#&*s^rSY0bswrQtPdH^<@)S5MG$fiaU)%og9G*{LA>$~I=mX?;+ z1yvL+JwH8YLaDX=3pZOy&K7mF2EZJ^_bfuyWi=p`DkV_Hl7%1GJP`Vj3&7>V1LdypGgyQ zmj+n^L9;sEdJbh2&3~yM8ePAlG^Ad#beG|LLqkK)Uzg3bmv8!O!>LnTIo>m0&_q$6 z@j6Pb$5r1PGtbEa=KMb6&4Cr6^J7bkV}v1er=_a@-t9?xV~p~UC?*mrFFZRr!l%Vg z)!;y^h(B=kgpa)o(WtBh$gw0waoiNa5xIYQ0bqdRBhYKj+|rz8fwzN^w;;DSDQ15#_ctuVw9M3dYvnZbszvn(J#SgewrEhICC#JP#OVz zDbuJ=0;qkph91{lQP!GYdh&f>eu?X+&2ipe4$IiJ+LqccE4{W+b$V+#GsMYYt}zeY zQET5lxyr)j`2v?Jm*rggt4gD}Af1f09>;5>2Eehm0i!*o#+^%He)HDza}`To5{`&G zI&rEh8&s#?+4Zm9bGqu+>Gr~MP9Th%z=?9b-Y$%=!*39?2a&DaFhGaA=HH$iba_#C#V^Z4lGBdtB^$ zytpz#6JXvNF(;(}f33l8GyZh<)vH(B@|RBOM9WLJ(SWGwxZ;z27{u{c+EO()emrP5 zZeB=`xLn0d175!FuJ6DaGK5aU&^e&)#PdzDDW!gdmII9)0^n(=cn+}(baT@*UXH2n zK*pP_&Qw}C#irq|w20^U$D8t-JyDVM>ne2G0q#;?9#~cL%lB(fIDh~?K95()raQ+h zO@}Q7sLlViF{Mb+OH^G$1GJBKA75_(C|?bYYE3Q+4iFPv8!X6{KDARzeZ_i9pyXof z5@-P>Ba3ZQxW&k#WUEK#jw*vYR1(!XHPwvz<>TAOUg7Q`t?ej(!;4M{?K!0$&Na-& zW@2JOMSIZgU4p*Tf31o0TQwZ3tN7_YFQ=bKxu@!-*NHkyi&GU&?r)xMREw6ModMyQ zo;%IQY;#erj~)Gj=lR>Wn)!c0!rX#|eK-&In)qswkihIUy`ch1wb<8>dfe(P6GM6S z)mjJm+sz=Q#!4*GKEC|XvFNYg1!C*-w^7W*DJ#~$1qM0uI@czp$Yr2W`qH~fyAT0c zI|E@~Wcb0ovi>m%!(SWgM{UA+WNeSS4z`MO`k~h^6OsRsuFDFVn$6fPGr$Feukt!+ zKeUqHOm&;e+1Ds9!hBJR;30-G&AdTpnM6AVM5Aovkx#wEoWgLlOJhp=%@&Ii*Fa?N z{hVA}Ty#`X=1+C5^faJQWhZe*q8zae&|-^{a-98PO2G-dg}Dsvx5e2u^6b6e)#S~) z_w3KYv3pMc1d=Pkb(ykw0+J!VgfZ_KMVq*d&w3|3qj;16GR2aG$ zcO&{)1G%Tj%gMlg_=jjoeIwxOmoE|{X0)c1(ShuMFCB5J*OnQI zOG<|7B_66leiRly0}`2v=HFwVy)*GbxQOL@UcNgTqbSQ}JhiquAOKumQl)+ku_{U=nqR$mrKbj6ocn6|oOEi?Dq1@vD4&zb zv(DdvEGpCgo;c;IY&<~=OC5=o12N!C7hK+2O;&ioF=b}8#9YUO>W4>s*@+}Y5UxX_ zv9U3D#DZ+ zWt#H{`Hbt$W2fmVFD4zny`8$WFhyrYKkxjW3gL3kb;69J` zd)EW}MvjIroIY~22m!`yO{MzP0`SBdWvJm=rw>v=5Qe)fm)T}Bm7MFG1$3cfahriM0_Wa#NSXq4YWubY&@Y7OC&JA_-dm)Uq@W)xWq3Vvzo@NK|D zvFJ-b5qQ{~W}F4=Nn1*_z20=XvH$^|LDHE-`Cw{V0=ARe-a;~%{Xf{oAJ{o}z@@t{ zFEtGstYPEomp3}6{C|%p;Av@Lj9&HIT73tC0O0Dfn!@_%>N<^{8m!L1ZAoREf zT5ts$Hj+{=z#tdF4gp!QhkcO^I$pn-+(RiK>(tgJP8NFFZQdrmNynR@Tul4F%ii}I zCwiA#FBx31Fya(gfTf*f+H@-ov(X$=j>1(-1%a2~G=lTbU~3yrPAIJF{6o<5I0|v%GICxnILc0h=Y$oZ)E7`aqwJKPRazGQ+4) z62!U=h4S-|RGmMN%(~m{lhW~uQF2a#1k~TwRTL-7301+y1oyGGDILZcrksREN8OlO z#Uz7W4@A({`t}i8dDD^GO$Y2dpHf)yDn5K6zSwtRcE|4B8O{7=aTzCGPA&=B(S#Fq=LDVuNOmjWu2#1XCEY#0=E+F zB4c_M0lS7k-qTB6qgI?DOoerXYg0zdN|{E+3<43MXhlZ?`ZfYa8K$D;mv&*bB15#> zhT`j@43yBVhaD+O2Vbk${Z;jwEbkKfWz$ir=~HPm8rb|)UFQ{hI|!Tj^xDQ_!$Jpt zUl&NkIcH~QI~ik#shr%n9#hc1iA+j2K5a>0mruwEP_W}On z4+x_MAw5cdd$v`DFB4j(7Fc^bWh;v@Yt_~>g!?zIz|eqRJ39Q} zXp~G~V~kSA9tNK7(V~#laDG?FLP6^cup)o_DcnL(csIHWeL7kNY$#q+oD(Widg}PBWv@Z)p z=rr_-$(=Kfl(ZnxPxcwdDf-O1m6Zi}GtJ5@EUG{c?8i32(zDNR?bx+Trv^bK6j-yv z(2nAksTC&JjKFGO4*U-`Hf3@ei*+AcWY5861yKqv=hpG;-GQKR2YcGCT4vquIpGDt@3^jlicXOg-JLnseJGco z(C8765pl7b9g?D*kHif8Fg%MD#dUSnMzZuCcENJOL3EIbeeRfPUII?OK|mm_GZ+Ku zQsNc`y3LoRIZq6aM%*xuR=Yz3B z5MjL8*w}#4LLj!@@e(|uS@8H$SO6HkPTl8h@scr~gDHW*lMr2!O}R!$#fKW_K7&-t zp~_#L#oQ9f9x}~6dzjz-4VBan2HjUy336wZeK|tf(!1r>V)^poZ(0(*AOF0TYDj^g zlEhBe69PmfHIU--)tx?%0oL_QO{0Qf?GRYSe@Xo}pJOT$t<`StQRr<}TbgMqoLlvb ztf~%6uicz-j&J03k=sqrZ8-Z2A!%x@>jZ^*p($}IdwizRi~kc&V^5;d1{7zj1nxsvshh6y z&I(iw8=}GCo)|u+;g4rA?1WuVG#emAeZt8v;A+CXGR;jOGXxNRr+L3!YqDbf>P{6- zPR^SA4$FJCN+{HJE?jq=XVSH>5>8OTR$&lDx-AAuhBCFy6Md&jdo$XovlOK&0;FHp zT(PL)G&a8}UowLOX!EbNXa|~O;M$MoS-3W95>hNCLPXsHl-$vI5K8A0M)1cF_+g9{ zKM*5PAiLN@2DS!qAQiMYe@9axbRCg%R6)xan4!9#?-N=IK;6^!$j<65zL~`zqBOdZsd&M{Wx2kJ|f2;=6g2qJkudcB?l*GxP4Zm zOH={j6Nr}iN|sETisyI$;?u6S2uL3U8$~NTZ_F=$7(j2HUB1JDZUr9~h^!PL+rpmXAGI(wDphyaOxGK18ub$9_zJ6icn;IbU5^K9NC4av7}R<}7f|=NhAVtZT31 zQ<8Y$>bHBSQo+@Lc4vRdc`P`N5FpL;ckz8J+QHyBJ<|C@z3>Fp2~ zKRh7-Xp57p;iJ~ zeEcC>_M-Ax{T% zV1U5OY|nW}SS2WOikR%1woc&da8OZDfC=&OTS4iuXHB8z*{*YU6YekTFQxCMBfB{K zML_+$`@!}U*DY`sWcWev?rSaw&2U%A-LVX)ra!0xc+jZ~#8FU1rR0T5|7A= zwzbN)GbA4(6~pK+3z(iz?2oSRm0oTo>K|cd@9g{)hO1o7@V ztAzLo15Eo=~r)o?GFNt+Xp_g4%=xe6n8fZa3r@~|XJ-rahT zA5^C_Hjir(kPm{pcn2cOBbl?yDU@t4J)-u;Hy*va=f@s#e5=y&`M&>!Dhw5rLP2Sb zg+rVLEd3hFi!IzjM5#l5;3k2`d3dlbjYX)Ux+f`wsM=(=$YZOE?A)2wUYr3@4jvT_ z0Ny~tcVagap8^%g=@6dIwO8>|d=VwPlck~KBM5{VU@3$_Hf>P;T#4r4+Q@n;ys}^1 za4+fy`-9d)7!L^e2&BrY4(0%swuGrno_x?pEUZLsN^p2rd4<_!pY?zNGUEtc4LTha z1pb|SP9Q<4u+dhp*r>b-GKYkmq?D8taf}opj)^EKU9M~!i1QO9@T`wX7Yc)0*I?Qb zaG;Us!4EDQ_QNb;kEaPLLJ`SpkVtk8xBPkVS`icx>+z4xc&fPtMuPH-Z;GTx@hxJQ zJOl36aMA%H3_-UfhZep2W$mE&K}Ai-D9lK2ncP^ux&lwC|WJ#U(iP1D4y2c) zE|PQ+KuJ2ii%`Z0Wt@+_yq#PNEFEs%h?vB;OSCKzVF;vRgrFzX2C3!2bFkZ6I6oI{ zhFB?&c__TsL4p{`wgBDRx*p}`vQl=w9VcvnL==N>(_wIetS3D!0ZyWRd5_pzb^qD> zyzzvA0SBo-;PjMfjzx|G>lOyYuL&;+aGfI1&s`5I46BR|D{g_2Cea@v6qA(1Qx!`K z26M!=gE}_N)g1cMpiCI4kzftN@mg>5*X6RLv#0?}`|K|+$C%EoMKZiO3O41fayVx_YOn^A(6qe-rAlyh2;_S z*VAi}UXS4sW}-x>#wr(r(g}KLO&%czc=nyE#6W%#KFIp>&VMnE?^u zGlQ)uR2-mIG}8RUBdce+GRS$Y708QZ*PmC>62nSDIl?H(UJIg2;@z0u)i`1DK#y7y3`O*te*2UUcFvn*yRU5I}@bOLk3j* z+Pl)$kuU~p&F9pm3}ml$8%G>Ngtf2GamcTZq9GR`QsiBp?@Jm!;S z+P6XB{SA#LF7Q`|Px^po)n6ho%if!x_WGA`)PI(VOeK933HnR1^3*fo6{~PO8s7iG zx?-e+6dDnu~UC6!L!ng{`$zVOOoL;h%`gqjRI~Uap))^_^=I)6MR5iF`;eIf8(;`CUp#9 z0^BR+dOQ%IcJ7Wqe0#ZvbxUxpn$RA-LCN2jo@e@8?=(a^To{|$8T!a{6d3X>-wKS@4iE5uARTk(x zHDW@Lpa1-n-F>x|MmjoaKh%xk^_%PNWgPRH)qfGKun)Pm<)-g%`yJnKBUz30;TU10 z3?zZS1}c04*rY(EN)cfaiNn+uJqY5=0j@HbLvl(0CYgv)#MK*q+da{!$?4ejT!g?0 z2mpmbck8e)KHaM&czGMxaudJj4-SC3?UVAG(T?_D1Ts;69?~E_pT1@-p%9cxGVnGh z`piudv+BtTU!QdI;=QDj0fTa((R+^6--Kd%-l%z%LRn#bSmS^Jl~Ik{^H>nzCnYfk zTq*C@fhMUbOCqkLD~6xR*bD~txGZb6)y;Hul(TLHI;TPov>ex@maTdA9g-}E1CSB} zOZI0D4f5~-bpPkH0nEqKMx7j8kRuLLCqE{JDoVuqEzXciXGnY}?mo4ig>REzPGQ^# zd-DbkA}V31<|aq#1(wQ6pTmerj2UDC&d0bJ!Tsmpt^UEjH{NJM?nd9_L21=x1DyROg*bglJ|~7Vsq$%I zqby4SD0NymizcCt@dRu$c+!{x-+#yc0#Wub;xLhv>Cp-<3}nABfMrb};sjE|A#BQn zthQgUMB3uU#33ZWD-WtUz0Dh^zB7Qg2T~}V2VTE^O(l*COlRz0Xo9R6!f*e@QL2mv@hc$IIGJiVt%YOhKd$l &vpMapPointMatches); int SearchByBoWLFNet(KeyFrame *pKF1, KeyFrame* pKF2, std::vector &vpMatches12); + // zoe 20190522 + int SearchByBFLFNet(KeyFrame *pKF, Frame &F, std::vector &vpMapPointMatches); + int SearchByBFLFNet(KeyFrame *pKF1, KeyFrame* pKF2, std::vector &vpMatches12); // Matching for the Map Initialization (only used in the monocular case) int SearchForInitializationLFNet(Frame &F1, Frame &F2, std::vector &vbPrevMatched, std::vector &vnMatches12, int windowSize=10); diff --git a/include/System.h b/include/System.h index 02d5780..b8e695d 100644 --- a/include/System.h +++ b/include/System.h @@ -59,7 +59,7 @@ class System public: // Initialize the SLAM system. It launches the Local Mapping, Loop Closing and Viewer threads. - System(const string &strVocFile, const string &strSettingsFile, const eSensor sensor, const bool bUseViewer = true, const bool bUseLocalMap = true, const bool bUseLoop = true, const bool bOnlyTracking = false); + System(const string &strVocFile, const string &strSettingsFile, const eSensor sensor, const bool bUseViewer = true, const bool bUseLocalMap = true, const bool bUseLoop = true, const bool bUseBoW = false, const bool bOnlyTracking = false); // Proccess the given stereo frame. Images must be synchronized and rectified. // Input images: RGB (CV_8UC3) or grayscale (CV_8U). RGB is converted to grayscale. @@ -169,6 +169,8 @@ class System //zoe 20190511 bool mbUseLocalMap; bool mbUseLoop; + // zoe 20190522 + bool mbUseBoW; // zoe 20190513 bool mbOnlyTracking; diff --git a/include/Tracking.h b/include/Tracking.h index 220df13..e754960 100644 --- a/include/Tracking.h +++ b/include/Tracking.h @@ -56,11 +56,15 @@ class Tracking public: Tracking(System* pSys, ORBVocabulary* pVoc, FrameDrawer* pFrameDrawer, MapDrawer* pMapDrawer, Map* pMap, KeyFrameDatabase* pKFDB, const string &strSettingPath, const int sensor, const bool bOnlyTracking);//zoe 20190513 增加最后一个参数 - //======================================================// + //zoe 20181016 Tracking(System* pSys, LFNETVocabulary* pVocLFNet, FrameDrawer* pFrameDrawer, MapDrawer* pMapDrawer, Map* pMap, KeyFrameDatabase* pKFDB, const string &strSettingPath, const int sensor, const bool bOnlyTracking);// zoe 20190513 增加最后一个参数 - //======================================================// + + //zoe 20190520 + Tracking(System* pSys, FrameDrawer* pFrameDrawer, MapDrawer* pMapDrawer, Map* pMap, + const string &strSettingPath, const int sensor, const bool bOnlyTracking); + // Preprocess the input and call Track(). Extract features and performs stereo matching. cv::Mat GrabImageStereo(const cv::Mat &imRectLeft,const cv::Mat &imRectRight, const double ×tamp); cv::Mat GrabImageRGBD(const cv::Mat &imRGB,const cv::Mat &imD, const double ×tamp); diff --git a/src/Frame.cc b/src/Frame.cc index bf6a6ff..717b5ea 100644 --- a/src/Frame.cc +++ b/src/Frame.cc @@ -1,4 +1,4 @@ -/** + /** * This file is part of ORB-SLAM2. * * Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) @@ -359,6 +359,155 @@ Frame::Frame(const cv::Mat &imGray, const cv::Mat &imDepth, const double &timeSt AssignFeaturesToGridLFNet(); } +//zoe 20190520 +Frame::Frame(const cv::Mat &imGray, const cv::Mat &imDepth, const double &timeStamp, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth) + :mpLFNETvocabulary(static_cast(NULL)),mpORBextractorLeft(static_cast(NULL)),mpORBextractorRight(static_cast(NULL)), + mTimeStamp(timeStamp), mK(K.clone()),mDistCoef(distCoef.clone()), mbf(bf), mThDepth(thDepth) +{ + // Frame ID + mnId=nNextId++; + + // Scale Level Info + mfScaleFactor = 1.0f;//mpORBextractorLeft->GetScaleFactor(); + mfLogScaleFactor = log(mfScaleFactor); + + // ORB extraction + //ExtractORB(0,imGray); + //cout << "ORB feats : " << mDescriptors << endl; + + string strLFNetPath = "/home/yuchao/Data/rgbd_dataset_freiburg1_room/SP/"; + int kpts_num = 1000;//超参数,可以根据情况修改 每张照片提取特征点的个数 1000个,目前是跟ORB本身的个数是一样的. + mnScaleLevels = 5; //超参数 + float Scale[mnScaleLevels] = {1.41421356, 1.18920712, 1.0, 0.84089642, 0.70710678}; + + mvScaleFactors.resize(mnScaleLevels); + mvLevelSigma2.resize(mnScaleLevels); + mvScaleFactors[0]=1.0f; + mvLevelSigma2[0]=1.0f; + for(int i=1; i umax; + umax.resize(HALF_PATCH_SIZE_SP + 1); + + int v, v0, vmax = cvFloor(HALF_PATCH_SIZE_SP * sqrt(2.f) / 2 + 1); + int vmin = cvCeil(HALF_PATCH_SIZE_SP * sqrt(2.f) / 2); + const double hp2 = HALF_PATCH_SIZE_SP*HALF_PATCH_SIZE_SP; + for (v = 0; v <= vmax; ++v) + umax[v] = cvRound(sqrt(hp2 - v * v)); + + // Make sure we are symmetric + for (v = HALF_PATCH_SIZE_SP, v0 = 0; v >= vmin; --v) + { + while (umax[v0] == umax[v0 + 1]) + ++v0; + umax[v] = v0; + ++v0; + } + + float fkpts[kpts_num][2] = { 0 };//定义一个1000*2的矩阵,用于存放kpts数据 + float ffeats[kpts_num][256] = { 0 };//定义一个1000*256的矩阵,用于存放feats数据 + //float scale;//暂存尺度 + string strTimeStamp = to_string(mTimeStamp); + ifstream kptsfile;//定义读取文件流,相对于程序来说是in + ifstream featsfile;//定义读取文件流,相对于程序来说是in + //ifstream kptsorifile;//定义读取文件流,相对于程序来说是in + //ifstream kptsscalefile;//定义读取文件流,相对于程序来说是in + kptsfile.open(strLFNetPath + strTimeStamp + "_kpts.txt");//打开文件 + featsfile.open(strLFNetPath + strTimeStamp + "_feats.txt");//打开文件 + //kptsorifile.open(strLFNetPath + strTimeStamp + "_kpts_ori.txt");//打开文件 + //kptsscalefile.open(strLFNetPath + strTimeStamp + "_kpts_scale.txt");//打开文件 + + mvKpts.resize(kpts_num);//reserve 不行 + mvDspts.clear(); + + for (int i = 0; i < kpts_num; i++)//定义行循环 + { + for (int j = 0; j < 2; j++)//定义列循环 + { + kptsfile >> fkpts[i][j];//读取一个值(空格、制表符、换行隔开)就写入到矩阵中,行列不断循环进行 + //std::cout<< fkpts[i][j] << std::endl; + } + mvKpts[i].pt.x = fkpts[i][0]; + mvKpts[i].pt.y = fkpts[i][1]; + mvKpts[i].angle = SP_Angle(imGray, mvKpts[i], umax); //20190511 zoe + //kptsscalefile >> scale; + //for (int k = 0; k < mnScaleLevels; k++ ) + //{ + // if(abs(scale-Scale[k]) < 0.05 ) + // mvKpts[i].octave = k; + //} + mvKpts[i].octave = 0; + + //cout << "LFNet fkpts : " << mvKpts[i].pt << endl; + std::vector dspt; + dspt.resize(256); + for (int j = 0; j < 256; j++)//定义列循环 + { + featsfile >> ffeats[i][j];//读取一个值(空格、制表符、换行隔开)就写入到矩阵中,行列不断循环进行 + if(ffeats[i][j] < -0.5) + dspt[j] = -0.5;//0 + else if(ffeats[i][j] > 0.5) + dspt[j] = 0.5;//255 + else + dspt[j] = ffeats[i][j]; + + } + mvDspts.push_back(dspt); + } + kptsfile.close();//读取完成之后关闭文件 + featsfile.close();//读取完成之后关闭文件 + //kptsorifile.close();//读取完成之后关闭文件 + //kptsscalefile.close();//读取完成之后关闭文件 + + // 以下为完成相同的功能,仿照函数功能新写一些函数 + + N = mvKpts.size();//在这里输出过ORB特征点的数量 >=1000,不会少于1000的 + if(mvKpts.empty()) + return; + + UndistortKeyPointsLFNet(); + + ComputeStereoFromRGBDLFNet(imDepth); + + mvpMapPoints = vector(N,static_cast(NULL)); + mvbOutlier = vector(N,false); + // This is done only for the first Frame (or after a change in the calibration) + if(mbInitialComputations) + { + ComputeImageBounds(imGray); + + mfGridElementWidthInv=static_cast(FRAME_GRID_COLS)/static_cast(mnMaxX-mnMinX); + mfGridElementHeightInv=static_cast(FRAME_GRID_ROWS)/static_cast(mnMaxY-mnMinY); + + fx = K.at(0,0); + fy = K.at(1,1); + cx = K.at(0,2); + cy = K.at(1,2); + invfx = 1.0f/fx; + invfy = 1.0f/fy; + + mbInitialComputations=false; + } + + mb = mbf/fx; + + AssignFeaturesToGridLFNet(); +} Frame::Frame(const cv::Mat &imGray, const double &timeStamp, ORBextractor* extractor,ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth) :mpORBvocabulary(voc),mpORBextractorLeft(extractor),mpORBextractorRight(static_cast(NULL)), @@ -617,7 +766,7 @@ void Frame::ComputeBoW() //zoe 20181016 void Frame::ComputeBoWLFNet() { - if(mBowVec.empty()) + if(mBowVec.empty() && mpLFNETvocabulary) { //vector vCurrentDesc = Converter::toDescriptorVector(mDescriptors); mpLFNETvocabulary->transform(mvDspts,mBowVec,mFeatVec,4); diff --git a/src/KeyFrame.cc b/src/KeyFrame.cc index 58c716c..bd6a267 100644 --- a/src/KeyFrame.cc +++ b/src/KeyFrame.cc @@ -55,6 +55,34 @@ KeyFrame::KeyFrame(Frame &F, Map *pMap, KeyFrameDatabase *pKFDB): SetPose(F.mTcw); } +// zoe 20190520 +KeyFrame::KeyFrame(Frame &F, Map *pMap): + mnFrameId(F.mnId), mTimeStamp(F.mTimeStamp), mnGridCols(FRAME_GRID_COLS), mnGridRows(FRAME_GRID_ROWS), + mfGridElementWidthInv(F.mfGridElementWidthInv), mfGridElementHeightInv(F.mfGridElementHeightInv), + mnTrackReferenceForFrame(0), mnFuseTargetForKF(0), mnBALocalForKF(0), mnBAFixedForKF(0), + mnLoopQuery(0), mnLoopWords(0), mnRelocQuery(0), mnRelocWords(0), mnBAGlobalForKF(0), + fx(F.fx), fy(F.fy), cx(F.cx), cy(F.cy), invfx(F.invfx), invfy(F.invfy), + mbf(F.mbf), mb(F.mb), mThDepth(F.mThDepth), N(F.N), mvKeys(F.mvKeys), mvKeysUn(F.mvKeysUn),mvKpts(F.mvKpts), mvKptsUn(F.mvKptsUn),//zoe 20181016 + mvuRight(F.mvuRight), mvDepth(F.mvDepth), mDescriptors(F.mDescriptors.clone()), mvDspts(F.mvDspts),//zoe 20181019 + mBowVec(F.mBowVec), mFeatVec(F.mFeatVec), mnScaleLevels(F.mnScaleLevels), mfScaleFactor(F.mfScaleFactor), + mfLogScaleFactor(F.mfLogScaleFactor), mvScaleFactors(F.mvScaleFactors), mvLevelSigma2(F.mvLevelSigma2), + mvInvLevelSigma2(F.mvInvLevelSigma2), mnMinX(F.mnMinX), mnMinY(F.mnMinY), mnMaxX(F.mnMaxX), + mnMaxY(F.mnMaxY), mK(F.mK), mvpMapPoints(F.mvpMapPoints), mpKeyFrameDB(static_cast(NULL)), + mpORBvocabulary(F.mpORBvocabulary),mpLFNETvocabulary(F.mpLFNETvocabulary), mbFirstConnection(true), mpParent(NULL), mbNotErase(false),//zoe 20181016 + mbToBeErased(false), mbBad(false), mHalfBaseline(F.mb/2), mpMap(pMap) +{ + mnId=nNextId++; + + mGrid.resize(mnGridCols); + for(int i=0; i vCurrentDesc = Converter::toDescriptorVector(mDescriptors); // Feature vector associate features with nodes in the 4th level (from leaves up) diff --git a/src/ORBmatcher.cc b/src/ORBmatcher.cc index 4ee830f..704caa9 100644 --- a/src/ORBmatcher.cc +++ b/src/ORBmatcher.cc @@ -20,14 +20,14 @@ #include "ORBmatcher.h" -#include +#include -#include -#include +#include +#include #include "Thirdparty/DBoW2/DBoW2/FeatureVector.h" -#include +#include using namespace std; @@ -485,6 +485,107 @@ int ORBmatcher::SearchByBoWLFNet(KeyFrame* pKF,Frame &F, vector &vpMa } + if(mbCheckOrientation) + { + int ind1=-1; + int ind2=-1; + int ind3=-1; + + ComputeThreeMaxima(rotHist,HISTO_LENGTH,ind1,ind2,ind3); + + for(int i=0; i(NULL); + nmatches--; + } + } + } + + return nmatches; +} +// zoe 20190522 +int ORBmatcher::SearchByBFLFNet(KeyFrame* pKF,Frame &F, vector &vpMapPointMatches) +{ + const vector vpMapPointsKF = pKF->GetMapPointMatches(); + + vpMapPointMatches = vector(F.N,static_cast(NULL)); + + int nmatches=0; + + vector rotHist[HISTO_LENGTH]; + for(int i=0;imvDspts.size(); iKF++) + { + + MapPoint* pMP = vpMapPointsKF[iKF]; + + if(!pMP) + continue; + + if(pMP->isBad()) + continue; + + const std::vector &dKF= pKF->mvDspts[iKF]; + + float bestDist1 = FLOAT_MAX; + int bestIdxF =-1 ; + float bestDist2 = FLOAT_MAX; + + for(size_t iF=0; iF &dF = F.mvDspts[iF]; + + const float dist = DescriptorDistanceLFNet_float(dKF, dF); + + if(dist(bestDist1)(bestDist2)) + { + vpMapPointMatches[bestIdxF]=pMP; + + const cv::KeyPoint &kp = pKF->mvKptsUn[iKF];//zoe 20181018 + + if(mbCheckOrientation) + { + float rot = kp.angle-F.mvKpts[bestIdxF].angle;//zoe 20181018 + if(rot<0.0) + rot+=360.0f; + int bin = round(rot*factor); + if(bin==HISTO_LENGTH) + bin=0; + assert(bin>=0 && bin &vpMatches12) +{ + const vector &vKptsUn1 = pKF1->mvKptsUn; + const vector vpMapPoints1 = pKF1->GetMapPointMatches(); + const std::vector> &Descriptors1 = pKF1->mvDspts; + + const vector &vKptsUn2 = pKF2->mvKptsUn; + const vector vpMapPoints2 = pKF2->GetMapPointMatches(); + const std::vector> &Descriptors2 = pKF2->mvDspts; + + vpMatches12 = vector(vpMapPoints1.size(),static_cast(NULL)); + vector vbMatched2(vpMapPoints2.size(),false); + + vector rotHist[HISTO_LENGTH]; + for(int i=0;iisBad()) + continue; + + const std::vector &d1 = Descriptors1[i1]; + + float bestDist1 = FLOAT_MAX; + int bestIdx2 =-1 ; + float bestDist2 = FLOAT_MAX; + + for(size_t i2=0, iend2=Descriptors2.size(); i2isBad()) + continue; + + const std::vector &d2 = Descriptors2[i2]; + + float distLFNet = DescriptorDistanceLFNet_float(d1,d2); + + if(distLFNet(bestDist1)(bestDist2)) + { + vpMatches12[i1]=vpMapPoints2[bestIdx2]; + vbMatched2[bestIdx2]=true; + + if(mbCheckOrientation) + { + float rot = vKptsUn1[i1].angle-vKptsUn2[bestIdx2].angle; + if(rot<0.0) + rot+=360.0f; + int bin = round(rot*factor); + if(bin==HISTO_LENGTH) + bin=0; + assert(bin>=0 && bin(NULL); + nmatches--; + } + } + } + + return nmatches; +} int ORBmatcher::SearchForTriangulation(KeyFrame *pKF1, KeyFrame *pKF2, cv::Mat F12, vector > &vMatchedPairs, const bool bOnlyStereo) diff --git a/src/System.cc b/src/System.cc index d877f61..1c118ee 100644 --- a/src/System.cc +++ b/src/System.cc @@ -30,8 +30,8 @@ namespace ORB_SLAM2 { //zoe 20190513 System::System(const string &strVocFile, const string &strSettingsFile, const eSensor sensor, - const bool bUseViewer, const bool bUseLocalMap, const bool bUseLoop, const bool bOnlyTracking):mSensor(sensor), mpViewer(static_cast(NULL)),mpLocalMapper(static_cast(NULL)),mpLoopCloser(static_cast(NULL)), mbReset(false),mbActivateLocalizationMode(false), - mbDeactivateLocalizationMode(false), mbUseLocalMap(bUseLocalMap), mbUseLoop(bUseLoop),mbOnlyTracking(bOnlyTracking) + const bool bUseViewer, const bool bUseLocalMap, const bool bUseLoop, const bool bUseBow, const bool bOnlyTracking):mSensor(sensor), mpViewer(static_cast(NULL)),mpLocalMapper(static_cast(NULL)),mpLoopCloser(static_cast(NULL)), mbReset(false),mbActivateLocalizationMode(false), + mbDeactivateLocalizationMode(false), mbUseLocalMap(bUseLocalMap), mbUseLoop(bUseLoop), mbUseBoW(bUseBow), mbOnlyTracking(bOnlyTracking) { // Output welcome message cout << endl << @@ -56,28 +56,13 @@ System::System(const string &strVocFile, const string &strSettingsFile, const eS cerr << "Failed to open settings file at: " << strSettingsFile << endl; exit(-1); } + // turn off the loop or not //zoe 20190511 cout << "Loop Mapping is set: " << mbUseLocalMap << endl; cout << "Loop Closing is set: " << mbUseLoop << endl; + cout << "Use BoW is set: " << mbUseBoW << endl; cout << "Only Track is set: " << mbOnlyTracking << endl; - //Load Vocabulary - cout << endl << "Loading Vocabulary. This could take a while..." << endl; - - //zoe 20181016 - mpVocabularyLFNet = new LFNETVocabulary(); - bool bVocLoadLFNet = mpVocabularyLFNet->loadFromTextFile(strVocFile); - if(!bVocLoadLFNet) - { - cerr << "Wrong path to vocabulary. " << endl; - cerr << "Falied to open at: " << strVocFile << endl; - exit(-1); - } - cout << "Vocabulary loaded!" << endl << endl; - - //Create KeyFrame Database - mpKeyFrameDatabase = new KeyFrameDatabase(*mpVocabularyLFNet);// zoe database名字没改 - //Create the Map mpMap = new Map(); @@ -85,12 +70,32 @@ System::System(const string &strVocFile, const string &strSettingsFile, const eS mpFrameDrawer = new FrameDrawer(mpMap); mpMapDrawer = new MapDrawer(mpMap, strSettingsFile); - //Initialize the Tracking thread - //(it will live in the main thread of execution, the one that called this constructor) - //zoe 20181016 track名字没改 - mpTracker = new Tracking(this, mpVocabularyLFNet, mpFrameDrawer, mpMapDrawer, - mpMap, mpKeyFrameDatabase, strSettingsFile, mSensor, mbOnlyTracking); //zoe 20190513 增加tracking参数 + if (mbUseBoW) + { + //Load Vocabulary + cout << endl << "Loading Vocabulary. This could take a while..." << endl; + + //zoe 20181016 + mpVocabularyLFNet = new LFNETVocabulary(); + bool bVocLoadLFNet = mpVocabularyLFNet->loadFromTextFile(strVocFile); + if(!bVocLoadLFNet) + { + cerr << "Wrong path to vocabulary. " << endl; + cerr << "Falied to open at: " << strVocFile << endl; + exit(-1); + } + cout << "Vocabulary loaded!" << endl << endl; + //Create KeyFrame Database + mpKeyFrameDatabase = new KeyFrameDatabase(*mpVocabularyLFNet);// zoe database名字没改 + + mpTracker = new Tracking(this, mpVocabularyLFNet, mpFrameDrawer, mpMapDrawer, + mpMap, mpKeyFrameDatabase, strSettingsFile, mSensor, mbOnlyTracking); //zoe 20190513 增加tracking参数 + } + else + { + mpTracker = new Tracking(this, mpFrameDrawer, mpMapDrawer, mpMap, strSettingsFile, mSensor, mbOnlyTracking); //zoe 20190520 + } //Initialize the Local Mapping thread and launch if (mbUseLocalMap) { @@ -100,7 +105,7 @@ System::System(const string &strVocFile, const string &strSettingsFile, const eS //Initialize the Loop Closing thread and launch //zoe 20190511 关闭回环检测 - if (mbUseLoop) + if (mbUseBoW && mbUseLoop) { //zoe 20181016 mpLoopCloser = new LoopClosing(mpMap, mpKeyFrameDatabase, mpVocabularyLFNet, mSensor!=MONOCULAR); @@ -124,7 +129,7 @@ System::System(const string &strVocFile, const string &strSettingsFile, const eS } //zoe 20190511 - if (mbUseLoop) + if (mbUseBoW && mbUseLoop) { mpTracker->SetLoopClosing(mpLoopCloser); mpLocalMapper->SetLoopCloser(mpLoopCloser); @@ -233,12 +238,12 @@ cv::Mat System::TrackRGBD(const cv::Mat &im, const cv::Mat &depthmap, const doub // Check reset { - unique_lock lock(mMutexReset); - if(mbReset) - { - mpTracker->Reset(); - mbReset = false; - } + unique_lock lock(mMutexReset); + if(mbReset) + { + mpTracker->Reset(); + mbReset = false; + } } cv::Mat Tcw = mpTracker->GrabImageRGBD(im,depthmap,timestamp); diff --git a/src/Tracking.cc b/src/Tracking.cc index 8ecb8c9..757059f 100644 --- a/src/Tracking.cc +++ b/src/Tracking.cc @@ -21,21 +21,21 @@ #include "Tracking.h" -#include -#include +#include +#include -#include"ORBmatcher.h" -#include"FrameDrawer.h" -#include"Converter.h" -#include"Map.h" -#include"Initializer.h" +#include "ORBmatcher.h" +#include "FrameDrawer.h" +#include "Converter.h" +#include "Map.h" +#include "Initializer.h" -#include"Optimizer.h" -#include"PnPsolver.h" +#include "Optimizer.h" +#include "PnPsolver.h" -#include +#include -#include +#include using namespace std; @@ -205,6 +205,110 @@ Tracking::Tracking(System *pSys, LFNETVocabulary* pVocLFNet, FrameDrawer *pFrame cout << "- fps: " << fps << endl; + int nRGB = fSettings["Camera.RGB"]; + mbRGB = nRGB; + + if(mbRGB) + cout << "- color order: RGB (ignored if grayscale)" << endl; + else + cout << "- color order: BGR (ignored if grayscale)" << endl; + + // Load ORB parameters + /* + int nFeatures = fSettings["ORBextractor.nFeatures"]; + float fScaleFactor = fSettings["ORBextractor.scaleFactor"]; + int nLevels = fSettings["ORBextractor.nLevels"]; + int fIniThFAST = fSettings["ORBextractor.iniThFAST"]; + int fMinThFAST = fSettings["ORBextractor.minThFAST"]; + //zoe 20181019 + mpORBextractorLeft = new ORBextractor(nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST); + + if(sensor==System::STEREO) + mpORBextractorRight = new ORBextractor(nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST); + + if(sensor==System::MONOCULAR) + mpIniORBextractor = new ORBextractor(2*nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST); + + cout << endl << "ORB Extractor Parameters: " << endl; + cout << "- Number of Features: " << nFeatures << endl; + cout << "- Scale Levels: " << nLevels << endl; + cout << "- Scale Factor: " << fScaleFactor << endl; + cout << "- Initial Fast Threshold: " << fIniThFAST << endl; + cout << "- Minimum Fast Threshold: " << fMinThFAST << endl; + */ + if(sensor==System::STEREO || sensor==System::RGBD) + { + mThDepth = mbf*(float)fSettings["ThDepth"]/fx; + cout << endl << "Depth Threshold (Close/Far Points): " << mThDepth << endl; + } + + if(sensor==System::RGBD) + { + mDepthMapFactor = fSettings["DepthMapFactor"]; + if(fabs(mDepthMapFactor)<1e-5) + mDepthMapFactor=1; + else + mDepthMapFactor = 1.0f/mDepthMapFactor; + } + +} +// zoe 20190520 +Tracking::Tracking(System *pSys, FrameDrawer *pFrameDrawer, MapDrawer *pMapDrawer, Map *pMap, const string &strSettingPath, const int sensor, const bool bOnlyTracking): + mState(NO_IMAGES_YET), mSensor(sensor), mbOnlyTracking(bOnlyTracking), mbVO(false), mpLFNETVocabulary(static_cast(NULL)), + mpKeyFrameDB(static_cast(NULL)), mpInitializer(static_cast(NULL)), mpSystem(pSys), mpViewer(NULL), + mpFrameDrawer(pFrameDrawer), mpMapDrawer(pMapDrawer), mpMap(pMap), mnLastRelocFrameId(0) //zoe 20190513 tracking参数赋值修改 +{ + // Load camera parameters from settings file + cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ); + float fx = fSettings["Camera.fx"]; + float fy = fSettings["Camera.fy"]; + float cx = fSettings["Camera.cx"]; + float cy = fSettings["Camera.cy"]; + + cv::Mat K = cv::Mat::eye(3,3,CV_32F); + K.at(0,0) = fx; + K.at(1,1) = fy; + K.at(0,2) = cx; + K.at(1,2) = cy; + K.copyTo(mK); + + cv::Mat DistCoef(4,1,CV_32F); + DistCoef.at(0) = fSettings["Camera.k1"]; + DistCoef.at(1) = fSettings["Camera.k2"]; + DistCoef.at(2) = fSettings["Camera.p1"]; + DistCoef.at(3) = fSettings["Camera.p2"]; + const float k3 = fSettings["Camera.k3"]; + if(k3!=0) + { + DistCoef.resize(5); + DistCoef.at(4) = k3; + } + DistCoef.copyTo(mDistCoef); + + mbf = fSettings["Camera.bf"]; + + float fps = fSettings["Camera.fps"]; + if(fps==0) + fps=30; + + // Max/Min Frames to insert keyframes and to check relocalisation + mMinFrames = 0; + mMaxFrames = fps; + + cout << endl << "Camera Parameters: " << endl; + cout << "- fx: " << fx << endl; + cout << "- fy: " << fy << endl; + cout << "- cx: " << cx << endl; + cout << "- cy: " << cy << endl; + cout << "- k1: " << DistCoef.at(0) << endl; + cout << "- k2: " << DistCoef.at(1) << endl; + if(DistCoef.rows==5) + cout << "- k3: " << DistCoef.at(4) << endl; + cout << "- p1: " << DistCoef.at(2) << endl; + cout << "- p2: " << DistCoef.at(3) << endl; + cout << "- fps: " << fps << endl; + + int nRGB = fSettings["Camera.RGB"]; mbRGB = nRGB; @@ -308,7 +412,6 @@ cv::Mat Tracking::GrabImageStereo(const cv::Mat &imRectLeft, const cv::Mat &imRe return mCurrentFrame.mTcw.clone(); } - cv::Mat Tracking::GrabImageRGBD(const cv::Mat &imRGB,const cv::Mat &imD, const double ×tamp) { mImGray = imRGB; @@ -334,8 +437,10 @@ cv::Mat Tracking::GrabImageRGBD(const cv::Mat &imRGB,const cv::Mat &imD, const d //mCurrentFrame = Frame(mImGray,imDepth,timestamp,mpORBextractorLeft,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);// zoe mark //zoe 20181016 - - mCurrentFrame = Frame(mImGray,imDepth,timestamp,mpORBextractorLeft,mpLFNETVocabulary,mK,mDistCoef,mbf,mThDepth); + if (mpLFNETVocabulary) + mCurrentFrame = Frame(mImGray, imDepth, timestamp, mpORBextractorLeft, mpLFNETVocabulary, mK, mDistCoef, mbf, mThDepth); + else + mCurrentFrame = Frame(mImGray, imDepth, timestamp, mK, mDistCoef, mbf, mThDepth); Track(); @@ -638,7 +743,14 @@ void Tracking::StereoInitialization() mCurrentFrame.SetPose(cv::Mat::eye(4,4,CV_32F)); // Create KeyFrame - KeyFrame* pKFini = new KeyFrame(mCurrentFrame,mpMap,mpKeyFrameDB); + KeyFrame* pKFini; + if (mpKeyFrameDB) + pKFini = new KeyFrame(mCurrentFrame,mpMap,mpKeyFrameDB); + else + { + pKFini = new KeyFrame(mCurrentFrame,mpMap); + } + // Insert KeyFrame in the map mpMap->AddKeyFrame(pKFini); @@ -670,8 +782,9 @@ void Tracking::StereoInitialization() if (mpLocalMapper) mpLocalMapper->InsertKeyFrame(pKFini); else + { pKFini->ComputeBoWLFNet();// zoe 20190513 - + } mLastFrame = Frame(mCurrentFrame); mnLastKeyFrameId=mCurrentFrame.mnId; mpLastKeyFrame = pKFini; @@ -897,15 +1010,26 @@ bool Tracking::TrackReferenceKeyFrame() // We perform first an ORB matching with the reference keyframe // If enough matches are found we setup a PnP solver + ORBmatcher matcher(0.7,true); vector vpMapPointMatches; //int nmatches = matcher.SearchByBoW(mpReferenceKF,mCurrentFrame,vpMapPointMatches); - int nmatches = matcher.SearchByBoWLFNet(mpReferenceKF,mCurrentFrame,vpMapPointMatches);//zoe 20181017 + int nmatches = 0; + if (mpLFNETVocabulary) + { + nmatches = matcher.SearchByBoWLFNet(mpReferenceKF,mCurrentFrame,vpMapPointMatches);//zoe 20181017 + } + else + { + nmatches = matcher.SearchByBFLFNet(mpReferenceKF,mCurrentFrame,vpMapPointMatches); + } + if(nmatches<15) return false; + mCurrentFrame.mvpMapPoints = vpMapPointMatches; mCurrentFrame.SetPose(mLastFrame.mTcw); @@ -933,6 +1057,7 @@ bool Tracking::TrackReferenceKeyFrame() } return nmatchesMap>=10; + } void Tracking::UpdateLastFrame() @@ -1125,7 +1250,7 @@ bool Tracking::NeedNewKeyFrame() if(mpLocalMapper->isStopped() || mpLocalMapper->stopRequested()) return false; } - + const int nKFs = mpMap->KeyFramesInMap(); // Do not insert keyframes if not enough frames have passed from last relocalisation @@ -1212,9 +1337,13 @@ void Tracking::CreateNewKeyFrame() if(mpLocalMapper && !mpLocalMapper->SetNotStop(true)) return; - - KeyFrame* pKF = new KeyFrame(mCurrentFrame,mpMap,mpKeyFrameDB); - + + KeyFrame* pKF; + if (mpKeyFrameDB) + pKF = new KeyFrame(mCurrentFrame,mpMap,mpKeyFrameDB); + else + pKF = new KeyFrame(mCurrentFrame,mpMap); + mpReferenceKF = pKF; mCurrentFrame.mpReferenceKF = pKF; @@ -1289,6 +1418,8 @@ void Tracking::CreateNewKeyFrame() else { pKF->ComputeBoWLFNet();//zoe 20190513 + // Insert Keyframe in Map + mpMap->AddKeyFrame(pKF); } mnLastKeyFrameId = mCurrentFrame.mnId; @@ -1505,156 +1636,316 @@ bool Tracking::Relocalization() // Relocalization is performed when tracking is lost // Track Lost: Query KeyFrame Database for keyframe candidates for relocalisation - vector vpCandidateKFs = mpKeyFrameDB->DetectRelocalizationCandidates(&mCurrentFrame); - - if(vpCandidateKFs.empty()) + bool bMatch = false; + if (mpKeyFrameDB) { - return false; - } + vector vpCandidateKFs = mpKeyFrameDB->DetectRelocalizationCandidates(&mCurrentFrame); - const int nKFs = vpCandidateKFs.size(); + if(vpCandidateKFs.empty()) + { + return false; + } + + const int nKFs = vpCandidateKFs.size(); - // We perform first an ORB matching with each candidate - // If enough matches are found we setup a PnP solver - ORBmatcher matcher(0.75,true); + // We perform first an ORB matching with each candidate + // If enough matches are found we setup a PnP solver + ORBmatcher matcher(0.75,true); - vector vpPnPsolvers; - vpPnPsolvers.resize(nKFs); + vector vpPnPsolvers; + vpPnPsolvers.resize(nKFs); - vector > vvpMapPointMatches; - vvpMapPointMatches.resize(nKFs); + vector > vvpMapPointMatches; + vvpMapPointMatches.resize(nKFs); - vector vbDiscarded; - vbDiscarded.resize(nKFs); + vector vbDiscarded; + vbDiscarded.resize(nKFs); - int nCandidates=0; + int nCandidates=0; - for(int i=0; iisBad()) - vbDiscarded[i] = true; - else + for(int i=0; iisBad()) vbDiscarded[i] = true; - continue; - } else { - PnPsolver* pSolver = new PnPsolver(mCurrentFrame,vvpMapPointMatches[i]); - pSolver->SetRansacParameters(0.99,10,300,4,0.5,5.991); - vpPnPsolvers[i] = pSolver; - nCandidates++; + //int nmatches = matcher.SearchByBoW(pKF,mCurrentFrame,vvpMapPointMatches[i]);//zoe 20181017 + int nmatches = matcher.SearchByBoWLFNet(pKF,mCurrentFrame,vvpMapPointMatches[i]); + + if(nmatches<15) + { + vbDiscarded[i] = true; + continue; + } + else + { + PnPsolver* pSolver = new PnPsolver(mCurrentFrame,vvpMapPointMatches[i]); + pSolver->SetRansacParameters(0.99,10,300,4,0.5,5.991); + vpPnPsolvers[i] = pSolver; + nCandidates++; + } } } - } + - // Alternatively perform some iterations of P4P RANSAC - // Until we found a camera pose supported by enough inliers - bool bMatch = false; - ORBmatcher matcher2(0.9,true); + // Alternatively perform some iterations of P4P RANSAC + // Until we found a camera pose supported by enough inliers + + ORBmatcher matcher2(0.9,true); - while(nCandidates>0 && !bMatch) + while(nCandidates>0 && !bMatch) + { + for(int i=0; i vbInliers; + int nInliers; + bool bNoMore; + + PnPsolver* pSolver = vpPnPsolvers[i]; + cv::Mat Tcw = pSolver->iterate(5,bNoMore,vbInliers,nInliers); + + // If Ransac reachs max. iterations discard keyframe + if(bNoMore) + { + vbDiscarded[i]=true; + nCandidates--; + } + + // If a Camera Pose is computed, optimize + if(!Tcw.empty()) + { + Tcw.copyTo(mCurrentFrame.mTcw); + + set sFound; + + const int np = vbInliers.size(); + + for(int j=0; j(NULL); + + // If few inliers, search by projection in a coarse window and optimize again + if(nGood<50) + { + //int nadditional =matcher2.SearchByProjection(mCurrentFrame,vpCandidateKFs[i],sFound,10,100);//zoe 20181017 + const float FLOAT_MAX=5.0;//zoe + int nadditional =matcher2.SearchByProjectionLFNet(mCurrentFrame,vpCandidateKFs[i],sFound,10,FLOAT_MAX/2); + + if(nadditional+nGood>=50) + { + nGood = Optimizer::PoseOptimization(&mCurrentFrame); + + // If many inliers but still not enough, search by projection again in a narrower window + // the camera has been already optimized with many points + if(nGood>30 && nGood<50) + { + sFound.clear(); + for(int ip =0; ip=50) + { + nGood = Optimizer::PoseOptimization(&mCurrentFrame); + + for(int io =0; io=50) + { + bMatch = true; + break; + } + } + } + } + } + else { - for(int i=0; i vpCandidateKFs = mpMap->GetAllKeyFrames(); + + if(vpCandidateKFs.empty()) { - if(vbDiscarded[i]) - continue; + return false; + } + + const int nKFs = vpCandidateKFs.size(); + + // We perform first an ORB matching with each candidate + // If enough matches are found we setup a PnP solver + ORBmatcher matcher(0.75,true); - // Perform 5 Ransac Iterations - vector vbInliers; - int nInliers; - bool bNoMore; + vector vpPnPsolvers; + vpPnPsolvers.resize(nKFs); - PnPsolver* pSolver = vpPnPsolvers[i]; - cv::Mat Tcw = pSolver->iterate(5,bNoMore,vbInliers,nInliers); + vector > vvpMapPointMatches; + vvpMapPointMatches.resize(nKFs); - // If Ransac reachs max. iterations discard keyframe - if(bNoMore) + vector vbDiscarded; + vbDiscarded.resize(nKFs); + + int nCandidates=0; + + for(int i=0; iisBad()) + vbDiscarded[i] = true; + else { - vbDiscarded[i]=true; - nCandidates--; + //int nmatches = matcher.SearchByBoW(pKF,mCurrentFrame,vvpMapPointMatches[i]);//zoe 20181017 + int nmatches = matcher.SearchByBFLFNet(pKF,mCurrentFrame,vvpMapPointMatches[i]); + + if(nmatches<15) + { + vbDiscarded[i] = true; + continue; + } + else + { + PnPsolver* pSolver = new PnPsolver(mCurrentFrame,vvpMapPointMatches[i]); + pSolver->SetRansacParameters(0.99,10,300,4,0.5,5.991); + vpPnPsolvers[i] = pSolver; + nCandidates++; + } } + } + - // If a Camera Pose is computed, optimize - if(!Tcw.empty()) + // Alternatively perform some iterations of P4P RANSAC + // Until we found a camera pose supported by enough inliers + + ORBmatcher matcher2(0.9,true); + + while(nCandidates>0 && !bMatch) + { + for(int i=0; i sFound; + // Perform 5 Ransac Iterations + vector vbInliers; + int nInliers; + bool bNoMore; - const int np = vbInliers.size(); + PnPsolver* pSolver = vpPnPsolvers[i]; + cv::Mat Tcw = pSolver->iterate(5,bNoMore,vbInliers,nInliers); - for(int j=0; j sFound; - for(int io =0; io(NULL); + const int np = vbInliers.size(); - // If few inliers, search by projection in a coarse window and optimize again - if(nGood<50) - { - //int nadditional =matcher2.SearchByProjection(mCurrentFrame,vpCandidateKFs[i],sFound,10,100);//zoe 20181017 - const float FLOAT_MAX=5.0;//zoe - int nadditional =matcher2.SearchByProjectionLFNet(mCurrentFrame,vpCandidateKFs[i],sFound,10,FLOAT_MAX/2); - - if(nadditional+nGood>=50) + for(int j=0; j30 && nGood<50) + if(nGood<10) + continue; + + for(int io =0; io(NULL); + + // If few inliers, search by projection in a coarse window and optimize again + if(nGood<50) + { + //int nadditional =matcher2.SearchByProjection(mCurrentFrame,vpCandidateKFs[i],sFound,10,100);//zoe 20181017 + const float FLOAT_MAX=5.0;//zoe + int nadditional =matcher2.SearchByProjectionLFNet(mCurrentFrame,vpCandidateKFs[i],sFound,10,FLOAT_MAX/2); + + if(nadditional+nGood>=50) { - sFound.clear(); - for(int ip =0; ip=50) + nGood = Optimizer::PoseOptimization(&mCurrentFrame); + + // If many inliers but still not enough, search by projection again in a narrower window + // the camera has been already optimized with many points + if(nGood>30 && nGood<50) { - nGood = Optimizer::PoseOptimization(&mCurrentFrame); + sFound.clear(); + for(int ip =0; ip=50) + { + nGood = Optimizer::PoseOptimization(&mCurrentFrame); - for(int io =0; io=50) - { - bMatch = true; - break; + // If the pose is supported by enough inliers stop ransacs and continue + if(nGood>=50) + { + bMatch = true; + break; + } } } } } + if(!bMatch) { @@ -1696,9 +1987,12 @@ void Tracking::Reset() } // Clear BoW Database - cout << "Reseting Database..."; - mpKeyFrameDB->clear(); - cout << " done" << endl; + if (mpKeyFrameDB) + { + cout << "Reseting Database..."; + mpKeyFrameDB->clear(); + cout << " done" << endl; + } // Clear Map (this erase MapPoints and KeyFrames) mpMap->clear();