From fc3f9ceaa4ef01bf242cc55427f3fe0f3c28c603 Mon Sep 17 00:00:00 2001 From: "k.koide" Date: Sat, 30 Mar 2024 19:16:26 +0900 Subject: [PATCH] benchmark_kdtree --- CMakeLists.txt | 14 + README.md | 20 +- docker/Dockerfile.gcc | 2 +- docs/assets/kdtree_time.png | Bin 0 -> 246601 bytes include/small_gicp/util/downsampling.hpp | 6 +- include/small_gicp/util/downsampling_omp.hpp | 7 +- include/small_gicp/util/downsampling_tbb.hpp | 6 +- kdtree_time.svg | 2532 ++++++++++++++++++ scripts/plot_kdtree.py | 88 + scripts/run_kdtree_benchmark.sh | 12 + src/kdtree_benchmark.cpp | 148 + 11 files changed, 2825 insertions(+), 10 deletions(-) create mode 100644 docs/assets/kdtree_time.png create mode 100644 kdtree_time.svg create mode 100644 scripts/plot_kdtree.py create mode 100755 scripts/run_kdtree_benchmark.sh create mode 100644 src/kdtree_benchmark.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 68a7b26..6c6b113 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -106,6 +106,20 @@ if(BUILD_BENCHMARKS) ${Iridescence_LIBRARIES} ) + # KdTree construction benchmark + add_executable(kdtree_benchmark + src/kdtree_benchmark.cpp + ) + target_include_directories(kdtree_benchmark PUBLIC + include + ${TBB_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIR} + ) + target_link_libraries(kdtree_benchmark + fmt::fmt + ${TBB_LIBRARIES} + ) + if(BUILD_WITH_PCL) # Downsampling benchmark add_executable(downsampling_benchmark diff --git a/README.md b/README.md index f0b59a9..587fda2 100644 --- a/README.md +++ b/README.md @@ -1,8 +1,8 @@ # small_gicp (fast_gicp2) -**small_gicp** is a header-only C++ library that provides efficient and parallelized fine point cloud registration algorithms (ICP, Point-to-Plane ICP, GICP, VGICP, etc.). It is a regined and optimized version of its predecessor, [fast_gicp](https://github.com/SMRT-AIST/fast_gicp), with the following features. +**small_gicp** is a header-only C++ library that provides efficient and parallelized fine point cloud registration algorithms (ICP, Point-to-Plane ICP, GICP, VGICP, etc.). It is a refined and optimized version of its predecessor, [fast_gicp](https://github.com/SMRT-AIST/fast_gicp), with the following features. -- **Highly optimized** : The implementation of the core registration algorithm is further optimized from that in fast_gicp. It can provide up to 2x speed up compared to fast_gicp. +- **Highly ptimized** : The implementation of the core registration algorithm is further optimized from that in fast_gicp. It can provide up to 2x speed up compared to fast_gicp. - **All parallerized** : small_gicp provides parallelized implementations of several algorithms in the point cloud registration process (Downsampling, KdTree construction, Normal/covariance estimation). As a parallelism backend, either (or both) of [OpenMP](https://www.openmp.org/) and [Intel TBB](https://github.com/oneapi-src/oneTBB) can be used. - **Minimum dependency** : Only [Eigen](https://eigen.tuxfamily.org/) (and bundled [nanoflann](https://github.com/jlblancoc/nanoflann) and [Sophus](https://github.com/strasdat/Sophus)) are required at a minimum. Optionally, it provides the [PCL](https://pointclouds.org/) registration interface so that it can be used as a drop-in replacement in many systems. - **Customizable** : small_gicp is implemented with the trait mechanism that allows feeding any custom point cloud class to the registration algorithm. Furthermore, the template-based implementation allows customizing the regisration process with your original correspondence estimator and registration factors. @@ -241,13 +241,21 @@ Coming soon. ### Downsampling -- Single-thread `small_gicp::voxelgrid_sampling` is about 1.3x faster than `pcl::VoxelGrid`. -- Multi-thread `small_gicp::voxelgrid_sampling_tbb` (6 threads) is about 3.2x faster than `pcl::VoxelGrid`. +- Single-threaded `small_gicp::voxelgrid_sampling` is about 1.3x faster than `pcl::VoxelGrid`. +- Multi-threaded `small_gicp::voxelgrid_sampling_tbb` (6 threads) is about 3.2x faster than `pcl::VoxelGrid`. - `small_gicp::voxelgrid_sampling` gives accurate downsampling results (almost identical to those of `pcl::VoxelGrid`) while `pcl::ApproximateVoxelGrid` yields spurious points (up to 2x points). -- `small_gicp::voxelgrid_sampling` can process a larger point cloud with a fine voxel resolution compared to `pcl::VoxelGrid`. +- `small_gicp::voxelgrid_sampling` can process a larger point cloud with a fine voxel resolution compared to `pcl::VoxelGrid` (for a point cloud of 150m width, minimum voxel resolution can be 0.07 mm). ![downsampling_comp](docs/assets/downsampling_comp.png) +### KdTree construction + +- Multi-threaded implementation (TBB and OMP) can be up to 4x faster than the single-threaded one (All the implementations are based on nanoflann). +- Basically the processing speed get faster as the number of threads increases, but the speed gain is not monotonic sometimes (because of the scheduling algorithm or some CPU(AMD 5995WX)-specific issues?). +- This benchmark only compares the construction time (query time is not included). + +![kdtree_time](docs/assets/kdtree_time.png) + ### Odometry estimation - Single-thread `small_gicp::GICP` is about 2.4x and 1.9x faster than `pcl::GICP` and `fast_gicp::GICP`, respectively. @@ -259,6 +267,8 @@ Coming soon. ## License This package is released under the MIT license. +If you find this package useful for your project, please consider leaving a comment here. It would help the author gain internal recognition in his organization and keep working on this project. + ## Papers - Kenji Koide, Masashi Yokozuka, Shuji Oishi, and Atsuhiko Banno, Voxelized GICP for Fast and Accurate 3D Point Cloud Registration, ICRA2021 diff --git a/docker/Dockerfile.gcc b/docker/Dockerfile.gcc index f683b0e..ad6e271 100644 --- a/docker/Dockerfile.gcc +++ b/docker/Dockerfile.gcc @@ -18,7 +18,7 @@ RUN rm -rf ./* RUN cmake .. -DBUILD_WITH_TBB=ON RUN cmake --build . -j$(nproc) -RUN cmake .. -DBUILD_TESTS=ON -DBUILD_WITH_TBB=ON -DBUILD_BENCHMARKS=ON -DBUILD_WITH_PCL=ON +RUN cmake .. -DBUILD_TESTS=ON -DBUILD_EXAMPLES=ON -DBUILD_BENCHMARKS=ON -DBUILD_WITH_TBB=ON -DBUILD_WITH_PCL=ON RUN cmake --build . -j$(nproc) RUN ctest -j$(nproc) diff --git a/docs/assets/kdtree_time.png b/docs/assets/kdtree_time.png new file mode 100644 index 0000000000000000000000000000000000000000..9a8b6a76730c10b146d3805db7332fb4d789ecd6 GIT binary patch literal 246601 zcmb5Wby$___652YDT1IPN@D>k-5n|-0)o<=(%oGm79}VkQYs}~(zTG34(aah?mHLz z?0tS`KlhJ&dEBt#i#O*SbByurch6)VUpP;G9)Unycp@Pthd`Wzml)^H;lQ7RSA@jy z2hUnU)eeCm>q7sBDn3~oSdAPO)Smq^mVNbn5}G$qE-aS z;UG5jLH8Z(jje1EPj&6B&8_UsP4uoiaxil-voT&bwzs#o<7Z*9_~$G1xh%G)B?55r z9rVc$Z4GqoO{^@hE0|aqAlO;iIhj~Fm^fG!*!cKax%t_+m|1zbdHHyFbR-TDi0get&6q+R{6&e8f&i(-FT=?wU#cC9q6G%dF%Jnp;7vtEPR*VrU~ zNE~v$rM2~$b*8Wn4<0-?pYpMJHTd_dPfrYfeOU9T)Y|+qHR9IlVMs^7 zu`4*sha>j)PfbX)&vO*%nA}%}_Dj~d>^}B70@>6m7ZUhyOJ4flpPai`d)KV5u<~pe zVpJeA5d=meFV2qOi*g9pdm-Mkkk6nuiApN+6Q=ASpZNc_uWv&PIe7UI|9n+-VGi3K z3 zjc4(XG&*+rufCP~@7HIqzMwGsf(@>pVy&HLy?PEgltyWU#gB2zhfLJ=QIx{D zQp6s`7*34<_mzKL%p|iE$+7k&9`o$;5WC=y|L45Fjt${R#`^E-|LZtzRBZ?HpQROT zWQmo;nP>4<=s%Y!sKuT$oE4Vx<`mey`}a(CD!oER@bRBJyMl?EhPRl&ZZQ?9`K<6i z>v-UO==;NJR483RIpVYNsP)-UC1hkXBXu&1V(!ulY~A?hYT?UiMJ(7!JUPq5caWlI zM=t14WosjN2geIe8S9w;Ig-3qCo-T5cg@C{@$9qC*T!`fe>c9NKkPz{ZZWshH(&k# z^sNS41#c-=-iv~_{B`8t$Gz>_!Ldf_80(dWiC+0&y!-ZF^ZWnpEf#rY-Di$5^|lka z>!;1te+}?|f4foOG2#Sa&fr+4QC^Av=hlC{_%liPHQ+VwNf_e#-(CCbuPtGAK9)DV zHNhILCyo}B)}>M*aZ=3T5#L{X54 z)MN5+#|Kwp?s8f;)1%Z|=G4!+_oab~m1n)6@kYq|zpwF=Dpn;kzgD?_XZO8DRlXdKm8K1G>|O7zf?NOBFdKc%!9$#g>Ifa;`~2Y`nk_3l ze-5_*gO)JpY`fGv$HAml!MQ1Y_C6t_^rACmA9iz&-Ka7GPxRW@m29Ft9Or8dg_ACx zSPy)dRKj`A;w2xACP7he1mfar+QVJb>py&2JrQ($^qHFj=TNwF({q0>^s!|m)^zt7Cn>DNRK|Ei(H~5_rYCgx7*pK-=~)0xXgv>|(DwGu zBlQ=hv>yNd$ltg(GbUc&By4AORMydv+ZUIpZg_aOWBhFl2?@z1V&aFQqKJ@?kRZax zYNGD$f_LxU-J0)uyy|PAU~kXK%*?D|`T2o~Jj8EoyV?fCC}RY2OaFT;JF*HEcK=`i#NFtV$V2N5>dE#HudYkv3BBW#W~- z2V=4*oUbfv21Ar+-}Ed9S#%)b41{=49=S$Q-^lh5f>x zyONTU=LiW6_twVGI{56_#hjcR0y1_nbO${>g~j7Ta`fx@`LCED-@SY1?CjiLXr=AC z-8q$3(4fQm;p4~Z&useE4h|MMoA9NI7iVGL6Id(>L~B@ zH}_Ot*!ywmI1H1gJMR?x>ug5hh~(kUa@5rnDoO#zfKQ*UK=(d1GvCaR)6$~GC8Yf7 zak%s9%^LxJ%1a@JaQ~{>T0eZ2vi6Q|yv?{Y?$3-cM3r@Je<08xx`M<^U24Pd%qXhG z$kM&ryKUhw{#P(XkJ!%GtHiBJ3Rb`OPwpE1W0*OSvdi5%Ld(;1IbP6%O3}S44K4q8fl1aXvo}RU>Eq~T%eRNC=a!?Af zl~$zv-e9frULkp98`etI#tn5m#MvaFf6Z1r)4}@SPm9!%3_LDpSSdwlD;^0F_n9Sc zu2zL2+WTdW&!UP1Hk{St*A=YTZ>Z_d@U zS&`b9^NIzvispkB^_y2P*|wKx)NQm?+H7brv{0ws28snvSP#6Hxd)0cRxxx{GDS|Z zIxd|BS&8^Ribx%vi++ie%GB29o2~^8`Y@q(AuZ64Ddfoh)739ouLfxMy&#>M(IGui zgsJq1SAfN1P~z9|nrgnSpcF}V5mt!7R;9n<<19Xm9bz-Pd8d+8MLlP^>?7d2CYCej+hxyPODSB~?FuEqUd2RsbKxk1?O6o2HgPG&u z#)hqirY5|O{~;0aNtJ6qdd-Q6UZF;=1${J?cCaQdul&xbC)nsCi9LEk? z3D30$6<7?;m~uy*>amj2A*q@T^Wq;~z7#??P++0{rAlXypPSpU>M76gpQB6aCK7tJ z8NyME{mNM8KZ;^LHa0dkG&Ef2;n@wqIYqwr_s2VTZfxrJ$17K^^xb`MDI~A{1^cCo z7e!rM_}16gg9vBS*+>bTU0gaUJlq5Y1u3b5-o73F5u1!&dkrq8QbTx_$2xf}Ri|G( z2jW`OnfyL|it|IMp$78JG`)*)e8;uE`o>Q}ZZ}*s=8mG78!11G()QR6%Zv97>G=)! zqM?ECzC%WI;tvyVz#a9wt&N_IEu^eW@bQ~lH}!ZN6cI(2NC_AbJKbHLm&0wfE>O{* zZI0Ow>GHHghx?9_(t$J`vJFf|Hf0>W`8pa*we|J0Z75pA@<4t(M5-`a=0{=)4tJQD z=@=ONA#Uh!N4)`|(X+M7{dHlp!B?Ses=g%+2 z#>SEciVKL}yJ_qAS(4~ne{|mWva;y!-*2*WaKL=ia&eKcu&_i&b6P2h zsa2K;_qYDa74G%F@RJ2279r?^yG;65QT6kyQxElxMTI9H2QBz4$8^-Fk4te1L=~78 zWOc}ni16|4tnb{s*-2?>X}NcB03jDr3OC9D^6Hl#>FMdV;YQZhtUf+QCy_~Te^`0} z;_*;qB`Dh3+NQb_3B--m4-F5mZ*ARXW)8~DWw*7nTi@MvvRAoz)2LbLo;=HS3>D-Q zce^La2TbW~JB_o^?0g_SZ5VDY(vx0bsIwk)u2<+yxnhRX*J#7bCmaL=%-f{Zz zAw5ay=>!PhDr<3rQ<%Wz>=Q2?_DD)f2oWBAl89_WnK;uIG|333v7;3HGvL(uK5;s_ zKmGO3p&l-VU&fsL>Rtr_B=6ozm?>?S54~XL>$UqK!PL`_24qSHv3G7-1ZHsdZoNN5 z1{$vti0P@~eC^Y^|5xa5;_EV_kSXCk8y)yH!HZ3Q-IA&%!@>TxEg@jrY|I8+I;2pF z*In;Q%w_M@WtuO4b?;T{3AIt*$goTZypN7J@@`sgZ@ZxrL3MBja_uyW@q#S<`nWD0 zawIHa*%imfhuVDtY^XPeIi@>CKgO){G*CYPC4@2~scf_OPq3`1aCO@HR$ds=d=zS! zPtzS=9&-z@3SX8zc17+(k-X;^Xr@47Ff7J6a-62{s$TDd=RxteLY00gVIWYI-Z`j8 zs5Vi?Y>GP=7~VHTb!v0$d}!3UrO{2gloJuRlWdookgjSGLtvOmb473V?Ucq(vtH(1 z`Z#y?1lUALvLeTvzqO9*YHEr^Hk&zaPzg9P9o$>7!IXSqLKC)q)B^vG1I~fck;b{(2wGA4>qUBpPjo1@m6xyN zq=hjkZ*)ASVY8ommh?2ru+X#ea794)cuQV9ki6EHNZ7d0Q{7)#+aqk$^DvNS)cxa! z51YFjJ0s<8s<|)lY;0^G>WwWdG|t9(wYJ6xM6&7Q=<4b=M{?A6=yI#Wt~=eU7kL{H z@S-k&3~-oOt3jflwY^mB*Hiu`#?#lN(F%B?rYQ`_>olZ+kewaBy47Z+GV0KMIc7mG zo6dVz!ot@#QZe1P%pT+&l6L);HvXD?{F0yO)91zuhw^sA!LuZ#t`wS$2lg9x&u_7F zvtUj#LVUJXEw(ifm5`9wlzjB(hLF&(!*pX95}NjiYu97DTiJ7ee_sXyS@Ytbl#jn- zXN9gs3%Ydf=hRa#o@X`v^8*X_%_OUUL|2Y ztaEyDEV%tgK7dB#q>TDVyTF``XTG*KhN#~Uj^Y!cA z5VT@Fc2t>5m)OOFDCg%sh)rqO9y#%D`5Lr~+$EQ;y-bw#r z77LOHL<9E8>qK&tGb0{iLNk{eS*e5D|HVjN}f1fH6kx~pB)YI*srIgM&A+vkr zpSxduUcp(h82jAj%@fuBS5i|gWZ1tgUpe%|-Ecd2O$O(V)l}J^ljWG=l0iNZOOICG z=-5^6!(`u>9-8Jg7DlGDGSlT3te+2^c7(WG6vPI&uKE4&)F$aldb;=}I(n(VcDm6w zhTp-|E^qR5zs<|Bxw+ZiV?Hq=w5+U5ZFO#k>E}3{Q@7&fTs6;|gCCq^jb1x+dE3moG8Ushcw7_-PD3$;aO{d2ParbI&ME54Pq%g@ZEZf{k@N2xO_ndC1>A+jYggiYr~vlWP)f7Lne;tXKxJs~v?V2QdC zl31qp&?C!2?=Ns`G`tee*Nt;}0jFp?)N+VBog$cVsP@}d8UG+T!P@M%Zvop)w?zss zMb7;?tgOlRGMKKiOxoB`Q{HK8F|1yhqFlwT9O}?t51LwXvZVMlwmf4yLWmQ`A`>e( ze*{qh+r`y2Txbo2Nl!@?d~12MaujoHy`DzaKOn$7&+4A1r{^?;1iP6smreeP^*V~> zIJcEz`^WXSXMZyI5ULoS@NBJ4FfsOatcXGBkkJ{=q`o(w97oD;f9K&FLI-@?;AsUw+t4p(`SNGEwJ|NF8us1NA6iqt zap;Zac*nLFPuoMrmRzsC3@iA~hKDffV!NI+(L=Q-b!))=@$xiYYRUP}n4h6OvkJ<} ziHSyhB@;l072DQQ50yKMLTarRxiU*H{Y*4epMU5NS5@41QEC;qV*1oO_2& zweI_%TPa(CEUOn4wd855XS#Y}t55LPZRf?=TUB{p{C)Z3w{(xI0=z{|o&1}6cLR8r z7WCT5$1VCwS1Tw~o;@3LKi=+*Tie+Y&LS4>?CR1)zI^#|;3#14_ec7;&pcLI^|HeI zx99qe;+{GI{IHj>U0HZ;6W8-r-{1SAXj?e`V==W(w^dc8wW7%&0m$9@iAhNSX@cIo zc^pN3R9FI^s^l47*qmvR$MBX=kBC9oEHdUD1s@UAI>?s%m>Nbtc=Ip|FFfk8sMO=T z7Al&ff{!tH^nMFwHc~m0NvWR5qf8kS50=NZfxA#+RBbLL?`N*O8CznhtU$Rd6nJ>q zKuSyKIIfq2=d56JU?m-!USt`Ykt*5fy5;qQ@(9=3hTVFyR&(Ed;~AllNQlL0S->#| zefDx(#QMU8YweYJahSKPG`Z_z)?DqjzcD{G$y=Oz5*InTYUY4nnWJlEX60lsUCYr zOfRmmyjxG>wH3>%`#?-bXUq@BS2sHsi_(~t6zA~pP}{kdMA=@u)GVqG65Tr$x^oVV2uXolvn^Ml#t;08~XcQtP3rN4@O;PV>F2`Up5zR zt@Xcl7=&(D`R>SIzd1JtY}>EYLat&ZB_)LDcHvwg|KkQTSWz$_ygOu9bxS;8j?Zaj z$Pt}=cSpUvWMZ+pqY?!6i)E6=kin za<97bPH?#=`j|yo!^IFGcE7G^yWdw(xZ-s*Nz)J9O}+%2UYTDcP?^DY%RP&N-M`=#?9)JJ-9S$;R3TM)=YvI~E zJk)0;b>5$jUGm))o}+H|ppM+tZy{AD%fz6sIXoN#*WB1>Vv$#PahRdMv(zv4=+XNA zY~07VxHf={GB73R1ABWTC@hP7s^1Xx?iWE#>HtI7uuXei*&2ss$+PyOF)i4@DM`n(wsIsrK5$YdbCLi6HaPCF4 zC22o$^hU4zlW7*OcXt>W?L80XlRsJ&Plq=)8pFKVk_)-ow|)LhY6XihPT1o-pp-@) zC#QTZ=I2LJU>6r3_9pxpvc^`1io5LUgQ!Lp zdor3TA+D6pPEYeWE%oKx=H)H=nUIjMQS7ypQ_tTLDmogAOil0Ma#@DrZ0)4Zv8xZ=%+J5NQuXc>B(sAGdGZs5(Z6dF^u7 z{L^&RyijVlrJTmJL5SX^vnle)(M=5Db-eC-*`;}T(-ZP-u|gD-4bdWAo@20LduxCH ze)sk3*U&rcG|hi|0btwzRV>VP#9Pt;##@6OM3D_+;ERbv@Iy&hh>x$Ii=ThsnhsQG zx>6C$7BG8?h8~tMf#V*qF?Usptj9xOzuqV`9mK>XEPDL-F)W6`LgR)HH>%JrGt$w~ znO@9w-8Mb#h=1&Mx&uL?*WEMY^#zJ>ue~+hV8t}0eJ!`;{J_r#w`NlUNp@v*B5QK9 zf+mN&T~z3{k8H0_TsCQs=CgC23VFP?wKbKNRqwgi7QutL_|Gkd zu%g~~7^hRtG2gvA4(&67uMqZg?LG|+5_>rwSf1Nr{l zY04b7QxZusF_Ib@lraKMbb^A>P#g=N9@%;BPhWFf>bnnvmS1psG%KPCMH2A)FeR6$ zsav5a=qt9P2hHL|f35+nfh477h*w723*8#_9goV6Hky|D^B`UDx0ky)O-xLvlsU6e zaGUGEoY>FH35{~`@I(M&$TjJrL)^S|3#cHY+142MwJKb9NE5JlqhXRTA%elCZ){?E z6aq_;jg2krn9I=GeWp3m9Vk&?z)I}re`V`dqjL=`v!#*pC|ap-_yDJ@EOquawV?9{ z=p->2*>6COQqs}{_wV1|n(Oc_D&hs;TnAI%S71SL=~B0?RDX#B15il%zh2>KI1M|z zc=6)m)vK@Hyup1OOg(+PJ8A@A&>Z$8PvO953T&L>wO{z?bIf`(GdPf9Vrob`zJwKF zp(YU<;!j)?40@uU4caSvvF3!YYLK6vK8_hWW-P2*Tf~Tve$5mv$vKtytAL2<$+^y? zzEs3T!dJ+&>`%mb3s{2Q2D>(KKWY6mgU9QKV5bj(bah?p^L01$+AAe76 z!K$h6*64K~_-S$jMsvi+$0u>IH|rGo=XL4<-Ny~47AkR@Y6x-3D&JAdFvTSj+G>9n z9UUEW+S!86e*N*I!31i|7_)-;;Zmm# zhODyCPmz(u3|w3eZJ_NC-oAZ%X}H{Nw?c}!`1UFQH>;Q?IrE{Sj$H^$nR|$B3hqyR)J#*tkbsf+h#t_v!BPU9Hd-1pXo($g7xp+HPl*Id@u({u01P@gS)@jJA-r#>l@2{z;v4$8=NXaV-o!KS^S*4H;218mtD2>bw8Fx%kVE0N=+FRA{r26v@6gLrDe8H=c#iYB9xxbu?t84z zotq#D05F4qCfgv9mKTx|x7P@&}GaPmgKf zPew)cp*&J5Y@@G&ZKXw}Qf)R$d1y$H}*?1%ex- zx*IMoE@58kAcmkX0n}lh$Dt!&&3*pCN*Ih!pFU*+@(rR9X@#1F7uYaZ&vXI;QIQ-* zJ^edSTNy&V1Pw$B9ddG)p~$GJuYUvEVG}rtZVI006M>5%O1Dpo48%`)c2NwM)=rF7 zgsMZap7oAZ8VSrfQE3R_QjZW3E$1E$xqbJ*IgQdE0w>6{*?v;t4T~&&y^yQ=X&Bzy z_*N|pua))4q_uHWL?V~#*sDF={l%ON2~aU4B3=a1zooy3U_^=vpk7TEs}eM0n}=JS znR@utr40;6wA?-y_E3IHACl`iir1bj{%Le*ns}0^8|+b@wpdpk`BZIl%unQk1Z6Kh zuT}Lof>qblMxMFqz;!Ab@==cRnVs3n)AFv}Qu%@I-X0zAr(N}hb3Bev&iyp$dVmg% zGH9sfhkvb3<}>S!$^|x9gROC%2PPL$0;^>ooq-TjYE>YDD0Mg!Wi{anxkH45qsuU5 zCuwbcoej-2KL*l^0r!uuukTY@TH4o;kqbCbP)r7oIP_}vD-H%y@T~lS7-MU{G4=Zr zr0(TCD8dzbOwc9j8`!@QFhes;D%sal7F?IBs;bb_79lw!f z0k`chICvirz^GMXZ=&Jsyyxw(*t4IUoLmafqDo=2C^YnPHN>3D+797fkg}y=lS+|u z8b7OqMdO;7kWd8r_UH8a%Ke!rDkQbXR>!B*SswDh8K)7K*}e*oLqT*ScY!o@0%6|V zyv2^YUi)Mt;$uO`TUwHC=mpFDY|TlEqf&+DKo?w-+p zq19-`5}M|dtMoiRsI9AWg+S3@Y(@uE1*;cis2oKG5du=yuX~Y3v3%Sv8&hw&%zFOp zS9AbKzv&H-&-qJ>p{Y{L#gvIQ)C0!eG3xKGB(14(-itms#70xiLpxQ5p?UZeg01G< z`p3KFOFqxBTovOUZZ(Zd$DSC`R^ahS*C-CP98R6pu^1_f%s1}wRi=C{szJ{j+ND_cx{Q@tPH{xK-X9fFo#h7UGefd zZL|QAKo2sUbPRtO34_wwkX@Ui*(UI*150M$-EiLI^{qld>{4D{EpXdiLB~K1ujB1}Y9qz* z@p1HZx()ZCehx=-4(KsRSIK#ae$73&Gv9^l4H1}gkMvPZl_dW7+*K%EiyS`W;x|#w zyYliqtVbpr?K@GOe_f)a?{txersxQJuSD-${ty-ewV!~p8Z)y*lnw(D<*J)9c{Rwft!`0T8*FsNJU0Q4%Wwnr#z zfpalXraCHA%QFmAHZ@J{=<3Q_`u2vJUpH-8`}CmqBOK}FqNn#=y&E}dRe8*PaSRGz z0n0@zL0;ZIPRpU9XsFl=)$>imWc7&=?Ck6s2n-Ai(+d^7e}Hv)nd*D0G+7rYFb&C+ zJ5u`ft;a#6X5qzIQW6qxQvg#x0t~Y|lxyH$&(*6TpN8cD5J}23d=HnD*IFkeE-vma zJ$?N&47p_wmNx`ZS3^U?5`IWwG@g69QCzNQt}p*YfEE_j5Ha6Dz^C#ydP(ec=2@}u=3%2#- z5r+Lrg zZDk;(ssK((l{)6zkwACc5X_ZFw!eP;GF@IBEM)Q8tEN#YbzCN^w+HHUP&!);=~=Rjta^7Y;TL^OX3Bx>D8PAo5;JsKw2K2YuehQYW2W}DN-C|xwHa! z12>6{L%#c#CKR3kB_T1rS)Vj(Bi>qD8_O(RnSix&tto<~P#r_m1H!{)U}m5iqh(?W z1T5XdZwM(fKU8UKYqGha;m0Ol2_zAV@I4y1dsfB4J@CM#aBwe%UMN|iwGC>N;nnOp zZ7{vlYW1UbKKJC3K9j*Qg?i9v$bsxjO>NXT4O1okqw3Z+oiVDQK&hp=o^vVN_+s6% zS7lTr1Cf7@#FVg{^;CVEZIl;GOVcJiZ{??varS79t)iSn)oKeIQCui9l~h_r+?zgi zp6}y2+mWymGs?V~TRws)Hg_=ro8;M_XI?1e zYhsEr%x|VWzw?gj`O)QTVHdKj|nPoF8RNI zA1xkCJ!}V5s4$3$EGose(;?vb>r2lr0Ep&<7RbMs81n4`Gf<_v76@f8QPil27tk@X z2oaIWTr~6SKt~Sdj__;Ot_eV9BzN0hPz;3zyMjMY*&D!a7EJj-dj03n(24UOK7IN# z*AWI>&@}|iCJwG=^{-#%!pzFb%6XNQm0$;I;$mTGE1o%l{OQ~hBf#Sfg`ZYRN=hAI zPc;@%L&KyN#`%&~ymoNc$jitCNddJ8RN3;tH1Z-)O=`V5JFqYDkzfam-dP!5lOs2UhV?U-36hP<*w zp6SgThYjC2?P^Rh2O;J~Z%57E4-t&2zaGZ!24iF zLg+x@fPkFWv(J05y{Npb;)Z5eHfP(6VE6#|G|#Zn%S2~KBA)e55)cyB0nG(27&tj< zo3h)oC`xddLqsr(6z5l__HKEe8UlY(N1fi(n|z94=>uk-Y+T@ zFh0Iw!uIIVBPa=}06Mr<(S98R!Z~R@B#yXgHT*qL#7r$J3E19g$e1* zP%ku{7OFkT#g`U5)fc4DOQTnFF6Gs@YbVESM_5acYAgW@ciN(vnWV!jg5+YJ$^L>zNiEO=*;U8}X-`8ED@> zI;`N|Vj#ZW`UeQY0ilhCTe=V}LEMOh0SH}PUA4*;Zbjp6bW5cqCBGc=nh6&w2@4Bz z4?z{E!-&fm-h9-`#yz;G1@rWa{rky~RhR1z+nJJ#5Q6*JXGT2ox9b+qM z0>M9|yy*)sqzH8t31gOa$8KM+R(*l%>adnlXc2)3ri)3t3*Ip_IS9lZl+@|1RbJlF zlud#h>UqC2;Nhu-q24P6IL=k7o_3_yMl)AN>fXPPgwlvK&`2wBq6(L03Y@$c*BKcD7&41qdV6~}A`h|guRenkW_I$YFbx+O z!RtoT%LTF8#v_Y*iqD=sv!c1#`Kz(%x<%W(>IohN6YUzsW_mZI^=XHoNHX?`6S=VvxzYp$Vpt)Svny?!K{$oV~jrt7=6NDeD9ZPHoVN%}_R zklbAvDyf&J$f$>R{&C9xiSI(JWD(byYy#3ZNFP-9|Zf}h&fnp4lJ zhecjI{`sl+z#TI(L2YgA@;Zypz~5+%ayPo(sBUVK%Cf;9u)gE__}cQMv(|Qw_xSMO z`oYs{9lx`taoRF`Paw)?G4A(Yj*hXAK?yO?1)p!j`ocwJq!9<{!ie6^M0Gi`H_&GH z#~P>lpjB~#`VLcsy`73`AW*5Fgkf2w1dE(F&p~W^*kZ^5tjO1v&I3@S481?n%l7Qw zjODfY#q3++H6WquWh2>X2Wx8+2NY+)q*(z(hU4L5GmoG&CF~z} zp&IUYT`#RjcwNWuc~sN{bxVH>$d+z9OEss5m8SyZ3kzz?HiYDyKb%ZWO`CekEnkCH zD&RY9RR9D?MqbT3Fl-J?ms2=sfUglk5j0Sbv&S0n~qObHYR zpiSUI4Q+6=w~nq8#;e~93iec2hrYFjGME1_PkB1KMEIHtu@ntZ$^26L$_7kLRup#wRDM0k1Uy1DU!Erb;6y$&B1%!*x7{w_{YN7#n4N671AxpAvR{GBHBDlnH|Z?^=)eL=?1tXo`&z^&qS^TY7bLKbg)%K|}1lWucOcUH_@B!iEL z@(?PNbWJi)|5T%+o`s1-heNgL)ayx8xWplq6ox3pam1N@Yc^DsfoN^ywMweY9UBM7 zi4F$W&0VQ#8`F8eu|%y3>P!Q#rBQI;Xx@FwT-Dw>n6V}6%g-}$@0GrE6gN{>eSPu~ z;CTEf@cyWHdRA=8%L*x)wNRVg-JhD8;>Xnm8CuQW8(pf=BAz^XVhQw=#a4PhFobgP z9V%d^n)nnEF)Ikv!RzE{E;*=m!EI)mI?Q3Dl%X~)586Cf(-@0ZD-Lr_S9qdYZqv~X zIJioN)$4OY74QWQ7Xd=FJ!X@4z%~~jF=$ge%%Jz3Cn92T1zE+MZoco(W-#G%e&D9XBK1#Pc(FXtm3)lh?xl3|a*7T}%9|}bHVzI3|Iu)l3rE?ZFj1?2 z{rWXVxB=!uXJ=D2xVjPH(+@I4c*J*C!o~dc>w_*`xuP&@zCLq~h-elhvKzFtwU!=g zXf_9NR+~bmnV6hht{4j6b_fa%&e|khtbhUF|H$>_*8y)<@yr)B-%}lzVRCuhs!Qoo z>_ABJabFB6NdI{;$dXTJEG{>1oLh#ueOgZn@8~UC`}_l5n#>$tit$vQvB|V-0-`A0 z+IZ_Wma!pQVv&UDZmvTeCf0L%6ya6N9w@=^PU+0DkMNq!S%K_@6$5|Kfkm>llK z2TudD)^DGA_@u8nZf9}tjo#{u;<2iDdlEyTC8E$8R8O}hqv~|0S|mC9=M#?dWX%zV z{-(a4iMXu=cjc2_xVX7RpuGl{(1K3s7iqea?JO@vDGZR&8+k|xYHDj;fJCadKzSqc zamLWL#X+t>q?ebMJj_Q_evP}GhRbwVv3Pt(bZDraM(&Gut6%^y^$gDc4b>y?(c>;a zu<18TJ;H6?wJSNGwf z8VU+iTi_`<909n;#}&K}umuC*y1Sxz5rT0Y2_ikX3#z!8$s<65<$1Zet-l!*Krhuo z0AHOyIQr?Qs`!}081+Jhp>i0$B;q12=;UQP17=v**lZpL_L&t2rf3rxR9PFQ^?}qv zU(jR<)RR6S!>ct3Lc;FmD;;TTBLb`pb{LdIkeBSz;f8MP&gxfdT%jRBKyVf%cXH${D?|$L-5B< zW>ub)4CEL!UJCBgO3yk>jL=#blMqvDm*p7SBfCPldi=O(uQe(Ew~V(h!+85WiT612 zw`{90e=+(VU()|p?`)l?ovWO7nfp9*(IrPOgZ<;Z)$DyLQoimSo8M$9R>xJxs7VwR ziV@Xg{>en8=jUnv$v3XSsrQGzsF|yR!IwU(tZ&A`3$!cv9D?}JX-XDTK%W(5@vvll z88e=9&nsyD@|Y_BY`9Mjb!KZIb#tY@v+)3Y-TkH5gSlk6U{Hn`*vg*n?tFJ}plZ?p zA!yp&ez3EwE@(T|paJYEcmW^aIn#ZRH#+9*y5w}%rrQw}F^0JA5|JGZ0Mt{1&Ma+8)m>3y3(E_0lFa>7z zq4n+G9^!+CH2{1!2@OTO*D^pW7U9ut1sb%qqvH&uguEuc zj9@!((@f1MwQUdO=;NM(OKRB`^4n7csgUbW-&>bV?msSsDm==oX|H_TF1qoRhm`LA z!!=j!&vrM`zgR}DYlA${(ZoI`qI*?(7?WuEW!kK0Ri5+mEHP?hjmmBpZ^qYtDmHP4*k=zo%(rrXLN8j=;0T?ywY>MNX=eV_W|-wI{FK)Cbe?$koC zRw~7|%$tEQcF}_bplWY-4-E<0gEHs<{O{_Q$Vii)AkEzw-T;Yu$OIlFZ0pZ6Vxj<| z-3yAbCrV063y_;sPapzvgEd!D$Z_fONOKqx6DI*pg*(F3$N*oG<7jW+j6FA6>D34; zyXjbvNvn+a9(Y&=KsaC={An`Tl_(YQ2i)Vr)j&6cx~=QFIrFp&DpmD^y}cK}rDa~< z{|*U$9x9*rM-XHM!FV!W?0M{Z2oQ0^$=dpv!HX9SRzpR)U;$uDgGcQqVHIPS78i#t zrk96=Tmqp|YG-@f0XzW74!~?MWYAfFEvFO6pIqRtQu8f`2i*Fyb@8aFsZ-nApLL;a z4~027zc+VwTFV@lzvSiy;jMu$Q7lHtt!D#V?n&roi8!x~i2=!>Xl-qs4`S3{io!ir zu!6~n?2TcTPaiO(LNn$skaIRbfvp5>>u>{l01tSK=5mL{@ZTW*r80y`K8+U-WS5j; zO*sz*$p-8?)i0kv8-qLivGH+%LSsU{7$2X7Ckhvl7;a<}s2fC0L$KmN-P3kRn&OIw7K`~vWTv)~BY zTIlu%5n^t57tP7Ra|tzTQwSpr}UuhR-8Y<}G_l+T|m zZJJ1FanKJzb8JFpmQTNRYy;<7HCS6HoCkKmt z{r%&st8HKinIFh!0C&|*q4JIQoeeM8(HP7(*dVLcHa5P8MVSLk6#{Jw zK}(F1d^6~-fqsEUM1;O*043jLTwGkJo%g^<03Te4V9};yW6O~XQdWhzeGKC7$jAsM zsEn!AmtGn9(-G;t91}lbJavn>uP#1P9zq#SA@q4#J3ix%nbljrTlV{uJ06U~N(NOY z!Qqk_B$I2`HenV0Kpl0r+-klx9jOayQNUqFSqT>|ILzrKusDT(+L9nHAAy`3K%5WtCtkI#W=48g$(8q7UYb;69nn$8VEy*O~B zvi1%R9&}!#e)LHk*B^hew*A(}KFktod08_5X!|v0rAP__yXpfTF`bUNc{BJkKt{U* z&+O;{)r^3h69vJB!}G{lCYrYjhiRkD(`tcv74t`1bC8b#JfsH-KPBH%e^15kEgbA$p$zuNpNqG=la2BLI$>4gW6 zI4uS~K`Lg~{e>kHC)@(S8$XDm@n6qthG+6!u zL3Wv3Ue+|JPh$kMjhoP0nJat??^mVThJ}gvX-53T8QlKqxfR3lb6f+W!?B%-UzR6> zHb&!XqpV#x#AXVA6uXdSE@Q3=qxaP_`%?pQgojUr54Yb+B_<`-4#perp?Xp&d`Zu$ z4x_s|Ka|?@n<1xm&hv76%T73on2>pn= zK_=rT`sKzFh`GmGxA^B}ytP6Bu5_H@5_Fz>Ecz(>fSp-&Xpb z$^m6iRa5f{%+3l9cYf)^|2hQRXV-xt`vY8KYPAbp;_MWgllD1^)={L6j-AsCk)>Si zb0KR;Q2@lj%foZNcCzV9mUO!)&1!e(yU>^P?fT zl97{}np#+7tiU3E9TPKrYxiZ=oiIsS0oXJ7fQ*UJ|Fa~;a@TF!Mh;T9;{%6}ka`rQ zWMz459UWUY*VY;=AiuR%$7Wl=-WWzFnS=d(%|%#Vbq|*lt^g~Y;RrN6N1|Mc2}E>9 z$Qw-^dmA0VaF9W&91vt;YH5I7lm#pZ+10C8r!9S-YXJ3rN#Y&lL3o^qSB09jb#^4s z@=4%3=?^65a=jV6sr%Eoz1ab#Zho}mMT)p z8SK%p;+j13(m(Ow2x%4KN}ih{=D1GA`_i6S_CxDC%28 ze}Qa}o0s?eUfAc)pA{N~Pc0Pgk$_%C$IMJfPfxFwZ>mV!rf6tLca230DtjCb4i0## zGextM8!~31WpcME-ud%4!A1yA%7SYQ9Qbt)iIR*A4dnp$gGLD40FcK?OM&-96Xk4H zhWH@Sy-7@@ZTZ5*u;~<^3+urKMhzYgwXw5{f8>9alp>H zUau3u=g*%5W!Rps$^kdpT1r`fL714Ie*z|P5SIG}gf)Fb!6lQBoD9yWmvX8pe(|w* zP%S1TCFz-%?5l*nII&aOeI-ykJEY`o_psp!gEpS)Bd#^)=U>LPONom(JG5n<--+wf zQ5m_PT7=M9#vx{rSSF4|P7HDU$<&NmTeG%5b@AO~8NCrkx#+Wn{as*9=7bhArLa#a z;XLwyf>Wq0P2vf{;BLm!WU_?z=X)EqS;TU*uZ)G(`!JsRyp{;VX7sr|#xAGmoxF3~ z_bem5Tr=mRiLH5~j`2>?leNR;P{e6|u+Oh`JGS{Z|9zmXA_G9yG%Bzf70z4Ar=jtC z@NF6DAi8Jcyb#SI)U&k8C8b`SLVdgn$BY<3>BS6n7hy*F@xo8j?t5uqat-Uz`dT(L zG_(P}EDe*{a|9QT7R$iRs0yXRFJiA~5(jv;!ygiT{dd_o;U{`)+IMh=`I3IEk_@*w z*7mfB^Rp-)+ThZj3w!kKnIMT!8*Ceh-f3%&`-(xvkl_+**WpN z6q(U3DWN2*?3tB_jD}fcBqL;&k(HHk|326AJn#R19PfL)$MHT7?)$pV^Lu{3pLI&e z$-yEi7wMT*<5m|gh!rITLs_c(wB4pSB}t9seZ|>(m=-!FH`>NleVgvvm>B$wyOP1- z$Ar(AXQngiD1IM1g-k4@APL=Pg4E9 z;YdkV9#Ey+elkWhSg- zlEx+xWAuYkEA!)z3Fqm4H8r(4uy?mKegx*>0PZnOG;|*Q6l3mJeU<+wYh>W0#m~3X ztK$ng1#4d0NZLsvq+ovK7rl`BbL_KiB-%nCCNB#_ikn(Y-j{M4lV z$A;BTWhuhQV;v~4TLz1Fu|e`i{ptN8fLhBDOdQ8?AL(^?iqm%|^@E*Dd# zsBu)vl)XkubgSYBTKla9PErQMbIzph0`N2dVG%gDH|?JZ!sv7fLz8NW^=C*&Ugqalx3v`#tzK$;;|67` ztLEk|&3#4b7vrZLpI9CUJ7+)c{Ogq^&5CNUJoB9e`lbhWWcunTn1}2>QZWTp>9A8+ zj@W%XCS&}+DU4d>m0ejwqfM3L5C<>SL~HH!TsoO*t@O0#wbUBk&tN~7LHT(e+f(t( zK+$l7JSgu~=r$|3AdXS&`mWC^xJ>?JuL&h#6yw}j!*w`n_)z><8Ei`O<%WX9jz+mifs-oqAc}$7vF~@&8O_RLMLHiR9 z!V9{z!KISSRH;aQdps#A=)zGY^?!cHwVEUDM(vw7kjmfQ?9SGR6#T9_OXIy5X(_eg zXt}m7Nmz{SiJk7smVaOEwLrma4y`Pun)aV7hkgepM)9gKx!j3yD-yY5KuoRIQY*Ps z7KbUPNX8WB_^HylD+kXCoTOu{CtGyz{W%d0<0Qkd+>sB z<&@~JOQ*K1E-U`AGb-}fID9hA<)foL!=aV?zoeA{%U?xuMg02%{Hr{5juPdMFKaZ& zI0$e(dZSYFF)#alf5kulI9ZqCGo`tASqPcGh~s!%;PSxc1!JCRIyp+#ppFM!Jlkj& zNF!lv$^ZRv@1j_0=6Svz<{r|I-I?Nii9LS=Nwrshsrx3~8)&hnqZM%4$?$L69&C66 z?YBg!*Wt2lV&4?=_C9*ke#m`S=Ge=B9*_556Dn(p)ZN~Vy_GsidQ@T0xnFWR--;+~ zW^umOR?pA;lWKM0R?UACKHu(=jepiQHpdpXRIl$zFf(;BIiUDcpOnU;KzZ{){k_N$ zu}v%&GkX60-J7U?bf$c9EqN4?e!25cuj)i>+kGwfuSXR`{&|gYo_hVp{2N?0snQ=e zaW2{1!nh`AVteK&uc$rO1Cm(4d;fBVB~qUH=_D?)MkRLwrx5};bh0V_d#$Oap|6^~ zYeTwcI{F)Tz8hyaN`ows-^(4v^(A2vl^-hK{`)Ud|4`ely7#7hz?;e-!N5lk;*3w0 zq~~pJXPXtd_1^+`B7L53iPpI?B;D+~3u%8+_}@v<7*{kE%)lcR* zaX#EaN$T}`KS<0&_)nNs(>ZmQ#r}nvDgNb4k=F$x4)-OLi~Alo{_O8OSDZePCZv#pG{v2;&LtqROl&R zI^FNqPkK4Cd2#r*%*uBA_^VzQ7Z?5B|8E`(i^*5IxV&2BX38EJO>kQMLXyT3 zkB;<;^z2l}V=ZrHmw_YYdP=Xh9H(%kWEDLT$V9)k?WBEd=5oi8AQhu-ihsV@I#b*@ z^QEHx1znxne&+*YbL@YZEG)S1<+D3m{qBq^t+?B@+PRj=W`RxlbbhuuEib9puu`pQ z2Oj+O@FE?F$X^=`Qk>QvzA5zIBW=1-S<5DLj(+IUNv($~(}~ym!dB6P@iOxWvFE~fXtgH(izO7 zogF_94|!-Dr&Sdei5TsS`tvrkp@L;bNjY+ex1!q9!Ok#~)I34HCbKf)%w8{Y-{5(> z>lbGk@~=LJ?|m1r7+vjEr+Hs;E^Rk*$@_C)yp5DXH8|TrUYGnR^554znyefe#lHKT zB)MsPD1Ey@Gi31wF;5MqhC^=Wz0I-ucby$NK5ECgJxIPyr*?xx=C#3BT2JQ#`SvU) zNd1)BuFunUw5=e(Dr%gz@XwugN(Mr%v67jATa(R9IN(xvg{+jcVQJuN_5r zZ9h5_jM5F$O-y+|vObQA(z3MVhUXH9uc?;;nLfLE#KGdHL!(9OkzIUhw%0drj7&Z; zpX2?3m%37Tl5fUJZRa<)IihIA-|iF{eJowzAV2WsgS~!f`d|Rr$0pr%WG23 z^0-Tou1_MG?a`6#Gw~K7H2Bt)VB{KuA;Q zQKF%6y~oe|U#Hf2cz6UJ)rmO8A|NuKBe-9Ne9Lf1kZ&@rA0&=hJ8Py`Jg(_6Rh{PqsdqyQEf^-Vtvgnk#aj5#BRN zDXHqt&XNqxbg9ycA2(F(Gp}B)yji(BNMPDJ&x+}CgzH;pUKZ;dyzrT6N zaDh0AEfjY@qDd6Fe)FcNS&p^E_xgH06}PU!rTVUO$B#d$LvK1cF)=Z#y1wM_Wo}vR z;EONBoU4uTVG;wFzW>qTk&$`>sBb>`<(Obxeg!FyXA#iI6faP|SuNvadMLH!U_vE0JNFw|$+C{GI84Ax&KhjHX ziCG0vs*OmVj~_pVIgym{!W;%?hkPS@j)*^g9BrM9b_+s&`s=~K`HHJ+B<1CI8C$QJ4UtWMcYl-GLW(v!9AZ^b-L0)|R%9x%IMEq$ z`}Rg)O<64p8R38_4X@nD=3b&W9@OU0z>vPnoYLrq$G1VIWB(P-I8_S~Sq5^ch2wNz zb=#B9T$!QvQ<3d=%)N!ur9x{z`7OBwYJD{PG?MP}8k6ZMCCE$V&CNS{>J3P*1J+7^ zVaEOL`ZX)sMwtRKj>cW`^5$kQw3s4|(%VeFN?uQW2m4EA(^J`oL71z{%>6ncW{)IZ zsv;2Wc8ntipow9f2`vID7!9$qUL4qHYdkxVXPYqgCqjTJl@R ztixI67&($Uh>1t;8?VCoO0#qmS3U^9pm8Z7U@8o!k($oV&M)EhUMlzZCi6$Wp1O5W z++E~>@mXF0d&(9^UiOy*o9~ZO`%x$Dj3iH)oh@`%VO3M}!2*ldD zx~jUm^p@~ok#69@!1j-(k0W6u4ieKbn@gb4M?S|k09-4%JjEv@Bm^JNG(-h6@Dg!9 zn^A*I9L}nF@z$C7c~~TMr}BaQNMn-#LafHumync9#NRI?udfgw?v-L)h~wY|AdGx) z^ua?{*U<2;we=Au>N(7R1VnUlKQJqRCxl@H8WF<%)b{#%&CkzVue~O!+@{|0(~`;l zV~ZiBDnD+t(Fdgk_77ZfRxNcM+(I9*dsu|!*WJqHnr(OgxA*6Peu`~dP^NkuCv-GB zIsGOR!wtFQQ}d~Fjt{4)mp^$7G!ER%b#*qEj?sM_EGqf@^bx?zWBAS;f1nub0K&89 z6f5~I=ANw(9(J_1v>2&CXZEeS0lWCLH2f98S03WoSXxxu5Mtp@ydCJr#l7_Z?Ew*BPxB7d5ZAWj*D4b)O*y~izt(>;r$+VQYZH2k6 zLXJ{7sQb#-^yt7?ik>|+s_`n_z24`IR!_)q(Njg4+bSQpj!-XYY!77>6`%3!;tZv2 zKP0&n&hry6K2(9Ubj_K73_BFyvP>TbG-)-p1~4TBYQ&wv zTkaElH8(S}Lv>x_cV0*c6_n@Lr8f~pG%!AXH#ax8w}Z%4At>xH)xWo3!n<=v%=E*# zBZ)jxKV{164{YWu=vAwnWHo9LsC;PA|DC7tkbYyT#vxZp6RIpebN+u%?cnJw=K=S3 zLpff{uYFZs9d#CZOB7272)j5NNXzkYyc%a-TckOmZ*amP;LY<LOp|r@xpY!##`7IjKapp$Inc^2G)6{mLAYv?7+b1 z*zghu#1j#F8z9(^@o}rSyJh1oSK8Q4`o6l(d%gR*5}WK#md{L>jegAJ&jc+P^Ywhz zyYWt%7?y6eh@e5#s63t^Yk&0*MQ>`e5}8W*szp%kEXTjS%DQRJhosH1;fFY*f{>+3i`9>N3F1Jdav zD?7W>#K?$Qq6n#a5PHPqU(k%zgXzg6hzWPR$BjGN@Q`DF0$8G1{)e0M}9thG7G*yAV1~IRZZj$f*U1=NdcE4PIxa0|cAF&M? zIK&9QI4xpc{rsH2W?7Vk@j&f`mrL5?L!28l4L6`MLS`#8u7jW>9l_QfdNn^c_rhcF zx;vxA(BH#Vo+*WIe3 zyz8l^RTcEYPHm}ENBk6-%vtEOUHshDr86y)m7&d!TieDAF;vsClGrMzD*L5gJ*Jo< zU9D`1N)sVtx%G<;Ye0p1N9GTyiC*wQ)<#^`xP|n}e?Qxk~ z8=SVSCQ!M*dQO+g&j!=C${=vz?lVP}UB&0(ZOa_Vcp=%K^oqyeRuYnvlN*zB>q-iQ z`)B6wf)^0_VHDoaNG}pa7VB2ha_$7e6JHo=UHe<M2vG@zi;J}@x-hE*prmY|HvMe z0#(hi;F1!b+v^J;?u(D==}7_bzZhOnaG@7D#1m_)t73?#V8=n{It%|j{n!YyUbyyI zcV+~$bf?SIMQokAQurvNMtA|nK`h&PZo%` z)%ES$RzDT+DWL&NKj?0PV6cD|U@KCqM&6<{>B49rKCglwaVsO<4Foi1h^~@BwX^i~ zT`9xYJv~3!EnfugIQl~|*k_ZLf9ir|QN6}4l5*jz$_Aa$Z*mj?%a2n#-IF*dTd$tG zyLW|SYiLB{wCMC^K!FcyIbUkHvcLSHOCxG>9~KmVksmQ%Gi?jp1}O3d&d$PMX#^!CHeocf_5MMF|MOl*h>5s@tSsS#I}g7EvKqW0_VES* zJI{RO@5;&?h|3?7lb_(xtVXLwP}n8@D{^>vSnk&emhr@~8I5w(0m3Ycj?3fHCGosf zL{<=fJ2Y4rU~b>Pe+u|DGA`oa=)}^gdF?Ui4CCW%H^dS&z(wZLmiDkJe^Nh6YzM3{ z`0(t}CniTnYcNaT-xIVcy?6qL`B_*AVV)ZJ`4fdm(|fY0gTB6mj+S;73e+t~w=ocU z0lJ7V@Ey0bG+R>KBerA5RY3aeWjSz;uKpd*wSMczm2IXE`{5G>kDX|#rCx`@dtsJq z8yX+K9Y@b`3yUw{OkjRx8bjSb>5qK~nG#JUL|cX;ku(kPNLLOwJcdAp7vI?lU-)cS zA<`!|U@rXyLJvDcH2)JeA`t-b<9 zD>jMLU})35-LkvcuNzzy3|n|J6Mt!tzo&e<|I#~+e#2bgOL2_Y{(K~P#Rn(384=QujcI~&xfk+o zE+U{($sgy!WsKv4Tc{#0PxYD-i5*1{y5GIWVO{3^WO}lxHb#y*-Lg)QMs@Og7 zlTL_|8^;^nL*Ezp_m4{^wv>WDV&;w!fe#N;GGPtTDjiJ+qr-(ln`^T)gTdvqCu(au z>Qzqnw{K~_e}2yNpsixae+=VvXGLJecZk*A5vtUk(zn*u)*^}Tcm`Xi3xkUR;fgcQ zHoI#r-jUJnN(_?O2pk(f55k=XGeJk+M0*fXkEsZ9CVOZ1uiD|+;EEoCPrcF$GR)O% zNyQ5>OhhCMTN}e~bmMw6)TB@?fpO?|vLSBnWPeMBvHC08^#YK;jZDc#7DG!=h~70m zc<@>@Oe4RcmA6K{Ha*{)gs2OeI%ZMxoWiyK5Eh&br#SXJB*Q9cg+#3$7hn~|eXx}e zRX5;tNrbM|;fKgQn)TJWqcPYMO4uCx3Vr5A1j9v;yK|VBtg*k|r0}cUB;Fua#Vg;z zQ27D9-^V;>hjfS0lB`-oT`j32{hO2x7YBYp({HXgpr9! z77+|b(sg-*ZEdc)RMMI9>IjxFFdoXFo)(gzOdktk<=4&-Yu>(zT_tV@%u4<3=5~V6 z>C~=4lRdODRdE{6{T>oPYV(nhLP%Lbt-$Dh0^*INRJGbcC2TexdG{f#MPzP$LG|Am z@)8rxDSV`f?{6OCyKr_c;zKO`X+6rN>@7hkkuagrCK=6ui`|Ai7L=C3(b1cDuGjg- zF^7qx_PH8pI%*;3y@e(XnXOh2Colc(sY6#|f$SMr6p2VRfqhd|xt-W_ zop1g3f*{zDiFs&99zg!tAa&WFCq|nJvBJw z`Y{U8bVIT_gFncTW$YJ&PLg96iAXf`L+k21S79K+MsFhW%V8AFEvyE#c7bcMM`OMn z|Mem%@gO7AM5v1hP9a`GWE5!{i;t=~F=U;q5<0jfWQ`H(FhCPKH%7m{DQ4*m^m?TGob?FqFbi8sipl1V-J^mk$YXV2aKBQU6cqL3d(c`ka-kmJamxS(JXq1%{45AFjnulp?C zs|QL{g{imU#r4(Y1uU&gCcTvVpv187$YmX| zw0t^)M?CNudJEb8`&R}~Q*s-h%8t9QpDpJ`>Dw#yVYjHL{#STul@ON0armiB9rVQ= zp|D_8A~UQKMXEOo$N6WxB`0Y}61RjU?gXeBYKH_RC7ic+2&og22c^*PlCf4}8(4)5 zZXL^P&&S?w@rQVXmZt||j#4w6UoERBlW=(2DnU%|1+!Te+Mhu{10}@AjWQ5wb?+@x zl#!B}^;B0^KaaSaa9M7qc)!`(02)hsZ6|ROnyA*7(6_fhlzTPUcGGgL}s!9Z6I;fW0P80Op&v2wf0-M{qmR9pa_XaeyK zsQggpFEdo65(CASPzUIwC(jdS0IXX*ZxO21j8ZR7hL(CWzEUgNkWN41J*-p>#o%?l z(Mt}`wk`i_hWLqL=)4oqSM4GZv1+am#}pM56gW+lFWMRq-wMI&ABcYiK!vbnvJn@d z4E>7AfA?A4S7(`gY$-`M)TtjBIp{w_NuYD&2($9}{>pg_V@Wk1KRzWS|3$J-pDS(_ ziPXbXADD~6`t*vg?`f3FKbE$(y&s5IhhM3kZS&^qvBjrs7~x-Y6BbyYQM$~?76-UU zc07HW&KhYH^_c(PL0EgiuJ01@<-Xi`m3e98SfL?%y|`U#zkmQtUvvOx8_cMP;8SXPH&LxQ9QO%;#=Z9o7xqJ;ti z{xX>3Z%Uv2CV>Qn8x<95Xm3}6dbMR)Jc8T=Qi+df3kkh8@*;2!6L15O8K#$f64Em^ zvTrI%YYjRdWT5gPB1jt=8ywr*^6m!5k8i~hcrZKX+v#Pf&L~?LM_Qa^xM>-;s^d8> zq4w+Q=JFEuW=5XI!;J|+seh22U`QtmEi}Q zphhq8TbBAajE3FH%1YesZ6k{D@jV`nr%p+oYTOC|9qw$P7Ky}_HXDeM8ww)L8;rRA z=y|Oif~W}99v;h=JO^!P1PwFWi9|+#m@kad5!-B}v2pnhk-C9X$`LQ%+Kn3sfO?0| zl=t#wWnW)BTwI)4-7ro=d+gkjw2{cE5<<9W|11D#(s>AqPJMoMJ1ds;$f9scra=OQ=8G^L({@x`IxIr-`?vd&KmpE^psMKAzwc{mI9J^X zO-}z6Bz){7p(zsejkjQ-k4PR#3J-T!D%qmv;l^^%#_#-_U*q;<>-G-<%04P1!TEnf zx_7_5In-^+aX+DgQe8iRyJcd1c6Gj-p-@Xt$UBK^(|_QcVRZFCtIwH9nwI5z`#@OnBNb#nw6cj{NVV0&yv64WWKrBb^q^T zR~q+9zI&UGg#Ru?guF6ych8x?>~a4Y(vlvYjmCrPMC`;M{WK7kzP)8-C=-Fx%{IMCjO{d9|7@Uqp7>1;&jVj}iNhaC6AhH_2_6ac*8i zGO2hWY&G*J?Pt}{yd6g>ijjj1k<90*XJBCBjj?qbUSLXOWF&3nyLXyJP~hXb0?3)cvZs*qnxr&dv+c`&N}y zU}Uc+@qVM9Jv&>5#xrxXfL4UUJ0J48|1wyifk4>Mg}?g~QD9N=@pfrpVMo^x;n#{< z`HeI8ue}b6^)WCNvLt`$_6B0n&BE4ELc(%V{R$XWUBvv@$jAsce8Ag)p)v)9glO7Y zOr;aqjwtNbXMlca++HCv>~{zWX-S^zRqjCf?ZTv8d{ByB-PSg40>au3G*1>1KGogb z`@t+7U4Zx2+f{}e$y*nSr{_i{Cu8B`UG+uTo5c*N`01Hq>o5un&FQuMUSkm+(2nh- zN!1t355jutW)sPP5#0@A-UXl|F@FdWWJ0AcK_euKfcvp6 zpB_b&k<^toa>ur&3U}J9jC%E1-p>^gBi}tIc2j$ge|hIqy&4!Y?J#U>lV~Q;;S4d- z1GW8;zE{IIG~f5V^t#wN9+_f$&Uv-##iT$Vj=&PYyMSXIG1>^T8By>YJ$e*af|jeR z2+qcn=$J4zKK`bPU_xZk5}r?v9zZdiI8_c3nPF)1(#>=E2$g<&hVF+mNZll6T!2Qn zbm#)4jF!djHYfW~vWXO*qpCg<-Gz9pux@PFzJ2@Z+8SC;-`lo>H_)H4MO@#Py-iWa z=@;@-KA?^=)c?kUi$!~H3?>cLP4VK-O(@u69eE9izl%c0!pTJ)tLm>b+7y2p-vDOL zP*6;B*oT~A*bJMXY$VK4KoCl5^KVAR#OUL}5+9o3)G6O9S7uSDF90JXBEjHLKc08; zP?a1J4~eSn?dy91PK4l&?)LUb!VcHiXb>fCQ;!Ir133QZ7p(Zu$l#|^bjGhE3N2)5 z$s1>p*^oy}OpGxkV~veT$fO5ee5HN-nSuvpsMb5sJ<$ptC#%-5j)4H)LSGvB4Y*%$ zRY=2FPF5cdsXNwj>AaIQ1y}}=chifD+L`Sf zW!he7tkCjPCslcAid(-9vKH6QHhToRAAw7thYjMCqY)mOR~t}d>82se=LAN-_0e+hP$xuTt_m-6#(jjpGN=<>??*#Oc$;KpP{a&5GU)2 zD=+0@?UlGfORa~hI|(~$`sJ4kNcy|Gg0x2)jP!d^)=p0h420A5gSTLj06%uzKY4@z zXuqSCjUci^exnmB^`<=NvxZamQt9ANS~5cn*vE2=>icmRM-xc~#LW4=tqSev2X?jS zPRwKmqN15)Xxn*MV0Stuzm)sJL`0S-dtHcYbj!6aF=7&aNaBA~_XJ^Qw?{vH{c5)M zk>}idq?;7G6P~@j=O`;Nzq6Ne#gvYgl;Knkwe=Zh&jn=VL%4X}{v8u7&pqt~=JT-S zkE*~}z(2{2G4f5a2wixZ_^1{i{)iYJLID)9cZoI+g(yAsa7@Y~<07)yINpF%PDR6G z37Vn~%4oAw;UVCMQ_zX0qjq^Hqtf~Opbi2$)k%rF*JSW5?7m@S<$Hq;XB0Booh%1I zG+*4i9o-u{xaX{9#W=JcqZDlC&g_V=k}z8NB>zBYIAWUyd)zZ$icQw*oi($o`pJ5? zBgDh1Q?!z=L8jA*EJ1!Isd3`5B4-cWYRr zqYetv{tCT!51||MNdG3%O%M)NW*>{%Nt&+P9UtLcPNBLoAsw~P?g$W948??cc=&!Y zu!lpmWG~_cqC6}ZhILmT5IK7R{#_aF!zEj`AaI`OD@($TJ$ZXA7!_d#GjuCfHSU3s zkdoSoNC-ejGw?Hc{-~w_5J==M-6`X|$;d_A;PKjXm>xAv^viPxKw>oQ(5>ikB>3Rw z5#noND29q98Vd*c*h@H1U^!+10fbXO1d~LXeGDo=u>U{!_OnvzpjorpB^1xj*B%0( z1+#44aImtnhKwsI=zM>VgA2i&RbS1>=2_JRWH0x=io?!&!d_>`B1FY0HuP?k)L?O! z=b?EOIY-v^{wTvkbCrjG_Swb#fA+opOV>7KUgWW+{Y#(J97_^D>adHepJ~^>L@A)d zYpJ!JR=2HRubpSz6e;v^;^{YzWZmTWdiHCl@0(>hAyLDf5Hq}jS+2X(>x?sckv~ys z>sXNyBm|CG+@O`j3W`eKKeHkX&rd=z%Nm}N7zvSbo&ebxqjnNLJ7nFO{KG=Lex0;? z*REQxweEJ;qO&+St`r1bESQ1!#{I8^2c{)%*n(n6h3?-ir{;c+j6{w8{vG#^XArL- z`7JfczmA2(%*>oY>~c((c2l1C0d~Uj->Y^Wy`B#~)RpntS6~BJ`EkStwwkH{ND0-@ z6MI=uAbNRi7(po(a6GueA|?v@-V>3{9+_nYZ>^C=;mg# z)8z#b1|Lr(e08Hdd{;^JZn#}-aQLt+9Kl-X^<lApg-goD z*N{~!h|Ia&D2h2;f47|cGa=8yzhei%TWmA7XYQwdMr}5PM5QfEXCGPCOKGIZU~ClL zn$#-)n!d%r;mnyc;7v-vUf-rBp}RqmFh98;t181h_Xrq#h+VEMLI%aC;08uFbLXBt(A_}fBM8Eni;;` z$=W)JQld1vCz+`^sslSHcX1tcgv#jlGG;_LFhPj!Nz1YSSw1v2b_eqZvd01G<{j8b zx)I0u{mhI+7}3{0iHSkO%!Qip87(W}(@wLicw6O2g7-a2%);omL&PCFsjJAM2aYExqH~*GgyfnyL?DU1CK_LFYp>SBh>Bd>nrEb03F6)2bISUcoJThlx${aH#OXt z_;Mhus;lcMCM=-I?il~-(RUHSti;G)6;zft6S5=q*|v9@TAiIOHN5^C4}HkCtBAv{ z-2i$8@URPNQ2O|IID>kIM8ZA_e(Btyi9pg`OEYWRs>{4@Me_`rHD8D;t@M2}Xj~`n zd&H&D7vJA;KjCwert0*@w%^pJPI`WNl!Bim)l!uT_%AoFMSfj8v|?IGk)Hbae@C}0 zGmYBn!7q(H%I+VNzr0`ja`e{5rVYmWvSvA9QEks2K}C7E?{e1cL!L8|m)rU(3(6XK z^&1!bO;Av!5sw`$T?yTf03*{n6^snrRCoYf_cZ07{7plB`}2FZkkH4i$lq?ch|bwb zF3vz#SCU9xFmf(x>F6a&RO22|=r&j)cO>y3x;W;SZrrn9ad3%F@SWcwHO5vU+iI&J)`$EC_awHwxqFEz`*k$dnsIs{j z9ggo;R2+s;>3eh0W$$NOITvp{~g`5ossErzaJJ4sGWP7T~s?LEN&g5ew@^>_LGA<&_mH zM6^`9;0}!=ko0tM+IsJB!vz_)r;yAWo>(OTfk^8Ii?4%he_R=#?Yp?LwyN(kLNy?^ zGMJFX{7SZ=ywognuduYu^!{)@I+1c8g<%I*ih6CaC&t;HcX)o$zGtUDR7J{HMF(zO z;(6$t?m1)*lvCX+T?_u<`J?peq3>A(0~gERGku^2oMeAKcHm-2>F{!e;Nu3S&*EP{ z*z}SE*^iZ9@hV?@Ja5gxcQ*UpYe*3FB4Rr*uT;Z|hH)3H+w|wz^7f7Wy{VgnJk~q|A6*O zt^34e+`A94*f$z5k$^gA*LF0GC`N1`yL(>eZ-88zliif|1M_=PobZQ6O+_e zglU{XO?Qe)2OB?HaCN8jDxo^@78t+#KP`X`h?%j@6PWOC>TTV#?J|PtszwhKPw29w zM9p-uGs--cWIgA^Y|US0Al3dn);an(WcSHS(*z>{;J5^er;(?2IZDL*a@h8st4 z_RkxS-K)OM4E!zSG+L~DkTbt9f875Kp!~{@L4s<{K^Gw`xg~Y~7n`mX{bZwGHY3Bs zk-k8w$AJw<^dXg(DCc7PY)Tyipz6s)m9zjt`QbN)>BPU`Bv8)xerSl2602t)e6BOS z)|RXDPqjw+PLHiU<6yDII}TZ#T(3d0#IZ_qgE?~TuinY4=I zDv#VF-*Nu_6Y-Slg7AjtqTA!1J+uBDJ{5WRafGvuj|i*s#?r-WZ%1{C8Tra~(^p&; zS@H6H20mUJ9fSg=NyHxYgFpdzM%;k_ETsnRFcD}`Mce>*#mY9K2ARj2;HyOo4};`I zP9Z%y{=IpPZEX<%S-`q50&@QdC>#!-=Qtw?Unc)=$a20et|LA}GuIwDv2ZH$R2lpVsdBFKqZYl5_VLK~9o_l2X)hcjtwQ`&yZsO-c2d z*}<%HAR>+(cyrUYkAW-|OQtiwtXa?dYoWxc*<1LvOitJ9bqB^Zy0xv&HzTN<*%jzt zkLHruoB4hQwNctjzg*1I{+|||{XzJ=Gi%}_>Fq0y#v0y2pqCKNas?fGpGmGo!N)w< zG`)y^#Mn-dgqE6J$CQe3atb)g4W3J8ls5CkD7*}2yk5nv5%3YD5ZAO`Bw~z+{)>s7 z7OGg~?;b!M4Ip_*UJQ%;t=OiLdKA#py{eAg%F5Oh_HJ&m=H6z0E{NEiyXZfRJ2=>r z1xZ80!*zuHZVsgqP1GwN0z`93Yp*K6rL08>{_2N%!+^_ZAu{nR2~F=C8w}!GbT`4- zc%|D=K|vu6>E}ZPgS=!JwXk30QQc2)jamQ|rAbCcMnjmS3)VpE504;hryKzSM0j~J zTi+4$Y;?&Mt5p696za>VcJ$S(Nur{;Uz`bJWrz6?`qI{y7h0N5=(TFfyAF-JV|KXWiy13-|%fzkF{agve=72K`p~F)?uu z8urX~&(Y7kAx)FOr|z6xl!3$mAT677#7cwI|5rC#q#iEX z*$`AUwh_kVX$JFYGF$e#p~y18X1)=0hU`mU_}%A0S*{Sr>1SeFh`k=S}(b4+uAt7Rf^uMthq zm!IcY{%apLn0_={c9ssyh*A40si)zc0#7~&H(qF-zkMUdS-ilpbxhZSNcRC|NYxMM zza1v&KSIy8s|EDf#~!uOUB)$hH&sO;jaZZ+ay=hG&GhcH#@)Q4B2zTqYE(oBCHeGJ z&bt>%U9`+(xz2ANuRl=4b0JCJA( zJZS+HM?zXgrjd|69fiWq&gbHVuV+LQ6-$hAWT5L8N;oKTgtP zH-=6oUt16tWsRD?6Xh56CnG<&-JQ^b{`!?$MD7zsszz|vyhT_!grk>I>Cx1qyQgDY zx4g16y`w2UGv&e=j1r34Ru8UT9UGKUEV*d6ACvSu6wKzfHe7kjj8K3HH~gIe0NYNM zM4~{30-B5b_z=|S$F6-Cc4Cl}!pO)-1R$p`sCW!edzM&F`kn; z`3Kl;TGZIR7u`d%mPb`oRP=k!BYE`(lQAG>HU)nAAMGkA>( zH!>uS0pFZw*k1$mrjTL3yDlT2vci^r(A~v<=I1}PcI#k`pnkXlbAr0+*h!4dcD{F} zFimzs1)^MXy}YdKA_!(v8hccN>!TM;UjXHqAt95-b-Qu0Q60FniSIo` zSBGANsb0B$yWoOJuB{4FKiUSTfWzf?P@ja5+oEs`e-A8y*^8H-_rkT&!)pfKX9!D5 zuf$s1)pjy0&}<>X97FiWoJLmdPsSY3B)+C-h`N!+YTg3_$8vTOn;0#*-Q5L77T z3&*Kxs|@3xd#E$BpsO%=9$Lb3N>WXx&e;SPfO! zAkUzc--pF7*?Tv|X0jTO-%hZ5+i7&|vU+a3sj;S`huwymCeeLyiw3$vUle0X{`0R@ zTm8_`5#x-HSiR{V@amKlw~4fP%`NI5-}BCP=8tZkDH)3UGv~Sr>jJT~I)7E- zO2o~7fQ_{gAb%wAaU#dLLPkQu@EJ@BghcBr6sbD6=E%HzD{!6hYuLYB`+%!Gef;=w zTxjUwr+COMot=t#Fb9m~s%PW@@=S%Y;Rt##S!ZmARy1z{hzet!pPy$ZswIGsh{^A7 zIvPLBHhY0Ocu!HG~nvTudkNi{NIQvD6a<>?L~h3c03&<*c}9N zwqSh_dVQLfZ|2vqp=m&>z9k|t5Ru_JB!dXLTYwjYe*OF@ta;!-A!ct!P|LEpXxi$b z!SYj&eE1x?FAqpDq!G#U@*SuuO@O3v+jx1iOWeBUq~+!15tdUkgm5*s+ON&%T$k{f zwBr%2S_qcL3wj9l1>BP&2w+^7fU-rPB$5M1cogaZmpCyJ&=Ms=z*|oA%ZT?^d4)2R zj{P^=-*2A{9Q6sIc~QqSDG9|nWfK{%iwR=$U4TCizs$??@x76a6YM0`2yv|yu=g*3 z0ym0PERa2)#z9<&2V_#S z4KholDSyEIhjl~3< z_XSM>xI8eCQ~-R%Eb^&AY5`HDPjV+$kXO{uZ}+!5qgj|^TzXJEQtr3P#wt^p(z zvp60?prj#m2{>oAl~ zIKOq&*4_fQ^bl<{LAOG^M+DB~<>h7BmOsVnF-q2BN5aFi(-knBVCQMzRvjShATx>B ztfDY|^hbmoo<6Iowzhx5!t{dK`dNBG-nDo^QHDyE$w1*5)hQYudTYx_uGH-dpQMvkqj-eNL&wSsX2{1xD8{TOFSN}%)G~+ zMqhYHcDvQq^Ay4}G{XO$--!c@lZ@axVrGH8i z6Hj~usqY|{A3cIX z{%*UfU)p6P`?L~p?ani6C{uP3DOBo+bZLbwalsooISWL!Aq4nWMf1D5y6UkVhPkSR zAL@LAI;S6JnlYgq%E0n0Le$ZjtGC4nR`{%|t7Xc^KoT!6?=ZwV{vaI+oO~2=qVMX#+T&!4WW2atgOojieIu3*LO(! zL5D`n>y}ZvBWhjy+;#?g@M%}E5Ze`e7qVtRi|03`W@l$FAv`6HPto(eLLeO}+90L5 zz1=iU@xsR?JSUnfRTh?(DTwBitVA8$OMV44{}U?0g*Z_@bxmyYsz;D?#u>vy7A#_E z)3>N8OhbCniV-)O<8-Y3yx~DIo;~3iM9F6JymqHGNtYGzgiX+^e|vNJT$~#|4-UA! z$*QOD>GFz;NAXn&(^P-I;gK&H$cc|7!ebGCC*^VS$U6&cLPCKJ4lhttiR66d%;3m~ z7C{={Qze3!FaiimR9l&wb0SU&h>ree$l)=m&YdkTDsqCpLk8Bp>OneFtzdL1FJbk3 z<^Dt%h*lesXob$x5E4&H3@;qowm!&_yjNOur zZey-0#R2aMqG+H!wEwYQay`0@o5+*dP1GI~741?qtWUA$Jz)+lB${&E!dpIT;tkGo z7V_Q|2o$u)5XIhr?Z6V89v5+%@?n_DDy^w$Ym;$+dR>)tU1cA7nehU26o-NM6!G@s znBTUH!Mp~CQfBi?|G>bOR&d)lajlNb{KCT5$U4V6z;53MLZ9rB?6%q@Mf4chRb6Cg z^G+@AClQm$UmSVDUrgu-uBkm@1NuZ@Fw)+rf{BnObm3gJ#9Xumg!#m=F$}}Ll9+LX zAs#DQ_IHwsmKyhHBA2a#kvxh7ZW$tI%h4Jgjb6F`%Bw|mH%>&4f!NEhEp2Ux&=Sf% z604LBoZx;_-~<|wL7r^Us^uV5Vt$78;_d6AZu z_72GXC8EeoW6-}rJXw%@>990P;(uMxq8M=FE-y!L@cC23HHHtMNx86ydjFSb??5!U zSX)0!DKGc81VLbg5tb7dikbJb%I@5GU=9HIM@Zvm30aiL{%eMnV*PXpNo3~_OgA=* z7?094>-mRR-`;Anx8ivH?bujeG*!d+)nKU};x~inbAcrWB}LonO@HGq_!^MdMxS0d z?cq#bonyf$K+|&TbTss)kZQxmSIyIpxl9Z79a-QX5Z{dPoRHQ#3!Lzfk(K4bAVN3+ z@z2GMKPb*UjQ31P%MbaB-{+RSgES|{)F(~E^MqV1A4!*J_HLSpB%=ZUGu5{p!!1hY zA>4=oEo?(UA1dWfOr}?Fw2Faq9>C-CY56jm^5VrifWRdBY-3A^gsWOxSHmkRwDEAXHY*Q_ZI*4;ve^qF9m)3})rzP;O!| z@fb~R@HUja#CfR##|R2J&Z^`_^BB1`kXbF(Iv{uacPJ!}c@ zpWUbE6wRd&mRsh1O+Nkxo2o5E;QX#Pd*-KQmZsPrWRUM|s@FczXUIo762$u;Q>%O<=e%B$5QJD<^8i)dPt6UL?=Y&c7~di7MA(gEk^ zV=m=|j5VgCQq4j#GBPU+Hw=}CZ-($X6qo0@c0VIxtF1&NB{$=3i0$1=m;jw_3YY{T zNOk}+TR07bd+GX)0ckv7Wfg;GYko=i0F5^~2sE>>@TWK5z06)EDsz9?ouyv@21;kp&98GWxL~_pvP{}Mk9s(jZo{H!mG@M9=c%(&5hcgsX=T+eUNiwH*ef< zRl_}bi8`$0-^6tuMHqoB$Wwu2UpZVD-w{s1kBPxI=TwPxZw3C*2dDdfJZ;o*3EY03 z+m@)NHN8|aB=Xn-cqjZXFr5#;YKe-X*-|_N)K?!z;FjA->VvKpxF7IAcsQJC#@!pl zP3~biNV|2(&@ykU#e%M1TY?c0-y$5|*@}w564@se41B77I;blMG}xhJ`Dg74Cs27H zVa;E^Y6(4JuXxAv6U`oe1{VSPqbCQPqV@UJ>(oP+NE?`#1m)y7rgojXbaVLA6@HEC z-nYIUGXDM@ioM4<&8vSMQXF=_n=si{e^=Yv_x0hRH~TNt$Bt^QSX}SeC*Uz@5$S}5 zOJb7k&I+Qfw3wA!=b^HAl)rjigtwD7LEP|s_>-17x&XS539k0>RyQ2{?uz&Zl_raY zlKqd#uBW~jvzMS*qS?xPuRg0_)23y+f1TB~1xsv-cbR=!PJd6P3?<7p&UY%!YRWO4 zs|y^n^6;M3{I$yX{`j|DQ;;*61I-;yhNbofbBm9FCcR6L{A=pv=-0@69 zAuzX3!Gfha;p{L@IT~-v*SVwbv`VeZ>J-iEMDBz^yZ1Y}$ux${U5yZs5|5Y$VFV-M{~`uHx=+W5pzEA<9R0t~#g++_41 zdNg8RPEcA<{oPTOgx_N+R2hw=#kuUM`>vKj4MQ>k+o|IcU4_XD><*m|a(jNUhne%` z_qNMZ@h!h{J0!bToyUHs#H8#;!GF+`X~Uqa`vqUeMG3L)Z$EX`m##2b zQEe$ZbpH7Mv^^Jm+Xfp4&r|MXy?r#&;Y7k=V=GqG3}c$;SEtrniC;5J+}SM|6p!f1 z)}Q49Cr_S~!IoGB+CBiEZXPA2mqG%6-VYA+T9@^Xl+2 z=N`}Yv$`5H8WVrI>iYkN*p1`*8*3Yux)NHu!kCR+I~fWL4@gP>{JVGCs+y^y3fFyu zn~5u;@;R5ElrobzqKkJde_gCCTif4JI$Eica73|YUPywr%W2)_ICHv6niA=c#zoS9 z)c}0}Sx_&>xww zBJ`7jytod&VyDBER;Nppn|e26K0A_$DP!is#0J65Q9hzZn>SYT95gn51n?{?|6Q6y zZ*T8E#-({CCMMVp+-bCSZE%veuOt8dM8PZrq~jrWx+_=!;H! zWpgv`K;*a2T14_8WIFl#LoEr4MshbZ(`v zp)fXaY5q-l%t_fy(~~d0`+8eRq|Z2ME9K1fHr9W4R(2;6%4&2eNgr>Q11 zOLYG(jZMAMQqczJrYr_ZCeR!XvvW0N68C93z&l1Z1gvtbGjBt+@7RV1w1rx-hf?@A zd{`RG%>4=X-QT|_sa-8}lZ^;1;J{yWLIeYedj5F#r&9hhrjte&{yx`}P1@?r!)Ceo zVr;u)QKyMnujR&|1L^jkuPaXcEDGron(EAIejIpp$a>AYyNNb?_3*7=L&n?GSJtQl z3vb?QjQ>(|N;CU&!Wom2yz-DXFVcqkvNeg0(vRwg`PsZ9a^LQKpffDLPL=h^+>CTH zh%3l$PnfCboZ0=1Mqg#FBnT&Tjix*MC5gxsTFk(L4t!kJ--|V%ACwkER&& zyt6y8l)0EwVWTx&@Lh$^YmI;Zc}r{pN`gv9I}dgw9bEZzA+Dz2^=a$C0N$Vn*EXfZ z#nyi$pFL=0{HABnZ_wJ3CVivgF!KfV3}c^}4d*KE+l7n<-112gvFjskXQUiw5kXbC zhpOUfFaDBdX-CIjh5o?*qv^T>vFz9XgQB#HvbB^Dg~*CZDnfQfk{MaqdsHeFk`=PD zM`Vwz7DC9(CMzp4vwxra?fm{Y=e)<;c%J+Ij_dkdpRqKyaJl7&Tm0esoL-xg+~x+$ z6n`-Mpt?aJ;8=NC zb2+J9KmND7&Y$V?(;c&^*Ls>o{{5e@`6-)P)zvFC#&xHg1teuIrb@10FQok{xc}iY z4ZXd@%(aHixeZfs5=`6(EXZK+n9vOdU=^y84km-iZaw;C!OIox#>nktB zbdfmDdmO)?_|9(4=EQBb?6!}2U#qQpWnb(AZ~13beI8R}W3QTTJ3QzgVi;!}`bmAI z-qtl?K&yd0Otc_*TjHPjCrMeECjwdvl)aji%>pYmAEd zDYw}q|M?GI|4r^`9>n~R_~pgB0@=Ogz8RN(Z*2Z3Q4`%N&KD&x{ zf?AJ;cZ5H4gsDi7X0gTdzo!aHP9~aaGcveoV69F?YKxyQcf3-=bZc_`Wb^puN4h#X zjt;jB6}}a{G}U_Q8mZr7LJIb3&a5u}Mp~`j{f}Gs(OEV!W-z0M%;x63Qi%a~+KbGp zF6(3)&&^Jvj`;^u693Jf`!HwIAhn}iyKHR`IlIRmMOwO`c){5pPV zVm??nUv%o%M%}j0zuaS7=sP7Iw+jt5JDkmZH}li6vUnFW>1dMF28Cp>uDHBa<1&GC z%MMSv9?YGK`RDjsT$a9E5?9G{;D$@pv(GuNSqB*QZjItkt@~;`xs(&SWA9ZqO1LQE zflWI#lh#Snybl}BW&iGc5voMIaSjz5>AGL;TlZeGc^Wof=%#h5y z{F`oYE-m9Q=hCLC>I3)UUkHzJb0(51`8HT$4Bykxy)WJ!flV=V^Ns%oPTelb-D=MDBYox zj}<0viMab@=UUqd@gE9I9!Yo^?7vW5>2~Dx3hQ7gPsGTBL039?u3|d|#b5J$j$y`r z*C-sNa;j`iuv7j>*7P@!?iO8 zePLm&7 zvD_hwPPK6#o_}A~x2d*RMcIVrzixq3cbpj?CsQb_E+gA#6?8XxENOb*G?PkgM-sz`5AXOUa&ChsqsQKD z`MXo)^8HK?o)o!V^9pMX3|E)B-2dTl_Q6^)k}3Xzqc4-Mg@<;J&m24(+%7iubk7Fy z@egic(+hWGR83YO{`n*0HSd?NnqN(1`6le-eY-j!Q&V@P^GWafb>EsjArroo$I0cd z*Qc?>GWu}m&lcN_lu}))0zUU&G~?*nQQ59G_=h*m_EMWN2P zvqPC;RpE?HWm2-z9!0)-_19G{LySp^^ZA!(?Q^v{FL;)&1ue<-l|4bK*>yp5F^2c6GiaW6w!$){YO4gLc3A@5@{m zy1SW9fBmLln_1h1v2iki^5$BrtLd@C4*TeQg8Pi`_DfRO$N4T&8zY8#cRr=arP5hj zZ6AGVLu&2Pe&7?cL(F83eQ{Q$VEXcO!Jc60xl)$yNl zOFIM|cYr@_gX#FharkkUi26B0(svVyG%LV%R5?o*R%$RSKp5f|H?S22;=30iQJ@5B zwgAXHJMGC25@513gqQakrbaw7Oc)R`fFLgnd5#7xt&F)iJQXl>IIx0Q8AGY>Y{}MA zI9$jOKfwTtf#%kGOK{2?!XcBe#XKSQ=iO~X`bR7|tkpvb%@tw07V;n|A;w0s<*)n9 znM%&U*vkrjK-jD>(!B^iQ6-ehG9^<0OX&s8nJ{QOu~E*8#DUZ3_o>AmU*|=`4>usf zY|cM;!M8SaJq(7HFhr9_LyuDF%hYw>5zrw9p{QjKVw1Ox^7lUvtumzVU(Styt^go% z7VuNZ7}L^_+y;;Tl~b*!x!>5epULQWz4`5a{g5E`PZh$1EPx#3*CEI)pi<&I(hUprTJoAUTk_;#ZrZPbi29T}{?oX^Ta^l|#9`7Yd|=h`-=K&Y~l zi1L)eh&gY1Zm!uiXaKs_gSHqC59?JtPu{a{->lrmuF~_x9-5&w1GTp23tNY7rBhIO zut_i~)1UOpZ&W@-o$Qmm#4;Jg0>Y7 z8xLV;p=)O5gH#iEHAuufR`mw}OiHw9V+q?8oz-Ljx;rZ3k?{NPw8J~Tn2eYE6~>{TAo{_p*- zvu@r^YA>Dnxu-{b@7B3xdVcG*E|GHw6rVB-oTQPuN#)_3LAVTs4&mF z(UeVo5Bq4t?Csbdb1b{G<&%Xm==PlLU(1>OE;l>d*k-a_RQk1_|z(T;PTtT zlVM3tuqRU7UE7`b|HrPq(ot*A3OQ=2odoaxR?bQUIvh&MYpraZfs;3o#MVDfbWt*Vy5%aAUEoK5wWl zTBAkwN;(>9(TPXM7E;Dt5K`Nte!7Sqwbz`J7OZ_3f^v z!DB^TD7q3c5FqSEf|#X4A^n`iw488+!n;>%@83eJ4_5}8@m2u9=E`>LUQp~qVqaFp z#x1vI`UPY(j7D~X)WQJIEjUE@W@q!^kb^?(HOh3Fj;-(zcvodjxoHzk*wsF;;Q7Ho z!bt{mno+dh;A^m*J^Kp76JD3UmbpjfVXN>7*rfw#bO`MvaB$$wheB$E;JpIgI1$`q zQV)(I6aE1FuAKm^*<5U_2d8vY_Ka@KhId;DFq;bNhkOe780uokdtxS#THLi z@JjUO4dnvGVg226U*G-eByAq?KI=XQ1FFNyY41LtT3AUM&hDPSqZUcia^VYPCiHMw zg8Fxdx1^19x+xwS^u#dD^(=LZ+3Me8j7i5q4i4!_UMw>5c^rTAr*${sw}9(@AM6uC z{|n&AVeS`!9}R=WSQ~ZACid;)$B#R#A3c7oXKtzR3<-7eXv_GM@VK5kH^Xn*OxzD5!vUnS?_(Wh7M z_ox0>aak~BG{D7ZlA3R!>xcl`)E!T5x!?l%sq*G@-#f-nKP!G*;k-NNuDX=(T;|P1 z`l!h%1ao%C&cg2EI=t+|KpW(~LWoFL2t@|~6Sv!7bBpbIE_wJiu73p#j(2QE6ix9T z{JXdeKD!tP*bqL&Tdz3E#%2uuYNl4=#_p%In^(8}Rkb^K;Y){u`;k#ZyEpS14SdveQjP%#sl;5$*#pF6p^Lx zr0x+_9yU`O1fRyBPjtQm)V&iTe;&K4*NVx5&~u-*#{@JdE6ZfCudksTzwI}U)p)rN zyWU|q--P9pjLB{>G1|SQeVf4*yB`6(#-t`BQh}?;pJg z5YpeGyzFcS6jMq(3nA;_!O;S1c&vmzd-kjZiBhgIGBp*LBJaQu=*9qEhl%)Kj3kZ{ zTv(X>K9@zUJl+b}K8AQ*xJ89zVfEkyFZbZ0wJcG`8A+nRCR~I)@e7V%NKbhGX(q|! zhj$XgZQ^x70;}3qU7ezU5jleZI3$ty%eygg*Gn^xLTaNV8H^B?*35z&vkS=OJvoAy zpG=Q^-22IL*0v`5w^==v^D0ii>sHhP|4wTApgVzUh3H&o! z=Ti8WpxC>Nu_c)J@wY!cBJ39su+ICX4EjefvJuBAPD#1Bj2zy*r@09VbmA zm%32&Jr6UKO+Ypupp;Tflw+>&W331IsAlHH;2t`MM$||IIMqmyK_|5BO z_yR6cF~I5@QK67>=}G_5lJU|DoEMSu7VI)-p)4)Os)7roqQj(YM){QqWy_6j<1-y$ zLbq()%N9j0ulbd>o|T?xKQk>7pp@RZ&s0NMTl7BZdLm=oV7c9h_Ww&AdgMYN$4t8am^5~a>HD+{oz>*<87^!dxNdVHq33jfp8iGtIsf%2k* zpq_ic*=!=!6uU9+6~T&wv&^Pw=^&0#FocC+x7i|QHTa|*uksVPx+({QLE9N$K-p~v zv720LA;C%mq2m$pA2cBXsQDLxr%H!DVr7EGely72yABEnsD`b$QMiEVdV7f{m|G(! zX$%*KDWpC$a9SLNC`p4jW+7R4_!aw|;`p^!(F==3iphb5r{9@{sa^}v$^(g8=nwcl z#39m67{mgetxCih>K*S*craFw5F;kT-ojju5X{$NyFYYw6-)ZX;2f9xT}e2-N#Sh# z*2BWent?d)xvH)efb%AZHB0%8t8*Sndy2@`q-SAC9~vJ|g^=AGjPtjbF%fy%wNg-2 z6b5JU3oEdMx~4^V0Yi6yd|4GkWI&>Hk91wrhh0u94#l*D>+E=}<%sWH14ly`){I5C z9}Qt$JdjP#XE^9RLg*S$*<06gz#uy=F(JW3)aCE>74UeoFp*Oyo?Sk^;pRv`?9Xw~ z*4{$_ejj4ngvRP>jy1f_EKD=$@%Q#bzmp@u`i++!X_61LxI=IWaH1n^3V8XFuripN z>VBW-4&UBS@YOghu;B(8g3Jrhqfp7$z(O+@_R0#;v5%)U)XD5TUcKyRe&Ial9-PKS zQVNqzj!Sx)4@&dlBPtemK|uoL=urIvCSODJKHH~3=g3CP1}bX;LPw8}NCJZY2C3R8 z?4CQUA$M!Yx3~p&x~E=Vo0pfDMV;ohV7x{+f`O}$gx8V$Q`||p; z0!2`cS!XaBg_ps>k32oezyW|h>mD2}3443^Rs^|BW5A*_&j&0~ zUdI`IZ1><2A|DgVs@ zbvSlm4Wa1#`{kBhyNu8QL(UPwp^|dSdBGIF5Z|7SpFa?%++%PZGx2nC7w>@@hO&Yn zG6VlE#+>`zHV#Vr#6BiIqttv5wd}qN@@e3Al0;TroOAa$%GhD2U*dk00-Yz7Hd8 z+@sqSlXHIXFAuSaiA6koxCwn;hr&jofvwZ^wk^9-Rw3Hp%1~|iev5u-1Lbs zLtS0Pi9kB+U=k+eQj>O6R8%NHkRAI8))zSD4>%TgAzFeAgbRiDHxK(apa#dnfiR8k zqy|kdd&FV+Lzg07-W2$L`uxS2Wxl-v*`^gATepR}U!B)be52nV^`k0WTWzOYc7Q8UNpaFMz5Irb`JQLL z><;}yb0dw_KRqXtO{GY&+2|}yySR&SvqqS%oa}kheC$Sc*N(EgHbR3lnxUI@aF`rJ z>tyrX+xxp#o~e2RsP7N>`K{bE2=_r1gd^OB;*l5jo})0$w&mgHpZkF4&59SpXN#Iv zV98Gio$8i&MaLRYIHUnCc)Kek4?+Qom_#l+U^tgL1xaX>txARGXG!Z9K}AvHDp4{TjGRebr_wV$?#F0;c7(RpiDE$~R zEG6!ck)_=}SRza~Kp^$FZ-{lH2g4&)IG>2aS)nK&S3@H4l#thY>L|i8KcJB_136NE zX7KB6TwC_IFIZvU)hjP2SLzB;$#GmHYMu8a(Z}}x`t@o%VWdi4xxYtURbroV8(Alr z*RD>QYRPU0j6_%`j|vZc`$mrD`vWR!QVY9Iyke-4|5ts-u@!{7pr@a~!`eqr?+xp1 zG#EPQsj*?9`Bc>5ciE51pD?jXP36QV0ihZs1fs$uXnF7k5*i(4n+iD^Qd4L*$v}b- z=u)e!oZK*WzAg?>!U7R)!n=fxdY0Bt$bj`>Ck0SWe8my{5YfVeo+ahW zgr38(lFZ4`(Liv07wfs#Xi@gj(Opqiropv%goK5wAR_K^FH2h-dOw&7`{Pds*x*}O zCkg<#IX%h%BgKj=JKBq{8X*!N<+#MfL^Whl(P+#u{{Rtv<{sL4a z;;$pm;-aiW9Cb|&D4P47HWY0<&;LIc0Gs{+?ilb*e~pbbMxUpEb(yq_OL51t`i2pd z?OrT=oH7+4$!&W(8?~`Y6Cn(NX>oqTvU+`Cu5JGgb9H9T;*yeWZv%Sq z%d`1pU;rQA;H18hPxNEo?^*k;KW+G5ssK(Kgi}vH}T~|!z zcfMl_EKdow;8fc?T>OM}LW%8our|2R0k@WXX^x1A-JHQ`dKt}yz|p%AI01F>@6JPR zBz%Bd>y$R)C|Yp1kO1UvqPFWyPU-b4O{!2w4%~hTZA{5RR=n znF+bbJGO0Wq9o!!lA}HYsj0?MZn_oKz{I=8-?tbr)xhXw8SRq3eG{gn&U3}E^02}c!~^L3 z1VsBKEqEAj2|q=#5NASxf;LY}#|8!6ywWaa;X(Mhtu3SUDk6?41dX`cN%`20w}!%I z(HMT|aUe_nz+rTY44Q@@ELflIyLN@FgTt8`xlsTHaFf%YpI&*_j@8`2?RDq3oG|d@ zYJiDn*YUYkdp{EFren^Ij$hMnm2op7YDa4lbvG)q5Me>O@79T)teR_96#0ANEb=2?JsbgY7IQ&d6EDYnCfivfF$Runrqm80S=@@@X%2FGiG4r+)>%yN(`Jpe;d z&XBXf5oVsZ3Z6QpgWrnM*An$9LN6Xq)E$ftTNGns^8)LC8oinSykl%?Y7KM~7y@m^ z@InXo)^-N|CtXpOzxdY-5tfI}E3e%`a5o$E6gysvI>!w1H)br#DJu>G6+1|TT^eDh zY!nXsxKPebMsyyq27$o0hT6LBSAnlL_xXT0d~c$YHkArOlPAy;BJm1q+!>VEe$Q-zbl}S zlAYY0d_pNfvJPH?t%M7K{nJ@!DBHH{z)88kkZ~g$rptUKxG6IU8v_wo7U3}-IV+k3~;K_DmJ=chfGhH@2S;T1WL??;Re>zyaNAlnR$&fFhZrk zY~c>AnwrD7EA<_+a}uXgPDs4<+@HkzfQ9N2g-Er-s`A0)7iJklVmVxq$In%c8~m|u z2}!IPymC0;$g_+a)OD?w{2Vf_C?(LmZj=Bs6;^c^Ol-j|kda5>0eRQOM>G>Th+q!x zmMC=JSl??;BKBCc^l9#({Q`{UzJw9t4KUg-W29hdZOz%TW#lDlGNs6h4K8fkPc1F9 za23e)y9zCtXQNLMw{Ovi>|y^?Xd^M}^$rhbB;YKlaiFoEC>(~6AwBP&J1Qt5HU`2b z%wogEMx3vLC(9|1ho4sQGplPV?a>$(n15K9hG~Z@33g5JI@C55vu%z~o9f8rgsdhG z8tC>BKR-Vs{KcqWA45e%WC;B1@An@$&CIL61qfI<`ao#@f-r73ut2b*UPq2``w(1I z_(UPD4!~uGIbOhoE#4Cp{(*R(nbsq6sH9(s2qxZARaC6&%+Jic7qi&ZtbC@rG>)E^ z@JqoA9{sH@pp8p%7hlZ3hGQ29WMQx^H?ev2Qf!wbdv2n3Uz6ocFIA^T#!e9Qd2fslVpV8ouL9 z#{HazC>!!I5mJ{#%hu?>TUGuChuJGi=pXK7nH&5V@Y*hRsFEdfX7<>n3AQaC-=q4! z*@%Z625sHx?99xo1pH(HG_l2Zz0`Rzokap8W5wn((G)O+P10g;K?Y5#z$1VzzbK%L zNr2{1MC6M*p)JyiY%(;{(Rs0lnfW9k!%9XevP=wGfMW=g>Z8QlF!Ct7cK*!Mb6B}6 zDf;jhJ_i5z^1F<3$~P`QNSnt^5(XJc$5P_1cX@eoe2|`Wo`^#S_?3i`l#RuS=Fi4N zx4nx}%S!nldBepx=Y|V4Qctta>sRllk(6ZGPS5e=?Cw366lhA5wumcR9<17Z{$AFJ z>n~KKE-k!N>>!Un$!r{+cQt%)v69VLrm4G;d}PgOzNM$jx!(0VT_GXOZV{jXNaV%G!DehkgnGgc_l%va%{%S_KV9kgX-e z&0Qx2BgEO6nL$!vVIeQO!}D(#G8j>99vN4~)k%pMdshG#{v+@sip|7Y4}&p#2y|ZW z)WJPyf~P{jceo4H;{HA$^SmHv$C$SRmj>4+0D+5k*?C8Sctz zVBUXGjD#Z20pyw(+|cmQhc`$Snq3r_^n}&PLJ>J(XY{OlKNC|eROEi&?+ijKMAQt$ ze<~P**S3l0c?FP}8@RFj=m_qn7ewoZQsE)k55!RgU^m`;>bLfF?^7_!xnc0|Bei_| zn-?c6RYgMR>nC+Gaz<(*Z_U&W8(sP8-xFY0F*%s(UZy)k5pb91UH1m(U(Iw6bBh*j zuKU*+HUum;wwx`xpdnYXX=T5};%F|T8ne-4lQQ=-<-6^pGUYR!bbkNFaMzz%&1`p} zzvs{9%~Wv zRpPXeC84n7{*!5r#*jtA&@dq@&Uad~9R`yU($uFzuf_Ye^2$g{D=uJ_VDO%E6CWfC z9$$Z=o;{Pv^q*+?*3!~4rk9|Y%;mjJDpuiGNX;`g-d6#e%ng2T7YBrW(J@k!!KY#- znt(d;{6uH244`%mx^|4PHW>l3Y!4?P65F9&HrtLoET$O1;U0zFA>|Q&YEoZancI8Ru;c_$mouZ>F!b`-X0I*o{q;(i@TA zB9@14|1NJHuUY>KOTAmV$BPOndR|YfL`X}^!ESI!go?T>JsB4m^Q(v*$+~91b|%x z#Pv$Ri~*=#+V$`jW5SifwEZPE5IS@PxFYr;I`0EqVDQVKo;O6Nu>DGXH-s$DQQAQ? zu4z)}c9$?3C1UA#d3nzQy+mn8RgT-hsz=7TJGB07w)H6UZ$bwN=X&_e5feLfaMjOc z6FFak(U87)AlnX-cs^i>mGGx z4^ua2xE_n`U}+8T-xMR~@b}``GWr}rDvn7_(#gm7FUNNHr0&dKFjgeH<0anMM z|G}Not8q@uKQ#A|{f~fL)iD`KDb`Z6G4HId`7+-U>iQb_mNNUpEui(x6MJKaUOc9_$(RhtmrJnh$W^c+ADI50Um zDO2)BOY!(U+on;QnblR7(A=lguphK~@ZlhZv2tn9Jlna};X30WX#aLr){|!bNzt#O3hzd9|sJ*K(Tm0wvnJ$myM!c>H>1oadO~spchjR}cP=@8dR=;fj7P zH5&V9>5t%XH98-u91SyXwx68VJtm46wG)CASRY{o9f~p>`n;>?SON06AQ$3N^>~!9 z?NbypDq}YYS9&}DZIK61GCI?eZW};Ve5k#7cteqPo5w}52fcO zcE#Z`Q9Rm*7h=kFPSFUZYjGb3sS0)nIAXpk1s**v!}?4*WtHrd`?^by>*CEoX*PJB z-v&2r=;^oBj-Z;M;89ZA)uwn_b-V23wV9246NQY;*{rX>HJ2r7y!>d$`dapd^=`8g z3%&E^0m;99xqDHwggLGF@@xsZJ#vhVY*k1>qps~kMVn5uRMN$-=WM-mISV-YLN3&Z zS*!;dGB#v9H~U|)*m;yqM&8Mn#YmHu#aAHSZNIO~x8Vo#iQZ?`T&RC7?C4r@u#{nN z7HQGRxo^2x#W(y_H9~zz$=}tNjoG@#-ZpCB!TPRXi^f_F0MwV6Qa_!HvdxAxP~y=p@d z_Hz7nj}+yD^ZQ}Cl_e0h2EuF0L0cM4#zP26y8cs-dEdTRO2YZo{?eo9=xEVGEpuK5 zpDZ{#85nORfhs$L>irRN%c~Euv$GS7%MC#LJ>Mg~qL_Djv6qKqrt7JnpBgi){mvf? zAiSf_VtMNNX~G+_MH^9)QN_qu3kP%`;=m2SO4Vd?0G8*2vJt{(9MR!?McNxye2*(y zgb!FuzJyynxLlH%ZC2Pz)YRHd7v4^jYaH<@EhCp~y|BH+e7%lbPC15|=iqMRa)s^D zoUXI)FW(pN6z5r2k8xFvy7{eY_{jL@u9l#nz(8eP;|1tjBp5PH%^un#9@l#k$UIrR z+SY=gLK6vdb8ZHogl5ND&QGtW6&jmKuz#GJ)3wO9eJPiC1e$2psGqC`FmBp@CF0%i z-c_&qi>TQR!aP2rHXSMsQf2G23;3!JOE_PM=TBP?UjqZ=m9Q-bk*9|065{Uu-Zm`cvuIdp+=;EV<8c1CIhco(7M$Z0*ZVmrF+C5Kq&=Sarg!br$BzUK z0;E5?C_^f?ALv@J*;~Q{goscAQi)8$QcLluN2PsdenneJ zyiNL^!4%XgSip0jk$bw^dy0f5_opIV@P?Sq8BaNb{fAOnjMg8HCsGGbx$o?{Z&9DQ zIfmn7r02lhgTuoPb2Te{%@&ru4LJUNvw}+2HSII{(zdiilkjpaTO2gnx|Dz_G z<@rsbJFau$&&gDUv zbPe`jYAM%hEX&!m>_r5ut8z+X>iS{xK}g~&JF1p(`wk%$HLZ1~JI^e9n*;_FH4zR! zasHVCVcIF7udnazXQrweyxRYmb*InMr&ilB48w$L<$|s9H4v|oXJ%tLV0RcrwwsoA z$Ocug)h!hab`LbCI|zaS`G z+dVMu)sz)IiwaGw{NgS#WutuozjeQPzP-{Skbh`LqhoA?laL~BxnuOPb8*QY2m9FK zM$gNZ+eBxHy*lC{d64?-wm7nJj|3Ipxt+v|ui{gknB+Mw{y4};we`AWkkRin9XO*dVV|@jYvgytB0rKb6W6pwYEu|k9IHjU!b(x+wqVmgNVB4*r`A8Ir{pg4YFHCU_al z>DMwIQT4JrI-gIH(dVUmM+)@fE;J3_S=gdj`zKv*QsxayfzQ0u{|@~W4ePVMy98e! z63qCkQ_H9>>?X`q$+Pi!R<$>wc>0BM@KoZbd$k>w2~~O0h0pyX?mNcH>oHv_bU&Z; zqWbx|ph%=km*Yn6n(xikqUO=MJPaq-TG195p7?YJqq)Aof2=FpsuXSYt zV=M$aFo@xM4+c+S<)EjvVB%JtB~?MNfJ*T;WEK|}^Gy%HTW%c+WmghLY3e_xv*0jw z#uBaef!ZcMl4)n&w|n@t<|Mo#U9U$8w!i`j7nKFflWiROy$(E;9lrZ}Rovz8yMU;u zsB@yCs~0RSEpxAhAkrn3>MVvIVwRnEg%&5;m9U9A)3Bu~K{60T_gZ%2!cVWCu>7+F zR9Hiv1QMe*cL-YZlf8I!O$h2aSuYg(y$U&qVn!0yq*CP+znf%DIbxq zc~*K(4w+uw$;55os`Nrwv%5=r>Ms(eQPYDH5zp_a5-Ji2@Z;pH%B}j+x?2Y}Qk0!j z>(dOcH0;)DX&sTs*fHGLNsJ*+oY;yaPuKe`ubx>=Jwq>va6S$=7gojV&Fp*ga zPGI(g=Gg^YkTrAUsL&hBjz!3+rK2}uB9ocFkBJHa!Rf9b5PS~}jsDdx_6azVlQ4R1 zHnH{B)9fr2HFuSZIOiHhATM8cgGVAdTgx{%JdAT4!wc7^-5aP4KtFgoxq^J6X{-i{ zX*9G498ca4EdO5YXf1Q;`A34*aT22RsN z%wOI;mPfhnrzpOlW_*a#J2mx~W#*q}9&@F5SxYDx@1FkHVc^EPU(NQP^z^r7?<(`R zu9G9xUEIAox^=_Zar&dL*01nInzL3_SJh};d&wQ0Lv7g~`{Cr)ZAl^r7&iCIDYk## zFucXO(vkn{R*3Meo0C3*Jq7)PgZi(b+?u|dQL_JaP*A+XNQ6C?fh6H%UjV(2V0)2m zswRXV41O4#egO>e4*a4-kXxO@_H9bbT?6oLG|^SqG>>ID+lg#sVzX;wR0C?>bNH{v zsdrX}vB?B~juLfjJSQyN!Htl^FR-yygz-U!3OfxziDVv>1Mk6VY6DrS8y1LlVT*vG zUm4;W@J8TQ#3I-n7lCI-5;>tp;I|Hq3=UQS5WD*xT-G*RWSy9PN2QyROJH(5hqYG- z54JpzLCkw_5nTfx_eeS1BGVD5so7x*ECgv3jGefmC*ni2iRvL{9lgH*pxOmFfRaQq z%*xyRo-9~m!i4QNpt1?z;7vB*qJPDLS;C-qCx|4oM12kFZrm%82jKw_}YVm z{0s(MWww!h^5>R5XIs9k#23Es^o-)W$spK>2d+)rcK&}Zz{;2@m|T3QOa=)cF9Ii|u9l#Khl1L0+{KhM~4-Uey)G>&`oWmH1K0x+@uf|;};=5JQY96xb3+c_t_(JCmel+ zfH9_sc6cRx3<9P}vvYH`e$SpM!LU9-8{Gr68kc*X>^btZB;9Re&HjJ~*oAjtUh0#d ze!%28_1`_ovl}8h42?-EOq`wR@yq*2ik>naJNlkA_xCV3>_4$5`VB3~?y$z%MtQ-4g5hHqXQ5=3dK2jIKfOLdY z^q=|pAq-34*SiIAQ>b3)L>(;sD|=r{en+u{fUQx2(=WEjgqatSCk^T|*(u}3qmZ?6 z+WaOGp->8fJ(O>A<$&tn;-Kbqp>wg{Z|H|(xZ6}{ZA4_(<3c0Ek65?Z4Fr1`vJ*t6 z!p|@EN9piDkJHNAaoJ-5E%RO$e01A`+|GqBTHD(r3F#4N(x>nJlpJfzsK+Rf&{E=L z?DwQ%(E-Ksk}uMIZ{SS|0u;s;qJpO%IbJp!@XCWuVq?P($P6_ksEkkA+fTug0E(o zLEtI~SGDLJv`x!!$Ydi101+4xaL5Ov6$!XRelHA`fteCAFd~oIxfD1mFBl3yWosaf zK$y{COe+q9B}{xrFph8}yb^V^@?S$#TPVNrUa8nU&d$y_PU>ccYTlmX#sbJc8cJhW z>W;8iAcX2-$AtrYU6ejtwsH=2jjxMXDvWCzx9H4amTy1zrENLm>#3`b^+r~8?*wk2 zT$@~OtNNpV?1-6et46So)tN*srvT^2*OU%#F+8rdqQKK{!8F&{rc;(0?rnGHV%SCY zgKNFTN(sHmTZcDd5C5~U*wnw%?x3)je10U4^QQ}?-PYdkB-B_6>qCV6dMlr$uJ;FN z$2|Yd^t|}_wuJi!Z>R;~B)6BQC3#@fm?(VqEL|jE_!pr0ZbHn*S4>Jnw@d?%F(hay zP8be1xQ0hSe4(4hIOQ`f7F$bc~&7#$65!?;CPZFA|`LMJDd)wi|YjrEZOd-n7* z5CAEs^jlR%ET`l@b8~5PE(<8*QF~q@GBVfE%Z(SHVyUsAhPw0`(D6LeRK?`yIQ0wu z!dCTh?Q5azs&{X3?ijA4UkE`J&|i0E8>XM#2vgnz-`6TirG#sl+Yg{+N6gbi1*leU z+iq}Q!Vb-Wp<(?w>*42X5U@=W$pnXwe4ckIF(??uk>3ooi!)Q%&BVl{FhSxJ!BkuZ zl#&5nSu>GsA&1+J{2(8nlH2>eB<$jOJUpS5Mj4*X(3-t>MM?8TdyyDZ<7lN#)Y$X$rlsXM^QaNGrDuN+$6SkHp`kujT+%O~HzF4Uq_ITup)Yxws}xUzM*?fymanyky? zba}B=juGjpte8@jU9>EaPXaN@jX_z3^AJS976H~`;3XJiVUxhlsx2!$lg(TvsAE-Z z*uFyi6pLVZky5o2E{bA!WFx6I&~}{KN}h3R!$mfVoJQRzF2lRh^%^mu%tyc&@kQx_Iv{t z>*4Wl)^9@=UZ1Kox_ejCG#u}7=7*l&Jp{7L&^r3E!&mrLIl6x`@YWuINk&(7AvoJaJ}=Y1#{OR5C0GKLeQ+_IGKvzr2*!E^N_{$S!* zQEx*ZO~eJpN?j6Prj={HXJ?mpG=P-U(s=ptOO}w2@jXDb-{qcs^=;VefHpGMJW=Jm zgN(ao5_+oVjDo&+&xmiU1gS?IvpIh|6%JbXBJzSDmO7`WPNXk^&QpNn>Hv>6SKfN* z%5Oc~p`tiVRTmfk{JD+6GV~|ORg>swhHSH4%Kd|9^Kpx+-d-rwysN!N#nd8bx?#5T;>{lSe05WyN z2`9C_fdQO7Pa)}8*S42aT`exGRnSqyIrgPygm;?qu=GJ+U*EsWJ*DmK9~D2*z1QOs zT2d_Sb?bI3dTcx5-Ecf*?Z%9r_?xrA*DWuu9Qf5fUT7ljd$4O~mZ99cg%hI|*KEG6 zK3hHhv7MomIafoLsM~}-cIdh7IsleN@S4O3hzZ@T?!5K^@Mk2HNtlxO@ACcFeIAkX zC^unnU|v&v`{SfNvLukFid(zHfwfr13|xEsd1y)RiUhvD|8)~ZSy#>IUD}M7%)iX* z(@%6OaOmrg@A#3**-WLU0^3}C@mSCT`5|+xp4@6%k1FK*9e&Z7sv}9tv}H+(+E5S= z<7}cZ=GTuGQU3;x7K1)NgFA(BU~ulsT$OmiF#|Q;^gw61>6Zl^1q@x2U8ycnsTZ*{ zMA1n?%|T>>sNSuvsH{w_oy`<9>rhtvtDBDI98K0#9g0!`$f1^SKUJHwXT{fbrE9zu z@Ot<#@J6aChTrI@RE`B~1()%Gqw*>&YgLdQXyxv{Av&A1)Cg3a1ImbDI*3Wo%7K16 z1`6@q%_5tx+-8AE+8H4@!E5?~G2{X4r3PHPinTY+>h$Z7nWL}f9#C!+3=9pc&yVRK zDn8-$Yo>Pm6)n_WADc1BFZq5)A7Bw-RFqBetE(`3p|#FFdv4C=5@^aWu>TI4^Q#cF z;2Rh*Mu0Yb2mZ=BMA%d|v{ouEd)us*%iyZ+2lkoRFJvppXyeEJM+uW;c5wM?&isfj z9%%>z4Ce@{D?qgB*AWprhDZ0*`o-tx+n2t7@0?jTNuVUCWD*JTV`%zx5lZqDa02u( zGjjr|CG{$;7l6SOw7S1vfsdfb5tIM|LNRy;qo~mJ%svZ{5YlQXYV+$w$yfb1Kun6j zDmNf5$$)?WTIfr!L%GEu9kv%V;eC1Vr?hW2$(_NBy&F4;4+AHk;Wp@ZEJ{;T@A|K} z{P}rl9;n154$743uV4K)BeVx|bamb5Xx4LK`f5-Eti9{kuU}0DK5^+MF`IfV#z{L> zRbS8A1$>7ymr2pqVc*~FblbQ%ZJY((Z7r}pJgR(f&mGkVrya=;kkoWUr(MtFt?`}O z{&yRl){aT$O~QE7!J(w+?{^A7q~;B+<#h*sP@~=1*%_;v`hD2=YRyS|xE_tQw|tUQ zUyIUAsn+Mc2N**p^bZP7WY<>J)eYm_1ARaxiH~v|DaIIq#V98KYK-3oK1)`Ip_7v^ z#-lJK?jIfXMvNyw81U4=^uB{N?2m}@0>FXcE5UID0}xdj;ZJUmXT3CI z06Cb9uI^zRdW32RRc7kF&}+wJLgz87K8*1Vn}1NyCG4^^J8DKBDZpx4!)tY4zxLyq zyt;M_>+WO|1KoB?LRk)#&XsG|KErkv|FQ`{)L|voW*UG?V1^PyG2G?9=A979;Lztu zbqDV|bOpeqH+rob+INZb0?ii3>`JI=>JR`cr22W`i$*IZBLSKiWn#AeA}UH=Rdv5f zZpTX(t5mFiEM7T~AE7tJr_Za(Ip760d+?W@o*rJ;i?<;YyA6PW0B+E`?$?a6s2wTG z**Mi*8)U60vgen+tz8^1p2Q9xsRv;6X6io*%M-H`QL>ZI?AjHt^;NK>Earj5<1vvZ zhjx{kP#6o=dv~yCi;?XN3h%kFd+cFU)PrnB>fjak>PJV*oYy<7f#Ts^oTp@>YNeP` zx%j^9(2%Cs%^hal&m_quXuUUiybr%ZDp(=@A?gY#N&9$)35E(UDb<3^hF&d*HWw_H zPW(!thss&K%-hJrPlS;UQe?e2HgWQOev*j*iNZ6!yuieCQ7O)N`vS!-)r-!y9Apwn z&gd8JbmW{s@)ufCBxJ38%A z7Wyu#A%AH1rv9EdWe!;k`3qCp#)kl9-wsMB-96@u1jHm9b&EvdU6WQ5v0;DOTDC{? z@|)E>$o6d`wcqr(*~*6lcKQ=jsc**_Txv(!Y~!|A)NTp-EbfB@R;@sTYT=%M}b zM1B=S5NzfFk($#yl5A=!MYCnx4ksqqDEXOm)LVb?7w`Q;9lBhbA{ZI9&3W6mJiYPl z5x0_^-rv98`FbtdIp)M&o6wwsWu?h4N|mo_X4(%1&8MWKwE5Eh!^f-H4wZbS{xoDI zt28=RPgo|2{YIJA4B22`+JzYQY~@l*BdCw~@hN7tjFqgnoH03|XtXg~ej(0(qqWK- zRB)q5`_t)mQn$srYbitL+sDc(q`oU>@;JA|Gr;eGppWj04c~m8J@l*oPjrBWNGs&O zYv`H~e$DlmW5xZ$%I0}r62BJ&RK56fdt{e){qqsYnXM#U{?o-vi{V_qOX$4PsBc;* z)WrEW8b%!R?2cG-*n0m` zZIR!Rc4R21?VGVHK(^m>P>0-8W2e~_xJVp3_AU0qaN9OO$5U$3e&<3&KkPSqQ7oE@ zi?mD!JEe)dO z9hNBrSDJPg+tf@RD&G|Scd&c+6Mouc#uwYTG9&BAZ4!3v80TzmSa7)NJ274@GcAkDcg|Ex-Tw5EW!s;7?CkGs`#Q+ZiOm=f zF}4_eD&4%fCXc(Jztz3-z9m%v=k2}=FKAs}n=#BjP+t1UlE~$}??1<)O)=alBX^YI z*VeQ?i~hm`QTdMHKsUmr!c-T6U*dMWM|)xS!^YxG{8Yje3KGt^ z8AqqsdUlet9%kF8MbfqCVcDKTQ5(<>D#YJ>>I-9oWw~u%C~j=8rH~`LC$aGDFKa=2 z`kvACio;tjCNrnQw1DI!JvmINmL$c94=m2mJtC@0dJ`6TlpwtQHuba2tCk(B;#99J^L$Lf%+Si|eDU8)?YFBYKSt3b!5XJ9V?jFd zBB5vE!o1Boh3Taffj(dUpBoA~>8B9kGO=ArQCI@)Cy<#(nHpDNn=S<)@7?VB&{`R_<6couIo;vX7*Ir_b; ze`ohZi>Ol+>$tqu+lCSK(Ct0U4ciUa0;v8sonr{O`sH$unkr@EleMSSJbJGCE#vl1 z{>NETp)cA#s20b(2w*F=9zjBFdp6Ve?+|pI9L7uKYreJwlri*Wo6Io zl#z&#YzmbXS=rta4Vl?8lI#^3nQsYY&+MH|R`&Wo&;9xSuK#^q?ymdp!uy=_Ilu+<^{_#7frZIriE%;r<5nK;CVW%*JJ&xG zRMec}uB3mf1&0CcR&o>P{j(#~$4|TZzsuabg#1U&v-S#R8OWTJP2-Kq4mYG4pYK}S z7<7?+Gris*S138ad7-}qbF!mj!)U9@|JNc%Ypp9Ky6SkXTIwX~zmKE9#H!34YTC#0 z>~bwwjgxO#tbB%ii=8rU z=tfsvsOlJ()LBYz?ZV~L2-UmXI!?lme>;cv9S2vtUN96zu%<@#w-~FbVg7dyG?jsg z*mKnokz;;$+0dS|)Mx9X#CJU7yuVVrKE4%V8-EVGV+I@-C1dQL@GjwvEYJ6Rf31LGBr&wtvPS?31wR0vQHKmwSPLAcXmJu_YM&-0=GwG-bi1!n@ z58j3NR7Uplfhc(o!976*;oBs_`e7L(o-#4w*#mYuUhfItH$e) z(L1_KcVLE}v_!3AEw#nir?%7|X>}AI@%}OE<=df^{`8(MTNXe5?+U&rw*UTp4m4uF zEEGOJHiXBmEroGm)iPCA_LL8b+Bwg3eOuEgEl9UNJ@R=tlwVgmxp|D=`XqDts0^87P5 z_dX#ZsO!m1z5-8S<&357uGup>lFm*J03nsB+R+Cq0qqH(be)CJM;&gMQk`v`DLQ-o zggCC-l{A@Yj~w~*>*rUQ9=$$a$a|;1#juh{y#J!<4f85i!I-RzRDqXlg|LmdF0M9h z=0}f%+bQP{nw8H+m0ScdIHD(nUkP;N=?nAUd0WUUr*L#4Yee0CpKu1OA0wa|{>o#X zK#QwWE&VS{@w*H}AxGDcZKt&G`}h^YX8GPDP$;v+H$du`@S~BVXv#OO$x+6VFR_k7 z;g^#MYjs8c7aci5tA@=l^)HWc_w+nHv)cTs_BQrMJjTYMqo-c3g-k5}Jl>9szLX!Sf^p}GcKKH_N8z*?W0u>uFzr4i z4E=UmF{hD0d~LsjFv;V#JK7$2^1c&NthnZiIqb=(?M{p84-sTH^PSx++iB##eKa#= z!h`Z9VTGf_l|Dy9@8_N-i_BVCkoKv`cD}T3b(*Kj&~TIGBx|CYp^rY|zjyKbN~$I& z2_@x~%a;jZIRN=(_X^Eujbs&<>+jy9ns_+n5Q`~%s&RSv%>T~B@Px-W-Orq^2Y*b0-Tofj5ZQ3F(CSbkx19-6a6bIM*Hj_+ zeaj5kbElvK?t1dWj8pdVeRpFR=>n3`snyj`fB{66AXnGH6H;YhhD1gS9$`(1gZFjdh%4=-J3EhXjT=;?((5qG?X#p>*n;>tg@Knj7QdJJ27$3VcLCzW5CVL46I%iAlN12G`g{4Z`RN@o`|K&^1_opv*vnv=f5|9lG)`l z@2iGNzM>=Bi)-@O>gVjX!K4XPv+8?Ge=)m8UZ3_#?pycnH1^adYWB_{W8KOCvxJE!h(o{ zfS4jaDy}z^{AmYM_(lbPp8c;PX`Zn*pd4SV{IPiB+5F~bsu&(hqel-zr!Fjx(iZee&o`qa~2?lW@vZHL8!ctQ#=Zh;CGT4%)+LcV0+nt4v)P&jJEy8Py?|0pnqT ziMoTp1Vr^apio{x=@KD`QB#Mcoy<=r?tkSiITriyda#Op=R?r#ptpu1Modrg1e0WY zb@r<`nd_-XCS~qw1M8;)6POanMvbi|&d7(Rj!44gV`G$ z7fR@L)p@uuW`bI;+zHn3wA_!_vD3W6M|fWN|CH$;n4UN0`d3!*JN18cZT|U$h_?Hc zd>c)*_kW7VzRfi(5)Zs<{NkDBxckfu9HuO7tG?x*ubTe7KX}yV=l3l{#^XbNd+c8k zV1`arIf8H)ZfpC&{{EvrS80WdgTmzOiP@Yoxyjog)`g%p35E@_Aez&Jxt4_T3f#!V|8(a zW^&Z8L?kj~J1;yT{ct_I`2toaZqsLiCv8C_X7n!(Jz+nlAG%J8w~Rxf^6%7N?Vzq+ znZ!d$!E^T;ZU3JZpzX@*Yu^O1Iu{S@5~Ow0jZ@xuz8|8vL%kR=#`1lyEzI5N-R^OK z!}$9N_nn$MxqZkwAu~Q7d(?JljeBK@{iwl&G_?`_mwPcG;=UP}e(u4*Z{)*{X@6ed z$EI*A|L1A_Zpz)jl%0N=yAdaM#2^n+1X%Q=g4$yP{wr6~|MrsCY+hoeFtWl_ zz3c6gBico*I@|P8t_e^+A(udCvBcQ^r=^0#)N^RxQqF_!jB{EY`q9Jzl;4#eXa~{s zUFSOQzJKVG)Xw=cv0ZF2w%q9=$VyA-VxbH!g$dZXFD(6;#cC+;sYw*H{-39-DQg!DY*S1Of>~_i0G8Q{BuLxmoyq`yGw*{g_oH$wW#dPnV~C-55~S2O{*V@tdBPWnyNC z3&3h|b0fGxPC#tK(adWOVSYO0r$$8IHu|jgc0?lYy*uq~ZPhmI>!YfPiR$+rOXmD? zvK67X$+er@7N!rr7k~d-MTmBk#M374%tb-##pC-;-W~1j(I;RE-1_7AZ2_I6#$$5; zwzgLg59k5H3&Bm0ZQL6D=9FO*g_oHY@6|r?ck}N1gI_a_pho(z4J4U|FHBozhV%`0 zg#fBc2mzk3-(?klja)&@ZNF%hK0F`f82=nzDB>NKFU6F*VD`VIm{(cYzEMUV$9ZC} z{zKWUb#A3sBtP@aa`j+AWMtxxKd*mXT`glYwEX-yi}q#Z?VOB>0qgRAWnUR9S?(N? zKd6U3l>Q+v26y<>VLE#FwyM8F`Cetd@#pt!-Za@%Kk!)YrBcv3& z%VSc%^zhGeEnnF_hU;h7&2faCcSIyC^MS^c9aVuYg!EF=(rOPsAo)z90*)J9YyEdh z=D{@~ZMS?CMoVG5_p6;T&yEg|><-x!T!uI}HFJ}UKI@s)nuGifbW9mP8{2g|*gzrd z$b1(3^0~T}h9Jss0h)O-3Wglvfdt%o0{-IasS%K=-SJ(@D~rIu*+%OIipOCf-HoVD zo$9Iv65IzgPp%L~d>;-)aXTPWVpV4&!3vvI^5bp=Xi_Y@J*I} z@crePIJHMxH4Q)*$sVrVSOu87(&U??qMcBj1sdW7a-lTz(0l`xSCl#*|3hHAwgF3A zM^o6|gBL8j&)OU)MJH4O@CWpOpGSt)VdP*sjGL9efkpM9BdBH)&T20ZMcUcJ&xJU> zUof3>wglp?9w8`6y$v&&wt#gja8gnV>~3mOhHQ%YKj2z0tu0vrg{V{;#64!fOt@>n z$JFeD-_8954t-__b}G3G6b!)TkI)=~e$c_^eSQJCZ8OmTyz@-qGR=TQh!AoR%FQ=~&#KhwO z)_J!>>GBq}uepQ3^VzH&{FM81a3$`LF@Eilr6m{8KY~}Us!4&JB@IfPb1m7;&CL-7 zM&G*a;9TSb?L(mkXup@XJRpw1&xPu0;t@MEL?G`~FVGdx+7Q ze?@*FVjs}a$f4_ymEn;=NOsOGS;q4>AB44nfgWU;zwE&y(T?J4sJww=yrKgtB<!HSPM@c|0W(5j$?;cxBEZS`dk|+ z8mTM8zuun8=|pqu@kFZ!^5+U|ayEm&_rCC;h4UDRM928&JGCuUPdCHZWD`!|A^7KT z{fTUH_YKCjDMc3XxBq@#eNJ2yjW{^r5i|?0`{6sVIGh#Gxv$x0!MsKgMo5m&Eqrr9 z*sL^aSPmmgG=@=PwKR>{A)T+#`n^T42z}A?GXQBb2#zb~ncwXvub4eDyC64A)aV%=99#f)^6F|0 zSUJ*Hf!+8^Jh8m|VH~7kcB-mx7vVc8(edv$Kof|HKlsLn?p^?e4C?pL1e2N$5V4SD zG0PpL`kzM(h8j;7gPE}G_3PJUpa(mfMR30rR9&O!#7|rJY+#hwqmo{eN5iglU@bbi z!S>IDCVfFPU103@nGF!STon@PzJR)SnOCbe?|6e+AKt>=%a<+iAGGSkszYIB|ed!(@psHsjs5YhmNiTUS3z~6iQ?1c*pxxik4?1Svh z>(>sb0MHJEG_#<3D6@JttYw`oE@>?*!X-Wqxi!zOxJ!m#}9`5F4$4hA&j$V3zURpP_MxT zISi>+m99&_+txwL_86+=pi2Uf_k0al%b}-025kZ{z0>X_c=4r#Day!q++k{O0cHF4^AF z@*aX+2cJUyYzKEcAIj=#5s0aNIA;#G;tr_dEKuSd7AOO-;8Af&N%;`e7~TPbAjZ+r z(Yz~P&7SIx# zp7h|Kf3hVC5^8z0UiDUXj?el@r-}iv{KBE>U}?&9o}BPojD{G^r<0&JyL4)V(~eA@ z?SFVeiKMF+thyaPry5Si)bF*gNSWAfJ+xEgB5}E0O+7Dk;rLj`p#4rbw-vb&;3$2F zjZB)dA9>o{zZmQuS!M}8t3Be13!#6LzagviR-KAmk-ow7!e!%5LCh+~KYZ4d;m#f{ z5*StVRIU@vD}eyRXepJCV5+$UAP)pvk`fcYDtb=+mlL=-81xLIX%!$U(prk~BM~gV zx1iMpO;y9egt0a7jv!g7oDv=RSL0RcecJB|N2u8Kr)u-e3IMBGuDYEM3J#uuHwaXS zonXBjqEzPWdnTc~S8XYz4@bP>X}wV~&}E0h0g_V#!gt8X3AzBr&G3l7_EqbFC$^7HPLN z1xuFt|CS>3*>&LeLo4kxa8H>+RDm$&5aOQrz=8I(90b#4Fm`ed4vUV(Co7P@O4J%J z%Hsn%h+o`M&1q2OKtJQ=kCqhBw(!aq^tXUfDe)K%`vy-pH#!7}!%1NX!a9L!s2$en z_?;p#dNkIQ62AW{XiHC8qX?WO6Kz35=m%Lg8>k!9A2ipl`@cihx*_+s^Hd7x3O?&n z0S$;finx5c3NV8#IFp~}h**J6$GaFJ0ySK~fYb%A#0RVj>Y?57aE#+58N+3k3nv_{(Bpwr5Z;NW)S}ctW0{F=I@~{Lw4ss zg;qh%=H$%OR75TOMJz{>+r|2-ap3V2lf1VF!|ZF1epkZB(+}XmK$a>!;0{|aAu3@E zhH{n|C3iwm2zffYFj2nO6OLohiBL3y?6%bCs2U;x9)j4L;-5#g7g%bt;8-!wh1>}m zGmuGyz{(|qRd4hKIA>;p#btJOQF$?m@`hoGH(SR~G0Tu) zUFT1ni0W22Pb1t7haXt5BJs5%_)m}dj2<^1ju|X&8lipfq9kql#hDYCW$F0~1I6dq zv;Fg#{G9@1`9zi}>!_xv4o!DX%#C&>Hr{nNZ7H7crPgSB?~BiyGK7;VjP`7)OKeG{ zsq_i$KEC!+hQe>fMl^Tv5idqQR7ZAMCN1P>U4^M9;2OR?rpM3A%!i^;@9yf@VHbWV z{;>7Dgi=~l#h` zm)}Thy7A{ebxCe1dzMqT@A06_-jaQ`&Tm|7)V+z9LaFLOp-e+d zPe0Ucv{=gxMZg9)^XXS0D>qANZgTQL=h9XYsJiy>|6Bc#HLZC13?x_OqpM~bHtpdx zc+uCmJ|Ju0_w#_*Om0vJ#eVbJ+bI8@m<)CG9vp^FY7oC+fEEQ-ApE98Yhj0LURbD- z-JtT*2SJ8#46ori({j=}Z4H^vP$7I10;R@2L>K1mK>S0@JVYegHdlk3a37ij;j4*% zK;O{_uWggKRre23a6aV29&!!+Rko9)c<3@eDSkfw>~6m=BhIvJa)33#oa(w}m)3}| zdXMAHzhAqr_OzY)JbUEqv_+%GgrmPhIYBY)|%Aao3m zr(j?F2P*akbf<$H1as9DyS`t|%~PM#(@8NY;Gl5Pn&-KvqvJ5!p16b)fCTd4=$~_& z2|{EQ_ecU18bFn34jI@vkD35ziO$pea&Zgx7Z+)mF+hWq;3E*((hQnh`W(ie7zC!u zY=8`L41%W2@DcQ0ys(~=L#kjy41ho#wLN&Jmmz-I{<9=#Gy2O~;p{DZr{82hq?hqcCUSq^ZpK^-F36mEp=HSEf^heOyadD%FXSZx8y|knEF+)?6Vs)ORV4 zvE*=Pm7#y_Q7{19JZzu#ZevMdVWuW8S&GGzCz-J#R$6y#exPDXqrP_E&#=)he9p)qYk2s@ zsOQ}(8nXZP=0!!AI>ZUXJu<6Kpuf1!%ql0|El1d3bUh z``W$lft8_S(m{d*O3IeDHoIQ=iem}aXw2{A`mRgOH zCL}S%RgdnKe0JnIN6gze9nr-45^=ad>71Z93a-1Cw*4m3cJe);MUI6FKV&h5bl5k| zMKw|Vp@K^5MFAG)^wiW# z5JS%Zfc^sd6AW?)XRilj&}$k7DGYv0jE&{gDXU_G<^+s@c(MqH?=rpl{{8!R1|WlO z2u~jcsUQ>RX(j!+Kvdi->jM*k^uY;^>+8F>0z9SD1q4=HRwA_-%#?WmDb*QHbO^L< zx)<$G*$x!KwMi3_==qGrxmSNa@P`~`z%E+n8eqxpqn6L*GRgZOP|PVHj& zPXuO0fjktO@%LGIWo6FjHuz>9V!dng;EYr4`J#9+JT*7>9mDza9H{2G?-;#62o5Q+ zbZ{uV4lsU*+LfHmG%&mMN|b^B>Ju3Po-XTgQ%F|+QdSlN(Ida!?lx4PkmjglPiwN_#kZnf_L zX=DhtwOj3~WEqKX$R2Hl*Jx?z`>>Fwt#>+z4F9T1N~+$3s%i1%0ft(GM)8Z?6FJ4G&kW3RK1QOO z9&l{ZOIb&$s;Y`u!hjK|CiKbkfnVOgEd^C zV@G$1E8EJeuhi}y-K!rTHAOck*cX(~=L{!JBf}=v_h%f-^@N{LJW7lWc=gS;zyIh1 z0B0Lbdg2yL!bZC@*_G4{cEq43_VS!ptAim25+lG?5Kz5X13 zmjdT&W|J9(=Rhccv0cEY9H^sKzu+JbTU!|A)SZXSVu_EXj{6cjd>iWsZY#T|BnRmq z5G$)_3zE8~`>xTmZsqU0EFWPpt6x4PP}L09th+eu-yk}>Ky^WfH1g;0z_{5PCE~$A#)t+T1 zm{moH?C$NI{X6jGQ{9~Q#c&-23(H|&!vR>QpMjEPFc`hh^_=+45`QVkBC&t^G~ZRO zd9JWpN_%s2Q?$laUtiw~o5+>F@731?<7O7gpDHO4b#!%oX`BWU6>uf$O*d&&TuE6{ zcHfmdCMxRL<+eXS*dSxQzbDs-lwM4n(>c%Dg3TLZms4%CX!*(?Shp_qGyEOKY z%;3_U4$2x;3@hNm<{pQD`-t+m_?W|_s7QQyD4c%w^k~}|xVpfG(h{KXF}14dLqc+L z2V?`E=*R@yz>6pu9r_D zKxU7xPyO@CGber~y%O9uEsLnNKVnuwf{??r!)Kq{6G3 zXMNzg+jG_Bp5PpIx2138DJ_O)l}Nm}tE?`x-si_ikJDYg$G!%(RHKv}H#n*$4iyX) zZ>!AVW-!yfcs>jmPVS~zmJ`H*k(?w!ruNf~C#?uVT)5CkzNF8=fJ;2r7;(zXll^z4 zQI2yHywW z)A^X;(t|5tU#pdu> z++jvJMN|EkZ4$DUL{4sm7yCT#TdVoi!pw!Z7vSK5SL!vG$XzqTf24V%$iFhoD>(+b z>Ki(W=5(A|;~qdm%sKg+BTgM>pGh!+NqAwb^0`I^pgAt8r@@1#GtHuJZf>sc=vb6l zqd!mK4*46Tur}Vu$8(Q>uNE~0kBFayly3V-!Ktp_VE;Cp-+mXOdg=lHD^iud75lC34}bvy^LzV3a`vxZ%z~NmrgGI6MRGB7$w27K9-*E=4zirbTldmhavB?sRdt zKH9mkOupP%U!{z1NW1Z}c%9IrmS|)**lzAJCdLO*%I$t?#G7WddxjWSY1T8=x+r2|iP1(y5s8|i!p2hgLaXJ+JK58(#jZ_huAp^EZDN==LRWA>F z^#8N~h@n%kUggsVBaJPu zJ&b&7Ulvpg5`A;YvZiugd2xe`*lcH{2JHiDQpqR2m*E1R+9nnaC7vhldA@9m=(5BcyrD4Kh`7HtlyIn(Id`{NNfGs%#1H&KyB0`u6 zbo(O*uJm4+3HXg2fVE7|-honBD6wTm2)e6BXz3eJu>z~39AGwK^;@^Bwk2W#ys$uU z&%9l-yJGD`{t$=B|05a$gH>Tz{(u@l5W5;=Aa7&AnBU2l2Z1HG`uG@ z^Uz<2-z{Z=;vQ;s1-=+3G#7z>RXale>Ib5x|rch|hVIE;%fZ8mCZX3W*)x2JuYlyiXB zRp!aSr(#=|B`>D={|qM1x5GSLA+T_{au5F^{=}d-_BaUh#cFg$eNAA8?L%;4-L!N3 z)nO*pqiZUXa?p8s$;edGfsH!`VD{n2=x9fX?>4$O>;;SA4P>Ct)1N;5urtq4yaVi4 zb7%*MW`oc{B#a2a1&1g`;Bt@z$io<#Vh(8PQ+G%NV7IYZB1KvO64(IC?%4dDIk2OD zh9K~H7#Knaq5I=bFhc~jU2;#ZyQx7IodBQ(9G5QL9B*mKafT49Yt1WY%F(}u^QM;y z3`$ftfW1`#15uwPG*WvosG|tV^1s0UI|J`T0ff{poaZ!9OSjRVkp+``6_^m0!O>d` zAG;EY9=`sjri@GM>^BO1Pkee%d*#cI|NY|KsoY|3O$(S z#~>AD@tqNTyvKuZqIaVyrwQPulLXeMwH*9|icpCj!n~?Dm>%u~_eekY!N`ny_!6~vSnn*eV;?*w9N`#&MIN&gqf%ae;t)Q}EF&@fPm$rfSqum(M(TjY%-1=W zIAJ>peK~IOC@{}VyvGHCrvB|`q1N3MN$x+S^Fh0G3s$GhpS7u#RWqp-dh4#1lEj4l zj$$S<8YOtSl9#WXt~!3&ZB`Vw$|RrRLR9R0~E?{qL^RT#QKv}i24Tu^c` zySzNM3=p)Nl&|nXRJ8!BI~5G3D`y~ts}e?_Fd)=#ZbI;aZW;`6$kc<)0+?c94u1a7 zGHCmYA;sq|m})5zn1Y=5m23S?!@~yPSD1ZZ9qU51SSA4>w(IbuawJu+F;W8A{`PTO z{Jo5jJ&t6r2rz)^m%{No41M4;$cGCi$BT}Ro`E5nKfe|iYa6!Id;!B{0t%n2qQjtF z<~!MX;3SRXHfNCaavMXTS#;26s=3H3NXD@RBJ7#)qgDr4(#265K7R7Jt9pg3M*xkh zX4!kX0Mx?`$xHHe@CnJ`q<=5ezi=o!tb(M!CpHNM0L*P~qMR27!A}1aq*? zgDJ@n1usRFBA$ISngwff3!2^*0WtT9zDnTWE8{|{K>nlNOnKeffpAT6X5|J_`l78_ z-}GFV>%mnNys%SD51Z6n{+L}_?I*LZx6}3TCR6KCz5G!1V(F@y*lkl`higV&a=V_b zvVsgWgER;>wu8?pgms9CoU@qHVq7mZ)xwN5yH~MH5Tf9@lK}--Fj<2m-=&! z_!8t3bl7Jr4DH&hq}XF<{R>M=pE_7-^~0sY6Y&FGi-JbMXz}d`FRP=3u!v08|-W2=(dHsSIb&UIt_QgFs3q1B<6m z$Cmq1y%Aa(KLtj(83yR+*e)rKeSFnGM7{z!RDt{IP+~8LLPq|n8SLy5r&wMtia|7MAlAGxRkw>j>+6?%Aip?%Bzk|&`s|`u{pilEV z34^{fFEgD)#VQpOPmCyu^%Y%I`%ZTY3X+!ApL9#I?gj3<s$FQm zg2-zAfBVi86^sDCOli)^Lhky?qxLC%8?N$_!;=x zYOApm{Gyjj2c*%f+_*7NcXh+yQxUF%7gs>L<9Pk#_=pURWbs-V5;X?Dr|zKrV|Hqi zSPgyu`a8a_QGsnG9hSpqIRET=ZT^8O%@9&fP%+4_m9D)L z0_{h}5+sX<951Oi&YXHpnpwd+^=4i?Gkfi*FYyHF^mGk^${eR)>la)v{&4%(AZO0< z{0L1AKDutbAuQ2qw>VrB@=^)jvXZC)(ucw^ZkR0ytwtT3SUH6`^)U?>s zwEHZchVx=S<6M&q)k)kHAV`fbu6|Mgo$>bB!$Sc!j35}ts1DKTqzRIp*xqmhcivv> zGw=&lq~3Of7OXS;b8nh^a7oLMcX{Dc7=GRO{jxnt9B#+ZZpY-2$*u>keB;_n zzo-e7LXxU~G@kKD_Hfw=@g-y6CEC*X@NwpdFJ3GWju5Av5Fd)3#6vM*qiMGsT~sW4 z-ET=2Zamz6^`kFXz9znCh>>qXjFhg3v2bN{c9Qe)3D4bgh{EE1I0M>#{(SQ92_Ps; z>4Kk$lXT#<{u~z<_mMO}VfbU1E;`vR2?l6p7ZhmlTemO~vJwg)xO2Qs=mPv2gq=qO zxZl_x${eEg1?|3g*jeLIA6GuJCq3D(=w>8H?Psgs*nJ#E5TO9_RZ}+>-|DsV%M{Co zTY4{@>Ah$K9`P31;0-@IgA3om?w!Y&3`f=5+ATu6g1d-_A^CW_jJQ+C8)Tkb675Nc z?&&MGv~!d>dnydwyd_3m#8h5G!P%Bq`GJF=iUZ>>n|W=qoT4x3sNgHFGehIGQ2fxI z{R_k-3(KxR_a35ql&I?wggTxB%`itcuemiJ3>ORlmc17+$W-1?b8BnWxwA>Ez@xnb zFrYd;j~ySUg~(wfh$ie;0&k!f&6{QPw*JejoT0y0{?0!byAed=!n#2^F*USUs@a-; z*&cuOpBM2h!dnu@^AZTFM*J(qxpNP821W&_>A(IGJhiZ96o?snKPbeAgwdQb8Ylf{ znl@SzyDX>X{$G=21Xt7eDqyrPqF2FXSBW5 z9)xTou~ZY1SOO$o=+y|mL!NOeJKSG`!C$-Yf5yz-FUfFI>v|}{)S5Ud|J2K+vcpS$ zJXM{t0Yhv`xqJFoz_0Qc7b=80hUJxIUCUa_Ptzwth`Wc(2`{zNInJCzDVJj#+|p%S zxsydxrwB4(S;!tN$_p>E0*RG2IlfWIF9jB5?d962k>w-lr6)sg@6vRuT?ofTB@cwx zJBq%y*{Ud9INYzHn5QrEbc=svr)_;!s&lPK;@xVR?6! zC+mLU-&x74zOL>G%n4zXx5rP@m7bQkyLTazlkko=x!PdfXgU2YW8zv_Y+h7LJN^K{ z1RHjrbS*os<|Zr!>TYLp{10zcnt*kg@-e`O-B}`(VPk2SQRk0aw*E+E&+tj?bwrqw zYBibBAaautPiK){SFn`$@ElS-hv1EFhvYXuXB+RUG>Rj{k^FPNh%RvzN^G_I$gBwu z>g#rY=bC z@VCzV(0QBfyH>U~Zl(P6D|i3IwduiE>SJ?n=PF;+TeWeXvP%1rgPURTn}5F;W9VwW z6u7sGZ?tl0l=~|GkE~toUG^!eOXn_$l^>UO+U?^0`MbV;2S47Oy8*AWad68VA+Y|t zgREV|UPcG%ct!V*Hj!X=P*-x6yV{3kU5A#wgNRm^Yr>msgwUbB*E8bxO zRFoc%q+uvH4`U>{!&MuZjPG(xi(YRq7adX4_ilmNjG)+qxi)$@gQ%0Vu!5txUE>Y8 zb>3O+1xY>QG#&2xrH)@;_WIu~{Ddu|B6O85sM#DJql(?8TKj!ArRl5d>fwC>QX}>1 zxA5Kwh?sHKlh9P87}x?nxGcf^yefONzKU47O}d2cF7fFiCQg;S zr&M|)e=YHpCExvck<{l;X+e4+nuuRf0TVpPuECX%gcG*cDcgMS7c_3epQNPqyz%a} z>io&#W%PArYfCeuBar!t3l#2pt&*2;q>Y!`mL31^S&| z7~CXcPvKfuG$%78;Gv-Nf2co|yz9I8vl7^YCuW@o*qc)9v%;!E4kCX!x0O~E9UnLr z?>GsqUK-gNH53$r-}v&$po-|u4Dy1Xge z5mwXq(17b?>-__@W}G6nW;O~*^6a`8st{eO&OLkfgub4l1lQ^8R}~n93Na!w#8)F1 zlR1y>#40&v$cO5a^16_d9i@u;v9FR*5lLa8cEX<1Zf^9YMz0m!^3*WWe8fi|+SbOL z{<<~RrRA{@v0=ZGloto7cifNFeSQt{fHjDSs)+Tzp4bu*ev()5Ac5P^@a?5jnDEBA zRpHyw0hKe)1u3Tu*c9N({$!CC;8XxUrR?g-wFuJp z)bSTck=GreO;afi1G3gq1V%1>{v_@%-jHMO=JpnTM7Img9z0lvhd_Dc4?vikhr}ZrX<{ zwL3`jQdFIe28o6Ze(dW2J0@ASWvUH^T17Fdrk;C^%Vmn(kM>@Wl_MsXO zNw2LrY!bI6;qtqOm%VRK47v{m5o2F-d~c*-5Ih?Am#y|foMrsSqD{`a;tBs(dImOw zNtp{IN5pP!@pc?0gny3-ciVfP8qsG0HbSt*gEd0@krDhb60wySwR)eYFY+jq(3e`P z0He!jq=JcU*7m|@uGc{6#FLCvDCKS z?-g-p-&dY=m&Ej$d6KRdg5#J_KD;8KQtw%9oH@B+(I@}A;s`bWEy@|45!1I9NpFJ5d^Toy&-f6_k8wBQ7|tE<0)Ut)sw zk_>@3OMlysF1^~oqqi|5CU~LsHg1;aF4Mb>U|nWbzBeyPaqo!gKFd)g*!7oT;UpMl zTP2pK!pR~|3FZ8jvsmdTNotYzY>onn5C_~N^3ET4DB-86)qUKj22eJFK)D?DOGL&3 z&fxO5L4&?r&||(14Yf}&|M~Wr(6Pn6%2&6j);8Q;ci1FMyPO-@P#7>CC4XvZ$X6;~ zG)OIA_fJyfES0p^#5$&i{NyyL5(d$uEh0L6D4QhesoT;;qeWXU5cbQ$Zu>d#6axpM zbmODn#cn%lx~<_`Q0?Xhhx9u)uckuPtb@dk|2XR6G)6BFF_Su`8dYy-OnF5&)`yoI zvYB1np8d>(`jlIt0JRmH!iKZ8s_tO(kn!FvToRZ3Kd!Ce1WAndY;oerN^DVKVHGvn z(8AHW&N}DUxMlRtcnyH`*m*IUD;M9>x0G`FW{PM#-W7tLvf(x#f5{U$c(^~cRf$-u zX?99DPT;|basr%Ov%2%&0O24VWQvxj`O(EK;5^mUt`0=@3Oo0i=p9~ zFwVGSnpQ#O_ROC@tQ;9Na^r2!6+H;GzJ1MJ(f|9Vv$Ip|n(pJND0<|n`-6K@Bg=$8 zly6!IrdI4uOkYc!bIAU829dAhT=V|1^?s~?Vd3wIA$sBq5n^-k`kZDlwvnq{~6dwm_SKFC+W;d?lLSsj6vUvpIJC(hA_x6x?!3sRz2 zf74J!+*Gm6BetmKGrLDxjI#7gSr2R!Bx#_(#(CP>6}U#+jqv;QOc~wOBFIEJMmK~u zU({C0nK<}hDh~IT2pn;KiGIe#Q*S1lupKk?y5psb#DrE=g%f9lSFej*W8}+#$i1&< zu3rUeZ}Jwr{w2Ufr%)eV9pGJuFmmEcUdcEIC}f{ILm1l(Ogy<%39-`e z7vn(f+Oi8qiDIAGxW{i{zEY zBn0PR`n$(SykLZG*LfTX@({^DjI3vll<%8Fmg2=C69|?c`9S1Q9e$v7$6O@uF;kyq z0DXUUBeI*HG((F~fvmm<54w(pX+T8}3HuK$EeWM6XT3Y1m9T4WZ&!k~Ku$q1IXnA% z@t_uzxwkI&nchBotPkpj3nr>AIBb?nC0gG#9!J0{t^!KmCmrZk>%Q*@F-5$U% zvI8_l$bsbn(EtmrI`8Zr9nLq8?!VGkk~8i@-N()|wxn0 z$Cmgun15}968F`c=*y3}rfIX*>jaGi7c6p)=iOPI zU005tv2+|u>{x!#!8h0lHs$=w@kEHT z1vu(@P}1VOscB*Uq&|YMBDZc{*BMU*p6I;DS04bi&HA$Mod%XD(CXOm1SIalwN7&( zH6YW`=|PZgFGfmYuuD7}g4b@b$aYXD0XWM>8>#dRHGV_}IShzTJaI*SV`WUAUy!FC z=sje?mmr$3W@y?%mJ#ID6Amyo02oX+WiNF62; zhNDt0;m$0heM}}N^j=3K^8~f)!HSIoA`fXFF(&(ccNBZm@iF#>gZQ(i9FqcT5GxPe zCH{Lz3}q@YxBUs38TUZ=H)4^eAIGeaPlkeg=wa?GFL*)G&2EkY)D6A*=^TH|b>)bw zt_@sB_lVpMlEz3kmb%Z?>hLK#XbGVG#Maj(vy>Y1R@Dwt^Tfu7Z=23Y-t9gWbtZaq z)$~p=f_;%Il=!;E>Pq5eGK6grB(aUEA2rP&UpX#V-xvPahSRAk#>9h*LqMRgCUW9t z3z(t8f!!+F04gFuNm)6g^j;QGYP818R+Pa`ExG)8+%3esu3glF0!N7yq^=Mn68B8R z7dK57Xs~ohKGG@YEj(c#Rd)!wT-KwGwpau>>vY8Ol0@8dj+ zwx_HvaB|HtRO;lNwOU)Uyc(ce+MDds~ z%9b%5@;IZr)3P(~P6%%pKe!`&e99{F=d#Lj@K_LS=$(}E)TdV{5bBMWblew6eV_aO zEBQ-yN14SyO{Bu*;#g{`QM-1jee%09cY`7%GBVNuc!J%=#zs<5gz6hIW&D3ky#-K~ zTlYTv0FnwQNJ}W)-Khd1sdR&MgVGIxNf>~1i6{+{(jcXTbhk)%H+<_p@9#hJojJ@q z?{M^qd+)W^zSb34S+5h5k~nxkG68Dm;q1f@z&BG-Q6X7cU1et=dYIAwS1D5+vasF) zvsnhniLYhvwI`w{mbW zv>t~D8DlFerfFdHIKfaSYcb{tIr!z`DJm&d!no!haHo2=wDaJF18i+shv9|q>F8AS zZnnYbTooq&LEVe|LqkJ+>5sBJ47g&$Ko7Ry03v-m$n!7)uh5<>BEm0PEE<2AhpGY{ z=J!3)?7qyHpvuu~Y@ce_qn6oD^Vj82A?(h%t671xK?Fg&S>o59Fb55qc91z>q$O}R zUu_6&9}g4~v_W>xtLKkRFPqM_9N8t=ua#37c9W{T37f{?iwTu(lCn~|?r{gh0c$42 zTDk#%GBi_@)puO}p_dWIv=b^5Na+f_nr1R@sWtCE59{Ed_=`~n6LeCqwQ-IOYXqAy zQQ~u#WoVH&#zNOpBR1ueFTc#0-jw;PmG*;`cyP@4iTCXTxy_Kv8-dEAVwk6&53|?L zJb67DKTavR3|(>z;p<^b+e@#UZ8mEH!b-9b{pJqWw|E=&uS3Pw-8AN4=;RDPo8ZDr zp3S8MF~({jitTM~{_+4Sl|SUQ`2elm7ZcPt+2g~Y3{r-PnJ2IgucM6p_qD9w$o|c* z$Hg&cJ2pt-N59)=*# zGw`!lFtf7K-tJeE7OZadG&N02m%Xzc2`4W`19WGMIo+d>puqLGViGE{EWLcVi=cqO z8pH%HJKEZg_Jh!A73Sg1D?^9-`}^cPlDYgvbljZFj* zomGNAwJ>~$6rh|>f#bX+C=hCf^YqLMHUu9kDa~<%s&TBXtqnBY2hZHx)_}9M>}X>% z0f0AC~bR;89`DJ{- z0nZJMoWQ=|FH>kg572I42R)DEee$@G<@!gO=P(9&Dt008fQx}duFpZLGpP#vSO#Y1Fh~-% zFLGT}y$U>vJ>V}q0v4K^n;Uu1`Wd9M=G=$;crxe*2npX2ft8@GmDSf7pzHjF{%{PD z$DDxJ`P~hiD}u%$$TqG8QSl%3>}dNZPaY$2>Gz~kyF*{TTtP@XdoWXf39OR{cok39 zghpUZ6u@*GFAecrU_%${+zoB9DxX31D9P$bV{}D-9@~A0Qwu zzzE7kB_!RkfNbmud;sP;c$q0kh?@Y31IaSjQ_$D?BN`5%J^chn-*|*}(+bV@p}^WV&AK4zC1%Xb-}oR`5}`&-fo9EbYvyi0 z!d)4hDnNYN&A#ixH**_Q&4bG@AJa28Veh-s-u)drXfCD#8>0uqg*eEr6`uyBfpRyl zXUakKkTks7&)ek=5^l7*=J@swY7TV^t%pp;C4Zg_P1*Uc6yWV{d}xo+v?{!B(J)o1 z4nWV{{K6TnvVFK`Hr1_a^fE_kZTB`Xte#4)i=pVsSV%UFya?;xolxJSNfu_1H2{9i z42CY=3|Ejw#7F?^$cL z>VN9u!UA+YpC#}RCnzfU3d^5!6xLkwq6LinE5T{!cMKF`pv8X%%QgnYO=91J2T61I z1ncDYB#>jD^9fc%5E7~Z;*2;!(^nN2AFs7GUcv1FW&m2tLJ+D1aj$ilQPv=JwXh>Y7%g4S;f~?r^z;tM5`PC_00&fe3pR)>7A5w}C$u8QO{Skbe@iWNX8A9?^&*7-P3OW=jtwp2s zM>CL9b%NqCZ9whsE3vJQmb5Lw@0maq(gBt>9wC|NE08iZ@)PJhQ{Y__+lB~=fvme5 z4asHn6?KjmK-CIcO!4J9gm<3p6DZ-cr@-TP#PIPg zP(NF`-5R?|#Q=Qf+bYL( zU~BMc1Dr)BAz@_o4C8}hW)eJ+79tezo>Sv=jJ+96+`Yj8brXvF$qJ2hYPU6_4D^HV zGX!|jR6VF54`O}q+Usj;r^={Q%_+|>LsdjY{7VKPa~yB?e|JUvI*dATWJrT}P_NJi z4u$P(=TFM|FWKeLm(a>H0(nOGuvt-&!CfppYr%J+%M+{H`|Dc;=(I4j+@p1teOdm}Tpi%&aT1iv;4P`9l2<1XkB zHjh;-@`fBrxZq9gHe?GP+Adq@9__rf{%qiystD)K+~(#ch!byU0Hn7JYsO4dTpF!h z>KGcgE|e+A>~Y&c^^Zukfq)uSU|4Au7Z*43w~7~f_P(H?Ag{qSKxk4~xwsaf_DxZu zpz9pxyilhz$)w$yD)IBt}7$OASN>iGYOe zcOYc4l_jq^c1=vw_(3zaos+x{^e__e&b)g9^ag5BUfZPEj>GGcA+_dV4u-^$pA<1I zE%(v%<%MH38KL_Pr{SReDwO|kzv`C!fwYTj@qeV6rx*4z=^txskJttt){f#* z;NgFF|EG;`7%J5da@RhL(7OmdYc))*bRXjW5F^v6V-OQ|y-!g;K}YsDHe2IsJ_Br( z6svhY%nMIJw2*q~cbRDE?qZktZbx2I<9K|c=ZVbJGI~-#nJlu#D{7%K#j5al46R^ak77q2uoqskHC#D}+q{O?}Y4S&H**PHlMk3E`PeGjC|%AgI^yN>TDW+>7|If`AL0 zlWc@^V&r@l3TXccE0QHANf8^>vhGm;6#|t2cw#HXO$&3PI7)J_NjW-AH(yiM9Ngi`W5d-LgF(?^3 zyPVd$EZ~aK{y27W7ECeakN~&!x6bQGy+bHE^F|Bpq8Q79qr=oDZApr?9D^TF`A=@|XUT^8zIuJOY zp?>rUm#uE9R;JQHd(lIE=;Cz33aa?*%)33|BRc>C+OL)nMXCPle zAyGXREsd3fy>NBF1zAA~ZJM`rOgHl_93&2}+a9}j8?C-M@*3<$bH;ZM{=k*I%c#%5 zj$zh~ad?47bE{B~zEH>u@ z?CtHdLF99a-44`LJQU!&5h=6Dh$a&S)H%%5Zk_6BxDPbJy9XhdT>G@P{I)by@}9I8)Fotg`5Pi!ubQhwyy(vIk7yW>LDM* ztKt63Yph8kPtAhM%F2`{FQVao@^9tuZAUJ`1_9LbcBMB7?p~;=tQ!BqPXu6keYNbUee`E9HXB+xjrMuXD`g%|Q9w7*>xPRe2y)tg&UJN))aH@=h8TZo)Frp!w5o0F(tj4jHX6BV zUy9aDB}N(XnJ?BkI=%dKg;U5E-sQ&~k%i0UKQGmA3E(sw!x@YyMOCFS3@2u{xVRrTsX62Ejj&);I zIXQ}uYa{3y1jdY?C=<@G9gAU99v0U4TMllj3FWUl00Z3ght(gC0uT8_q>1~ZlKepU z1}I!j66xw8_pR+~WNu#G+IwjyaFK|qBbh>c*%T)&T!E+@(v}FAcjI(OY^)BxO?@CZ zu4|6%H4RQp8RL(&h1Qwh#C!1%sQSAwLDT?651ZUH+exGusHG3Bhmzs|G}^nEcpDa` zf&x!JCTCTuu&Sst=oG?`&=blm^=t;X&bjwP{}?jggnyg^?yd+rYz;rii7bFRyMwrA7DA_T3@L#-_qL{5L{9 zK36wvQ}8T)^$)DQ=)K8URQLOF*BtHy{vP&EG^NttnD~jIOTySk;yr|pAMX*3_1P-* zqzXJf2SADvmK&AIoN6VIDx1@{_+(W6Epd{ zcY_;K-QiHCuwiabZ*W{v|M&Jwl5LqljJA9QHq&00NaQn;`~2Q^gF@u#@-b`fN>DvjDireAppF}KEWrC z92)+UUR2a`lTz)@|58?Zn9BrWG~&P6RWKi^H8j?Q)jyCrLfh9Tj|^zBNp}mC!yx@& zoS-VJe+4BEYd#O7x*!*h?&M=%Bjq-;|#n=@2s zehgrJufeX#UOedNlDOcXX<0R~Mls6pY>|!y*k<&6Qn$~JZ|Jrm#(NuNlSZ|5WsA&| z!=;>L5pk#wB{=*mIXUWmo48Cqq--MkL34Axsj{dJoe#UAE;i=Fmu>M0_Zw`M1hvGs zovogDIT#)KkIXQY$#=C=^Oq*O2b)EFOuheL$1U|6Rk(PJ``h&gCg#pN#yMIi?4Jxe z@+!M8rI@f)zoy#PFSIaD^s;r>DHqUmyE*>m&BWB&>3G0T{Zrn@W9(rMe3_&G{A&26AgKBC+#+rbtFzaUaoL4oIoT7{TFhOIxBtc{HgiH*{}u&1SXPC91<{z)lc!DLY6mHp{f@d^?F~5Yz%D5s@Ev_g{fV zIX<255NgIVq*1r3uz;+%LSA8E9UU#Lhr~og7SKJ#2>Y8*f)Xrbk)4}cn3aP=0OCw3 z0UpF0P^+;~G?0*Tl7nb+5*ba+Xf374us3f$SX)^9QdUtB1ZZPmob)!h4mz`A!3*So z8e1Q#Q%7)L;vpzW9{TwBM6I)&030`1A9$IAs0|MR`r83L!wYc4{f(Tpr}dZTo5#ZM z)RdH>&>(8E{9y+{IvU{&&5TYd`-!s_-B=3`)!2+7#I-zkQ5tH=%N=HN*52Yks@0d& z7bCU8!x6{b*l^Se4|tW@o2qnCcV^vf0F>6GncX9FP9Dyl5w5-ZS?WIC#pQ zGF_Q@C04O~x`eBYc2Mz{gRk@PM*m!iyA^|Qo&M|^)+SCsjYKw{+>*#ds7YGjKr|0g!_FJbR zRk=nIb$PFiO*P~f$=1Gtt`s?ee^%g*i5+@f$deuGt!EMvr35DzWyevMSZgYyN`_Ai zYsZIV3)A!D$L;98-Fdai<=^(DD=MzuQ%ao3V=4J;b9o@D;#Eyoa6Gn`@2_#Q9g{5g zlL`i5xtN?5$&&7il(p=~!jcpYh{+t=WU-}EO-xLT9kSqHZjiOvMf@Gab}aCO6JTz2 z3|Bf1XQ@|kTSn#~rr!R5>oQL0Pj6$>c%==15LL_A*r^zDhnbX)SASXXbpdLjgn}4m zgV>>|K-VS3&e%_%gjP=tLC7}6r~y^yDQXGKuHx&2(B|jonE+v}81!6&3mi2{KAgOF zO^W4Nr6Dnhw+UQ8^@SBR1H#sofq?;~mr_&Si^&2gUtiytjdFly1jKvqRZtoYFQjK6 zlzUya7&|0Ipwe^Gc=hYM9yV_7*dU?1KRY|~?jGEO;P*8EOMJS8!7)`m2!NSoe-6l` z9x4FslAJWS!ue>zb)o(m9V27r-JKx$41`?r33WK(suuDEBVA<#Wgiq~Q)pgxfT?OS zBR<2%lkIqq7^xsb8d*0T)JBY}scmQ#e%SxGLBDe4pkC>G@UoDSGdj}3(yAr)&`+=M zBt+e){zr5H6fzt~wP|%6#x1;}%nx+j)v_9!_Q8(U zOqT`hBPaAT?rQ;oa^sh(wB0W2?dO3;!ORCTmu)grX?LFGW(nG98&{+a$^SntfUe%9 zJpN4`vfY4xryQ?!8;&C8j;G@Grv%1pV@N;j7h)68= zY>#hXMHO6AHF8jK=5(o+k<}1F21VBwmcz&ZO z(8O;|0vs`gy9IX!{o4H@11EQ9-^FB4K1;s%6Sz-$s7arfdb+#2hmfmlXmlC-t_vQ5 z#e=qW4}`30VIUb8;4Iwp&u#~FuRk`&D+;HsY{N{-5vE*ocw1oHO1YL?>@s_A8hpNd zqG}LaUDACeIzpML|7?!-vZwmaX6xN}^3^gX%R04K&@BCVG0Kv$*_Eo;(=@ znd&cWuYVsNpo1q3<=F-t&EPyxa=aOMX^<#OL`j(gB0{?t_imp9I-0y1+5PJmPcqP) zg4DAIPR|kF!b*saaQ)kin@A{ils2`i1cMC+Ft3z4i41%Dmd~Wd>$^Q5J0WC#U>R8q z!b^QL*kT!XE#E+yjw2%@OGLbtUS6Z<hH+8^lpceB6&#C?8pZdWjwu zv@3IS%wC;2sC%5-@W1kwBKg~wC66s{GKJX3b#a+%VGLJ6!p&TKFJP-~+-BBIfZLv1 zih7roFMIa67W-%Ifn4(2ILRrQ#9mYG_O#S8(=maJMPKf3)YjE#(~uE_8eaOur<{MV zQQAAiuyUc-OJilSQ927L_i5|yk}7MU*ep;N_O8?V0B^9i7cO@);U>S zW#*uv0=w1x2iXOJo%x7U-#h$+3)@;OntA8DlqS@Qbl>(`73bZ*6>d)~$<*B1=)_e_ zkIH2Wjx%!cW@lK#)}qfZHM&ywJDyV6Glw(XTr(S)7=%r>TAEOQQJYqpJVD zdGqTVBmgRgRe~SG^Z%^hVbZgVco(^|Cql!N;sHqVDxkq(z`isFAdtJbyj+_WEb&j^ zhWe?*s;k|gKA^Uw&QA(hzqq3HO;qU@_1uELto#H2yDp%W`AO`!=L~f7S$VLY;K$j^YfXAx7$--giS(T57o-j zlCC*iZ?M4O=`}tMP8R3l=F(EuH9|t}RJbK?!J-SpKu6DkNn9uWojVSLc4Zde6nqRH z;Qf?`CxBP%>?|xi_=JR;h>0yJ*lMstTV(DIDF^mJ2$l~4GI?^0Q>i{H*=JyU-Hc3; zJwQfxC+fG@+V)9B{dxY(E7|}TNyuJKhT+5y5Jg7F-kF7QJLd&Jrt0E%UczJG+6TkU z9Td{ z6DShX@JGb=;PKp%mY#M%-UQJbS$^-Ge+a58pgT_su+#ZMqVw0<igeut$GYo1N z)9Iwd##)!dStU+J7MlRt?pWB%Uybj{tExsW8#vd_?*i893(O#`qtjCzaWOHr{{DVT z069GX`s#zI%3}C@KN`)g!HVku1?d3nJ;PG>Y={RNsvFp5981G=Xck-1qZ~@tIj;sO zmd1!A2cb%}*xWw{wb-f61H=-48YS`#BJZ1vP4Z(-24hmJBE0XG>W7DwYh(DaB1QQJv zAFz0yR85hvO^%PZ)qeEI6e}$^3#Q#)zn7J1jgE}4z?3=V2z;D;5HJAI_^G1+)fhZG z-gT8aS<1kAa|6gGlmHn+@Qy(jELh@HufMqet#yd_zy<6?sSE4}<1ZjZL*VElkqB6} zI9VWl<@AV4kHYdPN^I>S3dQqSi;ap?VpMw4wApvcv%tgNx$o?vx9 zkI)-nK(DiDeL8BLYN?Q^jwF6iQc&0u!w-FoB87m>qu+3^h&h2RJn}$RHp}e|oqO$e zE0riT5jo%i=bH?97$<=24XI~q^21E_Be-=7&BLhe5c$S_&+m+x1I}rD9$SCLcnR3K zP?fpcDHsjMK-b{5ft1?4G6pa#&Y*7q-~Z{)E7$Mke!);n&u=~!E*)e)MRNj3g@uaNLSHCxC&z`{~XI}3X^xI!NtCPycDr+O!(Z_d9KBr!SXHNAB$95 zx6Zd&B;f}X5&ss#_@C32>RVsfpO9_gx=`TQTTGBO?AjP$g$wX3FhaAa-up?%KC&J~ z)oV=jDLp^jr9{d`sQ}Fl`){JR)BQ-a`}}--TU*z2^Y!Q8b3li~<1`_XmzR+Dg>}NJ zy`y8a!kHF0a@Q#Mnnz}F)@S-Mm4H&s<1*90btv(}rXO?Ye6;w5{WA^L!FH_S*H247 zZZBPzPPuiXXSw}sbL2Y)SRR1&O*r*iu=uf4ki?Cx_$*aVYO6)R`-zm`y2M@a}1-?5x%YRVIhJxegGm!9L zCjbq9Wo1zX4-x>mxClyfZ|&C-IDddX<|KP?MFj-}hUTC5806ifJ3E#8VWJxkT4OP& z=Zb8D!!HWV|0+Cu$cwRcaG>qu>nm(OA0Q|9LI7MCz#Nmw-PKj&>>-kRE4 z@v{p6_?)x?0;It1pk;VCwtB~4KI&py|` z^TImvxdHcFtHqU$j87$h{rWLWrD;zqv(V`#_@1s)0OLSGQL&1i4YhQ#B3N#r9_zi? z_lx}gB4_KCTw4{z`5yspw3#OPgJU#E%23zU9r?x6_`aCW(RmH(sz)sgC;0=FhyyW4 zJw1xv-d_1gc^ksxutHQ(0HiU-w*+^CM89AVyUEmb_N$aQ9WXl|#P-S+71Ig|Q=6nVtJ&77cB zvh{I|yDDf8cHb2XTXR8Abz~EiGyh>DPr;=RP8?8PR>1I~Jcqd& zK(u1UsIG{32yprhbGWyN*9`5A8&3r72C{a_MK;%efk_hpBi}~z={Ud_8YT+1Ut}Yn zz{Pt=g2rH{IuMGwBv{@-7WhMF@6dZxte6)(9@i1fqlbv39nXVlBX4qJeWKc4?V@d? zlJ}Uf$JZ)0>5N+=dV4n}HBs0OQv)=)q>YK^nbp~8RdG~He|D2u zF2nX*HX(vyVlLY(u9_&mG-2;w>o^X1qI&ktz@`e;#2mMpx2m&7Ug)_w93gW9>ip00 zd_TYDj)(0G0s^k-8~eB$>lEX-TvuBS&87nG zdYFkab7q~ArWfnBym)QFQM*#_r>bBxjagsyMf&b_u|g=t0_)J(mHR`-C~>ek9hf_~ z6{?DO2oC)hE(tfKDKPahi1~s5$T;_g_YD3zM-N61I(6g4TQ=K-D`y117F(6cWa8Pe zgz_t!o1vrenZYhH#fsR{>Mj=1IrEbz=Z%sdqo3JB7Duqayd$Dgzmmsju28!z7aJSf9lBqGvgh?BxP*j- z>TEF)XXe+Pgn?wn-ftriA#C%%B;X!%|Fx5`LPrasiN(Ow8yURCx#G8L|8)GTBMf%+ zL{2?Uz4O8hO?JJf0hr=Mo?Gn=I^^?`Imw@iL&c|)-=or$*j?=`!sqt8=WU`;3HLqc ze~2#Ti`TJIQH~xGLPkRc*YIgoJ~SGrnU$5dV0A{E@nT%XyRy7E%aE%Ln&@A>IP2+Y zG6uRWU_{#?K}f32!jkJW`A=FVLNTN)gqX&o;(_!k%&qBS6kDcU3`E_@KL^;JZ#P1S z+=W-uIC~hKhj5a~)i*bKM%a8}A1$5gEQ!CWd2UCP@p)^`>+EGn!Gnh!FB2 z#FBblX*-;k^Ge<*aKHWyMfh38_Fvx5pYks1_4I8iyEg+<8fikj9eeEEO6(5|xbE_Z z#mK*S^W~hhOJF$J#gcRWWU-ZL#r^c7!Bb;V)2;|v41f4?jggm3$j|v&>23Q`i_Pi$ z)^iz^%<>15$0oO*NM}*9I{hO;ul;K4J0glX`J*=N+=O5-%UW=OvdMpK`%8mI$rqgQGk2-Ay5V%9 z1#TDnB_uIWe)_}H0A+Ts0(mcx*?6D2L!=cNqceeJX7g8l=|ar|Cc8(mGxg-GA5~{| zNPktinO9F|%*;5Kx`by6=3ef<=?wqJJ%0H!@4a5l$fg{J3gNcFtPWV~-^ijnm4DVO?@^@0XQ1g*Juw+Yd;6@(+)*;U?dFmoiQg+X-PdBNLiU?S^mdQ881aCv($j ze$|dl1BUXZ6t%R0G-`lS(8T1ZYVgp=(5SOpC!o$e7nNl<@Wq&w?n0Shd-2&L!Hkc; zmZv{%Q;wrG;vz>S^6!LIr1h;uhsg5$v7M}WBPKLc`!nsFXsxnwco>wtl=RgYat@9=0!QSvZWt$dJCL;g!P9LJ4Q zrD=`yJX7nxswpeGn(OY0<~#!CrdRXOt$L1{>;KS%$D-a7I$&9$ZKA*GVY;$(M(iSA zeJ?O9W$yA-dGjUdOhw{B{uOOhH+o0#p4jP2^h1-&lSG4KEM&(QWXfk+HN^`^jgvj_ zc&OEnEnsH%Lx)O^(e0t4T+=v&i;S~CDZ)v)?17s4e$Pq-<#Y3SPvel7f-Qk&ZG{_2t1-dmc%Az2cA)_yiNu4a|; z-_~4vKl+(7s3-fTHd*n;ikOVAzw7*q82Nm3Qx-H+d|~Yh6D%{Enr44Ds%9dbvu}Sq zw)VTF2GqDl!h}TA3x!@}hF=2u=-}Qwj7%ngN~RPsEof8V^zlzGg4I(4W+@cIX%MKvKX-zP1y|?VGCp z@n=D^k%JP9-1S~IJ`FwyR>n>GS-R2h@?M<$mT;@}wYCeNJjr{t`8EQS#YAu4NGIMu zTfW7nSo)BbO%6*i=9Ru*UCnA3MWnF^=l?~ZBb6+x{>0=PyC&KZ|Ek*GFeipjYJ@3~ zc_Cys+$bN{%iQgYSPxbUiFk!nak|qqA$ts7Mi)GD|JEJLf!Ms-D$*GFaWunh?Hy?G zj_KzKjaLpo+FYe`!>a;JU7XmHul~^QZ2c^P=w00vz<;7H*-CR)gjXs0X>OtX_n$a8 zR~ebyxre@mDk32FKfnI~tp?9;_-&kB&jrU2MpN*n^VsE8p8EfdN~_{>C`k@EBIuAg zmed1w3XP^(-P1)uwwpOt$!bn)mMu-^MLeq`AJ=|TxAxs=t;4MS`uxT0@4W+cZH?Ao zd+d=9MIk^f=}oIAd70n&Y5QU>o`f%qCQ?#Nq#gQjdC_fa*Vk`4KQk20?*13?{NH}< z5n3s@7+%KHLJhS|=vJ`a{kgZ%AAu~cn=X4%RO5W?-Te=D1GJMz3OXV^Ol;=3-B z&!q40)7u};YyKN3$MkZa$-Od$P06dC&d#32X1YFDw(q22Kaf}R)%YptZMSdxOmRO}V)$wC zr|)J?fj|A%#>E|GRTm{?#-j>C2>6b6a!sTev!=j0t*B0foZ@6Cw_@gUP?5?Y#xKaN(y#W|$lS5@I=yNhGV+WI-@cMnjeu}w`^kmwZ|5_1g2V6Do6--q zwPev()xN1eGOm}duFa$fTwd&&Zo4vTGbpE&gDb2VGr-L~{2QKl5&u(WDs$nF`gS71 zC5cADU$Imyq3R`ZCW-U>9M{l$B8a>AOhF{-zSX^_8RkZQjyM!+s)yB+3YB!T72NuP z^^_48cKH80D~cZkbN6UB*Nh6xP@4*Fd6o`0!mhnSukRg@+31gzi~85r6pI00X{scF zQ*8pxu&Pj-qkMYR(@8t+UmO`NW}5A6B2{~><&~V*j;pu-E~CqzhA%iBR_oD}C7BeQ z^`&t(T-cv_A8*7`Y)Vi4`haI7_r(47YC%DNb$6T=YL5|Rh>DguB#4wl%7v4?V$913 z>;9vaN9fX0yw|0fJA6+4sX32VW-qQ0xct;F*fc5f_;?xfCcQ@DcIZ+k5#L+3UYmxd zKS{>M9&w8M7Nj^vuRf!jc{XLLT(2jLj?f9?5qhE62u~L|WEpL2QvfVeL@p5B>KjoR{s3r4o);1M?(Rr>Ja@aX@|EeiFMvtHz zu)|m1PGUfIgyZs!8EhGJ3k>X_n`uN_Xg`CigX__p8W?zb?mvW2W8)c-e=*Ffi#a3o zbtr4}dUd+TcvoMt10dI?MVrAf5F~ArrW_#wN5RV zjMYkMdHx#nS|oL+eTZ=eJZWSVVosZ!OqssW;4vma`IivJ+wi}!#<-AqhTTe!yr~N6 zGWn(rCA~9GwQIk<#~zk(6Etscch=#zMy}2d<+&y(Fzy``XH>)*CAP9nyo?@v?}GYV z@pCZwk&)Hf>x5|ClwS)PiK8(;!alFusWk^afxpoSv`Tn~*c0zwWWSht`uvl6`kiAl zDc%oyhGBmmXv2INi*m*|DVA(QvkyKEif{0dG)E3wt1N9Tdf^WhD?8Z13`@EgpuA^~%UX1R+qZIs-653%f`xh(gm#~Md zN_%dnxxtu_NAw2W>b*~mPdBtTlvjk_#5eM9mv3)0;5bX?Pzq-2;JucPx^Je*B{;|y zVxGS?f91gSc2+7oP4Iz$zU*C$T6wRJQKnw67iVta&8@L?_oc?&7W^UP%mupt4qAOj@F12LJ^f9Z-_DW4Wwt**m{(c+lFd@9B(kzU z2L%MT?ZP%$v;TLlB%e^WJ1L9suQ9$K2Z9@y;`7jllT5trzBf&hFW&;GEmS@KN~t4S zUHzUUQs_3TFT0wZh$C+0yL=Og@_$LoefcZB^nRCJlx;X0>VydOPlk;Sb1jH-*qIw^ zZ`g706GLL}LNC&f-edlvZa+dA)3}KJ*G}hb*pg9r9;%**UPt)#WEX>u*UxwBf6jA0 z`sC=9lr4HC{AG^W50B3opY3J-*WOW?3A@aU1&;~q3P&aWqL}A@3ty_-n@c8}0cb+P zkj*-gD$0_xcd3l_@6*?#Ll35`diH=PstO4PktXP*LN8NOJM-*Z@L2CzWzcO4n}p0! ziog2bX+r9EUUGr;d4K&1+sZ9u>y$oHe251<1^U*-)?wl;6GJ1bhuvUZ{6AlS&XuJ> zE1%AN6FC>P7( z+wz*r7w(VVTX-c6TseCnGc9^ujN;!=(Y{^=1B!u^xtKG6%3!WS{gIZbi=o=L6lH>> z&VNC_M}EtRU%d|lc|F{g=G3m+7j6V3jCdjD5a@Jt_>{@wy||PlH7~DYjq+vJ+hV?l zZ^gP=FapVM%?)wWzIlUXkot^ck}dle={iMK4)EmkBq4hgB6%l~P$o`a&+*p?#)}ZY zeu4IO1&Aj)<101y7Gohqj0&<1YydlA1OCBvXPYD-rU2fnjX+xM-QB|O&z`A+vAiY# z#OVW|OX>L;s+|a)=9@4zqJ}`6_uF8^IWOSfyzUH9kQaex+po@Hx)@UqS#vc*DT^?Q z{RGO)z%7t$m~6p>#L&KjyqeBv-NN7U()lZTG3vxv@js%D{TJq} zSHF20daH=8nhkwl`OBtAl9^vuFP@3l&^i*4B`9nh+4VnAZRv>Yk?|tqz-vr8Vl5f* z5SddM?Ff?=IBw1s2LgYwbYx9>!aaq*yxUZD=~hbps&`&j^T5}h(&7ZZ@>XX{*sK}WPMk*r6J|yFFkuN$yGUNg9T$yt{WBv% z^#-4Q@&TW7gG80Mn{(7@od$_TG;yHNtGHhriaTuhk^H~Eb5S_^EteFwi8tNH%FEgeMn{LQCGWe? z&r6Ga0$>;ZiPJSOsIa}SHtF5b-cFfx2*lhiy>A%<@wAL=b_twZ|qU7^CtiZb-dB%>F2v_aFcD_>}rgB z3*6tWfH!&3dr1qMj)P4L&nGkH>vw31SIvhtzS@W|_o&-NBouP{bp^_weZ&83pHO!N zCFt_?{)Q1!{hf#zwFL2*E;&1u4xsvGT&2Ii) z>`u!PNHTQcpIix~evFxB*;i;-TvfE`SusT8ytraK7*B)>e*(iK0?_X7Kuo-V2?J_E z59ZE!NJ6iOX+uySknLnPwe~>uIRd0x=11v|6hNnu1O64dAmP%BN=&q;q^5R!3Su^c zO!d*vxk$#rckzI;AL~#oI<7IIa4Hrc3bl(|+#_!tbc{9cXr*cF*Sws}15q&zelz4- zCBaWG8V-l+o!A~D%$lD26>u?iA_@A+bV1!kO_d)y95-Hz*U)H>{X6@|V-8!ZE#)sC zxuT@Kp`@2`Qn<@=^pxA(6r*<4a80=y71})(?{in zR0+Q7iZIWH(fTVI`#*(r!giw5_(?6f7$%O7N8;z>*Hp*4s^Z-D6*DI}{*UxcDu9pe ziVgCR*X^(Edi~uoEnf^WBz4@LRVIkXZHb6<-!8jtQ6xUO>Cx0z?oA>$z(x}Pl$Rkz zQm(y)rIK2h#6Rh{Kpt zf#*o;{qMsBB;jVZTNL|Tih#+TGDuj)YA}Ob?4e?7(A>IZ=#6l?K*_F8Kr3aaiDr{* zI3wNQ+o0CK-{4dlgVv6cPNU@^F1o^nK26D}jzBWHlW_lMi+D@&m>tLCnvlr$=9Brx zj9MB?=e{XzX4HT-+WWG+s#Ig0@{mgE5%1}f$^_g0fcdU3RubfUrmrSFzdcUD{=n|! zFn%gi{~&_wT@ObF~)y*V}nb~l{D+dh@a7myg5BK!IE{*j@J zQ?>FOpB#n#=V4S4s|WG!&xKjL<*_ARfV}Rg(~n%Q4n`mcas}<852HMdf#@aAt$UlY zA0)Q;eamJmygd(nI&+Cawf<{)bCKhw-X_KBzQFh59$Z}pwk97FRd&25*)B_1*r-zN zKPWK#@VMGs=qZABj-{TI*tNkeoh{s&Z$d+4+a%)X-~Rns;TH)dO| zbUppW%*YrIuKT|S?F3;e^cI4I1G41V1kEuQ!FZTZD|V-^-w_kjPl4{l71|Gc za-KAxOqJ@rGn$;^l$4wl5E0S6K}o4!`0)jta!I1DtrFtm;{zavafczMj^MuQpp5_w zXyQQ7`5Ok=U#6y}1VO=<{ZS!->t)&_76z~oAO&`CAE>|UhbO4MArhFz3u7IfiSo{lkHmFbFdS-QXe%GDF+ zR_^&0ZLgF6l7^CoXuNl^hi}cL*R3w<@%cKjGV|2n&#I5JKU{5;Eybuc8gRV2HJQ1Y zrEP1HvpR;p_He3cy6N%{+*+%x+{3uC^1g=WZyV_OdkaGS@o5Vcd&wtmArytd4E3*M zuM@^*U4`Y|C6f=Uy}x$zAB`VZoZRZ_)kO~?+2R`OGe0@eWlHlm-?=~jiV`ZYPM#ULS3AivIXhz=iSG-*SbkYMH2e`gQ(K)Pds&TK0#Lr(YknuJC>Iz zuRAg_)1S*7P}_vNCVid#6&0Da;?A>`h#0-$8FI59V!;N|P$z9{misdQ02Oslke9a? zta|PozhO>c8Cb6dt3N;R$qE1sYH{zR6;Oly_6K$Np+BPBBSvz%4M{omHBadhfn2CC zc@Bg?iv!4{iNb<`W&L~L9_b;ft6o^$B|y>Lge@W308)uCm=dR=#&A2qx@_DLNLNlk z_AT4=2TrgLc*$Ub3zHJqn+%Aj*MPWw9R9}sT_D8lU&u5yHFY3T)d8T#Pwn7Y0}mP4 zcuU1@%j)ldPd+9^3rt)|paK5mt~OsePMQJxJBMJ7RD!rHhl zt47?h9fRFcrw#{~7hvuc1iZvQvk}5mTYrGMUdtv5fkS_Rug*9r5r45iY$6T?fPWGT z;yEC^X6#=Zjc?~Bbn)d?SD2tE4Aw)l*y%at&0H-?-0kiUArFzTcbOx29un8}PaZXXgpo>n&~cleH|BORp^z=rJiCH!J%*l`*<}zBT@!B>kgfDTdEf8kT9d)2ex47R1RTNgizwh8JISih$KEvU_ zqtJrrHI6Zek`I}KS2Fkke{$1tyj)aUN9SAlgJLzZbTnf*1GE`jQ}P+yUp-vEM6n&v z%h9MmU56X5%eS72lmCyeuMCSi?A{z2R6qeiTIrCKMnDu05Trr6LqfWxRYVDqZj^4M zyA_e{E=lR`*fa0DyVrle><9her7|?c5M_ys(1OPX}(YZ%`_wf22dCen_H@Ud;b_g_UHMM&>LV`ICW=;p7(se=|-zGRt& zBD9|-F@4ykcj+kJtrkoScz%*v_J2r;++GS}y~TWXlkuh2_pLRbqy&IG{|m7u81dT| z4DHZ}z#5w2Ou+=k_{RkzlWbK^(84a((!fWK1GA`ZhR{GtDBo!z`+@q=uFzc!RZ(rEcI9$$~pCI1GWzah=J@Eeqm4wI<%>?$K(M) zOPlE4y;n)llY2mh+9a6c2&KTKzXxnmq;td}gRa==BH;>nf&p*M5(5#y47mTLZD z3T&HXSBM_$Fi-I^s}c*QfTRM!Hn z&vGDL<~@9vxyJ3G7JA!P->iD6Kie1_tc2dv00=&h}xTF%xWy*TzDW6R!IW2_zeFYpds-&k5w z^Fr28pboNHT3XUUGHBUj2r@fFnp-ABL>N~%{Tsk+3_OP3O_5cNGkkEmgzK|`w z>*mA~P%W!&!%M^r5>Af%aDeJr%#^} z0U41OqUg<@hf@3?<9{>7cIkz!gGqc(7#kXW;gD~`*Ur_is&*u{8DmKwmx}Mz)c<}=i_-DDocerrQ1A099|7vGCw*1wl{d4M zMvK|JwKrXSbrG)B)5GdYv!bDIzw08tKeD_dEg7>psWx4KpiVyfa!_(G;brdF!)>+l za0|aGB?hZ5IAE&zWB3glW>C`sKH3JG(!;OuPOxxhI8m5`l`nz8Xt87-v=j5b?4PTqG!KDdjLjG>2_{4C*N@sG1j-sy7&aMKqE1`jsMyQFBGe|N%7wjtAclHW+x48Z>+OdR zjnHhnj0^bw$1VY@I)nMDJ_%=S`;%=fp>ocAN|sas1EXO0yGL2lk3DlW^DepzY<6%5 z3-|C>#co>#p3&dqCA+JpMj9E@uB=C;py^JLkwKD^Ekoy|-pS(biOa&^-pFcMPR43g zzb{r5nlvev*LwInAQjn@`@Zj3xPz(+cmg~Z}C zV3i)ixUc{>v$ieGE}%7s9o^l$>rkHDfta2M7Gax&Js_F14TDA~U0kXkdGw$}sDq_4 zA&|-$e2~H?pvpB!G2Z64nONkpovGVE=K0O)L|-89Ujc{3j|Cuo9|oVnziZL;y`7zp zNFkAG2dod-NRXE-c#}@BiU9sljJ%lNf|(+S92#UiAmi`mdh#){fw+L$A_4<17#794 zjVlTsWFoDvw*FJZWHa)iA=`zixTrqm-Me>P5T1$w%EAOO=xt`89g!Jv4F&Tip^e!_ zF|(m;rSgci>x&gJ5wXhy73AA$dj_L3Fv1-+;q~?uI0kn^*$6;d%D93?WWRQ+Ca;+e z1Yl(u;4$$RYE{3pHWg9_ABt?WDnar*;B~YyE{V+GRlkc4{To!4*SMS}zi-#$Ai#L5 z909?Y8WK`cTB5scgjdiy9a`of>GxpY%D@bsDBEp^-I%y!s;85-jr4freEH{K=GML3 zo04)4YOrN~moAWpQ9`m|R3+G6TR}gFHqmhoG7~2;WZ3}H_!OMzxa{pQi0Bkz)2ZTI z0N?7aIzgrRIP>J)&`+OA*1$mRC-M>0*VkKJO93&s>jOSDmBZemOu~Qa3=+{9*#xC| z9st}{8b-6!zeCR3YFA(|bdeJ=9YKMnfp2u$lY5y%0=k%rKrdUV>ny zKoYgdrv1h}bSJb#Kjpbwb~kPvytj09&tEqhu;XFJZoBA$3Z#v zt#jXAKVsOsCxTu^`@7Q)ii_En2f-)+sHwwy$T zC8i7A#@wqjuB-9u6eOZC>Nz$00J%npINmcp2!l~)opQnQ-=AmS@VRK+FkKvK@j{Ee zR%@S_Vm(HUOl9L8Nu{Iua-$BjE!75P=P?Zm5*4e$y@=CkYWFl2j2qiIE6NFa$LuBI z{x8|!BJq~qBvB1n2$`~i!yDkh7&o4*Y%BW5khtNI&t5FQ@;BQ)Y^J= zd5q`|>*p%6gb$2naHybWaWWeaL}$7lEr|UyqN*M(b0k~2s*)OG;*c|y*FgDQul{HF zx7=Ta6-6bZs_uZCIHGIOo_Dt#+Ox7~88Sb-U?0(5^4X;rUSiW-qW&->asIWTM(Fd! zMQdbKyP`VrGk5n}V8xO>Y%@qTHcjFb%4RJ7Xs7C|b_WVJKxREtPy(NUb?#|2o3=Ha zF4HPkDOwoC9%&%GiIzu`E*h`Am|;qY7XnZq6;xOP5ZIl0esaQ7^}QCB9$huS@Bn>> z%MmDcrf%N6DG%&-T^(2W|B)gZ(429E!Pz^5A7%~9cLY?OYncM!Q~aHSK?M@)sj7ZM zpcEgacpb%cLIku*{C>TeiAgLms3-j^1_BzmYKU>w)YQI$Iu0`~KHd_vL)YWN+dJ8R zHo|-|O&CnS$_e4%q?6Q0Jt4xOQI>3zRCID?s~ypG)~#*Soz`_8$C&<3^G8e3I`zJ; z1U>dmbkuK|UuVE1h%Ul}d+E5{MA=-KA!^4vc}3K*^L)m0t1BtabJnrv_#&5%o4Z6* zSXlcM8W6W+z+Fz^kcSDmY`k)K_3BmQkO)3Db|2E^X#5m^Zh6`4?N;^5rx-SEVsB_v zqY4_pCxDk#qi{o!ha1#NhQQsO0Wc0Z!j_irQ{M-7>Rk|{dd@)O(kgbgN}Do*f&llB znxm9}_nuqTSq{L~j6w>Y;Kw$)_^jn*v1?Tz)wVN2NiRKy)ij37T&~bS&$bSNexDU& z(JQ$W1%Xe7R)P95kfGy2TNlXmJV>GiWIZ;R-oa$NvRGfDqn9o6LJWT2xmkzZg_eKG z&WMJOxGpuGZA8)A`ra)&Cn$Wx2If4|4Aqb0u9L4gJWGxZ)}-VHL-Q#w%vx+WqRm2g zK3YT*^^TYfT3B1NKj_Okk!Y>bZ#rP?;{CTD_H>P1dKxE+FY=0|C*(<_bOJrLl8Dhb)7;FN^O_ z!_S%&4YA=YllbSYA;!X`2`lAfl;(eJ@(__EBVX<7-VL?>v|x8pyl*ST5JNz;Amf(L z@lE4o>>;axLUdz58m+i7!);>W_kFC43#*x_h3tXx6HeScwi)UP;_~u0gmkll3cUO~ z$|$QUJ6-(epR21!w}PIG7Sz;90CN_OSJ-H0Y87nVr{9BHD<@cr7BJ02l}x#RI~iba z_)xE|>M!;6$@3yK#4-%(!!xJ0Kg9Ef{{WgohV&ZAQ{n}aigEx2Fhith#q9sSGq$$2 zuGcGyX=`tR3SK6i#%=87!^vU2Z0>bK=uHaok!uR#Z@+Lb6cm@6j_)1MbqoEKoH zGTe{*{;46-D5W5I6aWxb$Rf_W0vEhd8`3Wj-?+R0GL~0SDLHw05vXAAEG!@>ND5Mq z*vHWOFB|v)y7I3DtpAJv4WUd1@oG5qIvs0UyPhpjAa!jDTrQ(D^fb+X6n*<9ZdA|> z8r=fDN1*9*9$Y{C3Zl;%Xfm{MeP6-cD#Z{H2j(zQFe~jH`SBtEOx**=hWGTZP@7=b z!~T+(IQ47(3Iu7js1G$u(p#O;IDM`zETL-u0`U>s}2Q)h+hE5_IDb8`b#%2<7V17{XZ|F|VozyK!|&BeIqY!vld)8>;~ z#U!y96cM$T-~SI6pkn_XMl2dmet%fb4^%$`fns{&o0acojWlK#=-W@{4zM3-I=|Ylo5^OZWl6ve!>&CVwjpAdkGp(icqLn!Cgzx;NjY~B zrf6%L*pwaELbqSGZR;lF&OOdW5%3!G-I;%_d+_~ImIy+Umprc8w@VOFEoO3yJL%l` zFRd*!k0{ZMiSd&~{Jm*^^M0(fbxZJaKY!)!M1MMb+CBL)I(hMkvhs5YA_if4#yunV zHlk>t;k(qRQmhTrFX?fG<@^cwXMeTUtfn~5{nrb%t$vZl8M#uNXE9jV(n zkqeO9d{GK-#>x^~ElGNsX<*hTNBo}MNNVm@I>F@lzt-@46%yu-5d_1OKSBSZ?yxvU zYE6Fffia1+psIxA51aQ^P%1wv^0ydy1;ultK94$-o)?n8>%Q{RQIyMXKj?W)%978p zTJXo+W*hXO5mRN|OWrKyYbjk_(WBg5mb(pA*)(?cc4}T_eAsVUA!;h;q%y>mP1Sl+3OwrdP$3s)?lw8OHdrVxD5|K?qPd+e#h@WA7V@0A!Mi95 z`PFsFz%ns67v|yNkwyV%FTa5VRtKr6_otx;UIJJ{z4Ixu85i+^gX?8z_^oB+d}C{? zFpxOQ(-S6ma&7abN(RvSp`;cUE9Q)@(^nJ*jDTcCnr+3z{#9kx;Tf#OE7OtJ7!y-A za`ND~8cew&D)T&k~TJi*xEpJNk}-EH(2+!wp;hF0~f$9MzP+os45 z)o*T(9_~T0%WZ`=w_mrHNQVnV8RXhlewJ<>2*EeK?0jsJyK=Yb1ZzVX<)dQdWvxPy z-1arX_s9+X*+x-UL_gwZmNqJC34SbOQ+*kVB2B@kepQoFTX!sxBr?5q2r}9tQp(2S9+kr$?wLFAME3+c-$vmY-jL;7-1koxz^K|OZ2hr zqUk~6H5{<}_r9J~u~d6G++N3zGoDN*z}asPnZtKX!`>w(y?&O=vBmRZe7rNN@tx+i zxu>Tod-{fNM2dJn^W-L-GIl(w@f)trjhwfel{sNd+01iUbtz*J^?~VM)8Cl#KD?pb z);XxR<+JdCDSE@FGF9TjNbK8D%e^u(>8YfEv_Ei^=!ufHAAcJ)k7QNS2)qB6MJ#bz zDB8W)dx^2Rp z|HgW5jjLFCo(osk@V?ZnD=X&b%dV@-C%WFCluA?jK5Ur*GSC6Khz@JLKCmz$@I4y1 zF4#Rh+!Xk0ffa4Na0CO~>j<_1P|8kRq{VbDF~A`T=(mVOfXx`6FdJy1gw>er933Bl zdb*aP59I0Hv=ZPW#W#Di^R)cUESZ(&>h$x8kf=Jp1#3)OfII)v^D1mlqsSvXA!m287`jMQJ$S5q47l8A$<XE+`_Xg&myUm-x4F1qy|&QGB4ofh7%ix4*N zp~y=K|G7ImeyraohqJSi>HhhbwRoQM^iQhSS0iu7Iw~H|DKz=`<#93I8dp1#fW~XX zP=0_cn1R;nW#N3v=ymB}g-2R)lBV$KPFJ9b>XDvKIzJ1-aE%j4pi&Wn4P0q7Xiq12 z9q|2YD=TzkO3(;KDjsrZ-YmSTz+de5&f@#>=f1&L_xLMxi_QmDJ`qAq_{$qER;nf{ zJ{QI==ppEFr!G#3Y52zEWZk`$x>G86<9>misEM_-nyR<=((hOzhkv!`p22bzJem$ZPiXTue*^NheLr4;nKJ z%Z%w~d@&RwsEAM$=cXHTHgj%_mnm%zwJU13H{i5$AUHL3JzBYeGeJTkU7 z@dvHj#Ru&9lg7ww)bq=lF@xN6P>!hWWxY#FN1!}X{4jCvJ&(YwB zO`(}oVZ?tCiZ3h*B{Mk{Id4ME{zNgrrM8DdS$R zpAPOf)Z!Q1JaLOy3>umZ58+q61Jj6lr0@X);>rA?b(Lj*0ZHu}!D3h`U4n(OyEmBV z+(Fur+rmxZ1VfIX^6Te~Ww5`xBh(vONiQ<1@ya@u+f?=tCcQ6(+kJI#qLsxveeH)E=a9Rziw`w|4`YuN=c8&6$-#BnY#A4i=lQr>yIk34`)Q1QG~eD8o;_c1DcHRO0(m zJNnR-KOWA#;oFmH?0WQOBw6Rh8|U^KSWppBGg2p%rwF$K2RlPf=8M&BK{7|{AH%-r zSd7>qR<&CPztn~8-{W+iw|8u9yrx>XH>s-iEl0Lr|#}ty9zJA{`e|%sg)qdsUA|hEn@}g48Q>yf_rQqil z;%||fcSp!aUfo3Wp<4OQqMdWT@Uv;tA$Wq7?favtwP{-3OZ~X=8}cf;?ewdE!{Mr$ zKk3;@=h$JJv&3mRo4jyKcX&W=cS~!vaYf-A_qRgS0hiVej{A?2-w0l|&tmG$qnUkY z+soS@k7*1O8TS-Wa`?WEmz4Tw^<=IK># zY9s57)fWy<;heAauvjDF(rLWEnf}M?=Y@{lA4}F4$-VNvmMkt7cQsD}? z^UZBc`$7nYLfcr#Ta_S*4{62-c6riE=a+@B30{$(fi@}t$I_ioC;xy`h)BQ zg~1Cvtz7Qt!w1ZujG-r1D<@ABm6iXd!tF9baS^SxkDL*8nQ>mh;dnPQIH&?f!R+8W zsG;RZq3_tus|Ap;F&s%ApqH$5Yk`;G{@Dn@sjgvlrkpO*j{_3e0cN8K01fVQhsm0< zU-MHi*LenfnWrpK@c@8}=4o+46pec03s^QC!pMUM&WP%j{LsHXG({DHEq`k<;GntS zT%rcP=D8Ms+k&`Y7xSm6;Y{{&-~~rinXT=(Ic)3{KT?QF@YRo?97!$KpnXR8bgg|` z@g?+C`~@VKhouSFD%L*U3ei7p2Frm8nlz3+q z|0pNsPzvLI3+;D7MCzp9xugu+{uLosPsfxhd#aGz9W0+v#y|DpOfn4Vn`UY0Rn>8S zEKC|Q5_LBv1!{jj);zi+L`btDK6ZG&(!JK_wNgB)xt0h&mb~9ba;#pe=2Y%s9~S-D z3ts(n?`EISYpjA99qxg5K~SRaq>%KsMokiA852t30H?lGD(2mQjSmE8GHv2l#RDL}d6a8be zP4(B{mt-&l;q{D_$hd;QHHQj&X0v&xp&Gii_ivr!p7?!zN^})!f2`xywC4uP`vGeg zz1dxJN$IXtOOx8M*WGW`8S=~iUBpb(Wt8>+p5kKqD*IN!>^pLw4ded{2biZ@<-i%Aatf?RCMvRij=Y1Y(kXbrCZ8QvH1@5 z4|I|k?ApX@#Q6C3Sk$HMx4H}ST%P)yQg?JbK;%ENJzdM+-P@~B>2>bX3*CI+s#6W0 z0@%~^7O684LG7ja2|EGZ$?del!j~mbeHFCZi%swVlkeXm`-}W*M>{)xaA3xB)$-of zOe(NMal^ze>pPsMasKb{%$t>ji3|p`pJZLSPBF9M*d0n?H1X7$Rhh*zPX_ zQ1^%Sd8pG#C`wndh&I{|EMz>iYD1BmnsTYMfBmj<1?uF;UHnZ&9i1t0ktP%F@W{wT zRJ&GO{#&cO!oeR=8?cC7(`-ysCb7=@sYuP16nwj%1SFkT;IIO|~*GY>nr$`+cg>9!htOoUs%}097n7uv6 zlB?^-!)FOwhS`j9-t)d6;u~?95uY`1;nUtp8Cozt!e9uxRUkxQCfXaPJ-eLv-IQW; zSqkT6#rIKGBo=sb;qr>~);dY6pU+c6<(Q?N4?JS^m<2^C>-uDmwb7rUR;%{ta=HGn z>EI)N&t_RFpEg*`ZAf2f+c=#`RNv&?6P2{^9*v{eZvUyMz`i)vN+XQ;d3=MNg!_1WW|&L|PgA=hl(Q_I&Ne_Js5& zP1+}Sn-0ZC(}u0a6C0|Zx0Cj;AVP34A+G$lLJnXG#;D(g^2wg}RxFG*5dL8j+3Xj` zfCpv&;87afFg({pvd++M;kxN6^-70fQiwQ7FCF1Bbu1M^qxGg|+0{Pi$r4#W%eTp^ z2eq7W!2-4K?ob`cg`I;@wX(jxf~qPJrWZ-TD}Tcd=rh(AAlnsoY?RejqwHbTjw`a@ zQWyRYZWVOLkQ3N3>R&8ID7*y^;_x~6Lc%Kl7cau1Tx^J-Rn?f8gdVU0TLBAG zgT4QcV`zD-zwXt?fSxKtbIR9|c$$yLZR)&iI@SrhF769xxqEWi2S4{H$-@KGigz*5@5 z2c!URVLNw9@S@@ZHh0_AuLl`8e1Z3s|NM?M@CI-Z5Q=(KcfM823dYZyXI&dVXJ_@V z$Be`7B57}PK%%>6!yV@a`;9-^F@4zu1ySA?yX{nP^ZkLLsr2@J9v)S5rI#mw$y4uu zL*7#7k^|ur2Zs`ej<58F6_MPq!}#$T$yn2ulKLI`*5!`Nc*KNRUG87As!Vax!EjO=hGt3=u61Z$LreF}X zgLmgL#=c7YrpbD4lB#U8w|_|t}-i;z(MqeLiM}6+p z&g*xu?Oxd0dJ|UQ_0-6S27W?-%UdMU_|4^+<5439A%l16KEEn?-fJG`TP7~yRh(*q zQF&1s3p$Hk;ooV2v6?ezm$X--H(vVhT>f3BXEcRkj@6y7+=hQ!ZKw(8N_8{k3%Y4~ z`W*Cv-h1pdZuZQI&jQW<1%v}6l-snE)_GBx7X_lHtd*XqrZj6f-l%T=w5nj75@l#@1xVv4F=1q@{yjybhFt~B8p>Uc|CA0-f|5Vuj$5d4 z8N3#2WV@=&yRO-c#h-uIMbhA2pK=8xnST;Ozw?5QlXW77(fs+1mBuE%msGa}Nq$Wk z6{<0o3wM+$6boFsnr}1Y5FH++}L4fQEYG1{-)hpKmn1U(oCBgjO|C!80t;e^|g{ zZKtY+iu(EaTRVav3iA~M9UU5bdmLMbqvwAYiLe81hdd0ICcW#FqU%*!a`bIb?G8~H z0xQs)ZGrt>i-e@)Kku`DS!IA0KHr+G?Dc~4HV=Fq-4DQ3x-$nh3L4E246F;x{zPMA z<8}yaRIjb7x(Bh)^U6v}4}4a?1%8?Zf8jeLN0&RT_%ZPP9^OZC6{vxKDbaZb3XHiH z%3cltiC$kgZi7AOCNRe+fB~{%#6uPb;ag^~PaXM8dPECc$NcclrA#<~ zTu6dcInbvco-Xy*o_Hcm^(=+E?vjS6n+_e)|TQs5&9?N3SC0pPR78jKFT zfj4ds5tH|9HGSY_R|P)#@mqx>Qw~@tK4f8HQhW;^zzi7E8vK62QBQP_kTA{J&W@(Vy>mwisB~_dpmCaTlPT9K zZ~{(Q19(p#AMWoDhLG{*Hg|Tu(AUw~uv;5qj)I>9(hD`@|A+N25tp3L4S{TeOgCQy zV4q=hx+Pyah$cCbm}NEMobdLY%I7+d7_*a3=-qjW`!-Z?ca^#cuSwR=I?svtfiQuh zkg)K=U+x{WP55wEorEG~=^ai}u|u)ZTm3J7y;WvW$$!Jj@09;>fx*!@exJvzrl(D5 zK*{BbI7a(y>etro{9Am1Pk5D>^XMk%C(Jzc}4gwHKHot|Mn^gEcYr|q_iM=nk7uij;rB-5L6_|QhN?lVJRLSg%R`EasMNx1UD zJ&QkP=SaoAr}N)Jw56m zdl0yH3sc6xz`!`qcy!%K=(R@NE|SI23@bujFx5X2d3#d44hdq@2;fX`adIm11OFjc zc&jR{6}Q75<7Tcx@?-Zclgdw^tJR4jxn7`Q{BF!cyaP4q$_Vy3t;kY-4bmDlh^GvYpm_j7lyhK; zM2lXXERfKPsIEhh&;UJ{Rsu72as~oNHGrDIN=8mjPi%_tg*#yVS14uP;qh_h8P@%X zj^es)?zsH!b1G6&O=R;Jjksq8C^(Ybp9l$Qs#oxXk3=9|)Do!XTL|PBG&eVQ1|{~# z8q{b@N2DI-Q3mqQkyF~r@-hqXJtKj({vqK_P0j@{F&>^AP1;TagDR5}Op*h89l&cp zN>5MkHDnE5{7z4&Qv*bz1sG;Xtf8cG#)B0}z$a7E(psBaSs8uX1B_Z+1(8G5dH4q# z9$*r^0$Q*dRA99l1L1EPzHdrLK(>o1Q|BlyhUQSg7Z^B0Yv!!0jx-5+H-&9XsVh;b zjY5^*-Z&ZPxg5JemfiO7ItAqfrSZGx4K&RA`4O9eemQ`)H;uZ^q3J-@nzX#UDJVxF zYyt0N7sG$PW!w8gH*mwp>RnBs!)(?0t9v!KPw$J(YPTA2?<{}df6Wlb^A&M1OB6S{?P;#1+(Ik7M26 zXOx~rBU|@TVxM@dQ|6AoVv7PmVf>A6qt905c2WdZ{{;J1J2m^MTe2ILe!Tp-5MUl= z@cU6r^<(98>}!ED{G-K<*LwQq`Nob*X38eaNY(|zncRj6hyT=?j;P2n^Q_t1&+4;E zs<6)`Ai3Ah(SGr@gO)*ix*cfNicCaZ$PkH5)3fX=!E>|oz|dBOENVUR#u96+ri>$Xw4VBxH5-XD78upDuo z#rFE+d&}Wt#BrA3%CG(Vq zb+)sjxw*Noic@{=B4}u7WfT;!>{7`c8g=b~jNC7kwrk}JR7IVU@Hw;)K;x>aUTw|K z8`?QIkPYR}L4Kj2Z&8tLSYZxqabCkEJJj3TYY=X*ZG}8%^z=dcg=PPT3qa59>gt*% zn^DrJXv6WU)}>(O8NLV+H)vzlfcVMNc?N9{GC#U#QwSW&2Z07b`3O8|H^C{tAnT~S zWiJ^}__WWTJ5%czFJ*veu9Kr0U!(o^TV0*bNMGN5h#1}8wKcM_DJX-Sr-{L@WZ?d< z93nMn+6c+IIm8cN-R6bl)LbO(y*6&D{%PLu*TlqIzIsKCOKW*WTNO`#-!^78$hjoE z^%(yx%7sZ<{iEC1Q@AGvM|B%N`bVgUQS^Mkv@0oM=U_3bnsu2y{c9-7>t{ie71L6()u++sx!0;A-J0gL zyXT|Nn(g;5vh(H}wlSMpDqf)?q(aDkrZ`^9NoAaJOtDa(C(*`$YEwq;F(J>i(WbGwMKZbp1b z#sA&U`Oog$M>3Bo&npiWGNk^#ml#RW?ro^^x+hObeVMrU63JWAHQq8Rn_PW)Y&tr& z&q)g*fRHD+*icv=KMHdF2k;_%1+_lg(%0s32TyN3P zC-x-nf*$&yCNiRToHE3P<|V2&3=7fW5Q8Z zg!b4@d&Oty?feDF!N=DqgC}RpMW>5XjQJwf6@n4d?}A{>aq{38iz?yZUgh&y(M7bl zGs1eM-sBCDe6h;pQd9GSie2ZUrO;L3Dz-hosVJJ$qO9M3X!85|M&3<|NUFh6pVYP_ z@|pWr)Kx9X!9yn=cwy;gKI?wP*}kzV7N_5FU}t;9$^S`4yyetI^Ggh32~9bQtgXAiKL`T2Rgqci(v7H$?Cj#bhX57vyv#(X7 z&1jB$Xq=3=-iVjq|ED+b#w+UUpIaJholz1B4N+Fn7kC|}7f%@A<#=^KM9@uqYSH{N zh{C9^xq-N?Lq;Lw^t(DW^~r7%8h#`aj>WAIiMj9TyO`;&Fo!vZZsz{hYL%<=Dh0FQ zJHDzzd@Qc@ug45kWNsN@N0X%U@uDcvC)|P#QC|r~3VI+SzEf z9>M&b{>S?28d8#87*wHDl;qLrW!<62DV&Ir@#Xft=rL|^?Hc%Ks#5!3k407l^?nsw@IUe&=Hp7{ zx^U>?h$G>~$9jF8qk!kS_{40mZYhZm`3%p}mSd45!Vfq&noD%cPE0>0*+hk6yKT+i z@3%`Df03U1qoht1jo$h>{-)hBxxg-tPB9gV&=7LmH`%&hDO5RF0cW`Gi#uHXcwgQ> z3pG+wBOtb(VJ#TTWuc{(JmBUOc)o0|xU6<3yOK(;G6jH1>)o6#>4Q&Ura z0XO}{La%Ng8?=L&-JPAnkH%bdS{@HudUJpA)g-$vKq)g6GFxdR+)d04wd*$St$$0Kv~Ln>pomT>By36}ia6IQcM3BlD4ITVyEi=a*%= zR1z4zS}JVqJniu@S*Hp>63gDkU;K+^Y|Eu!z)td|=H`G)!lRvnsGAn~kMgigwjOch zUEJUB_?U?Q&3tx*<)11gi5%LcLB+dJpbf{m5p|>zgNwBt4nnrC&PSeWB^)U zSdJD|ah*sd$6eg=?(q(=czqqApVa%SEaYv}(Ouq}c)ZCB0%jE{x%r-0;h>wJp3$(3 z9g_+6iB8Lznzx0KJD5k@>uj(WeGJV@U_JXN8*(MPdrm+(S!9N$r1(KMI$}j%%gIV{64J_pP_pS zL@)Q2ZPe&VehWGKw)iLU$VS-h7D@cYt7o>nuR^v%rQHFT4N+2&MA4)B8oxb$Jcq-Q zcnW+CRb=ppwCkh-OfzP?e}Cp&zK*B|NQQUHzMYZ;0zPV#Qq}I?K0sUX&GYTCeRv*i z<*OTOdcu!(jbc5WPmH?hL(PqFopYavz7>o87^N;uFuVD?>U}g~gcav(i7rBPV^ao- z(2Im*lWXlNB2~l$7Q#f;WDFZ2FwD*2$`ivyK^M9n3fx}Ouxhro3O~W(=bSp1#qMh^ z)xJ0F_HF{BxB25P+Y+jjKH9V5sc&<8ODv6fV@~@Fq6(*pl?rw8@@eBJZ(7=*I9?=P zKWZd9XZ04DA8ln{xYQXJ6qUbK~hj2BWTQTa{Og`3=Yxv;hULnt@ZaZ#85&VPs# zt|pOA!E5U{D=(}h5KVR&JQy#%@fi7H>E}Lh!ox@(0Q1)E`SZkW=6;t#bxZrRUi>(P zkDirY&ssl?lw4JtclHmv7AUW0JKX2Y?U)xEA=FT4U$*f`3QZi8Sxgp@koku%tvhIs zn=ejkGLl#R;fKO7Cf^bax-uZLe>P z1NZCAuDC~5Sd(~ubKIH4(iC&X>_0ayuwD)DjQp zB_clg-b1Jy)FLn=+c9S&PVz47)vA;W9(@+e(3q$)eJC`}z0FT-60mUb$dE>9bdP^= zVey%c!Bi9ZK!eT`d7QR6nHjAbl!=9jehAXN3&2ETZ_CP z_z7oC&QCYH8@-&*ghmo|S_?OH>o}J%GBM=HO{_cv`%O%IuDnN*^x8WHBGf0{1l@l; zbRcClQcqR?q}+JvSB^lC+KDZbnTWae&kpcWkBwJmB3YRRRf^NNS^DM{Yad+rs#48= zAC`YP2_N50@f>q`rr{G?MZtaiYq)42KbKOn5z#Z!I|UiSN~nl2N=iW5Pc3|4lo;74sc z!9u_CY%d%9+oVo-zsb^=UUGjA6%0!=e-_r$`W=-s@wK!b_Y^5tEAt06R(RZ{*4h2sFcd`agNRGrt%tdS-FwY_tOkLz*Vn1IHA>`}dD;uNFMsUN5uh#Bf6o z5a+k!yNRAOx3Jg>tF;A^JB@S0v_)U_`Uxl^b)&j%8?JHf{p{EK1z)L zMOI;AZFo6;NHna~*!}q^*vx&%0XAe$nM*@AmZWKW}A1X(I`I|^Pg-w zu?+vZMF-ja+~!3I!6e2n714*(A|p4k+KJD}$k&+VUOWIs-##OrKR0=pH0~B*o_*A~ z%UQy$8x$EDoI(eDr~xDo!hfHFi!qh(HQUKcrdCyR{n;0OXOTp**N59w$11$?5CBhy ziuf7_%;Q@z6#st+&lQaU{@!Vo4|JjxIvRXlBe^fPJU`{GbubUQOcxU} zVBnCZzKG666{x=xdP&0Kh*LJ)!#J^V(D;|#Zg=Zw%e6|Nv}Zb`y1ZQC--bdH1^dhE zk#u^URL=UZkIrw#@_4F_Qr5`08?udOaePft7B`fl|M07D=`cy>Zg8+_0_D|0ouYdg z?izDv=hDS4x`P6vQmpq4^G24bXL+Rc#bh~k5trnY_Rh(&(kGj4?)qV6!)W0hCT$|z zgIoKN%(y&c_$bF?_4vpa4mSvu17$Iqqxz+tk;Uj40XBNTQz=u-_7|ZGnRaNY{bSNe z4U$7`GFw9#gXQ+LKBiCei7Nfa`ZCCHZU_&KVT! zuaztkNqI^OlAc8!EupgP155qODXqz`XSzS<#u;uqp}o-bb#LBxqus^LGevPR+gv=& z>2d5+u<4=yT<$5j&sO^;$Ca1ZQ^o~C+IYtgN`9vptD zAtw;y5wjcrMCjxc_~XS~?s-#V1k-UI^#`s>r&l&@Z4+I%u})F>A;~@Dv^Go_!S~Fa zovpI2UB_qbe-!Rdl71e%&MZ#2w>063cX$P@ti824AA<2{k^9Xr=~^{J85!mKe^HBB zkr7_G!4tWKrGHHwa8T}0p-Xw*CRzwm_+phXRbFF>>u#)UXf zT%pvO!Q?*4=Va6mFiy%YOUaKVRXnd#>?=1*lLtc=z&JWo+|`DA~uzIJ=PV^EB>(&9CW^2m%Zike?>oNJTQu=+@l_m^zztt_Al=A z9pm2tbm_B3qrhsjAl&+wr{|ik9+ZqP6trv>mKJ}O{5H-1sOhK0OmL2Q^9929rU9vl zT7}19alZoU3914w+sff*=jmryPQ-ucTXi^a=PWov4Ld!D6SS=0y>o8tIw{%pmKn^1 zh}mjf!={cV3R^Svg?|fO>ELx2gGI4A4UwEQlPh)LX#Vr=mtI&|g~#NMrNhI*k18V~ zjH0h*wUcDD77rynBwT9pMqXY|kJmEiv6haj11z>lDz9Te0Zh0%i)2IP1<&4g&Hbplg!);1K}MmPMqIlb}x`Lkg$%T9>(3LM*Dj( zmBiHTQww22J7~s9TdZ~%`Ca|%p=ked$w#!{W|O&u16!>w#S_kMp9$Z|{uOD{+ip?r zpFA=34g-FjHCM>qUyZb%Sr{ueK%0D2xgVBxom%oOWAXJ{@5j$8DCTE=9Pa^7Uh#L0 zzJrGC5N*s6J9XXvBoIofPfGj`0%6eChJcVILj6F&hz8z9%lMiWZ0jxI2oQ70N3eOL zG zjo~+Qd1yE>@vo89ie%|6N%EC{7eh(qmvxU$*w?4MsugofjuxQC=ir&I*aCx!Bd=L%#7 z>s=sVa1{6a=I$On`Y@f~U+UOE%Soh!^K#yoNDy=#Yu z-KHqX340WS&tGnji0TXMp!zf{_kvu{(^|pXS(JQ`uY}8n7Ut``qnD&y?}d%G=-8R? zf=&u?Nj(Vnl46c(rY0pDeS@e3E&8NKEzfx8v)1TgwA{>3^&c#(+ zP!^W;*}s=6R#vY%8cS4EYVCcYPbf*~vH5UG(8tB=2Ok@nAAWOLyD2?`S77pYBGu{r z>U+*zJnSH}pm#MkldIlub8X;WpsQu6?XIa8^pweyrX8T&D{(xl%yd3#e1F7(i2v-2 zjAcntM()#bwa8NpSt%m9rQX$4{yqz{)Q%sq;I!jfe{3p)voTxwIrlqw-G69%XXQ&g z%dA%A8vbu~g!JOMVohpRQ!|;R__MfMc$D{Jf!2%)dlW? zV!zqF00Zijx{{L5 zI^E2X74MTU$IYFQpi0Ea&PL$FFs+%K8@~Ua(JQy0;?6DHhbV~hvY{$h#0=UITE+7o z4%~kMds%mZ9zUQJ-K#-CW1pxs;x=Rq16hV{_1d)&u5Gm=9RFQ5FR2u2-P6=sA z>5^`~bM5DS#`nJe-1{DT@4?2k=De;mj^lTXUi_$=(cid*Mg8H(?Ln*VBlOA6E%qod z>*#=Fc}-Fy_}5?o&$}EIRqsCmkF4~#yX3De9tbIHFYV3Hi9S~_F(bb6jQ$S?OK!!T zubM|n^m8on7jnMG9Kw|}p>Bx$Z|hUUhR_4QbGpN&j<4vs^4O>HG&y)rng~BwuHcj? zKnd&AWV{fZ*tqtq@Spwe+Pz!2em-1R+eJs;)I19b?Rc@u8(U$nX!@k+J_m{P#vn7* z!p7X)K5A937veND%bxw^Ioep`2^uJmdi9& zR^eL*wO6F3eB1u!3Xa2pj{fF!S&fCN{feGBrY`RZP7i3US~p}<+o0edl{JmV|JqLG z2yX*PdWK9<#->>UO%~r$+tB>wSq2RGocW9NJ6l(Urb{f9#z#20F7e2Vq=)~8Ha0*1 z3w8iuuu*rrfL15QTH8duokrqZMIGgpFmjfgifk%Ka&~U;ZH?NZOboRF?Z(Jpu578w z#MCk7EW!W#equkF;ly?eDZY$^)OllCDoQ0I8|Jak@3kJANz6pmRp&(R)iF%7JY#5q zKZ}93(XF|u2F)~yciSzBxx@z>zt5q@i%)OU;G;^yVNOIa=Tqi@+!K?760j;Qz7trTW# zmT?Vq&7*gnS3()TE!3g-$4f~{ME?8i@y6aD-*K&Q&ijits29FQ#(9R+NiyLbS`O^z zU|OWYx3kL?K^%d$#Z=KzQTT_2tKO90mS7fV9)oeE!K44YS72~F6|#J3zGJ5f5<_X?!h7P613RE||~ym+O)YLgJs zh+E;f@`$ZUt*2T(p)d+<%EfHpP1?bj#(^r)Wm@!idkLEd=muu~vOJzxODXxyY5eKq zM~}zm5+~X=%P;t2)5d_N7!Vf5Xl%jFNMIhk);4JST`lZNtrVF#d#M5k&D>Bx%{1pf z?0v?p+@3X4Ntb<2Q1S0?DjHC!jA5KU*q?h+MAdryC~m!oJB@9>GI7@9s+qkF-^D{p z#-h<00oHK*1eM{rO`DJcKaJvV0mDrieItAFl&M69v8(*7!m83NnlkwDTq5IXMwc9v zSjn-=6K=YRI18#hw-VzReu-74nwc8Qq4Mpe94+-;i0QW7j}DPAR-qt2bLC3?oI7W7 zS)VFL-X42X;K_5u1mC?AF-9wN$AXD($Nr`pmfMHyB8uj6JGP!gxlgfyUu$Yq_W`VO zyjMH2?as5tQ=h(DH39LaKY(!8VSEQvn3kQ+BjwM_bweSBF=^eg3@wj_EXKFh7vPQg z49m+OvMD^}m6ca3H+Wt9O!@oKPJ{>PcSJ=*_E^cLKc~P-F>_#VSPjkndY0Y%J8HTwdTqQq zy?OPG4vo)mLdV{!Rm|>9o5a{VliJ9M_p~qm%(@=NNN~iV2a^dgV!Y9!lI9%71PeI5 zf6r|XO4WJEbf1k7AcuGXSPBlmq%cO1sz8ye@7Zjh53CAy<>I>>GK^d*y4BW*)g^;H z$D8CXJQ<}Iw4Uh+`H8IIdv!`OF8s0kJp}bOsRad}IyyS)1?PSmPSViC4AF1eU!PR& zBILikkb!Hz`}f`p`~|XIsW)=;=b9g|A{d*#9n+Oy+0p*xrYKWo9e*XLsiItpTda`0 z$XEp?jNguB9oq60k_pCocb1RsgYBo>XI|Tz1ivS84oQ3<_L?q}`YOxd^DpYpIlj%L z#vi{K-~6Ctc;hsKu3ykUIqPlym_pvL#?z-Ca({Y_HR!Gc5`MqM-e9~|_WV_nvp6${ zy8qDh^u)-Ah|5HN2D>5TzgBM=-g&x$JLXu8=j>NhK-RiO7thyktI}InkW8iiG@);D zv!I$fN7uX2b31PUQ-acu;(q*ml+S>eq~xE!Emy6B2>_aLg@R)D>3k0`Q1YIY*%%sw z{Mb!P>-Sb*&x+h7deM1)h}fo9RqaJP>oxQaObtPgrVpBp!6h0#lgG`it*`7S8@W&7 z0rbYe2Z*9TfE$^NnLp9gWI5aJygdXEl^)stT@x!s?Ov#E;+`^mZf#Yi11{7C?TpMVzS(+&ux_17x=9p0ZGy;>}Tyi~OM#1)KU zPuAIE+!W#I1qgYI1W_nZ~zB*w)z z*XO%;KMjbPxtYy!Iugcx|%hZ7rPj7hs6$K(dK7z zcz;;bt%jr9)T!DX7+plM?PB*g;YjQYP-&C>UoC)vsi}s3y1<3_x$3UMYP-0;iauwM zZcAYFmG2QN?+f*Kc))!{O&r{~CcN44<4j;na^dw!3I)P*IeLKqLgx0qT~o`kMx8hl zwhcBz9Uay$deMQ(Nn)iK0Sn6W^Ycl;M|};T@BzE}%Z08OVKFhd7`!AEvW9+w-T|ap z(c(_q261+y)09tJsu@cMsl({g7aR*4%2=~EfxQ+U-rmu1?7rV4o|}2+VlK(=bnnJJuqetHR4V-0b@^cfv7HPH_7&2n z##1xgb(5u2jKiJIo`kxT|D0;|Yv$um#21}<%2%Bvr#2UZK*$MT3E|U2pSRy*A11$C z$KrBlOkTYf;T0I>0DesK+`s0(xH-RZ(wwnVKQp);AM z<~lyE?(GAM*KTlQ8P4X{D>**y>;EdV9Krf{zC-QFSC3x?Njxi*lUO*zcn9~Dzl;Ah zDKcFjcY{b74R;Dbe!Mf~8G9g3ip`zqU>deOn|sl)trC)ySXWE-^G&*GA3u5We0zI)rTak!IfzPkJ9~QzeR||?0#dk$TTH} zN`J)hG$2voyqO)O=P%Ye`N6TL+WS^Wb?e6X<%{dO%v(0|joQ>jq)M^tH<%l`{d24b zZH3Nz3)5;T>-H|WDG-KXCO3XQN)o+m^tkcG*#(nF%-PZ_7vD)Q6cVk(8m+X=dKHi2 zC4RdR5A{54s0=kx=RHb!_4y-ujP1-gvgr=Yq{*YKYu6gc2QZopculq4?oq$+_RF;@ zEw;x^P`TOrPpwavSoaU1?gYM~i_#$G4a2&5T+eoQES4>VKJvEaz5ahkT%W0~TXccMdUhB37Hi+*KF?U zJCT(_mcHV*7o)@dBh`c6n!8l~g5K+cC*1{V)Y!LsU)ngT;>4|c0`~Ds#7l3mJREG1 zzIgN_S=8|oSL;BExYOn1*qU3mzvP*>=4R`XXmHQhMAXg_KdeLzUovNqJEGHZ9|&QI z9q6bs5Y*_f6JSumui2xB;}x{LgwwuRdjSyTY~zRN{k)bRw4OijZEI_@`P^=t`6;ne zdIW43Y}cUOed-k(8;g2XPVW2)#KA+r@gzT6w|3vT4}r#l{X6B&?=b2_wdrmShi&P?B+{^L z^!bR0n1fkcKUr*hANeeu*W8s>6mo^@O5bnYyE+Aufr4wZ+m6^%4rBTZC9c}7jASOY z!u@IwX{xLsXaz37b4TA)Fu`^2f8tXzBZ52(>y-)4Zn8Tw|KAaQu^?sPKk= z_Ognlf?`iv-Vzcq3FBGbve~Pf4kfF>o8Hg&v+BbbzJ!XZ!3hjSB(%jnxv*Mp{j@$<)UEAM&vAx3*k;x%VEy+Kb`~2Zi-_uAVHG95^n?n0b7)Vjj zdG1_5UpZ{X|Fa&b`%>c|7k{W3Po3O}1WR=@?s_%$*pXtH*~Q9;SJc zlNpko&Y5^oiP2MdyM~5Q9E-B(B;0gBA>m_nrjq*0D!K@s5Fex4?k8O2bXnE?CwtSY zmoIJg-S#xy3rB;2?p!$wM1ob5=Dgw6TP-j0d%J;_YWH|%W@ZI$T0E6R@pj;y?km%L zeG@*5^UzDVSy9yox&=Sl5E<{m&-+!?KQ=VrBcQFPA?CU^yI(9AKI$_YJ4I$TIYUd7 zkKHIp1^*&u^ZKe9SuRLR3hjo?%&qmynw% z*1vzGH=4Y;FB3N^;qM!CpO;$Q>izvrxO>ksxr}H|v8R&^NHYE1CVX%%f}dS1A*|jY z88EF~0KOO1;iS9@J~AC(BU&otfkrU1xH!V3#x@}~E^e8anAnmV5ohS_THH}an4&tD zovRsCR8&|6<1DQ#EdhI|e9!*7eZq8_C0!rGMpz^>G?DSc4P5ov<5HmUdy z5e}vU;1=~|WKiR#{9uE)3z|Vjz%q#`d10<57i8m3T($nVTD(XS1 zySR{;SR5e&JeSFSvk%XJ@Bu0-u?|3gq$mY)=H!Zs zSP}Sh{sk9`sC>KTlP7%r0|Q6!!4VZ`zmDg76?z8*+{3FJ;q6N?F)si1 zRr1T1zvxX#m7vdI1_|dcd5<}k!9P6)(el3&^>68&=+(H!Xgqt?@uEPR6~v#7z#koy zsAhbUt^KRWun}hpVob`q6D2AS6qUWM7qG_IDA-e?4>6*z5$P$KQ|IB9PnUj@#dr6S zuh5N|RjTO^G9c3ePTGrazR#0BvtO5*vHGy)jxj?yJC_}{Zhm0&FYMi${_ts@Hr3vO zKrZ=3W`y3u1$9a+ZT;K%p#fRFs_=Vr%mr1U^9y3>bJEc3D4XGs+Fp_wVfe33tG&sJ z`#19mgRcD9Fzcz#ryurki2A2%;OHzT@GyV>EBz;|Zgbotwo{_iZW|{x3X?YsbGGhU zTJRT>lGMlQqRAq`tW+M9 zKXCq*KYG0IP(5-St2*Pr;eDWj%u}|!k*v$X2A6)mfy_AW8Q1}i!X);!)c^$O&vS9q z>z?~iMP-B1VfWWP#{2qCf3LW&?gw7EC5rtOjE9*U;Nr=`@_@(UBj`!%(b%JEbRih# ze%g31{n0Ngan@2Cr0wsUW4>PTxk6A>f2cQD+Fd|1<9EQ{)Co3$SB1aZ;T_PMdVgY> zk4NZ>0?^$c;fkLFI^=wsxC?qvK}LN?cNsJBzq@)j-vQ zhYw>qqi&OQbakygj(3=8@cju#{g)5TvkbM5RT4y-UBLR)5)lzmEJ0;2I#~ru&trH% zACFyUax@0UZZ3Q%juW>24O%>R<>WBW01VxOz7tP014q~uG?TToI21~kwu%bT-!qN= zI{=Ae8>?{0`UWpOGX3cu!;d6hBL!>(EDtr$ zpAHnwa6wT$@%2>gP;Pw6m6eeYgDQCXwO^vNIukX&g3kIn zvxa}PY~D=q#gtBd>AE%Qp@;k&CGqMZR8UK8nY|51&raq$SRKe~s`t4V61J8|djokM z!R*2mJD;jf4tbB0Pv?;nuz8fPy@px0D92llV!{B0?u6B=BwZvIImb89@ISkToFmf@ z5j~CE7Ssr)G*Qq=eF>^33VnqW>(E@#$51l0#D2AD!mhk@0hLDDw&V2t1?s34X<;xg z;S-iVlnq*v@}a!wt}uzukqp}Hu&3h^BZx?G93C-PG`N9%!%$`#14|6o(PhF|aAu%0 z>C!t%ljwi#e^s|+PH{0MTRd6?V}5Cm210kiRy`5m7f6{L_SY`=BYqMOFUHLWq|{uf zxK~F%GKS679Joj{hqu+AIR;W<043k$+@H=)BSH1TAmj@G3E7Hs4&0oc@l6}WNotE$8kv$C?@qpS1$d>%_Z zJ^DF7sP;gt$D3H-${&IeDcAYkJNphVedq;;(Prmv1D-BGv;73&b{60ij=(qJ1ukh} zDM-+($MK#y1~`Z1Aw|>jt_TV2*YK5 z0j_U5w0}vW=owcrFz4Toh9rqQJ;Fo4G?Py=8U-I!-|8MkQ1hMcB&pis)Ko7t@m3`2 z%a?p7cy#0oh~!86dC+!5-PP6A7!d4*`}_J9S1+)tCQjtMS9W%; z*vcvWvz@?i_8Dy#%Avc|3K?yN>MAOiHo-4-DF94P_6|Y$+dX2N?|^X~1Qzlkamz9O zbcM7O7<}$|$e)G<1rg?DX1+K%J~pS~)@36hAn4bGbC_vxL)bx9c0goEY zV6&k#!h^};>x>fs`h1#Z&*^yAOdp7XQ(E#^_n5G^#647zDr|%6ekIu~aL@$f zMQ}xwX#;M-#c*2IhGv2+{#Re)S6;FuiU8(vmVnxT(Q7S(cK!L?*Pq9R#ka(ltXH;7 zVlx;mO)%kOHEg}G-mi_IFBi*acEz?uQK#+BFP{>4U?Bwv0YZnep^@f8R1rRuQspl} zY)W2N{w*eifm4R)WNmE@^$?LB9@2P)T;NXAYv;bhyTR?f*s7bDzYZ|NH*m{luhHmde3~&Hy8ksIV@7E&Mt@aFJ(;wPpsD}EL)&|G z^jlQN2P2foo7gwg?K?g<^A?Zy+)@T_T^mxIX|P?c{KuqTx}>gYP_TEqx*snm^FTl+ zFqP>axpwy1&58y-ZLGl5WGk&?@tfqDPwdoUlKlOCuJX{F{KlJP74YoYNQ!JT#BCfu z;VyIG#7G*J!1JCKR-z>yq$*7A62|-+LuC5K?qp4F&ZaIw6#KL+hV;e_5Bk~YMN{`` zqTYGprlC<9n>RRoa~vGA{?;kx!aRxsoN_t+DUQ_&zLBE>Q2yUHGH5%XI(h?vGez;# z%|^5%o+@%$g_STku7US%8n`BeX{o7S0IeerhU5gvwZ!+wX71^a?k7RU#172sg0i(X z(O2ReWax}+HxS;o&tm!f@nf=*qM};H*RKH(6|scQ^l1dIqf2opn3br|5aVs|)@83A zk3gBR3QES-pwLh)29Y;k^V9xTYGvizS5(C7Zfhg0+3kP$r}FLk&oL|XY2yVJ?Ac|P*;lEcOEaP0(eSr#wQVHn^UpX`RlA!FUuIvf5Y8-TSZOV7v%gtSfvfVKWu z$#H}7I<2JSx9i44c@`ADma>~@qjttqIJ0`Yx+tv1irO7u{yTYR4AAUO>gwv5!NI|x z->DNFZUK}KdWdoU5eC2&Qu`xD{lLE%W7*0aGG76#vN%!(wnfXDo?PAX1{C7%?!J!B zG>HPv%drK2tcoBe+}lH7w_dHNZg``l6wJ!Xny~`>3$Np2=LIxCcRA^N_nZEd7|bv1 z&c~LwQ328v)~W5V*>BR?*OB!ItY`;+NGlHJeqG zlpe!dtGjtf`))2oXa#1e(is(>K79r7@e6MquW z+$Ru+@oef>41kizPvJXlNPxUjfI)Lt0B&QPjvul#blf3j!yk;2Z*|I_uu&8}e}5#e zq)q`%xDyw++Q!S^aOlcC$-aB!wigSC@=IWo-EUh&PMi_F8ud`)ThbhsG5#Su%1S{!|`A zEV6e9c_d1M0S6o;R#Hf&PL^%cl{!G_URc5@&W0d}QavxZ~so%Ir|9bHK25wr_ z1e3bH)kop&XioQUln38#UV;Csg|K;PxAC958?W%FnRfsxT_`=6LuXBbY|U^m5JvdMj-;J+g~4lSoz!KRpICY z6yaY~WA40c0D9OosANhAvYL;8&9Z1F7zdFIs)M5h(%>hwYy^7C4S;f00YN1YNF}`f zI5xXY=p@?#^;2Arr6tpDsD3p7kFt6Eda7o!TMI#u*JDLLs#bUG;dN(+luho3P&HVO z{*-@VjY!|WkN@!7z%L~E+cy54m|zqFO>q~PdvOnsj+TL;@RX5(A(xAd%>d%Ax^uwY zYB#Ls=nFXw`{q!sZwi>sGU z4PZCrIVn4fVE)~oi(&#tu%9~wyha>M*r_hTkGnySiJYFEItPE$EizSqC@bqVi*7#H z+1b$u*&5}wGg$iEfc6CD-=7^QE>O}pF2}&g^DGdXkkUTO;RcL7VEj7!?_CRYZ{t-h z)!pqY95!di4%;mJu7?=!fYklGqsv_y1H{)2%09ndH+jxtT8?|BO5d#{&ci-eBxAl* z;A4;aZq%2O{EO-G5$41UdtS!itxwNl$4VrI+&E;LQyT9G!p-M=9Cv2zTZRPdITIj= z$0{<5+`!OAf>>&h$nSHU$O+2+wz$|&rPa#&Le3A^IWc*t5JG7-1fO&9Hs(jnpsVQp zeX#k0{JXjjjXtuIH6=n^(!o)bK1MCVpZ`f^B>(cP8>I}o_!oq74#U^O%uv+#nc{Gl zbCwtVxl-tC*_lzu+h~FF86*7TQWPGlGj-=HMY^!7eq)Hjk9#j`h$4<2ebF`d$t<^) z8Ey^=t24!SZ4H_sXH|G;M4y@acV_pG_!qq%uhg2j_e1!BIQjC=Y$o|hPX?H_?s)ZB zc+t3pOn=gCKtf3-ns`_Pd36I&gBk|GhA(5BjkDgfUI_m&t0L_|er}0k^1k z-^9ecrHpV6`R3}9_;8haJ;n4%@#LBzL#-TrRsta02<=0(g@Wm?Ub7n_4CYr-1T6ML zdaENk=v=A>G86)9LBY*-V5s|wCWLP9@BeOYY8nX+jum(M*#eAjriceLV3?XmBf)Y8 zmcPSeb`1g6chf=vd!Q^7au$HA*#r!G)eHer25-O>iFJ2~U~~iOvJ*Vo+>}9L*kS>9 zndQJtuWWk(#pGjvO$PQt8s&kVx{gjKf`}$qLH%E1CXzO=%!Ytfn&`=sCui{I*nt~y zT$dT$5@g_`L3??5uW}(jco8y>B!1^J5c1aIYZP!`C0X*(j>gr@Vtl__uSsxO44zZ-<=jRV} zi~|_~+vBgBkwq0;P+G5Ez4F%O-Ylw_+uY2f`fwM=SGHce#?@&WCI=R;%Sm>9iYer+ zhd)f)&>Gw?S|)kr|AHAkXnGuKF2n~wi;X}n$LLh3qrC&qp?i6U+%g`gvEz)KT|t~0TJ z^ThXKW8GXS?rh_A-{`9gev6xU&5zyT30^2W69K**GL>@wD^HAaThzk!YG!)>2P7$v z)yFJc$aH)}YV1fiuZE4*6#D1*J%?wuX3l@#fh$KVb@#z_j-8j^D_FhT2VLGuddvG; zmrY=I3>A88y-*!5zs0fxu{qC#?^k&1-|=r<4n zZ$WCw?}>lqD}h6k($H=@o6Fe2z_S z6tZbTFM7%ODkN&Q_nEqg?OG`=3KEuG9`f0iH#WJ$24l_dHM%FU8J$u2bW}oW*A)Gi zkMKU~KKd_2V_WA%rfk;rx07^Ru3PtF-J2Gc(a94?U5O=1e?qJ7oR0s%Y3f--xDR11 z9{sub{;ikyWxf`><=C~hcz+6$gZWY&O-juWISP>#j6a>mJDtygP%O3GyNcsEvx|5BqEiV!oY#-i^ zMVn)tFbroS9>Nh3m;r~T#j+2#S4H5Doi7w*rYaWBhKk@RK3`+^sF_s1~m=;}3kC zFA6*i;U>{`C-eQeuaodHrL!($oF4N56R864qY#R7mGdn}T3z`@W+$@L8*&;CB6;q7 zL=gDNW%tXU4FrdUU73lBk1csLv-t390P&mU!JZGDH)bzP<+*SP!h&}>lLgE_sV8{C zZ(x&sO8qtVj{qB^C&}#DEL6xo>>C;igD_t2a99#h&=q~=IeyM#rPgY0^*C+*&Gn94 z{*(%}OKB;NWQp}(>u)vD=+}#H`P^Y!2~u}ke`U!OTra!#z6u~p(l zZd?0^{5Nktv&%mC_|v_?m^bhApR*A+1k~BgEKzgEpAQe^%M9dJNxL+=BYhMd^0Sq4 zx7fHFuQimVkrDW|!1PEjPRjkgwz+xcyLvC|A~f5tB4^DoOY!NGC&NaMwVa%eKK`aC z#i545NGABB3D(vZS60SY?Lh}Zxu?bGCalg8Vecy|L;m6JWUiyUJT@T29(k}7)~wD| zOOR-l;&{SR;od1O0*a&(i~hbo>4Sg&mRTK%D%z`MhGadIX+6M(2aU9a zXW<+>g~aE}ECsdF`tw_zvQflG(P{X!@^U-__#$Hpi1f8^)H`L`$btj?@$r2jY=Q%y zKYW~Xm*JRf^_}zDvt7OCOzWc_kb@wC9#s&}aKob&N8-Oia`yw*%v484n(v|ckmYqg zUN1McOb-hw%p+XS{sE642LeNMf`qiR!~=tZ52;D0i)BLW1QtJPMfw^2Z518zER@f; zCFAhUPAA+&EHQaalnAiTW3HBD*M|>mgWo2c|a91yfH%II0&e+l6` z&DaP-*efDp;&sY8C|?^Pw{CiskZ3}B)HuDVVeu+s*QybZQi7;vvE8Cd zyo8IEL7oK$GQYT381aB50glX#s+}H69ZP5rO$y&Wg304C%#XaTZpK-S9uxR_nQ)Q! zU8RtpDH*rYn0h;Ix$;EcDP5A8nfWIil;NL0&r*<){pu^OE}p1|#GbYHZfN7g3~Tdu z%sWz7w+;8HipMV=mR;`JjuDtQ3Kf(kVx6Bjto+z$`;PsdPFwLCI(7?H$(R`lOq2>r zPLdn_&?`{tpb!d=^Nc=`CXR6U8+Z}}aa$xvq3n%!W-^Ccs=<9iKOaqxU1Qq3mwZZh ztWoWjRftC$=x2Ee5BX^E_b_K$=zpe&G)u}7d8Gqvv@Mmvt-4d?+TvFK0{+l3jFw;% zrw>=IM-6cpW;~k_6C=cyn())hTl1Bk(92J|?k7YFLmaf2bxmjI=X`P*h_gpsa_wx^D_M#*hGCuN4jz96v z#s3JaJ?<@@k(6!)BN8eoc3%|J(+k-@qE-)uanKGdCBjev%Je13M~Qp9BI=r|k|5n*d?VS&4* zB?SCrt=qS6>%oX&6(nVqi@1!gYL==}utftg&@#}U#DRD!(F=S>=|4IlyY z918hsFpxt>Q1rlMJ#!lfOFC$3J`Yfl+F>?w6M|GrAHooUeRa$Pwu_gMXdXkae(2>k zhO3IJr1kVB1IlP}wF_kb0h}fl7)>K_f|j4Fwi*aS_IJ~MagupJCkQd|Ulebw?CQc` zk^s~L?@EqYZ{F;LfB~kFVvDGG5W8e;K6^U@WVz2k96Vtrv#R_1rW;m|15l^ietl$C z%18@8r^0!Ug9L%hN^3p?^z(^lgjG#@xPL8~*-p{Fe9#8Jd3&~GJ^k84na#iYj@g&T zIIyjJPTAR#^)*Qx6Hh*dme<-y6}7xAOgd@UxZ3{@ZP4Tq&372c#^kAul6;M%Am?}n z93I06-P_Ya^gl%qr=jk{&3}JM?z@_3xQBgy2cNIKQA6@wu0)I_#xf7F?9m|x~Qm02W5l(EVJ& zc&uwSEWgA_ewe7&^uB=M41WdP@{)KOxKb5JQBw@%?YVq;vgT3GlkeaZe&4_Urz$DK z{({HxRObIXFVmJ=G2Yr~^xXr5IX=EIa;%@O-?|JDPzA^-%oPkZy z!0=^qa=F|3RcrthdpiOx3893zI1$2h`GZoHR!-(rl~ds`>}MFKmzT}*1DgPi84SJq z?eCykX&w3l&6lN#NyZj5UU@EXstF1UYq!2A=z^j3>pbdSlfv%JsvQ+bv%l4fPOI*O zbqjzl^VUs2Jy%z+KLx6$E?V#gKwh?jjj4P?xpklhHv9VeP5_VVBRYcq%D^{O>rM}? ztf4_DKcN`3j57u$@s&@XK4E6+p{HL)cVbKc)2UngzPc3#<~K|A<)Cy?i9Cg}_!J!< zn)|#~|LmalqB^nOAbQVPqS$Iuv==H0O{H%G-5_pxmXKo$>t-i-BqcpPJ;%_mA4=Pc zhvEIuLt&o}ywIf5f9s=supYCJ1iYag(1#I^Zd)O%32iq(vMs{zDOL@y#ve2Z zkqcBcP>+v+9D2qUf~U!lY@O2F3@IaY0|_P8D_3+yQdTCc`R-j=B-{@puS-TFJ3Z6> zZEf*n>s6K#@Qa({c=pKNjeFYoK%^`0s`Ny~2&onZJM` zex%L`prWM@0Yrpbpv_sR@@0x(0jtrU&1ql1`oPlh0Bd8cIBVjWxe?4sd*HV% zAqj8iU)?)aaf2z~(SOmlN$+Mq_(`44kZ@@Y1f=(>Vkk*fPT^&4pW|kNT2Czn!vAwXs=LedAsG$1sr4twvNCX9 zUan&Qg&)lc!9lTQrS0U$=_nrKIkZ31aMu7thFEopUQKbR*SK4v9!Yc}>`<^%TeLkE zwTZU3iP^s=WU;Go`f?aMo-MzcRqS>HeQ!5m^Nr`sr(pz2ILUX&+s??^PVh~ajU?h0 zF??82`Wl{t#e#9K9Vm;>s+*tstiQ!U9+y032K~5Mx>;LpuU|QpZLIPuBfnvyrjur) z#0&8Nkr$OM)Wk5JC<`tP*kRC!?fbGxR7iYpdi5zWTkq}F88(GzW##EDbD3{LshZC8 z1Th4Gv=2?BhBYxu>*_z85&0pm?+=rk&vU7X2p&In<^68-_=$T^oyX036PHUX!bUU| zg?xv6CLU6Jmrh0O>UQZShdYdMaeny4DXhk+N4O<=_2>MZ^ zymG~M*}lSQvcf_0s*u%gvBR2x#qU8zcvj*gB3Pou9IbpDE&%kuf}T!1a9KPAV0Zh< z%1Q^i@U8_;=7=4~-qPn`e7*;W_VWyVMMgV{NdvH)tA5Jfn~5u zv@Wcv*y#~VhcP%y^_~L-`fRf>H&2E9_f~y0qkL29;z*SdHfO}}iVY79@uojwCr6+a z8JoBbL0E#XN7Rns5X3=ao^!$d)C0}|z&6)^hgG>eG+Yql_;tL*a%V|25k5>?*rTza z^+O`>wvvP3Q@4YlJBVK7MdK3zJ5JzT?*XC<<-vj^C=B}h`{N;|IUc_FQ2+`r!p9D{ z^_K#If_G5=iF%%cd88EaKuai)I`{xhqZ-lHKvFB&XR98Qj+n(F>nG8=Ow06jwPF3A zx8E3SUXScYAxt*78y6L=3+CRmwUOszCG>M--c0I!1}5%ykHSMp^%et_<+qu;b`wR6 zXY?wWl`0*)g-m$fvC%KsJ%G)@yvsFmU1pe`ky8=+H=# z<_9~LM@vMMGtHWHvaV%f3?YPfA^l_62+ja%2TZ9YwXQq0*Oo&&}1Z6+Xo;f4@|06#fB=!oE3MpwEC`Bi_bV zsB-5#nM-|3_)~6L!<%t<_aR4am(OFcn>2 zf%HWl{rVh27P{^&4i0TloEE{U(K!Y1XmjKc1Zzi$iHVcuzd#fBJx{m%b0t9kZDHS3 zSyPi}b|;1hsF)?3r!eF$edp}Ff{B4qF;unLb}O%{AD!m8opf>9x()?|3Lq{y3rC3{ z3TF~6WG1BKG}VV`PL)M1TBQR3+HJ|hY0OfH16_pnN(I!b@FHk3Ub&JE@2~~Hzg_;q z72=)QyR-Z)NsC*zEdOZmhsG(0JR^r_WY{QTvxgzM^y$L(vP!=}NK@vwCAZQSQnHXncg@h%`!m!p4s znm(&;>z9A3oCso+TJrZ|H`_o>m=$&VIXAk>8i!WX2c&8h6xuW-6 z2jI;`gYfMi!uRVmzp$|V@WBJ&nwpw1IK&^giysV!TZb<9IAJ|SCL1kRQ*bgb%jh|r(!&!Jqxg{uJ@7q>LQ4#t7UP%3dMgPcLX{EhGM z;9%2hIOUx|V#}%=`&GC6&C3By67jzEJ&>*c0DkFxbnyhg7(YIOp7Rz2WD|`PQ+#}@ zEjBHRNwS80dQ5tOsx!jinPZ>cW$k=xA@MN@<4~n=R2;k>Imi3&3SnS}!*>!F75lpE zYKVys0&?RL5F}}dNOf|HDvUl{1OVT4TA!0?R*2zNw*rk3j&TE zJF#^m{Jns(+A=O!4BO`r>7KEE1?hH(z$N<%EDBBh>P#H|5)@rQNnyx^N7MV8TSqC4 zH}%WT4LL+aNVATMeTVN-jFY$nqC>6+g}fIyKx(r4H3n}_Z=uc zdm_E&bHZ*8#l33t$CC!pD5(hi*VUJfdg4*NzE*;19JU=ECkOJ{+SKsupgi!C-EW$C zL&J*$m9iT`N<)Ls9X0-h3d6IH5NOfy@T%Vf;&v7sByS>Cj!*n-2DYJO4nh}_w&=9> zIkd$p+_ygdLy%kNwquxMU6r76n?*GWG-u7UW<>cmG+Sq7(-oYs)#R#RToRSie ztD9x)1b7d;kFz4XE*4hy-DFj#Qy4iLYO0sM)U^(bg~`1_sU~7fG*k+>@$aeYW>?}N z)4cD5Yi5Pt5&bdfnO&GaiIDD*6yI15ohpxXDL}hj^d|~k8VpR;gqW63Zcr;lj{m@_ z#d@tWF=2E9y*31e5WuSf5qe7-d+4&1jizmEN81RND{SoSG+!`1u23Pa2p!_x;emei z;}X0oC^;|qG2dvG`jn_dch?EUTw$|(G}HW5?X}p`K=-Mu#AKy~Y*)#dT6T71ZSQ@> zWj)^Apq8eVHGUaMbm8?ldG|~6M(s^g`#MKa(nzAa6ZmC*yYF8IniPz#N;3p`hF5LO zK4$d~xvi(GuKaE03HQ|yA?B7}-iMo9TMAy!F<>UmJ837n^yQ3&O+k#l@FFK4%g>4% z0iV=sTa{M@&nGMzzAIA`ksY3rGVh074!%P(I6A8K@}*2d1omD8U9^DF>MPSH1s5+0 z36wEOPtG)1@3JXTPrbf-w~*`;!F6rcX+lPp?Sy-dBAC!rJIBDvcL4(GO%FkCGg*7Q za%<6_!TGxmtH{hkBP_?DOp2m{!?qea#UZx?_>f?wFF%Amo#lek^cTRgMYgt7JswJN z9X)krTDA=OPORO5qI0HsH!uCoW>Vzd8*t5lRFP=|h;$$?<%2=puRoG{xLEHBL9% zMpu=!&+n5X236lkZ+C4b@>*Ch8d86+H80q|t%#jj=wjVDjhyp=Y(?D>)643wj!O#* z-n*QVf!qrQH=Kozsn>$;s)Lo4_hB5naNN_ZTU#DID~Ua*%%LVEl&Nm3=@-i^vhqNz z(kvef-8bmn8L@E2jCPeM%Y6ouD}$|*B;hWTa=9f6>=d3AzdlAB?qO@`MHw5S<3NJ% z+`2w1v-00>>wAor$TQ6H`y=BB5>;5WJ3Mns*LA8r7V)<+^k4;X=)o z1I6hXMq~z|r%u~Ial4|voc@+n*a)lhNw-wqr&{-?SwFBU&Bm@S!TuPDAhP!B_wi}H zaUyaeKpQA#FAS@?Gx?M8lIlbK=w*q46eIK`($L=M7UF@!R1hV}k0c@{81Jwm2TQH# zqy*6GmhutX3ar2VRxD!cCgVRYi@$dvjd!|k)cwBG=nh82B9~Cs5xYlf=E1)1D+Aps z`CUeLs=BvIEb&zt;_=zyqj{3`J@twNin4Fi?s(lj3m#)+Xm{Bb%r;+eZy9S&Kl2m{Y9;sFp4wM*x;s&4IXPTEv!wx-!_qP zn8AQ|fTv@9IKmVIRrZU#K0)-#rch>|B4gQ3GqWcjUA6cSddIJ4VbgcN^%J^CI*N7%0~Tk2zP8X$@RDf6$z~%ylI>J-lJCMmqji zjQHJ_i^r{v@+1jPXOcr>t&;+Gw<~xFB>9Itu_21=DrOe6V1z5u*`02weEOptE1FB_ z^|j+3-na5Unf-B*`0wJLE5G0JCHIiTIz`1`{E9VkV;SaMg37OdCCSp)e&3?pIbAe_&be&IueRl{ff;PUG88>yUx;+rrJH`*H@IP}g<=(e z$<{k7b7AbF27xyQ_x<$vP7>l-$qL*l48G@;8t*?Z!*j6W=6{k~mt88g{Bd~^_s<~v zbaRu3m;=X1eSKZXv%z}@^a|xc;~tBYeQJ{55g0!*M8%FbpFiX>A6z|7Qd>4jH4NyjtL{?@Q9o0d70K0&ekK<-i(_j=^1BpqDtRzu`?~#zp3d5+`ag-&3n@O z$HHa&+@wFcGwRM**C*0l9Y#nMj3ZbIZ2N?`D7t&Oc zk}k%vn6K_Gkrj6_A5wkA@bwoPpBj~=GbKB{$%%bxQiLBAD*gYfd+qm@RfyMk=pQ=QUK-}YRPNvzMPJMp^70ib61J+ zvIbuKoWQ&3HYF?3oa(*Yj4RgH&U}a~>e;ehKK6vaOR+~}eDmmOiZ{mPZ$xEMo;+G0 zswsalR%BMbUqS`=?RO4v2kZC{ASHpk8pv-Xz*l}k3L}}$q*FjZahN~{rV9ZxA2@3qL7Qoe->;lDPM98!3sY1DH9~dex z6GSJp(5>K)AgETF4ROc8A1jD99YQDiAl zXMQ%8P1w+|?$p_Pg#DCkh-!Z>YHt;KH@z>VLNT<%m7OEEqi@30EzDlen5V(`JEpfI zzW9BHcN@i|@7U`vU;4S0{Xy2Lf=UU8wn_ps;804IIyN@B+?8f!LKp5ApOpsr=;D3% zKfDtYR>u3Ps8majY2FJs;}>P6HiP4i?AZ?m`!oh-v8MNRFBW?V z>@mdp@Rb;^X}_0Mvp-2Q#%jKU#ZO#Cgb?#n8`JVM#iJO#rKt%6nqL@!7})mfBHYT5 zVuREa{(n531yq&W7wx}8cPQNok`mHNOQ|TLA|c%%Qj$s?N)QAL5Tq3WrMo*t8tD!R z2?6PT>)ii)Z;b1>V_fliVt;$Dwf3C9S#XYxJVHsMX0}<5BJdrN`lm=0v$P-{LU|R1 ze|qlpOX@D7j(nA8{b&V;i6fLyvvt^3vMbfTN4#Mcb*VWsqgYTV%p6C5v`ZzsS63Y} zZN1(wMR-Q|*3rQPzm^PzY{tFOD6sNG&=UnH#4~Swy?CftdP1w39y8Hsy-^DEQ>4*^ z5T{(Y`qw2))%Kww*D$ur{IqEn+^R%AxI|>Ag{9urA|*4Om1$*x67wVC8m1f3nM1rx zd6E&u{i5c>R{J(v4&=JKx-k1^5)(i&EtxZk`Tc$Gy~FB{OG>2fmymo+B9>~`l%lGPmoZAO}*M$Y4JNSP&?zun5vYn7@yW46V_&u9MomQaH zWlb`dmR3Q}YqIdb9G@zYZ0}$T^DuP>63*O9#!HW!%pEI@Y^T%DM_LxfsE&!F<9zDE zWavolBFyi2*{W5-Lf&gh+OA6zg=2Muk!z(~)RDcJAE1;HHhL4iR4o1s3-TKAGND|# zhdf7lp=Qi}sJE49g~cDyY>x9V3BSRQNn&e zranjzeIe{xJL-=Go&MP5n7s}0%Nho2-e=Q$ae*2I7u6ppVj)r7cTz-F>YvMhx?OX7 zy8XqaTU3EINgTtNn@M}+XSg8YJRq$1LEOnVT;Rc)U2J|NDv4?yA4RzitB81NAtl~n z_hw(p_>NE7y>8bxy(j!$0MTlwOV^2ryNt`g`{d>80&A3BENSlX zmCcEt_1o5{06VL~ub=#%{0z?YBO7*9uKS62sM`eY#1W82=j^#xwp&jWQirnoGCBGx zoai5T|7%Ad#YNq*{5~#3JK2sRxH647>3i-|Nwx3b($M}eFeEkGF zLH^o$Pk-O)E+&l2&dzSU4t#yfE&;k#8#itfRo}LckYf4oI}bd}KN*uTR~>go;_P?m z?;`a@$k{KGDl#A+w+i+-QQkl$cVfMHdBX9#Z2hC-mGa4@z0a(^#ScA4FT|R( z*k16zzP|6SQbY-*J^^(w*~@S27OK5p?Vpa<3a-g&oa)|!2Nb6ijzf3ald>KTf*_E+Z`%IJE6**Tvemn$_eQt2=q=S-9PJ1` zmXn1BpGb)W0c3@SIg@DZ;)#vR^^xvRGv$l^8-|2Qsv_1dQdcxZE?#}fHX&`g@KEUYf?{$q`TRl$ zdh)(I?kkk9&gJ;gvEt-S&_Gb)-u6M)I+^s_CP~>KTUgkRVUrTk~KKUN}?G9=1 zpzji)`nQy(?qurYirLF`k?uKKtDHM!#l`i1H{2C5Cmh!7%S*-ceaTcBL~99C@)Ng) z0;vDU;cBc4zv4ojFxPWnY)J*k@jd)a%Ql^Jl9_WqR~ib$gSDOkG4gkn-Lz*_VWT){ z%EqqM!H!~He;ICx9-qc)&8ZPL)A)+I$f~F?g$Vd1_HQIF@nR~gdYxx(UY@yR z4$Qm?7GW%A^Zo_GQZ$T_hNR_!p;%g$ZKRFd4jLp+_g`^`)u&m4VGC#zr9@n?&}&jYdgVm%`F2;2mjpN2>-!!@TJmrI0=nTAOvZuY>dy znrQ*bqy0IFd8x^B{WB_R^5#-t%SE^M5%Mu8 zyr$Hwe9Dm&q4t zY{aV>>i3b4$SoY(zW>r;kQ+tRwkc3sZ&5=G+m6vYCmHEwI(`m@keNsSlCotl2D zW9!?ZmTg_FC(Va+w6fh@FLUxMDC7oCdMhTJye5jT!yCsLB(O$Sh;@KG<9!~xI z`SX36Gm<7q=cNLl3^+b-y10mfoZe~SCp84?vCo{rz5vUGgkc)hi&aj%HZc)qynf(W zNLSy++*7veoGez8JxwZ($YZfxFd#$KG+@tYGEZ;k8tM?GE!0SEP#@*%@BX6t9sF_!v34!@=F#mniTF$dfBeCU}h?uX=|9-9ZkCw9uM^5pxi^E;LYo!`^w z+1#XIr99`M5Y6Wl&;4=^tHfGZ^za!gUwBLB$fww3NmkuiUD=4nDp<|;KYlgKVn8n>GjdXQtKxb*Dg4+E6GY+qa(3?`gG;v=(IMm?`I8y zpqqU>JF3dc3IZ_!wJOv2|Eni_`fz5-5Lui}{CwSia#-JRj1dZA;5djknKJZi_?tWuz3#jIMMoEsvt?K$=M za#|^qGXk}*LOjYH?qK=ISkU<^X9sP^MBZ&pOJ*%olp zL5bwsb0Hb-T8Z>hbZJvLd0mG~9E{6mfR)5k9^ zuM$eX+YM}UT_Srt@6~LTLNAguSLd%s!-@BgrgE0|U^phTPp6Nps_WD_ja%xVVUXgL zAzI#t@cp+tLeg?(2s71H26_)oqQ>7J-U=_;hon7_VK5-Do}g-B6Dc~sLUs#5TV<1m z=fA9}Hk;+9qIkoA3;RQ$?mS!P52U58G&yZ>R{r%=ATfiCfHg^ZirCDTAtc<@ap`sZ zP7Yde%~htwsy>`5VEWR*_63WSproEZZdJ@sOlt5(PYNH4#mO)BSAkM;GVlyMZMV|; z(Z^1bOex%RZ=vUd+Re3*3weU7#%5!wzf5j-7ZFDei1Ca>>$2txU}}S2Pf#Ed_efTA zsU+V-kzn`wp4(#0T7LO^b@T9!{P4u?6GtY;4FR^R7C&B<6n*VDGct8IuFY-wVLn|X z|1$^aIX)dEy*;m7zbKqcH+tnKIXO#2Kr}uIaUHv{eDy|1h4-=7-p38)`0rURa|Ykt z53TQE%7b{+eUT_p^fU6j7PpfZUq(AtVR3ARDSf|YGT-;m%c+t9FYGuW^ybet#a|yB zd%k)|pnRX{3z5ml5VIy{*LN3{aNDn4a4#nbf8BJ`X*x=&Q!SEiXWyym5)t-8T9i!~ z`s?U3ih9Jf@Y7qpn6T66W2di21jUv)J$veXzE1t796v7Lxm* zM5f-h{Hb6j?1Y%kiRf%sd%V}NgtVlEH_~6O>zV?c7M{Y$m5|>tm!gKziw6>s)@A)d zWw#rwROBhIQMc3cT_RlJIoKzcmAl~O^BcW)dy}k1XeJ{~LDZfpa9;RQ=T9t&r^a=^ zrt&43xPQevs;6#r{;f+9t2ZW=W>0!9IYTG!6wglUAH#+%r+{bZPc`9K&_+Z9x24H# z^Q84sSd{0O>>ByCS8WO?LBcwSUpr$K7j+q2C-D7+Gn3Cl2+05Kv}>HB~tKG2^SS$Nv}@ z8)Mikg*W3^Gvg>}T=K+WWjogStnWjpF`nlKN`l`%KSIT*@om@A%d7Ch9?Qq&zJ{C9 zlHPPfcSC~F9Uh|$6kBxC;(YXxU3XsHaZoX8Tk7eyk-z5PvfSm#cRwLCRk{pcxCWP zD4T|AJvslW$STc>>o>ZB4hkMmM8m4>mC3_!&BgUAMtR1qZ~Ik0WdH~JgVU8OeaSRoYLe6 zvHvRuTuiZTx9T8ml$ChKHh<_uPbvxDe;cba#umLAlr1N&LWMSrZUPoYaaq}M-{cHb zpn>U}(^uvR0?#N$KSuUZZ}^wGj5gMXGyjNW`zdO0XAOo(~E${%sIc z-+6=gXINc5?hWiG4PDNHl$ze@+ZEA^spTzXs%p3hy3m!pRp1*Bl0h!;nY0uyYNhI~ zW~-1{ug=2wpB~yLIW$jlHUjA|i#(~|NzS)#-{@9MNa(fr^jHRe35GJ)H`v}_!2E7E z9p$B#gkndg>P|zUwxCeQ^8uyo#8`xdOXw1(QnO-+wXv|6!;|+*g<9v>N>vris#%e9 zI$hV8@~)Ew40_)4)b2YkZ5~gdAba*571kaYrxx^=j~id5n|ni_gjLVK!)T;$XeKGg zb0z?*cz{rb=#0sa;j%JMpve`AA9?b056Lyo2tQ~s<5zO>ctn`IRlTb?_ai9eE(6)y zH?y`8O_l)_)l998VM2!01Wn3&eI~-YwFTtOkJ8!ff2E@s(i~v+tv^KXRLfp;o}d!> zu!eFEaeYpveCc-c2E|bj9Xqv2@h!wYi}2$U{>~tVSiTjL%wJf)j<^!GO|KBdiIE_- zvye($se1tWja?hlz;qiNTwI0E8ZJbqkT(DJ7RM=r0~>@LgE-l7={+#azU1VPhS9uu z&cQihU0hPq2LZ^mn}=R)frJ;U&vo!Zp5$19+@l`Mk`ZfbYpB(j&5o4f;wUg&zXcp} zIsZ?#2b!AAk9eaKnwyo>^z{=wC-WHJf&gk8#896gtk@amj3s%e09;E4(aJ?iN)xb0 zUlE&dAZbMXMndo$FZhJ~WpO-XJq*3-8s5LN^ks-_nox}q`5MkD$MU>lLba&jGjP&C z)k-JpB}oo$F*@CDeUdRYMng-aG3pl4rU z@hw=`d{gR98Q7Uq5S)OTgCS3yjqf?Q2q7_)O?8q)w&RW!wao5Q7nVx@x;sDANbQH7 z=TW|g3l&{lND|7d2uZ{D8!G(FLO8%F=JV|kb z@!$Mb&#L;XAf;uHDrIhPi`k{^aET-o=-zg^Ch&u-vVtZ_i zb8`bSwTOeSI1Zx?r-QY^z+n$33ky(k@^!F=13jc!em}3!vy_XG%D3mlX*Avh)p8gJ zY+@LgneB3Oa%zMC>^EcOD<}^ZWQL`f z$kxV6)JlPHkph|^qBS=ubKy^Rje&%fn5%Br{N_WD_Vx5hx&I~c+#9vB1-#XHnTgPz zQ_U7AblcV@t0aC$Ya4zC2J%w0_qytLO<_>%Lg@AYw}Fq34PsI6P|gM)AEs$q^3vm_a`~qQn?hap>2dFt3pvh){XW=_6_rM zTB=pQ{zUmhas)B#y3HN;+;1mMQEb3AxC^V;&D(0?KyRX({C30b^8S~&h=y4<;lau0 zqGiXgXSbG~TY7M&bKtWmAt}FJsIyVL-KK*cTv_qg&OL7yGrA$av0rawS)sVzN2JHp zWX!}Q?~Jh8-s_rG$;Hnn~Ib{o@VInOQ1H&(fQ zD!11lQ?e|O=q7WCri=XXRK?bbg2`=Fmlpu>-z;Mr%WHN5i+rh;7QGde?GYd5NL z3wy?I*a+#~SUVo(qfN~iiqOc@5M_J6556u8of)!O(`jC zzv9GfCzSf)U&Dgrln@vHcXqnrtF8V?xTS|xtWgjZ+~kMRWfxE>Uq3spJ0H)HclY#^ zs)4ljudw6d?dr#T_;B$b;JHPff~qze6shFj&blgHSLcBL(gNyl{Ym&6#*VgG2>!mI zyVh9!eBtLJ04;bR;r`c*>*~;9p%>Q<8TO13;uDrTjv$VwcKO%`f`~{1(QXXB^>l;r z(!MYlhZ2`ovtnwUtG`6Z-CuHE%Ff1~oM!cNG)t`}(UteT?pl*nJRL)Xe;?YVz+ zX<>J=5wO2sS!28KMceP*FC7IYk`IN0nT3i8 zQod7Tw_0;wPB%OF_By1_?kdg&-#hjf@UXNCrgc0hU-@H=4ES|@c*I2J@tTmr(jtJ6 zl=17km#vT2kJ}k)X0a8z^DB4=FzG zgT+MSr-QE{jW@x4&7qnYQIE(Kfexhn5xs)N|z(o2_?wa*ViWi zZ7q8qt8?|^)VZI%V`x}d5QsES_V)J91~=LC-M#*`b2S_u9=-?8NsTLvZ|vXcV`5V$ z!2S^cT)_F)TuI;RK)mx9j>wP6$$}n#(qg_46A^Jlf-F1VX}*;npax6s93wy?IRxkf z6`=b*97Zb4`JOHLGGG`czOzBJrU2N~ya>@p@tu|JrPkeaX%UV@IsR0P?~G`>vm?`smM_2l>3}>*KJ`xNWwP z?gBk9f2B~krH!r3Ahq~`ab%(N$;^Rm{RC~^)~&p2ySS4vsltlK5vQbL&ej#HAU{xe^=$FU<1QKk&B z-QygNhV1(~_h3Nytn@s3qv}hA=gkLew6lJs4GJ39L`&7ubf$;OUL-%UuoCMk*azfjLL?N`iRvBck&Q;W5jyfxeZLF@y}%qfz3*&<)7Yh~LzKUH z{^}*w)-vncq7Y+9bo^_sC%>CM~O1dAa`l%1dP`T~bnEcxI<1Qrh z+f^tT_!GXnc(PI}uZ!-;F}P;T_bLxPbAuaS!B2~H^#5rAFjIrofU|D>?!O+{e>dbY zXIV;t6qBTv^6N6P=ozo@s&Ou5lyiUMR@L>Ucl1k!+KDp(l~^+q;xmof=&4|~oLgoN z%K|>w1Ig}s-iGx}gp_>szEm77Ps8yp%NZbd2Gb5cFXA)h$c7gEERr3^+YY!U<91__ ztFvtYlob7nk37ep6@Mw!36JZ@`Bt0lpQ(T!98P-YbA=m0(;EUcZO_iL4breAY{ep^ z@+IZn93t+^T&5$-cbj`y!+MuT6g(twv|omvwi44C+ieNzG!ephfK+WwV9&}NJ-6*S zSt_T)L>9G6aol4|A~c3gd%Qpr&YenA7Kmr!X3EssuB5R!(s3_%wDrkhOtDMo>CjMp z_6a>tp4wXEJO9@g71JCPUA<-E;xa!=rz?SDqWFnjz1e>A!P=Hiu{mYICKp9DblY#? zJ1-o42GZ0b-~+m6E&ZC9=)_o{6u{Ks_35r9AOMmq!HdCSn=mjq=#*<%^HU_gOBB(s zbh*t2V3_+#&|wTg#V>*+NV%)`PEDz2q@{hLA_~fZhM^3U>$=|FG7=&pzw+JI$LuMS zadC0|PmlN2z<#TGm1Z1+k~9LHEm*A%s+VDil>p0G{mH|Jjb-EOnm{hF0q@E>6yPW& z-ra6MKOTS|@&h=yB9tx{0NG{L0Z0k_F&(aq$t|Xzp)|jOg9caV3QuSw2);NVNrNW7 z%W?%`F!}_6q%*l&{TT4Cz^>e|;OFO00HfD7h|~u!UAkoN`Y!6um5guSLTIU|%vnV& z-xR>ZbOr`Xe=wEcm==u4IxpT`&(uJqGO_Y9t?Qn&`ya0JIcV?!XnM6Bvg}^`Vsu)!%s^{FvQl)NLINio58t1v9A3i zBR@uKy*)KRJ1xk~{i760VK;|d>=!Ry+^jLYAI>5(M#aSRtjci~%NJ5Ugwr0jf4bqC zX%EoH$*CTAzk$F%ix!oTa0ZBlH|V7*!NhIjeL4hR(`#SQAUeSc&<0!;$dEsR*TA;z z4gIfG@;@LG=Kyf#JK$Ydj^vx9gW^7mUsQC!)8J~%I+Wo`AbXdVO?DuM^%21+(Jch* z$eIk2bD&gaz{#Rr>NKx{ONcCsY&UfOI>k1atCM(&(m|ScoRcpj(?Cm0p<0tp)_YCH z>P04xHDiWIz0CHctq(?6uo;^*RtoKJx7Ds0tGxv{jxXVDrWMNaf+`pHrESLtlIg8? zT^*WZknJ=4gGB|mQA@nN6H1-3@tXB;e_KS}9Iw8-M|qb7;eH%_#EfiOY{ew@@Mtuj zC1Y;JCLQq*X>wz&Hs__pi39* zm4m?W|4d8DI)c!DhBq+c8=9?{?qufSrp4ssMQMxkD$}R)3fhAHrG_|)VI;GC^Aw43 z5wTbPgsAl(T@#X{?csSRq^)20yr&Fr_{!egsBy1vHM1SA*L+Aa-}2vp!P`*wsu+s% zvM|X()60<4R29Dq`s3E8#Q$Il;K=e3>2MID3Noi;{cehSsGJ>re!xaKw)*sehDOA@ z_d+B^PR2aXf-1GJox^E9GLSNfpYP8-Ghann3W%pqgRF}0|dj@Q2r#!-NLZT3ZNz) zf`Ya}`Ia|yXqS4Vx9?UvAA-q5-O=D2oFwA*Q`HrC$X_5J27*W8j<~~=z8jbvx1eie zPgwH5?!5Rd5keHGsV6X&S3oQKIA-xA1L1t6($)459=i#w3(y#z!SSbp(K^3VNiB%) zKRlj3pW2%X6C64N{{PdJ3WF3FP*?&dk8JgTwH!xPz5%8&TOzi3(g6LYW7WS6+;Qw*=+<+D| zO6F)ewW$?0xffe4w5!88dNDBW99#D{1uWzWz)_<*%nQ-#wcy*Z32B2*5v60vOM+34^-wEIl90^NH5f)#br>kM7h$D#}}EFxnGW z!KM}mA1DUnkf&EBa7|F~et%IUfWjtYjC^!upa1@0k0J!~?@5|kOnOvIOqBr}CPJYR zLR~bIz4vr2!0r~G;voF#8z69{OaN0qxq^EN^37s9KvJBoQ2_sAN341|RFt19g9p>vdUyP?%m_T=`fUl1 zlazJ!beI19i&{wG5lk~ynI`=0OA_TCMa(Tlq<=(n%jm`dcFoX;oqTEskI2*PHp>U^ zxo^FAXx;hD%lvg^bKc+au60R`(JPa8L*mdly8e;;m;tI|(QNgn9>mc$()HS=;QIqL z#E9f~%2EB@d=z1=q+k7)SOXKJb9LnYEmgVW`XN)81r0Nj&4dTEe0%Jg+_NA=^)Vv6 z)whc!f}>^k!Rl#cn<*0NjIJj4D>U1D5)#jjJfua;w6L3&P(C5+xufUm(iKS5zw(j1 ziZ?P+F)4*`@16W$j=S@9a=_v1?RVdQ?D+h;9#Sm9sNt;}6vvnIt#W`UtdArq8+G#b z&JPjZ2J)Ohp<*Vgbx-wTiS`FC1gQ99Mk^g{&-U&srF|vql`20IGOQpu{gkwwa@NG! zx8Kv6JJ_hBIl!~W2-3tqPd^R6r@7J+`@`7;KQt7+@KhEElrf5&O8<`j*KJ|k~#`I-Fsf&zO%3gNo7 zy^a6F7nH8S_ySpS6rIs_jyj*tAa;DNX2s>hsx)^WKfz&E8y)yldK zJ<=^RKv7z`IfFGmUIRn2Q%V4IgbT1n%hZ8nGVdrkLuCh&3rVPs)v|JO7D!oTCxGL= z^0ByB)C?*acUaq(z=f9j4D4d;a6}4ZeEk{=X$D1>_Zopqxd3&-9(YD2zyrK`ohf1- z5U1~Z5w zLctfe1<#iXla$-qo%^4s+7sQUuHXHx`47X=s|3^DqX!S(8N=(O1Tyw}S%6($19N|Y z_p#d{3>Bh)*Zs2ONf#h2dA3=MToJr4FVT{zz00LR5BuS zU?ju=vgX6kFOJYy96i3z1=Zdr)JEYHtQ z6`&NH0|@0eDAIC)d9>$!yoU?m3qf;uQ}2Kk*gFm0N#6U%o=}gbf=^BvxCc*RQdrmx zXAQhp6asIk8VpVuC8ed$RU%n(^uP^=!Cie%Pk*%!=HNg8WNHb+=1vLt%o-+Y>cPW0 z0JSv(SaBW$R=gr5rI!q!f;dCCrjJkUGN3%Pyuhz{2_}oJP(S{B8L|DZSO@0cs`~+OptWFV-!!bO4lg$w@S_1`%n3uG%uL=X z@EBYHxHiR$F@ejM8yVmyGPARPvr2ntJYPz5uhh$@eA#qZ_c!vJAg+|$f)sD1yM9kw zs?=FE?rh7YVK~b8S*B&KZU0muf8N55zWa8 zH1Gc3P3(M6hhWU2Y5m$md(nPp1i>YO%Wi0c5#x(SCni?y>U22Un*ivX|u+1>}F5B|YtTK-ujJzh|_q!*>y&HfPEvu4gRxCB*I}=~FB=hb|?#lSS6+ z(Q_8@uGv^?;%evpgh;2^d3jv(glXTMb<2V1Zx5W)sH21K3F&3A5oDo-im@I%;${z{2~$*3=9lMV$NXojs3uN|EH(JA7*&& z+JF3@6P?Yeu1T9F+-whukEf|usi62V*e%3#bnui0ix85;k|jn(w)Q^Rb_d>ky~2& zQNnq#vlJ%!hSWqsiCpO!NiQ>Bw7p?t!fju%gEpxVQfL0zi8DhTv%? zKgTpym>7{00PcrM?|y#xy&UuWu046r#?Icf3B33#c9WHl6&^&fLmB1)Z!nS888S&8 zL^53$PAx9h^q8qfwcC|VF7D9-hjbgDQzh`}m|aWmaYyRGjoMcWC1@#T=U~46oWmMk zyaFcDWK|M++X0yGHX}kd{TwxAZUEu-83Z8I3)qUht+ljh9RBpDtw3+5XJYc%7ytmz zq2;Rqxb@)K$4hijJT8#?9w=gRNfd!vj|1gnuQYruva8!*JW|7i1>6~)iQr1|__7co z_4gL!6j+TwQA<6Ag>)y&2_9kUGVmS$wX|}DZHNnqgU>NA$fMn1Bkl4^HtF4gM_uqg zz17~;6)gh@;0LTe2PR9n{~$9c943iN3(sGa%|C-=vP}2_zk=tuo!$BQ^P6zC@w>Pd zNdleV0NC5_e~GTcpHO|hx?k;c`f{-P#r8u;Oj>hu`ZB!wCjg%ujJQF7XQSRHi9q#2 zj#0H?dIY_Qingw9JH!G(MZC<|eY5)!%4_CdWd?B;weg3?|BfqqhG)J1=5Zx;D;L#w z^S>-=dWb4#mggM#8YhIfB74X;BJ&gwcO5kuiy8a2oOLhgU3O5Y7M*INF;-Jn_rUq# z9dBTtg&R>v)amU+p?U*HbcY*^Cn&_Y1Chi=?r2_dtek34fsZS)F zg<}#t2qc)g5ws$+FH(=cDXh~`;7i_;a@0VXuRxfz+!2mTTVIA0HjG8pjBLf?&iEqP zSbENOcC1H0$2|QyY1|M|RH7qs9pyqEwm5ikZfmxkXyPM_U$7;If&l#l!yDwdv|1u+TJR2Q#ov7r11BQdFPwN z*Pon3-cctlOw-{JgtfnVRVY57|KM|JG1ZNxD+D)rFA?M@4RmH1d-z4SmVC0Idvcin zi4NyVzH`x8pwK1Fr6y2T!wEc7T5ef}`s_j6bg zmp{&xcVKAfruJ0X7I9Fc`nzeK165VkfTllxWuMQW%bsfC_)9^sLqDXx>AMsf;Lc_b99 z2QwerVF*0O&>YE(h2b~;ZvQYY^ZI;YVPOKO*nt{UL6}6HiqLaJ{s9#RzyYma5)cg% zC~6FicrLtNLpGsc3c{{;@I4+^(cYSFhdO5fPzt?C*PT`V!Euj+X*9h4<$H_UGQ=(pu91?k3x{mG26UB$rfKOs7{2k4Qnb7KirokJcoL3;S3Lf5A%6K zH_6u4mf`v_X66co87~HDKM(jXYAv`)qJPW&p*eK=TzgB9H5bOND0*@?myq0itx^fRm1 zrb5ZDQ&4{n*rMB)`%>=#KwQ)Jba&VUcIbD|L{~#U`W(@z_9)0)a=-gabPBfqm1}0L zIJ;M6OvK}P;=5EpAf{?={Q>=!+ z`J`>z?sUS6v^s46OoKvR%6A+{i$(;;Klc@^{!|X=yen+1BegpHl<3><61$t^70=I3 zzevM=)RA_kKkWPpKQMA<%*Dges^v1s!3JzsDfwUTjh(ri{;?lcc zUHO2c42vO^diJ3#O?br0(5s%$PRrjv8NcM!4g5SC&+f}bK;*2t=K2{ae6IEcy{Iul2J z;+datAmQ^O^{E~;zUMyQC+#x;LKe;<9E(D3-@d&F)l1mJ@4pup76{X!W*=VN-2n>8 z6(rwr_GaEqXDzLdkoPX~{^Z1q5{<@2#>U70KxPC1WF~x3X4w~Uno|mJ_EL>tdglRv zELg&N;xaI~g$z9%AQ2rx$HG#yju{;xwt^crH9A*IUvv~E!vJ~_^OW`U^z4uGV+7B? zGH-p>@Hl+{ta%W33aenZ4rV;AnoLuYXn2aYlX<(=nZ3?C=xCHjnJ? zQ+lWT=}gc46=&TCc_WrW1(IIlccxdvBp`R40{j>0@c!%^~I=n?@U5p zzrHp&FyIpQo{WsF6d;8RzU@9ovFZS#0d)F(lLB;jq+ zqtDT#SR>?UJlp*`s(LSE6-6L5#LD>o9n46vD*p$QREu4je&t0dbZ#*dk3VV=Pd~D) zIy046TXuY9mI0wi!gH+V;!F#4A@|~b9CJj19272hbT5f2&qvI9|Kv z{_I}9WBz3i1lQ2lNqS)GfUL6Fm#f0q;m1e!Vs;dQ)5!Mgi^#lOv}i=KR+IVaoxL%~ zaw=kxFB76Rm(M&K?6G+xioTquO`==Ws4s@%&2i>`IbVK^{V*~|>9K!aSY7Muv5S+2 zwEbjsYnl=Z@#)rYK1TkfI`y7BArXCQLHtwj{LNx(Q7^rKAFU=?Z856R9RGy>@@zhK zx;V?uy_?Gn%DsccCYoD_2GFHGUvr{+mq_-(5YOTl&1S%;aJC;)i8?L1Kbes-Uc7pr z)c&F7c$s1efBtW76;5113rVF>T?&9H2)z`Q{O42g+%s+RshP-8iHd$dy~a1Onb08u zGqgR9cY{fh;;~syd~}`Mh)J-DsUL6i8=71i-grDxyL&JZ1SmB@&QS2sV) zdw7)VX~{v;vxk|u14pl$Dr@l0Zn5gdZ96;2x%`rvDnqn^P_VLYxEf$|R~~C^Jg&>hjritb^*`SRsUbp#J&K$Bpy zADKS1D;=_vNb%3x#HrkGBj9>jlVn)wVsi(E3=VM3#}8ED7gr+NR-ZvM4j1G(s;@wt z7Aqw*s6KE{jAy}eSzLT5RnZUPm8t&T5%d>e2w!%nH_vIT{74RVhm$|#{flh{|7~Q z8jKrah=Oh&mpjcD1D{849CIZD8;)Tlxu5(Df@I8Nf4=WU#zvPdc5VPAp59)6$`hBhHz-(2+XZxmn7IWR=&hkmI4A@$Y^V%O8pvM;Ad9 zg;=-M_Uxs}C1<$fi=~umG8?y46d}`Q{i~nEB61qn9fLvM&Bg?j5r)ws=7jQ7c+9;w)96dD~BoOZ%5U zrR5IkX-r$nyX4pPuiXp%C+v7eoMOzEvU|-c^A@g3j`8}i|M61bv%*h~S}$lYvcy}v zlmj-CA8^y&VDER_8|mdXt{aV@I>1+vL$|fbOy!*(2Q--|W)%_)F36>pd`CFPUu>F3 zBTOj^XrmXcWJD@rv`3tmNV>3=<8g#U2~Elhwu`Cmv5VfIVK4mkPUyzPEqb#{Z}Vl0 zZs-zJHe^Ng^HI(}p}2hIihx&t*xPO#e8so#P$nvPIP~-s=5Mehgr94?5`L?DDolnA z!d24AeTH4P0P2-_i<;73k2t^4%ZyoA78C4h#68ydGiF>ihD~#nsC%mZ&gioS8z(2; zh1+#^@-7mba`N$Ixi*JTo)*%cZ?&;Dfn=faxY8RaO*SxopSlxwh#S+vyt#bovxfDD zj)jjHWmlQ~Btt2*CyxOg)ppl1BZY^8pgN+7M}D8y;Z(8+I&8(9(a}+sqCx|wCy5wL zq93HNwllmk@k&anu^8EZm9_bo=R@_<4TqaDO$V~)`=wKiwY5^OmHI2XO$!dFk(sNH zjLXLR`uiK9DK9fy0um}wE{ui|=L?fEQ-Dg+UDH7!qWAVk zb?e97|B#?VLPCT9^jA4-#wjUT4v`t4;Ygi^bjKec8d`_9AxmY9}57 z#KuZfm>p5d9OsXYglQPLokEP>yhqGc-7gi;*|)e)y-=-nn68~sixD8apCrvA_2S>x zHNet(c49DhV-V{yHNP|suNsAhyo>s^00Nm8`0`}vX*Bg|uwU1K1K#FEo&Ao<&8O2~ z=OYN{iFnUEnZSG;6;!+Vc&6qLI*0wt9t8XUaBL1S4aXQKiJF8~Z%I)z==2>|3e{I%PaPpNK^S6m2KMf2skZN+R6N!MDtq{CT zL4+1zYV8%FsV_24O?!;|Lowkpexu+{?Trq3(We$q%p6IHP!V_#CCIZKd?{3p+>bD5 ziLuHwDXHqQYyO{XcS7VE%8Tr_@K#9r=cYMdJ`LX~Pbm{2xP7CmVhBl|$TJwSS>04z zAMp&e`hQvga?C}2LarR?hc4SWO2jx~Ae1ACIWF=U|$91ulKFchT7UoyIduOh0irs13DI-^C39+ z_w&Yn%4?( zWQha{+oF7gDvV9MA&ij-83DL5_^oLxaf_@=ou^pdZKC!x+eZ;ldL=J$mGA$Ab5# zfJ-hJRP~P(We8xrxf$4H(&U@#w$PD=lfkB#MCqYA%kD==j$N^l-(go$zcq}m5G3in z6-)qz)|6pje9^H;SBoGing%Nc;gcq9@C+GDhNcSfTRxd?`>#h~WVl}x$Bz0@KXk#l z=2{Pq5UD&P`YK{!yc$tMK0~O_ib9g?BX}EB?rjj}3tIWvup^PK2&#C;dgDGK|31gtHGEnk-4^d|(Ov>jooy7By z$%}u(AWE~77g24RK1;h@H4A2rvT;x5ypnXh#jqITN*BWO2>OVheIJghdtUQi(YpTw zM^J`2VPwSKw2m5Gl3Yh0ZplaF${EGb#eFT-Nx@3#Qy&R=MxNn2A<+xC(j>J1-dHgG5*BQR$jOCsiIkzRV3Xuc=AslX2AQqg1 zlk>8O$VJlvPb9M4+`oONL()bshr_RcYcIk~J#U!&DLU|!A*!AY2gU4E1|5F3TED5I0#y9F7^DA|Qp=G!~Elp7dz~(a_MC87ytLq18S7<`bbN;&!hW`Q zZ2YE)5mG_)3=F!$!@``aLZm(SvMCVoe4em8g2RwsR(47g68JzVLXn=4QFTh-D9MD6 zz+HA8*GEWy=yui5)ixL>UAi`sY?di^H%|0+9VBW~(a?lKY|?tiZbNivC{eC@hM6Q> zP{B-P*JD;wM`wA<*9Q3MuOK53lFa=Go;_ERfV=8txWK5p`t_!wB4)_@Xc|bCE7{rE z#Sl^Mq^=$@@Ce2=58hEMS4jbqhi!r?)|Y<&Z!Km|7NxIDZ#aG&;4|bbKT9V6s7D}q zqW;b@k|NZkt%$Y$&-}QPEa&_W&t9Mm*LMD zmk-A$`o%x|M*G|*E|>Xh(abH+HeRBe+*Ql3#d6BwqR6^Im^4^5o})q$u+nSujVPY% zqH1fBSe7q=wb9F97K@L<`UQpx@6rhHf;X-k6H)yxX1cfc*Xg12S1m^#E!vRn8LZ6* zv#JC+M7YT--ahZYkfi*1DwObi?_DmI^8NwS%L>85|K@;Dy`?zNG{S7*!9uM=XnF%N zSrE4{9+omk;Ox7U3TbP^I_@#I-QGEqxdcy&cGq524cDDeGYv!Md?RmtwN6VBGL|(4 z!HgPa|FI{Vwzds>_1A;dg3-czi3%hGf7c-*|E=SLx=R17v`y!0%Y zbh0Zp0-5wI#opDkWQF4t4kDMv>=mLW{c+;yAGq;x#~=)1=nn`te!YYc#R`4M4ikav znzLRUZpg~Eojv#pe}ZImG<)S}C!|rgGI;h>qk(SJ(P+J;AUHD3+K9 z&PZR`X1ZTEQ37UR1hbSD#O(SvRzEvBaBGEQJk7cju2;fIWTvb8Y36%IQs^Nl|2?P1 z-Av2Is}k$}R<7nQ0`*V^!}5M}u$$*Qxx(j>vQ+8^5x}N{peCU^!(0tZ!);%VOwP{v zURhm`-c=f2Y3YgQaOt`Cq}71pz4Mk)rOWsDZ);(2-)9S& ziUXJ%&H)Pan`f>&QLC$~Yc*VP-ln;#GqaZ@2Z@?O$Srks@dLgu*z%g1QE90gvaF9z zO%DGptb?qqAMPo=VN`JW9A03>aPvz2ZtMm4ApMBJ6f*(AX7(#B@R6B=EQ2Md@S~tn zF6PFz7mm|L!3@GA7D)+K$`ONOa9KeVsU?7H5Cp+4+8#J!I#o2a2tGXM!64g%Qp zs`R!sQX*Wp|3lMPKvlJMZEp_UDcwj3(%qqiG$IYs-6bG#XaNxr1QaPLr5gl+L!%%K z64KI*l;pq8eZPMU$8}uq9SCRdHP@Wae4@gY7S0E;V!3F>1NKDX=hCn-R7L5yklI=s z`wefNpFM92SY?dQ6*@NLJQNIo$2wk69h%CAt;MtIRdAICJkL2NuG%0BX2>x_xgPaa zYBSizZO-NzyT)Nu!PeXga%*_6Gh-fGkh>oc`J6m>=HJIWN^UJ9`st?sNEJ_)IUxk6 z&3ReqmL9v8skt}2o;7n}^p|#_YB_9Vd-+rr^@6^P_m~a3T5k6&|66-xYqs&>>(YTu zIB%4l6g(HCMMp-R^3t5x6#{(|h&%*XQE)|oDrKNPwyT);Bh;5MuHH@@n2m%K7V4Dv z?@I1T(IfN06s3Obpte<09bdA%`aBROXRuSB^`0R*?Ukc;?_iAPj|I7Y*l&ZZuLKl6 z6dp#QRF5y2r;h{Q>BhtNv} z!1zpgy5m$-@~xTT)grms2!sSZ-d7S=d!kPLI@NRz5Pwwfi{<8sQTz$^@fb&Y@8-eR zc`m#zxjb#OI*rl@g?i*KrS}o?U$PXkBKFrlpX0^Am@SoY_T)%x6=`jiNo-^4{%WuK zT~}8S*P$;tLD{ne6-BE7nW%d0ufLr`dt@XRj<$umDWNX0LrMA^({N+Iy z85X08G7&L~&WW^zGMP@|WeMiH^9}K|{0&3%T@R@?zY%Liy#f}6&Bu(`tOe%{nHn{j z^I3a>?Xqk%x+35Ai()ps&Aj*Q*5BJ_&+qOJN-bX9E=+*fEE^C>TNnz~fPX-%>l&s1 z+T~H;tBwGuYR$apZMUZt}Zv=r+yP%3=;GQ@duXBA;=y6CFZR|sRHCqH-M-> zfDdp*z^<#12R`E<8syWnQvDu11A}-)1qE)TF>&*Gb_GCYJJY}tQ|1t`I5bf=z;3Yu zF!1i2DoRR77D48~5i(}s6s$^%fL_ZM@L9T%d3~GUu?0gGAfDLm-2zBG6^0=Uo(JDc z1yl*mCr<=$qZC9K84>$~3Aydb-)#m>+*_XoAorC)V0mnrkdP3*k^NHhJwQP*nhjF@W5`0btNC;>blwz~&q$CS|uzUr>?LOFR4nGDOoE88c z9Y=fx?3*HBR4ZFoQ1GY*+z;IvnIiA(ZEP}r+6mTMc16RHG&lvelo`hl`&9>k3~K{+ zIB{lx3etuAxinN%s&LR?Q@}AE8C!u$dlvyR_FjDTmjq#&gAPK+!0(4UJA@a@br3nj z?%mXdcE5ulnWpZK9v-ZmSwCZlu_BkFi*TmvDESh1DZeOLv%Hz0b-a4%Heq_9dYRO( z?@9JqV#YJ8jb7}o)%j}fp)@9hht{`nF!Md{Sg%EvV`<5mu92M=jhW5Q@ZDzm^zy;V z`U-V?`WSa9u)A)Rd%@KYr-{P_Q-b2EH7~}s4^nSm|KLnSJ{9BBR+>S| zt|?cjYY7>9c4zQHWikYX@S@-(KU~m;0e$ z@tcl_bso-_jVOO)nesF8V>GSJGu!3!AB#HfpAURBwLtMhC5Ly|M&l4tRI zt?ZYS@9zl-%w-vO7Jp&Pl~}k?QrR^$1M#v^pIqsBBnbx|no|l&(o_GW+Vr828!xml z5-l)H3s+^qm}iXE`8o4%9ACG}Z)4@1Hn+V0F=b?N0kf6*1LnShu!HDH?y!i_9m@wC zaBu`0dMcX?SU$cv{Fmz=OiH!pMFpngeV@#CwmMHTlS}h;9Qg7O777h-qGwl()U98s zyz<21)cr$pe}I*;GKoo*Evz;jF>5qEp){>0RQ3dwTR70L^t5UxaH^4#Z$ww_6_=adW?Yh0VV)&@t^sdf{-$Y zdc_C34?67uOkFx@1vU|GMjkEkkC>^d+OUKB1_t71KutXYjSB4@Xng(+Ws33!fV{{k zuspPb`~gUt3Yv^DP*KH~K)vz)4WLu&0$tAWiHZAISXfnUU~rxUTFC^@sdIoH8LR^1PP@&450WGs@Q+l1`tU}11q_xW~^$TEoxgV%=;Aari(0#GY3$;rr67y|wz zi}hUsVv2b!SbmA}s!Oc`+RFIm>E$t4oGBp}X7b3?jU;t8Yv5Q}`fKOkn;Leo(V1*m zbVo}10H~)X0kAq|KvV1j<~(*n)B$$2??rvL_2%mw$4`(#opiMz5QzgQA&IPD+p9G+ zG;~HS8xqu{_ipxIfNd>5I{;5r`|c$x$_ux5Hk@wHIeyaUW?L8S6wPF&v&$~b$&{bcWC$#1cW=B1{O|Ey&vWFbL91NFn|846UZ5#^cjI8h7i2D(T;z3?eBM?@#MXmzz7pY%l1oM&v|uTa(-5 zoD?leyf>z+oS!YJQuf1MCtF*_FH~eG(FX8RK|@F3n%>kL;M=m6viwul(!RlhYdFi zyw(%5yZxdW9_Grc--cenBC!8quyDV=x=ct?X3~7n>mOC7aj5n8EwkL_wYRll12yR{W`{U`AY2a*Q95Y)=UBZQ;?%`S0!J1PfzYC*v6#(oCdSnVDfPq_4QKKd|^L zC(QqAaj?7-n z7rvJbz3oY$5yh~vwGEKuUJ?`#C%P8P8q4fCi4EVyE z$Wd+MXXdZ9a4nv6!9!0i(O ztMoM_4vGS#4lOT$OsL%piq1=w;Dd(XMaYu}ukF(>nD!5pM!&S-MziWAU(FksK!P$W_VRYbiM#Ey$o+bP8RXoloS?g zqqI1%=s;$ad_Wd#Pe8{uXG@7~2E9hJ7@eJ+-3Q0&1luiuT%q*rY|TZ_ zJ~|ELg))xJ3uU07ux~q?b)GvzYA8H`lq>4${J;PtXZ+B6@DAiQ9{0YcQeYxOce5EH_@ktYbk^956A2jx3K z%)aC}bwKmfAnOkQ<6N zp{7(0`jFKwJ#^>ziw9ed3C?ZGNz6wpj&6Yi4~1Q1#$Oe{nkFu#P(HRA+q+>LazUg` zW7xs?;bIsTfnZGxtoDgwP!Zrwip}7M?|##cu@C8w8lC;CZ2sWSYWdn~wHQm8#zp9P zqXJoJ#h@_G1sQ>?B*k)D>#r^^F(h(ND2oaI=87OZKP^v87n0j>q4H(&@Z?JRtI?O) zGj#C?q6&qvEf8Mx`7TzF;tensGhxP*5G(_Ci9f>Yr_Ea6=PioS>Z_}A%%Bn{6_6hu z-QJkoINJN`O#Hc(1V$vI5w+xbBPi-1+%I3+YN-dqct=!c3~TvnzvGas7gyCy_Q>9b znVI#TrRw(^r!Co8OIH!Y9|M-n{@5p9z4@{walIX>5KZ<;2Sit_TaHOZh4K=Xu!}ac zp5Ca%JvmL4f)sjFmfz}KMTcQOR^DrpGLtmeo+Lh1;WuYe{G^W8ma;3NtlwU*L|8fo zmBvLEKEYI4ys0*-8qrY_dKxVf_FQpvJ|Mhj=f}Ds2jVq)X~^8G(4;f;&?#7OJu*w@PQdtKAr~a;hGiu${m3mv4qd6 zR|@Jo%)>t&?8{tdQN3l3CU=KTF-I4XeOFWe2+v^w?SWO+KqWUTu%z|eZ*lj89Z_K~ zMN10>5FNUB_WACRn!bQMdRH35zL&O?g{&Y*`%8Ynpl<&@i@q8<2;RE(@@O!Rt8#hf z`|wKJgv^kNVGp0kRp&HgR9;wAo<0;`vEfAuF~0pl zl$P;&^R;@njSaIHkENWmK_Z)B3td``Kn9PO(M_)!Sa0|fm-R@`1;k7PvSKGaX~fp~ zBB8vT+=1j7YP}WJQuqb$ijM31>n~oMx~&B&=WjcI#o|jKY)?&`PpTU1&P>2OQIa4> z*q$h4yB- zFd#^=Ndz_XUhzt(m-G5vKk=PW)dj~n3$)32`!u&o$a6~@-&ybNpUeqzNV~8!e8w$0 zgSR)W^P#J2cMyLXThjS|9bfCX83ZRm)I)4xE${nLwRa2V9X&c=R~R-vH(k%63wVpA z*E*9FifNMEy{1bif?cQqL{T8}ArTb1vBMyQI5UJGypgnlS^AGz)vatDc$<>k(M?m4 zXTC{)VZ{6AugBjDzU%W-)mQk8Zuk&KuH;T|9A@`VjNV0**RAM8U-h{v z44=O4nv6+)_Acso^lt*+u8+&?XCN)~dj_dErg#3j0+Ux|Dg;gM2^kv?DdtN@AYwxq zcO``V6@JyeHkd$KP z^kV<7yx6g>v6x37OfxPwH@5*KHPf=6)61J{=m3pjgvROw-3O0*`D5>oZWv6D*#=+? z*X9#F=y1@AORWL2Y-UMOky3$vY3%732NGJ70xI4c!1*=?W;K_)(_ZgZFU-YiuMhAT z;I#X!&45tT@##w{>7B`J@Z*R+*!j(m$xsG)+A^tE0~+ZqWjVAGRHJd5Oq4q8b;5`l z-pcErHKtYx5hYK9cNTxvLE?BH(&v^ir{yGA=E_e+yVVS2^wAhc>l%!=K^R|M#)i51%;H+{;Ydx)Si_bdtt~g zjzc)CD)+guAV*2$$;I~6ej|FJM+2Z>LTx&&eztW~o+bNa1kV^cm$$pLM@!7lRSz`~ zAN$2K$Yt*$Au<%W*>}U zf30L-?k!*fS0b^sE-^{^QVmO|c9#I&E;R)UP4iCIy3tvaMxhhwWx~c#M@ANE@8*x7 z)qDP4;@zB_u2${$rSVtLh8IJl(SK;z{n<+B|CO2K&c`JC*?orC{PjK2s2Gbf({La3 z^mzsjFE8xwsw(04vymaCZ==DxGb{JvN_?05#MvK1NGFhzb2yYs68EN~qXVR9ZyC=< zTY9Q*E!>p~Hn5Qz#?z(tw;o7Zo~-oWzK}D8up+a?L2~NuxRxxwPd&gcz5&G*Ae#Tl zh!zBirZa#&N$6XS#gd?!!uG!H-+E?T9(^B2hfXge9o@#GS2 zBJyzS!ENR5p_%WAjI;K4FYJuQYUJrPMD=pk)55~_Q7bV}1VZJuhowK5VEoZm4WT2I z6nVbznpuN*+OIfljWbw{@joA#$u5Ui&FN56Er@#-gy@^fLNH$<&{3Pz(BW4IbV4Z< z9!j83GTrgaMEN}xs1CE7sQvqG<2!l~j(?Cj$$kzouB_2P+FpJFt`+fHZhe*Cv9xKI zurG~XGq!H{*|DnI8_=s)6^t( z!^rnpH=YW|x0bYH<5QwxKWv;mHz_%-n%eF#&T7%aOB-RJrNslOHR)%KNYX(Je z(sGm>=+;$XS}+J}Gvnp}-UOOpY43l>w%-9}yLRjn0>q9XO&HK%27gx-xD4VB4-Xf1 z*1<6hvyc@N{SgDXppBS?IikRS8Rs0(M|uMOn}O$p+hQ13D4pku>`3sL>|>n_Dj9Dq zC80;t58)NrCKyR#Ibv7=oelrKt*l#3Y*kW{vtO}V2aQ~y(4itxOeMlrKv;xcqY~ld z7Q^OGp*JVLa(~-MLg?_BrJ7qhgQvnvw0I(@7wGe)x{@gVU0)?3#ACB`*hS8i_5Fxi z!#VUJ{@fDan-ZxL)#0L;{N&*1){oo}pn+aT4zDD=avE=f`4dG}WXdZxqJxN&_z1z} z&u2$`{z7!xNYabO%k%R#5t!_?OCIj|(k92LsN-kGi6?vWNe4+hl0I3aPpg-&9F9@) z#-QFa5)#dUPi{B+yX5!q3B6jPE5z*amR4c>LoHnQ4hO48x7$`zL0yTBSyz{sNEpv$ zJ(@qOCuBSdw@O%~c@mSANREuA3;U)#-siWNwt^)n%AMVO96}jM#iEw!(-gu%{Mq7u z#Q13)p0T#&c&{lYK8`%kj{%2v>d&{bFm#bRZ2%x*IQR>F$Ws;^hUnG;idr8rhqbqd zQdBPj-t(#q3jBaIoKbtW7=qd=DT8D^b9&_|rG18OUmTiblYE_|ew}zyiiG#%;M6!YnS#af^$KGeLT=s)uA4pU(ssn@nK?I?ynR7@X^`k(38PMkQ(ndM+Nq zAVO9h7PgeyYh^M1GhgZ2zGG$eFN5S_Z_TuMGu?U7f@FU_^*ok83^a+khTc8Ddn|v)vCJ^w7yFl%|xdZW=OsbRU5 z_c{xB9!*bBYxD1mqluY9Z~GSC%)F@da$YRO9$y>Cy%WP9FI3|*Yew_-j5WD>8YJ_` zvzo5w_QXfq>O5*Wu=d`DuM*jqseWk18zpSl==tRkCKq2H51ng5V(dI&D$A9C+d0dp zG^75Xt*658i8y3o-|)fc^%IHWdjRyh$$WBkc^OX4#L9_fz&liPH&=Tk$M1>4Nc0h0 zfdI!l=-?ty11CjN3snWhgAVQrxd7UN8!Q(k9YTc?AUDhxEVFnxtUEp(`b5GFv{U4{AWt9xC;~^IOm&yq6BM>O-6 z9^Pl1LxY(7TB&?)bTV@z$qn-5eru~-^87wmW?)Gs4F1~u-ARUFk?YTV3#1x|eP=E|;vP-Q#bYn3dzu3wrEvS^n3|=pH^O< zQ`j`#1HOhpkH5O`{~)%Pet!uRDs)iw1u7RveTQWa^j}))k=c;4`w(3Rkes{CX3d;G zAEU9{bXh!LUVzD16}et;qe8@nlbI|vf&XClCN$6A{D`N!fRZI1+q~O{X=DP4DX)18t&n3*Rkn|jDB|c zq%+wsoz3m+_2K3Ku?$0Eo8XR<q=+={RJwB*r?Fu7Qw(gezx?NW14ChO)&H;R*1l_-F0PJ zfOIa)6lZEaVHIQl`u6cnRHA5F<0g}3ODIEv2#e-qRwwcl>G@*e_eRqb4(Iz*uF6K& zo+W;W7|c~a{Jig6Q(HzCc(W!V8LIJD)v!!My1mzLI-!lv>63gZiCpQmrM7NWW+`IY z8JY?>bMUYu^@j~dS{mhIyF5)+zIub^3@2+pyU(m`U{^7T}O}XJ{46` zQL*CNYywr|2mS)@2ZBwE$P4SfYHSWqj&c-eeC7*W$LYi*>YU}{yidd_fQ?+XH1cE> zdQS~?mK1c%UXeqe3LR*P%zQ%2x>Pm~2$EIMk{wcS8wg;}G=x4~o88I0CaY6&&O|Jl z|EUB|DxW_vh-cA1m-0ml4ma{eX2cT`f$nfEq~Ur{_0kWo5|oeVBWh;i;6-*2BfX2z zg})4?_grc3E$dh~Zbde$GbJwRu=SV(Tm%PGB|qW2*(b$wz36Xf{*3J`-|zLOm6TT2`J2dPhW+MKQta`fOC0 zoJ0fyAu}E>V`WFj)S}QTCp0k&uN(fl^XCn7Zi%*W;f-ZjWk% zFFR;hc~9$?U_blZC79X{k9r?Upz_2&7Gp|Yf}6&9&T4l&m$Hd2r%QbsHE=Z#Y%Id&T8<8_Ors-I03|_Rh`e-t}pMmI{ZJfB2)YD#E7se@*vUBV)PMN3J5$! zcW|&2$HnLFEO|g=X9QRRyYSAunYV4RtfIc0Sfrq6M}Rev;u4InCcNn-3pivz^x)TW z^JowIh){zjj~ri7MWYQQmzng{}npNG=4^%+um(*r6|OxVWnL6N*)gHAdVn%I^^e- zfTfuWX!Zp0v!Q7r>JA+0a$n zlX+hPu+3uFW(MscD%mwg`|yp=dQexuF85q4fDA_+Ty`7ia#p(bS4@e(Sa}(b zKSLAvu;p;{U*h2rJ_F&{D5NjO8dcNkC`BoraR4F1f-J#Tvp_EkB2$|;%&zKdCw2E zZuTR%_{z^{cm47Qc!!;^(8@K#b+WLUnFxy5WGGEEN|)LjpQGIkWh99B|5M9-_El<- z2TkdLg~%*pnz*DZK7-4Hd+O;t9sXM+>J+?Sq{nZWYDExheGxU8E4v!rd41!wc;HW4 znWQkr`81n<#-e<*tEd3jMs$??DZAcleq*bMqz`;-s$3p*C^~Uiry5b9>Nt7ZFI31q zod0X2;VzXEi}1kYJ$mQnO6$#IkB{3Jv*@|($?Y|<`;Dt&k8TTyc<)DX%%a^+L*is4 z8|_&SvZ!RQb=JU%TRA-%w2!@;-bgu~ENRKej@cK@bO9tZcbD1N13nCBX!vB z{yX~3rchq0BTiA2TQgE8(`eqapyw3dod>(BKUlXmu<(F_@ZV^Vnu-bSVp3p%mugL( z1{7#Y0ob=kh9XR`#q4!AoH3T5Dkmjwx9_jv@E4D(LS6*0^*+8>x><~GE*IQoxwrED zpQ@p-G(lHeotHPdb`>tiZ`4!RP@8`H2ES8THBFoOe!V zUqcm-`^_Huj!E>q=rc8#4N*n)Fy1d z$-Yp&^+Kw9;6B~%)zdXyv^a^j#j>oZ@(!$gmi+c-Cym0HBQh#kD7dJ$+x+=Ca+FVw zohpGocrzXs{&VP)zO&DR!*mf!i>eb#fl@jJ8A3}Ll47Il*beg~ocUpr%U>NQ+MN1cPJ`65xU06#ewh{Nf7=XD|d!a3y`gSrbJ3c4QMob z?(mk{TyNNJ87gF6gHy`S5`>Y)`ta}PL=0y|?nJ5RCWS*Ma9@i0A#ex0Rfut4s2Dm@Ov7GJ}xzS(-&4emKq zFD~79PX)gD<>O{f1D>`|oy)He^*YPXeS*jBJXon)*S=i`x3JdRgn}?^`F(?;fLw7cTQ7c_s&i{xJZwvW}qSKSfs+G z4SxPkIAj<; zH5samjm?rfDq&2=J;*iwReZE%+J8);O-5p4^*UKCX`Qu)@++Bj>-|@6UrE$i?{V)M z3#$J}BcQsO!kGO!qP3N`Y({)3oQfjS#LFR}%|V8RgQK9WO$3G(VluMGMZW{ZXIVRo zQ9LIp2@;k*hqng?HFtC;>oAK3{?86VxhjPW0;RVqvX1R(oS)tKms`f??NLs9V~h$f zc0+(EIkMqWkQKOxumV%2U7oXmrg+oqJ1yuMYsn58hWQ5_MyoKI7JiP0Yp6kHEpjU( zucrn>H@xk$4|VpHA$THh(CbW6w`ll=F>~ZXNnh9x)MZP**S`UB$|GpsLNZ1xhqT0}t(!dPhGrD82{ODGwOj%NNlV|3ZW zCqS$&pQrAMSSMY(Sl4466u}@vzYcI?ejDB@QKyD=+}U@o>Geem++;7*-*nQYS~*s8a^G;*WA7}$hdDbt z+`INhOury_zqI&1chfL^R@j6}$Y>WUPVJH5G-BHG93%f%m!38RPzBfcuT9;pnioN@ zRwZI@936A-o4H4t;6>k3`AY_&T~ECZF-knUIU~nax77g4pVPTiz$&9I+xxNM#}{=A zXk)K>%=S(*$m79^w6A1WHq*DWzew&&mwNyhNfs6iUSY{{mSiSGSWPa@RLJ%|$2gG3 z`*`(2AA3+_*i4*&OlV0Vft-q1=H`Fh6j6l}t$3CDCwq2HT(~j<9e0p+Q=S;hKsw_7 ze`Nu88y9L4FWzIFd+CExHT_V`{3Y$xgEPy}o)Ajc`ScjPbDX};>8PfMTOt7d@tGM4 zcg2-COa(WAX-`wi|6z`3u#S76X){FOeo>oqxsV9}#=ND(W40il&uCzHr4yhxBEL9M z;avC@{Cfo7Ew`FFY>b;{yxl_7V!M#MMGGy-AC>)*-JI}H(oTuOIj*`ghykGT3g*^* zAO2V-c$ucp>j-JJmH*zdEC?dkdbGuqIwyAo7qP#l?+#5{>nMwLs{Jeaxffyg7GD1= zym|^=O^0b+NhJ~0Dq$wm@Z(X5+pOi7MmsdtC@flmk@AVL89 zd8_NAO1O_MuT6B{(J@Km1KL(Mc2Yr6IQu(4NBb&4FfAn)i!Rr6yc!539df>MiDhb-k2`-L2IHSoe@(Cun zEY#%;4-Y2-j!;0P1cW)AeSMhmLt*`Mx{$$F@^5h- z-J}U`>VLGZ4{&=*gN)uxwyE1 z!AEjZ5EutgPYqrgM^O?4|)9iOtz03n_C9(3`TN~HF9Kv5zNbeyVH3<;ISKy zjvM{+?r7r6(=iZhYN@0Y&B?@+=dKgU5(!AC{i#n18G$bxB@NBaH>FHmF&R;V@t2~5 z9>3vdRyvq)?`=I4%8Qi=w9d)b%~g|Up%$PmF+;mZ914wO#a3hdV}?y)XNVz=FODoV zEkFG7W+r~ShPGKfA546o2&z$U z@ILM9jiF9cV+_81>_dX;=WmB>Pu1Afp~YW~YAydCi)14M6Fb09iZoDHl+6^PnpHjlLr#GlE!+=`wF-W$TAXLoXld=4pL z*_r&{+M4aWN$P3`d6LLZOVe%pjJGdCG=jFLMY(KhnuwXovVa40Gcxc1$V>ohT;qV< zi{c;PN7*2mk#PwL!oW`0_xZ=O2OEI0v|>Au#`^E-%7li7X1JyH0GK51)&h^{3}7kZ zOh_l8Cq=Y6SLc{=aC5$xQ)Ty)y08|4J`@Geh`QlT*V-p)1q6JZcBGq#ZrBaQ ztiLqg<(LVxRUMcm(QQa~Q?9SLI`+3}qeK!1*Do^pxxC0PQg_Z5B0Kt0!2jR<-!c}f zb=jDS2@E^Td>O76x9ay~#7(0m%Ds=oSvoP#hhO!Szb9V$tMolm6WQj*limy@!qf>@ zBzjOgdp$peUhc_RD5E@bo?6kH=d^idzihE4zgaHLF8D9@hELFojqO7D)8z_*f7Iw< zoDd`5v(+gzKF3FV!dmNScfDwa#+`_o2EXvovsWb7G1OCTF@^E5%R$aOz5R6M(^jgU3d>7d*WC;+}OF`l<3Ay!^|m)TK7g z%?-L14;t(CTmgDJ!zCl0*0zZ{hyIpM!9>1Fp`vO8%Ht<=AMk?5^#jPFv>C9iU}Da< z8IbrVlgGCm4cqLm=_j^PamvriUIhH>1u-0rTrq)CUGIQHV>K|oSOMY&@}D`f?RPtW z@JJin=C^MUsD$0@?CdmmfIl0aN1xaNGyvO$>E>~ux(vqiwoUgCSAF|tDi(TsUGVnp zTM@PU$tvCYKobF;>mT55M-T`|yj(c}>r{>1+u%K8UjxiDpy@XZ0nU}pFFG_f-y!+R zard~Wfxejb1XvPZ%ASlUYA8wb|S;M6}LbngK;(=*I2b)@9>xTY@`In|z3MNaNKp2YpebX2(x#(beb-8peA* zzAX3gWQR(JR~>%pB%aHHEERx3s$*r3B<6##SF}!t&PfOkLDkS7NC?6i{hI))7o`oj z`3)}?EH{6e^|;FscfibkC%OaY>l4shLiA zZEa~fA-ONJRFpJVHm&NmZCT$Sh!IkKB(Fy<&1?!`&;XkscSpzNIhO_R+LRLQxLI;J=`2iGIK`j7A3lCvT2F)dI8o zVBE*a;VcT+a~_nFA6z>a+SjtC!A)vl=qfkDE&u8)u14R}1@1jVl6ExF?%xmtKj(n( z*hTBgivo;-voDE&BldqW^38={bBKdLg>Gr&Hkg;mp(~VYQp8ah74Yu#h*6Q{B#CHE zdg{wcti-mmIyHz@mVGbrBDaHL@A6(RLC8->8@pRJtt@~Odkuj_+nnIrB}F9>>fY5A1S(R{K^2|S-X$(-g@ z)rt^f$}2~E)H)MqIvW|jjq&jpz_ZaYNC(~0a6O2aNs!y08q@IqA=s2$=?eY%9u=B1 z8xY*OGl=X}vnEbcxL}^Fm>8wGxp^@4(@^G=@6mx+ENQOd^-ZjTL7!umNkpO_m-kMO zHb4K;wI)G_M?M@C!jyxV49AQ}fyC`oMX8Z2w8vBxO$Q_Z_S9$4uG<{qg5Z{AdIA5g zK#Ax3^l!IzI2^J#-JVRyY6R|2Sa0a1xACFMZ^uu3uegr~2i3=cfs`64Dd{+sn)inXzeCU6Avr~q^nZ&+*X;)ea@zq^8u9b6 zd*$IjK8JtM&o_Ra@WAXI^(My0iWjYKmBZa(c-vY6Xx`2_st0l7Jf({SK8bd?~;FfnxzN`dS?c^ zF>m$HMu-hWU7e=&2IDg#kIV%OPd7%VPw<_1CQk>{yorP=u(#E2t4#c*s*?>0}4 z4vz^p8}>Z@3^y)B3^+?sjPDOgClu2MkoA6~ofh8z+In1|`>OBF9>-Z~(Dc=N5uA>7) zg0b)kaKc%D!;8kB7g)ECOc`3i3sH3zL)(qf&lf`ZwS9V*+o@iO?13+bF7g7bH@?`h ztU2r0l1C`MZpZu1gmXX2pNaEPSb+tvVHuv=ZTicpxPv|3&dw9jj}yZ{WlcH zh1`M5Z8HKPH-{8L-2mworx105#d2rVEYh*w>=ku_k`riaWq^^u`Iu8Z$V%x|2M*$) zAjr$1+p2ne(<*;dWpAO?#1jM;7`eKZkGP2Z1ttpRK=$+Nq4~GztqfY=QE_*@A=?JL z`}KfL#RE3B-Wp`;7m!G0yqp~dibbT;xE3&htgEQd{HU z`V_W6@b(DOJB_98n}^U3#LQg`Oa=9j18xg;)gAVvHPm&WI=W zokw?H>1#BF%iW(4_Ppd0sODh7W0sd~i7knTYptJ^C&my!Vc(@2^D^O|TK_kBDV+aa z;BAMRy2bbl$5)WhUkvkuMgeNScWK%tXQgamOqx2gCvd@u6P7&s>dAndo)ZRhUyGeXgr1E?Ox?qI+Im#UJ*Re2)kTD$SCAKRY7-hgWY~yF>)B|DB@pp8FRf{@WS? z=1{L!u;dWk;_#afl|$jae?34ubY@z{&I3h;6PNaKi~bAR3*5}h#F5G)vd3Yz zMiak&;r70vn|qwAUplD(y^4+X-0J)X%u|og4#t6|ocwsk-rz|NuTf2bBZ%p+%{qU1 zebmQ-iAO!qeNYB2Y#xFFT? z)lE%em47cm=UTs3-ACV*%%c2Fm>Pc(C=&l-Nry|OLWT>3Hy`(6WUwMF<5{j2J9dWjC(}MK6D~QO)E<5CIl)P9t3DuivOM`Qe$km$3Gpoi3@$YmuyIx9j%H(b$?30;X`9s zd2L=pW4e`&T%|fnIW?|g@B{UqKaCIhuaM0OUiWx3^phcVfJp1=n2iB6zM*^+S+i zFiY8~P?;}=;X8~f{rwE`AJJ@^|1E1PW1@i!Zx~|X9*O$~b)RjuX7E|U)_eLGK{M+0 z4~zF)ev{(I1cuANGVMD;^3O>og;abLP}cY8V1DbeSvPCKe6c`#eS-;b{=y z9+Rjy&9=`T?U6WoEAZ&5W#8EIO9OiQ+T=^0Yr+s@UAWEjK5LH%Tzi92z{-evCA4 zzX3jEzIa{Q#^q_49#jXQQBiYqbR-5W)O=gu1-(5np$8ne%a?%B-uWCj3rj$vN16z< zJF<>r1r0_o(`>74zQ4TyZseCpMIC^5JlB9_v?G}4?SK{#8S7(-OaW0?^Ai6HeA5GM z@K3>S`V3+oa!26YM=JqeS#vObZJ*6`b#_XaB0i|I-2zSFJq8*Y=SzSf>;S>fPY}zH zgmf2M20qqr9~#x%2Tctx;9OP?^!Nc^qZ8iHfAQx)h&+7_PPs6UUCn`>{=rLN2FP4f zTiXgWbJQSUD^}q}IF;r{u{;QwJ|^+A>HPe>5fIBhI|9GyTcmN>^lK`?Cy$tQ=CGIh z7(!2w!e8L#vJ2etn^TEAdVy~)KC&=x0eg08Frx4T04s%ez+c;4GQ`x>H2q){ls{Bp ziq?&M9y>rATuu?+GYCYNf37ACo};_ZHw!NTsLd?^s0lMA4lp6)BT5D0#xh_LVYfZ; zMMz^jwd>(BFoZh>(Z#IafzXhg*ZenV+>VPtnus^3!VbV`qJv%YJrd4pjX_}D%B=L-46by!@iWSNe^#^%T2hO;3Ul41Y|Gd%5|9h!7uL-PI+e> z{IDV2rO#Eh@$|~@e=W{yO|Zi-MICzLBG?>vm-P=5t_%%sZ2(fVf%H2KAsI>I=!fsA{4XYUTW z02Qz4w?CB&A=MS&vvQ&wHSzGFVKd_nHrG~-M)8fA>h!o-cJqB+mH$=TnM;fN)LRIm zp){eRbSB=NVvbbTJD*S_nyyKJQ@QQI!9f(I0z5wUty*9Fg-j zTtL#J`q_U(JE^CyaPsXX;*vfQv6DXkzL~Ddw_p-Sq$6o>9355Pfn{P#YMhE;=yX!W z={WsC1Hv`51U!?ayV@7o%buzBb25z-j*|vv`qkVsUWIeL@M?`%)VwHi5*4gvTvq-_ zlDDFHYpik~!#ju=(eT!zk}P2VkEpkfiu(J$hlg%ZT3RV-k?s-@q`N^t3F&SS6hykD zOB$rRK^mmHOX=>MdG5SF-`{#%tR;UK!_4cRd(Phb?9I8%Tj$ut5Rm$dz5Lfo?Zg%D zYSj23GmF)%jAVB{9*v7OY5Y7O}Wxn1q(i%guk(k!&a(dly&TSK9T0FKuHDAEyr^{cyceoG7h4 z=u%unHvCj}GE;0`JXhn(zYTn7k<|}US)x&cDDnPEHzwCl;ggBjPGZ-tEo;9Q`$l(5 zbbk$FWfb)rZ!ps2C7lp1Dw_RD$kP{O*zERb@o0xgi0P5Aew=?X$Zo& zPNPp1iNmC?Ghq(}tQszNrS&U&-T}j)9Mc|=yG(0p zyLz=6^?<(?GGKnT41C|Ewh%#l_6I=Cc!Sa918{sqh=v)F7`nvR0>>I94R6N zjU*6xmZfS4{8t2BdWf_O;dZI%iHUr^U|yNo*|CIyOdV`^nNt9Es4xKB3i2EH_(lU; zh-2VzvD5~JpEqGWzrk+OLD%ClFa^f}u^ddzAYa3~dw+<%`Pb0?B{OiaS3Lhz-byT{ zgCGu4Q{2GMBK;UgL?^e=CkA!Q@7q*m*RT84cD?%Wt9r!A2rRzMfOYY|eqiVvhqsu6 zpvEr5omB#}FK<`Z%QmPj2{D_VIovko7kC%>Fs>2) zE&+oY7%142h36q)haBY50V z-yt~MFLMi}pt&B;x@m5ndDDzQE^x8W#AW9Tw~I8b3kyf_Z&9N|cPUtoa)1~`7xFU%11D@+z_GjD2@a05t| ztlcv}#P@bU^;kIUh5G&7W-p)G2fo>vGH~`16cb=%?4If4zw}-!(Nt+6{#7egUcw_e z)96$Kn|dd1@%vN#re1r-TSTAb3!Y3p(GR}UUSyOJQn(*xEE{N;Qs-mzUbLc}dR+xl z9y}L$ClTMUz*WJg)HSXXkmHFND;BV-9rRb|%W6H&z$$XA4<(ymHCB%2h4JStUE7;S zH;ujib#2k$Q+Ky@c9tGZojGS`Z4LaJf5*Mtb|za2)<^mbLU+w+@pFcR$E=-PgQTZ) zrCSxLtL7$k18>VzLy8mmpE%r|%m`FW^IoDquE?Opa)<{&w7v$peND&B3&M>^=lzOP z@|)8fLH?zSC|-ePLinC1a;SDxrAWxym!I|bV*M69>jjVt;=7>nNBRguZuhTwo z#GoE0ADiAg0U$+RDij8Sf0_U@BEys*4-fiFQ8~K$HpM)s)YSB${icV541~@6 zxV&1l?+amufMN9kMEFrStcjTQVqgDP20^M913WkI6hO#2ti*~HY?5AHUT&3;ADjLHaDatN~Ry8m;>^uB71FQ5yzwpz4!oI#Cuo(`jBT{UIr1 zDehF4C5IV0KNmON@nEy^g?deTW5#dScx&iBExo_hc4B}n7;Fk3kHu1b}sw*#7N%&meJ4em^SqPHH;3NxWl8Z@;O<&sF8C4AL&U!X> z<{`$VBk|Lr{SpgJdP6m(3w4n*B0eI{l zaO@B@-Utm1%>XVR(Uq**Y0i;{pn+FhsOhA>@)YKHU*5-YEgdPCW`o8$!DWviaQ~GdR8)d}D{~a0_aMaY&+5>Y= zsz0F7xs4oqh|;Bq>@FDC*+ z!e~h=kIvH9(7tLKJC2iankZYUzDIN=2UKSm+OuE$Cb^{3GHSHya*=Nt=wIY*i#D(h zBz@5ns4MT?z7`fMK74~2@IQ&G1BPqO8BSF-?7o9KAmzzEawBF^_!6^;q|yRPU>rg{ zM~5$L;a#)YT5Y2hlj?(s5yPqo4`r#~U!HukK<%IZTo%0-Ws*$EQ&BughLm98jlM5V z_HA5k$`?oS_Y`eP7K1sS=*3UGq^qh$P>PB)X_Ao3oeHKCpc&&e$E;nY{MyQ-O#HBK zu~wVvg#kS#IN^c3e>3||rFxx^Vy2S*h8@~xYqsF`0>j01otbjy01t?SKVl~P3ELGC zVKR`rDulgyC89Q3^A>6H#YOJ!J=u?kbgGtr=`K71=9TTe!Sy{D2pA#16{~+%%kJ3E z&hM(soqjzBdKUS-7tG9jFc&{nZc( zyI#<)Sy-khJjR|kVld!lrq?~~6^(?-Im%odx#1oxcGXxF{r&eZ!t3GGL@g~w&M_!O z2nDed-O|!>j8(sm^<69-0213ZSAfG-kW4us4=mx<#Hb>eLx28I7`A7;>H{6QM)M85lOtF94j++b#NPr;V|5hoPM#^}nrKQz>tu=PTP;uLhvfs+dJyQYsPuK0RWhdaN zs>II3#Q6ZQ`_VgKtD^*bkUxPIe}?*TN46AD43ss+z{^7p(i%pHOrV5NHP-&4ZNs19 zgwOo69n})$Bf=<>P(bA+L0q37<_)GL8WeX)xR=wr8q33kqK_c$3-&)KHHQ3G{A%7{ z4Sg&oJCXrE>H$$PCe>%TMpdzY8<^f$_0`f&LF#7gC@aAv^A_QM0R0p8Y)r^Pv{{=S z@K7=8`R07;Bpi;gM#p>gPG+`X{Dit0$g59N7->g1m@KciJ`G3h31 z@zpQ!ofQPt5^xD`AbiNEvy$}fxU%nXBYP1KA|@Sb3!a?txL`r|f0I0X-pMrwEY@@9 zEsEFqqg!F_yyur8IVEej8#@;!;Z)wE`<3_=^9~8|;d%#nKf#5doEd4or69a;`VKcj ztE7qYu{VPhHqU@`XY|vn<6qb8-tY0b&joc@$`LsBt&{_sec29^Wfksy*NeMjb5@#S z+!lcJ{+|}WWt}o_tXzXRG%~W+hWEPRE=a6ox~my+=|^S3YSWMq4ZY`|O^Wh{7QYL| zBB{kgES1Hh+`29~!;m=5MYiXlAs2o2o~})<{9~1_+o`frI2{L5tbsF~Rb_B=<&CE1 z=E9%>4gXK`k1Gpl$)2CiJ;J9a&XTQ0S2DjCqQu4e=sHVuX5!(rZ;d|(BoEwDW)?VA zS%EXwrw)Q2Oos*s$tI+Kso_9de~nxA=D8>qOn!CALPG&(N?{gwHibNzVhaBD#!9bW z@%m(@0-+3t4{5pYd|FhQ6N0{D#KT+-lI{z60bD8Mzw-tcz%YR(;x9&U9sNWnf)DD3x>LPyt5?#W5#WsMK zAem(CSwPo_fAu_tmT7>A0e|VepJDqyZN$?K|Cr@F_BHXbEl2Gqs8(;4sN+8B| z4^5UqHm7KJ(_GZhGW%t)3)V4ctjz7P@akJX& zG+@ZTwd#uAOTOklFuTA&k61luS!seKt6Wbb=_3{m~owX(-L4c& zQvAHuomDkIB748zxcRVz5Vg!L76u*@Aeljcv?hl*SyslVK<1cJCpat2Oc>Ok2Z;bYa+)HSIzObCM`I~-I^=AQ+ zkCC2fF|Srk{qLCyOb1x9SeX)j1_UDUG7=}IKELR%=&!FkoAb0#eNx0&rtKq!fMFa$ zZY+nEUTf$5)p=K+i!b?;SO_TDZstqsTT?1vf?rubk zC)W;He^cey-e5gvWOj>+S~P~GXo?A*Cvkwdc&&oOCR|3I!?V&dDdPK}K!4}i8yA!B zVPmi92fEFjk=5}(X#3ll(haEIIX*L{;hzVAl*#eyvw{jzoA(&Hy6(KB5dxbV;nemQ zUac4N7MThD`}(UXEg)LA5VRf&hJY>F1x|{nJ{a_LbT^Q_y*<=YXtfS2!GgLlXwI;n zfT#+8;F&Gi_w!3u{g59V4tcyUrDii=Ppqn}R85bM=U$`PTI&o-$vOdf@xtPTww9Kp z7xr+no2?&(YP|uLU0%|boh^|b$8{p2Z)8-4lmrroS>l_iOhCYdQUGwrFI_y;QqUj| zI0dET9x^dGxlHS6Ut3>a0*5&H;Zt6{>D9qJ67CA{0GHH4?Cb8n0kIT30QvC-FD{r> zu&BJ8`oc9bBI0rth>O_VmtD2PMz_^%fU8~uP<@<(b9sCN2Xy{TyyK|N0Cve&Pn@-o zK%*Q9UDJJ~_GkHe`tgVHgl~Ib*8oJBHr44P#b-|pWZ4A1?<;G@AJ!XT0H2z*fTlQ4 zj6SA!>sqI|2oJlW}*c8uq_wGf^2_r4) z$}rPAUHYB5BIG}#Gu2pctZuzRKEOfYPstzG6hmnrT41|5reC{{cYOMQW&Ic6%Kc1^P+(PB}Hgiq+PpKV8#M_|r^yWlMP61jQ# zNHx)w4d8&d4j}S2r^j?0J5lQi9TU?)B50iiLEbC$uzoet56sl5GD0Ei=z@P*jqG(q z+JKzWx@E7p1eJdTXpP7a;9+IMBO|z)kgTGzGODoc|L#I~;cbaX0AJ|BWymbVLSzRd$4 ztC?tNX{8uYE()ru)b`JB31xCPpU6KX(uIOx;ot*(F6S+UK46UavmF3^-vHC;D4yr4 zshN=9)+YMPS_2pu0=cf|6}V_d{RWu|cH98S)@U`E->-rK0q*yx0o5adpE}F}F}lWl zSDPhuz8>5q23)rOaDQ&xoH`fRfBKxn1N*I{pPh8SE$$tOAUd+Ir4#q*+(_S?gC!E? zZ`guyqc=U)1j)s6{(I_{tMnX@`$Q*8cRtn<5;+I`AHA8@f}O{$_jxhkJ|+yI3PRw7 zDgOKfC%jXJ=?Mkelqb33OV`4v&fC5{v@~|DT>umoLaC}~o zkuO<9$IjC#dy>g*#(UQvlMZRZr2v7F1d1JYeVPVK+6U#r=$|XfRIjplQ%^ITn5UhU z@>qouH*~o2L_;QYL;DI{ zDT9Kbg%>YSr|Ems0m5t7=4r#mySahtmzjn=w=4>6yQG0Am$C?LVM2u4Ag)@Bu9RhV zB)|nEti7!3>#SJS=wA;LSFgsaaO{s36v^M-eO@y+%LRCvVgxlEf0duxpL|FF>xe&~ zwGx1zjq4T=ypXp8Tk{9t&slg7&NZ@gYvI$0LNW&~DPiC}z5uu4tMo^HSZVdX1lH%! zERnIexHu6aBBDExwntgj!D9-zwCyC|+35>hET4)!?kaP^$$j~}*EJ(6D=TF{s(wg0 zx$*#lra%1BseJJd1V-%l4-H}6dhw?#p#*fAkZN-JRJ;V9c&Y@ENYGHmjJJ&kRYOf) zLVL@0^&5aQeD}HooYECy>t=D9teZo7|I`-i>0(hyeMQBHEg19|h7T!g+)BApS;XxH zM5!&nxyL~!GwlXAUsNiW0&rL#xZ;myONF=qg@w{og0|6ofkWr!=}W+A5^;6>(ycyN z&&LZ`+NbI;t)xg8tc9c6UciOjdvAZgRt$DKItf?7OQ8H&IWApm?OIp)k(l_&+1dHN zr5p-CI(pz0AL63~e^2k>hfllQDE$Nothw{^@-78p;1TxflC}Q8z)(J2i4kYUiS{M~ z>+@XRr7va0Lb5=>Mvud0shF^}_-yvuE8o{Oto8 z|Cm>Rvb^Yfy9on`#xUA9pKb4#X(6!XTQ#LFzg?EMN@Dyy`}9vBb2ew~K2d$NZGB+* z$T5sg4xH7vJ8#ypQiQKLyl$Koup|&wK@d%sv7*xJoXUK1bN8L=hn5idviH>;2Ic%= zH)XzCnnJX(#@pxNe2C0w#VvZTZtP>q7CRr6F{D(GwQDpcZ}|llG>0`MH%g zlP(FtfJjV;BCCbWjSdxgr{WB|pr*Vi581p8w@U8xi$niP3lS9jUA<7@^h_VA0E$v- zSJG`4giKtEPyZW@8u?RdmjhwX5!+zFmxO&%C&$WOPRwDr8WC3E+M~uY} z(b<57XT-C4fwAMpzyKx0P! z00q!u{Er`7%MFfZf5AxfT2M%68pKe!E&=b|=V555o3ZcME6a4N8T? z?)Hm`ccDPeI5;xm22@Ny)gY2>aIhJnR1l|CW}xc|2Ey$&utpOK2&@IT%jzy1?gYNV zMNLh5tpM)qpDxkv1Igj{qQKW&J|HcPLfObDqq?SM$^npoe}x|}Ca2-LOOTIk4ew?D z>ul*kzrHv%#oaLgi_3h-wFNq{P(W?;f}$s8-}9X)gqYpHvb?Np2F^h!7_@rT3IIHD zc4lT~`)&k?s3Z869Hd4-_dMI=va7Za1f9zR0|RYsx z1mc!{P>7R2LNKj}i0{MZH{>AIDPI^YU={(*LHW9>_Hjm0LJ6C6++yeDiSe568qFGl zQ@~IF*XR4_FmgK#XVwqb9#U0ieYhaPRF-G{G^?=i8&JKiYZHFSWgF{lj&v`&&_s0N z?0Aa>fk4mx88-~OkaI>#{VDgr|9b4ermo*j=$2&PQ@>f_m|8FH@M3&yOkAp~5_$~x zT|n*IJgorCNRCKEj!ea?OVVm`EM(ct0J_t2zV`LU*2}K4=E~gA<6ldI?S6vP5%Qh; z#u}%4SH)Bk#eA43X(9rjsWZ}hVy)x|I4{Saqh$G&A6#(wkfel3m2F`ZR?OX})XvDr zRA_9=PJc?4M@Y0JS}GgqDb)xdcaUOOlXr`y+@&`rp)o%0%fgl-jf-y(d<`e+R$ifa zOA-3HyVkE!XYBh0tcf|}-hCSn8_!lLnc8V3p#F~U!0$jr6rp?IPDiiqypXK%Crwe) z8kH!Y^vavwptWxo^Vq9SCYxrl(5!CYB^Fdhq(J7G+)je!sp_pnubT5VSY+pV5xQ@`M+Tc26RfS0oy#P& zpyQO6H7#GAG{r8A_Z7nig&nW0+5gQw9O@LArhI`SPD5&eOXcIG0a}V-MQVEfsw3-H zWYv-Lgpg=yD4c)$0f6-Rc5pj)1H7#2xXke@Yo2g zS*rtRNtrB_XYLWB*sYvWVI`2kboRo5b<;J=OFi9J+Y zz=^-BGQ(ztSp#Rq{-Dp!BLW3cLWTvCazG9F61H;PmUs(-M*Bp;EgVM${I3xf0pT1l zZb{)99@c3R4ZZ0Tqq>_P_51PPAM*p)kqFuXpw_P1;3el8{K<=Qoyv_dw)&-5U$Ccg zeY+9){reg0JQMbdR3SGVJp8`Uhub;;-Mogk=R3~$vB}B1dd+UOJtnxPoek^3ohezvK? z8ALtNo3)@Mun3sq2fJUrZYgJP{2N;b4mE5|WigTj#5#P~2Jg47|v%b%aKv?7# z{;*UR!kK}LJ&o?i`6MwdO~K|MOM;6)Mq8W2(9jSVsGGhb4PF%=3xOc;*4VD4=es+g z;bvMy$ULAGp3lBlKirND;>bFphc22Hm3sAIy0Y>{Fg9Lf412B&3MEbmTWI4HfviX4BfZ;*f_*0vP|H#wYS664FJ^YPg zb6g%voyqkLYA#9u>z0A5wV;?NW9q=xDN(v?#4N_N(1!xpXZP$+NySPLpUZY8b(-^z zLlb!?hH9LdQGbbwtbBDcBtyuI?I%Rb=N3{;cH@4!o+JzS`VXC}En${;uu*PPXLcR#uc}-lF-d#Cn0#U0O^z4#xLgK}Ir|grAA?F$h6H62rCIf=-0EY;qy9Ofu zP@iVN7l1eyOQ0W|BiL>O=_XC@I9jLf;P|Sxw)Q@_8y?`SdlLvo(OXeS>7}m=_0r-t={i@;^9%oVp8j&AhX+#h%{&WPQhMR!6P%y+dULUU-U%+DnyZ{WM z3bO6=>K9ADMMYf?!yA+w>c>J6MvK3P>>#EI5h$pncR>lo27Vk(K%2$W0k-eFrhdY; z&L4orC><>J8uh;kNJ>iTfPZQbc#67z7M{q3N-20tK-vP1?mzcoo>?8B_H2TInJV-V zj=D?7k-0MD{p8J2T*0^>Nm(Adn%4M`IMMvu)R&GF3Wd}{aakyEw?zK9cEC9w(S8N!u`0uttDeF-he%RpJK=*=KJj28(hL3h<0mv5a$&lx;}>u6QIvUV7yw zNQk>Y#JfP`wvfPUgGmAtyfjEr%yEDJ$F^vlL{3$t3vDMYe%iDpUqA_G7q0?gw+FQ=GM9A#{&(fnl|-oF>?qmcOG z=F^pkTQ}FZHkvB?Xt2_JZu7Aq%J_r7rY2Fd`|-zx8Y?)5yVwwD76RhZ-q-5sHn}j7 z4F}}zInr`)L{(M2hTy!~vQ7hO{n~$#~Um^Lm6xd%P4*TF= z;rn^*W}C15R`CqvCH=SpRiWt$FhxQi&;2QJWtIOljczyl&|y69!|(+5@p|KZ7CFxGYo$vp9y#ZLkX0?AcnxB zZ3%(4CUEn|X~UII3&450Ky;lH1B4Kw+K+bEmEKK)aM`isn2{;&py6RQo6Q*p)5UnY zR7I0oqV%pWOJESS%q{HTjN_4%RsZ>`KbOwu8vX60XY9e@jZUkGG&CsuWAn4S!uyj%m{;r4__ z;6zLCgtu;N$+BN(d!Sxi3Jzk}3+k;G#L!e|3oeZS>Hyf3L2p)Qz0Hgs-a9j=Y$cBrz_K zvs2N$3F$nXmvHdpO+kQiXz5Bo^{tH!&Mv=x3v$aevX3{qY&Ndo1A%k?*uhz}z&Rl? zs{!duTa>#GGY?PbK)hnAM9(kvLiypWIYKGfLd&nOj3VhugLN5@s=Y%WJ)e4=yt~m$ ztD5uALh;TCszW6&EoG}AkldM#P;d|~@S(Pw-bo+DDp02M%Oi-l{m0hOfzC%@IL#Sof zPIwB7#y z$AmIvPbIC5C-VN`bm>1elZ|s(!(8*BA%BZ17*HNC8=x#JaHO_Y^?pXTFI3f&4N|Pv z_aiMa;fdql9{+LzX1)P-SZq`WuYyh647%?2?~9@5{!BYL-c-fA#qZUJ8F;nrx7s6M zJtQYj%YP&lW4+?hHNC@Q9wY4%yN#veztCl-M9YbOz>KyQR~0#Md!&5~!u4-n9=W^R zS9QI9B`|Io8u?E}o>^13FnM#hn(%^7?-SmQwS>O;k~z`x^l zFuES4R{k@E+()*!S9iJ-DO*&1`8fMDFJj|p@@T8sbCq(Ha_`008;<|vA#1tx8VDVo zNB8HSLqg_7ag%VS94?k%V#r1xO$tuUO_&{!D##lB=ihF7FgxtO+IIoUM;8&6o;A3q#91X%Ho(ROJ2ZoG<6QhLy$_*zNyIl zwL&r=+GI4QrcvU#+s;)HH!qI6Ix~rpu$*mB%ln;{thn_@Aa{!-TGUohaI=zpm)b$l zG4aO+GkdS0MtDi?m#SRuhJ#?v2=C!d+K9S1jHWxhzH9R2pR-RZnofBHPqg?!m3(ho z;aJ$1uI0Zio^8w}D(P=(`T~4_fB%}-EOfb=^Mn-d?vS>8_(H?I$f7szT7eUQ(-Xm( zOkCIIpmB18$nDaE>UvCV?QG)8j39Qfz?1FFDZAIOA1M5~+3=x=6Lo5kAS)1fFry>) z5e^Rz7X!sA!vT^u(;qiwa0(re2N1okzYHF=jY7(fY9Gk6T2|}q5ym^p0~o#7#Bgr) zmfv-_nJ2a*B_SH%E`|6|+Phzq1`;H(E0g#`_eOs)83s)qH;sMOB{@s2_LKT0>h|DH zAtwC|20!9Y(3SKgi6DfueXvX{gP}FF4a_x;emMkc#qPhq>Bvryj%lzSjbDVFd3K0& z;5FGNU>lFUB25k0M)kBw3U}>14O}FlQ7gzFCTS{n;ipSx7)xHUi=l*~t$f`xbXtO` zBo#pzfJ_P{c&%7e7sijFl6v><%@y|Ll&K zHU#Q+om3}g5UpG4S)pKWjxbzmX24s|b4Ip*oO+pU1dNOp;TkuV9ACB~+g`Vj^ zUJ;^nWQKS=yjzohBQ#Es0-ocWWk6C5jPpGmvw3wc<_rtzi6d5C8cFEW{+;@tSOl@t z1HTv|jz}e4HuWfG!tT^#_teQ7B65b&fz*N0Pt>AJ6*_?Xn}LR;aIfA6&w;jT>Qdw{ zLBeWh;Y1A{B8=>j5T);RDK8%Ep*Tfzk<|>peB(upg52wf)ow(;!g>1UhcK}(KPIwg zwTo#Uv0pY&eN~VzRr`dei&T3&D~Ozat`mgc_&Iu6^1ekm0TkF*Dy5bc(@o+ zUd!|AP-Jf$>`+U`YE5qLWPW)4YSEl-u|V9~ZNs)^lg*}YT1C-Tio8^GpOf|?C3sH#)xAgnlq&+TPA2EhYG` zV*rOR5aTDZ2WR*trWC6;%BvRzNEgP}3~Ll7g3-ut5N-Qs_g8k?Fiv5}c|G&LH-)IT zCyUz*b%|a!n4i%%GlbQEp@JkY@4=AAI#jST3|$gwk6|ur381?n>wq zq0roBdSiS4G;vm9lMln3JxzHlUVwJRuLW#9Y_RYD+u;BwN-Oy9vo=U~xrSP5(x1*L zIgMNkhgTwDgL1l4vQZ*sM=?tpAK#EMjaj~`YXB0PT1pF7f|*|4wu|5=cL@jrAs+~n zUMMCJ^eKa*)jl2ZTAszCIvn4%<#WJf$i%C;_ELf5!T2Li^UYvOYuvf^(%g*P(-7SWayF;6Xk;<`=mUqUG@$Hap6rw?Xw1Y!9~3gch? zcQim@M6AfU=OsI$GH=B3D7|OkAGn!1V`{(OaCd3ANBx_dI^pTD(v_CrG^3i5{D0?Z zpi4!5aJgf|$l3U9Nm9^4wXL55XHNzC2DER;ApzN$T~Ogq_r)6L~dih|R3~%k|d4XPoT@R)581 zn#%y>CS|-gp^6yFbLR`2mD3+gN+P=TP(-y^##VfTraVhu{$`@u34x!UniHd2?eo}rae)`iKp%)gk`Xe@>yxeM>nj2RzRf>=#3v$}t`_Fuxy;3ffrz=F zgOb{+?1mWn$yl!+jV(~B_wDuGVmID~Ay~~8rqIXTsX?muV)5Q$jL!qn4OeGv5B0G0 zN}b+}KL9mWVm&3rGzE-R?LX^X_@#yT+2nUo?etlHr0ksPY<SH{a{~EJ~L7zEeFza?&!q}$wt!x%0B4-pcMn>ly5q^(1 zJ&af$3|qNO%S>9SZXVglLM`zgJU%HJZJaH3k@9dmdQzHy;*xEBbUGr z$bba}qda z?@R0bVSWH{<+2z7aM*`H3)h4H_C4C_uV2&Brvxi8)>0}_WQ@DiJ);Vek+u&142aQz zajyw896H&d_JUs0w-GaVPp%oiSJqh0i*^40zulQFoWCJz3ut|=+~ZgpB+@D*C=M?Bhv-ZGg_URl1}X+se}YIr(_=tE*j)~Qnu zhAw<@S63dp>r*vjN1Jt*!PebR*4AUYE>o^v9v1%O)Wo%$C#Wa$rD=%-JSNQ+>_c>1 zGE#p(;jHcXJ(t-aJ``=YDz05q(MJ`fI?1u056kxA>XjlN*OB@)i6xi)JB}aAdkcmC zb>dps+dV1<@qbVppLt+z=87fbPvnUzwmNgG+Jh&i*v^RW-9^`AZB{uOl+%dR7@TL; ze+XdVXU>N&_k-;Apg65<{zA=N3!74Jk&aC`PrqiSl^o z!kQQ7R4A|56&oudH)C#%A9orxL6w%J7F({lVP&^5)Zd^Q@sw_fqp<(mTT@fBZ=t*1 z>LvGnd1#0TK>OFrT|nCtS#+RzTn=9}6ECa>f96ifK7fQTs^#*nJ@jN<)afEl8nfeRR;{L}fsMUA-aQX7g|SD| z;y(&O7xV<{n=8tkp8ZRuxw-#4T!E+AEjej$d~Ic`)%Qn9g0&rMLyVAeBSC~3S5s%} zh+|Ur|Eqxmp=kv+$TJXzzeXQfWI1K9PPEs2I}qn$;-0W0*`bXftRNB7l)P9!`R%|$ z!S4X{hRZ2O)FJaE72gD9YKvH z(RBNKxh{S|BcCXp^veYUKTf)k{oERR;!9?ffY7qWQl33nACb~w_fY((FtL#Q;l%MH z>DEPnaZt4Yl74z}nKgYKDofQL;a7Ssc$g>)g`^i-bm0S5q_LCe+&VW8tM^^^QWyE! zN7r~xJFTSGrn8%%6m9@zNejZ^O&Cgd(>+H!375-1(8 zQIYPBGQF|b-I^&up17^;VZ+h=TQzIVlWTk;y!5@k!XIK4jDZf8=Yi8XS;IJoR49~o zmhMur*Hud8flrYmzC@@YsFH>1PyQK>=KcCgF!PcNdpA$>K_O(Gv|7>X+!U|%YQg<$Lpvn!RsFBbK+31lUaa8-U zJ5tsN&r7#%p?xk@>$eF76QP^phB}6W|`8{yC^)x}Q;o_TTN3q2d6Xenu^O z1n18s0sg@PTS!vEZsgI)iHRZeHdF(`C;_t^m0Rt^q5?bFy;ORv*5^fX!z1*)PkvW2 zp!}WOl0YvcoQq&qFbuk$7*Y66ukIP$UwlbQ?)LKp&-ZkJBsoyTll`j3*&%mCO3nHe z0z!F0>tUw)?4iv(K)w$ zN~!PK;_&b5`#m=)_PJ86tnmNWF^KIc>m+9P#qA|WEm zRx5&Q!9G1Au04dN$C^-B+1nSiwPkd7zrn}HkGyh0CJ_Jdfu21v46JxzC_?y&7iRzW z7~V%Mn-8E(&Djs!9ijezHA3JxT6LJDNY7-T?AJmRd}qdqTJjvE}A3^Jk1P;WCi79nYvMb9?n&>xw5H@x&-5 z;az^N_$L-7CMMZK?=k9V%euxQTX!`8xXrHrT-nRbUzTf~mNpD=o_gE~kt))7g3d+U zVKP>I7J?PotaA@G?53=FfD@0vg8EYhh^D3{uni)hrsgo(B!~w&zy|CjV8t$DOtLmE z5ByN&v=v_M073dM6kmyCo+1aSA=+sTxFH>~pDq@Sfo&zyAM5mB6@Ef>Mb1SA)|B z%B-il59MhckB4tW1%^^Oe9?o~>W>e%GmW)2uW$&D6EIQ2@)?}Y18ugHBdI6-5SdXl zcTu^?EF;FBta9o|_?EZaXM`3$e{=y8B_?}Np#~()h{ag@Aw39(Ixy#(d2I+X&3n@K z^V^Z#E75PYBR-EXi)ECpL4%(@5X23n5fMIEyniK)b6s;Et#3kRN798~zlkHSwGzaw z@T*+PK8t}fIjCqiUTH9!Ss?v;xPssd*=_VF4W zm3B&2*Cxm}-RM~rD8BD1+R4}qy<+nWKb^Xp$jEFq5M5!}Gq?NOeKh&+a&qe5mP%@n zlr3(GAkc$QL0d=my0@ueHh#785^1XM)Z#P178{r$_AS;rO~BEvOEqdj*TlGpINfuwJMpvm`jlnv-*FZ zSrUQVf*L|e^d?k404v~UHZLh!pubqmJJ)yzZzQB{|8#uz)VRS?tb*uNeo=W-x$iMq zPY+8d2uS=y!u6M*V0n^AK-Ivq?*cmAfU@DD(v{yMUHVLVH?p1z3!R!tzp`mZdC$0c zuhyrZ)q(*zy7aTpp3rD4NJJNQ(^Y*;m(=q^0H^T%cWQk?XAJ{k?zukh;9j+5*@tVE z1n%DC%G_LaUZ&I_Fv{%3Yar4JI3CE9szm3{Mq5k)Hp2Y7nqs8Xi|Xm1oR;(-cY1mY z`c{cHK7j{2$7=k|d{npRoI4ju1b>p^2;>su`G|61Kw^LW||j-eY!!_f6A zZ-~=%mJ!RJrOsN}`w3ug+Ouoo8@5unCWD~*Q&OyP)M1##aoc7p^R-xjztWYBOlq!G zlfItbOO!z)%oi`E5QqpH4G5)GTE1&jWPL02IQ24Y@T2KJ2}FPS(t+|oQ@k*oxanHK z;!4TSKbOfiF21e?+jpg0+t_w=Fzy1`X~bPP8mk=jq6^WJ%}+bDF>CT6bJqT_acRBp z!O|c1Xs@W@unFX2N&NSg$=8WKVc7NrkCj3a%?X zIZ^#2^}qk5=5RC?B93r_c!ZUX3b}?fxFAtYa67Enj#|41_MBvh9h|Pm+#K0p zKxj06_oOpp$_Z04L_{HFjvk+EPU(3V4H>BT|)G^c)) zC6oart1nBcC>w$hGd|#e20%CH_*K zhBcc+<23Z!L26(Cjjn9Q9nWq=@4jen-ke9;ySI`tYF{NkysYZVF?sK17is)7=%{Rm zGOpH$x&3aLS~WTut60=^$4#Js&;j~2YD`Ww77eo<8E#j3Sx5nN@S-z#MjB# z;LE9z0zWj@Dix>=a<~t#l|&NTi?^m>RKOBmmf5mla#WNo4yVVpHy`3JS6bO~oOj8< zZ)j-TI{I-e1@ZO_!b>QL`x|jt^TFvkIWq={kJdKqok)!SW&-v&)$RwfgLbvA%>;5J zkU$#rpZf_ve!K>xyMBxcaCf+zQm2GP4MqWZ#1_yGO5=xibGjcHz(Cx+zaV=e7SLbf znpe-4l?fNv0TB^z=(IJD888@FxVgDGN@m<6J_qh~@4%|`E}rm700T2~@#Oh1wUAr5 z``v}r3b2@T#lXP$QAV+8Yi+)HT^9(WDo8nuTevxQY&Z`4>T=rft-a7JudiZb3R8oO zS)Uc}FY3nEcoGNWKfZ@zI<^@?Aj#xuMRLn5*PM8HQO7swqarQ@cSMMIAnbn+XZnf7 z+y9TLw~mT3{r`vW85*Qhq)|i#L=dEnA-u} z4_k*EwvKt%M+$+_L#_|+vuc0($j~7Wu9Dz4=x1E=B$QBr_cPaeQ@@~fH)h`5YkU^Z z!MI3o8`YDjnsMcQ#-+#2HZ`6vlFxC->6u+sJio1E;TnYhWo~FJM|edZ z81=TWPT`zP(!OHk?xQ|lMVFr{41cIvGa7v_ktw_}{5ySFGxcG3@^9uJ%;yp`gs1r4 zgAP#>LE_=|+EjzHJ2N@WGyIQ5nqTI0@s7=knSO|&NZW}66DCFH22!oPG0FS{%%g2vDGhQ`jp{AiRTm5G00QI63Kuf3rj=V5Pf_Qj%xJNdl ziuG13gkD#Cx07>^1;nyyIxxGwfM$ozfxd~hc8l8GyYs2yZV~CJshyq@soJ2UWeKXl zmaF3R?k~uC`o*(JtIf8@57mOa2J7z&<7r!)lcy(M&c419 zCYhRZ#}8-_faB(V@9dm!YinCD)IekO_&jR?m^%$%*B?3A+5a?=a%2qb?$}?kEnhh( z*&#t=20yk&F3PmTt*{y|w<*On+bI}_hVgF}=TNrhVmIS4D<(a|U7s%)bM%}#twjfA zex9#>w#ilIq!;?_fsu^Iz2wb5LQ<^3x)| z*i`8{GVE<6Ja)7Nsbt6QwXFss8y(wHsHV~PLge)__b}|;iOp;7CLI0&SyWCMORHt8 zeNRY+c1?A-6OM(Q_x%bVT(2hkGpAoTkA6>mM1`kjE3ijOi=RnI{DAO9bOFY8WoBH* zsHU?eJo7%O(IwUqE>Zgky9Ro3`D;xyzMMi;>|6(bLscfW=^NBTQ48PIl7xkl>-nmD z5JVwTb;27u4$A zt>%$<$L=cV7ENCIgiCXG9~=w4UP%rP4Ep}ifwAy`cz8nJ8PleqEX-X8{5!pyUGx=r zZwG?^5Yk@0{#e^qZO^*l6jL!kQXBN)T?d<_CN|`LOZfd3xesAv@1tUwi0e z1Ci(f3VjLUpH3B@Ds!)bYLYeyKDr%X_QnIgI8%4|p#r1j?O+~p@hYRO1SngtwZ*fu z`+;0VHsuc~w(eY=yw|p6$**6%;`wEbmIXwe8DK`1ffD)p?XCFw`u!f_tFY;R1%&(| z5cj*X0el-;u=+4^D`|IsPA?jmPL7rQGtxJCuHi;QJN?97T{T&|;!*37{@#@dnPbu4 zo&4)AVZ`!9_P>PAP@WB34Xu2$hB+3RP2WK%Ou@~>#7$diw3%*DuRc{$yIuRG3pfO(5Z>umBM(sxichq36+(hZ%ja``K z*0*PPp+^a@CjaT)SyegnYT4cbqa=%xBGV7VA;lqt0R*&dwp}8-kG2#wFZ`8PJ3Y~C zy~riVca(hS9@b$NEG|r&eJ9bh-kl`-&QcKr16q9&WlL@{Y#G05Gs)h)$nmO6@hVw( zCE>YGN*=t0yz+OA_fLd#utZ~iF39?Xo~37|y)3e(daRoN^VqHK z&?+{!KU~gXMrcV>gmC*M7lnMwSR2R9oJ&33j}Fo$W_6q|H!yIUg%&I`S&=QPpdskt zPFg8WcUTTol0N|$__L}&qMwlkNa8R*|LWe_+WPw7?~*y+rAv=kZwA&%zw9Z}&;J4V z5LUmXz6*hRdP(!3TXs3%S7u}>9H@u7y0>on{5kJ*xU)J_5Tw(xt^e8L_5h&t&^X2g z)jtTP4vZ7j2#eUT9UBx2L}>4GSOugM3A8VF)SKP?zQ)S4X{GJ(u}v~(qA_>|kN=fc z#)j+|p0^7&W=gowrJ*T{=w$fJyFgNF)c_~jz9H5pL;{Uc-#G&=zE6D`*u53cPXoo`1mOFy2Qfp4(s3Dcx5lSg|`Qj zp5o?# z6mUgV4aL%RJPIv|;ojkiy3k@DW+eqg19_NmCR)%^OQgY2fGE@jk2zISHvZDFOHlAS zgZJX)?;phViLPix1*x+j0?oU$bbra#y6$;K53DKH^^%r#h0I8JNd}e;o+%sb`;pwB z?-ZPu!u)q)W$@@m6PZ{0_zLHL<*IuPVB5bTrT}A?x%zp+XE8Mz^4%+-g)t&H;tl8O z-G3#Q=m1eULqtIEGY%v?>8YuEUj%@%4C`~AyM1>7r8Pv~9r{ZjB)P8xbDOEqu&Qaa zA?Rk%%5ZVeygC^zY zL4Za2f8~9A!ABbKW9lfQ$m3Xn$FQvAhL z)(-`>U8Y?Pxu?3R<*8FK!!Intcy>a#E)yEje=W@$xEma(rO&Ju^d_=@Zv34BHx<_n zK6F*)y)Wc3vg+37Rq0j5sy|EApIv2N+^E~M8tz$HA8!nE5=|w@l#NQNWcm_H4+%+) zr^JqER1PX30L^YyIqrX@MUec~CuD@z7{<=JaYrsB4y@Jc=T1%)OceGc73gf)b$%F_ zthG@iuqTY;V0a#s?9K%s_}&4D>c;)`sSQ&Lve&(=sco_rZ>0T@LCkS6{6(`yz8HZ#?vkd&lRS1@Ft=F9y+|wqDKl-px>XOpGD3tGlmn$FWka9R%pSe zC9aHCXuQ+OJ4+hgBx?EXMFaq~ZNs;wV>y(fw@OyaKZ)_`zcKu%1&@j5kd{u}+y?qtwa zRSk_r9jG5xJtc8suDD#V0Hlurc*q8uTKKItLB<0gC&`A+>3;&;-wu!@c_3`vlObAj zlYx#-umNOsv7qg!4h6>Z&c~9WAt5U;j%$PSWkSoyxaeWr4HS1rz>(L&i!cdrLQzJy>C+jMVHI^8=~rBA!pgepruQ|L@eE~feUT3A}TtOMgY0$4z0tz*9dZ+=rAS{AMMc@I-EK)?Lq z9}q12Y8H+m%-0bH6f#X}a`MQ` z!7hXsT$r(ke%xcU!s+T??T=oARc?!7Fra+`dvphCBXM9`dP9%(4VYUs7SOTrj|44m z`z9}XFiZQE2Ev}V7kan5-RmGkmBnvRj?XINFLviVjrba{E{0Lo|hL1!N0na9{ESH~>~a4H&I?sduja z^u+HP@|0Obb@bWsh&c#oHvyZ62kNTMRLP-3`46;lEaF_&fijLGrMa#9dqAbsEmubb znPW@uy;a_}4wzVhqT3nB0A;xEX6;Sq4Ro`Hkf-L3IhR!JQ)Sv&;T z332{Fmb{!dFv6wf2cPy2P|Y-}?1l=);H;FZ{MN%o$K0H>=s(*>p!vWI;`{7p10gsY zhRaXC+)hhQ{+4px=Dz)w+w#VA^Dy|Wtw5B!`o}{J83yqNYtV)5Resxh<*ol{xdYC2 zZ2>}URsPU8sBMivP@RRhV3yPWv#h^tJS`6I7f}W!h7*x;3&=&iA#^_BiH+HN?p(<- zoLohp{w@Ihyv|ZxqxL$R6NMjb9oldIrmV|l=Ob>8L&nM!t`6;`Q8reVxCY9Yu&{Ppa}9Rp zE63(n^INgsW=##PX9Km(drXGh1a0wnUktH^cHg-9zeoyrdLLk5qUI6x*`o zh6~nS^9$P0WmVe$opxy~{M4xIJJj9X_UJS9d5SQ@T#S?=s>+ZeTplGe>E|dOI=yp+ zaDPv>HTLGR{}Lwmw}B~ug5IS#&rA-aut(iw#*?#5|F z$GbJ5r)z6I)MV zgYTm5YAE@+0VCQm3Pu(>`T7r}9LK~`o2O+TK0Hf{sHaM_rh>Zlr&hB}XbM z^WFaZA~8|8et+TI*GTrj4>-Yj3mATQj8(eam5!Ho`)X3_{fwQR-ATXP{^34!ow0lj z9UeeUZUhRoLeRm|#igVDtyPntV~^WbCe5HOasZ<>KkWw(ihXz29Q;Aw;7-Juvu1o( zu9(*Ylll*?IyC`$lk@xgHYp(K5Fhvrr;U&W)TdbJlnoyMm3toY-y6^g4QHgMF9yEk zPfgeqFKzoCfZocVNJ@4`5QcjS<&N|m9PTWfN#G1P()9e<_b>dm33TQ)FoX*O3ispy z(0Fo5DJd&hrF~!Qj=6P*o7DTi2Em`*Rv-ZxF1S{$o)o=KPQHv_I29t?_lXXGxV?#R zfI&`+sUR-jPl1)qoy(Um>!DDn9gtmbhTu`i1{qj)2rq~YgzKs$*D4imLTYD&X!R7x z@$ZV9ChPCs``pu`Stx)9b5q^kC3l>GPB^#nQ$dhW0D*Ub4Ui`$o+viIH3bi&yY3Ws z2xMZV+wbp>!addPD>S*O1%RW}3GdZyT++r#OFx1azYp~27k5)79?*g${#^|XEBKD5 zIx9a*Zu#QAlX0#0=I8sl_P*)E_M)~eQPd+1$E!|dki)ZKy=n)4<1ze#As|V1We$F| zBM8V5>px2_Htg#GJmVL9_t@OLJaY;bG0k0wJ1;4i1hFq*MJ<^9dU6u5}S}9X(`tlD)iUZXC}^IC^7we!gAMhdywNqcr_fE0)PkDN zJWjjhz129_(TKo!{3jma85R40F)%pxQ&EXZZ8Z}|aexqje?G=RK>=?T(!6eR#d(d} zx3A%0!BCcqkAchq0?SJr@$a=&ouNR*?&@eo(~|prU|MJX!IivcZ#Wv3TO9*y(dlPv z4C6k?qb|V7vlMaix(Tex1CXcLO5jwW5p|m2GpKgAd0=mEpR;fW#1ty%U_AB-o@KfB z?X8jvG*9plMXqO-ptgQNC-3D*wMU*kh&pEC3g?Xn)U2$m4igPQK?PPu?(U@zcl0}T;mFoK)IL?o~|G79bJDU%k(O2DE?c3Yi+fU)TlciK7Ih|Ciq*te?1qrZST0aTswz=qf`L2 zW}9cvo|THu0$?8tXeGRXRYn&yM(?iZ7V!B%m>(5+{8H5tKH8J#`4T<`E{@5TKiF3N z1=ZP(&YV}cYNG>KB0oXQ^`-rI^@HD6QJ9W-2`w$H5(AAwO(UbbK*JttMohs7Vjn6A z=l+wo%CSOm%pxC6!Ia@UyjPOb?ZTk1K;N9r-kpV?$QIl*Uym%bKUaMp2eiv-Xp5Nd z-@i|D3Ov%=q@<)tz+b&fLJoPPp!Va(XqXH4NmM7fozinW^g;4 z`@fbzv3);!#yey$%ae`!lM6e|(Zys#UK^}#JK09VUs9;4zl7U=XYTuB%oD2qsQace zhe}VIzgd16@xdvv-e@IJ^AvW>oY(fPnWkD{gs~stbqD6DoTYbUboDNs!Trj3b$D6` zf^j&5N4}5p{%5%Yx5>T$lb~aq}J(YvjrXuSMi7 z?kiHH7aCQ?a^os)X%{7_m^9FO_NEch``(`q0quJ3J>P*#yo7bSU-cPG;4 z;uXgd{VZU_ntS)+?A0kFr&6<@YiHgmsygOQ1%|zdL>zauN7BFNwZ0DN@~|)p%EAq` zLO!IlDdXlmi1S0InG?+i?C!$trp{tZLy{3EC@CYa3kXj99#=6$W$=>Xl>37VclKeY zmLdxU`o4d?`BLBe--FAby~GD_h=NH-0Uo>fY;Y&*3irQsr%JX1Sz0PxJ*NhzC9-5U ziEG4h(gls614H|9z%~NzG#(ZfZs3~;L+S_h3)Q&mAIm1KzXhU{Pk^e-=?lfm2)(A` zDwGrnqB835FYZl_!Ccy)7(8q;fUC1J-5j}Z-u86!;~NM?&#FDlun)Z)~ zNu{lUmpb66x}Yll4XQ|tUm;Xf)zcun(M^!tYqM<o!Z z(ihY25|-|?@H~H#-D_>l_3TUD9a#f39^NW4Rd@$$qD_o3t<3rLH-}VqDfTRdOHH+A0Ltl& zKb{Xczod#Q6APb;F-E*@0W)|oabMw@vnQ+bjvaPoHk~~hT%L%Y`cf0K4#&Q|_+QSH zXx2r`KAznjq_sbcR@p{Tk#Uq=AyOJkdn3R|@%Ur$v?6ER;$W%X?!YGcI|~bieqQvR zC&8&C)nBh3J>F-#m;&81A3vCB4&K3>&>+~!Rm!|L5+f4!5h2b%wi_hBWM$-OQ5YF) zSoDgWBPrrpR(+|*N%c0GGzX5=q;22oN>aVUP5i%ME9;XjT2(|fX0 zcf-H;^{Sp%Epqk04Gz9bKTeWj4~FFrT&fIlqIQ4Sy{Ay=Hf4~Crctu6rjT+L|@Zcu{BK&vADW8EFZC6-Wn6o%H=Zuntb`=`# zg_5_SD(77h*~gE0a)f8W#q4Qc-+fW!42+Ac1SPn*nzHZbegX^I6^zkvK*9_n7) zO8jae3fDnHP3>=$ai-=l;`P3vaNDeSm<`1LN=h1`mLo?Jz*=O@krDb#H7u(X#hEiJ zdf6V5J=WJ55tu`afx=~3=W`iQH?YU`r%&VK7wPHfoPi%2L;zn-qWiR0q7bCSWK7nh zqKMBqi`;8Wgfch%FipZkwa5EROv6_12oRQ)T_@I%+#Kb&g zhCqTZ|BV3YB$dJ;%VHn^oYR{q^n zxW00OK-9t>(?9U1VUGGEwVtT^*%$tn9jTYEqH@#GiJpi$ySM?LOu}C(!Ig&`g5~FK zY5X@CH>5OS)CqU4IAtfD5=Yn%f9jH&2F!MkR{LADkee4vK1Wt!{y7bXtlCDe92sT;Z5w{g=njne9kCY z43&F;D!+Vs>5l+u8?$I>E803HOmNT{Nvy$>^|EGLxshXqb)QDFY_FloBva$=SJ6BS zAQCOx=*I051~&QdIYZ;TCGe&nONKDJ6WNdH`UAm80lRg$dN0QU z0fzm9wOI%gQQH+@8?XjDa-v%~^w2s#|x1XTDU-+-6bfm++lYC*HJ?|Tr z=_U3{qNb$3@d}|*l?9)2j{Y~lFM4W)RbLBreSF02VAOIM*#i{~vSWf%R7QFED-;4Y zc!BA+EG*_cq;JJTAC%s{sZ9mFoQrZS^GoOaS?lY}63B}eF9eMQyj)j6PVa4DnTY{v zyc{&hMN_%!FSkicks!8ZBa1{FK?8r&%C}*By6DRgGml1c`gg5#-``*IQiHgvgB@SP z&5ZZ_Peg7aT66<1TvmJnYVL1c-nL5fY0JBUfT&W81VVAC90oxR8XE0Vih_A3l&D6Ga65ZGi>H~l>g>? zm2McvwWL?Q*X8b0hm0W$?uB zx0-ZfB>I8a=R?TxJ2(*|`W6H3*OjR0_)Z zp;(gFyV9ng#Cz^lO%UtU(7uFeYw6<;9&0*BwyOi>M@k;b)_08pud*UovmTBGp%neC z$U8m>1Vx4AzZpMsGP=roXas&EzsAQy6@HpLT;R~(-~SA-+H#?Uumv{uBf@QDesPs3 zg#3OSiEpIKF&{f7G=KV1yCTP|{~~>grMUEU&RO5K9@aV6DhDhEbpRsvw~f80!#4na z>;^)u-Iu1M8jV31cDFw!$86u%2mLd@%20q5@!eUmc>_ohk-885ZWg zbR7ZvsJlUt@UiJZ&-eDc$)?mttes|>V&~Qkx86L*soWid-r5n*gtzwuEdZ==Qc-G; z9&uWM0Yx&DU%C^Z8x^q-FYGeY@@w!mLFbk2QB}PSuehgd(jy5kUwZfel%WY8EJ`Cy z>Jsne%QK+SNf``<4=HZDbOon0QIx7i9>4==!q@3NkS5;R{Y(!}R91 z-T1FJXt_Ie6*VP>Ig5y5QxRv45|3Lc$8S)kLdc}$WD9?uym=e#xu9FhRi}Q$0}^Bt zd)M%Yga-EP9|sYO>uMx2)=S141-)oqdK(hj{Lb9=COz9ZwkKk(BBXpHXa9QjUHTET z|K*9cT=NYKN*Lp+=`iLhG*pstiALV!TV#Dmyv}%+>^(JSye7{0wI^(N&w~?$y}K9B zWUgA78_M>+HK{h(gFYdr+mvohm^}QOARSR8cA$}0AT=xF9dB5&gQm@2;!n9svH=(P z%JqkxMV7MIK)CZ}`d5Vn71Gyg5j||w2}B*7&%a_V4m6Za?_;#r4=0+>8ZfbBfb-A5 zhG5jgnO&wE$*?bm(nvLy#FBg=o8g!~wn5ic&05e?!?{74AvU%-MAF=GWR~{dcVKh4|sp_7fy0`>X?C;-6D_V50q(yXiy0;I9A@y6d~ zTT9FLlMNcsK$9V8GGa4K2?Mo>^5BcH6Gb{T~*f%FuE7OO-#M`5ZkxMH8E+#b6wn<8RXMLdVGHSC;y` zW8RZ6bo%q?sy1*8uJG}FUmh#b&({V;*U8-*uzAFJsNuAX$q@@Hs}dN3bWXvZ;R~oD zn$N!xcl!;firMXnk1!EKF!yt7eHg87Om4KT+aX8Gk14_`rC9~UpH`^X5tQ8@0>{ksWzxxdfhd;64kq^fj+t?sI$$v*R=$=Da&JhZGw(`pH zMI?#{i!#M`W?L&iwUY}utzZppjT2w)=EzeWDp-wwtUJ4On$|oNPi~t`BTJ3lBt0P_ z8BP*8&r%YpEdR}EHqBTv^n{0keBYH*^@Ul_PoADBe9h(EcOD})u-VS!r^(GC75 zQvaC!)z`o9(!VMt^sxS-j3W+~y3PbYrfIQ6VE2H{pMdnPIWw+NPNxIu4$fOn$``y} z>;|06nIQa9$6&%3`!!-l!dz=R@Lyyo;QYkijJw5av{+W>{ly#BBo-$oo0Bsyo$laX zy_q=3(%HTO);uMrzqO2LaPP_Gin$Bb!}72yX=UpTI}K zIDfgnudfoJf?HFiV->kjJ>y@?hFj6&JjX#VtRXsI$Iiy@Ib$@`)Cd(Ua5w3XKu0e_X2!b)lHJ3;IvBxXRoA!u}EbU+AFzTYEH&j8@0cfExJEw2(ZycaM4z#&@-V zee|qJ1(DDNH1@;2w-T;j53OeRQ{GhOzU6R~EX&saBvnGwz;H5RCQd;5+>B>>KKQCa z3j=Cf37gv;d{cD4p7E9yTKXco`2_XhzGKg?f6)gVQESfmQGiOl5Nm?S5>3?%NxF>c zZM!|jtvuRYZHuNAQE5y|X{2sDJu081Us2XHho65*46}=-cQUGiOMz=KrQE;PvoOrm zWV&={>+>uddTWQGYI_ZnmIK!^uS_fGwndgJA~~zSXSL{P?dxfRAGt)aCWXkD69%_# zUv{+?61SB&xi_0L|4{Pf7wy#%^%XQ1zs{H6B2+^|Ay%59<{ya$F6U;|y}!mHK^E*! zVj*;P?lOVAIada;4yJSG)L-%&VB~g)6IU9G-agDz=}B;;-1$j>P0}GytXLO8k2M}I zIP7m-5vfeL6DqDt)LE>+>m=AX5!)D0RrK)62_ibzIr29$s?xNlu4HQc^pp9n?SJbb zu78VX;*iSudvxL3%R`BR05bp~MtYdE#KAhwU=946k_80TDrYGaEG*tt6%{3HfnmTU z+~U1&pd; z3s&q)ZFU;LR%5)@;RqJ`?{UjQ?whAaZmr0X@bg;|;^T`!)Rh=eJ%MPS z>vOnTp#Ub_WUT-~wB_dFO8#tRB!Dwkr27p4JR!l9Mabd{xkh!+()&dDo%PA|TOxS} zfM&IHn5cb7h=7{6wZpBr8}`G3MgX~8ha-0co)7LzZ{}f)(*;U#1CBpGE0x<0T%N~G zlRNR|p}|$_t^^W};p8)OP_DIu;$jhG-&ROydE8gHs>!5a73~2y+wzZ)HOjz&WB_m% zssRpGB|kra8gKT+eVCGuqB7pS3p3KuY17Qr<`>`xK|dzjVm*K3S{yn-R9ZT97n~?A z!G=ONPy2GpP8q;AK%;)zE%`Y#-Pr&wk5c3++zo@dH)zL@J6{YdH4fTYc^C&akOcVn z!_bQE=?VyawK*#I_o`fhI}#0HKAiB5Ld^W-U{V}>iE5rI<4DT+fNZLd0=qP;PHTYt zO(i(v$3PW6k@4)m>`FDB`}RW4`Msc&ydTNM^J*?RJI5=UY>z2p@nhsd@3%DmLqei* z|B0aB{oj6(p7_TOYRsIaF>{!%Ih`MJhe>YoeePpqrC zxgbXGeO`z3UfzS56W!3$$0=_w6`2@Xh3VTx=-b(RoVaQy*l4}ItwBMK$=}R#8$P2S zgRRf;y=nL@6z~hGO$6x!o6$#jx<4v4`DL0&q^I?7h`-!VfxP2K8-m*Oq$bt}(Gh2wc z&P7>+Mj6L4CeJeGr<##QmUs2 za96FHv+c*_sx{8jXe;>AcZ0iO==2BiqVfa%L+Z4793uS)l7Z7^rXTz{J#O?X26y6y z|K3I=pgU?onsCJT2(88` zN~RnGJnjqF>m)Yy6S`u#1YK%NU)(AGzQ=}MX7<3D+ zwx{Ge%~Bk%WBYo0-!;$J;w+88}v^K+{wro&>|F^yzM!Q`0Kzd%;v8POkU z)>^!nM&}!A<*2=nFr#w6GSqhXtV4=m?{)Edf_8MTN8sALSa7rxdxY!YDGFg@XPd9P zD;aX)fhH81llq~eN3}6NZCJjD@-IqR>Pg(nyhJ0bdmb|`Pc%ibSF+DZOd7A?-Vmt5 zEKI!E->s0Z!|k&|mEIUsqfc%QxWvUi({EoemxRgQqdEV`b3Z%V+q}EAhUETy%9KyR z<-m`Bz^p>fT(rVUsa;~D7FC5JrXiAN_yn4eq@?fBG*9NL+lL?i!+UluCV9l{r-7e9 z^KZV5k->$mgs#}uISb2}!K0dZdWE_hMB!zGzrGtuY+KPnE8(*psK-&bwEIO?ChScC zWoeBe_9759>M|++hj*Z=NC6L!oc}lwzF-Dn4wo?zJc&OMBHl3HzYZOR64Yhnleo1V zTpOY8Kp4aKNyC=@0WP+AriJ#>Tq3?bh{%d<>%o z7m=`th>@MO@f2ZLfBXWWd{V$wjdCeSaB?`xXWqzO0AsJ=Xvv!L6Pqb=LXM-0i~iqymY{Ph(>pep@tJ2pK`h6u^0z zufW8>8|M+-e;5mhK7eL6XW{N?zy$>AAOL^LKF)Jg%^gfdl|6}751$0!bc>>HM=*a#@-pe8kaVm|Zd z5>W_WeQ1fL$75cDtF_8KlX7^j7g#L5R%M)b2dchA!+Un*`!=6-bXZT~pUlFk=6U;1 z8;h5z$G91KkF^r~hfFsV4JV15B_8qfVlGLuE<8Px)Zd@k{Y|-8HtbUrZn^i?x~1;R z>ncP)@Gx)jQVp3vgx9E7Jj#cW+DL0+ZT8wFLUfhcmv?Kj4UkQhKG2|04s{YY0MCnS z#J`jBi{>!wk2{X8w+`?4Emq&%YlcaanHVRnV6U)Y9Mv^ORcfL}l;MZ-Yw1d3DQ=s- zf?Ba;?^z2^cJ=)D*h?an+&^ypj|C8MwlR47tGsbesEEA8@vGmJuU@>cFb0#Y`odS^ z7)cUS$Tktl$;^ZZ*q(T!n{lmrCywa`$Ke$n9bHkle5N^c_|>@8f1Xa>5}d3KN5xRYHANl_W<&OE>nTLLPzrKKfX^^pFG&Wk)){T1$iO}V3@QuOZqdrMZ>ft*4{ zAOx9pJD{Vy#{qCgs@!sZL7iv#{Hr2Zaes!gY}v?b z{QY{g=sXOi%3<66i9P7(o;SdX9)Vm6H0}~0cl#8#$WKr?Z(JA;#3>wVh8+w<%DZ2g z;r8cwuw$V-E7Y?1mjJv9^5JnlWbWJjHcvT_T(9jfdelsK8@m3K&c`*la(f)D4= zN=**618m~}-~es+08NC3i-23U%=tJvY-%@Dh&oTnYAGwX&BLNQDvtf801h#ot8EJ% zUnw8}ZAQAZU&SbLEy7;UwWFisEQrgmKzh#xX@lhWX~>%bdHMO4PnoVYE$$~l4gC;) z9GUobyG@y_{w0C#tvVgECXhfbrR7mmnJlx@#X?=N2UFy)0HcQNKWJR%`x*-5Pj<&L z09h*K6c!dXhu7E#&80w0t7}_JiylZu4^RQNVYNRe-ly-~?PP!+`=xe3k2whO)aWNb z0?&(xyj*t{`+!@&hF;^`V6S}Y- z28#T9*h4{In++|8Z9r-XZVC4I@#8-AR{ zLZhEsi-~M;0h7}kZ#=8Ku5!JujBA25?F!y)ZG_7yuQ6R3CC_1>zp)rx>4$tft>gb+ z0^M0$?>A<_&;sA}7s?O~Y!4j^lFsrJ3e$6#Ae496VZ?r-3mRMW=Z`DzOXEj70>zt8 z{O-MdduYh$X+?mZJ*VlS6Yn2Gad*8_dy}b>cQI4$TSye; zUee_{f}B)B1$xF2E)?^h@S?LxNGtL@U(qy4a%$4*JI6+=RQloQfGw_uhC-*v>T$5n zBxVe`=Gv5%aE>|nO_2)SC51;hhkJ0Ps52Gin z=N$_GCP)I18z}l3ekyQQ%R%oCaEth`Fnj>tkFQKqjZZ-p201ZF@DV!c``Vpq*w`t+ z{hnGg@ECUp1s_DsTe&X`QCoecon!xPnL<6U2{s9M}h2r=5_&|Gw9-p?M zpMUM# z&750C^7QPdxK~viBw0+gw<(pIT8)f%7ZAjqp~sI|@JL)XZTS5x7x7H@`|@%IsHAUs zdy7Gx;8hX{-0j{=a})59tg+BJHn8G2Bzvckp(^d771^8F$ENIBHG) zi4s-utISKBzwPm%>U?kABZ}(c!Exq}_`P6`RGGa6#S_LkEQGMruw?G^c`EUrmM7ygMdR^JqHm_g7cN1X4>s;bakA~7x<~PL=QP@~U@4xdp zpsA4pq~RH&j8}QatL9p_lxw|eV7{{k*_22+my2E2{#PVnw=npkvAUHc)eG9EB zM?!%&2=YN(&5(FTmVa9I@;fZ#M)cI7Hfky>qi_al;jn_Il;$GrXUfmeSW4aJ*}j!t zLnxnR{qvySqp0Cs2C**s-4~L0c^yT%&ualp9>R*Ofvmp-7!`S>L)^&|md;VVvy;s* zj@jnsIT%aRu|wrgq*`|J^)$blI=psxDRgs1Si{|0%Ba!I3x_LE3Ozf|O#AKkUD%=C z%e#7_mXxZrqHsDb~;w zJBut1rW*hA-(UR87|b z(tf65GQ}eoz;7l9k_)PNO%Wi@p3H?RZAD?UNNiN3Xd<_7%|x9fgx@J}%+pZ_`o*Gl z_H2(yeaIV95rLTVUnt_0)xGIlbBoR^9+EZdkvIDxmuZJ|{`}lG zKJTS`#%sHQsO|@1@B(Yahy;-^7&YqJoh&pY4yH`GdmIN`X9$g$Le#a&>earq1!*ug zFKmd@e@Yx*?AYjbanZzgKXSVD--eQ^;xhmPV_pdueY9QQ0q%_`u8|8L7kg*GtaQ&C z;Iej3J7Q4=&2TVdVN7~`V#NjM-#m9yBjztAzLnMLF{?tbH|>6JV2mk0Zm+UivYUSC zm+ezPI!&5&|Ce0~n}#mRcUz?83l|+LF(@H#euY$tKUu2?>}mc&66;X>w9P$4*=c)m z9_ji?_r{Z%H<^rXoFICkiB&A@^>9?VtMvbsjwGg^;=*`8Tx@#&Pw!zdia3rGpI5{3 z)JOX?DR|_&y~PhZ7p3z`|LHCW`yb982)FHc7yWyhQ1o> z=FY^GRf-e5wJvK&k6F6&VOw%?Ot}2asZz8LnT*>1A!jCU$0k8|C9Ie2Mj9vA}3q34xiaQAv> z(L0N$uZ56k-b-&Jr1`{u3bIeeke&PE^8Pb()frJxqfuf3`Sf#v-jJR*_q2-sYwCElaMxl~L)65oU2XwP_Y#z{8muQ}h^b;g-L@l=y^i*sv{ws9y_G8~^a8P!l+T%XI zU|D%0o6IP*05N_;R%M9C{KXY6UQZ<>zKpD_yiX3gnwolY_%E|dspM3x|51s&-uL{r z&}+5qp-J`|wAmNtc%Fx~EFSyLi+ruxO%vBzvse@F_ED!!s;@+l(1(LsgqUL`iK=N9 z0qLifuRAmgu6SLcEdIIiMm1KltlBPIic`>;M{w;dN39c4#S1EVV$Lvkf_gOa8PP`V z-9!RVhPJ%BB6-u~g1M(&6}M)iP9KJyoW+O?kYrvW4J+rP_P=$R=73V+_X=m!Q>vyH zDR{H{Tf8R+v?~wnT;wi1^Er? zmPAfPhNr*2@G7?6;+D9;_9w~|swP$nMO$r0%RvcA_cEE!ti!CDh6NFoIS54_p67Es z&k{WGKeDwI%lC8MEocxw!D2}jy zzZ#XiFG_4=<1i1IK$o0f?B$8ySXDr}_lu2ImC&ZV7*k{(IYD}4Y$$4&VjqUa2c8le z6xeT$c-E-LUl6&BFIgfOJ&#Qw!nkPQ1^2R!-N(Hzs=k-tom`6YX2doiET|1W4Er=2 zl7PQ}wxmGtlE^6jT+GNPm%lxDMzKY`=|k@^Ra^8LrJ;{DD{>{`1P8jp&){H8VPz7Q#DJ z{EXZZDj`W6*UUoCN8OL2=A$p)4;;2$T?xu@il;Y|`TxDF@1~z^(3tA!!MXc`_Z`+T zNCc9En2KSjkppB3J&Zq9FFM#sv_YE0K~Qza=b^$+FNaSJ<`0Yr)#{(utJsoKf4UN; z`IU%vb}E#QhFI15$ZdU~&U<;!;Dg9u^(w=ol1I1i^7H)ut0w16$ zy;J$>y6kMCLVUq9*ifXNaDzSxi%4S35Et^phbSphjs_!x+Y%9YQ;W8ycVFG8in+&q zOHcO932#SJTeZJoY_yV`nu*>FVR5~r73ryIDq-V+ucGxb)u%$D zgt|u%si_P?hT%s@vG~kmgr?j{mX!6jIfpw9>FERoY&%t#*sxuu1det0hyHGIFQWTz zD!$Albz(P)IKDtMChEq5mDcA^(;eW#t|4ZQW`rk1o#@KWT@C7gPvOkRTm)WGBWLEtH{Q2XQI2f;d|84k?$~9tMiwDZh@OANg-8F0`vwtT*RoX`?&RV zCllHlD5#m~&ofMR+yR0$`hHk6J+W38my{68Gih_`{+p;VhV0S`NtO>knC^WP&8Y2) zaxFu>x5ZN(_`W{xp{#8eFdih9*S>HElMs(PUm@qCbOeO~Abvi|aZi#*1x=kkx^TE; z?bg2CGTC;%JeLBs-bQNs|L*3=Tr~Fk&S~AWl?>)#;D_C-`=8>X1A?f3sNy`Q%x*1&c}y-+cAJRsdWhTiGN4~_wA)IT}M zY#NG2*-N&A1b3!Xync*Xf5gLHM)FX9@eHf^-CxRU=7yd_y)en%Xwo~) z?==^m+#V>TQsAU^|8neE`fItC=l_Bg@scZp@6mBa`tN|u>75{F_9G$;J^8LM6&8&Y z?k~wmhO=TB8%f2)upc?ZPmCU}mT8cr$KSZTJL|nIQ{kG{9DMk@%v;|aQ+Ya$mu(qr|J9OOG8EwOXvbfml17%8{dHp9ZMEgrbev;0{g`W&u9ChyK1 zX17eGV-lkoAT3|Y?9A%9Tiqy!Q3#<5M^IZQQ z#@xTW_m?t%FlGKQJgn(5t?J^o9iM6t774PfBS~JKAe!CH()VZL&O!b6M7YN)Rgywb zN%J?1BrkX)Y(&nI$R*4;azc*vvTf~RBsMi`UO(L`9;bLrf~i1_g$uADMHgkGrBMBm zJ9&!HcjQqA$*&W;DW=+G&+3HXH)B24uim+4P^4znj7eF*%RNQjWwMUD|Mvp!!V4fq zC*YgjBB}^?XCT6M7kV8UB;*A9eAo@YqShcY$Sf8)Y&FW zPGZVV}~dP4|yXts=hKgC^&uu0A+tT5=e)Q=ibS z^uq9Ilq@yZyxI9M6>9d&4o8xg_z)DA48@|(Z06PYib~^>fw-#_3)8WZM0<6e|L*|o zYf(YpBO7Yh;Usa)h?PogxQK=jETJ!nmlZ&co-#D}V?lc;CTV;S>a)_eM_rM{ENMHK$3E2nV3 zIK@HCN&L;2Sd6;8+LEAG~70c8Y-w615^EadA z{l$`Ty}iEM0CJ}dRWH7{BD`ZG|SytVKaBdfpXdQ^NY5s`6<0&UE80(h_?|W zwe4wNL9|H^&6n^X&8|I<5OckU9EbApL7WjHHmcWbZ_%uC8ptOv^l0w#&?x8 z+wXc%M@|B?Ffue;q=hdteRSNGsY?}>NRtTfNQwEJB-hF`RFmrMV|I=&)Jm&Icsca^ z`4?nGA&;!??$|HWYiz>Cy|Pm~YA_`m!&jG_%B|rt5*C52cAzK}^sjp<>Xx;?qpD1z zC6%A4xm!UQva|W=(<6Pn=y_5TPmlZGy=d|}j;r-o zE3&dk)7(vDDu!iEt7mg~(T9%P2|wJH+BK1SgCuQkmYuWV#*dTb&3$aeZ=#w#*_E!@ z9PJn=Q-zd-JhFJVBNja(c0)etRM7k7sYeyN>Q{5#MC`fE4Z(XlWfhk+5`?r@w>nO1 z_nhQDIZ-^c?;f%&q51TNW{OsiOW!Z8xUCHX&%F@#j+_*w^SFsk{Cdngk4uRZrR^G7 zDOL~h%EP^)KT{7DWBKLHjYR|V;Tx}bEaA8BpYAbkNj{;m`EHi}4W8x1}V=oA?_IRNZNnmRFSN3b?QOOjorq~uI!Zg)z{_6Sr(2)5>;%f z;Jc^I-J+naD%1T`)*PhasG3qZ`88u|IaSGa>8Z@er?#dpq?DsWF0UU&a{MutlD@pV zC+SLOh(ZRCwdy$flh1Z@?v)(-);&p?G_&9r=4hympr13Vux+2UtVOHWJdN@^xs|$c zsk!fm;6APTle-zWPzQ>&Ga~JSgkV>mPyTt!*wyPNR*KI6JYGIo-MB06F)=Z*UZpW@ zfK#f&ckD>meQXZ$U(ic_F79rW^pT(Y=P@EIky&y3Y3Am8M2$$W3|^56u@C&!b1gS$ zUgT!5mwpY2{r4}6J}BJZ&L8A7G`81W7N{Sj9{;me$O@ZGai1>@GS)mI`LT|M%vP-_ z`_?YSJuDHHiHcl6L;mFa=vBJ{@vL#;(st+K5B`xvWn_GAe_ zC|h5(g^foddjOHjvDGD${rvuC)HD6*1`jm#QMcMmGuM`bX1{jl&c8atqUA65Z69e% zrr;5IoXw(snfuC(B9V^Ng8&sG$DYxXSrJ02>hHC_?4O+v(P0sZ!iWk;oR12MVOW-X z$?hk5_D)mA-D64em8vni+ArDzsW0}Eh;FFcU;Qx8x{`eub&TwdZoxr{+K1v3`JGG4 zcgtTK?w;TtH_oe-6fjc?WEyfBi00R`xzKu{qT@8rTdG1d-%8lo<)Bt+&9;8~kNT0$ zDHPrv z$Iltev$Da|gD^Cuh`#YQzD`RQWe^{GIh~_WO+X-(HUFe)^fI zc>jf0WQJvbEdQarhjM`z8K=GmQDW+%oc4pa^KWu^9volttw?&eFm#G%(l`mL|4YM5 zfcZ;@1IqJd736oR!|k4~lRSCt6lz4^&_6uev&9 zUw=H1teUTD-BZDvj}TiP`*c?4oT6S9aVNzw<7c(6G?eLBc%Ld%mHOWF{S`5QzsGX_ z)Ohx>a=HtNyvYCWs77_-Q-irPewHU)XBVu~CZ3*JeED<6?~l5I{{BRm zolVy+i)*;N^M@upTIovwVQh(Or1zv{c4syhnCO{fejL7sIXOI(&^P~0qm))aAb7#Y zWk95D++HqyD~8qbnqzhCy}YPu3|41xgnq$3%jzT&YtuC^jyWNl7u9L;9DaPvu5ca6 z@+uc*rndIpp3zG*8RNx1Jp#g)RIA_IbI4{Sta?jZWIpm%id>x zPs$M#{)%P7d)z&WKYb@{eP$QxM`i7&(_i>RMo1W{aN(o*kM?5C1+wgdWjjvi>nzeE zzasD+cVqd}_whg1U&;QOg%4`QOD&7!PkSe4W(EwJFgW<|9MS5gYs4-S6>K8ZGjFTP z?=lPFGV%PZZMNpHc<$R56h+ zB0C;!iMiuFc{ayH_yYV__k#Yd}XNFI6p z{|YzO9-4H)f8tsHi$S;VP{<>Pe!om?r%pZAt?(8v)qB$hwu?`Hp#eG#CHVHC>*r^E zg9+J>ki@SB4h=g9pcjDXamn0i0fat8A~u7kx)blSPlEETXP9bOLx_)yV9pHD&j%vE>U8%&S{G6zAhrcTRz?bV2SG@m6n0UvOOyxAro zKH}rz@+64<+?PE(KL#os9LQeOlarJ6r=6BaC%upKoxV4ts7OGy+Z{iQ`bvX!3!Gu` z&lPI&@;ngE$UV{(Tx}$+lC)b9-bbkLErv(WUXd@WR~%L0$4<-DoWCiF?RhiJ#&*_T zY(+7j!p-taz{QiR$N8P^dw4lnva2l3j2Z;@1o|0@|4gx|M#;y;zhC3dl+k$Zq~n^r zs20F=&ZfvMWvOF5NZ!tNmsggCO!-b}UFxuF0{Tn-0vC>ol`$Ys*V8k^E=i2!Sj)zE z@WuCAw*$_EtG)Mmw9sWtJA3kV-sQ^%Q0E*NJeee4H?a?xt}yB&!c%c^5e`672N3n|Yz|ZHd*d%H0)@|sWiq!Tg zukP=z2=Bi*oUUS(Gm$&2qOqyaT&H}8W%iMQ?;mcyx&HV9cHy+sUAAifeMF@GTqPyxn6ASPO8^kGdkw=~;g+oTyn5$>j&sme(MhKcx zp`S0^P@ZUc)R<%(#;~8@+o`<&cKadSkh(VZ)5yYdQ{j6Bl@I&GWl0>u1!1{&IAycPleN4OO_eI6Pyu5P;Q|7LQ*Na0&On
  • fYa|4}-kNyV!+M0;Ox@GN^vv7SV23S084puD`R z22-1fw?D)i6`rbnRsC9-Wifj2DE0efQcv!_rIgKF8=WWbm+H!|wRYUgR3dFmUHqg^ z3O)EqR&Q)RSxFse>jC2g{qd(9g*jPhdfyB&h&Zn|jVs?-H;^!`JmRI|4ND9c^S!jE z&^+9naVfuFJ*qAxrec*ME}nXe8$T=SMaMTT$7{Q*Frr&eRdp$7>hkAJF7Gd6dTW>M zq<^A6go?cDxw?3r!>Gc}5qXDRIfr#dGKuK?Uvrq5&}Q5`?Kv~jy zO9lzMfN*6Spm7j?7e894uy;SPT3lovzP)EyE9)%5+V%T4)cv1cH7Ub41!pXSjtl_( zH!LkJOMPfQwdb2O(2&27hnA-CxsmdN*FhzklbhQKOblqV>-O?v#xgK$l2TJ|=;$yL zqnEpVjy`?*^bD{c*xh>_w&T+5;M|Y4C>-)buuvKoHK1}ipE^?gW#uUIP`1dev8VIa zH+_y89Z$~^0-neRfSRq)o_N8tJ7N{|48-tm>3F3ewt84{3S$C5yL%hRo#r5|P=t2U ze3eG0zduZNC#Z#*K)wjoS|3GyFoY@-00mo=$Bt!pcXvk_so}x<%(w-}kqe{niVJAn z9v6liQ@(jy%zef&Vsft9#o2<(|`WF0*aS;{s#bFcb( z-QO9mp<>uTC@XryQ<~4^lRQWey1&~VpT0_t&8#LCeihMgeioU*gDtTC%EaO#BlZETyo(G7HZze( zla>ha{dg-|Oe$?)L>v(beT2a#8zDx2^e}q?i@!zW$)EgyiZiem7(rssDA6rx;Sc#n z^qdzdJah1*B0wm{nN(AS5~(OGa))l_Z{8`9RYuB=Vc0Tm9v`YAz9@AJtDh8A>VbqJ z_SDh)M6H8X`-7@>Gf%1)@QP@@g>xKYao*=6ELYcR)#1edk&)wtUY9RxCF_-ZbMl8? zBBxdE{d3M$p7-`j6NroJJ!|kK=H%gsto)FvT!Cab=pi!+_Y$IJzWdP<`8J)!qFGSS zYF+|o`Y1@Ydkmceja|>dMuNyY8-&n8`{6ZaYW&XXe>uN`nu{MgA>yjso zb@u%^W4?uE!5#!!e6GxUyd_%|_e3lGgGqdsSG4gz=@cWLJ1GlJL zj2WJikj?CCkZJecJZ*2&gyl0TRC%Lk)DoK8`r)>N!TGXK66`-mwhuHo$j9(_GPmOV zu3&XhQC62|k&}!9sMfkJvCz%H+Wb5#TB4oUmV#}hj2w3dsYL%hFg$vR{m zsbWYW`>iQLQgvg627xk0<+xkN0;ytFjZZ_n5`Ce-@)+RE~xfdVMh#50z`7`2qlWwWN0POELD^H5_0*FbDeAA!S5VWWvYwGCjMlmJ?=0LNm)IXmE`5w@Y-^*3=bkQsE*En90>Rn~p7*~5Ii$4j!44PrESqX~7jiq~0g7=P$#@1qtm&`L z9fAQe<|d$`WfJpBXpVBBEsi_r;(ab5Wk4c}kMYN+XM@UfH%Rt~(fS&*2eJbGA|*01 zGEu&p0w(oTn}C^`mkLr#?J0wcP>M@TY_YPmB+xCUL6MpS`s!Woj)ug(`Qr8Iwzp(h zP?qJ0$;uk8WcnTQOn?Oh1^4`bpy_V^B9wTQ#1np1fxqJ?D2zCJEUuM-QM?5_(`ov^ zlj`cTG8TyxCqOe6`?GI2?5>&K^6)4|kc(Vg_1<7z>67056WrriT-G!LkiRSr5yjz3zk+Fkm;7dqf7>3 zL+ZBFG`J2PMa%jb>;X~jViX$DsiVOKzl@#UVj8~MR-ADM6FTnAQkBRyB!iqpR?ddM zBQ4c0C@0384X=8M&+`*H3}}P8Ts<$c*v<9t!YSnvfM6q0&;3C=I%Bf`2qCL}OkTut zg%cI6mj62qK0JVDn^*EHon$Uf5^ed@yN0^T*d->k=s22%q;M zbS3I=xw|J9i4t>=7XPoN%ZjsY}`c}ApkBoM|?;!JP4?hQna<75B){Jaf8 z`1}XVFgFZ5ra}Ze_CRjTGf?DUV)EHhQSqg2$qp8aL<%9eFhk!5K$2_%OGTU?=(W8V z7#Q9}@6$6dh_q7~mV3H1fj`3)<02g*F0`XOr4+k-)->0U4e zQO(cU--#E&NcS2AJ<`O)&IEG8C;%hG^*X{R-Ch_7o{@OfS`XaDXTV!MkEnt?+RbP9 zpYax^q^MZJnrmG5W(6)t{At4^05yyAGcp2WBO`eRDtx>eQy!&K=#hmkHC z`RUgRu7J@~OIDwNCH{7y^}vY|04hdZHK})}o)Ce4q<$JmRguGF1gn(odyr%|zgOfG z6%hF43cR^%6^Rh!XmW=Xa5LgykUs32afg_xI%CKL;=&jd0?h4ak+vntc1A|u!a?MR9JOaa_*T?dEkOOlehKzJ-!0p!foy-1NZ8{B~*eowQXC$sDm?m(9-cmR5( zi9+z^{rA_oU0AtlgaidM&U0~jlF)i@kGQ>2V)KX#8?c^UahFn3RsA3g`=JHl+A}MU zJa4IW5KwZbkAN6=9wr5-y_M|kvmPa@Q}7#U{Q7SicsrDzh(xAaJgj_2fxzy?GGOn;q_QVuC@8&U^ZKaB zwbN-qVv~mStgUe@3+a76g_oV!mUKoapuOXu&rlY_-7dK?{9mnMvBlEOUW2_kXf40( z3(40XLw{(&SVwsPN9?Y|oScU{twJ52{ov-jKtKKJptzA^+QLx?7)=g_w~K_C@Ko_f zQ$}*KxDz}+O6U*~3jNowwCA=1Z153JNb>^37($5kVBTeba+yi`0Rw54{@MyGF12VJ zfn`_>{vT}s{b>_8X-o*PD}+|E8`$QJ@^!=sFk$Tn4?3Bm?}a_m)s5T)My~-qYznYk zHu%Cd*;+OA_4GI--iwZig0%>sOHo`xLhH}&CAM_UIuF1Rp{yTHIfsDqCnCg##2s6C z-S8LwOr87`1OY-Kbw&^jbF+&VFP65Y^jYQ~T(}cjE4$Xn+5G0s8(DBFcYF>Fjrk(& z<(gk-JkASD<_73-QT9v)!9j?W10(H4`FgwLP51@_0IV_R1Ky)8VOxM79Kdi9y_MRN z!~9L!bwTSa@{U!qcbSQoKu|&u80y`G!MqF@CxsXC4r+38RjMDAuQ|i!dRe!?+DLe> z;BnIl&=0qUwoHj2fFA8I?VIr$$T2n0zD!tqif}m05aGnp*VkvBs-ChSI_8}l4ig*z z(5LepChN~Gdl^dsr%YNgh)o}g`ySQSBC&jYd@@db`fg7U9Nf-8f}YwP05Ya+5yHE$ zpA6`vit9^uxsq-17xh%i!V1Jt@@ z3NB<0dbroYUbXIde|mbF0{B)#zpX`_%-W;0)pT?`6G}?o-uHT_XDx| z>5Rke_)p7H_d#l{v*5k_cXN+7{^6Iy-I>_a1P;Q?d~8I7C8*Y2-z(P0y3Bq4!r%i~Oy6~=52Pp?8(t$@U1LdAEw z_=CRsFHHZ{?l^L5hLE#qZoBC6zx#@}BWu%p>zya>HQKyafR7c-grL6G0U4~Kn_?NJlBdW&O~m6{BX!CnpbM1&?_5<$SX z52-!7Es5V|xkg~J(}Z}fM+^gKTT6SfGw#!0%qQURI|Hmh9&OtrV!CM(Iv3>?dMhhZ@Eoi1_bn;qcTNF&VRQ)iKSFc`W*$x+FXTf6s z`O6n3NK1Al!33iBWJ~Rv_aIF6fjj)=>QlV)z>RqV-t1zZy$vR4`@y{jG;?`Fpq6oW znD|`g;h78z2|0$sK)lhX?}<$Z$~ubRzG(mg`JRS`1_i{Z!s6lss#;o?+FM(x$^gYd z1RZVk_5jT;(nt17nLA`K{^4ar3^{x0(%+KhbZ9@b4~u-nNl2SoB@uzg;sM~AxG}I4 zo`bn~%oF#Nth*v`u_ram2rkT{-IQZuVuBY5)}A0>7te$3iLi3@39rk0dzVeYl;%l; z6DQb-RkLC1eMO*{b{G2q-Yo@|kCJFBaEDyA8N6mw>3ir%1}6srPEO9hU}<~?4uflE zDEIX?QO-?IX*-C72jLWI=+a(KOG8uOvs!oh0_0Yn5zKeB>sO%wb{jmm(7pF)4;J3G zblLM#Qp3|8qoot;yMcsc#_sw|yi(wqV-`&(=;MyF%gKcMCdnWwd_x8=yr!EPs)*6N z8#RZ%)MH=xbvZU9hHNl`=DrBX!OjXCx(!%JSm0hhcI#ig`IRau^GVMt4b4g{f;w89 zas5wt^VSNHqrpn2r_Fq4AMDa;-|%VkA#$^&v^9%Om`lI;`}Bp3?SZb6ZQ)!S1c{Px zq4@T#uk@wyvSl&O}8at7Z;VW5eRvzCs!qkg=@#G zMG|7~rE5$=RW5p%xr;4Nhihmy{!SQVD}FVlpIfZ9Ev&H?`7J(tm+5`0m=;L(VR4cy z7LJqt>)iUhLq^}P_|Sm^_G zg@#q)d|O*v2xQtCChFe$&{$VOcZf$|A$c$9cT|=a7pH(b6E~9gMC}s7t5>8tYsI<` zN5#mCcO&9Pi=E6HVcDKaKZaPmH;?t{wF;F8sHq08s`eMcTmf+2*?^h{e?1I<$xHb7 za`YfQ#f!u70QQU{P+b}qfKPO|3&BDbr~YkIW23Sa58LhBIat6E`#+7xi&Zb>5y+Mv zU|oB~jCpnk&Qy%s(BVKSO)Hzj_2=_rgWympXklI_0B9X(j!H`ow}$2+q-6LM89DSA z({b{?)Hi4NxlXRx-J~|N$#*QG_kMThP!ev-8XSh-0J%*(oT;m?=Z6w)3l>G>47M98 zDeoP70`rZT=%nl7AUzcVn81{ckT-Y$Dyr^*3Wb_FA0>D5<_o!G^)>L!YnAr`4MPJ- zN=u8|c)IY8n2r`hJxqoVMtGm>_>f@*5n7ZMf)Tg*jw5dd#wj1N!OEV@jkx)rbmh#%NZr9F%Qgzp6mE$cP<+Ty6*R<9s^Mf+|b*@5Y=m`tAF+Y zELJgyuQ$X~Md6TzMt~PBSi(n%vxID@@0a7l5Us@eFGI4F8o>fSF4z2xpQdB+aLU7E zVnRX@T*2DVrn@pLOO;sQ@~^%$?Mb1=A>(X&x6jZ|7o7KKnaAxJoNU$O*IIBq zX#%Gt+R4%JJiE`vgU4PZ$OfdvX4V&}PIX%5-&KsHg_aI8`)d#ep^&p5l^5=o7e+DB zLD*C_s!Pbt5fI!9uxsUj)#%&3M5{BMnaRn=ktL!fc-7n76AzZ|eQzl!0(sH|5Czm6 z#zR)J=p6W&)nVP98!BAJ!aAxeY}$OP?N3v1K8%aLLo5y0-O$*~DH7$}J>lV)l}nXm zDu%s5)RjbXq}aO%n_M3`@^_8&C3WrGkfvzyA%x^b-n)V?X;}k{#48eSu`-LTda28zBeFvqcBu1^ze+)CGDvN?q@v?eZCE&r@J9W0Y{VFc%HT^M}gY*Q6wJNC_z_JU7f02xh5;WcfKda(hT) zySl0=OJ2Hir4A}-ozM$p1EQ%25g62<(*@%<0ix2(@@iCt8ow= zehM5LM>10KjNkTje$VeYDIcepjhzW2$33S@9y5<4WKZB6T7%$#ws^(X5^_N5-1O`S z5Otf zW$Qv5*m1oNfL4@YEiQ1z34ECR$BPtExOr1}S8w}oXAKns;ktL}2#ujot+aS9hgN#8 zYtuC-Au_Yi0QI6wP-ssri91z1udN;T|)6JqSlRqr^V_S_+Bc+tnO|*4eLwoT zp!~P2JMr$7sOQ4N3?82og@-d-F7F>#sSIIH@c2(NQWCjDhv1^P2KA13&2N`Zo2`2} zF0lap?d2vqGN~`0wJ&(ARfMxDjh~V3SJ!iNZHUmKtaQK#OHjj)zQV{8k+uR`{zGj6pht6@8G(o9{^D9MMWO@BN(|>z@ z^%cf0cXl2Apg-|DVfTmAp~KkXIUo#pL++(J15mV%)z3(z{r&x&;K0=GX}B*zrc6zG zBbfjDeCt#JZq;4J{Hvt-$L-nQ4J#9G`9lpeW5Bt&ilouSE z0`PkUYE;b-qm}gc5itF<$oTlUuOZj>NGHfu zudLa{ibkSXP21AX%?^h)d^eb>@J6m9-Y%pP^DbX^pZfg!?;2yVJ&-t;`P{)B-M9LT z`KFog-Ky}oUo4J`R8SXsl&TT(94g>p{Dy4M5MyDKz_=KNAfcS}D&#eI5ml%lS*KL| z{P~lsaQB9uUKA4ooicX`#{0Ma63`Z#7w)N1?tmD?v{xZHk*?p>k_(1lad5RCK+xyj zHqj0VSahq^DPWQ2mjm^%X=V>1LV2t<_qTYPTi_Cg5EmvT97rjEi#WTdls^o`GM3ys z>YAGC0HP^FQ^9}ffe4izD6$;b-Ltk%yC5ma0_p1ZX&>++`+j+t3{b%5TF~-9ZGno) z{*ji}-~7jN;6gNUeFZj1BX{>A&FMfml*Pb$?I=!!5I|(U(7C`9nSwzu3<(WROW;#> zg3bA@`%>}DXCMr$dD6lKP$E0t_dl756LFIw{R1oeHki<)R$?5pdmY*Di;sGZ(mDU# zfSsB2XDo}K3{V#yR_UGE75r&37Ai)@^_>}cX_z=FRb=?;-@sD-=y`>-2IIqrR+w^; zgJvJ`&c#kPKTk+h@*M4U_=N&AcnPrCeO{1zHh9tsUd2ojEUdxGz@PF?c->#=S6P<4 zZ=Zm*yAz5fuydS>^)A7J37d{?8DBUo0^oI4AVYKuZEZwudg+ot<1VBMBXCV}XD$!w zrLi3Y?a`7`$gf=U`z8ts&-<+Bp>9?U?qY9)i_0UWnluPt(ybhDw;)k;<-&!VvWxS&+`j<;|=U@&YL4xSRQx1@dRY~cxu^YIEfz-`UwzP z)j|FYs=4K(y0CD1ZO%P9j;KV5t-d7xJ}d8QSENszz|KutHBW6iB)xT)_$0CY2=B#z zAH@e*c0TM01n6snO*T)`sSpW79&y|4XQRS6)+|eEb?cJh3SW+y3ug!AM%^v{?@hLi z#*i>#ZMN%?s}Q2ZRu28KBUE4O2zxbjj};?~_%6t;`Rf-3F$*^ffd3na_>;Ukd6(M9 z?K^H)KKad62Tvgq#CK+Njm^!Ln>a@ZR6M{8o{tE)Ee*3ld>|t<2Kt?QP*NU}Sc3|! zGjO=|OGPH2_GFP04IyzC^jBb@9^LPP=Octb%MHqul#~qJ4nm49U7dS`O$joBI8eO= zq6t~xq>^M40;gSUCSu_p$aZ$Q?^9u?GsS!KN3Axe;S-%Qyh_D`NYhR86=)FS96PD=QzfMk07j}1dZHW$n<||}3T1Gr0NEgEfRw+w_0Hyx{2<>6C zBOF{j2=(cXj#NnZyph^=lg@w+K~1Od0W_=>&~h%Ss7Oq0d9+;e@t1eDe+02@h%qV( ztx9p0UXC8iFTEArY47#DMn~ztFh_6)V^-3!xbQOXDXQu;5<{{gf^`-+t%T(I4&D~{ zg33VprzUp{tBH?!qj5YzHayjFx{*YfE8(B5?%`>x7!d{}HviD*f7@aXbpyqX+g8-y zd)X=-4exD)?|v)p8_RXNVo+A}2HH{>c(2ygLf?(eZp-{($N=_;6%zVs@I^?tSjIx0 z_$7?YkK2u$LEXfpq=SNjf@lJ$s}V&+`nMxicG(H*2U)}ju;xQYA0A@@ih~YFY=Dy6 zf;h>_ydy@xuS>*tvq$qLM2%g9*$&C|YdC1Y^-l*8zO!em44_g6Yiyn~MA{HbUY&;f zXyDAY4SB0npnhuR`yTGCK#^ke-km$C(NZ2cT+o{2p{{OADX65}fwy@b(pJGoz{i`Z z`T5g2-Ge4LIJoWg>(>cCf68})_j~_6v^F9jJ5X3SgKEI0All0l++;1qMhk)c!hY?^ z`|4a5FGlhilwBg^EdYm`LQJ5S6Z(?P&ii_9{55KAZx02&yM!rpc6daf6oB8HjDYm~ z2yGXHV22n4|tf>M{AP)&EMQ(0xJR!di%*H4}LMMh$Vag)3 zS8H3Y#PjJw*Gg|FVMswmh!@)3LEXF)*cLxVg!Tx+49G63*+bHG`v~rL4P=jkumB;- zOn@j(5v$ES3475~xapKI8+_}4k4J?F!06XEHvXOs#}z4~pU+Rtczyl)RjvrqQ!CK9 z!2xFdIMAvLo>CL~)NH<_X88$g?nPE1GnFwy{+Q4$B^>g)2QWc6p->`v{(LQ*godBp zA%u@RKPmaotAq<&7b4W>2%HB~!7o=tMKw33!VDE5v@n3rH-ajp!2l-#crT8q#LDQ8 z$aFj|6eYu+sPaMLFlbZ^3dfWrlsR6IdT;ulf-5*NIAyS2hpP8Uus3{@67xri1z4f3 znuziylB4G0@H~SEVf}DAxBWEzk>}`@{ChJX3w~O>a+_>L7^{bHqFQbHXQ&14{7-;< z6gMciKi2ex1f%lM;;mYaTPXAx%aDL_NrnCRPc}j;J=%1Q79VI|k&567hHQVsOyOH5 zB*7gBH68+f>-RfAvEA4#tUOGghSKJ(tw+m{14vz4TT>uZ9HA+u7t8MzUEa{!A}9p1 z@V$`q(A$Hl$A$;&P5_}>r>_$q2w;^m_+Js<} ztEkrr(txwze@~Qx1Z9lnx9jrq&u0B;WiI(b-z_gfJHf>H0z!kIeAtua3v6NqP2Y$> zs_sK@FsHcpPF9|gkGm-3gCScz8*=^nkItfyASR)Do}1o)_j7^vUYZ0INDMG2a|lHM zi9!dlGb$hwafLA81=MP1Ol+H>M8SRM_U-4ewNnoO62xSh0)QjSuMh-LhDi^F=Sl!{ z{Co~ynS=nVZ+D6XzQb=w9x}(OJ(a^jt&V*S7`>gPMMYY9?yD2^+j15bNv6=2pqS7A zq9_wVzN!B0FZXh52kJ`CJfRXms2fNY5@s2cpd$ABDv$ER%n>;_^Iw2fDdywHZ;g$O zD>_`5jlZ3nETXo&xbx^4TSRW&vE+|m{7SCzs|njKw>O*o=}{wVx_Lkl?nLA zqe6aegq;jYeLKyyfD-7T-ORgrCYLN^_&bi>V}OIBN7SCz0qu$Jxt^s9yML+9;v1baDRzT+d^<=AMS4lC`{m~aGtp#UKuK!wpP+tDY7r{ zX<4o+MGmGwiVbjUOxeJsi%Uq@)3ZB-(Z-Rl(>7@@Rs_ZL&5UJA5S$J{2Rsg_-vQ^% zn$T?H{@uI6Nj;XMP_n%V7_+N@WaH{{;Jh$T;l)&-02o$LZK>CnkA>Dl=t<$22 zfP5^b`79a_3sDv@=c=IX9tG+wA76V{shizzf*Ro@Iq_WsS~wXk5kvxn?Z6^m#};Bh zVL(br0V7LaK|vvv3@=THP_AEp`m6YqoTX*Tb!bfhcaD(PA*`N+wlU#tX6*#UtE|^n z+H=6^0tlrj6fT0HK#SGc8X@LUuUQbQw9 z4ZrG6^KRb}WOPjc=Xng1k{uHJZ(qO8rec-o7J$TFY)}VAz@E_XuMX187od+q46G>; z;!X*QkYIU8$>3gRE!uxzr{H~;Y~t@=fscB zMkXoutOwAUL7M$HNVm>IJsz?R?YC4^t`Rt$W9lqWd*rT!eJ2MlTuY7?FEl#?X$d)W zc37AOV`Qr8m=GaH%1A|Ok1SXj$6}Bg7GF{HB~n#Nvnx555GjG#Wj`X2=ay{I%Hg3C6~vMdNetakSboc=IT)#N)E68@6v_7);{Cfv7} zPN2o+T92O+<0kSrdW8Jn^QtYeHxlggd7IS9=pzwM8!1JK6f1cUDGJ;b0anM%d^;iS z;;xn74~6^2An`+jVcDO~5@eI3!#*sM9gCalMHi7&okuh!3opm9o=5l7;snC;kKfu} zrwGUMQ_8XGjr5QRpk9c&x!zDNEjnE#iO3MIcw8)ekr!lxkYbM&ZQhPvQtHIy*yVey z#L`XpK|y1+p2hC73;@x}VHh(MLwDOHv7Osmgr12Da0Yrx$Sm6~SL0=$R)en*a?k?| zdZjWGC^1Si`8$Gx+js{}K@|3kO014Z`0@`c-3J{CNNTlSrh1Op(i4F@qEZ1{%d+QH zFs;WxD5_2`s^e!cTnZhV&`A!pK)j+UFqW({e@@^_-+sZ`j$O4kG;5l2 z=-#HPMR4np{Y7k8Mmg^Ar*`*UFb~HJiBFzc5yYA<{%VwsOl!B56U8l9TtWwICUgEra! z*|Usmh40Y2>#yFt$vJ`mNgR@s@c=d{CTSInJRxxBz5)8A^Gq{og4*E)>AN$_6+H1}_vi<3TlY%MDhys4Z(XrIN`&$vMeV>Ob`a z@zx|XIJ;zZXNVk?MkKU@zZ||`v5Aq8m9_zCkpRglAR&!)>OJUlE)Cp3CXvj}#K_MW;kdxTF;14qYdo zWgrzEwtcyL-A_|QfVJuB;^6lTD-28EA-x>GpYZcM7W$Hz`OiTt+YayNpYKb(-SU$m z)%QECQDM3BB(-7CK8-|lY5!GG>5p8NU-xVm7f7#-$KNX%3w@VgP=}W7b31mlOSNlQ zbKgoD7a($w?BMe`8aX-OAdAg23!FmS+2x3_HJIM)|2;{Fx#G4XlfN)mx(hAU2$s&)@?i4EBtMja#TK_J4|D0<}zOB6+ zI%1mwRL4v7hp#qI9{n#!`V7Ka1V@cH3Rne7V-wV_bOVEeiwHR<`YZ@_K(50QSNaeg zPWv@3mqmWCjR6TmJ^p8f^EhK;c;n4*5sm+Dl+3^Y^|{4q8^j3H+i(Hy?koIbY*U8# zX_YZWH7ijkgx6-r=RR59+q_m+0U!DX$x`?lUAM(C88eyAt~bDMNS(A?jGB=cQu5cf zGn2xyQJZQYGpGY9oD&ki*dzAeH+hl@Gq!GZ_aGhl1!W)Q_^x)_6QD{H`8DfIuF@kX{zx{J4r)2vCh7SvVYiw!pKYA=C8fZ^@Uk*2oQ#D;2K zl)#Cq;|MeI5Gh18lKsjxl4S)PL9aUR|Fi&KtNs4{zh2SmAr6SbmHs}|m_Pm_qOp_v z;J=|b!4KW@Qpr@Q5YQJu$rj#V^GHpN2!U>wB=Dt$ogJMHl4+{M5O(aWf3W{-DP?tj zHJ(a$Er$Bon1fl6yXp97|Dk47nNI zEBNnMQ4YiDp)sUbe$;`ifY6~X2St^yKyuUVgR%dT$mFYVLMuHdAYgwA`v7>p?{k&l zBAvCBl-@C}`k0G;XJtYT@LTPYdY``UjV+f)o?OU@yTJdX>FwJz>}?tj(wt{!(I-wR zJgDX8erAk5$?@zvqW~6lN;T)Ps-uA*uTfahvCtQH-F*F`G7Nh*)HgSVuemK9mUReq z3=cg@EKNvFEt!i_OSEm4`RMaRbls%o<3NWKiP8rIh`pJ=>nBCs*G|-W-qcT zy^R-OHrJ|}s}ix&*i9@AhIxeuH#be6>SaMBLcD}hL}ZBqdCnCIid-6@b7!6Z%l`M9 zAjQ9vQ6a2&{3Q!1lx+9pFk_H=dK9701~0w;-Pq>i5zipQw8KQwZx+ge~+&B7YWrnHG^}!x7Mk|qb%8FC%h_BGL){mgh5L=U; zA&KfM`|c85u;6tX=h$jBe~q_Q>rF^j2%d$=NpQf+Gwa>IkA}Q6ozR$f63W$L8Rg|Z zTDdJCwfQasy(lRIs98kJbK68Be=p>0ob5wdAww8S+lNuK)q+kjhx9y#dBhIMBxz7Y)1q!4$#b*ed9!@HhAABbV6yT|4h_uzTJGDWM)F+YNts=cesH+$Gx(%!JAU*xd__`0 z7UR7FztG0g`=Q&q(mEWSmpHRX)YP!6E^9Kx!|dWR)J3I{EwBukJ|XI@-OCPP`7lK7 z#lJXm^2G`HSEOGM>toh(GuAAAXogM?>Bq5u=y*5O$?PBV-L3a~P#aOTs^$EOso&{g z^-tvRlvaMNxGOrNZmT#I$;FPD&tx=Q#7br-3@>yk z@4@`Y60qqo>(hI8cQi0A)`f~>;Z@H-zE;v_j+aKAH)DP-t)FOZIb81+CA|_Lt+X_t zLw-QJs4;`u^om1)(1iYwcSsI~l9tTycq{gE$!+tCqEmj2UW zuBx%CnZ*>YV|;a6=+uV5Dq;0PJY|;j@p*@{y+^0ba)h$BWHSPX&!&x04B>;Tn!4@q z>CLyR?qkhY4mZ#^#ks;n5#Ei?L-&Ac^Q@4|ob!z|HB0ls@G1PNm4`u`qerw!oMc-E zdRXcE8Ha{M3##%3nK`7>dAqEE0v;8*o`h6Fz$2XE?BEPbY-9a*dN~0_F_b8@3yt6_PgDx zOwNXpok!&7n2m@<3inQ|m|Gi&N$#g7o|U5ZS;-*Q$Mnt-&nG2^U7y; zHx$o54r^P}5V%o)sFjFo-z3|sJXv)K_vFB?BK7PtIj(Z2V(L1t)aT&xcg|#G6auVv z?}|<@J3m1AYT4@-+8K~|#Vplxt!13KNg7hVLUSS0ywZ+l^i_8lwX*&=rtEnA=5DS( zzC*cj@l0b|^-|ybj?DNEl0K;uV@HPHOAb3oMEE}(I;a+yXU~`zt>B+OA3odaKKGbC zzT|N1Uddr0Hw&iTVEaJUexry}pjPhQ_Z^})3@Rt2Wdk^VKp6eq$_~?8n ztL$(%rs#5bpR#?EzbmGQXEKDAGJD%A>D|t)YP%~bc$x)+t(!|14M5-ju~Z@q?~<~= zM1zYYS(_iHhQV(>`9e;Ho|US#xM~yclzoI3_Qo5=A$!*<#@e>=>sj0GZ`g^aoDM6U ztiJ@lXD37{8WZOiq_@UD?aq8%!H?82)iz*gLqD*-5x*;;UtQO49QtL)VW33(i|MVP zRo_qXn}xecbl=SfLfmCFz75|#vLoKLtBLx^_Os*Sb}A=78FEg+?ZaGyjJCWhS()_A zRh(#eMeA&|abVchiqNUC)Q`^!PbA_(Tmw)+oRgKxxo3J`@zs&C*nScu-#KgcI0=)Q zV?3T9TA#@!#big$OsV&g)$fzL`;v6-MxE9vq=7m7ddf2oy$1W>dGV@(>Q%S#iHN zoAkI=uePo7y!VUvVDref*0+zcs?>k7CM$%`R&Mj#t2800O6XD&cx%Vi_4-6f`z&mUYA+xD|PUA)ow(S9Kg(NkWw+~GgMtnmI>+wZ*W@^r2Rbr>&)$i6YB?a#5%)}LNjLP|4bePHKTzxriFYNwh&yAw>`ySp>evA9Siz^LJw7SX8 z@{YEyo|@kJ%=q5ib@z*}>a@B)Rn*_mVs~cR%5bD9+B}0~RG;Aqj4R3153@9H7~#xW z3|}on4^ySlosp$kF3WaNaAhi+tYTj|#H*&!rejivjO%x(;cud=foEGVm6gxLy=ysg z7M?ESYi{8ztL=*UI0$9L4bywIqelCojYEO&+Y&Y{UX#*{)kcMO{N%VQ=A*W++lewD#gzFafIiN zSHPgat$DJUkwBe_H=;TDN?rRzx+dE=in0KUW)uePd(+jLe#bl~Z=ic=Y+t5q+{ph` zniFr)#ZRsZp(1aKz8yvI9tM59R+w^tvee|FtzluPWcX)W4h7H9A-%)3}g4!d2}`E3-RIKdc_%9zq!6>5vlet36yBh##JZ} zj_>$hNDy;+IVG#qwI}!^+2G3ZmhY8G#9n$<#!mQvV#&K``+9$YM6%5C;f`l>5Q)am z%*MdWs3>`3n*1SUYt|^y>7?;9l*aoBY>EzthF{_h8E;vM?5-IoiIZX9-%~*W3pE)(6qAZa!gkKWs9kci4S&aP{M6%2Bl9BM;??s@;)~|NhTP)CePG9w5L=&*#mjW z>U|1(f2J$S&5gTzbPb+_*GUhZFGl^`{=5B;3u1_>I!{R|ysOoqZ=kwwyNR)+A5+{h zKUIelp50Z-tq#u5R6t2Jt=Yqz}pVnrvqYit5OI=&L)x)XaZ z|EZ;zOqaanGaLuGUWjA`U&WHBO5@SRI~_`EJNB*zS0=pr3MZ*!4ljIaVBXme@r;d) zjmHbS4Kuliec0M^t*`SAw-?=sxL$S`u#ELiQZvWBXCkYPk{Y&amShtn@>BUnD&yH2 zdF`ld`$Dq>lBTS;%D7g@d+1g?`HfQ}<%qp~?GI$vKC%TRVFl z|GfRS$5K6#u8KEhMdlnNX0zWq)!r7bwGNBtum3Ld0^VkK{&CG!xqdutja_Fj#f8~= z#Dgq5f7K=S%>=F#!!@Hg0@$gEUA9 zsGy8iIuxX&6qJz8iPGI&A|axJQVIehH5wc-atH$?H*z$RqX!JOcl!N4&+qxY$NSF? z4vzb}?kmpgjL-SG?$fHUoCKPB+HCYf7g&9 zYBJpZV{;52O%g#hm<%_F=LA;imn_K9kyF&T`$|kfx})^lu@!InBb*maU#4}O)F!QF z(_OTh>WV%~e|XY*Eg)2CUQmdSY0%5~B-f^AE19FpcIFAo&ow&UT|6W)#3TUFIG)}b zCs*ar3(j(lSeVJ`IKB?AF61Rtl8c{1DA9o5huY1zxNce-cF|5gx(uybRA()5oI8|> ze-ZP0^YqbJDQJ`jm3-R3R?(+2h3U!aECmiM&`BKcB0fRCckJ)s-n-zx?Dr{iRoUhB zY1EXiZ@Rz0UKe&JxU01AU)1$OQuLq)5x{`ixfmBSJX_&>t3f@!aeqiXr2!8E<5b0G z;?WG7_4pB_4-z#+eP|g*L37AgXw7r-XR`*DO1%8j_r%85**%_VGT%tVTMyP$g-3R=jxUW)I&B9@8q zhiBVaE-km1Ca|w?YT+d#U**|RHyClhc;6ycjwN=j;aZN{4l)1U>XWnmnhfDzb4E#I zmF|bnOizic@Ng<7hB=hc^~c_bt(>cpsu2@?XGMn+FLJbjDMrNBETV3io6gIOjtD(V z*}Ean+Qi~h8Av025te_tiP8z|(rd+%?T1{_yL1&~@TmJe-~1bx-3ssd832}H@+K{Q z9!w%9n>ksItEsIivmMq=-*#=`uWLUZlbrPkjXSzFIal@yiQ5U9GAYGV1$KEq^rxTa zcfK}`zZUwgs6{I1`uv8dUpw1U?oKDRUd0NHXJ6(CGO8(zmWr=&fB9D6KMO7w%9H&% z1z^yV!>hRGQ%oc2FsKKN{-D+)%f9}3-}^pqW<&Vy>Bp?LW1*}u7$q=z(Uzr0n{p(i zsqLo*S<2#h_5E?N+f%gC#m#-8FF|;Z`4lG>wM2mrT{EIa4mCHBYHHtjGu&Qjyv?P` ziI-P!V+?(!a209`^c}!iDH)F3Go^KnUr?8@(Q?ZQL`Z;Ga|HD)cmqqBYaFWA!*qlk z4>gBbYtZjHq~7t^yeXOBNQ$GhN!qDut@~;zh!JT)bnR|1uw0@51~D|5ZjF1 zrX~w|mNEtoR^~11QUw2)x`tJv<&H)>@K`n5w#J$bFehfUL<7N%|e#zRB&xPTWUOU-of(3${DU87I4uHtpDn26$4k6&&N zWcU_4e-jfBi4x^jqKd*>Iz49iNBeU3>` zpvT-+BB!xAm0b9;jf6zC+gi6obQA@K=wj6bv30SH!tE5bmE}HscUq@d&&D zG@!OUtt41Oiyj!Poiv4vE&X`e{>L9vt7Bq?-@+oY)K@=ckwD9!W8IA= zOoJV9onlvMnk6SCzOxrcYS>^Y8hRd+87sBN6P!feNac0C_BE@etq%|Hjxq8;pTsyy8LX_X}t}?^{JGSb@oWDr6PQ|rXuz;R_JD8wr z9bI9-qxtEbYnc@1DRsk((-6A;A0bx0?Uu^jo8R)vAqcB$IFA zC(@14^9q=2qU=@wY?T=oy^}@JCB}5t18AJ^D=>tB;pjJXvh>GPd)BOL9K36_sbol- z+wym{JTl;!YWsyJC|N=<|FW)WsXD(_0xRZy+b=cw^{cANFwUm0iZlc`hi+j_SL4zw z>q9<98PVFqsFoOS&T(Nip4t5E`l3L3GmChli_3Jj6=1|eo@xf-&IlIwR2RrU>@%-i zu(X@bPH%tRxve-=^h9=B(-8&dK_|J2NO90ys#2cbaUqLH8k(;5q?)y}gz9 z^YPad{((jHn*>n`r-`US-{5uMa}NED--%xSVrr#Ao8=&kTjhcvl;?1Yd)QXl+cSKd z?7-2U=B$if5LlbR)ZR`=99p0>o3=CZA>hD8GvbVG-l9czCL*FpPdU~lrQvSoWbQG# z;p5}WfYe)NTzoO|xKNe!D#iIsyWqTzQz{ebb3FCN?>~_00}+XVB9|@_&lk%I-~XV2um29NB!vAN!nqk)td*&jotqK!EC$JNC_*rfxuqpsZv; zB_PytVge0uJK`lpI3Dq+;d#NTV}7ARPKaR5m=6phFq5Q5+yGS=U5;#DQ^A7HCaF^O zsaFWiQs%3QP9OCUmgYEj8a1`!L$~K@AQQ2xWEWH{bWq2nyN5ad7#(T|LVZ~(6~PQ# zDu3{O@CkgGfbgzy%1c=(^Mq!z`%*R43gy4f&KYJ1f&{rA5mAoUk9rAiJ5EEY z)Rc<4S$8RF`xRHLjvdC*`+O$>ujegwp30e#%nynO7aWp|vPnVTlN>H7A~94U$- zz9wy{i-q7tNuQBl3XM;YOkuL3mE2iD9Ax$i;eJl7*m{mYpxo|mh+;!Qk@g9v?fnP- zZlQr2O3EWRi}!bH&@IwW5<@;{8SjX0>>_SHQ6!J`ZD^-;;&Q_aM)?WW(CnoGOF`Za zEn_;kAD4_6F4JqR-oU2}yZDq1i(^&dnKl7&2%zeX_5@z@2z8zx%ZZ1Push5&vh1`X zqc~Zvg;kk$VW<`_gL%^szZ(&RV*p_yPRvbu z7$#X<-d9W2CN?=-#FN33uM-+~8h-kt&#+;5Xw+!NFjP=CLgMX7K5!=|c011e+=gkR zqAwlk5zI)#oDU+E5E(dZwwy-QE=L&TU}u4so7&TY=F>l^rnqX4qy<;KW*%&FrPIvd zN1E%7_l7Ou&siJrI|770ULnyR^{3C!VBoO8_xz~$U|czIi@1R7RiF4$0N-GdTbc*H z?17^!6w&k5avD^#EY28l6Z3NvRWM1lQV!fHPUJ?i-DQ1-I^Ej6-zsskgPbp@#(e3j z@5%6nb)Bc(`q*`jlFn@4={Z)VlD-Gq#6M5kLbbkjIL40wch(540}G>NLorU3UH!qq zuUfViv8}p^s78*Gx8Z!z5$waC3GWeSX=j*&oc_?BjxnDur838e;mmhWB`%~f)rpph z^HUpH-OYdFn568NLofjm_t)}=m5I0RFu;1j?yfd<2bR8h%)-2U@|sJ>Mto^s(_m~h zPa+xoK}3WDN1w5O{vr6>MHYSWRN(Rh@UmpigplMEP8b7)*BG>kgU<49@VZ<)d8WlK z{2+h%5&Yh-sJKsVvBM52=({iIxjP@kOB?2f-Ryr;SXbmshZU zp7Wv8o~{IdN=`6SMotdhlm7BVD~JEG^1=DFmJC=>bDjUf0dVI$aXS#m?MF8AOu+HF z_5S{0;vV7Kxt%=QFqm1NhtiRfpqQnp`1&}$A|^G%^*;Y^dA3@gw;{zb>p$f3GEAU;b--{cjSliYi* zb*?GqrhcLJ)-WJ|DDF49{IzLayWS4({-RJj6T9m{uy}Z!vC&8fDDfh>4Rk{==)KC$E>Nir55xQyoxeZGV&&QBgc2+ISD)Dd8lIm7JUEm{CA)1Y`NpCVzo8+XN@1#XS?1sB)PeC`G zue)@q2}3~Vhf^MMM8>^O!0TVz7s-!xB?>p&kemI7`@)+Te<{&;!1U7EW{DcQ8Q%DLaM)3CH#t?;3O)Hatl8z?~rZ=<#u9QHl>1`MBHc#YZKw$ zGKmuJ**uOhZ$=X^F*8TTy)r1f?eLg861)0w`?U3r^YtAXp!%`mv43c59PF^{w1ayw zuT!y+J9+|-**`v<==MW&aV>jvZbmRH$ey03$)85HYR#SDlP2)iP}b9Pow#-H5QKQo z{MOldzRnNa@YnFmlFmArjIh#5T||P)2gSU0P{7jGlF{fgn1%_VOjfmbCbmZeZyuB1 zQ`S`4WJHF{rG&L5ALC(*LM{l#G$kn(F2yHc3A~oW@sVFBKGc8dlgJVe?`{tU4=9#0vKFse^>&tn^p{=ljk)ox#BVWJ#nS&F%xx?yChCJ_mN z*Y6Ub6!%>i##DTP2T)7_a~PR|4sXqOuAyK=?XWE$2l_=quX8#2$H;->`&BEcFg6LE zXf#F)=KBP+E;NbrC~msMJT>_|3pqhio%vO_Y8{?s z0!q@|QGl6+uJ7wxc(B6i?!(LcdxSq-N00et-hLMMq+Z>WQ-~d3{oK zmP`*Qe5k$M$^n^Q?Jks%H|g~_ev8Hr7d7Egv8QP3*jsadEQv{%hLs4{?Qpg|$6;2` zJ<0dp4yEsWmR_8a(J!vMxLVvHY#p8b;qJxye(bgilm&G@#=HrMgow(M;X$i9D?V+V=roU!j;;)J$G3O&pT5N>$p z_Ru7+M6z%h&QwzyJ_k*)cG3w?YQDXcvHd&PAF>#NZYYpbT zke8og{aVrhnRYQhgUgd9#-_76Hr!pGo-HxeaM_kUHSO3uzS+{Hqg-q+(gAa@E3E2N zGsJ*;9gge7)b_x6b{`nZU6B^mFgwFY-t8xkrh=v!SPT@O+61GIgICsktoE5fLZ6ps)GY7yMwfB zFb+R= zXZ~;47nZVI?Rk)3_po0;)7~LFK}XA&X_Zq?zGzPk*!d*MuUdYe(zQHPC@f(1R_yPH z5! z+EI5w|01tQ+;)cDDo&mPNITj#_VqukkpFE^K*~iTyFhn&HcSKkqAx;7k5({UBlC(aS`_Df7 zf1^=*=b-y}bYVR~|5oY0?=+Ndnj-t30oz9&l6zXkNEx0yxc~36R-`oinbOD@kRg=9 zjF@|DrRGTHC5a*tbJRXm7g{<9d_;sI(P9(MsUWFnggbKuEn}Mx^2-G+v(ed~3-Wb^`*0NaJTumP0)J`7DZA6_Q%T|)MHfrZet*|A(Rp9adc8*L zew%WQQsc4ammg80;O2{aJ}atB7SEYBE!{==Wl13*i$^VTqq#oym8`W+98vf|hiuCa zyY>t(8i!uVCnl5mlM+}Z#7arWMC?blQzm4oWR(>2wEc}NOB+x4t*Y;>_U%GlXdr8wgO~~^EoNDjHZh=xN{vT-?fw=?f_d*0vuo@-tBctXY{r7wUX5@i1 z*f}8*bjNPjSEd@~z2T0}(V^ae=V3V{&`W5|6e#dI3SD})+$8d42-p=*U3nJ#UY&^m5?gTG>3X9@nuEKaKZ0fzRB z+-idOYkK$%lVkjC0SGzH%9lt&N}G$sGN(xNGm`NrbmcD@xQ=CrXu+suKk%criag*b z%)dL_r_6Qim+_yJ;Gc7tcxR|@p#W+{qLf&H`wkE{s^Df*^W_EkdMRXrUTIms`!iV^ z!Y8t3sm$d8-JE^&fV1bQ>m3#sMUYLOOE{8J?I?@Ng)w-?+~%kmu}M;r$p;xKGb)<6BY@1Uw)jougLr%E>PGvd?^tlu=r1OxP`={d-dMC%4v&aE z$DTRx`dS9m2dQG7FWCCDbGQ~&tJJ`LISh{4IfOpG(Z9h#8+x^gDUce%haiGI=2CE7 z-u`6MkIR2^iB@rH0C2Fb@DaOGS;p?%KLHk(BTI+mKTsHu;9k#_X;nWe(7V5zr4Hw_X;-EqiQE<5Ze2GpO^mu#*<#A(VAvPtBuj1XG`C{JijPH`t3;} z(9O@4_4gFggw&7(-^<1%r)htli?{bdLnL|hJ|>1KIt0fERkI$j+ZzyTBon8?e0dBV zFzYWCDD{Nif;hs%Rhf{Ka^hI!VG=&^$3uITF#Fy~P|cQ2+=Tvopv+xJF-=;l*u;m3nQI*9Dz-RY>yDBVa{ zjSrqddb6lAA+2i{O$K%Q2+x4BnuSe_4eZcb#!u`QA`h#bcsL~-R#0HjzI=IQRnPQ; zj}`3aQat)iYXf91JZ4yuki6ieD!ZA;yy$vJlqP8FazdfT)DcxE0gAd((v|m0-g@O@ ziW?bVe}^C^gcU4kq6A=V`9I&z8WmDC6HWpwsLAYPH}yJR@Tv##4v*4PI4`Kv%MW*@ z0^L|Vb^To#*Xn<_JP=RHkxd5d-2$?Vs=0bL1KL5OAZDk$ME!@ech?+91Tgry?k<7m zuv+>~bk|C!L~c%#NuF0=)eN-^Wyp3vu@b{6**0K7r>&sh9 zB2;IX1x(7bq>8J-(sJt_uSDpq2S#NFdGP-J7wpLHUsk9IE3y!O1g&Gkms6Ek>v16p z7^?H;7XoE6JmWO?A01yOg|%Cr+hX2u&$&3X7D>Ny$;D1&OL1`Dl>MU~8W}yi~PU zGb?{Te}A#pkJz>A;NWua#=p>(1R`{eDao@TdYUFQNT9ta!57 z`bAX$hRSsIheODs-=i<7FFi}~y5{M#* z%}yczk$3>jMxUe&)xjX_NY7y1_tBdVX#h{_HzzkwTnDLAd$_I7iJb%iD;p`4fa6nZ zlXyt*?~81^;lazSLVaX$7BJSlXUgsciVPO5?K%W1!*OdTkJz1s*QYvH z&E@m^M%_y$Ket(YIC=DQD>jxMa9FMUZT7P#$KF#{31qqmGm^JpSN;dN#Z$mqbp$0Y zubcbYraS=Nlb5Yr9qdBV&`Ep33iQ^<3$_51M@?V_7BZfMVA6V(7Spu*{_(j+`neNQ z-W%$Eg}C*IZPYVSjkHto0Lbmq*Kb1+K4-zxM7F$aUp!j3PrZ@$)B%IK;NNjGwmvJ1 zNZk0)=Xd$FiWGo#;GS{|Q6McFT{Urw{?5aledPC}hbF~-F?Bz)_{*a?ht$;^7L|bg z%jf3PQsbIb$s_Ud>`x?k#zLa&++w_~9*gu71+K?xy7|=^l#J1F~N2a zMT^)*_d?5nU9d{y!gVwN{M3J&ZbAKt);rz=(W5Cm(>2B62<8oh;|9KaI^Ut_+78;UlAl0yAQ+9FK1Dza zpQ?_9U>{++i`TUhs!oq;wrN(JveLjS{>^2=5w8c#S^018& zT=&aim{?1m8_KSKT)f1?Zol|zlA&^c#PV5yJYd!!6q4std&K1pYk$uZk<dc++_w;9S?>7V?N7V-T5XSjt-rP!WIaSsR>27t zVCDRH64dXWEgY}(K?1P*CW&oEypW)``_j`o48j}dCU}m)# zQr45eOCRQ%W6uz`d2OYYN#?+WxK>3koK%i}s7-0U6Kdx1j_78;7rl%p{7?jLXMYE* z8{^cR--Oxpo5FA`JxmgCc0z42F@*iORPxtpIU>!pjqj7pQaAAMQgMF75JciJ+d@3U zr(npLJ7CBR%cZw7{GKvJL9rn@*Cm~Gcu%o`z_e>-(VeWzyA| z*xi|o3vM{&+;1U2RV;G|k<9>3<*G&UM6OLt9w=6hEi0ocr*_?i`OoX0=)D&vmfG zrP!TI(oqF=(9zDV+<_RfpxrKCd*vdZTU`#XmWOl%pYrKSDr+T|PGM|EF=6%FivB2B zQhHeDpwcH9ZtVC`nAcxlG264K$z2vn)q!Ft;^W@sua zv&LeiP0h2C@8*h{QSW-@!@ge6jAC}01G!bGH(AgRwasastdif)I_hCdf>@SYqL$Bq za7#uX>e1QSk>`$I$e;;PDBBqzcShI;;zm2hE4ax8`G3N>=QrB2!;H4|rsYqxpj30# z0{rCkvUVcP0lfm^ydyM-@)Dnqnc7t)K0zciyW+iYz3?l=>VfoQ&2mOxHr0b4t{Z7a zjQo*UUlWRx+Z)f{xevS=2IUJJU@j>a*0cEcd0Zd&aJNVX+^`j%;P0Nh%)YPmiRkOr zqSJ!9*-DZQQgNNsmGw~Htmy(jenwZIGGq5xGr_^aC$xm3(u;dfMUNuDDz~LTsm#`* z&Y+vSU*(~jqZRCN)_w$AL%j~i;v!YKzH(OXGBcDf_-nU4^x7Y7{2Lp}Lqk;0uttYu z{nUJ{%hmAXh78e*F0?tCT*t1BBoeWegMZ(>ANstt2H4-G#k#_o8&*Q@Z{@_|(iMW6 zw&U!7ca|&mu1qnA<1ie>GL!E{;i^{Sc5)`US5*A|pNbcR-HTYeZY#9#$Q3um`l-~1 zGm7)nLE%a!xplw-H~sA_hj8WA-sJ9mlgZ|z>l&Dz4TwRf37(Cyax^bd^c_d6Xx=GF zy#e3w;}AoxW`v}BR{?zs*Vv3JgKLT#O|^)plBaW2XdcQ|;j?BCv2@ajYy&wiZbO5> z#?3e)g*c(mMJLTP*vdoj`lhOx%mjFwleo&)2$`MgHo<2d1YY8cmt+3d$F3l|I`-QYSv3fQjYBr|uJ8VviG_9V4I)0;w;kNvp zjp#bL0f$ALEMT{X_T;#s$Lt1HEGcK{e9z2+t$_dU8dY?ZW@T>qLwU%~tOwc<246kK zQk*tv`L68(7Fr&GmMF4bgMVp3h(d@>j{`TpH?tl#&9Y`|uM4u*+2sw3c^HDZJVTb` zvK+bvr%c5v{&zXn$ zN!qT2#Z}q!XJU$w$XSG+7{sou>~Q;2m})eGiz-(W#Z0P)VK9nl!9-8%=)P-@kIJ3P z1>oH3j##HCo2DJjt>Emf$e&1QQ|AHQ1PjWy!I}a5gsSp(=wf-j14EPP>ihbddyP5|YqfgZ$7CnhDo8{+H*Bgz(=o9?lp$A3 zucK?(81)|e1sji3GZ5nbFkx2MF595~wP@{2Yu)pY+WT&VAOQG%XB@Z_ye&U;SOVNh z)Sf24|8ddG=NVsZYT$?z zCMKXub@V6_l@!im;|r>6rSkZompJZt@-nJcEW|jz#u+!W|MA;$lp#`&|kaT&F*YeQyNE9&&O1q4Q-joTkWi|j~m0P*0 zxTNS##n%{dlwbuJNo$5|y>O9CywQRO@;Xid{yakH1kRmGH;L+PNeYR136{X|QJ9eB zb&@xy*=Gz}fl>Z<*)|pk#2cr=@?>=|)n!cU6YIYi2;qk$!x$_aDM)>glg9a5wtEd6 z(QPu?&VG8`Q*dys8Q!sm4X}GnM)*o%pG{}-3yjeg5-;mo4FgG74X9S1opHlE>>Pj! zQ1UDlfp%1=X&|F?{3YqkiO22YLr&7|_hC@qYjdSrL}O366J-mA`cv_5dsBLH7lYtg zXCZo3wTdR};LnAB-J)V7x>U?AFRsuaB1HCl^wt|C8?>G7`=?F_A}(%%13qBH z;I@|n1dYg4>@$5^AOPSATnqG;J+Tz+@bw(J7sNPcqt*HoTWW2)oTE}~-#)cZ1Ai>+ zC}<11nihKYvSl$aY;?q$oy0;b6&)!bWjVFr2kAUOdc^e#%IWp?U-(~lQ<|3)@t=2- zXx+C;uXBo#Dr#`nspgzuG&UJ(6MAfgW`E36y6kwt##RVck?#5OM4VocVr-`>M*i*v z5!PzQOqnlIBPWb~z$}rj0NwY# zg7_kBDGWv5bMt0UGxeHeI9d4TwcjsD0WhJx`Nc&LuMAbvh!rDXvYUnS>?Mk#Jo^n_ zlKu*t)(YQ;sKE(N3+SX4>Kx%F^>sd9njYayv@aIq0w2h;KGjzw%gS0DY z0KiG;EMIynq1JrQ<`Kt>e9T_6YMOn?M`t4$VrarEeA~r37vt1GO&xNQOGD|=!KZ3B z2F+!^a6Z?)AGi7+0OaI!BT|k`h;NAvJK}kCW|W&wKBfDX7%M5iUE2&)NvY_j@Bs=N zQ-Ic1!k-ycs##J%6pCTHi7PhLmU>DAHi7^k(Wve&1VGSjIMtW-c|%oi=0PsP;Rla9 z$nQ&j=xB*UblxowNo(z3DrnuFcQ;7Wj^tfHI-R5Sn9U(RHehFI7&wD>p z%`I~l5>uyzd4>!Nk`&^S;to+Ew;M+2PVLK-8_4#LiV!lN(3YkDCL=1Bd`WNRQk*s` zWqC>86|y3@rsb)F8C6}r30W;Kw<8mvgz)!g4J14wO!SD_+O@Y!k0tEyGxpRrz<2o4;?Fn>*VL|5pBr0r16% zDw$J^=_*HxmV43DsOzY%$4FdG-bDHYGMKKdhB-b9b4r8yCU#4~VJ~O=YNXFFgIB_FfHL~KOo$IyHqbj#d{&M_BvzdM$ z6;BRNfxQ^=VFC@uecgD*S!>B}POS4m-vd1%rR-;|D-2*ajy8szaodmapw;g%rOeJ%0K6_nBmle zV%p+h8Jv6@tHwWhzvuFQU9SIH;B_y0z~XwcyAs|Gn$g`giMbvDYgqlQZ_+E^!#y#8 z5VdDv^IH`8(@!;D{ctTe-~s>i-&*UxExP|E-u|Q43E4X!+b2~=@_LH`>JjQ>Si>S^ vP+o6i9_!zi>8t%k@BU2_{+Y?hEgWCB^e8c+ebtq)5C9zwg9nvrw$c9w-pFhI literal 0 HcmV?d00001 diff --git a/include/small_gicp/util/downsampling.hpp b/include/small_gicp/util/downsampling.hpp index 2bf88b7..294d230 100644 --- a/include/small_gicp/util/downsampling.hpp +++ b/include/small_gicp/util/downsampling.hpp @@ -29,8 +29,12 @@ std::shared_ptr voxelgrid_sampling(const InputPointCloud& poin std::vector> coord_pt(points.size()); for (size_t i = 0; i < traits::size(points); i++) { - // TODO: Check if coord is within 21bit range const Eigen::Array4i coord = fast_floor(traits::point(points, i) * inv_leaf_size) + coord_offset; + if ((coord < 0).any() || (coord > coord_bit_mask).any()) { + std::cerr << "warning: voxel coord is out of range!!" << std::endl; + coord_pt[i] = {0, i}; + continue; + } // Compute voxel coord bits (0|1bit, z|21bit, y|21bit, x|21bit) const std::uint64_t bits = // diff --git a/include/small_gicp/util/downsampling_omp.hpp b/include/small_gicp/util/downsampling_omp.hpp index d802b7f..c1f98bf 100644 --- a/include/small_gicp/util/downsampling_omp.hpp +++ b/include/small_gicp/util/downsampling_omp.hpp @@ -30,9 +30,12 @@ std::shared_ptr voxelgrid_sampling_omp(const InputPointCloud& std::vector> coord_pt(points.size()); #pragma omp parallel for num_threads(num_threads) schedule(guided, 32) for (size_t i = 0; i < traits::size(points); i++) { - // TODO: Check if coord is within 21bit range const Eigen::Array4i coord = fast_floor(traits::point(points, i) * inv_leaf_size) + coord_offset; - + if ((coord < 0).any() || (coord > coord_bit_mask).any()) { + std::cerr << "warning: voxel coord is out of range!!" << std::endl; + coord_pt[i] = {0, i}; + continue; + } // Compute voxel coord bits (0|1bit, z|21bit, y|21bit, x|21bit) const std::uint64_t bits = // ((coord[0] & coord_bit_mask) << (coord_bit_size * 0)) | // diff --git a/include/small_gicp/util/downsampling_tbb.hpp b/include/small_gicp/util/downsampling_tbb.hpp index 8c1e6b0..10d190e 100644 --- a/include/small_gicp/util/downsampling_tbb.hpp +++ b/include/small_gicp/util/downsampling_tbb.hpp @@ -30,8 +30,12 @@ std::shared_ptr voxelgrid_sampling_tbb(const InputPointCloud& std::vector> coord_pt(points.size()); tbb::parallel_for(tbb::blocked_range(0, traits::size(points), 64), [&](const tbb::blocked_range& range) { for (size_t i = range.begin(); i != range.end(); i++) { - // TODO: Check if coord is within 21bit range const Eigen::Array4i coord = fast_floor(traits::point(points, i) * inv_leaf_size) + coord_offset; + if ((coord < 0).any() || (coord > coord_bit_mask).any()) { + std::cerr << "warning: voxel coord is out of range!!" << std::endl; + coord_pt[i] = {0, i}; + continue; + } // Compute voxel coord bits (0|1bit, z|21bit, y|21bit, x|21bit) const std::uint64_t bits = // diff --git a/kdtree_time.svg b/kdtree_time.svg new file mode 100644 index 0000000..513916c --- /dev/null +++ b/kdtree_time.svg @@ -0,0 +1,2532 @@ + + + + + + + + 2024-03-30T19:07:54.181443 + image/svg+xml + + + Matplotlib v3.5.1, https://matplotlib.org/ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/scripts/plot_kdtree.py b/scripts/plot_kdtree.py new file mode 100644 index 0000000..01f4091 --- /dev/null +++ b/scripts/plot_kdtree.py @@ -0,0 +1,88 @@ +#!/usr/bin/python3 +import re +import os +import numpy +from matplotlib import pyplot +from collections import namedtuple + +def parse_result(filename): + num_points = [] + results = {} + + with open(filename, 'r') as f: + for line in f.readlines(): + matched = re.match(r'num_threads=(\d+)', line) + if matched: + num_threads = int(matched.group(1)) + continue + + matched = re.match(r'num_points=(\d+)', line) + if matched: + num_points.append(int(matched.group(1))) + continue + + matched = re.match(r'(\S+)_times=(\S+) \+\- (\S+)', line) + if matched: + method = matched.group(1) + mean = float(matched.group(2)) + std = float(matched.group(3)) + + if method not in results: + results[method] = [] + + results[method].append(mean) + continue + + return (num_threads, num_points, results) + +def main(): + results_path = os.path.dirname(__file__) + '/results' + + results = [] + for filename in os.listdir(results_path): + matched = re.match(r'kdtree_benchmark_(\d+).txt', filename) + if not matched: + continue + + results.append(parse_result(results_path + '/' + filename)) + + results = sorted(results, key=lambda x: x[0]) + num_threads = [x[0] for x in results] + num_points = results[0][1] + + fig, axes = pyplot.subplots(1, 2, figsize=(12, 2)) + + axes[0].plot(num_points, results[0][2]['kdtree'], label='kdtree (nanoflann)', marker='o', linestyle='--') + for idx in [1, 3, 5, 7, 8]: + N = num_threads[idx] + axes[0].plot(num_points, results[idx][2]['kdtree_omp'], label='kdtree_omp (%d threads)' % N, marker='s') + axes[0].plot(num_points, results[idx][2]['kdtree_tbb'], label='kdtree_tbb (%d threads)' % N, marker='^') + + baseline = numpy.array(results[0][2]['kdtree']) + axes[1].plot([num_threads[0], num_threads[-1]], [1.0, 1.0], label='kdtree (nanoflann)', linestyle='--') + for idx in [5]: + N = num_points[idx] + axes[1].plot(num_threads, baseline[idx] / [x[2]['kdtree_omp'][idx] for x in results], label='omp (num_points=%d)' % N, marker='s') + axes[1].plot(num_threads, baseline[idx] / [x[2]['kdtree_tbb'][idx] for x in results], label='tbb (num_points=%d)' % N, marker='^') + + axes[1].set_xscale('log') + + axes[0].set_xlabel('Number of points') + axes[0].set_ylabel('KdTree construction time [msec/scan]') + axes[1].set_xlabel('Number of threads = [1, 2, 4, ..., 128]') + axes[1].set_ylabel('Processing speed ratio (single-thread = 1.0)') + + axes[0].grid() + axes[1].grid() + + axes[0].legend() + axes[1].legend() + + fig.savefig('kdtree_time.svg') + + pyplot.show() + + + +if __name__ == '__main__': + main() \ No newline at end of file diff --git a/scripts/run_kdtree_benchmark.sh b/scripts/run_kdtree_benchmark.sh new file mode 100755 index 0000000..e60dce3 --- /dev/null +++ b/scripts/run_kdtree_benchmark.sh @@ -0,0 +1,12 @@ +#!/bin/bash +dataset_path=$1 +exe_path=../build/kdtree_benchmark + +mkdir results +num_threads=(1 2 3 4 5 6 7 8 16 32 64 128) + +for N in ${num_threads[@]}; do + sleep 1 + echo $exe_path $dataset_path --num_threads $N | tee results/kdtree_benchmark_$N.txt + $exe_path $dataset_path --num_threads $N --num_trials 1000 | tee results/kdtree_benchmark_$N.txt +done diff --git a/src/kdtree_benchmark.cpp b/src/kdtree_benchmark.cpp new file mode 100644 index 0000000..e003685 --- /dev/null +++ b/src/kdtree_benchmark.cpp @@ -0,0 +1,148 @@ +#include +#include +#include +#include +#include +#include +#include +#include + +int main(int argc, char** argv) { + using namespace small_gicp; + + if (argc < 2) { + std::cout << "USAGE: kdtree_benchmark " << std::endl; + std::cout << "OPTIONS:" << std::endl; + std::cout << " --num_threads (default: 4)" << std::endl; + std::cout << " --downsampling_resolution (default: 0.25)" << std::endl; + return 0; + } + + const std::string dataset_path = argv[1]; + + int num_threads = 4; + int num_trials = 100; + + for (int i = 0; i < argc; i++) { + const std::string arg = argv[i]; + if (arg == "--num_threads") { + num_threads = std::stoi(argv[i + 1]); + } else if (arg == "--num_trials") { + num_trials = std::stoi(argv[i + 1]); + } else if (arg.size() >= 2 && arg.substr(0, 2) == "--") { + std::cerr << "unknown option: " << arg << std::endl; + return 1; + } + } + + std::cout << "dataset_path=" << dataset_path << std::endl; + std::cout << "num_threads=" << num_threads << std::endl; + std::cout << "num_trials=" << num_trials << std::endl; + + tbb::global_control tbb_control(tbb::global_control::max_allowed_parallelism, num_threads); + + KittiDataset kitti(dataset_path, 1); + auto raw_points = std::make_shared(kitti.points[0]); + std::cout << "num_raw_points=" << raw_points->size() << std::endl; + + const auto search_voxel_resolution = [&](size_t target_num_points) { + std::pair left = {0.1, voxelgrid_sampling_tbb(*raw_points, 0.1)->size()}; + std::pair right = {1.0, voxelgrid_sampling_tbb(*raw_points, 1.0)->size()}; + + for (int i = 0; i < 20; i++) { + if (left.second < target_num_points) { + left.first *= 0.1; + left.second = voxelgrid_sampling_tbb(*raw_points, left.first)->size(); + continue; + } + if (right.second > target_num_points) { + right.first *= 10.0; + right.second = voxelgrid_sampling_tbb(*raw_points, right.first)->size(); + continue; + } + + const double mid = (left.first + right.first) * 0.5; + const size_t mid_num_points = voxelgrid_sampling_tbb(*raw_points, mid)->size(); + + if (std::abs(1.0 - static_cast(mid_num_points) / target_num_points) < 0.001) { + return mid; + } + + if (mid_num_points > target_num_points) { + left = {mid, mid_num_points}; + } else { + right = {mid, mid_num_points}; + } + } + + return (left.first + right.first) * 0.5; + }; + + std::cout << "---" << std::endl; + + std::vector downsampling_resolutions; + std::vector downsampled; + for (double target = 1.0; target > 0.05; target -= 0.1) { + const double downsampling_resolution = search_voxel_resolution(raw_points->size() * target); + downsampling_resolutions.emplace_back(downsampling_resolution); + downsampled.emplace_back(voxelgrid_sampling_tbb(*raw_points, downsampling_resolution)); + std::cout << "downsampling_resolution=" << downsampling_resolution << std::endl; + std::cout << "num_points=" << downsampled.back()->size() << std::endl; + } + + std::cout << "---" << std::endl; + + // warmup + for (int i = 0; i < 10; i++) { + auto downsampled = voxelgrid_sampling(*raw_points, 0.1); + UnsafeKdTree tree(*downsampled); + UnsafeKdTreeTBB tree_tbb(*downsampled); + UnsafeKdTreeOMP tree_omp(*downsampled, num_threads); + } + + Stopwatch sw; + for (size_t i = 0; i < downsampling_resolutions.size(); i++) { + if (num_threads != 1) { + break; + } + + Summarizer kdtree_times; + sw.start(); + for (size_t j = 0; j < num_trials; j++) { + UnsafeKdTree tree(*downsampled[i]); + sw.lap(); + kdtree_times.push(sw.msec()); + } + std::cout << "kdtree_times=" << kdtree_times.str() << " [msec]" << std::endl; + } + + std::cout << "---" << std::endl; + + for (size_t i = 0; i < downsampling_resolutions.size(); i++) { + Summarizer kdtree_tbb_times; + sw.start(); + for (size_t j = 0; j < num_trials; j++) { + UnsafeKdTreeTBB tree(*downsampled[i]); + sw.lap(); + kdtree_tbb_times.push(sw.msec()); + } + + std::cout << "kdtree_tbb_times=" << kdtree_tbb_times.str() << " [msec]" << std::endl; + } + + std::cout << "---" << std::endl; + + for (size_t i = 0; i < downsampling_resolutions.size(); i++) { + Summarizer kdtree_omp_times; + sw.start(); + for (size_t j = 0; j < num_trials; j++) { + UnsafeKdTreeOMP tree(*downsampled[i], num_threads); + sw.lap(); + kdtree_omp_times.push(sw.msec()); + } + + std::cout << "kdtree_omp_times=" << kdtree_omp_times.str() << " [msec]" << std::endl; + } + + return 0; +}