From 2a2e1429df5b8568d7f241780c7555c33dbdd71e Mon Sep 17 00:00:00 2001 From: sachinc <sachinc@253336fb-580f-4252-a368-f3cef5a2a82b> Date: Thu, 25 Aug 2011 22:03:58 +0000 Subject: [PATCH] tests for fcl git-svn-id: https://kforge.ros.org/fcl/fcl_ros@4 253336fb-580f-4252-a368-f3cef5a2a82b --- collision_space_fcl_test/CMakeLists.txt | 33 + collision_space_fcl_test/Makefile | 1 + collision_space_fcl_test/mainpage.dox | 26 + collision_space_fcl_test/manifest.xml | 24 + .../objects/meshes/9300.stl | Bin 0 -> 190084 bytes .../test/test_collision_space_fcl.cpp | 758 ++++++++++++++++++ fcl/src/BVH_utility.cpp | 2 +- fcl/test/test_core_broad_phase.cpp | 246 ++++++ fcl/test/test_core_collision_point.cpp | 540 +++++++++++++ 9 files changed, 1629 insertions(+), 1 deletion(-) create mode 100644 collision_space_fcl_test/CMakeLists.txt create mode 100644 collision_space_fcl_test/Makefile create mode 100644 collision_space_fcl_test/mainpage.dox create mode 100644 collision_space_fcl_test/manifest.xml create mode 100644 collision_space_fcl_test/objects/meshes/9300.stl create mode 100644 collision_space_fcl_test/test/test_collision_space_fcl.cpp create mode 100644 fcl/test/test_core_broad_phase.cpp create mode 100644 fcl/test/test_core_collision_point.cpp diff --git a/collision_space_fcl_test/CMakeLists.txt b/collision_space_fcl_test/CMakeLists.txt new file mode 100644 index 00000000..a661bbcc --- /dev/null +++ b/collision_space_fcl_test/CMakeLists.txt @@ -0,0 +1,33 @@ +cmake_minimum_required(VERSION 2.4.6) +include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) + +# Set the build type. Options are: +# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage +# Debug : w/ debug symbols, w/o optimization +# Release : w/o debug symbols, w/ optimization +# RelWithDebInfo : w/ debug symbols, w/ optimization +# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries +#set(ROS_BUILD_TYPE RelWithDebInfo) + +rosbuild_init() + +#set the default path for built executables to the "bin" directory +set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) +#set the default path for built libraries to the "lib" directory +set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) + +#uncomment if you have defined messages +#rosbuild_genmsg() +#uncomment if you have defined services +#rosbuild_gensrv() + +#common commands for building c++ executables and libraries +#rosbuild_add_library(${PROJECT_NAME} src/example.cpp) +#target_link_libraries(${PROJECT_NAME} another_library) +#rosbuild_add_boost_directories() +#rosbuild_link_boost(${PROJECT_NAME} thread) +#rosbuild_add_executable(example examples/example.cpp) +#target_link_libraries(example ${PROJECT_NAME}) + +rosbuild_add_gtest(test_collision_space_fcl test/test_collision_space_fcl.cpp) +target_link_libraries(test_collision_space_fcl assimp) diff --git a/collision_space_fcl_test/Makefile b/collision_space_fcl_test/Makefile new file mode 100644 index 00000000..b75b928f --- /dev/null +++ b/collision_space_fcl_test/Makefile @@ -0,0 +1 @@ +include $(shell rospack find mk)/cmake.mk \ No newline at end of file diff --git a/collision_space_fcl_test/mainpage.dox b/collision_space_fcl_test/mainpage.dox new file mode 100644 index 00000000..b2179033 --- /dev/null +++ b/collision_space_fcl_test/mainpage.dox @@ -0,0 +1,26 @@ +/** +\mainpage +\htmlinclude manifest.html + +\b collision_space_ccd_test is ... + +<!-- +Provide an overview of your package. +--> + + +\section codeapi Code API + +<!-- +Provide links to specific auto-generated API documentation within your +package that is of particular interest to a reader. Doxygen will +document pretty much every part of your code, so do your best here to +point the reader to the actual API. + +If your codebase is fairly large or has different sets of APIs, you +should use the doxygen 'group' tag to keep these APIs together. For +example, the roscpp documentation has 'libros' group. +--> + + +*/ diff --git a/collision_space_fcl_test/manifest.xml b/collision_space_fcl_test/manifest.xml new file mode 100644 index 00000000..46a55814 --- /dev/null +++ b/collision_space_fcl_test/manifest.xml @@ -0,0 +1,24 @@ +<package> + <description brief="collision_space_ccd_test"> + + collision_space_ccd_test + + </description> + <author>Sachin Chitta</author> + <license>BSD</license> + <review status="unreviewed" notes=""/> + <url>http://ros.org/wiki/collision_space_ccd_test</url> + + <depend package="planning_models"/> + <depend package="collision_space_fcl"/> + <depend package="collision_space"/> + <depend package="tf"/> + <depend package="arm_navigation_msgs"/> + + <platform os="ubuntu" version="9.04"/> + <platform os="ubuntu" version="9.10"/> + <platform os="ubuntu" version="10.04"/> + +</package> + + diff --git a/collision_space_fcl_test/objects/meshes/9300.stl b/collision_space_fcl_test/objects/meshes/9300.stl new file mode 100644 index 0000000000000000000000000000000000000000..7159c022ac7d8b620ffddf91aee16a8cc9f19b8e GIT binary patch literal 190084 zcma(4d0b8F`#+8^GZ_kHmMJ8&l%c)X-Of;^D04!lh!8RrGG!(+WmX)=keO(&`)+5Z z=$JB-naq@#@3oG7-s`zuzt11P^LTi@JUpJy>v~@Ic-_<5JwnEf9}pT6F(5o-^r))c zMvo315fWZ?=#WuE#tsM{GPr8jj;5+@LqdmC{r~g78zm&k<8u|U=TNTFeR3O?p7zD! z+}JZEBW;qGL*i%4E5FStk~GOH(*A=*w#iIs>N?p=l4`BK%scpPR{SD|F+{0<PY64e zvOadA*NL1DmYCE$7L_eYWA^6}<ugn1ehIx9+CtQcoR^mLv__U;!78J7wxc-w`Mol8 zSX+iDWTS6MD%I{DcbmLMseXNkE)Ha*r+u&lJqe?jBFM+^ar?R3=NC$FuTlS_N>dUa z_RNx+lb=+njQ-JoDUa8UOwOqhMLslJh)PepYDr5oQ&~l-aiqj?dH!nUpN`|09;LBS zp(N!-pW^cEx#qV{p}IKGpF`qz%k)*P_@A=s7qnUFHK3Nqe0RMnR1%&2-m>qb!v91b zcYZy8ZmeYVn=y`RP_u=o_^_XrIoT#pwKgTG^*<YVrxQ+w>^|cdqL7UWC239lef)9N zcth1LVHCM$3)$Iz@2JJJ@%*Ez=4B`4uMZCmVt<s*2gZ?}cG6;>$gHKieEbHbOzdX! zz{XJwZ6PW)Hr*m!+rj?S$La@NmD~ocJ-+;<mX&4;*{D#GG6wJCSKrn%u6EGJfsCw( zFP4Zi$rOj$b`v|SQ@Yh!XujS;uL_m8x@KDftDf-u)2{08+|O-l&opjYFq)w)M8(Fw zwM^u;Cbe%$($(mFeAcvj#!TBVhA3pCLP@%OZwfEAWWVw6(i0ilLbi9-L(7RAJJTOk zH>B<6@zt&yYTk*``M@}m92JY$)Y9`$>AorEYd#j5Z20>{6hm8x^2y?ssqBeoMw;5A z8drT|-sxJ~@c2O#Llm-6p(IJSrttVLdyUh}>El2~r2S*d^Y6^`XS{N)xYnHXy|_XC zpjU-TqO-4AzD@J7M&99sftPTaU>xKWNh5=13sITzH!SUog__pKs$*ik)@^vZ8cD|N zni14?HCxC=g_7jZ-i_~U5NQmX7|GBUvXdOoSaO|bQk|=1wcoCjvanSl^U7Un|ImD3 z9Ak`IE$;m)kScZb8C|xJ5`OHJNBk|dbTwOuiq2kP35;1{Ww^(;QfifLpZxex6hjoU z(KpqHBu)SKf2HZ9O0$J*`@}OT)%I1Ou|!qXzGrErV7-^-bI0{QFph^2y(}LtJ6QYq z-dP#R+hd!XXMKxeXbVw8gGYJVC;nymQ&wx(>EypBc$&S5fhc67Lh2v0=6ZxKI(NM9 z?<j`0kZqGW&JtmN&#J0k9$y15bK0=uncfG+fo=LvDg9SgXbVx;yZ(<coeEjkKah<I zC24ZrJsuSjU7D5opE!_VpE%AEY42tE(`*0F3;944D#5W*!>g*$7NT&})-w==Z1gQj zPXo_*oZbAW<-T9~`ap(bbRUaz;KKh$9Ed_C!NJEZ*?!Ic9}KjGDEq`@OIF0-{|5t6 z$VT5ZT-~0he9fBbk#D5hb~Rhb&WgB4xsNAhOKLyQ?Gm8$Z!9SXW=1hYVH}uCQ10`6 zE00ggRXQCFqxnO#g(!V~m02`GaV*<h32han%S(`rz9nf+`XQy<lS<0fOVf05AS2TL zx}{3=P-`3|p0DJ)Hm^`#8Nzj{P>HMSBg+_L0QFjRR{QB2#V0l>!+Vq%Pvfp;3sLE5 zcPzhukG3)#77pVs7tSfh!jou@(rh6c6-v^ZcKehw`PV4Bdh6prMqKP)lx57f*7^Nn zv-$b5g?aXmaGfet^80r>Wiqp@kq>Vft2o`+q@+bnV`xi{+HJAPjJ0N#E!r<s9xS$1 zp0Fr}C}g8TN&3*}hmvP*MV{X_l1Y+g3)z7&=V@$TN^z)jl;8PyKK1qh?(}ek&IiVk z?RSGz%^+23eGFOih"&UYQ@&d?U3TwSkFhP=q~Cr`}G+{(|nx8r>DNXp1GTgXO* zl630EE#>8`lS*8#sk%6jaUv&)=D`GO9M$JP<vwc<a=EF$P8BNg$vR6T^?G8c*=wHJ zW<IIc3ZBq)Agv}eTZjsbNuoIRSsCANoaJ2t4)I-cdox5K8x_*3XluMuXH$NDJik5; zWCRB<qE>Ry+DdwLSjVMztN6U?!*r@p$%&lpmPGGk*4A#!H&ZE^_(7?$XDW>hnk_{6 zWX+_!{gkz=#!XwKd^~YdIqEizd}y}xY^_8jsYvK3<?gC0%9_U0D00n~p1qX%N4m9@ z+#VRm8*W&^!*{50Xg)9w|D>%H$0=(oIo5wTuUcw5KbSk5;?Qg%Dj{q!wcYF1`nb8u zm;c=;nwL%<!w`jR^essjSF};QR^}?hu20p)fsEkbww5NYH?5`nV_`@BWx!V6r^iU0 zDpV2}Gm84heX2pVf7CBfU75J?lTz=qS|6G%L|u<}qL%o|%Gi?Ori>q$sjTlhjoPke z3)!epk~aL@q!d~*h7bBOk)bVQr=@iy`>(8J)xBsK-*6y<OK%70d|({@Nn<IFM-=%4 zilbS(rQB<by*R$V6+>HyTAJFM`o~MEbCt2~VP9Ty@-;r?+W@K$%@(pzp(JgO+@!c4 zna-2HPSC}Hj8}fn7XPGAR#nf7F6DdwDkoM=^3<t9C5hf`Xtn*0qE}Vj>N1-@;&sKU zca0g^LX=~44T|FnmDPA+7`IO1MLXCFv#U2l6tYnvt!v94Rz4Sw;+7}+IFKPpg()xj zY^{&lmAtueqq9i1Z>dv-N^CL<QUCaEjblalCnc<I0kL>$FB%gyTZp<I|1M=o>UV2> zv^blG`<5;s^0)0pIUL&3*m{MQa$^<OhyZ?M+hkpRpueT5hf}V{f3WuR;I}W8jgk4p z<;31PRj4F2CnLot>zg(58WEk9gB>UE-ZdvNw1ud&w9u3$u3xSF<44^9CEYcg_b^Uk zh(b0hl%y6TKbf!ZdBS~m4W?G2*+RA?Z6;N}tYziB=%Er?w6It#_0;*mI1;^Yri2-P zS?i-%vt`PRif-aS{-zYUW(!fd&gPUvZz=UpyP6WSO!2%|OqjlRqjrV1G`3zL<;c_j z{84jiEl<P@0JBU<I=btp*=uEzV!o!&GB6vMlih-5&fV0b)XdWB^Wc_~>`t1SzK&vO z3sJcCk)-iqhU4kVdGm|xD26Cxqe4jvw0v*ba%E4Y*tRI$IttlUq6=B#V$V_Os;W9< zo;E)i7oijytM`F%;Cw}q%fHP(>i(m2oIj1BEkxnmMY}ldkD9+XU9A+O{0dRXMun1; z{W;cSWwS}j)j9e&kdfpVO?93{tzFHp?hO8Bt~WYaal5Ejg-URomn7wLx_NQTE#+DG zG+Nzhwh)D5KJ5X7oi``8yQ0)zGEFz*AR84*l2bWfvv;<Oa@?Yi0~u8d&X8wkXItYK z=x3u8JF!r)nABYZO%*E9_eaC@w&r1><#|xqsSIr)3i~Flak?g(i}zWl{GgpXL?Ih} zQ_mQ?&5&=@0L3Rp9|tnZ=a2I=*u1vR=PiE>J3caBQy!FWicS?O2`e>Ab`Jb+^jTwm zWAJJez~|?UU}y_bk@jspXJ>!4W-{eh&o(%GbmhapM>0eq8x=}Y=($6NGmii8yKy13 zn$T<^+i-sqGulY0f9Bdf^-CmAJ9L|O^%$!2fpOgVS}=vm$jZo@lXZM)b9=#$bzx`= zQJZ7S%Zc83Q!~=SsqGGGz2o>=%N^eJdoV*3vQeQVO;aiu+xN)gQM-od;y}ja7fU?D zj6baNdGGN~##_g#iI?@;>QteUmE}S`gM+2i^|9*goI3S`ao=nQF@8lShPDv3vEM1$ z_xW$;jBDP-c$nuGw`T+}L?Ig$O47&ceT^UQrt;%mLv?W=!?Gj8Gs6Cpb&e{x{j)Lq zYCh4;v$swaDoJw8p~!Qsk=I)J+xXb`Iq&jt07F}d+WEecDLD9zwO!d>dv2Wd=ri9| zt{?S5%@(pzp(IWGnO7bYmd*3$1TnOQ?EF1ynd}qaTj#+dcN!bp#G857<dHfb7)R9b z!ls0<&sN5Mzrpf0W-ro(4?|msiq5WM3NwD9u|%!GuBJ`KVV8V))|<%;QOHJxl5`+B z$r#jbtz6N69Q$=O*!0Tpo=F{Fo4WQf-H3l^Qg;d#nEXjq*1!Kwd*QWa$p@5rY;U8+ zw9BudDhK$Q{F9!V)LcDpT@U*E^MBdY+I=q?3!CT4t)`A=XbVyOjyELcbE}Wt*VB!@ zOXkY8qQ^5tAsc;5Qb(J<#!1cG<^1y_b#Wl0eEtchxY$h7pFL!kx9^N0vp32$7mv}Y zLM2PqbTRp4-63V_%z3BlG2@M9jpQDcBWb+SY$1x)<|f(Zl<Ci&e&hOiWzRVq<O;!K z7^0Ak3MJ{-ovX%F_cn6R3zI2Z(rh8S<sq5kxJjj}stU@}MDE$*v^+6=sLlt*vGaW? zs*jh}IJ(Ap7^B8jkawm{VQ33c$5PMJ$neS<$7_d^#!Y<!<O$CwQES(1AsZD+QbYSB z<DEP;<<z)HT^z{Rae4-|F*DVNx=-z#|1ZPi&&P}_9!=A!LM0uW*_v{luTv{g8S?x5 z$vto0GDJL&VrUCd>rb|&e!iX}pF)i2dj|~FpKUX~FBioSg=|zPNj}Xsw;aChnL#{> zVrUE5Ee}bafiX9%s`84uEvmLzVeHvM?*rpFne&DA$^R?e8OyxP2fM@@ceq4R<eDu+ z#l_A~k!{{uYcQweAdeQc6O1YKq8Or(jS3~nbK0Zh%Wlk*_w1cOdt{m|WY11HE^IPC zTYGI<zdS8(-R%$}_CfpK^R)%Q&F{%q~F*$11M#mpk?(u<x9Z6WG;#z4yHe^8yP zJ4NM+Z#K`nKTQ5=oXik~Y*Z*o`D+$cTypoy*I1Y?4rDk+uS;=^{z_$~?iw_yIl~;@ zwK&@~yt_^nD)DstC6=cCq{!8EEzgQN-p%uuJg#X!%G)(th+3MuI3>yPH}wydF}`%T z`Q_;1>`t%l3{l8Nh143iJTzBu+b^FhrH=y{O<l87mZs*A4>gY4>(?tk*A`;+Ouclf zP)S<aRmzaRTjTih&psu?-;U++@u!hmvxO+1th|;m;}@zywLb30EmP)iEzZ&=b)(gt zW((P<klI!6Tjmv)4#>;Sj@H!&GU8&3(B9G;>$qz=QGr(uc_QCkHbAEem1O(bS%QN< zSzF2M8jNTBl_T$-*oS;*wh(na-kIWfW3BU!F_n0}s9*Ap9Raj2s@Xy|DwL$zlm0Ou zcj+V>jz#F=&@-;2q~<)Z_VYS6jQ4QOl|TCFRiP5urWxJpcx>&pgC@370!EgXt6iEx zk!!XP<)74mc8ac9eViZMQW;dxU2gwZBtsOkQ6aVV1b?M=L^*kX`V`tJ(rh6+EiH`h zmt3=s?QL$i<Gp`>kq>3}*7?9V62iJ$mZm<kw#1<?;`ph45_>qkGqn=U7NWBK=1>h@ zwbsX+y1xAVq+9a&BLf(skc|o@$^V_NazE+3(PsEGT^z``9^b`6XL;m99oz49*~}*% zzAhV_0(7cSNpSFL%Z+$$jr`Px1xoeFMq@DDFF{*~!ZTJ$itIO6Y1Q$t@$x8jJ*e42 zHY${)!M<6^PaZEe<_1OS;y^}VOnYiqC#`X8_4t{*=}C3-MLJ7G6e@Y;=b4faHr2|Y zm5BP^boG1?Z6ONhu7A<i|CvsEWST8xqi;zP2M3!24m37CPu9nQ3~ZIOGm$dgV0_)i z*n`f`5rs-{zLKQsKFbV4-q_2EVXCfwAPVO$Iz<l7W60e;+t@u^KXalI^estq2On-3 zvC^D;i_SSw36{c-zpI$mwz|On<R#hjvXdSClamcUqjY73^?~Qyk~B2%<uSi@w&tnC zKwF5?@B4IWbm~}?<NM?mqzX~UMun2p)VGeu(ASpat^X4TGU^2GG7a2v*?JFPU-|wm zJ2Z4Kd;O0pRPrZNDs1_aU%d@0VO-<pY7V;^#n2X_;$rWcq`GsJKl$#?`92=;2cIN6 zkSatW8x_(WuNLu!W6h>|OsCr-Xbag1VP{Oy*)=VH^4-%<OBr1AZ88^lulIp*_$Mu= zygknHN7dx2<&6%avNC^56pcQbEkyZb9XDN%pJ(}#>Cdd;X~;Ksi#g?u+S)Z+$VP>f z$*gH=+&3^l`8+U+&ObC;$bRLw+GLY?*z#xnk?!kenA5^hDRn{b1LJu9y{E}J@RF5L zf7wH$^u&V~E)hX3QL}}pf-}aEk1G_pnln7>Q^+`EW{|RFauh=pvQZ(eqvl>U`lfc~ z%UVrlXbah2y0)T`=P{L)>Z8$&n;v@}nv`;f^*%5Tn@k6)kH^%m)SbH}hR4Pwx0mpu z^}-q2LKLp4>C|%ULu0G_UHQJJlW4zPvxRI_NGB#Wj~j2ET+YYT3fHaAk&UZ+Nvd?u z)*R6#Oj)@oO6LRPz<nl3^4=F<a7bv!ALT~q_8Aa`drq`gi`;7X*v7~cXqAd6RDud6 zsmg&E+3(YJ**7Opx30w%WYCidv<Gm<Iy>JS&{v+&e5HK+&?wz16<3q#X$wrWA8yU` z)2APn^A9h=eoCzw+Cr3n(j1dZpt|N%^W9}X=gJiq-jI)+>r40gG+W3<g_KjrotIzs zEy~XIG*XY!Y$4kxYc=gNT(D++Qq`$)(BoC|=n3l0Ow9+zQ73Q{t%QX&j&^wy<y_-c z`DCSD)CV<Nh>FgRHzhd=YQJjR&2UJP<MZE=3&eDz5l*v(Z1gQj?8IKVXp6t){&oZC z{*`76*;x^XOmnjLSbYqrFhTBdd5(Or{%D;Kj3YSs5UtO*Q{-y@7?gHfK7R6;ydb$N z-Q>`0A?ifVW!hU>Xf3Nvi7E1ddtClltv8Lknk{6bLh8LPXXS7EHp|bZ_oY*0%@(pF z?axvSi|CKK&rq57ltY>gkx#{q)A_(S;$nB1($f;CK2*jO=go2tmpFOW`e54Y(`+GX zjL}T>vCNw9mO2(Bd*AeuXXl2~Y@pdfHY%hZm2t>;lVuy1cbrN$=rmi%c6I%W_5k9j ztp2?ZxAm#9%%+0!mg-Y<J}?g450Ip7e|sAav<xu#=cqR`HCu?nT!L<S&q_Bg-1NYB zvG!Em&IGbiA>CrV+}D^dri^j&IQ5pE76&rM7|+ruI?Y;EOTM%+6svU1qc!D;h(aa) zNlB*d>xNq+w+U@$G=CcE(P^LRL$ie_|D;={UspY?HCU>7HRD#FwT6dunt>=}qi@Q> zOGg=J`lT8AhpG(C7P8aRZkg7OlB{uDX<y7>^WoX?D9TF^g>hj1AW1DtBpF8SH=9e| zQ*RY(wh)E61ZCmj%M3pw!jfB34I&EJ=v$I(yVsQme7|5=*jZgiX>lOKCiAsvBL7bL zmD+0yIG2{?G6T(H{if<vp^`-JkETTL8FYVFWo-CxQts8p&G@KLD9t#UEks3Ue>e4N zv6UF=`n>1oI`V~r;U1I5PN8#7%@(pzp(K4TW06zt1{lvC45jf(vxV%eh+n3W&s?oO z9wyb2JDD@gpQH3XFpikiucpGg&FoK>@gnHATqxnPdH>nIG+t@85Jjg9UZr~7B!)VF z^gpV|mtVRY=S?5U5QS`1NEyJgUvf*+LbIt<KN@{BTgVPGN?uakLRKH8FFMIR%kDK# zi<_eJfpOFc{A^0e@ezOGC^0WfcGy*0aa%ovp)EwI|K8~CRq^KrM8uDma>c(UD_5Qm zq;{p*LN+R-I};5b$tyOMQXC9_eEeq%*;S%*OwA7sOZlU!^0p>&+qd?{FHa+NKJ;-s zqh04U#8AiG?YCp)Dr5Z>w~TRgUaQ%v6R4pAW1iE@`99@O+r4^mnH=8KZ1(Opo_uI1 zJzI;9?q#HT$xj2vDsAsY(CSXJh3q<knWmw^O{`gXz>JNC&rY*FTtBLPQ1gLtV17-f z0kiFllX*quG`$``TZqD3n^d)FW(+Ja*qkp(pXnnTeM{15{#@=YP8v_{8>s6afia&< z<?|Q*cYej*B}qN@mSE#bGkH#>&J?+ZO7wnf`ZlcrjcOCUj5aS!^U5@)zpMS+vDIw( z_o>ZB_h}P!{Txv^#z@lp8;|6g`yLs8M+~BqNzE22LEn-Tes75!HZ<4x@$op_c!lf} zIk!yxjt`-j{#BJxf?Ye<QLg0XtMh?z#H2nk4LA3&W-?6=JeDh8jge1`?@c*_W(!f6 zOOUE7=j0>LJmjtOf~gN`wvdeqCFyXjDe{a>UyY}0PSC}H44i!=DQ@I>d4+kty!&d9 zP8BM_{DIEsFD#II3^T}Y?~T#TgNVX8SdxlOSSDAw=^^iY8K%o*PzfrOq|dKj$+KsD zQqJ8EBE}a}6WV`O$Bb8gKTNZ;mr+lh;FaX~k^X*@`k*?tA8>gsub9+RiHR6Ut2+&a zBM$aQy0h(?CYzq6DhsBD(21gE3sKlN=>~-9rrgE<v|<w(tQ#4SjlLzR=(K0@-<^x_ z8GL{)4rJJ5zNcKYisjFkcw$bb+#u3{r#Bp;Q-w-0<6oK_5^G!j%xa55F33xiCR|Dg zrv9PXLX>(Ibt1=y80tCaqiLz~<VQvLqISdSHHT&k*{D#G3f*>Ki%&P^XO#B3IFR9x zm_u<?wEQ`v-(K#UTs^>>7ftD{Q-w-mQs0_rg-0Wtda6ITb|a=t@6VUiZcOjIG+T&L zRT*tOEbC*(5#w9)vg|-TZ$5aE5A_et7P3*HBt0n^By3pb@%tM-^E!biEQNPhVw+=+ zc}ChFvAp}Mmhg0S^;BO(NOgOrY>tifq+7+;T8J9VS?QbFP#`KWX1B#~|B{f>)2N;f zT0Gq*q)ZR4MU2OuJ;bmBmAKcOf&y(JD%&rK_FkW)c)G42MskTBB67rZW&6~k0#V3D z-;$Ivew<);MktSGuG7VV44cezmb`V#ri2BTpb^NePpGJIw*}AWy@w+Tm5ec-w8X{k zr^vsOs=W&*iTM}Ha;F2H9Bm=WFX^JiKWPcY(T98#?LJO)+;&&7tFVeA3fbtJ-WBDW zBy#2)@ffH~)y08~_^?Zsu;8b%r>h6~7+W_|l=yjCY2s2>rwWzS3A|<*JFFy)5(|hi z-ZDk>p59Ecds>mBEkyYx-LgoT@roqvAV%1lNa5zPNx8eTE~(ONAsZFa>h9qbkydMr za(`TDj<%3pC-8}7*s}U+>5`8&B_f4G*F5~=>vB3D7>9S(Ez9iezf+pKo*;&EgGiCu zzbH@jEk+E@7NWBKUQxTcOOe;2{^7JZQjBi=TB$M5o+Ap`sF3zc&Q1}>pH5dgPPYG_ zIMCm7%RcWsw8xx}eB2!vDV`NA#G7uh(WycuInKFsZt#GzK6hgH^qwl-?rW&5YFms{ zX|@n`A}80fZ|qv~;YN&}&!&j$gQArY<?J}3kc}}(Qr+59#ly7i=DoMe=;A<zE8V5; z*sP>ybJulLy2FM~6|ZbI7%HUO>QteUY`>S5nX5c##Zp9#BYl#1GT$Jlb}GZs7NQ&y zGcD5+4|om>K0rREQsg76Z#Qh3R+1wM*{D#Gmj0X~s?9f>i=V2Xivt<hDrrnyGf^~e z(oWu7rlw96DzQ(zK<@{=JUv}&kg8L!CyJXT3K|_A(_2O8Yly<JQj)U#BE^nF8;vdn zn{Y%S8x>MZ6jMdHBlVPRGbD~BinS@z9kS=!D$@CO0F`d&m`G9PcQM}bdR|?fW4nsZ z{%PseqA9iZUc~U-HcezMTcQj)6sMpqL?wjfNll53H4Y0NMGTiMQ^lzMvy^bV90gIx zMun7%9-SsSb{MV<skTEwTgXlblTtf2^P{|E1o=o0i4?sICHSXdc{!pmj?DOPbf5a4 z6gu@GM&{8eqRo_|T<X7*d}y{1<&gN380RSRP-1k<m?9>*7vPqnhZRI28+}VsO_wNP zI=WeD^)SwWaUjD!QA!<XCy^?3c3$`QR8jeTA>Qq3iWyO;#3AuFy&hOis>Twdd(ZL0 zX!k;SQD%;ewh(n9hweEq8&7W()x6|J#V9d%<u>I<;&ua~kd3}+*ZIvvaVK?!@p{d0 z8RI}koxtCgwI{36Dpg%OXLsr<uJ386EU#ckXGL0ssKnLvr=|76ru1b2l`)}91F_?U zuX3h{2d$$tTZqDM5lB+M#GWE|_g3YvA%$sgNwbA)^esstD<eedR>zfor#*CWAj3aN zO0}#1kj~ZAvTD7wshBi7S{Z++sZJFt!T0WT=k9{57+7>-@*WR&S{rD#5QT5w>Amy& z7D9a6YaV~Uq3-29vQZ)B)Lo)P^(Ah`Qa45#u|AN|)HP4));5l`U!wMpz>Oh7emzt^ z-6c^*6e<afky6Xv97V6N!-&y##bi;|u7^DIpY;mbLX_GncfKD>BXu8Q%(aga()5wW z;diDO5ru5@ElFjDMu``nY(0vkEY$ULWZ)=4cb%Q4h#dj8vg^}JI#sCTM9w#Q?bMj! z@F7)6C#Q;>vO|nJI(^cOSBS!~l5(FNQ$?M(dyU`fTvHH*N>HJCA8v}cHRzymZ-@N4 zaTnP*6G>9>E0e^rI{tFzotHWv7)NIOJ6cJ^Pz~0hIQEa4DDq?n$|Gu((9LRy!r6zu zu<<rR*nX%Wx8ISMBMOzELVEcUGfv!XvP8b*UYMgTWM@UZwB+ychBDWBq)Og3S#;gv zDR<xen#M#;FUHX~=9}ftupPuu=Z|zYPV_3ZQg(R#T0vWg%8bvo47B?}jDf`Pat#*? zUoMgtOF0Unkd3}2Y2)mP;%%NO@|o8QNR?&_*)gd<ElT)a@}Z8Ry@yQ}?Ol7zHMg$U z`M@}^O;ZLica%sSSx=t1FF{6Ih{E1QFI4tS6iIU?%kkG2D2PHfDkO&QSmE>~L0&&$ znHl3ihT3*L-6T3!Q|FJKlZOja8Bh7sp2Ip-s06<UK{sW0^%OIEE|7EM-^geSQTS~L zdYdsSM3inHEHApfS4I@FQK2N628<OA=O)N=+Uny#MrQmQONsi8Xy0cv#bMv6m$=t* zjojAnu}&2#admxd@g3NJaw~QISkq^?P>P<Acb&{Hqb)>5XFsv5EZ2<~YFTX^IYMl_ zqsWct<d+eJY*Z*ohhhhc%**HG$xc&cw1w<CfsZWXR|Hs9rS9+&o?hGKwLfiXj?(mE z9LF4=(LCry`*7+G%i|^f!g6iDJayeu8EqlT)isOO(Lr?np+?@hh>ytYazI|WK0iYg zve7r4O<e6ST0Y5=YZvdVivt;Zy>HX|^C{#*Eh}@sUgAmPM{@J%wK`R(WN7d$x<MCV zRaLTE7f~?tt9)tW78z|JDmt6ioW>>A$mbmFDfVY&$+@*R%7{WXDx|aRZv(}`D%tV@ zLy!^c0~tl>W#*HNQRHJJ#nHAvSMkE82)l5|pi_lPTwVX6TVYFyF@_i?TK5(Qt`=b9 z9>yzZ3sEtt7cBOPF;wUN#IQW<D`wyOCD&{9%YZ0kqe4mg%iK}Kjx5I}-dV4pEo4X9 zr;@4!@}bVoy>@mGO@@|cwuMa8b~U{ihq^bA8Nbn5A9-?H3U;Ipt7mqW(H5e7vJTM= zy1g`(sO_q7h>u{g6<IN#!ZM<ejlL!6*M~M@_{OR%kEdA|2Qsq#4$<z%L5gEI`M9>p zLmZv&%+|y=)Tu%xfiZ~|pR6QOrH<53pSg+hMVhikRgM|Z7NXMAHq+g~GsIBWAC;Q7 z6t%}SWG#G(QeL9jLN+R-J^hXiMd9@3%w~I<5p5ycK5+xJ_Omozse5D#vm1+wiyE*z zheKpUVI0|h3A8>>v6gPhBp2a1$(@ae=|_3HW(!f-esR=4&RfTliK2n<J=&DrookX2 zg>3XqyDTv!L?7p>tis)*bi-7$h3w4um6oQi>DE3NT);uNH7Uiy>e&-R(~EIbiQYml z)&<3(-cER&wS`ZMcqmu7)q{39HCu?n+l{o#xv-eXc~yxuA77I8cQsqcM&EP>S){0l zdD)s>4BAbRYjGgM)pZ%IiY}8Xb-ZdhGn0?$>&|AKu+^zTCH_gXskPsv$kj~0`Q`$m z$eT9o&8Q^mQJO78C4|kTmy@@sN2x6_{%iqJYf4*IZP{VUsWn^3Muk*XD=LZIv)i&~ z)2iy?KnB*PBvo8%E0!+vVY@!g)2TuwuCD4Ab}my(RL84|E_KDZ2L`s_lVU_$h{85a zr>|)h#P>%stI;urd}y}xY^_9S_H02d(XknO5?)<KTgbM_TxFrVk5szqxV!E}QStY9 zSGF_erOpS&kr}^;b~$fQ>8c}Kv!oir^vsL>=y1!3wh)yWztr+D;yN+Z_4yY!XVJH^ zk)1nIo-zQ<7P3(x`I!HUhdTCSQ^zKGpe<xaXV0hG(YL5{)i|cD`@m~|^kaKkB<Or# z94B&SQsn9jCAB`>J@0Yv!E}-lP?L5)G+T(O6FAG_7=4%exjJ68-Il{Itq5XvlcpFD zg=|zvyPVat_>==f7%yEzL0ianjGjn)8CljbvA4%3Zu7>EwRpCL@+(a*#t|Gm;a|p| z*3M>S@ux?JF#q*W3}_2ciQauFj%U`E=#YMahg*g-=NXp_h(b2{rq#r$vpjnHK=w2> ziryh=wvcU~IF#P%KO`S&udOux1CJfrg?+EOTSgSdfqj$qWX@jY9^2g6rxEJTgk}p- zI7&!T!8Y0a*rm>F=bR*6KSwtDrW*WmlZQ+VVh<({*2RI0Bu5jqt5?=IVv1hji}Sg& zfSV<Cs!$2uNtdMa-FNc~zr0vza&bBt(QF|KZ^u)wZDQe%zqVx~A4|IX?Z`%jbVI1# z3BGOXaMtp~XCu}JGW?UgEG~hssa>hP_HVwIyEQbjK|}3zs!)kdW)0ds|7eYTVY4fI zPuNfvdh@XnZ6RuDYBkCLK3RR3N?zwh!{|+Fvu`vqXtt1z3Mo(gnaRBd1+(w7vW#d8 z*>wVKY1iPhRaI!2-F&F0k-Zt{K<8?j4~zrfY)I1blY9B{tu0vBjB>P7q}f6gz8;~q zZR12<=3)zWsYH3*`wwKJZ#q#t#Cfd>Bbnc!FkKwTh_L@f?{U6cN1sn&%Xsv|?#wRp z9p&wsDpca1^d{xcYbUiw{n#1H-ya^!%C^olqAf%vIi}MKp5NAa(5%GsHy6T~UF#QA zgPJX5qi@=QG#%%y%8X+BTXk2kK9CWUT9UrvkxTV4gjBWaxr9G?I-d2fb<YD)sKhb) z0==mEO{1uqS?+kVlLwRyV+TH1C>PaiAxixULtxAo^3jPHV>a*S&DM=(Ccg;^qL7Wg z>05e+Yy9BXp=`v5)w(#4(bTmA<-0GeaopN+mK#=vux=OL>r|nVSAMN&K7UH3+l5p` zxIE;%(O@>iJ%e_<G+T%YjG0a2uKH%QH!;?kuk!d&L)pBY=?bEdjS3~n@ahWR<vxtn z{Jvfn2QsjCNm8faTYOA+dgWdJw@wu*xgH-%`R+q%i6NwFch@U?>cC;_(CSzPZ6ONB z7&=|raG8IbHjKRq-l!l7*{G2A8HS$YCA$r0?LGG?Xbagm`_Sp@y*vC-=3w@#^;ew_ zjDx;8K=a^j8hwUQ9N#b8;a+Y-ShEk0sFi4QDxz=>mZSydyL^0+A#7r|2MVH)jS3~{ zq2En@=lc*gq5m`8e2#3)254uy!hL?!cQCv2_>0a5#&IHN3AIG^)t1_$!fJfvxk`Vw z!|}@h<Ruykb0SG{J$|2WYB`uiM17(?OAUoeP$8{rmlYFTYjk5%7T%+MI4xI0wj`~l zwc0<{{!wDY58iuFAGR^EJnf`vJ}?fW%_^D=E>b^N&v7bEswI3~Jekk@w{)(o+0vsn z(mG0AtMw<wj*Z2{h`n9e-V?cs9;LC-H)Z<wYm4VUJz12frHcdoVU|f}cikHbv7iN8 zFgRAHiuNY|Pf0@97V77xsXm61s#O=7iZBm17Q%jepe;mUu1y($Zv!#0g$FBty$bD~ zYqpS$3h6su<=w>B*G*a5YIzK33)#3TrmqNAcNJ9>H@1FDyv~O{j=hwT9iceX(%sV3 zM>J^a$Xa|$P|#LFn1;eV4mz)`*-RYn)r2`X2apd9rDtpL(XIG3ZG_Xjs%)NPrf#1B z*$H9$>AQowsMoe8RUz?BM3?Dq%=cb~&IiVk=)Hwj6R9-r_E1~NC3jI^Un3T^=PfZb zTZqbv*i0+oWNKH87_C;i2{+N0mG1DBMjy=<vQeQV?F@Gj;|Ca6yvq;T3)gHRJ1}M? zy|p|?akM8Nqbt=GjRF~aa`(H=2gadq(<{@y@j810S(rxwj<yhmy^Gd3m7PV%8JSJE z_e$44kc|qd?VhbGY6g3-EhXRU;y^}{<0@L+nW>f3pg2}!<P)pb^k&`sAJbmA79lF} z$(sJ}$S^FpIWZdMu@mFk`>|CKKWK#0Y#}N$US(LQ2J;f*c#C49+|aJ<=ky|U7e}*& zZ1hcQ=cZ42<0=E$@Ir;@#6+`&?1vG}X%xLrK3vGhZkxyaR_Gx1q2gl&Q5Xl#!E_UF z(pmmX31LeQzfjN?qA(kfq?7Jh{GacGST)zzy7?U0=$pQz<NlP#Iu2yd^XcP2My_)s z%CFS@k`FYJ{*o<x*N5S(z{?*xRj5S$`<(0-RD)$H@=?c6@{(smSnx+1j<ygLX1qmj zMsJZ1br0)#q0@Zv@(`9#rwB(BvQZ(uSF^<PjW0&C8fQvyw1w=1u;`SB5l>CcU7wMU z0}mJTyQjyoxo-J%K2*kkncnQ|F~m?;6HXLIm7%Yc?951ZCaD-lTZlTlB}d3~!*y7& z`gMwN6_;@T)Nw57bY6}qWTQe!YPW0$Ki_vW3;d^`E)Ha*rLCvZ%_JX7$jA5T*-H57 zNETk$R;LP;bbHi>zDK5h_hT*nNvHScdwWb`g$h>TXbVwmV?$DMoi9_{H4uXt+VIT5 zli0|24jfU)MuoJxvpd2gw}-OW`o(o|AcMXbk@CtfjqDGjKcnTvyqD8hHp#xBP8BLi z2-`ra(oCMN6^Y><xQCCL6UuV>xO23HsI;_K^zF73VmzYryQfFu`Gf<bSk}aPR92cT zWTQgLWIhh(^%{?26*?>@Rhlhi2R-SM5*K^QG(GqT`A`}edHt>7?7i&>oezwoQQ;qA zPWA<2JS9f7=V|48d<c8r`2t5<h$?q;3B3V3O;K+qM)x_RdC0ku>_@2;98t(dh4eDa zX{az{-If>ltTN#F2c9(GX%?ML6bTaMyYJ*)2cGFpGjK-E_Iql1(Ah|>L_N)@czL*3 zbn~?Q*Y-n{`)Fr$h{Cf;T7NtpDoSs-DyRJ3Ng04<3)!fUPLjumir%)#^05=I$cJ`b zi)=jYrMo!k{l(+3ck<`3A37fxheP5ux;yGhag?Aq!s14VhEd7#^3-A+Z6ONJyy<+f z;Be7q;3>I>L88-e%@(pzA-$VWMu;6xj>~Q2V!HElWUF7gp0TR3wV(Sm94IbzdM@9{ z|3*O+#u1ZhA;u8v2<IO;M6~UhDVMBo%h491($kL67vI}cy9%Q}cRvjgN0wZZjXR5T zJxWu8z9s2k<^JM{{X1DnDn&jtTgZ+{-Ang+!zqsC<YVQM?xNs`B5YRgJUSm3hiWOw zF^00GqEsLCJllyyJu9%c9f}e|vxTU**lm_Nfs4uhZu*n)t((|g&xWo0JKw*m{<DQ_ zR7f|^e#l}+-P-Kiq5>Rkp^rL&+bAPfUp1B{Rhbvtiq@fyY)Sfi1yL9W=5vy?uT?X# z{c=O*d`6<1nVKy`VQxqLqZ1Q1-qm6`*YeU>qGguIM&I<kj2tHRm#f8I?ar@@0~xu_ zYb{M(x0yE63Qv;KI=YKNry8;A&+_P0p%To4=uJbkqxfe{8|HJQG|lIlEkt2XM04!} zcd@vABX%<Wmo6hiHY%jM2Ah~D6<Uk+yQQxWWaK)>QJ%Qe6c#*z;<z!srYP~$lf4;} zs~`%MWJN5YbyNaHzJVCs&KX7V1ZP&iLq3W_vxTT6#}$-QuOdcoVpu+T2szM&l@>*4 zWYBCO8-3I1Yi<K^;jTN2C|7}_Eo8g8s(bw#$$l65Go_+~Sn#|fb8;xD^MP^rCyk<v z><FpaMvQBBN{i{eJF)fED{{1js3gZBwDQ_bWhE2i>~MS0J5MKO^PxOP6tYnvof}+z z!KeENu>qYbQyiKtWam29qjq(QM$whzLlk+&U6KZ{NneZUd|(`y&r$9ZaEAXb9Kw3# z*iwCHwh)E69nFQGp7I1UeRrp1ab0GKY*a`$;<tR_P3-B--O1v*IFMnVSeI6J$EkFy zQ5**<rSs0^hOv+xg><S=3FZ&9rzlc*iHF13jj6758&|W1D9j~j*WmqSUM(<~bx$d! z%Vdy^3aPA8e(?7py;;w_Ocw_-k{o-}8RQOYmeIdV1|L6Q5NkZVk4_aTNph@1t>l2| zL7JJej4gfh3EMrb7<+n#d}y}xs4jGKU@PTU@x<8L^COQt8Nfab>Ol<67P3(x<%#Rx z^HD_@yEW(?{ko853)!#y8qsX<7uCgd@-g-DK0fJ5KNi#Bpw5Rrjv`cphbWFk#OVJt zlXv!z*~|h31lme+)KIVdD$xn=UsP6Yi7{*LeSYVRiOu`)g?u1NQ-TU5slkC?{Ay<x zHZ8gY-Ky8(Kz|YT0aPDq-w0Awb$H1KEve6Hc$e0xLM5p=>aRMiB~|J>mXUAri_2S_ zSYjDFfwmCkpER7-wb4``rHOIvL0+-yW<7SUN@0O0WTQeli@Z@t-1T>61zs1{#eodj zW+L5TSxo(7KKWRy*of<+oLCh7KcY~Hy5{sxnr<!KQhjX2l1|lF;iMw8R?=)Cs!H@+ zi>qrC#W7Beyk=ohFs3@28D>i_cr;tcM&FY3_G~GUl)pTyFveD(Eo8@}##jOdhnP}g zdy|h^FN=wcSq`k)v2r>e7)PS_T+7C{Dx*9xSbInDdgBZET1E|lwh)!*y~dJqz8x`I z5Tnd5JK=xIfz6Ax7l=YODx@2Ym#T|*S(RCf8Lv6UfecsI#k7AFMfDL&J}!o~5XJs_ zFIV3w{f{b5NhJNY!7D%Y9pqAC#FcL;R^BejCa{w<e`vN4<)5^cc2Xm(>!^uWnv3ne zC7E&Ud5$P#qe9x>{opUwxBemr6<JNQfo2QYiQa!(mcMRJK2DITr**wWz`6^vdx5Vy zA6TM3S=%X&s#Lm@iBWlTFLAv~io9cvg;w;MEkxNT9=4Rv|AAgw93)0aW><05GhHsy z`W)^1Xtt1z3aPvn`H2^6zQ~5U8+38#89Oa}Q!gsra`Y#Bb&y!t+9EePxkjf7m1M>r zv8--Yh0u2N$1!n`i2Qt2-s$Z{k!!XPrDlCv-hQQVKXLBTHTl4{`Lr9Q*+Modl%$(; zhKemmPRmv2x#{wDWaFBF)=>|Ki1*$0$?sb(()qwR>=RE|mR~sKN#Eq9INVx{6l~#c zc}$FpZvBBM{W|LHsSt5&aI&1ct{Kfynk`g<3h6v5W~?v_o-fZU*+jRFLN>mLq5Hc% zhKWv(V`ax`t93pwj;si7*}iTzwUB-E$9QavDE76OT%=YkF|?ODh|<5unJ{vcSavHy ze*AJi<#3uUWTQgzGoh0x?of=~_86yYS6GAU4X9k_>D13#Q0Z3P6d?S4e#mwu>*`tw zwhUbF&<R#yAMtWcMRx3i9gQWLEkxnkN0M?{^%9XE^RSqn^>r&RWTQgb{rJ>gtiEc? z>b@MKivt-6VXG*PMb`YPYHc5JdrU>P`MzEiD#84k`bfFf!tkI9D_yP<t%@{Th{9Z( zZttYF7PD-tuwpiqbeTS~Q6atNIOr}8J+IETK3S!U0~s-?(Uh00p?o(#)yME|jYQ#5 zuB_c&`W_OfLM51AOVW(eWkk2*KFqSK3ze>B3sIPB)9cKx^~LGQZtTdY_PR_T+31^U zkZuB=Y+8dAe|$t22QtEp(=7D$H;N&JT6?F!a-!`zZ?>Yow@wu*!F-PH;=C>`0z8|s zWyj9aUY}-5kJ54?TBZK1Ag*OJW98HK>M~1Yqe9xVeAhtqnc&3SR_)itfef5|=%vN4 zQlex2`t056S2|Ugonih!GfuwBV&~{uZ0yD-x_J;$I0sXYT3ShrsaumR4u8oJg-TGN zBwec1P<)v4gy(ivv%W7Wbpo5FHg~;5UqySC5}n<MzNdbY-fZ8eCvh!PH^=@%bz(d7 zIUnX%Sj63N7l?Z0mqI({b%}kHUfmy~`wT7U`|axP`DFhqT%KD}BsOvvXbVwIU6aXQ zD`MX!hW&*5e0_XDu{x`zKoqjkH=VIuoX0!%t03-$dJ43K>@G>uXxF(-s(OoqZr#_6 z;WaPYi7{*2>U>}vg)_&|cOaWl<Q8H`J4(>$aaB?CUR!~-5EW)zAcBKi6GPq082V~9 zFLtTCxVy+C5QS`1NZ(0)Qc!t*w5nL*;4RP=vU`<C7g-SvDUL(r<9W^^e!<^P-0S77 z^MP@wd%cd)HK}yfRZGjhu1eV?J7Ig@U!W~Sg|9eE*;+ZOe|3HE#Q%`e@Mswkc(9W| z6tYpFBwcYCqP%WJdG+qD0&OANC#!u*dRi$eD|Mgj%iqy_=iAbv^T#$i9~ei3{dQ_4 zl_~Pg#Mrcd0yi7;ijAwgQiiPALKNL?PoXwT4D~x(@9a%{^-LRa=8_++4K!QGMuqgs zw9<ZF*WnXio#jhySF?p|o6Hl`O6<vpdYaKO<RbSSQBV|pz;r$^4%y~@N{(}Nid_AQ z+0zF3#qO-feEF}I0&O8GFy<x2QI2Xbo)|H0?(*tWzVUl+OtfOrY#|#J(yK=EX?|ev zUB04M7hN34@X6Xr^&zE(1y3U%^OhGCl@k8pw_ADWROyx6NQtyBM6E<E-QO3_@pT8D z^3NqYQGK8-4Mn$oQ*1J`=)Hb0F<za$#SesC<0peU(dte^AsZD+(tsr!c_G_-yzRzb zx;T(g?q*v$V^M$YM%_bhVY`hd`#j*v<sLd!s3godlYV{Zz9l2A8!-xeoW*atWbsdO zpg>!QGH*IgqsCo|qb)If`Feg`e#EcE_M~2`*+Modq<25&Ui|8z5ByqMfG!R_Lu=D? zvnKI`vf`B_ye{?8sX`@__+I)xMBY?drIISUXSF@NGV_ViVSRM{15wyFB`HDKue2!s zh4;JBPaq2W2P&j*A$?nK?C>U^P-X<^`Z=<L7MG=;+b%?{eFmxOFtw_Y=Sbqm%RrqE zjKe3Z0)0E~nZ?t!D>0mNP4d2={G#06?gDKg>PGxK<{bFZ+OD!btTC<{nP0s23ZTd} zTgXO*baycEi?Mn}LD6(bPhA|ykaky+V^XV9Ygb2~qrpu6-Z;N_{!Xt7m2?@H!D3QN zSo=qlQEOz`tBANbxV=DIh_b8yf$m_|vW^S`D>RccHx>{*XLc8eLbgt!6u5eV@y#JS z(P4wXE)Hbis7*J|GG@yzDJ6w;*juLxm3S_EB_}z$QyeK2dF8_ojHfqL78_E%b@K<J zaPFd;PKl-EM$^lPR;M}$MCp|1N_WTP7}?XsNesQ~uA2vu{iW+c`c|2V#$9zjA9v`I zJlfV?yld#D^MP^Pb1LW=o$XGgdyW|HPNi7wueKttdU=7i5Y_gGEB*3`Op&Xn)v=E0 z@<02_i0|B0APU*2kZvK(UM5dFUq`$)G}gs|jBZJZ^rb5wQuTy<tlMtKCgd$38kKg^ zsX`@<3p<gj)}-n&F*;WNDZ9E<6g{R_5oilh31Kzqmjrx>@roE*<R9`^rGjYKs;WQ~ zvQZ(eCPJfS-}a5f;}-RGaUkPCT1VMv)0yTd^>-9bm3S?0N~kBE$fb3vP)XY(`8=~C zI#J{~#Mt9-PPVz~A%fl)7ibGn;VY6@n6Vqxxq45==Hdl;M7+B=wxzT{6tYnv-3xEp zOU~}^CWZ{Er;7s_D_fPOJh(HddO@l-Ur3OT^S0u0vW-p^Dk+?Igow`WPK=+#xIcTR zu`ur}ewVZtXbVvpp9iJ*C-tEE_(2S}E<SQjm)0U~N+p3PWTQf2Y|1vz*yAFScgVUp zkbzkyok8w=r)+*;5^iIibgEE^Pu6nE^gEHN=cGzHGLNs=?j%knHPhw0h{9Z(BHwyR z$vM<Wgbi&*<E~~4m7qdN+BJ7I@3W_-xN6%}m$xH3E$w8At7`{qeS8ja<x8u#68WO5 z=zL%tul)9<WXAhbOZ-f6JWRU5a}pbhxuInR+Co&A@p6iNVrN>h<PziM{Ehte>?UG$ zL`_;1X||A!3h8~6+e0qW%8FJ!>gnP@#?sWgDc)JFsB|BYk5_$v@rUo6M2{QxI#sA- zc6Ju!yX~z#YEOysBBM-k@hgu5{hEem3sH&Q@5x6SYgz5iQ$Sc|mlcmJl_^`%Y#|#J z((RqsS9z1VtwsNoZ(RLt@ZjLyR3<iFxz1N<b=Qslp4ZDhac@diL~r_4s{+&qr`CJI zJDhYEE;ow^L}46QhIA5ld<b7w)mN05SB!EW%@(4tHtCjL*RwqNikG-CKEJL$kd40S zD}uex@jf#<h%vKX>Eb{}LYP8%dq0Z9mf~3Uv<+Y0qMKOItDsI5D#>-8ono}<M>S|e zjKHy7`J$=8;=1EW+F{XbAu29*SxQXmKw^|3#@Nntd6_=F=v??U?fYo9kc|o@>Fb)G z{MiQ|k+X#B;y}ji>=#t$eJGBS<Rf`oJTDUzEV?~eqf>=Sf`c#8=o3V$$`K=|qrDjM zxve<ADw1x6X|@nWzmr01gTPc;gAgP0##i2KVi)22bTda3vQZ(u?sxK*-F{CH4=T9v zMt7Yk+aE-2sgjpn;xiE&JDBWN^-9}Pnc^5kzd2c+e6(Gk&*)q!O4Jy+K|$2g)S6TW zLx}C<H7q!oR1K!cs}N&$NSqQrFhaDy-j<^+L}4k=ss6fR#zw`biQBFp=nMOrEo7r_ zdV@9CU*<)|i;(MGbaChy^~Z|L_yJV9_N3}fL3icJ=5R5z{wkd+RC2YG3#|tSP)v5j zX!E72T<=1tI8$>!w*y;<dR}V=t;+gQSrsS7<Bj=b$3tU8;hyU_qL7UW>AsKuIb*Wp zU~%~RLyoqPJ$+R^`VF2yilZR;@a>U@_edEoqK{d0J}?e!)3oEYs-rToW*@QXa6W;y z5QV*q?%i!aVBS%1pa^w(r|TccMul`6H&1}f`}Y)IhWygSfedO?#^B%pY9)mz4)eI3 z#%BFHi*Kv#b*fMa&cT$)IBb(k*KaF!j4vwC7NRg4pgZ)vd&^5xyNXIp3h3r@WTQg* zM#`nXDU<0fjt=}s7Y8z)*D6WhQ0;4NB^w;>$VXj$#MolbIHFL=ov-)kEt@)0tM``D zUVfK5?DrKjk8UR)nk_`lE0f1F$62j&we3DzeOb0?-$l$0y37%UZ1hc;<$^eQV%@=F z7u%zY0~y#VY46qhv1~gpP>laFNv8^xgq3Q=Xq>W+3}rHp%9A~YiQ>D1bo~QSIL6Q~ zrtjnO_y$8n%_$KaQK$qJ(hmJ|Zg^-MC$81q#68{K(Cx@GmIrCCJeP)gQ;AwE>b=LI z!TmhdfB*9}#EZ>O8sF_2ECxJ!z!7!Nsg~!%h$M@Y-qCaU>&>3@{+!tAIgV>xlk8i4 zv=~um9Y<S;iW;8Z6lP2%A4Mo<cv|X+F}u`Ak?&+OM-;Nrw<Mi295Wos6E60SiPOb_ zjMfW_dHN@%kq`BhEUQpkxwYL0k@<C>P8BNYcsALSZpsp)4l!O_d1<UQb%gj;IEAAv zMDa}vDDr=3Mejk3W36`^JG)L0Mdn3wL?Ig$N|IlzOUBzxhKoSwvm9+9yL|quo<3Pu zt-CnGL}xjC_6TwRz%HE+jN{#3cC@>Fff%hx)$anc<U*+fgkm|*(H5faI@y>WMBJdr zCljM6kC11z2ojDDuX02o8x_+1M4$C?)-!ieyKXgsaUf&g*!7-{(YI+YLp>2cy6v63 zZFXZ(=VDQTC{&{OpQOkilBzMpNb#1~z#+xO)kQ7>Z6T`LqgeW#(PzX6A;z~g8|8JM zn~SwA90j6~jlSv4=&`AC{W}Ix;6znj9LU)DzNM#g;BE5Jj(qHSdRlJY-$685;jUAK zO1y%G5aSs|-j5j4+PU)KEL(AZjgLTEh{D|#THU?cB(JGzBmA9x1fr0Q3h4_px#4oL zAvPjsvadi}$lf>B(^LKZ+6?-p49y>X&dDj|ONkTno9ldF9Chc;@uc4YwYHLLk6y|H zALJ3^MN5iYvxTVfD<;v-M1IQK=aY}_C3EH1mkJ0wuciV~$VP?q(qdv6c}hxAQPQQW zE)LxN!cw3Ute(Y{mmy`v91maJ9vSY#)th^SzJq^-`bSezRsVEFd2-E0;>%VyU40-5 z+ce##`Zh=&QM8)a^0zDyg-TE%?c#Kn<bF=W#mj$A>iRjdag?B6yuJU<_;Ym|;hbAV z=L6%o+G)AC9)FSQL%l)wI#V&&y&fmJy@}I}SBSzfpYA8#I&kcLOt7$@agTBz%@!&_ zg*4Zu7Uyl&hl^GL(YkRL+0KD;=`HdF8WYv8Z2ErO%xjHu6QB216Nth%nz{~3iLlSG z&^JGb(R|+$?$L3CxDvC3qb)=Q2X9y3G*IN~8U4p~#rUM;P>~=Gb3`E<ebX<pl^Mi( z9&0Z*nR`v%H+HsXoj^zG2PvkS1;^0e%Tq3rY8v7ZMc+quqJLL^gT$^-3+DcHmOQey z6GK$XL(OTgr(`O%RTKSY82zHBBmF&%81MW|EMevndBfYX3~eFm*VQ1(OX`rn%fxU_ zYRUF_Oqch3t*-v|+5g!>Hu|PBugX=~m0_{6-RS1@J3pE&Wbb^Rm*&B0<l{Q|`1-sU zo0qX%?nfu$h{8C^-MmL%O0=iQ)i?$e%a9kBKPWFR+lzh^NwbA0b+^`N<3KC=E5vB- zUx~eVyG=gwwK+o+ve7r~mlUhRCNEEv*R`vwivt-4HWZ?<#D#p^Cm&w3vgMT@Q{?P_ zI_XrQl17cs%HCNus6N!4iC(EW^2@xp<-Da^Gqi=M>BG&kV{`*zsQZbvHa(R;*SR1k z@s12p$VP>fk$r5;#!ZZp@5R>B#es~3ur~C$?S@nzx5&r5IR#nXFNfsaj%{_SP>Gr| zX8Sd!QB>VY9qQ1S8Gmk-W8c-JuSRIL5S1C<i00a+<l`YR7F*m{l`%`?Q5$M9L?Ig$ z(n<B==FGKUs=RNMJ$<c5vxRK>4l>QP>M8PT^0B9-4I44{o9yP_Q0D{VINM<^{bqnW zsZw9K74$E|R!p*Cb?a21?;UHl5an~^AZ5q~VtgaUqS|Fy<H--?tcmp*qL7UWB`IGY z`sU}FvvSqa4!SsyQU5?q&)8TGYaID@mtqGu7H3T|^r}!vTG|iVt!30o)LqVgqua7j zpKJ2SrXOXrg{UQK94Sv!_sCSn_d0FZz^ogxjq@iNQOHJxbl=Bi2&>U&fb0@>n!a+Q z)dw;{mKmvkv>+eq?)lI9!EDj@#q#RFJvvpW<lF>zQe~pZ-xH(M&T!V_U={iA1yM5E zLR6LLR+KY%65|Ci!lV1LGJma>*Q8vM5ru42NV_5116aZPq4NEiZ**}WBWid@YFDn* z&(%8<V@FJ2W9yfdJ0=a&sX`@n0==mQTUbX1m(f$%0{6d@ch0tx(H5efX82S8aHTlZ z`wWF&PG(zM>@-|^9Z28g&}<<a71BGFLj#!o=sfa^GtYH#AOm|BoezE<&!z-T<I@WN zFd_<-+`LF%II(GH9Ywpg3t&ILoi(lv%%|(;h{7?SR0Z{B=O^Zq*VM_!5QR$6H@%5V zohCBO3yg(cE~9Til%Q``w53)p(=U<O(tY#xv@-SZa&@(}#KyLz)wcSky6L)!qS>y_ zJathe8u2w0{n`b6lfjP|&FB{@iqnm)4#Y4LqfuI<Xj<Em7pg3bXbVwej3wx9l<LDo z4BIJ_=%#E7-g`qeI-k>QAzSZzSH=+WA!{d(@mxV)#?x#eJJGuc#i7Qe`Y2mCSU9ZP z#qZiI)A_(Svi<VY4eTzdYKhQYgA%=k>j2Kn(KBSUg{a`*U$g`1OMTFb7>~pd@w53Z z-mvuw`ns5A3)!eplIHmMi+rKixYFSaeLYFDh3xC`&*^qTH>;1D`+AGQogQ=h(lI(8 z7{~1F_jLZzlS<cvR4pD;Q?%V#Ll}BolhGEUWE(*z4FTlClNcL!cM-weU-I_phh;<| z8x_+2RkzB*?wh-Cf3Z_WTgc9JK1qAX>aMdp`M8wYOALARnfJUmK<5MFpxZQ*S*og< z5aWxllh_h$5P9|n%6eNG%0KBM-HlRrAl0|wqxaPoH|I7LNv{^jXbah>kY3SEYam)X zxeJFE4P?D7%}1hl9(ubJK<%n7`LJKqRm>Uui+?yeSLXxc@K3U#uM~7ARgH+TU|(O+ zbM#j}(Crz0(@C?1D4Wcp^d?R{S5xCC_0wN;G87U03VDz!%@(pTKFXFd8i^mt?xOqT z*YrgotxS;dFyaTD6$O$i^%b^llYYX@^9P?XV7g8fDpA{Uq<t@nye2U&+zb%2*5w!H zH@-2TEktES6s8{4i+ofi#^)gcqG<{GX5Wk!<U_NiXKN)wx#+!mqEeKHC^7ngE)HZk zMn9td5tOR#z0*sJ;{jsx<@~~IdZJT>O2!!T(w98dlZMK~$S&j|Hr=l;j^B@=@5yMk z5T!pixZ=o!Pg@r;Z_X4mqL7UW>GsaLPU7Np2k{~7J$>ItJA*)WaBx8y6V<X(&nEI# z2oh`kKl8*+Yji#^j=&fj8sU0UE2%_`L!U!Lw_WFW-eG4Iw1p_2EE^j0dr%FkXA`3` z`U$)C-}tHbW9S<Ynk{6bLVBa<mCOI`7bMb}CmFC^VdU52_t8s#^;|@)kENOAMaU-~ zF|}a@jwmbzJbR&c6ZzKh%8N&d8kakAw1p_#t*4b(s}KB9;~>GFoS?|HGa+Q7Z+eMz zDMI{JuZ$eci_-UZOVZq@-o|U|<&#y4-n&+%^6{qgL0d~qYDM~Y^(*E+IfKL)mvP2J zzn{v8a&;|Db>Kv8$@|}#GbXhfvD*>jSXEE4D<j)Dd~Gd;w$xeeKU7?70ZWc^MXJH} z#5lEOpr~_Ujq#jawu~rbqi=d?F`&6<<9@=J_eDdxX{6agwmMShIM*g09m&U!CH+L` znWu)h*dIC{7>D|;Fv>0{CN+-Q<C&Nqywe<WyAFLNO|yk4_1~kjU8&Ah9}AYZ5#H;H z8;dTk{_mIA{<DQ_R7h_#g4&7evzsd&5-R`e<3C&I!zR;~#@!|qhgu(r|AdIon`Cpw zfDFpvG`$#yT2|g!Y8>9g=<hp0<b3y6&J~?c_qa4$h*H~vnkQzYwIxQnYl!gse8GI- z%H@CS{6AaBM&FV&zg>HgFJPzAgKpkqnII!NySOFWuO*e08pp6-<AvAn@rqOb1v*uz zBs1QQ<`0#js+#vCObl77DDD5+PHk7Sg(%e@9T%mlZJI{WHe*DQNt=|%;oB*D)odXf z71C~P+*q;3d`#JYbp5}o{<DQ__3t*BjLNDt`FJsHl5n>ht<+5!^*=te5{-*3NeqLP zkv?vUa9F-YIX>3mU&ep75S5x^N8i9UQIBdxK7xl&5CslzP@0vDmJx+YP$A91<HJSN z)=i4bp5^~Pas1~`&4bmy|0&(i!y?6;#X^aQtF2RoO4PE-jQ1jj8u^)wK;f&5=DoK) zq1jopg{Uz`8+v!At_RinXeGvpF?a4M<vjnW`p*`!F($f^^0ANj&^?;BiOQmUSF?pa z)XXw4M!grVs(RfoQgq7B%Qt;4@o(h+`M@}6my70e_5PKby~g>D7MEsE=S6o-|2IR{ zY-uRWwP_#DZ?xE)cLvWYJ)LqN4TVZjA!QjGJBfgkyZP5X-*s^yqfTHxi_xYX_1ZS1 zYEhRVVl8F*n|iL+sX`@~U(+hJaZgeA%VA#3=N}pwG+T(mT$^_8=mz=Y`ltEYDpz%x zKC)3Et<QgWh_FMudB?Oe^xJ@1eIO$tEQju2wV_s`j_sk_P2$mr^Sr>I0yHLSs!++& z)F+f7cS`*;<J@atC;FG%&%ampr1hX?3sGUl1LUJU`S2wlV;6de)0g+~(uK-0L?Ih} z(_8&&Ek%Pa!F-!-EnOVQ@X0Dj{ljRT4XSS|A)?rJ-er3$ohnokVgHn}aJ5INsvKs! ziLe3XxH-HLLtBW#u~L%qA8`}^oC)OfchzNxLN+R-JsFF)sI=3>ORO)aivt<hyJ)BA zmWMEGx8;ZHy69A)5*#0?U4@Jj1?H?(X1$8l^>ak2t^L2Tl6q8*w`lg8@m`b5(TTS< zQlk=7NcZ7dN#cB=sm9Jf0-5@YXgSWcs1&<-(RYLChDcRv8C|^8TTk>dn#M#wD&0C= zYKUciS;i%ft>}zHLt!?6^DccU{c9~zdPS-^^plBNiDnB?{~uZ30oLR9{{K!1A)_Lz z5S2Z$>;0VG8QGK-A~QRMXi!$!dzP(ivI)J<sgRXDvdN}wW#|7o^!Yyb^ZUE5uIqid z?$>?4?&pl>JomZJedtrr>Dn(WEAFoCqi^@1lV$}#(bP7wcj`UnSCuU%Haq%j{Gf<H z{buCD$@h78_~HJ|PMo^3*tjXf^Z#S@-)g`*;WBb&nxiL5&qq!@$X)xE;%$G9Ms!Zq zMWwR6RwKu&1)iI<;p_a0yL@mk?)@+rD>79VMN@{b;k2K7-g<1@F(-ggU0U=`w1)xh z<P951iB-j)+V_n;4z<+Spih+cY0T|!bi&A1@(u;N!Vgs!m7=2yxl7~!@Hba_@UGo@ zX~qXdQ-)Z>IZS4g%R6xYm2>ss))U<?rnkp4arby}B@8=!ZSmW~<Jp$+?*9HA&>k`d zaB=4_R%LK+KKn|NLZ!-?O?0=&Xo=p}+M~^pQOL&i1VX-Xx}A4tWn!=LYj;c;)kURz zns-OWKqova`NsLNU@#l@cqYHoAw{856isa-el;$bZQr|?CqDk1ME#(MGaZJxXT)^^ zLm7?Q|3P8zm*CXa`uz%(qD)fG_jXUs=>k98faqrkWLu{1<Lj)~yHQ<K>cXZ@h|qhZ zCpHD*=zu^LuiMA(_U+_Gr6`)(M)eD2D06hm<o6ED*Hc{-UCvBF+sL?2GuVj#<-z*& zDlUF+-J?(`>WA3S5OGoO)PM1-xjj7D(32%am1gr4s*6fp{_21>?*SVvV8eTDOE#mQ zjkx`EzCxuan%c%b=jq1GuQ7JpFYZ>TE{b-y_=;Q;8OxASwIZx0J2S4Fuq^XTV}tq; z_Szi%s_WlAhJ3g(g;{!pljwM`2&1~F)Z?msu{w}`$o16}xB6`7)Y9UK(=&xiQ8Z<U z>U&+AvS({5h&KE8YW$#x8ou^u^ImwmvOP+)e5YIsa}y!+e=1apGC8zvFYcU?@hkas zCmgEI9>mlaKMQQdx<u7Qr4);@h|u@J_>d8=V$B@cqz83HWb<7Lm7-{B8!MT9?O1Nh zqT=@A6&gP%g0?1n@o{DCn%fJ9O$#-wD3cn#4826QU?Z@a*kc5%vhe`l=<28GS5%7j zX^f9+t=WZMMa3oOZLp#0qD&}5<d<ZQW2fq_;PFvEG~<J!aicDx=RNbE)v<XltnTM3 zqGP@78XMG)ItTQa`DBDe#^G$%g|SO3yYPrD+>Pp@QYUlV(dIs>|L)rA+F%0vGi4tC zZexNy7F8ETQ-(U-t;gfpkL7Fl%bAUElYpv=qCZ`0jGbTE<}%hdN7Q0F8#NNYE(d6A zP(N<R*<wdgX1CP_;`|{OcIQ=Nk>}G&PjykLo|eVoM?WAOfq34|oefH>E~*BaDpZQ1 zDMLhYDvxI^Zg1dzE~hkpP=wqu$%yNXQ7h|<7GKkp-D=fP+_cPaqf(T~;j?wI``#Cb zDw0*R0c=%)ul#YAlN;4Vr7nMU#rs2!sPaIx-!_otUHHhay<2#kN>Mbmjk(>SEjv64 z8TZ1(NOe*4tTHvw+a)U*Bg+$xEULDLs8wle5|yHUBuy~IyxT7oaSR}mE}5{!J9~?y zO(i+iMWy7frJA4kZle<$I=~<<oVuJur6`)(#uwzMPV7o-SuxwVQsW0jxIJo$-Y)ar zWzKeihGm$cNITIyxV?rIWm2L}O^m2M@WUF2nJ@J0=T!%>V`wK%by2B02O1-1LS|;l z+HJ*})MvI$8j1KWE}TkHG-asMMHXwwDs*rZv-RsZ)kV?6{F`9!t{41}S;fbf7GsM; zJ;lyru^JoHj~U5T;fEZxmO#uMYG9Q|mKQ7YrXv$j)kUSOW;8?J?GA(m5DRTRSXi5K zqDG^coJvtNWr!7-DegmRSxpSMwU$#|6z%rN9_=CD=jO1n;7$Sd`fLZG`?^JAgZe>p zRk0$gdQG`KyS=Dg2T7eo7nPz}v#8nUS%@ur)k=i@JgUiirD)0!wO9`}We+Rai)3WP zQ$Hx8ZDtFs0KMRc8T?q1_*$tsKoP}le`r`yCUXtW@LaynO@Ju*vJHEC_$MFMQ&xvj zbx|ofSNi+QFJT=JL(-hslF`+KMZ^V8r6`&*)alYLc(dNRT<*0n7FEnuT@)>|w-P)% zVE0v?t{K|#k@D?KbJ4O{VL_#+AM|V%;)$y)*!W-0BD+h$zj<W;>7r8flo<9>Z7o>I zW=_JrP+`qEFUo}4#vY6PKvuHbd44-*mc|c?2wv6}y}d2`_zXXu?sH`N8Kp&`W`8)9 zqD;)EwZ<&k1}!MFUQ#9vW`QD+k14%`Q(aWbKB|NJqSRJs4~cjh-kXIwXYef^ahys~ zG_{RyoIg`o#-HEDVKe>Q4y^M;|B<T+Ymdm0t-!<wzimCfb!&;dCAqsKs~e9h5y`f^ ztfN1qUyc29RchdKcdU@)*skc|ciez=yANic3P7YD3}UW_w)1yELtLpYDn;jfbgg?+ zShY5$ylFy&8<nDHY8&@pJqlt)KF4t8RFG3YC}I+4`LmClMaSj#VPiU*inBXb7^xIx zLgz=UeSY_6A(P+opTX5R)kUS~T&dGtjr3#hO|!Yh)2f=8nxd&~)VbRf#9CBZ&nww~ zFj7A#;@Os#STo2qwVXx2zU<H5B|PIL4tr}@Q6_YL#7e(kKQ{KtTYl+OOHOrBDLTjK zbi7$#cBSqoKDcRj%}h<vlp%8Id-&<ij~(G<k^<QJ{-=>g@-s!=M!DQ}H0BQ-dPcCv zsq5$5V`F}&$lu7*_l?p=M6?wB1FJDAg{*PJ{tCd`2_CBh`k;rJq+-nu#8|JkircGE z;>XEd3e`oWoJ(9sul$qp?}ogG%4hv*Q%_O3iXEd;6isboUoE9JK30$Omo2q^P(<X& z!iM<3udp!@tXftcr9>1OA*=`Q)3BmU)}AV9NbvlQCnEiLS8R;3<E^(iFv5&cT~sP6 zs|ND)zo6cvd{#k*@k;U&FY&~;Afr+gO&Q{==y-GX<857Dad%C8`RF{Heb3;|>+v3` zIhe<5O~Osn6Fe>=CrVZ=_;;^mkqbpx_>l$1&BuE%Dix^LdDMS!11GE|dSrY3LM@gh zxNlo}zHMF^HfmD|ZkyGCQC(Cj-1?iLp-Wb>L}OjDrz|^u&yv5X*a1--RTo85+c>*a z$c=eE^Wyf%prd|JgiXSCgGGiFo|U|RP}teAK?fW1qg`5QSWzZ62|38quYf#c*&hDR zuB`GrKYl#CI&Pg-bx|pKOOxKh6@6FQxbnC;^DXVoM-^}eLe)jll%Y=d(b<tbwz4!H zoaceqlKMpdo;xmSdO|Xh|F5f6i2ZxIVrd|&Qg7jj=Y{toreDBAmoJs=RlsB4xU<O4 zn}A(X6A$Yd`;f&ad&x*&JNC+bPtw#<?f%;MPZyQKSoA3Eb0^=%nXlE@kV-X-O+s5D z_NwaAGEr?KBHZzqQs3__54PyS%%_dVbH9#p5aLnhPJe?uF(A47G@ow3?J9rAKVksh zXB3A%rlR!CmW)cxNS26KKuqv>x@ElKU%d?39*LtaDko9d@yikqMs-msR2M|Qx|!dC z!LQSlC(m@^?V{F<N>MbmjauF*hm`b3UwOrxjv7BGB0g}9Av(*5HkY^28Wx{dM&}k0 z4g(bpE6T(=VT~ct?sWdB?a=&^vaa?Y9y_}gBJ`>*Ds?i4;~DPA_hZiFWF@AriCBNT z4Put6E{diMkr7{LlHxmH4bS{BO5+DbWP7cIjl=LG6n>OODW^d_?(@7LZw)KT#6Ien zAssh|{=3)m=wn-@xPNgzYik%rt*VPkwaq+kxD_`WZ5{?25w4+1^=+|S|78^JwN!Oc zG-ZgKi9Icq%=4D~{)rIuL{%3>C)!;$G;*1d&&u@jRi%E_%lvr<FO3cA$H|;a27mvR z`EQ)~&)1cPm1pwtp?-*isk*3CX4qY{`HXzT_ln09XPa4Ec{_wrDT<~H5uMmqhJAl{ zg6|pDj8R<_eKGwmSS>`GkHfQipHrNr?JXcI^v)U^)Q|YUn;226;JHK`?cah0g}vvy zy6P~)sk*3?-r@nC)gssk1ft&OaxCY~RepFuJ+!&1i=rt*tQn3JX8k6g=6<p68b2r^ z(e9}Mbvf~@<eYdqv?=q6{>~o{{i9GR%0wb?j{?Srybp52ou(}C+jBm>WMQ<2s*6hb z<DQAAtTFkXcQI+iD*k%IO$rzNi}+6$MN`{2S2RLVUcCqwAC27<`bMU!feQ8dVU<w; z>s@)@cGSQjdb?&LL{7u23YDVklH_&ojj1`NKuABD6gsGHJvu@xjh?5cx~No1Gg*z% z4C|m_Ks;}kp=U)xMW?~t6e>m0)Hco!el#;SDjzA*-mlYBT@<}KCKUNTrm3h?1RH5S zcaxUd4a4cPdm0<mkFE>4Alp!SE?dww>X&i0?Pw7db3&oIs8njs73>w6AO;|N;>fuj zjRVCvF?ZQUg-TI0WvJ7Y(*HItJTyX>JD*XgE{c|wtz_M(f2*ak+qxL9o^3BG9jU;m z6!k-%wa)S~`MYLB{gS+0#?!O?#qKe86{?F$<vJ%JqfrOX<(t#mJIUB|L1(dPhz;J1 zsxFGAws9BswaPr__h8{W`>w_hiny3w7};%k`QzioG+Vyl#z0Z=<TDK`%0#jFn*2B{ zFaK@OySf+eI@C+t-%|wRT-8OT?4le{(fV8d8)xZ^DtyvVe=)h#6=Z*^x+t15#Q3NZ z!M-Hs8jaJ%2^trrk-M%77~-PxORp-P)gEIIt3G)<pBL@wN~P#`6#a(7S^ZxT>{6?P z`nJoax=~$JihfNZM;M3(xqFOTGH+|X2PvA`2BKjkOXeH(&a3JsQ9mf+!!`v`PMM7> zvnH1nj%0a{6ZH2LEi1}IqOB8pp_j<~#9v***xIE%mFWB8IMqd^e(h+EFX0}rArao0 zkt{nZ*X`HYL#|Zn|Dx5WTYF>}dtmCJT$`Str@AOwenGmp$lO8seZG81B<ud*dW*K% z^Yv7U`l0=Hj)|GVypkX5UDj{aQ(aVwev9Hf&hQBKbAwU8e%lmH41l7kZM6B3NO5%C zW;gGS^^LJHCfJKt{+?aXTbQC!w#<$Bg4JJv6pIWGjM^^-ym9J;3)`Y8#-t;)IhC@= zFhy>RtXc9C-%tfpGQ(tLBUu+`eeDpjWnwpF`o2QQ3R87aDf$0VSu*z{4~Y5eBE;ij zPu<$<F5=EGRTo85+lbut2o=ur2Pn5Uj?z<I6djdS5IMr_;RjaAy28l1pHb<nvC9Z~ zx07mv`jKc?5UgaLzKp|}xJHPQiz^$;FMopj2UT5E%6E}D#(77yc|jn`pN<eIo#z|h zdo03z6RIwXrnYf|q*WOnx~99hzO)FVGmgBSDNrwK+fDSKGX~<XZeNUbS{D;xx!sV@ zpi13}`+(YZKk-JM=z%J1ID7E#OCK>_?~c6nolc@`zY>h<qEg!VYTKqdyiSm(SU00Q z?v_<`Q8cxUTeR~!v29&m8V@$L5g)eAMa)~~I=1o1yAgu#{>J#-$|Kx*E@BRK@T^+n zSy^9kW;1J?NpkPwE~u0|$CBVFa~KRBlXx#gyyVF+4<O1oIj|Z{KN+*%dkCtFN?ras z199qVup#r|O3kmtbU%9<?{{w}s1!w0+sHy1YRZP^EaOp+J8RZgbS2~B^4zc}bzuHl zbVB_)%#WSnEsIyytd{5s3HR|BYWNODYySO?x|pL>899{O*!RY_v#N_q`TJ)ZPUf`D ze}Am%`BrH=YB~SYyC+zwx+t15M8xabZzZdcKfjdP6SdP+T@<}2^}PW*bLcUWRXpxc zjDE@am@l>(8`O{Z!1sojm>ysy*CpjQHewgY2Jy{SwNU*|)kUSW-{%LN$}^AdGx@*) zI0;I0Q8Z<UQTu4L*fCJA4;0DBHZ()-X#vbKd$8&*f*x*y*=L)<#l;jE#zpb}`!Sc? z^NSQtP792UX1gMXSCxv&DuNkKu3k18g7h+Ds~GxK0uVjkj1jRDKj~i-If#s3RTq^? zv@^k6QVuqZKot5lQfzrQSU=J69J2IOT@+1iV{hVVS24Go(8m`mjdORZ9~2R0or@wH z7VzmPY>Y|iA*L8Sm8?^y=p`yE$|TqM3+hJMV1|?R`ZjVqv9w35Vl}!svR+hORLVLb z1NlCsVB;hZzn69uzC-#c$;ajFqw1n)Y8zD}BB}{v?l$F0s|NTIR&`Nyw$~M$`LV~- zm1lSxUGWhy+xseSZNKAGifV)Uf!l|X*XMwzdliT;nU%zJyPL|5BDL^ctLmas@qwq4 z<;gJA#RX!2Cu`9(@}$zTZ!=_htGXzf+D2Z+)3Tz{mWRrsk#*1$Rb3R_$mJ>GV+~+K zo*x`A!&CITwo1wFTwG&=`XT4Xs4VAv&o?h<DyFr&sEqku3XvdH7nPE%YWOxr3rZVl zFFT8jv$4vF{w9BC>i=|6G-Zgh`r86Tddc?6l=f@>KHdLxQ5!f>iFZi@*pT%TFI^fY z*2K9e+i#ryyB7V=2K8f6stH!ejzGwh-V=I;inJ+P^f4Je@^t3^bWtfp2QfD5<+tGG z(*wmpzp={Xl~++oQ`JS$lp$)dE({Wh?@W~a>(*l3uIi#_M7c1|YoI+OtI>h};*(7? z#jWZEjSa0I1>r|U^!5`#40sYL?tZ+H^nS`DH>zt<swySl+F4#zVIv8MvjYOfiQ#$r znXd7$p-O4ds()DZ6@0-fCSFit(mHC!2knVZ!s3$??aIQ&71&r?UT|AGQx;<0M$_AA zuk=n_kCRBUT4*K^wXzoTW%1dHUA10}>Y`HHKYF8`<Qe|^Kzy8(%j>tep%@Rh#yNIX z7e!NssM<BMpcqtqgK{degT@bvP%O6LTdh$3T+*>?3dhHnvdgKrh81Pv?Ar?&o5kVB zMX+jm?I>S)B3^0HZUB0_s*6em>PIHe%=(&wY9~PSYPpB|hVEB>e(^&USXCEAQ-(TS z@LUsdHy~DN{-CqQ4~j@nzX4X}`Mu=#%wxREtSw5}^L`pulu3Nx;pFu6A9!;f2dkcL zxA?ld!xhg80~ystr4Zdgo6EOPA`qi$nu!jb<|x&gb;azX>Y`}M5W7q597SI7dCJoZ zjWvEy1f8{U2hX0eqHtmd<@_zr|HFzh`2f!gfYl+e`nkTbXl2TjIzQ`Z-XF-C`kxei zcVUG*-By%e>Zvpg@kHEPm7+{2L*z^xY9f*k&DM{Y+EDWzq-dFeZIO|KukGDnl~k>) zDDbD1QhH}wjSc!l;{zX{UPf-pKR<$+l@tvZmQ!5+borY}{+})?m1y@CE%+v-naf_- zaA{vc%ua2gtoYCw?V;+@GEx1*>4D%|-1gZBrSGo+SoNv8C_2$@55{0NY{>Wd+qegO z-InP}cK3c78(KfqzJL=v?T_+_FCvsL1N~t`)kS*@?UmU18U2tSw3?>O!OkL;(xO%W za1tW?KEJxoPMN)au*MIHko6i9JfEYs$YJ=gb<S@7VC8(J^?WTW%A}fkZ`_yq3hg0h zQR^LoclhASZ|@t98BWzjr5d?(z}L%D*pTb1QGxNigiB-PL(Kq2r6`&*#BN`=8~jKG zquxUd)A&IVZ8LvhUGgNqUtJn^l;5nqm<K-^tYJl&$lbZeVUK~3<D=)3$GpLdR6fM3 zD`MfQE-EEgnX;zSzrK4R^btSsCXH7YT`*s%x+t15)aeGzFDO#0{&Ab+(MRJ4MJ!4! zjwdUh?sl*mKhR1n5B|gN->9x(MVSQY%cLw!eSoLC1qgRk-mj6`nDdMZShuUXs8noB zIoy@<42VrYd@E=oi~$!<bSU2srw3GB6ipc-);GpPRI<9KFITIt#t(|nj;<4mhd6uu zl<{zOH4Q7uM4oYXv-q6vhYr<YJ*v&pd)}_58Rt|=J72wO++Nh2z0cTwYz5TaP<2rz zlp$u(=gG>Op=KiYL@PlnOm`&}zq7sE-90l)Vb!-%w#SbZ%F3-K!hBs9O)YO)b&A$^ z!b<;Zj$(D_2XD}(g`m2ql(ueE+}mWuW}unqXl$jaG)2*rA@VFoWht8<6%g+-n```_ zh}ak}MAhu^9^3^#8YEe=^tWGmrFFG6tSFNo5!3OlUJ{5kKs@c_#5Qz!$*)eVAgC@X zHHpu1|975K&h1^!TC&aUKJv)dbp@58Xvz@pk3xPdq~%8Lw=sp&O4)9YJdr`w3@eK} z2AO4p(l&Uj$u)KT5mVUXZkBv@+^ZxiMe9t^8W-?<=VVr)!g~F#`6U&qi%QXI8<-QH zN3u>04!ha+UE)TiD4N>Fy%~K+vuXtjaoZD#8b2uFbmg{)oyb#kFW^UCvrv{&p^7qa zL0t_i%H(E9J48QP!t-n(mUoO`ucyA!hmMbRqq?Y+HgCz7M>5wn`;uPAR5ns6ilz)P z@A`$aE7zavua~K)P+b%)5o-Qb(6~wLW33uW?7p@Nm7;#E4)8!WRU5RXtQX!PBb2>; zrBedhH~H)Nf4Zm?&0)jr^CFbp{$i%=D%KEtMXD~!gxc1Te^ccRdH>tPrn}bOi8HZ_ zoPoJr#!D7FDaPi9))rf*{ZgnD-9K+ocmi(N$;{traJ4MSbW0kDhwd+MK1$U^rJ}NC z8N#e@<s+<0TCf)t>x%mNJcUY8G_{S>{V}Eakha4`U*GeZdSnTn=aQX$PoTEtZuivz z?Xg-qp7QVZx|az<c-3!SV*gEZc&<wME-H;X?sm$%88F6oB;SflNI?YwcVrv(wBX?x z?L^NF<pkA5rIxqsfO=&6fVKj{Eu<$;(RUN`I!ha>E-hNMjh(pYeZ~d&Qaxh4q49$v zv=uPfl|*B?o9#txNO=t_%4BMCd(35rQvTg*X<EU;7&D=lIPj~8pt`6Ot?G$PS?5Z| zo2Pn-xRFH!m7-|M5S3NE3bWyL-zWpRHNh_OHDtHUGswJ!j5uz{_LA@Ki5{7_F*G`B z4}OQBUyVOshE2O!lKCcDVTG(p*+=a$q~;t4IvA1E?S`7ZMnfYPnE~PSAXnM9=dCiZ zk%Gvbs*6fRWyPWIihLX2vMtyJ#2EG`*J4zPqN#1%qO|^(GCZLqOY*3JlX|Kyif)^^ z61&J3{`!Z^Wp^7^$=Z&sMdl2ZqJAhAYYd9T1;fA0nrhKc6}#(Y+0D#aSjnimsFZhN zG(5j!xRNgOmU3TZD`mTwvt{p_;9E`AMbXqYvel2bW@!)W@-u5IvW?{<k-ygnk>++D zP7P)wL%j)pdm=Y(KHeV<Q~#YZEq8Ph>%Ql_vD(2g3YE(CnhkU_d||i2iNiVAiEHxr zH=;Oh5zP8aW20~010&T%rD%*CIgnK*GS^L&c%2?2P)}IZMbXqY;=4A;+Ho(;3%97M z@q;23u8PLUt@qbIMAghEvo}Yrxb?1d4J*nd(Qb)*qMbZBDeD0^9~{EMBHtLBhCEcL zE-K~Id@<fpHSvy;XZ0&9gIKFq<&4KJzr$%GRTo85hNwH3I+4xaFxYshYm`EDQMALo z6=)kL*k}VA74G{pr?8F2pqM+HN>M*(d>>Wif3;=Phc7d(4X-4qE-IznH^>__m{m+G z!aZI*#vO<1t_4L?+sLi;4`DyL#~Ejw9ij1qA_kRQ4nL~pKdZhso3qe!^|<HMni^J= z$*Z61u%lQREhu+PEVoW##l4Dg*M@x*s*6flWURqns$J^8zB?xtHMX{0H=Z06txze7 zrVMpDhZ2)mz(*^-^Nb%(#jCm~I^23I+Pqvot8rsIS@5c8&X1K6REqlXBy26lM}_=d z88&n*D|u!v4_G$>Pgm7NrIx<kjh<))8wPmp@@@<(5@yN!>h|KEYE>6SQ``80eCWsa z^s#oc@AOUM2Su!ZzY6<Q<uPhy-(~G1*yTZYjW1U=!U<576=m|`%1*3HtnhSYPn`c* z&%C`hyLrv8#i%YS^=n5AR%F)sZNB-(0M@N=p0UY`ESwotbx}06jhv#v9&Gl=WMlZv zYK-cl=qmR6u&-vB&uZbjp{$WbCTCIAlBg8*<BeG|W(Ldr_UL<|J*zQ1n!hhvoKam= zYU$gvcvco@54o>)sd-nnqv9pw&^@IYm7-{B8yN~_{l)U>@th^5a_#+te~=r~9Nh2Y z{bYi@R2iq1anZtt2vIYO89#2lYjpNirRc78mX{8D&`p7mQO?z;B8C0Oif;DLYUrsh zDn(<<I6V*&DSp|98{62dO`=j1O>OIR<?i^2_I-Ep>-P?7{Gf=;FdcT0YopE6!0K(2 zDdJm}E~$P%8O({Qhgv2yvh8LYEV{>f@#agq;ucq`OO?{bsrPrDAlxc;<kz1M<}@}< z(bP7o&<-6bw%4m+3_G2UGbW|+6s!N8U%eAcBlcF~@0-jz!3wbqS?^W$_Tdd8MZ;s; zlXkyZi^_Pa6s^NTE5+cprUp~QwNaguc5N)9P+e4tR-?fihee2EGnyJd{km_YQWQ;X z>vUE>h9Co4RuXuo@q;3yrqmo+?^XJ7>g8my>4~}iQl$zSR+NcE{8!}&k;&KyVe>`N z&;P>zvieUKm7+D0bh;`hr-;M5g7h7CfBcL1PZwoE8KRer@nP2&r|_E2DYzq7JxfAQ zkI=6$#KKeUSj60-;_aA{f=bbIEcDJNWHe?}VwR>RV)O0tg6g7D^qU%AUdJmlA67&- zjxVXXKZ>HMZR|9>4rW6u2Pk0=D&Q1EQ+(@p$DC2i!>p&g-(LQ1;8A6t$KO1ef2T7Y z+D9_oA`9cdtFw$$ik^_A=SQ(?vNe*0FDq+|jw)lMx~LS*HA2;h)JPVv`DjwJ4z@-r zMbXqY&WBGKA-?+!;Bn*kD{+B2sL}Q>E4^sO&y@7^^uM|JUWq?a;sZ@muzo|o>fSI= z)LUrBP5ss@RO)0-Udr$#!N~Ft_OMC#lM-gV5_$R(G3s!*m^Z!||2F5P8`VXnY!ZHB zpZgpTqk*WDI$j)Z+MHK+nygSMil(+vQ#K<&Osl_;J53v@@q;4th^W~lG{vsI%$lro zIaIt#?9VsVI*>%AD3e90UlAR&#s0@|APPSjBPz5y#@{!KF;ZPr>X_Z@6tBeo_;wxy zgsXm{*!W-`4_eyCjY?58wT&$A0s*4p{3AT{LXwf{qUapwcc>v$3#?>4nTuv&qRQKj zeD&asMk+=9$cX!ar+YOSl`nvJWjaZ;dpL$4yY<6Jby2A-uk4gWy9a0wM<AMCpD5~A zp1@a3dS|3k6isd8bY`Z%a5!+C53i)-)DMcVkIF#(vtanq1U5|TjT05BF6Yx`+HfjG znM7sX!F<&cPuCiV0euGwtM;$>_kxy~OH^G{%04P3MX`_>zcSOQ>`8xdH1r0yJo^io zPO2`7rnXU4#V|<hOMk*=)+i4fsxFF-jS(sKQG?+J$9u4a!#I)hX*q8cY{jV*^}{ps z3Px0Qj3~JR*q=94e7SLj*Vy97sV*v2!}l=ugge3W?mz^;A1XX=UFF*zROM8PqN#0U z2ssQE>*hb?Ln_;Gs*9o*rJlsoEsLo0K-j1m6exnrZsMai7Sq_Ee*F1!9lhi?W(m35 z*XiLHVZLcMw{xt(sV*v2!}ko{!3FYfMEKD;K$LvEgRhRL$f*=XQ-;{D<$<D3%{4qG zrxN^7by2i^)CIJ823QRNtFW=bBJXw>KX=kfV}ttPnRz!wR@wQNEi%h$l30Jzhqqf- z32m<GqEcRomyl(%FxlOuFKl!f5iG8zgz(FmW$~<3T@+0jVqLv7Q1G}Ie&LFf#t(|H z$PjqC$j9+FhYi~w!J=`ye!Rl+1{zkBNs#_jN^H#j<bOA~oP0l0oGv$)ukW;iQ(aUl z%PSE!p2Lr2cyFECFkaNMn#z05X~L-#MN@`Yw|5&OqOAAu<pmuzeozE$O{^K34G~Wr z_VAqku^LvCiNF65%y16qiLb#b{?#DS-TOXI`dnAjuc#F5)A&kVK2+?xa+$|=Y=rx~ zR9%z_WvJ6lZr)ea*5~jC8(V9}hZemJ?~iVXs@(#s%^5vJZHtTiRYtPL2K6HgaYZ@K z-Cbq?Q902=B$dzMzotKiAF3`YrMFlC&yhiQaWoL_eY%M`d+%`m!N{o;MN@{@!J67v zOm_OhBP`lz{GbRImrW^gfm2e@r_is)nzj_LYJBDuVlp+XD3g;pD^XEyI-;uSU{!H@ z7h(8lF6<9X<5U-wT9mpX<w@9l*eDDe`wn&yQTNQn$kb^#y{zh@Xvz?$GY>Zq$)6oW zy6bkZQgu<ZzyI8n=&Tj!CEvlyu0b79CZd?=JMyQ-2K6J{IvQ_+d1%3vK*WzIDFz*C zDiSJRMGLCBs8pg|5d2t=7Q7CGGSX3mcXJeXPMyOSy{e0%DMO5p%Js#@()C359U&S& zD8f5&Y09m*m3UV5@vMTBqC!b(BSghG4J*pT**6mJ^KEz=)CR(Ri<3BK<0`h+Yt5-H zD%Cb~I-=Y%vK<1%?LCenu0V6~D`E_8+E8^-G-Zeta#|-bqGD;`dajnn4~n3ziJa}R z2GRaYb+N%e8Q)Q=hm=XK^LntFj~46=R;!|WiZ@@(#m0^$HT{Z8X~+5XfX-sp&Qc<! zM0MP+rs|?hsBNr}b9#vATjnC@ruIEZ(OF(w(c5R^S<MHlgm5O_)N>N%VV{gtiu#cm zwh-&xc(jK^gj7((tPj;iov_*%wW=;E6&tex^X?`fHUg1$jEUSFM=_}G2P2iDXlfff zalN~VPJ4=o9k1(Z#yLgM)d1q6o0<!!Txa3!&`!gOG6}cd39px;J&u7@%Y)rT&HjbN z!Fdfd>k=wO*F^Z{M27ciheD!5p(Yp~sxHceGQ`cKN=MPu(?*O=uBcgGQFLb5c6_UE z0;{)R)v!w=QMPyk5pdn%|JYEUsBH6G=bgw%k@;|ow>gRc3q?eFS4Esb)kUSUycVL( zj{xx$h{$R#B79hVvG1At-x2knE{diMG0qDW62l|AiLV*$@pM&P)JAN~7{nQj@FN8_ z#%wPu_(o4L*1e0y25pZp>j=zn2f=C^5X<zRxpnh?;?esWXb)8vl|n@}^u#o*MGpW` z-nXc5w(Tx{PB+JGo2o8~rVLSy-Q8R`zUwW@ubPuYby2kMqLKJcJO&%Fu;CM6CyIM| zihZpzj8uyHLHji78uWJ(q5BOYhugbRT~vyWE@Y(isVMqvYAec2eyJHB6isa-29Rwj zns)6j!W|B}Q9mdmHb##&KbwL#0sI))t)loA-(ECqeJqJeQ6|X6OKF>#jP_UtL|RoR zp$ylH#72&&LaXYcQn}8J@cy_28*70G!(3JAotOCS6RxLH6isd8hP>oTqVDo`V&a4d zH>!)GEizou9v9HBmcWKXSUK@wb4O9}hy&t@Dqrfyld$e7&b}$|V-^tRyp%{x>mqFI z%&{U<bx|qr#1>dnUjSkr5XvDtF=|O$aj|!OBbB0PY8&_b{IV7~R$YWi)m?ZSsJbW` zHOR19l72+NMx8AsMBa$5Vn)?+h=r?ssUM3|y^yV*obvCj7G4u`RX|s9ul*!M2UT5E zD#5b`=8}tepNGT7qOvw(=~T=>P0MpCMbXqY=EfsBakYATamVryPS>cqDB9V#9{N=p zYz&5t9t$kR*Xy0d-bt-BHmD!jUcSiRP0atg+dktVci-zHJQu9P+ga5`rP9-@!Ru7m zaD|QS`?C1CO?`xgV+f+PsxFGA4AHOre(^%JJBanmk7)d$h}4{7$U?df8>3*OK|nH3 zj~*aq*Nf4xqD<tOpG3Qh`F^Y&Y9rb=wG+N~%mvj&rDXjFi;PTs<M_kICXef!GrcIw z3S<9V)kV>iA@cfsdWelRZu5?tjwr|Mo~9hLlV^1&V&6GCB}m^M`31oqi&9@A*LgVp zUq+)2ycr@IzS+bdG~0}m7OE7De$n_0A}p_miG8DPbA#K}B&v%_(HIA+!#o^}+quv1 zbM40At`s%uMA6hXc6iTq6VD1g;X@wm*Z4sZfBxLVIG=@fmw6dCR}2)ZMt$Vx(u*SQ zqk2f0$QXcPu>enD6c9WA^c8h07ZBTmhv=y;DpkYxGRDU`JS%yIch1+o!lw=@A)Fne zr&1J6Z6i}Q-5~PDKj#C-eb)Fv5qgVzn0;oTm&m<s^F5tJuSOPP_Ohu8m7+}gExLwr zzWi@%q6LRLh-o3$dG!vca71)bDHoUPh=tDwLS_z>$S??{-*dix$Y+I0Q8cxUOpYSf zVot_=p6%HHr&3g16x}xSEZ((i@kJqRM3n6)5_cCBA6w4U*r0w~Oi#niuoX{NwqTnN zwql9Zdv5yD5qSWrE-K}_C=q__%eOJ0wXLYs_dOpw!U-pGRb3QK8RC6j)lOWlUqoc~ zu)?ixsxFGwTO7mJ#L@hI)!fEYWbZF8_QW>8IeOIw_2XntGFCGC;YR@cXjIl!oIKzx zzSL-f-mdDRQpnQ9v*KuTiFj4kT{v#8EKa`cu23n8rna#kRm)1WA6-J++G(rtgCg`6 zJMjKE2|r}N8eFc9xVqj&u=4&IR+LF**v`MJrGJ$W44v&n>8zS!2)hA<s*6h5N3BDI z<ud$`E%>o+C9(WLEm14_hC-z%nleO<#s>D{^BP6;T^OQJT@)?HpLN1jw7HB^SF)%s zhTe4-bxjItY*0U9V|HMipF?}d==sR1RYc66)*@tfjGpSEQn}6>5#PUpXC)D=ij!at zOkB<=fR&7@i=rt*tVPRL!duf_1X+Y>{Gf;+{Zc%uI~arV6y2q#wqiqkM=`)VTEmJm z3DU1bd)&s;m8_y_77<nE_7Y{xr|YRMDs?hvYDz<w=ddAbC#*`u%_^%p3!lZ?fKYW& zG-ZgI{Ur;CfTexK-4UCNR2N0tM=ij6Q06)hfQ_$KWyH^tUBuFa7Dg&X{qXnSjPKe@ zXpbR4cs(g5{;cs9H$RucH;$@{O3Ck=Kz$n8qazS+mRX2OuX~6GMuB@wR9zHJZ6gaJ z!daZTrWY0y3SteX>Z0gGyMrl<Qw93fP}p#IURAhzwH9X!m}+cLKWJaTZpNFs;@ABa zBD_*e64gbeXs<*@%4%ovQtvMM-D`tW*lNF`Xvz?IOY01xe-%`3-PuIr2SwONokYLd zmH%|x_H+~9n%5Db4L@sGQ6_Yb!A`@4E+Tn`wRrequ951ZQgpV%oAXU8aVf8gu**G+ zUZT!@6ipf8w#_^ye3Bi+s7bXoeo%zJe>%SIR-s>cqdk5O^A<-tloU4>Z`ZJ*Oz1lp zZ|By1gwCOW*cJN~EvV|EQgk(dH)qvu;%FaB(KGhi-~EsO)&>+!8DgDSkBN67&SF)u zQ$}sSQteq}97B6-fFIT1M}a>+qOe~<@qWui4J*oo?zdnCP`sN+I$m7Nz4ZY$R9#d` z8)ul-uA8XZthgAvFBi{B-T9$t>Jz@UEnA4MQ|pNI@y|4VP(+Y^J!1Na7$0Tf$ILbz zgz;cm5w*<%El63ZyFfG^fc!*6)i(dqi^JclB6_asqEa+AfSy>zRV2KqC5q|3<GWUk zOi(nnjR<|Fop|26jo39MSK|joL}ksvEGp;ry6|H{6&rDLPe<W;(MH3HGKmkIf$v)R zB`hoa)n8CRto`OAR!lF09V}HBm9kD41?k)Ps|v(Atn?T8b`<v}*>WmH(Uc)-f6jWx z9lP`w$KTaKT^dyvMJIT6!aM3V+M@()_`LbUe-`L1hQDvDu|fTa&gzHt)p^VeZw%<| z6;Ja<qlbyZqZEAOsJf_BMw~5nejWgU+Gn~(X771YWPdT+&52Vfilz)v-8l6kw|n6) zmOZS(sV<5Rvu=nrwOljE-M&mmoyaQITU`3tP-BDoLE|$RgVWz~`{RDXccC?+II1ox zMPnR@xmU{MM}`d$VSa7@PozjiQ-;_V&fUdNEFUe7jBBCsgW7AG`6)RzMn0=2@MG?{ zXZ$s)?|21P)UcvVvb?NQ-gw<W)IetB9=#LCdkzZ}ZbNm*VNrEaDb#aIcC(N+&I9qV zbs9HIA1QVYNj6d`ilz)PqTB;{V$4KQZC62!9~5C16^HXtvhrJDw0S_iAbx%NB#~U} zJaSl6R+LGiT~spK0e*Z2t8bf4`HL6fV)mI|xF=54MWs;C2{);IK%19_4bwM0__{rl z#IW2_$mLXZQ8cxUw?W-OJiXmSvFWFS#t({k687w`A8Y^CTt2$)fpL;uxOmj5I__6f zSy3kG=`)cX|2_qgL9n_x$&H`y6e7|JIUvHK>e5P`O-{|p#<Qvj#L;VQc+jj6F}He2 zPNgWC+Q#_UK9EnteOp6XRnz!E5#EV*_{MpLHJqGx=U5fvul++s*PTr@tZ+*Ce@t?n zf8pF+Hf9EUAk2K5bH~c#h1a#|h@`5zsFbsB1@y#s@WUC1sI>w7Ma+27rhg~w8>qS{ znlePZ-QyTv@?)fMeB!9_gCgiGft<UAm$=*eLE?Cm;Tl$yNrI;VUo2129`en3?AlYF zFms@2YEoS@Ur{MKSL$?or|jp>{-ea}O?n_yU6cuBh;M^tnS5jEfud8St7hJ%XuBvs ztamf<tm=c+h|VW?{m_Bp`nMR34eCdtU1P-C-@y-wSXjQGIK;b&%9Hz`C#t%rRJK=J z%!yfO!KOfzUuY)oPW2Y|(}FNQR9zHJ8RE?|!c1Hb=_Ljy+G+ft2>SNHH>YbUk@upr zm~^y?h81Pf$R!**arfbeyrCi|+DdE_T}1e&(^xI3??Ea>*F>m+omNnkInhhpNHD{F z^r|k3rVMdz)Z9Y!n9)ltjXHyPySi?t==i{3w8tZi51FlQF}$GIJGzh9x@}Jqm7;!l zC-%hCeTk>bfLJvnn=9#q#QM86^;8#?ibb^(>x7r^ycH064GW4Z5q(5~4R4aD6h%|p zSYOR3ChqL)A#|19^i&r``z}%tHFys{WUg~mq3WWPiHFFvy@ZIc%9r|)?bQr#=g(l} z2E@7XE~0D?+#&U2ho0)9QcuEaV+A1Vkx3g%&XpGaPdkb6-|bQJOw~ov)HWiJf4sz@ z<po8<)UgWHMbQ=+PFN=*+s$A0lGhdLi)D+NivlOh7^xKX19ce@@%j!w<c%S3%JvoY z3z&)&%UG=8s4i71+p8j^&5*gQ2jXjagDCpcK@`ZdMr2!+qG)Ox$O+X&GhH?Dvh@u_ zgsCnStytK@j~}qp2sY|Abr3ZMHWE>h8#FekA9QRY);Fo3Xj;ZioNn=uQ(aVw&JwbM zvW;NxU4`SH{hD!3(bPXgxXl`hCbcSvJv&cp{GbTEg%x_ctRg7qlFg^H_@W`Lgj3uz z4J*ndBd!?Y)IZS^>j5!hd<ik)oSpcMK1_8{DOr`vcaf|L-4KY?r-}>R8+&o?V=<wX zQkhVO$fj!7S@d+y<UcJhX#Ak|<jr}gLIpqMZOxneRTg*4<?*GDP)>(<NSVmrQCa55 z_>~!S@1vUw%Tnk0{M99qE3E3GQnCsdZg_=_=0JF2XVloZu&5nl0UJ~oMXNqx3?_9J z%e|lTSL07<{Gj&iqpUEO6oCyn`?MS0Tx_;H$M=^jrC~*x<T@9FA4TzW<v3@!nKZiJ zJnmNaI^rd&E-GaoRRWdRiX+cf+PK%zPgphI%g^3DfcLqoi=rt*)bYA7T+}IefiJnE z)A&IV-ic*kqcHrCb4jtz!^Plf^Z3qFaT->XiOi0!;afZ(QO7StT<SQ1_ibMXGn}f6 zO3B+R^%nn~P`D8kBxX+@!!KPOk1sD(7e!Ns$P527UR2DA<x{8ZIYGxcMI_o)!YV^n z3zdF+su?U6rWD|wC1)yBiZY20v_Vfa2ST2L@R-qCoN;W)AM&5b>{oSBsRYk*f5*o^ zg!$A#qSfU^eBdyyP$`P0wy}dX#zz>!3X7>r%=FX`ilDO{5T!lD&C;p-!<|And9Sjf zOcL#?;Ef}zv3tOeD|zii@3F<iyOj$Rs*6g|IUm{f!v~1kar^mT<4$<4>e8ZB+sK*t zzJ!0RQeLdeR&aY=Z>($I!1_eg)*gv>_-o8K!MMY(HNI;<VBVE+>Z~t6IeXnpup7P# zm7>we^z^QX(0>F%MxBrCisNGnwHEP{i!-W=N@?rd{dl~aSKXnA=6$SCBSqCk(bP8b z^jB@?6Q^_+Z-ZYbR2M}za;b-L{vH0weKo6ux4h!Mfnv$41U;3ae#9b!H9qh&-p*ry zh`4;8yPX~?c-{#;)kURJb7~{LD`#qn*nj0dzj+F|eT9;+%20JtG_{S>%O7U(jbK&l z;u(z}6hW(#BIoD%7Cw7spm1_~s$oT$EJ`hf*8BrMWQ2a}TE_Rz7%M#5#bC!ot&>Wn zXsub)#yLETkM21{%$t8gp;8o086qR)Pz&ynGC{mIAEl}HO40Fw&r$Qt1fy2Q!lyM^ z%m*(I7F(KZL+-iCm-><GY>gf&>%EQyV&e2}yj7JjadulbBh^Kv<Xwb%3u$8*5X&}A z<O{}xh<Y7oAv;0UMbXqYDzUYw$(JE3zF7bM8b2t4R_{ga=*Hc6x9VYHT!NMrW%49! zIqL74;%zVjtRjAIFz#v^DXuP!KTdT~DO$r=r+fUdDxb1=vZ(jUMo*<EnlePqfx0`4 z<6cFGZ#|riR2M~m`CTzNCdL$Rwf<mrVoytcba|*~H19QXCRD!EkNCh9$;ghz)Aa-5 z&iVR$_^vQ<W&d3x)kUR}Cb*!@<+`LN5FUB;`ICS!vG?2?w4kbsqN#1v7p?iwxW7(> zh^*PpNOe)Po5dv5>oZCHcXww0lv;e%#Bi~_<1UR2>PN2gDb#h=0nrDnE_bxxv$jnU z9^1|~r@E+=j2g(g&hlPU#FjcX<DKh=i#jtGBIi!kMbVTYsz%i8#~0&7$K8rW{>Ehf z(?!v#Ij?ZKKM$kU3pV<V>CdfJhlmQ!7c@4seiX*{$8XGVvIWy#@8+*pj1`9Hi>SV> z>dJLir52}F2O<YEwT$UM+SZ1LJqQz154V5~RZ5Fi{X;aW+h#t=47YSgyfIQ;6dh(= z7w?a6m=g!X#^U}%`GhVZqFVb@jSa0I>e$3iT;vX3pc3M6(bti&rRt(1n9dSFoY~Az zWCn_fz23ows!NMj{nP1I&VI&=-54bN+;zx$QJ)D#B--^u)F2zPkK9*_et4VjTIny` ztxjuLQ6_ZG$Ij)|A3T0fKk<G0B~+nRbx|q$_R;BX)O*f9-5w+sKFYy<l=}XlXvz@x zV13TwS6dDcaZ^ia{Gf=`oIqsnJb@pw&C74g<!#LUM2FKU8dj7E-N(aeK!cfh{H3RO zH?0<@x~LS54WQE0iX1-GvcIs4DWus^q-e?ztPlg(Gi#7gHU?|@6-C4cw!>Fy7W`-n zKbo&EDgrL|5FZ~eMsHU=q)cc$04LVpedAkW{6wAZ_mikDDn(-hSdrn9fw4>dM3bL8 zFqf!N4vMC>5ob7NA*>(t6k&y2^t4}5gk6*q)}px>welR~{vE|dfOQXHy-BC1Qj`ge z2Vh6zQ4J9vTwg>!S&lV>s*6f#*NH947ZocG_7tyU%4#AL6iscTCScqhK0JJwDBjdr z;|E3HI}NLh-<V6}Ij=+A?M04f3$c3hG7T%r#4f4=-siv2f-;ITq*GB5=iF4B?(<lo zx~P<QqB&v!@_r;4Te|Y8h^T+BnRsUR5H?g@TD1B^uzI~2&)2RVD`GrKE3`c*g3fkm zkHGc3*)R{Wb!KT~a;P3sCaF2MQ3q01$L|1E*Dtv9F7-o1&(z9TGpO?}mD0XHqLmfA zy6JeaWY<SMm7-{BTc=C!8p&(co*;&9ucgq+Xj4~oLk*cH$VohHz&A&7g6AXjD|yaq zUgH8hbl4PebK5i{mFjNUI9bMYo4H&!q~^@VzQGf;;0+)Q6(;Z*K_SBSjE#}%qEd9% z0lCi0toWiWlf};P<rsrhm&%0NMn>a}vHW|T(PG{AwHiODJzAj+=WA;O@R@h<rMmNX z5|z?2`GyLAcj5UF_|bDoD(9xXL=*osMXO7dqE*>+y1NYp53b%r%n7)vVE^QQy0mE3 zCuH3ZD=21tY%G$$d{nf$RCL=+JLF7U!;_Y^4ILdW^V$1Gh->o(>ZuLt2i-%`>4v#k zh(*SpqW`)Dda8>`(cLVZ?dx`j+a4Px>didrMx`j4+QzwwyS8G-9wt@{U8eDaBD@o; z;{9<0eN0xZoBOD!xY4<%sN3PX8<nC=XudG+AG}{fl!$Q^zN5<Hi(b`5rD*OjSiN%; ze5Q-&w{V#zbD5&4ZQQ!Bz+QY!y1|df$htU1@Kyb<_8&#iig}38|7jy0PXEO1zFya` zqD*i@?B5KbW-c4xdE>(FBE5BcUUqR6P4zu0MXTf?Yw`&b{qFqX*IGS9Z&!6uCX^vo zutkQ7kgW;4)L!YiTKkWp7pKZEdbukjbGA#h=qwH=;J)p(J{lX;k8Cez>@LZ?rPV-8 zzv(Z+JRWeH(nFG{E-HncD||a=!p3qSzPuYEI;SS^X$_VuREnZ0L##z#pt^Bh20uBV zf|2T?Xz#?D*wvT2uZv*g#7=K9IUVN#R#w*7pnlN&ZJgW2IhJ=$&cY$RAa<}+T~vzZ za$}~egUmME(7pd>N#snZndB5r8DhOV+(*>w@rmErJB3p}D8k>rD&A`H>CT29EnezH zKZCP)HLS3Pm6nN`{f(GRoU_O*Sy_}a+`@?}s!Nrkx!h=z9<79NW>s<4HW@RuDn-$h zA^L7*AJO0JGk^IyLgNQT=q<{ky<cD!T?jw!_i`3ZnpPImPH0(CCKuDK5%;-=nPD0b z*8^IMp@m=Z%9+nN)kUQ)rWeCp@(On3v&u1Z5e3_tiTD@4IF+Jk$`BFy>ONxd!%sZP zB~s%DMWD_LM(x}D-kuxOTC8~gl8=A?e_5$aWK0&l96fOvSee-j6+1)s@du5UU@ukG zMWy5%^IsKv<nIm{EM}a$&Y!O6_&2`$pDv1~3~?GzH&Iwt9LXCWwMQgX)kSS&d70t; zQ84x2IDav`vxuvEoA<47Lt}$JQF(G%t}OqZ3^RW<SoC}|jVEqR!I>Xb7nQQe_=%N_ zjL^%PnLSuHF`(mCzIk0X&Mv9CD4H@v9@+ch;$rR+Zq+(gGhfk}LGBK`@sjaGd6w+v z=@B9=?h3!K`pXF_MMoEXZm5~*J4qZnJ%ihqa&)7*s1$vMh=m^>DZb>K=MO5kLOlSr z1u2@^#tEBIfx^LY5wAV8qs9-4pp{CoAJt=$*pf1XS1YzUiAqr>+PeofB?pR^#|m-R zb{mnut5!XwQrbGH!;g;_+pI15_!aZOO1(pYqN#0EhiQD9m$}nVtgJE{84&6j40`Iq zcab;dt9=+B)@YBgt|dgL+)g6cq62ms)Uz4%{0BXQiJE{3rs7ss2XSY^W=?fcDS8?d zakvwIxOcX<sAN4ybDoo;scr1B_+90BcKwCt$;BE!D8hG<9r{!vW*>P9JJjbZfBUeL zaO|*O!-_JoPVhvA=@y(Ai31|qiu2-Yy9wjs+d!zgs1&Wfh+W=(kNG}*cX9FRe(dV2 zx+t15M7GHKSf2NAxQI4e`hWaT?fLuPN>(gR!;eyEj~TDy@Mi8U>UP(%qD*LgNJIyl zxbk~(V?^l1EqH&Zx~P<U<98xD>kLjvXT$Th0~YYQfy0D@#Wv(jsP!Hxn)-x1nfD91 zL+df3!-A<AKPbZ4_YuA(&gY-`dAg}CcODTWMs!@NVMUoZ`_94_%LO1D;Q7{FwfPV} zQ50|24ZTFwMWy`xx1ye9I-XT?Aik{j;Qnm9`0;%*5UMVUrVQan^nB%c_j+u`h1#rA zpUwvF#23&L;^8r%3+`KbWsqk+W+c}&SY*64{5zX5ee@P3Ilc!=34f+gsZZCspaNo+ zL7tU(+@%(@d;(hTf7~uJLz(oT3!Bx}oKam=s?U(GsNMDzXt~GIVaO`wz{Ae0?3e<K zN>Mbmjax(0B9(5BN3)R?mMT;iMfX4c8}$=^fSEii(`0*s((u@DX7hf6LZzr5p|6`5 zd>4I!=Q2V+>F!b`s6{X<7+pV!>Y`HH(~25y$9;q6G6MN-?oy?0_pxlnpPmYpqG)Ox z_t)-gr_}Em$X@PPtnq^)a3bD4Jv|SsWS)NQ_1;Rtm@xL*^|6K(Wg=@g*6@`XlXBmn zc-^=9*QKVgu?5nwW1{M!Qi*4KVz0`?Bmc(2mG;V(ec{Z#|4BqYR9zHJ8KTWgSu3?} z3}E*Lzt;Fc5zB3-y4ywlH2gb{v(06#zG>8W=429sb-T)nGFcrk9k&epf#>oTKA*-` z`iSDLtjwIcxDi^_MWtR{8HDQmzw-O;+wfER0riHkO&L#6e^=E-(bTq1_ruxRZM2OW zGv8K+QC$@6-Z)PzPW}CNtl*Y0=V|)-E61}ir&x^*>c{Pn@1kv{&g0+sSX6h5+uHMu z*wEUI8P!Fl7N;&qPPF@zKR#R@40pTmpb<-~+L%!(ilz*aAJxMlX_`qVcD_?N>~pHR zDEf=@Wb9^`c>Fu<RJzD2w>ASNvnN|>DpZR4ai!`{ftye~{*8~#l`V{kZz7mu$-R22 zi%PAI8G)Qs6L>Dq6`8q3yZH{9%y#dtsZc43rnYh4cBRh7^l&fMb46*59~9y2dlWYQ z*Gqhojc@8jus1)KYgkbxGqX0~ejM2za%Q+SU(b&(3S~R%=Hb+@s*6hD)Ffu=KWKBg zm)f&ydH&Wfj8%-bQm7O~Q-;X#YB_?R^ay3Phs@llE{e8`x{!?BaLiY7)H-g~@t*Ie zu)>w+B~dBrN4D2uym92Hl_y3H%^b!3_D^EpJ#S%;Mb$;6<ZWrlzry(F1Vk$*SKfGK zI9n9(EQv}{G_{Qi0x7-t*X1G1_Qwm{kf-XR=)lq)U?UHGSDuv#Xg}3hyh9|L)W-q& zS1MoX$7Jg=a%U9%O758aykL34>OlmvIh<^yx~Nog)qB|K$iuUevDd}B7aOaMk6=*) zb{nY_MN`{4-Oz_e++6-dur(fgjZ_y!hrBjNJ^%ln?jy5=q;^ju+2q^Xlc*H+gZ62x z!VA>Z?>-gD62FyprMjpT9bJem`3!OU`7Dyf#a~RKQWQ;X;|4H~Ir_9A5$x;WqZ&Ub z;$}#wyLaL*Jgd%lRxA3?(kBE)vS(+8AEQ!~37zxtZJ=+Utm+uf&Nq%nHFi}Om7;GS zovxc*qJBox2zKq;8ti7M?+=Qmwvj38vqIlv+Z1;H;VX?F6d|kRS!8@fzmmDmX~Wwp zL*|FF-tF#bSWzZzGjmbB^*ubV4aC~EO_dgVLRr{6Gfs6;sePso+ynLZG0u~LYOubp zQhZn#D|huXa?e#=6ipdoy?bzi{=um!?9})V8b2taWWq4K4Zh$#SOu(n94jb$R)?|p z3B@$5D3jU;jJO-*1z6n%tLu&1xOLh-g+1I>gi~Eq>g=W*p;)}evyvw*%({=z`^=ug zdV891Dn-$hA=X!%pP1G^f_05}q49$v=;*>4^0tq$PSh0EHON%MiZYp*6_orW><d`Q zeCn%9dvVvjA?(c5$C`0YrRW@k`i7&ujHgnjFt>p3Mk+;_P=;6`n~YXO126W46%swH z($TiZ4YGEVzyEslC0Rwq-F<h(xmYJA8~#;+YCY9Vx#QD~Rask1P^qg``=WMmq9Hk^ zocrak70|B)e)q=L#Il+T_4hXnV3$lkbE=C<+1^=*GsJ1Iw-E@_W1sZjGdr<AWo!hM zqG)Ox_b9ZPsx*t~#l}qd!l@q=QEtz9_$T|Vv~jw`GW}Hlfo%GR_Zn7|$uNI^AkG@5 z`X2$p?|X!DyWt3CIchtnx~Noq;C}aPFNt^o#L~M1l`bU*vs>aar&1J68RCq<mxjud z7ZX_J<pDS)r0SyRt5sW~D)41PpuZ)2d3WDL?>s+{ogAB>u|fTqZE$BbeJ|#-ny{?0 zeq70LcEF+)r@E-rl}!b)vb>HqcY%!yWB2HrWKLuuUQ;=hqG-wx8NVYejh-*U*c{fD zQ(YAO;o1X?!T)T0{W{rb{U(47u6<ZzgZfdw@GpF&UdZ>O^P{guld&PJ`h^~x>Y`He z?UU<#4Ksrq{D`eQ(|BoVDEr*352sQTO&Q|k<iHZfow1WyrEXO<eo(}R$@bz&*nN!J zrLdvAy=Sz=(@k#Xq+vywbbs19S<a%!#Km7wV_##ho0Hjz8)Z1vMWyI0fnEJ}LyayG zliAK^cAQF4G-ZhB`Ls;829{G;c~4udAB6k*_x11|yp3ly8LXTYb2q2pDJ=L%2@NaC zgwB;1wf*ds#d~qb^Di?_bx|ogYh$%kIM;1;jVbK#b8F4KOVQLPtbNK)*U$YJ&Wg^g zq49$vXs?v#!wt%n*bwF)ZKGjDnY1sKhPmrfelPh@+e@)Jh5EQZT584zm7-%4Uy!pK zDzndpFgCg>r&5#&Wr#fepkU^6P_I-y;EQp76Y+$3?y`!Q@1k_Wiz_wV<@|vP0*2U_ z9QP~fW@wKM)BM@*+m6bcs7r`OsZu!aYN$2K&RteO%ymvS<lT6TnP(sVHeMLSmJN$j zestfB=((zkN?pW_S!X)9Vnn3@u_Adi8#ukI(l<IDF=SO2MN`{4-J0{`*(&#GO0DVj zG=5No-r};M*&Hj3kLj|<qdvjr?MIZm3+HKAQ6_o|VJPY2iW$xkh|Jtk?B~6M$}SIQ z>>H@Ms1#0r8a`cXZP*yI0*GDB0$8~xo0Y+F&4EyLQ8Z<US{4Zd*w1z^l;5*z;B23& zi=uHP&T!<jtcf!de<{a(m>qkktZhA0V}ts!ICVc-bO>0L1ENkuXBM@+BuiP+0J}@7 zE-K~XvLE;4Mq=KTHEZg<?aj*W`Kj3CxgvW<)kV>iA@=A$wq^?|RA7zvGSr|`by2je z7iEz#BcE0Lnl5bmY7@pAuGH9|et0Lw8@fLo16C)|ODxMVwsTHJw!U99PFkqCs8m$e zD)il1hJO_oJKyqPn|9l>UhCuuH>yiTYZ<<;)R0}r9V2<;E@S^g)kV>{&Px%Kn+`wb zfYmNDPgZAAu432rvc?AWBR+7G!Kb+|p6pa0J_gw^{Usf1P{lz|T~sR3Zk|Ej-1F}y zngOF+SjBrKS>1jQ(c4vB6ipdod_-BZu@B!XC6?3_R2M}D>NgwSO>PNR?qJn;xhMO4 z=Z@00ZI;Fc^&{MRpP^ylnqU<TM1}i$=27{gGVnwZL3L3ni;O*nt5vJyugGE!>sg_M z3rhP?3*6AH>Y`}M5Iuf>brwIrIx7%=Nz)$GbJQt@53AAUNnn*;$eiu9EWxtks%f4s zeF`ovV-10N>@5AQ7CL6=FC{HPVf${qz{wX?7nKSq-2r`fPkvAQ+MyIn+3Cb81^q#9 zS9MV|Wr)-L2Wv1J%ZBXcs|6ZAC?YCriNQW<RsQ(6iyPn5_jO?Y<risKQ6>+n1sKAt z6Y}S)+I1>2=G=x&^Q!|JsxB&(5jWrPBy2Zq#Ne5Yzg~ugHfqhBj)!t8MbVTYP8NS_ z!nWHwvx%`2HGWV89h=B+52(#XHfzpqpDC|lMVZ70Zo!CJ3`TN>D|lVcs{O9c(zn&u zjB_eQ=NM$&FKN!=!)vmR!Hv*&sV;S#YZ)qYJlK};Rav2SvSy|_Ur}^|rx9`Z>3BPz z0;|FI>aw>to3eEa3u|mpKkTFS8giXu@pNAUv970q6<u46rL`!4-3(P1mBO9@`jxCE zC%>I%?P1KMi6bj<p)m3jRb3QK8RGldtRp+`P=*z)Vy*FmBIvA*9ju$3nU|Fnd*E!Y zVMUq9HA$sD{)T2QSzu;W(~ouS_g;Bezl`SnL8a)s3-xiMyRtQnOS0b?#j$2kbx|gi zA@Zm04r9Y-UsP(x7uCE6DOzuF$FMk+fzdbojq2Bpt$R_7E&TQyC&pD9)Q<$u2L`br z5Yi3tbQ>NS%|7%xrUaMxggW%9E-HoUVuoKk<Q|U91f05j7;CS;qV!)OTTs<S(bP8b zwp#_T<>PiME1s3o_(2hLHGtTU7{`1*tWY{``l(?>nPi4N#{1(NR%DOC?CiQ=*2Hq6 zvfxJ<&ANn2(X}1oK8u1_n?A8hm&V0V$y3!unNWtP_&zy=eG6-+tlVB4y<J@=QuLzK zOvC<hCEfqs2l>V(n05RXt<?PX5j8nf8`KZ`sP_iH8hhM_``hB_>gI&A5siu}BeP6U z8&}murGoU?n5EN`uB5+$=W{oOu$V2L${~kh7$2%Gil(-8x;WfF*rTqcQhuK)s(7fn zD7uF4Ps7IY8`#<y7qD74Y$AKoFha3PdW0G&stxJ~vJ(vPj}q~=k(tZAE{C(8x63Ps zcAYg+T~x|Dv4BU&@CNMP{RRzBgs}s!>nKnAJi<v<RTo85+Za*T!`a+STO}s=BF@CA zx+wYyBDG(B&jzc}VD)J9MArGqWMzqqtlXm7pnkZx{4`v|Dt~Q^j8iXN9?Gr>Kc)87 z+Bj*U>Y`G)&N`1<FF9IJM(6|1hq5bCos{!=2aHsTqN#1HcM%y(8aF^O^{k0Fv8s!r zgY>_!W-tXSx!X5*%S85QPKXkxd!?~K{jf>MG1Pm|5Hqzu5Xs*rv5FQ`lxDYXBvD;d zDoFp$P@t9rVtw)?Qr*Z9)@so>C3di*Q7fe~p$u{UW86fxuftsB1fK;PsxFH5PW)uJ zu&EvVkY}(8b{@+Lp5CMEI(SQCgZd$V*Eui{Uo1m_2=N=uyvL_1mnRNKo2$C0RJe7v zAwF;fJeO@=bj(<G)O?>ZE@C(GOH^GHO&KCyaw~`(DY!wYe>MY^zf?acBGK+M*3=Bo zO73$OxjKq9T9&5#m}I7>Qj|%M{+*%Ck$(A4cjxRu%sAk<^7-s?oCZ{NQ7OH}Tf?_* zz2Ujssct@DEPGdIm-6}hTd-1fQ8cxU*lWFh?DNA*%J}pch3cYcoa{%x8lUe+ttb90 zHtjCHxTk4sP(KpwUK%pPWK=@-_Fqr>vcq>@DZXYwI0vcfqEg6zG$h*107C9ZowxL3 zr)oV`7QY?@&sAL%O&KD~?M+X%p++Irt&^!jby0Lw)&s2J=A+FetHgx^*s|6+%G;*q zI5(l%pnfEHKE?OoOd#YA){Rf?+0&&JSlR@4)Mrq2Q7M1_D_D`O1w!87(%rQe>ltmq z+MihIMx`j4+Q$BQvkolcLpe6!>oHWbQgu<ZO+qHtKGR@Bo^~41bRe5l;)BxGun9X@ zDqrdc?bDcd-w$CIvhFG?ltP^9qEhm=`aU;^0jx%!k4l@IU7GPh(bP6>mRs79g-^0& zm)~sD_(2h|F;~&%%h0c6)_vn$BUyG@nvzp072{m>kTRib3B*j+;I_0GrC4^*E1a%T zbx|q0s=@re&Wr8Vmt-HDGx4m{bqPgN+cLvV&vJLxWR}BIHGWV;EUK3W>i41Vc84GR zV;Ot#(~%YOm1llbR+LG$S0Zxt<I#e0A1Bx4|B?08VO2HX_g7I=Fc85O#XxKcG2qT{ z0R;;MY*E3$R<Mw;#a6Jz?nG=w<(>g-U+lnEY{eF^@wZ0td-nPK{&=64$7ij**S=@Y zoQXYq9Qpd_Cj3Y}8HZ|%qN>JhKz2$h`b2sDeA+Wtet1(o?o#mq_8?VTludo3GDR^5 zzF~k1ZyfL$UuV@8We3KtM4xyBK1#sHO~!dFZk{%8^-bf0#zDv0*pI5wh`*WHl$&-c zhS95Pi=ybLAG5p8j{L=EXMSwY52#Yd?UYRwVzsts1-@x}8(zMdti-0qK^cLu^9(jI zm+(AVAdVI1Ecld39r=^vg*2+Dl9lmMXo=_0i<*K_&Mlj*xYV1s^ZJevvTBQ><m@%c z<}Mi0N8W1--nw%~UTm4ELQ#}W6=IinUM7p5(2u{4FZgFB{LdC;mu%o>2nmsUcb4!` zEU*x-WY&$_ZL-w(pmF$Qw!@9Lr!bF_nf)UVA7-zjhVe$NODfbBMbTAN>@Ka(Wcwrg zq3ssLC|tEg*;FBFK#VxTx`hqnJ-3=G)D~rjE4A^CpFkX5P}OjAA%3fHHy-@5q{au0 zgU+dOCz8)yw%R&~FS#-Rcb}=YD2mSRb-LePuULU9K|H~smS%oV*;JuU*Z0L%cI5X6 z-nDOeO&pX#SBjC(Fz60js}JJlheI@~sFG{#&9KgpBImUjU2d(nfh`y_oU=y0npJ0t z(ymjtEV7-QJUWcq&1|Vq6jeeMB4=X2TGlZwgqNwX3iA(jKZ>&HZWeajPn}{m?E`s~ zZl}fvjpOdOl8EClR*L2!4yDx!R_IbEzH9gg&Au8%(LFt#PQ2L1)-LSBH(yCqD2ghf z3NhZTc8hiUF@VoBe#Pijeb;D94Apx<)oZ+i?eKn#dbNwaPana@eJ`wO?b=qU?s=oK z(f*yR*TRv!Ld0t$wMBQv>FzsD_ixz82AhrGXA1n#?4MIMRfunG#Z0!t(4UW4a$ge% zWlT$%h<^7W-i<)S!9$KQhoIrSQnv#dRa8lj{#`Mn&%#?J&!68I{E;o=!MscDQATQu zq7uDhF!p(X-%5^mAB?)k*!}_hgTq-PMNu|Yh<X5>v)HTd{rI?zdtIq5%64)ZY+z<D z;6sk#8pZ8r#bQQs%SnASK4=^?rx20XQrJMJL40Wawv5`MD4N}fG2F>3>|po7e0oA@ zJw;JARfyWS(O=n{5q<atv(9=N2W6z?%s>vL-0hQN>JukUvxU8bcv8kfjVh|7-pmpB z;yeLEW`BN~@Pc)@;laDxy~FuI)fPo*@7vzh>oGGo4dj!9r!k76Y^o4vM64|MfxZE} zz=n#NI4Gk|;8Li%mjBFW%{Ad=b*{Wvr{@|~REb%}QUfYMgCQf2-(<ss%lYu6f{XOj z7Dc`B+lcY*SukWi+_j@+`Prhre0h+p1g+YlY^o4h-i>Q=%ODSKe>4+ySX5h-9h0>U z&m#@v5;>2G=x4$MyF2j(*M4C(q57b4&^ybqGV!<yKYXb!-+l82qqZoD-ky$;ewQkI z0C(cc3LRq<McLFho_mP~+<vPo|7cjHiGwoaE%0eMN%*bgY~rGs9lzGKE)RAxYE)4r zv1vw(EEDnNly8)IDHmRGq!TajxVN6#q9{6Nz$#8|Lw<E-bAF|5qMo8Cn<~Wo<AfXc z-BTB9KM(ZO7G+zbg+y7c$e$0s8dHONcB;gi4E}`LBC1{*hxX3<cUvp*Ii+>{;FT(z z+M=ivIakpV=i-@%Bl3qHc6|GZ3VfsTj!_h4Q{Tu!`sK{4&vxYFCx6hyK^b%wrqg{` zQGvVP)bRmMRW+)pk|djlh<rwV&tSD&&&?{C@jf;e@C4QQAVtx+C~~|SI`hrFEO=Vo z`<U0NwkVq_#7^~*Y&N+>AKvuG6V3O7_SAHgi9Lkph4`fMJ^0=Z^E6)r+S@TRIqQ-= zgPcJgbSlqBmTkvRN8QwncPWaFwUMD2Z^C=PM}uDJMv9_Js6w>F&bEB$jFx<F%YB-0 zJ7vdYZNhl>G+MjNJs)Xq!7p_V;NzA!YJAW*XupD7=YutPRH7I6+xQ}x+M+1h$Dp#& zXd7;G*oPl}!?6OX_Lh`Q6=Ds!dp&OX!HqjyOw`0d8FUtgz65i@M_C3w)a|ZD6;(pt zN1UV^=*&NwHQ`g=57x{FDT=<EsPGrokeh93!4K4!hBaihm!V3iLS$1pdh?WaCc=K} zQS2hGGst^PWJZEj;yy!`pI0hw<U)qUPD5<k;MBjlQ7tzF@DZnPD?e8x<E)H|3PT23 zoxplHiIV;&1MT<krumE}E}ghvr-EXq<8aKpR9iAn?H?*6<QRN+PsLs;-l`>Eefg1Q zdCI608?a-dq9~jC#@E@kCvV>8gVLySAWo&IwkSJe(@DfsIrVaSarn5^qZ4o2=9V(h z?6}4UjRQ5;F}t%y9P;KxkHy1z^^jRggAOq`Kd9QGsEkeLF(Nyae-q}_uwJ}d><#7p z=>@nOP_;$bR3S39ehlHqe?=(g?AODGYKyXQ6BND%-&6i(i?n?iz)SwVscf35XnfE( z{F9F1i&O2-)5NUkp&uWRv`6`o_!=`W)fPp`-!RFh1Q_v%{Qi+n+^gAMrT3MG*rQi% zQ8rbG`l1+(>7SY^-N&8L#6cN)vsA;)P3!aT0Bta+9WUQuj<PMe7_vxJRa8k}>@h@s zHRbQV^ZDui{J)AB#?p04p^Bhti=txFj$m(M5*YOnM}|*N9v4_!Nm=n7Em5^a+0-}c z%B~&6_vV#W9=|!OiGwog1fDZw+y4}Q_s;{0`13k-9vcg;(W;_KWR9iR+<Rg&@)R*b zKGcU_58B;g*qg7oQ%|);Q8Zf!JBoLD@pD!88jo%Np->cMQ-!$4q~tiBn7G~eEOUk? z4$43+0K=`CA!2=e9lRfL!-nvxEsE-6OfP6uQ6<`(qGGKgxyOk_ec3x+cn4Km6h-&K zPzQ3~Sl(#T^yAwu#^QOXxlxo&6(VQi>3IIL$OmJ)VI4GaP==G!U4z9m_mt3(iHKuO z-za|f;R^k}s}34fR0-YxLXDKU(R}>+nQr=<c36{9ZBZ263&UM0Poufhf2MAYGHo<F zag<FJVvVfNcy8`mS!sFLT@wdoB-va+Yk!S6d=W?L;%J_kwcU99Ln)0at&+!hqgLQP z;Ui!;{T$2p4jZlfH(OT!rnXen%J>Yd&=<uC=}lm~IzOIweceduSG5*02UHYgQ-!FD zlODzs=TB9-d=JpXK^e5S!+K)7P=0&eTE!->qDB=};^g$7!8@}dzC`l2w7z44`2MJ; zic?He_)z;@ilTi!X2Ksw@Yn4(DSV<mek;`$WmARN5pNpAv$CEkOW(<xd)4m;WnV}? zZ!pgon2P*IsLI+ll8=4ANhz8nGY3>3G>#;j+lJlVdi=UCz_98)gx~%x6caaVh1#O1 z3+Z<Zeo2w3gF>od>{D&%5MFqjP_`sn<F`_6Q8x9BY{P+pykEO)<^Ei49F&n{W5hbc zG^pAIRrSvH=LM?XRyNlwt5HRj;I=~Sf5`h%e}Pdyp*tTxF;AJ;)B&ngTNLG!nT+qp zQhaOW{JGYbo_zYkT%}8LW4!08Ey|_}QLpb)H@<A2PE^_55Z@@(7G>jZ4vZ7mrml`J zg5Rq3=f2!(W2SPUlZD0yjUzVglEFT3X)0=3fRW<Th2LUDMUnqZup6%0qNpUBQ-<{P zjd&h1zhtUiFaEmT7i9!PeH>zovZ+GkxAzX<b6S@adrePccS*ISWnV!YE1^o(#!Wxe zkLT=vr1*6%sPRGLNV3VqjDBV+PW*yV*wUZ7G%79nK8V9uRJBD>VfsgypD#chL0~+3 z)0w|V4%x@<C!k8TMcGs#syc@D;=juMR(zg~#_dC@Ey{l5_s%ddWCWgvJnhuie-QVc za6x&T@=N1`#t~)p4sTRX#34`c9Jx1wH<)%nvAMq)I}NHWit<nTiua=hd<+ERQ0hQl zuiSMdVor*Yq9~gx#94slVLUl>qw+XfU{6@JMcKLb-;qaF3BQ%x$0<L2IM1=!uN)g& z9JLcvy)=$ktifeQI^zj80HfCMF+8sFEG3N<MK-Q#i=sA%e#5*r17kS3Z(uwS#(UVV zR@NJT<4!%*7G+c4=$i+P;T7l2QtZE(VtrS&McFY~FOYwgn=&Y*AbhwF8O|$s?pMsr zi=$nsK4=`YkHMF7V;En3C|=o~T^yNbsx6A5y`4_iJtd6CTC7m6-L}y5SCmbCV=X*q zJfA*<DQtBqO&pYwu_@ayZ&-(v%jsni$HKg^+_*AKnbOuuqe`np{dQqiG%1=VE?R07 z-sSN9pte+$_A7ep@_4@VNGrwJzNqFqNZC}OPS@Tdn%nF!QI<9Sgo<+N^UyMM9_bsJ z;F-&H>T~rb@)?!)xt_Pl#$KwbiYlS`Ea=<&PUPb)>*^<Wy@7pa)fPq3+!pL}7M{p+ z9=36F%lxUytf6e`8+9grMe&a_i!08%9&6&D3}#lq<BeYmo`+ng{@Q*LUsu&SdDZ@< z8dX$DT24U^d6o(G!Pvfj0yp1QSo!p$0%r88Es8SBC;;SM_>gO4OYJ7|LYc|NO7+*E z9+_&3vZ+Gk8uW<ZaktwmKILv`;-C!rcIk9m9z^r2$(5AmLyK!vQ6)0tCdsA%`YRbn z-SXkQNca>b%6%4can$#mqG%t3o6KBrQno@*rHygRpX{A~wkVq_M7<ZQa6YZhG-Yyh z4`hp|{T1~Qi!<9%RwdCV%6y+KZ=(3?^^KMCqZ{cdipGH|r5-++X?Pwo1ESrkF#cwc zzjAu{bVhAal#`RrLsm`uo5NE3L<Ao_*<ZP0wnk4;ludnO-=N7T-uFzr;+gbC69;94 z>2opaYk^)=<`f;g8O)t4L@VaVYNRNt#5(aCG9b!;Ay<UIdv@eqM@?3$wKqi_FVz-B z$qX31nJa!P$r$(}m<O^k$|cWBjG`!;`o@lXmr?xtrxnWU``S1tV`cnD#L*-Fc`W+e zflnGZO_^`0RYjF-4t;Nk$4wZ2<LD67i9c9&UO9c}9IC^pwkRqD=O1IT<ejr}MflOe zUOcGJHl<m|G-SP~wkVq_#0)Zi7%%iaO_}@ll^bnWltI6uxDnxIXWnJaJ*Cj~M2#w{ zBnrE5<{42?C3gYB(|Ynvtxd$P6iYX1i=yaQLZ{39I*=D@nxU-Aa@SK7WmARNQ8aet zr&bmdI}3btqqZm;zYo5(^D!2cs^(8^&o6nuQ)=B;7)8-Il5Cz}gdCIK68mp%$xVxx zhzoC17_~)Fdb9fmXQx>BkZ)A*nD*Qq>sMj^I~YY#Hua6&SHFqe>vN`YuJJqW4Oja< z+S`TTJAQWDIDF5gk4uLq@twN!M~}o9G<_oNck2Y2cpN-?So~#Fz8c9hQcfESxjHdw zi=u2|3VM9FS_S>CY*)orPQ)3=bH>W;OJL_mwME%fA@)CRjN@a@I2rw3#-Ng?YKyYt z(h8!oN(u3|wO{>j5|44*<5niS7`{=e4;n|Vy@`j{+|~SV&#>;pSl;$hnp>&(`Hb44 zs5gEEJ@$?|i<%j72W$3}NIvE=a~<^4pHUQLQ{Py7O&i7MeseP(PhYQzgECM_%LCQU z@I0iCa;}4T(H|dOD-F%isM0FINX)|I_}_XNLx<PoDFX`{UCq6?)|QG2)$2SO-@lF< zEaZ;j^1cIb%DY=~M$;!~i7JY+sX}}?BSs*{E5Ybr?vN%9%D9kTz@tmaDfxZ7=RI4# z?Qu_I!Fw$=s;H8*9G!=*UN~BbjC{!YZoK}9D$15+1#vsDYKx+1uZ?-_#y~#B<C<}^ zJ`a14sx8W<3X$*A1yw1mE*fi`b=AZ{8MIYm>~MM%A9%5`vdVK7qbRC`e!DQ<ZGaPv zqs^4D&BL)*q`qquMc+;A<7|rHj}Mkm#@ISAilS`l8{gVPtrgE25#nOy&&VoP@0_Dm zR_RS`I7L^hurk;#T6h(FrK!bA>%GRk{V5jUF7C_eA28c){PMlgwXkHEVid04`bJUo zb~a=uJbY`c?iVelhyO5A6lGI|SfSsQef<84Xkq1Qr%+pzJu9UypPuzk)q!1wjMYa^ z5au0=D-=cJSmHTX1jata_)69TX!@m*{@mPXG3lhOLTyo0$`~i^X7&VMoU33oyOVRg z!<7l*ic?{Qq9~jC#y-xirTXh5CW?_Wb{MHG%GPyjjunN+@FCB+&m20&7+!9YxL9Sh zk)miED?GD=qm!(~dj^ad>67$P0po<#!I_NOqNrvMONmIUr&wW01>-`|2KqAb6UFJX zCyW$D+0-{yYYRKNH7gk{o*i*y)D~s0Z+TO^_Irv}BG1x0eoQd-?LJZ5%3i7QLF3TY z__gsmZOr=>A>s<OWYiW#(Hh2BC-Z$}42g&mSF4m~6h+xoAyzq=JG*+IqZq`Ca~elu zr_W4kmo<<tZ)nML?H}jI(aB~MYv}1LYKPS06!q19H8;z60#veL`|1Dq-)hQ6MDB8A zGBf|xNmOq3i&0w?wf(e-JHFO<f&z?60aIA3>79geLLQ?i%BH?ihyFWfH=m9ZbFMMX z^Pmj+G;w=Ga3IU=86iG3jnz{WRbrKRhChmYgqY+CWahe}Z2GGx5$gTXNNrIRZPPei zlV``a&500KOH^hQMcLFh&Xf7y)Sp4m5OJf3LTyp@{xwz61!O|ib*QS>*p9u5j21B- zzuhQ`#<9L)2UMzfkpBe7^(oE5{G&vt69p7%i=x7nU3eanaTz`?tbL|G^eakqZELPj z6lGK2s6&7MzCN*Il(-pGO%n%Y&|U&(_05a1wYo?Vv!K346;+b`%L{cTUgochj%$*j zA5lG8w92ih>8~h?_LVwa*)fW~ZE%$Mw!vPZD5``i#2RwhCHni8(c;sx>Y9F+vbU}p z<9>6KycN+3U+2oBOR~YQBE(A1x*8uej*LymP?<vB+gBKjx2NyuQ_Dw+D!zJ!+M+1G zJEsu2yw_5mMEY^1BzyZHLRh`7ixn2t7G+a~7|rNc>igl|j9r!eHE~eJ-ES_ar6+IU zvw@G(|J~BhY#u3Ip|%r6Q6=x9mxJ*UGp{OO9LoBjA7eFMWHsuIY(v!+MS0DQM�m zTyJ;TpQE207a@vzx+@e#+0-|(MJzTYKS>-W_^mXB+M?{|mzSZnXXDqEb#XqXH*j;9 zJXW}vF4Xv-am1}Z?e6IG8LeHa8m?=kx3caijwM+MYKx-Ao9}mDkoFBeYJm}4Y>qy= z&oI$>UaCS-luZ@lUb29y>{XFb!fxRr&GVp<Pqu2vZDPLU|5mBy!K}%Y-s0!g$C_W4 z{t9tvdiO}H-26C9(%<N_jb7q+d0RnkX;E>gC-W0eP_EF|9Qr`tc}{=P<=I1IC#be4 zn<~U=?OF$8{HJj7>Sd%R4$A2C#2WXp$a@;(uNzhR=kef+?Zs@j@)}k6rv9IjxU^@& zEJNPMBJ2A^^=hm*<g^keK2{Xe7Dc7ytiXN3Kk!@Gfw9b?wJ~O-L8QCXMuk1q7G+a~ zI5`>HRM9027kf8t)x<#=^d?+X>}}CfnG@<R_JrGNR8b{w{Pv=%$|wA~vL*gZ2vMHz z93mE&>_F{L^@d(8O1=FSEpcuurL<v$$hol=HDy&>luZ>PXM5fTef99!O46yZBJM5L zVZAG*$u;kwW9L|4Y)#ZBcJo*<;<2!avHA1wILFd%p8fz&HGXiPC@2cG7%&QJm?m$g zd}&u275?nOa6=qc5B-gAZnsiypNSOI7Df4FF2bEiHE`dAyyNf$?%0}YF;HoDI$Tf` zWmDfe-L~Oh^(6;fQ^KtWYT}@buM=0|9KRKOG=Yy-ZdZ?QuwSgSaTu#nMU}**#o)f8 za)?9T&uRFXojljBfVliTP*7VGwK9GR?!hXKU%>&4?UmOXlZK@#M;Z=8yHagYHdTmo zEIYO+(?-8n<}LCU)D~r@r>EmiBuhLSsj5Wx<w}iRqm@s$wLWMZvaVj8z{-e2K95?1 zi;CA%mnd#i+6romqEP)3w<?!~4+h4z`Qb{Z?c0=%HwL36sJ1AZDnw5mn5-lit|{*W zI&0#f3}*Haw{w|8l?!|fLoIT{uf0kQ)=r~}DhUb6!;MoVajTWwm3iN)h$xnKU5Og2 zN4+D}7Ddt9B=J@AE+jlZ-BmJ|=}}`#wME%fAu5bF+pUBSC@XF@cGJW`8FHSOWFv1y zl+S#hhl!{;qJTKF(Ltk%D$(AlS<m~MV$uhDki+Yv7gKFfl>A%0XY|DHg5qw40wTDy zqvn22%BBi2k_q3hO#56>I661g#6cOk_VZ9Z$pp{5F5=iV?uX)OVJYTKw*UWB{Zo>j zeh=@t4$q@L7&&i}l<OY0LRY9UDpRPoD2n!WSXC=~L@BktoOpM$8J@Xni?XRg?8ME? zH9EAk5yqRXG;vVI&m9{?j=j7iw+>Y89P6Zv9%(CH%`<3JQ6;p`$9`><!^u5u8;X>L zu7cXqqSUVsRwj;Q8%qT^3iHZMG~W-(rV5eov*&Q~!j6t&_zLawpp40$bM-M<X6UaP zA&w<eg7ptZG0|>9U5zUG9o!uHi#s{V8$D&@Bl?@Ly)&J~`l*hB+M=jKXMItMOy2t{ z+it0Qt@R@#>x%4HCMb%ssY2`z{wmCD+?|DKf}^0eDBEl9JoqS>h8-FBaH=Kr$F8&x zbNV&V_@Hq#n?2b5@7Gy=&(C<-vqwwaM6LI=1+_&{+VR!Uji#(*3Ktn}c7mcPn<~Wa z>xCmMtGufywc1J(2W5QNw$?p1tq9%^N2prRW)}OI=qY-1E~`;Rl?06ws61Q%k<0hP zdh=zL;NDWiWq((wEs7HB(l8b^1;ZJPjSFV7(j{Ap-2GO9q9~gxgrC+1<L1MKh5l=I z&HF*0ApQF2bVci!u`@bLF<^KHO)H^K^X28oJS4;ts$@@XIDAI$edD2G^|-(0J4jJ< zEP;10=)HdFZ!58+ps%1Ps)Q;;=JM9<tjC31rD{e8&G($L!xiqHV_yNP<X6pc{0eqv ziLF@Kt*OQbjpJJTA?`6*mUyFNCdbH2IjqR$uS&LwtDv?hN><s#s1*!(-}bR1huDoS zZ<UEqMNyPZ6`}%WgPOc{(0|JM683`HqU=En7h+aa7Vn@uGdkx}F`krZD$07<Ykbf+ zPE}ii%8@1W<G8=mz$;Y0rrh~ZKu}v0wdidEDo2(9!vG&CGmG-PiG@YcX>|ofQ8rbG zGe4Equ>{LRrBI80n&&|ypINpJ>fBY!A2U>2l#P>Nw-xu}UYcK*{t8}mWi{=}V7Nn7 zaI4?!z>4XLI2|CUEsDDIWtw}&rkePzJi+LjV#ed<?p2mMc;OvXZBaH=h>`wkJ*ym( z%P#x&<dcUaW39Sj8nS>4jUCQ1@5~zb`;nnzk|L}U?V#$p0kiEk<(TJzboL)=rBGDR z{Bk&nZ=ELZ^Kx&Zh_syY_zuc-(OlEj#uCb7wrqcYPHj=t_K*Jf*4ls}^RK$vc4LQY zK45mPL8#2F+M;ag8<n7KJ2Cr}d8~F~S4|w0vEt+-RH1T!!q4z=rpkZEV&i|ZO9{O- zs;H8KXS-m$Tkp>=g6z+;?#YY(Gvm|BcIDI-MFm-O!x+vPKEA-mrx`z!&+RqkhS=_$ zq9~gx#LXwu-IZ1Ait;mM0ywor+4h0UQJ>lo&*PK)t-Mz$e*b-9eU=Ake9$=jlh)#P z6}z<c@tI)QO+BH!xM0FdPw?W@7Da6iJ%w?5BSbFiu=qC}piJvuf~PHN&nb$ssY0w% zH_0}hA6bj9&2`trK^brSCZqaybNJACU_Ll)j?%1Ob^f(qbB!vhB*|uXN{+o`{Di80 zO-z)^cij0X+ghl~tJ<O{)H}quo#8!~D@A$Bnd17mDz~iffxEC(Ta--|qDIQMN{VSe z#z$<j!|JSRi?Sa_9>iRYK~*96$kJsfx9eE)(($MhPkhigLP9R4#HKaF6U;>%HG;F1 z4`plec8@D?YKx-e?R-f#?(l(KG~K-63Cgen&H3%=74aQXZBaJ$jXCGXd&cjUU3tSY zMKy6yhOAGoH}iy#;_#6d^j6t&y#-g+>NKjT5@vP;ad@KlF$ZH`fR}RmVQ+rp#|!Kz zs<tS~Dls<2ETa_|Wxz-(-%g46){YO^V8JPhvZ+FxKR21I%#Q2I#~;qdim+;nvi*}3 z#L*gY$o0e%@82lD@>=kLOLZC_G!9f%O~Lz(RwCm_jeVvJ8`qxi9(#^aTNH)!qUagg zfng0sp?Z0W!$2?oDEktlD9WY^aTYmXkz&pJbBj9%G;vTydirY2Qrn<UtOy@HZ<z?C zW&rPLHd3RCDnUhHRL5@zMrAPk&102MC$TSVS&>m&6cv}Y8<Dre^N=en-p#u!H_Hs? z3s0=W-Dj#T%BBi&(!%euaZ{tg{OXBxO&pZbu4(I(kdW4B?J|y5=aY;!hsSe^fFO-3 zsw6!<8j-g}9CF3$y5|A68Lvn4=Vq%IwM9|eKR(7z+&@OkNuP|a@5XWW!C~;B+S0P= zuUq=oa^uS5L;2=HCpB?UM#m(Eezz5#xoo@hTE*%8_2YO+-<cX!R0%R@MQoaEi8AuT zkuUVsP}iVX&*O~RqNrxGQ}K=R&VN6eY+a>yMizEs@AJsZP;F5*RfxUR3D~o1H-K;Z zdYDmLl$|nWF)~BjB901B)hXAHMRW`0^)}4c_@Hr29ySo!j<S_h1*7wv6gFY>Kwjls z2S#mCR9u=h)?V8qa=8}%X!}f-hT73fcl2TuMcGs#elNEr?3(KU?pJfSCJxGQpKZYE zy$@Q6C49`bzRN6s_Txu$t7ueFCFKjbAj6`4e&j`3-DC>`y7OA@TNt%PQ8i7c@KC*c z2QA=ZchD8)@whurSg@T@6lGI|xT9)V9Q#(a3$GmiK@$gMtbV@@&)gHLWbbo%(F<nr ziSsqBzGzfYC6k*U)MspxJ+&Da$M%kAO;&sJGs$H*wM9`u#|Dc!fqFba6EGf(9mJv* zbmkYf={QAEHdTn~c*7d7Yq2f)yEm0NwME&FE`Gtg<A&c#e$V3yon_TB3_RDwRO5rj zQ9NTYGB7+4x%@g?ZFt4@Th-+`v&wO5i=uoEAHWlILti5A6AIt`0XNvz;d`oEbBdyD zst`}G{7|-UeQloGwV5Uk%6Qb_f)XF^f;eQ|!HPMi+_P{=o^ht8Mio_Zw(U%=H*?7! zk^Qzk&0HgK{`Es^+@hq~q9{7n*6BL<u3@<@_4pj$2ArZOn<_-+^0Gzx9=?t|<+O`7 z4(e}Q$rS%2Im(dtbHv@N$0mhY@)NV#YgADsbX<ya+wZy>XZuv(yO+1)XNfI}qGME@ zPT!*fYd)eB_nO~PGeV|p8WT<;T};v+`{K;|EqBtyK^a9e>ZNQBWoWyymCSlRC;55z zs(e-lAB`%igpTLXQ#W3mTrq?3v5V?*YKx-i*bZaf(|Tj|XDxX1xeYZVOUkASF~`|a zLjQ4(KksE%S`!Cl(6<Y>ZQd$sjIGm+U(773QAL#`w|4t8A{!JUM`Vfhrs(VT4dxxU zd|=cTMbSPVndDxJ^?SZ{<{vwmbBdyDsu1f}<+Aiollt@JT^?xqE6S!{ADyoDx-!N) znO*sM?_wGsG!8nR!^*_QwZ^r1!MtsYx0>%DMbWVxa)e#pC+Ch1;p4_U(2Ojp5~>gt zFn@L9uPipR<+E?$l#p6`oK_pB6^YSP@94^ZZE;~SwF_chRIN!)&kxF)PN%BLo9iay zzuJTSdGymIY}Co`_@1iOjVVf74|&?gPCPMvDJ!u26ZWH2Ta-<GBaW^uxwsy|tTvU! zs<T>KS<6O!--_0#RqO;+hZ8#US?e5`O>$vDQ8bP^fkzBU?%PrQy%iXyI~(%hrSxoT zxhD7yskSJJne9O3$d~Suoj#-g9Z}JP-?Qq&-uqR-S4Fi&+0-|_&ZzG@wPqm}Yw3<% z0M!;{2gdF<^osRx*Ig(MRe5nf{9^8D{Zm`54;qI&+Z(rhEfl$f@o|DP4~pKWZ_&sZ zV?osxMd{5B8Mdz~#Q*x}xUC6)6>(g@6Bln&6lGI|=;5{{87=xW(+BUzEk{|4u?Mlh zusS}<BP3*5>a9(RVNgh<M@-hfRG-Y9`1c6BwFM?GR9;@Yz#d=gjk%hN%JQ3$D$iKT zTmMj{Aa!%70DC+b>5of@m#8+?<%Au4sJ1A|C-Y!xT-qKmWS-^OGs~4F0}@%8A^kZ; zQ8x9BQxLto7(H4g>T4xw<DiTzzci>?4uz5M@glsqsB)t)A7fHmqlzjC)1OSu*tFIl zZ!d%@OKUO6=Nap;zX7MVC@LoFQfjDv0dkRLy$qibMa8aX+3dz1M`XmSwkVq_M9!U4 zXX9M=efn2>wQ*2JlFgaaTzgs9S;ld9zNP49cZ03H?yONol|)%xO*PAi0Yg5I=||=& z;~hJ*`J+NHqgQQFRK})Tscni6%YWvF4y;ftR+V4_Pla)cqHL-VxlxU(iMHW8nEzF0 zPHj>4@89?FJO=z}G1y}<a}sXFF0oUO%4&SjI0lB?K?{w{e;yGHn~C57sqDS8HK(>H z%E>7+^~1KHe8#R-jl?VW6qY`}DyJyQrV5dl(Q1^ax;NBVZ2d-@OD&0Cu^h%99v)eK z7O62=74f$heo+gkDueNr2mbz=9VtAM-n+RK_QCDIDk>(cG}=;?G|U)1G9%@`%N604 zVCZZoh+NwVM*rsKIPIj`qNtVerBn50CBcyEqOOUPgi<%=p!K|Vs53!rsch;SnFH-i zc~Xm*<Xtbi<E_<sSa!S3<+~P#Tlb136nB?5A!bJA8HT@ba{t?Q-%ahv9Xoy3_ibDn zH{_`(?DTlNwyWSSbC2Kn74Vq4)b$S=JJrGE`TV2=eHLm?Qd<-ill23Ypf~3GSZQ0H zyKX+LPgvIu;}X>tWmDfcw|!xpFtm+gBb#2v4c!*FZ?`R;fs2Pce-mZZ8qc7ahrGqt zDpAgz<sQr9X8~fv;>#>;@hN=ORFqGq8J=28pjvpyJAkwNeDLcw1;hPgZSi?^c^>xj z4eC>?wkWDjV3E`$8|g#t6-5NM5i5@r<!n?uY67aZD4Y7m%0!J(;y}6eEPBd*O&pXF zn^qd}$vLNtV@9P)qV#(Q{-n-njVh|-Lb?U|;P&`Mq^e&xhafxXKgNqbX+dpKluxE* zYJ9wJejJzUj1h*FE11(k8zV(gHdTl*b&p|U>Apl(>YlSgZBcfVl_j2sFJ?t@57IiK ziYVODiJy!-ijj<}m&Q>i&>X#}jH59aR!f<v)36Bt;&25|P_;!-^4$#8cfb>rd#P)C zGtoRPn|1YnkJ<^UEy||8ads(pB-cIKsXtbCxANbH_U>7J{?Oah!|h>L>_PcLNehoN zZ3kj+qCI@by&}U6e}1a<LgtQrbc*`9!_VD2Q_kYuJO(cu?w%PbXWKH%!o_PSA2fHX z{=<}03bjR1QC8z{e@&Y-v_de3d=BNMK6cidWbRZbin6J1WE-~Gz?L{P6gPtE@Ue@> zV-z9tbPpPCU*t%Ae25IHV+PA<MX~!TbGC73nXb{nrR?*q9^y*aT}DwfUzFzD;tn_8 zScbCw;zHYsoZ6x&n*EEKfV(!cTDKg;w}Uk~MNu~Ojd|_*iDJ>wtH!ZQ?32@SEK)C| z8}j=;+1tq#TDi|<fp^{uzpm_eOWI8mFL%F5&NW;8=Z*S@@=q$6Dp$F1hQY(hsT5kf zT=9}SaTkY1igoYZ6|Wup_0$$ch3QMepJYgXQGt`hjr+02<VMerQxs*(zyJBhDkl%* zTRIF@){TC}61^jkv*`vUJ|4$fPsU!F9_^}?$JSNT-J`5pASQ44aKzcZyjxs3apRSd zqP|azL|bBDczLWoIUQAjTEJ2(Fb*yZN2c6R<<z13dTNWJ-uTTzn{I~RN-~P<isG%$ z)K*eYZ_`s0WmDhSSIce3M~zNWZdb|qQ=j2qZ5mpQM&3gao96JRevwWW6M&QVm2N3Z zZwpP$8d?`eTSKVDc@LiP`l(X$<OfuAP;F5Zt&xOvYMb`lD(#Bm=8fHIQVWT)sX|n= zF6hPQ^h{7%_{m%N)EYaK5tDTQ=g&<LM*!ZR0Pm)JW4{b##O9KMqNtLpG21YkXq<|- z77P~$-2KsMff8QFMNnH5^~P@}>NDI=(XG6V(f*x0JztZ(SLv!NBPfcpsc)=VI=ADy z=gd)NelMnpgEDA^9h~S`R+ld{OjP>+bkeAzN)o*f7((?sQLRVLSYCv+=Sy-w7`G-{ zWB#F5>!B!GRR`meFM2Kt1uO5XRu>dS*;FAi=;oH@d-^R=DphES*`4~E&|hJ5=qkge zP>0mNbG5>2Yx4M)_m$@xZ8g6YeIEWv%TQ@5C^aR%IpWC9yvas+Co6`~PRK}6ZD~<6 zZ~|1;*fIs9`P~w{=+WcKB0r9KlxmBzsY2{cG{40Xr=}}YeLD(#tN+gyW!vtZiaM!N zQ~%aNvO8CaZ|Iw=gw3$k_@Hqlde1k=N+FZ~)G1mT@P^Gl@LVaj&QnlZ6jidpWcZi^ zhMWmkNP5FcY<s4xzT}DLq1vKssu1~!MQVyG+bgqeE8U?g7rPd6|J>aJr-?B_YKlIJ zd-x}r;%~X0D8ErBmbVoxS50Nl&lSfygNi~98OFPA=sEQmEf>WIK(5xxe%H5W2hpo# zUDohxDfm!rQI!0iXZguBGTHCmT4y8XPjAcO`+5k9qHO9LcV`yYiB$Jw{kx%onm8y! z{vBl{cf;lPBdK{4F(TTGZ4Y<QsG>?@vPxja;sjN46n=3|Q&D_hAN_(?e;NO5QIt=n zjHC9SUK_K!RR(d~ZGry796P*&sx7L7D%9z2*BmYa9;|fxx+VqVE7cZdZw@Vu?_)#! z(sDL2W^$OQ(mz&TwdhvVXHb36I1;@}r#d+`&sVkBagr!_J;615=LVeBS8Y+0oW0n@ zIOTso8ru#MVfUNrt#;hRy)vpT%BH@tUUDi#SXBP$IyU~kCJrs5bZVVIJ3J5hjk=Q& zC0wR%O}-cJg1s756;<M&WQiGBoqScFDhw9yp4B%x%)g4rRa+D#$EZ<Owf=l}QKRv8 zxaczB+p%W$lktsGZBaJ$jh5&%Soj^XG6wa(s)>U#<S&xtXNy)MpU1eEp6C&fV|&m9 z&s<eSmB_!-a%}Te4Lmzq3}18JE$HN`KfmrjTNEWN{hLi<73W!)c$K?9Ik?5PKcnz} zwx|;78~M)R1H>1nAIY|(A8X>EjKJ8EnB&->UCGwI(k4QTxBBIpxqGNa6;-00bB-=H zTJ&Dg-8gFQT4au^wkS%r%71feo$kqpfx>kC%H(EIw={ES%BBjjPJP}-c=mQTp6X_U zs&(r7K^aLl#ZqI_s-j)V_x#1_p2DL2F=IE!0{E(_s;CmHM01Q2%jNez1D@6uz1HO! zGvB!iYKx+17Bh0seL9K>Z?lbl+e;(UNVP@T)Hhayv)hQGHua6&wpY@`K^e4{Kwna> zrs!x>N=a^F_#ahjW_L(PF7g?w;|a=sw^UGh@y+aN@}5=g|MYPG`YVc}eLil_erPR@ zI^`w5?biXL4AmA@LKR~Fd|QP0@wykY33t(7NH2;RwjWxxrH5HY5sZ%H{LK8%Y}-G{ z4{vQrsLI_nNjzA-%`HArj}y5nDlpa*?}Xf=E$kuZhMAEaV5uk=*~cQqtiI)x@y6nR zX50U4QIwNYkyQUAIfs*bkma{d6z_*5>O+PM!5MeemYl2qV^iOFYn{i5-8<&6s`Kh- z;-Cz@nR#lCeJ7|Y3m;2YMhNTeuFCjWokkT^lIUFwjLwKj?zpet87%@&7g8pFO2f@r zsx69=s}wddUBHlg+l_;xg~{4d%Evp$ac_odi?XRg?6J64<=d)T^5YGQak|4tcNf#s ze_~IVr~S=BDj*v2DG}xP(dBm;MbUlE^%dXqw47FWf~HXQ(#sdc(r>fu($|okpxUCS z1<P%a1L+Bd%yfEvxC)=0REEFyD8?y@vZ-&>rfS=PZ=G?IRSmexs4dD~^tNXHY+L3n zEiG%$->2E|3+L}LilT9R4KTqdNv<=<mS}Ui9e*~}gm>7wmQh<2HF#kYWM=+t$Cw+$ z`|;Sguk6I9)r_JjoBBq-J8m%lP-YcN+&5nn2W9ME)AY{@!ry&P|AoVN`pp9@#krzJ z6;*QREW><Iu2RUz$Gwc^+g_GrW1q~{Q(F{uBF7zh$Z~B-2S)1N5dLK8c9t|Cj!_h4 zQ-$bDDxn7bs@1ITr@fjuDC68XdFIc6EWM9-<{_uYa+|XDtbdU~jH0NL6(c;5f!zv> z95AkZ8Nt8QAITo|n9HawimDpp>8>|(2SeUicxz)Q52!nsm8mk7Q50oU-<YLd3F9q0 zZ({u{*XnW44xVji^cht=z6N+=`$@ic<vcphZ;Chq&~|11)r0=g{O*ZLtVzfMJw@$b z<Bb)TE`LzCQ5Sj00r+)gmc?bK!Q6NFS(fTim{D64MV}_VAHRq4DPNAV0j_3@q9~jC z#_Gr7K0I&iN47uZn<fs*kWVl$HsDWu=!?&`<>e<?@=8xzYgADs<qMU?YE(xsWLDS) zq36p>+4H)SOZ{ny|7=l|%(_pqk$t<&lQ}e~Eq`>VJhyo9LQhdt2~~(za;7}DHf_uO z-h9(jTa?}3;w<;hl&!ryd>m-ol6PrSiNC+(jT{zLFO7q~o5<|HX3IaFYr$X4j$zam zMbTaYdtNo`@}KpcxOf|*dCw`E`o`C}b$MQ+XInl$^M@u5%5XQ^#&hgtUm~-R$}TkH z@m;<7#xWZ;s;Cm0ql43#A0M&#Gy3uaYit;`MNu?c2&*3p3-SfNJ@}l^=Xf4!?hs{D zg?Q$v);wu;2fi>VEtx(K%Ba8pKE59v@jPlGj=VEJ*v_ZD`TJKkZWKk8q?`{1Lq5Uk zU_>LsVw<BMH=ApQ+ssv46jgM}7QQ*uHx2izgYl!7j(^<Ti?>=a(T$=goBBq!NUM$P zQNSpEdgCY~wME&wj2cGo%y#*4WK~LFrQ<^R0JAB2ilTAQ+%J4bl&b7Na5O*f9;v6c zD2isGVdDp<QZlZO;LV<Ax=|EmQ{TAp_N~HFY7gO;_E%MC9F(zsge9vJC`V56l+fT7 zKCFG=D1M^y++>QPN{TnwkGwv)n_&k=xi9YQ%+%5RnSG=}ZBf+MfN7Y`w1JO$U{qge z&6-w<;->3O6pEs3>Km0jhaF+dYY*o4TKj9_po}HuH{<<~*=-Hrqw$?uEa+?~-*Ib& zMwLbhmQ??)o;L(z>Jh<;T?^m?ylyHQTLd*|;Tr5uw!t%(J0@?_uCN_L`tW<%GZh^{ zQ8rbGUQ}4~h@EZt*=5d}I4HxtNlARw<mgqZ8jx9@&l}W?H{N(qqlzl&IKLG7-S&7M zQdQ*o=Dg#+s(ew;r3$r0QLPR;VQsl1o`(|{#~NDm@40S#ta+kBQIt&;>U8hUI`Q^H zt+`>(Wrf<JY&kN(>J6TU+$D=?Rg&NHsm1S<HWd^_<ER!>2B%Wm<TG}bv*(s=Ub89D z6>tViwM9{M_XKz3w$bx%uTA*H8}}88qHO9LRfqQV=4TWmJG*(SCJxF7e&&PU$`7jK zIbpW18-E=)hYddSTA?VaM7ziG(>a>|m|V>`;#*yX+M+1BhlKHNulD@Stefmr%5BYF z5oJ@~*f%KCnLqLV$u@tRqKShtm|0WA;h%<g198j|6Zj?le*Mix=|+m8N(yz6tAd>n zx!j4X+J7j&Xm^awGp~Rfx>Z{g6|OYJ{+DFP_dF+hIIr?<F`H6zltNLIO?@L*t-pa= ztSrNQ1J`NdpbXk7u~Qw?fford<Az#;HL9o**%mg3`XTbVP~{b5$Lp+Z&P%o$ta(2u zO4C>BR@Y+u+t8Za_L$*MyZUE~DxnH-ujO4EK76V-Uu3&q^ZlSc=+{T5>o~A2KmV>g zPuTLnNKrJ7=a(yDoam3Ywie>Z^K;~jw>RY<=QnhtwkV2zgOQ!k)`jnU-iQ}SD5Fpm zWmDhScg}O+W~NTOqE+b@)D~sa(HX{9<2&)SFU@%O&_Ws?G>!$!T`=>KBWD@MBiw;i zwdH44rO~J3)D}h2u{LH!BLn!n78cy%$8I-@qHL-VJ+((Tf4XQon?L2dE44-0AGR^~ zI)PpDRn2TLmU~QHzzTm_Vx%Y<hwWaEKcoJ?=be}Coy2GNu4$Y%=v6YcMNxA0lI7P8 zEm58THCZ^0Pj;Hls=KW;QWRxV-`GDN*;tqb;A~Nj3o?hlrrJBWqpI6@>{R|r^_uI9 zzsGr4Cw@tN<F`IVW>#UHI=HFusfl`Fc8zfsSVf)4$x9uya4f3GjrG{${UcSLSooVw zwdi9#;o&>g_$<c_H|nUiC`$gjJkj&_o}Y;4^~H_w7sk4=E%^VU{wblpajvLlM^U$Z zRb}?tQh$8>vqjl@GwCBIUsdgoOoX$NO7JN=jSm`!d4`N5J-^P~7~eMHzd;^KoSikY zlT}+3wJ9_QI}Mev=RF3$m3<k#a5!Y4n5WuvilS_)5bM-q9L1JF&R9Qo(8NI*CvrYv zJyBMnmCxgBie7~KwpLE~*3_t?O5)?+V?D6}RLMNDtT7eD^A$~$rI)=qwM9`Ua$aLi zzcKdcrH>odPNJH-t1>O4G1sD0B~&4*8}F?kruNh;r5Z^esx8Xi6#63ds7+^7Bayjk z>-~L1TJ$t!u5)RP4;lyVfK3h4w*g};7>Rqm#oC=|%GXhOjM}28qc%_AL)J-^k)Q0# z#JTO$6z^|UFzQlmQ8rbGtgv;xjhUftA}Xmq&$Um+X&@bX%dsAVLPBsZu>eL$@;R?h z@ySH%|KnrB04L*z#*KtcrxwU?Qc<X1f*tsRe;D_^nc{8IVMHcXxq2T?&U4RF3j6lM zUaV@1qSDicr8qi$%YWvX=gf`Whd2wD!A&?tQ8x9B8;(X~yFCmVDo!hBkt4iT$+0&{ zlee$q01i~iS_U0F&bIA}vup*S${(tR@|vu~jU&bpo1!>H-5OtvTP2zz4quP$t4{Km zELqXP7mU<9i`b&_J%v8#9;3D>s^k1}?l^M?-yOj?9{EXs&3~lW&}$c?D9Wb3kvsUh zAG4b5FTPuwa%zjRU3%9=Zi5LFwu6t{zU^3Sz4FS;PvM-RXdD*Zj^dXu0#!1O$8S>D zO^cz*$>Re!wM9|yqO1NnNB{TE$%BIv*vOmJ6^muVIYm)6^^H0c&(qno2X10UJ#$SQ zlyUc42-brN;MbLL+=@BDUKSdr^r@;<MU|Y$2|_h1`83;t;k_Z5H4FQs9KG0%Q(F{O zsnL9_8p&tg28=qV*08WcpOs7Z{qfeSwkVq_#A(@kCB#VAoyxC3PcB#G{gZU~-g$f2 zpniT@&QJ6>ULJ|w*4Xos?~2S-T(;0zJYI5KsnnwqPBf{g$C351TK^RltPH5JZHras z-*}_sj>%V#1|lG9fikRbL(~saZBbOBcLlHuB67J`G;VGKp}1dGdY-I|)gaXtWmDg% zt^T=+XgPKn%Xrd4lP{{x%zT>q@`t>~UFIPd_iZ9>Tv*3eR<5qe{-hb7M{Qo<E9#M- zjeE4Uv-mi80~>j(Ix<XETNEXGpKzs=;cup_^*Lv8qv|>~`fhbjQIt&;V&6H~(RgUf zB^Ho8n9~!>^whU~U{{>_ErB)53s|#U*S{X~d8#mnErT^@!|C~RjH!?<Uj(PH{{v&i zyYI%t@<*6Wf#En=Ol_&CQ2mgU=~=Q?n5;E9SL7MDR!?F+#$kBRR1{@Xh1exa^jF$o zeRucQ;aI7mwp8}d>pJ-OoL@6@QM(!XoRlqW(S|UM4;n|cz5ZBdD2O;@UCyMPR>p`Q z3)x1;v7Fk{pz3WyCC`68Yyt=9!%TLtkmg~Wq9~ijhuh3+`6$eP7Bk0P3N#MNsA<|A zRk>c`w@QYpk`F2vPnBKHYzB|fsL~N77Ktx}ec&s+9|{;3&U932FQ1__85+i^EsE0C z<$QafyfS|78g^)5D5ogOrV7ztJ$jm4?dSo0^s9-e!rV4xLE01i?nVP;_jip&O^_G) zs(M~+#eN(VY;u)B8Xq){Zq1!hw^r7<ldYuL>L7NeS~MGy7{;kBit3p89hHwi{PB%h z>Y72ucH3RpxQHlDQIt&;;ul`sl69T6ilyEf!Kp3EPWfy^6?N16R^n#w#WD|UVHcc- zYkbf+Xj{NLXq?05l{&}@_Zz^eEsCP860^vrk*s#_jqJ&?A)0nY*;FA`yh<Erk50!i zXY+oVI4EOQ+1oretuXrbG}%hlUS<CNTiF7W9vW3tN%`9k(2HB4r%ngMSi2<8y1js{ z#>o+Ci=tW_Y=)Uv>9oIhBJDeJguQySmbD8E<`hNQR3Z8j-AVS-W-(iSGDs5#WeiES za`(y1Mk`5zs!_q8nT`Ks*6LYTjVh|7TXQe$$`ryAJPyXBGH;pp*h%cbvF@DOq9|vl zei$?4rXrgWj3L&a*+iQuti`>qc;>1t%BBiYTO>At#q2n)Klf;)CJxHDIlh>?P0S1U zkZ~+XdCHDg3DAGq(qE&BD#`xU-#tD3HLB1a0Hf%lb?n{dDT>vYA)MNxD4KJNJWqCo zwVZrLzoEk*PEnLi72*t5lRV{d>CsAn=!~9n9lpXRFj7rHt5}JVw+(W~ieoKt7v?yZ z@bA?ymOHbqvKZfBzp~|46YT1%D81QI<oNUhV;E+rJ2CUBg^b2&VE8696(PaP6+J2y zQd<<2<(Guqk7xOJ1J*cWBWfSms>JShLH?C$i?XS2tS4svRNnQBQYO#Q#z7gGk=s+_ z-u6$K>?F^?rkvJ`kM~C^HYWe8N>!3%b0F2d$+(osA$Evk(y!X$;m1^C_GT`qEs6?^ zO-OZncuD9kq{GLaUDd_j87-Bi137XgR9loy6=JO{>27k=<Idvr6m30ZT0z-;Zh{i3 zf1cm(9_{0&3~a_ksp>U2MbTcH_K&!2JY|C0=@$!)EBq#LYKx+1Ux}TD2e<VH=YCg) zEbFD|sVSTK#{A=HImN%VC%;(P7P-O&kt_f8&!{Lp{W|7UKQP`IhrGUbXj4CN=10!% z?o>%NzR9V;BPz7z6eUkJCfWQp$hnh!;E|M-@xSvKy4DjEzmceGFp#05gKCSSl58%( z-*5OE1s~UnG*=RDIPh5Jh>?tHi?XS2tfVd*Dazg1t}oDY&!6)+|8fLnjySH$L|^NH z@vfSYhPChulf<IW`;zB{7e@Vd6-Bek<>?x;40+O9j*uVRnJ7+e*SonCNkNu{YKx*| z){~kKH>2nz(b2S>oA0+hxG7e(McLFhM*7p&>93!gDBhZkFw#oEw3>3FHv-DJm*4M> z9A(B@Mxi!t{ieugQ0q6-Jbi5reP(MEda3Fod>pJXZdYwll(xUJv*^ZtRSXw1ZdK8o z1)yx|Th>;e!b;2^Cl+@)s)>U#ZeM)mZXcL|F~cGBq8DB#vf=AGi(bL^G4oYbQ6)>S zpZXIy*7L#0=zE=IIP?`CXZD6F)fPorPAiU^<!+#--Ui0WuvKiIQy*cUe3DTVWmDg1 z?X{<}UDL*i2VqH?I4EQ9C<}v4%ndw`v+%Lo<2hS6x2G64bCO0CRZ`o*9{JSih<rB~ zw;o+&Z4V9<8`l(3s4a>*{Mlf59C;RT$S>!^&-+<oi(#T>Jv)V>D4Qz8?vmwmR^>t; zF}AgvLTyp@GS6V#MRyEwtcQ>Be&)PdQWx>O*D^PXqH(;7=Ezn*g*f8DsJpl*?^dIm zI9<1ck=mjthoVDp_t{}EW`j}VNg;mpVh`~vLU){^D4Y7m{Z7sm`J3u(h2@-mdTNWZ z8{KaPRp(N%%K#t2PL+9CbL7H38P6z+#_`{VO1SCoI(}Vw3iRd1+I+xiF81f9>!~e@ zN~l~BPw*!C_61;Acc{rtXL$;dGgnVhludm@)l+9)@{*G%a(<7V+M?_a+e{6cLmxub zV)$@0ap5h?)ewD0tY8#H<G5c_2c)cyzYhQZ8R*L=vr?jfTT4c5QPekw*Y3IYukp-R zfN{jOF)y$P^JlLrjG`!;`bPHZ0R!LkvaImAi25JI7G-Z3n1QO<Sx~hJKCVQT<B>P& zi;D9zH9lw@7kA!8)ofY0emfX7-q+&uKV>Q=4{SKKMNy59AHvShTRe}QVC404;F&dV zD<NLioT4b3Dn#B=au2@n&MD>n<$ansD8q8gIqX_~fseKDQT;+){%TaPl3dS4qlzk- zcQ*;+k*{EE1>@(GV7`4zZRKk46Gm-O)LxTASobNAh8$!tdW`GDxAy%{`90?>qbSOz z3URuBN>6UTx1dOEGF?xf2W4!TbqT+24&K3~@X;V-Bp<v!UYU8-U89OB+1K$9W)pHf zQAXbKOLrbCUMZLBO;@Nbipu_#0ES#oTmnWtHi|DEy-F!t^{JksD4Qz8{Jh^t9<ywQ zlGklCs^hD+D0}~!O&GVAz-&Ucs~^3hcs)B?CF)Fu#s`gK^~voR^O}JnzXp#SqIquR zT8h)MQATQuq6*eqhdb9TF#<>c<5SZ}zR9Djl4iNjjiM-<D#Yk@bpUTPJw+Mb@1`aW z%5ZzQ9C4I{D*4t<jTp!G-x#h`h$w;k4b%v!66?g}$k-~Iud4gwPJBpEl43IH7Iu+U zTND+p%*1|erF_QI(w%s~hog#L_d5zjQ8x9BN;Jv6`HGh*O0Kd|p|&X7rS}4SohxJg zN`B817mVi(ZjDr|JGaqO6pbS;Z7DJu%OY|)kLve3g16cE%=o*W8>6-;3ZqQCQ8ErW zSDRdV0w1}xgpyD=Tu)JyO?_ho@Toc<bE$~9*0GeJ?P}7H?RY0X<4v7vSk?Io_Rrs; z_n8GB74Pb}dxJ9KLXBF2qB=c^N6UDDw`j1z=zkJ3;m7zp42+n7cg$&3eX;MfrJ%Mb z>V8c#!=uPsU_^j%czSg{qM?OYJ*Wt-KUHl}Hua4&yytrGlbf@Y3Khp`+7)Hcw@at% zAK=1WpVbvreR?YtMU_NZ<>J?U4psA^YR2q9-ehS3;geTOPi;{Y?PGMh_|DDvnXF1; zgMKGY<f^tPoBG!2+D3bFW8qq&Rd!h;wME(V>w`6bHZ{2Zwu^9`D64y^K4={7P0AZ^ zU0ePW<kpS&En^GuX<<w3*Q(!CilX0O<VJZn=kv-n7N?&E>nVz|sc)=!+1l}!r#wWT zM>md9Ta-;l1E@yws|1fe*G{~M8G`HtRWFUBP4QM3mz+%fdt>^jRTX%L6Ya$A2_bIO z7Ddr95zg?AtI6%pd5ZZ(eDoAW+0-}I`g&P$_OXL#cw>fUd_~!&Qzl@JxGxpARHBtk zYF3K(;{igqeVvh_XdGDa05T2jsyqJQ^jayNb<t0Fu6S<L+EP&~<EI&BWbHuYE?~4j zT7oxl>m>U6Z@?K|6-C+9H}*N*3h+kHI*Bql!;p1PZK>?+U#$#jIdZ&P6F%NIzRkKW z?ksXU9z?YT6-DFtu+73?mG~bRUSN29+R3&w4-(aT?Z-Q)+M=jQLkeM>C?hWh1}}Pn zMb+smhL(;%C1}+aWmDg1SJ4G{nI8e-_l|H)9F)=5A`<hDE%5OTZ?DytUCg^nAMxqp zA&n}kq+q?4P_;MpQTjbFnoNAa%x`uShlia|s4a@>YY~cPz7C88Fe-n!$HHPeizCV& zMT=6EP=%<uy!0XqE!RP$zPJM)sx8WX`J**_Y|3Aa+F+Z&y7ulPeoZ{2@j>HQ`@WRn zjo-mk?5{%Avk!aN!-j1|+!URlwkT@t`znT;n>K?{4UFl@f*p_a6J>lJDilT8R3T1O zmH5Hd2D^w7({+NzQKd&D>@I@#(a02;i+NNW&RTATkMNH_S(V1+#O&@h1Vzykne+@M z_G_(ddBtPaVrnrHoGeytQ4~E5iu2A3i}HD9)x@dWr8Va{DVzGnZbo(y{;en~<3Bm2 zc^;HO+X8A?)OF(J%&Lg~U611wwyKIMNy}M+*<Bod-4BR7eya^XU6hHV!>4N66-8;^ z&2{H0^33k8BH{CTg`%hu>Kj>lgB*DOOO9gtZ5Pe^LD@+*8_=%i;@Q;0JLucYm76av zFTS7Jq47cE2#no{6YKKS?{maqdb~BCTGv|CUD6i!_NlfgN}d@%YSSH&yTgZLe-Cc? zxRSX0bO=tkskSJaD%9y3>K*v4vyLM3MsrOZlo1%a3}1t_=o3f4$Ni(Nc}}{u7+2Cu zqe`nJ!H{b|C;$5qm+H*RmUk36{fj^qwWXq%*(yV#_a^jk+u_4`ZWF$zWh3D+pg#IU z6-C)pA)ZH%io9R6mvDL18(DhPmdZ}_-e*WpUxu-ktTR!kVk>_BS9$U3P8W?28b^|i z5i{Xwm_hCW!*GT1`)0PH;+tTcI8<#>luu?d)&Q0w4q0crRw)lY@uiJ8^r;<wE7cZd z)A&&N>s|$()v%>_J-CM^4$81f++bK4zbEx??dZp*u6)slTEg#6PmL<7q)y-={JLAf z$cCy5WlHe(7k$MW^Dd}TpxUCSQ2j>qCCT`$N_wDe?JmXr?zRzp-x$;{QEgE+Rfrvp zYgYW_`8Fb=1;bjjYKyXcGLz7EC8Rn#m4c50zMlO41{<+E)lK7r#!)pU^-oJ&9bW{D z>FvDvehci=hZez^QPmbjVU-Bad?VtJ6?@B_;e2gk4RN=#gF;c1O%=*}0jznmBEF*i zp{qt32W8~i?}Vyjh@%pGG_z^ScfEBG>$Wa2QWRC<gj)n3NAAS)kS7#I7q{gH7q=1) z5x%$uT(w0}vPyw}(m})_^ZMQ-+47I?T8f<s{f!hw+0-}AlBL(+uP1tm=UXb{R(91E zWt(N3`}2+Zn`JTE-Ice0(?GnoAF1&{<ER>Q1(B~r<jtY#{5=D|bJ9*2+B2M-RBcfd zy^|RuGCMtwJ6KPgyg%JYQIt&;Vm<L-1KzK`tC(i7P!k7boX9z72#igFDtX>H<ckk) zy{L+aFA=LzMU^CaUqEZ$iafGDV0Z@C=X>JZMAy<&jno!JnPu$3o0Nw4JP3?d84dW5 zD!9#~%UrC`tF|bcD#VRfn;P(H=5C^U@r{@;sJ1BkLVB73HR$lnN5IFf%|1N#iH%4< ze%OtoXdD-C<Ki2?)%lD83AOm~kP2c?yN|f>R<%V@Cvp^nS;h{;A@kN&&U59Jw>J=j zp7h7L1=SX1Q{TA%+_5@e^Q)2AgPSU-Ey~^;dISB{a;TDfEL94$<&G(pM2Qy#H9lw@ zSR=uB_umcOq5m29$QmWYop}ea4^M5WDD8dQpZB`+fn&;vYmXN*YKyX|LhQ<{uEH-e zAEEDZLQkIujXW(U0qrUUZ*3^z@W?CAKfkRhp7hAp{JQj4uu9yG@oq9&;%G3g);Htz zrZpF3dfa8y7DYu_$-eSrKI46z@;s%kqd3|6A}ar?wkVq_#C~n<GF++JQM4F<qFkh1 zQ3jqfR9(a~m+dMo#)Pj5ZY_p%*rQQJm7umEzUS$9KV%#!CrtU0!(QS^$7A?)Ra+Dl zlQk1{KW^qTo@JQuurIB|*9u2*(>S%Ivb742Ehxj+ob4c5R8G^xLH+qB&B6TRF4|Rp zs5&>KDBn`wUD#!x(Ws(IIz5?Wc<uKHzwSsdirh5kF`k{p)Gzz>)D}f8^Yk+~I>{R( z2ZCXHq%=QtqoZizdsR<SluZ?4)gaP}n@sH}7K|M0Mr~1c(6d1F?QifrWV@PaR)L3X zb`w7F8yH2=I2?+O!R}IK{;%tnQ-%-P#>Lt;TN$-QQPWa-qg}nkZzbRJHm%F@p{KaG zRBH{RD9Wb3k@x!a4(m27M4Yxr(9<|5Bj{NR#3Aps41*72k(aD~iw?rBhR~>@N;*Ah ziQeaZzN*S~H?kXxdx@wmr@>HdQB+J;9kgBPL+%N`w7AI(4||G(5zFygskSJaD#R>R zNn)Glj1ZUW+x|}+s=p?^ZLmi69jfH}v9QHr_Nh-lkv{Q=Mio`E`lJQMS27z{{<@Kc zr?7%HBgOSaQy8^HQTC;-Vc$SzG|E1)%fvbCMDgKbXXXq>QIt(%LN>0&5jOJu2(co? zL=y*P6iuj(uk&}bl78@!sq4p9v<Vl_dKcBGqDs!Red|6w>o<Pgp<s9p9L8o9ix7UT zRwYwg6jkoF4sTQ*7{OrdzB!G}Y9B62+&$<<QIt&;Le-^q>=^1N#FcoIOl?uNZ{HPv z@?M>t2Ed1i>ddaO@#1xtf{dbQ9F-dN`jf@__dRdqVaj$X6GZBm_+)B}qAUt6!&tZw za#iJfe!4+()E12rw=NfOqbSOzzA;N})P!wX5-IlVy=tU!P)641Ygj#(dEwpQBR)1y zZ)`t7Ed99LNKsUYaZFFFQx`xMYfms(JI*fsiWCh>Of*tk6m?a%AGP#;<C%8=W9yYB z>`rW?Sn~FYk)kM@`o^w_V;$BvF-m0bTyLbdD0`V_Kg>?0DnIy$TUCq=Z#Y5JyFEeU zgT^st(7r#J<d@TB<UhUyuxVo=#ehvyj!|0_MRU2aA9bN5Yql#|jQOz1NKuqc6(Wn( zqbJLAA1fl7dNLXZW%PGlhtp0ne_v)tH+HDPMka=fE5`PWqNoy@_l#cj`~o(ynXRZ0 z-yB&lsx6Ar=2QQC8^V$cjuD}~eHlejHua6{vo&Lw-{>*IIl);I2W3pLyP4mY_#lpg zZ<5)Cx(?#{RU3^es^saGBiQ*Vh}P~6MzKd%S@)1;qUz(4oZ6zOaOFLIEBVZ2KK0?* zf_47fNci-x$|;JnsY1+HX2i3%dBerD8a*{}P{y_PpYWc4M_<w&KE`a%WHWm^iYl2F z8dX$D)7gd5`^cWU6&S6vR<UMVM~QVSQ}ompMRh4z8uRln`98XNoMVO42Z<hG=8U2! zn<_-xb?eW{93L;buiL13KPZE~UC2BOS;h3X!o*?cJR?O>B`<%JGEC2sw>5V~98ah8 zVa->Bi*vq(6>5v3Xdi>NYdetXmW>ym!qyupin6J1%m+~+E#@rl;C=d9(_c|G?X`8f z-Xm5qtBf$Q#xYOhgT_%OumMI(Ir(u+`E{Nx9Wz*jZ@OiqwkV2@B`|~ZSjAc`4ikkA z6u}yRYKyX|LX3C49<uP9e&UBiVTIbF>@Fp{VqW_iU*|6Pb+7kX!dA5!Evi?2h1xr+ z4;qK<-kKO+$y>nXDTo^l&#+3RhKgzFD~!|@MY%U|$N1_E7_ucc%6q_;|39v-1G=W{ zdp{*a5JGgK1yO_OdH0;W1Sx7FdJru-iIzx2k505flu^Ry(FyX-d5J!v3`Q9Y(TPs< z^8XH*|K0aDYt33&*8cYX_PeK_efGZJS57}=FQ^nnQ`;ufnD{r$?sP9%WcNR~`O$Sz zbk3T^u-;Xx4D||PNaYjk#nvIR(4Ed2m7;#oHjUS^a|-iiB|T(=26q_MMWtx(!WlB( zz*c7sm3No7G4v0LrnV6$<NJy={?JQykIORnK@siemB()4Bi6fS_;K1?l>bxKQ@WK& zF|eXcl3jA4*Q!@3DsOFg|Ej!LjJN!;VV#-kqEaVY*&zd_dSlWAh+5a&c;&r~Wc!s7 zsKKM_qG-wxr?qXH@ZTrZlQnvL#7aijMbR6=AK|_>4@OZ>*tqG#_yXH!;TrnHV1xSc z`^zWlTsI9TYC!a|cH)k1`Q_q1?~uzv*F~jbFI)#A9}vp(=bg-aZ<pHAW!1P8Dn-$h zA=d53gZZegj<Q2ok0VqUMd#mt#Va8pAI5f-+c4mV7uSY<5QXpGV^oUz;a}%E;u-Q} z&jwGH`tyG(NHN6a3!}QI)S~C7kW*IGmR0k|3BOkSZb7SvuJ?gaDT=1HO{P7Oo%pd+ z`Q@iBjSf>kDB|7F6NuR^09Goy*t;`rc}%w%BIR}-PNgW5r@3u-AN5}r^EUnZ^UUV= z#DeW-J*h4#WvpxIgen+$r{<NHXBM|oDT=1HF>@B+{9@<ga_peBg8D%b_dlc~-X|Yg zdo%bk?pYH)K2Kh`=+k{cr6`lm&vqlqqChrcuzgwHZ(41+W7b7Mbx|o}-B+ivWqI)T z+H&Le^MXoIG_{RAPOnR>&Hzn1e9J4TE{djAV{yBP9ewiVvNGoe2T7%<AG9{8$#kX8 zerDIFo^-raK~h~*idHGbjp8?F9#gl1%%7FpP-m2)scmFp>t2p8aJ0zFr-mX2w%*Ta zj|xh@kL(w@(~wCQ-=oGFcRnVrrrcs)h&+&buccp;{%(lg+4+$@NcWME+pi(3qppie z(cch}96s*6&7FGk&9vTzFG$hUHtrC17voRgwwCX|+8O+y2(iWyyX|k-8>nmx+h@OK zFV3`)|BO0hU`3hC?EC!Z3i(2M9UwYeud|o7ZnD;a<$~&>Qh%&;!HtQEXK@2!|DgNq zuVL-wHy<IW6h%{p_=R_t;@7(d$mQ)mS?Twnh-&p}V1KU802;!^^Y3ri;y*gcNu_5Q zSWzZVtG2*8@hK20Yef61j=XGqu*^*Hwo+YG>c*#mm~n1nuB{Kmgy}`N|A|1^?8>JU zDn-$hA#RtZxboW>K61(EN*eWpBIxXc=$EICJkTdtZtd_qg-TH-dscVE3FJfgp+>l~ zk;u?gv9l~(t*}OQQ7O8X!0ep20DtP=Nt%-zr%)-1rnXI{2wNt*bH9(AwI;wyby4)Q zz-d@5-9Woi`@z=VP5jfE5INs*IHKEhzSIxrq=mTuxPV_*#kaqInUBA@*GaBfztBo` zQ7L+siRzC2Ir*0o-Q_%2tCdPoG_`FqeVF@&McVa{&%!eeeozEmogr>1e?gwdJy`Db zJ857=nHbOgJSODk6Z3bKoBBR8tP`meU85q~Li!KZe|d-u-L~IKr6?215NDQ-MR}pE z?d7sZ35NR*deh*Xlz{JX60Jn#DJovAFdy0_NUlA<&v2VT{h+@ga%}Cl<EFk{Wq{jS z{JOd>Dn-905S0q^Dffe9P^B4$??KU&A>xql73E(qwU<L%zf7U`Q4~RMvk;L|)1FUQ z)kW^Ekk7!1GD-5Cg%ijN@Vp{C=V|%)`>mbit>2Oi_i9v%-sxe48&QBa-_}w7RXzas zIJz#%gfc{rx|x@^-q~5ce3xRlAEf9pi-%)OROi$x2VIWu4&3KKCwcKwS_+k-e$X)n zRi`gJVIyya${taL1=U5R=xB$0eOvSJkbGTbk>6%nsT4(1+t?eFe9v6ob(bF(c^K|% zDFT_Tu>UxVb$bE$k@M+Awsd@N*)#VD11rkp`{iaBsUN~~b^AJRz$Nx1S6?|VDOgZl zRI2g~AIto-8yFcJfC!Da$a)s<D>Ha!L8T~~GDL>)1M#d##o^N8IZ{wv6#XpF0b~0U zv=Wu|bW5R8teR<{%qX?jV1xQG?n%y{w*bHDrKTRZu5JE-$|O~0qso}Bi%JFlbNpv4 z=dYZA@2W3gJ3bGSDN{xXDn-$hA@+lLerKKohD%%XmIgm4A|u)Xr_L%)U)91sT>-K4 z{h}nF&kd|7ldFk`vEF?I&+Xv(;PtK8@oJHBMno+^bx|q$76{R}W!>4Jmt&>>nl`8m zs_UX?$`E&Nqc^gQmP6&svYiZmP((d@@1L{5h4ee{<AnbJ7J6*7?CHb}tSA%u-UM%D zh6(01XrN5?Xep>JDn;L(pl-&PeXQ@CA@az_I);}o6ipdoz3Xz1omksT9;)8P;0HzA zX*b2f98&Q;9>I@4hrPhrYY*vCL^H6WO!lmf#7KPztzAVGw=DXdO?c5+4vr5JR2P*p z#<tvOe2=A!=q2s*w@1vju8X26L%dLUa)~wG*IVW)HPGM(MbO@b9c1Aw_TqY1S+YkD z11rje#(|)|n#f{ZW4p@wcA<uTPNj_FZsEJ{Sji1t<=^4G4G}4n31x^Z|HJa~zzv<` zj8b_FaWeE*IEy%H=CBRp)dKvwkMF!>bH4YGTVB*M{8sdP(Dy$oAAlWi^q{M3YU*L7 zx~P;f?zQWHXUwNmFB#XWI!>eXS4|X68DgDi$;)F-c9N0(><oTT1dV#a+Gk=8-u$l+ zd8lJaGnJxDXnZQxyAkDhzCnJnpI54t>Y`G{c(@wnT=@IH{ba{WeGHMZ6iscTLPewJ zY?xD)c=ep|JC(ZQ1f(O*URrubKgoj;N96%*;k_y$0U4tF)38Rw=rgB&HU6&QO;LJ& zc}}IeG!4dyhsuHM?LDJ-JybaI#ovBF+)K~PZ<k0E8_M`|s*6h5Z+FIfWL2j@ogo)0 zl9#WqcuQ3C@#IvBqN#1<psTizjU4kznEcxr{Gf<eo5Ey5f*<@)Icp}YeZgKGSthy< z>S$m^nIyk0hingum0BTNP}8#1(s^P@%wSG+QK{UMH%df(!bUI<*K3_%1^hROlZQh% zm7-|M5OEndBUx0>+;Ud!AcG$ifml>jKULpG{Z=h2*t1);SBtMa!oZ3$xxcXkDvh_m z_Xq-_+%7w@rrb+$`fe}0W!803sc>!2&l>B$G6MChxL3QKd0D(aG644mRF{r6GL&9z z#Kdz)#Qpez_yu)c6#cV8jLDMCs+!$WEl-{)BI?0dgAM9O)RVS04-fUeR{gr4Ga3l5 z>J7!ie<NW7)n>AFQK@Hv%WWCa&C-5-55GP6MDedNBIfWIPNgWCGDIe}AqDuZ4gRw7 zAMuPil)!yWH}I|Ry>InS^oed@(#$(Fz7n#S_r&*5IWzY;eqe)pHkIw$ePvXN_O817 zW@3))0Zr;8b<gW0R^v>6nKXMoqq?Y+*PL`z6z!93qvWWMta<(Ra`KQ3j7m{7wT+iA z))DO7yn!;X^KM3UQFQX#Z}MtlPyANu%rfrAZr1x>Z`rI~0Zyf;ANMb$p%PA4uu>6Q zqk}WFrGEs<R_=w-+I3x2YG(0@wzKKoU_<R7PsU7R1Ddv%*4}oUN>MbmjoN^(yv&Ks z>&T2rp2!-Z>!N6tF)PVeWykl2jX|Fo^F}=NfbV_=8`KZl3y{0*sf%biBbO|fqs!0C zU%D>6wbM3@H;S7=w9*|a$-U!R7<v?CLK)(O{=zhCySEKxzCaIy9~2R;McZPWyTcE4 z_Ihha6VY@-9$E5Kuz?k2awRbt{UaE^t{Qhs{XSHj@7zcZ+g2U@L)S&6n1i%kO;qhz zoov4;?kRZTx^nnU4^E{hnli*bYHU8M)159dK;||0K@s$8BF^%xCJJxpF8jC2VpNJU zsSp<fKSJS$I!P_Kf3ta9T7+C%5SiskyP{IGO{??v1nZFRJ>|`r9~qURXlff#tQ);j zZdV*5Ym8fL=pPi_z+)<M#r4HmxI0)q-?BiA?Au$8`J863LH&5|cFY!^))T+3I)Ri^ zHi|X-hRB*{doikuN(CjKvxRHDF*2x(q$3YZ6&sEWksS*zWmJlyDMP%qJTz4t`DZLo zZZR3V?ME2<)Qs%r9j^TeCcko0r>Ebysd|vB5>&qMBBv{f^MT{}h(UujDzzYO2S!wt z{kbCQbDlzvY7IZsevrT4CcKXf=P!2TMV$s+7nNcTkI=4K!$vV6Ha0sWeoGq6tDJAD zQ7MY1wsG?_J%@Z$DTH4eIosd|MI^g?vxUUBOT*h**ch^?h_p><$NRqjqERWzBq;g2 z%_XiK{3s2?$IEqO+T&*Y;D!`4)kUR3;vG_d<;GQK0C%rG7L(uh<t^<Nn5h&+Q`?9s zoA*V;m+Q&%Rb6H9gCde$a-d$3%ImDoURUL*EE6lW;B!BfwNfd{MAaTqnTPQb35e;} zs><ONy!dACJ3#2VsFbQ6;+&*%t1BC?x7U)+i#>S<`$IqLnEa=UqN#1f4leI3hgj{o zW?F`*VqF)tfqNq4vsA2<jr+4g<gg1l_^qBd%v8$gM}B0N`!8>;-S1=N?ciA~ZC>ON zs!LVg{7=fmBR^~?M0MEcxud5nc<m$03f}=gbSWd6{#G8-Ysx=@>hJ~KmSH~E+vwfs zn`rI6Xs`Lbos&Lbebov!3c`ltJa@UaMj8I4-8n|3(z320e~DKbPE=6U>>XB1s=A}v zpYMxlF6%EU%rjc!=AG!GQmU$1T9&HlX%9r~tO~N>h1xuC^ilM4T^B`D+qfm0)lwb| zEyTN2`HfLs6de|p6PbJbz$zDPTner!+d7x!(Ic-LY*0TIq-9~9=#BTaKd|%qShbt1 zdgU>@H+LGMKXqMHO67ow%Tz1N??4nv^p{1VOnjByLDZwybx|~Bh*fyOFgf(fN#^C) z#^47<#5k)8J}Rqx9{BO7%rF^nb|V|Kr-gwPWfGTZhyI~{-JC$ID>+dv9<o78sCn8< zbx|o=B?$R_<`0u~KJ8*xcRMmFMbVTY&P7l6mJv}ItnAa820thwLd%2dLv6F$)!Woq zIrM8DcJp$s6e>lT7;6bx+6|Zcw(et@{Zloni%QX2Nf>umj+76ICa`B8?jsskuZcv_ z)V9eK=-y4HmwL~>`*tw+K@plmE_`!UzgE5fc%el|Vf}+Go3`4(iZb!b$b%71?O4>w z-H5M2vi9Zz{LQ8UjOwCN@7;2zZU}FOwyO|R>b8+l^NRAn^H*k6ilQk)WGUF&UKSWy zl)su3qfuQHtq>vcid6~N`29WNIFF{VMr?&Am7;!xg*l*FT2LD9AAyLeA11p5+-6-i z7P3-ZREmyvxaVxvM-EDR&b;o8(5MteQ`;D+i@M7$xts8QJAWAbpa>J50J_Ar1uJK; zD(3Af3zqTWeouG({2u>#NSV;N3sFe%g``8hKpwTg9ue5OE-FRGO56{=K@3^P#{Bfz zkBGpgbE=LuGQ58m`Ke3S=Z}l}WAvflR!7jUi4({crR3-0oL||y#K4L&q2nWR&;>V= zD?(lQq(%!3?TSj#u@W`!C-}&|oyzfmm;l2_ZDgV|#9ILSf^6hy3$OjOGVj*!1NMU- zEGmQ5l9H1UnfJw_YM#%}^C$j2%knGt=jdT2v?<6Uu&i+lPNg1S=!3n2%90i7?HyVh zr!60VRvAfmxAoRMN^WD8&*7ZvqEd&_{zTr|XRsX&M6;|&Exui8UVcX_PNgWC+Qymw zpH<kg&yD!ZT6GM5P{f&aMG^1wD%+0@mZ91$u=?Y&kridK^>q>4<2=Popjhp5tIr0W zJi)5%7{IA6D%JC_yE@~`_WXQ{WNl{X8CL1sAWo$ynleNbYmSkuZ~vA&yg+e-9~3dw zRtNXz&wu{XCex1tXEmfJU=MqaF|eXca@O>OACI#=_Zl{ZMGmaOZ`5hRsV*v2u3K9m z9>SL>c;31HXm+(zCEml=%&8PbQ-+ATKU;&vOxbNs84<&2Mq?~j|39zug%2Jw%PlX) zL=_{vHu|EuTJjKS4mioE6wL}<w`a7BaaIu!>cs2(#~M~&TM?07F_u$ZRI0+RoVJ7n zyKEcVK9y%42Nzpo>x}1AilV7)lWAG*YBHdO3mg7Y!&~Hysmx)g7hc8k47{2{WGPy_ zjr(QnOO5547ow@~f9UplGA?f!?Qnr6$iAmb(TsaB&IeLoZK^8qR2qn33qxe(8B?_F zPfe2QqEgjEj;7jgFU!{^90FqDsYY_igE`vQ-u3Z&=(;GH+QwN%S{*sc-k;T}*TCQh zMN|*jnOfoES+8I9os+Khk~hoT(>7dxjaQAjhm=W1v`AI8v5}7q|7XN?lRc3$vvK6V zh?>-OQ7Px7{i&sLzk!XtK>VB1Ne=$diPc$V!f&PPqG)Oxr#KEZWMs}^?92Ox20thw zE^{?<8<w(oc@%|>Q6D?XJ~KD4?+@=8SWzbG&E2!W3Km<!I3T?0ndSWv8`*}1B~i;q z*F~k0e3zx#{`3c;DG*annC08W>)D&tCGiDyT@+0jB1-Q@M_GQ6V7H5%|Cz5ZTvPR~ z+`X?R+G8!E)(JJeGolM%b`C^quZ7k=;!79#q17iA;n)RtUb+<Bz0iFEGSEbhm1WBN zvW!44oX+XGsFZR4QPnq89zJ`YUGCWwxkdEd4@Fbk$XOFHPVUXWO-nr2(clL~sQRO7 zmGP_2<qj?tM6gy{*>Sz=|@tnpgn4B2|%1?TVaSV&%M1pRDim?ZHb{T^E&dxSAg; zWL0HOoinumEmH1xZN(<Ps)XN4*G18kA<i<|O_a$?$66aVu8EbUu8X3Rd<&)qC9ArY zYL|MlR0R6oc2>sz%@Ha^{h)g|M9Y2{D?ePA&en~7cZlkuQgl^gGIeP;R;E{)!|q0I zPN7m1O>N^gqr@0FV*6sjK95MDeo%y}kQw9L1?{a0{5Y5yBPSK8&kp;SM67}CA!VYf z+PlQ5IwtCb<xT%^+2qGgVf!P-lj@>U8PTe;br<|r6@b`tevF*HZJwA~uB=9-D4N<v z+kFr&j|XoT!>bh1s4j|D3=<MM<D08foI9Q|a_Y9`Z0hucX8$Yo--(C%t$Z_r;kkMt zJ?Y0dxu<y-F<@N{+(+rUsFbnJXp}ZiPR;Bsrg?;0sT4(1+c+<&I$rK6?I^Y$xrnx_ z*DR%ITBQ`<{M$G=dwzGeboka3Dn-8sU27w!)9dll=U55W(p1Y(FO^EsRlms;UuwLp z?c~M=wHjijQj`g`jVPr1(eh-@HQKunPeVVaJxXQr3`%aF_A6E`;OQv2WaSd^Z_ELW zO3_vsl<a_AQAf0ry6Ov-9xNA}KP0;OHpUB3U6)a+Kx&e2AikigwN>U-ge=|q4{@wt zaje^QT@+1iV-448xGb^CBCMs?8vLM$80R8ryQ-d-icgH4A12oiN*7J<xf@s^)BgW6 zQHZcGHEOFH6NeE)Wx#=C;r=~0Mp0cCl~OgU6B62@?W(xGkVoU?>wd+=`3jw_REnZ0 zLu6^r_murnrko5q>x!KH>;M0)E`6Pgng+PlKZB^3(XjFRv1@GXx;!%Pbu;Q@=x=z9 z?}S$(BIP*ZGSsWa+h;Gah}c51$(F`g=jghelXR&h-x-KVQMo^rji&E!v(c@J%0ZcR zVMCWPqIKIqeE7)Ri#C(zgFZ6q2SpfP>e_8R#$=gXa>&-^23C|wQ1UeRq4HlTR@0~D z;r`v4BMv!*QC(DuzG}q@%ZD7?cU~iTXZ8nV?A3KqG-Zg`kIPByNa3<#^RQt&B>pkp znZHKOpmC_seAO}_tUkU$H1Y`lYsr7LRqC%bb??>|w)dahVtu`FoJt`BDPD=pgj6)@ zO`OM0Vk*#T72YiN8Vh*eMtt|^gS^+eE-IA~{SWd+O+^f(`hrPLJJ`es7vZ#N80t;v zx+t33#yW0kGOO%VLDU*J#NY=-TuppxDV9_XtwhzwX<2p;+ZyjD><<n$u%b*nJRTsQ zOz&(~$=lP}jAr%4<vwAkX`$<)Qfe=FG|Ml$B_{1V$_AWp7lR`P;+9g^MbVTY^6wP? zApDDVlU+u)M?Qc_sr5Y`!1@T>8w^f0J3RTxBtC6M>YeC+vsvx-TqwHNEhZbh^~UXz zF0~-7D^Ba4;v1+;&?8eFuHHkt8Vk=GeBC0Vx)zWfCO1budtDcm+7LbuXEIl^f2$RB zc8fuwWo4^2jqqFPx+t33M*nE~PCQ%HO}al0Huymi5!#~E6$#hj$0)E0{CG&bUsFh) zAIc1@D3kcKWoTa)fBJ-o#&Ztx{N%=xjl9FCE-F<%ZZ&M2&+bv*$K{g!-!_)pOTA)L z%81r~5!^e67LsR^D#>ew?K#y&(VD{+%mzonO#QmkBR7iRZMVhVN1fn@&X@WTl)N5e z@NsyqTH@*{CRw>uE@?NkJ}OS>x~P=O$B~w`EBkx62mKHet2j!xel_qtbX^opZ6lNC zru_V`vZ>mwx*a8R*n+n`kG&>&yhUHxW9bp^?WOY2tBglat5(Opz=jbjx>$Zb_Sj7A zg4Rh=Da~QOW%J71Tp`Y;@3MsU^Au`liI}3`=j>&^{95O2eSpw)QK_Kh?UqyP;^Z$I z6Z1Iot}WuU@J_*!N>MbmjWe>~v#jyuG;J;$^gn*+_O2%WZfXB@J$#xARxOV0WkKsM znrE*XVPHj>R1ZnCTo^0ZFT|X4xmmsA)6D12#^N4c*F~k6L#(ClE&K|&hQrP1u|zgK zxw3Y*<48mY=(;GH`h>{kHg?Qqn!UDWM=bo%by2im#_yI@$GX@|1Hxb<$>AWge#xOt zem&e^gZdG!ZMSSb(IGnne_HD$tiq?$)=SBwu)EWBQK@HvTQTF@vYA#~hmHPQ7qO_U zyk;+-F_KDAG-Ze#<e@zL*_o@>Po^%C>Z0f*-@TTfksW9;h?MP|lV46eWe#B>1{>6m z@^QN@sIiB-0IFSO)M&=5wDh$G__`xYny!mV#it##tSvp!W;$C7HoTGDziRD6)|J*^ zNu?;7GQ^5(lAU(sY)*OOVRso8Hrp%Oc{BR6jmPp~cuS;mMVauDqbdG<J^r2qRzJos zOgT`sp`3NO0V;LsQvbSE^|~9Kj5-aiy)Jx6#QnX>Q>1!S*tf6Nkcx5QO!YC?pX<7) zl$ZT>%{eJ9)pRZ$r>%o+le7-2eu!tydPpio(bP8L^y|JgKUmdY%<VBwQe70SDx4+x zZc=&fz^Z_Cr+JfCJ(;w&iNOZ-W0EZZUw0o6s!qe@NoB2#0$k-E#hOd1i%Ko=X=QsB zxC^=4)LF*!%K5D)PFI%s=Qo#BilQk)+;@jBvHtk8uJ|`9#^47<I9%O^I&o`Lf7P29 z@XB6vF&C4pMjHbw$|T8mi|tBc623<Tu=;R3Qf#=DSH5`F4%L`+T~sP0z6efOw!)7N zK=l4vLG+!KPadfljFzbDqG-y{WE!x>)jGRxUop17@q18&x>3B6sIu>=c2%#SpD16j zth~FUxq%gBqH1j|NJ~(8?toZ(w6NIM>~|4)G+a_$RO-E(YwF!-Wka>Z^Dl~vr~8)) z2b^h8DT<~H5z&<rXFWf9zL*m<Mp9iA?GopM>W*`>ZMc0HC>jnfE1#9|HrSwkI4Akw z^kaFdEuj>C-ObOIh`A+l%BR!Y0io-nQZ8}b;rXm=&zsDO5N{jimPsi=(kP{)DMJj_ z6IWSJqVh>Q?}-2LLq{aLRL3`;mi;|`D>7Fs>UB&+obPR5MVTb|c1_hBCZ?KJB;eOg z9C*Sy#k-O?IVT2HNpxLQD%v>!J9=-}FahCq{-rf~$t)3>IvVXt*G19v7r{yDjj3Ys z%E#8>e~gh-7e%Y}<I$`x7>QJ^l#^rbi6aG*#BcRg+tqDQKc;7n!)j@A_V;KqwxFE( za+`?v^^sH;m7-N?Os1jv?~CzS+r-YuU`eGYn%YLTbl1V6eI2tnk}}%h2Svo=dnda% zWq%K`JioluW4}ln?`>d3nHX!=q@Dju#IRwa_08U>kE83NQnWS?vMmg_ETSHU3fKI7 zq)|#oQ-&tfR;TjfS($~_gW7n5AJkrw?-;DYSK5A!?cZ)larc0)sGV=1ffZ$PG;29_ z^zoS0TH_0PKE7rxvE3!5?c53Yg1Rm$rLulSiSpdEq7)FX`aiZ>9wb}aw~EDYrR$<- z$`J1+QvSA{I#wmcwsZn|l&*`SHHXC1!d<q=U+a?S2SQwX>n9%67-+CT{h;-DV59pF z(WOHT>p$yyNUDoU(OU<T>B68Lf=#|^-PU~s&fE1WLljLJA`i>0l45U{&f2Hr;|+dL zL|o=d+<&yd$fL&H5%D>tL-9Css~RB&R+NeHZele{6>lnk*G4}djQL#GMWyK73$kV} z*(0tb9noA)3^&}dP&8$T{0yGAt*0hz)^e_hHTXdhVPVs;FZhzZ-gTJ0P4t*tk`=Bs z+`x)5$qZbC*}&2AYc^P2zm7<2Xvg9UMPu!w>!MO2@sm=wzD9QCpJR#5yP;Sz{=JsV zDH`>obX^op8NyDfXmKH_KD$?MG*;odE{aBm*wlYr+k%w|-=xNmGh$s0KQ?_}e}fI` z2fe32{*nTD<@wsHSg+3kxMR_EQ7Pm7$AQIvihM8HuweuG8*WS}nli*WgA;n!`=-q4 z>nMXC6oG7YsZIBdwy6CT_8+J7NWXELS^FeE11rh|XF#dHzZ`^H88r{q*_AHl`<!PD zX9P*Ai%JD055}EdT=rej^;0&HbLeU|>R>O747x6grVKHbO!E}$rn=#sL6pG{ieL_X zQ{R0H&2A+QwT}qd`V3n#rL%z*WfJY&7CYfN*`DtyWwTcMQI;LO9D_ZMu8T?qB{#xc zJJa%O|53SCb@7*I%yu@9!YHciqG-wxd*`O}t(hA}vTa48FjDKfC^{&)QmWd){9237 z{eE7o33K4bmzoVWs2^!rUYKo`TYjx~CmlH@)()${%MPjq8@etk^(?R~)+L*OXo)ZA z_VSQ;@G38_^4&*LDT<~HahG~L)jFj>Ec<kOticb8Nb=2*`rd6l`k>lJg_NBoeta*_ zLl1fySWzZ-qu<%kW`Sr8#0;OR!qbw6pTNx`)kUSEou}K7CpG(ia9!yl;=*1#e!;Ud zR+hRhilz*40#bXQHKzAi_HcBh!4HaP;87lT!Xv>-?a!Z{+h83&;V<@d$3O!s%0%rR zF>_{*J`cLRNV(ms7<*AQ7A;ZNMWyaWud;<cKo0t!`>5s>9mM;rDXes1wXfB6Q8Z<U zySs<U)+2MA80#_~p6j|O+O)R0=Zc@TSk(N{=UZhl_v;PjHL0(`2K6KPt%h@s?Pw)x z-Tr-kL+je*Q`o8&k&^17Qg_;^`RNbzC{<H$%K9bNm*-;H%Jz|xN>Q|dp{aekyY<8P zICksdSV?tJ^oH;j$o957o7IM_E7pgz3-SZ2Iv8wFKPC<SicF%1@IBOS+rPwUYvz)Y zyw3O5c!i+rqEdfV>W=fJ<m?e{PRc=RiD~)yn}HoAm7-|M5Oqf9d1!va;+Wt6_(2iH z2cPy@k$?&@Kj)~{)mCavT?_F!-8vXpQ6|fNB%vPU9(bMyeta3-jSY9X!|W4!NvexV zg@xJUt>tFeP<^ofmt$K0C&yT^JVPXvqG-wx(YV{%X#QUtu;v?L4Bvwy?w!1VC?wSQ z`MH}Yd!P?{_4x$jANm<sQ6_0wZWyJPW{;vpX1vnkPSs|GW1}V2MWt3GSS$er#=>)T z1`yf*rMCQ!W~|)vaTu?3T@+0jqUQbYue9A~YqOZ~(Wp_Y>!Rqm%n`WXiOy!V!E-Jf zYr4T2$AuVdP(Mn$x3M@U{g&NICg9c9mj2IJ;h@%-opoJQD%oX@<=)0o@I#$UG`~NO zef*rx#;oWisT4(1hR8G(^FlkQHDa4xjebzXd$(zpci&j{_xNf#!TQ7t7Vx^WffZ%q z;Sp~MebDm1mS_rO+pY()myT-htm`sLEwaoVS~=Ust%q${V3p47ZN_M<8FXC~O&KC{ zWaxa>Ge<Wz^7II4GU>V~IxTC3rITaP>~H?}z)S4fF2QCU4>s7Kegq}2vf#!tdquYP zZcctYz9Z{3q9eYbu8T_1vt>js7d^m)HJS~59ERCI*G18kA^L}_C+krBiuS`h+TaI8 z#AU`?_N>Nw_vg82)};&V+tOt1{PKYYR+I@nhs7P_9XocFMVn6^kHr_%bx|pLCX0LF zJ>6Jv>>{n?&~b(nVTz^<O{N~hA8CbpJ=QFH#vA;g2>LZmCc86Lw7RQnYhB|f8dy;# zD-t?b7Co<kcBS@%?Y@oCmN;J5o|TwjXjfE<_Dy68c@w8?E_*`T$|s=L>bfWs%Ftx$ zxO0W3#opEeQeqALoT8WdZ1bA@+aQYxX;pA<P`;t&Y^$f0nljN~gZdFrKzNOfkX{(! zaLPHi^$7Es?-p&$&WV!hqEd7YM#S%jYFb7Ee{I*eiIPfDG-Zeg(;us}qkpAqE3=G# zPy`+AaD!EGrDw#~b=sSHMpgzUh7~})<3G$tXBK0%D#jYdT{=6{IT&%_9zV=&zdh1w zHk)8r0Z=BCA!eL%(bgdszgWjCjy0T%(vv&CjElC!aR1a_zwW4|g@jN1Hes7O+;BQb zPx0tE6J9&@sA+8xXD<rH#^T;U*F~l1nG>p7Svy$w<8<4)JJxXGMbVTY+OF()q`SkL z6o-2g4SrArZj|M&kzO{_&;L%pEo60B{VB!i&_n|($|N(eWUA|p>NeAbbPd_2n>S6_ z^l!Sk{Ue3Ybx|q9*EHpr7?Q#|A5SR&1eKy_$`H{B4-ThXI-6-ed1<0yok-D1zHL%( z4&31NYb~mctZI$9{WRrKlF<hBgPzae#o_0!)?VkknmewZh!wJ~i%QY68pHwg9AtH> zJIMTCzC!3HMHEdLA`aldLaX`OLG6$B6AXS(1YIrTjn2PctQS@t&_?HtHL#*g!ovEb zz8GH~^M_g?=UwP2o~^9G8sv>KtlOy+-NPZWCdYB>lG-P<Vk={DGNJ3DOejO#5B3>m z{o~+!Ep2bCVgEtVbT^6ds=!6-_g8;tRn8b~82!*sMNFnsE-oUMeJ-{(J=(CZrKcbC zjKgFa-w~BtCcM=uKZ`M(uuvwHp~-Z{wA1r%%X9N$^bgub>1an=CH4r<-<fAP#GChD zGmeRL+|AwTB38(MW%rM6`=1`_H1cK2ci5o1s1&_JGMPGfCYoJd&o;+DnJB3gMN@{j z&Db8{`EW)~Ym0x4{hXrromzqQ?&Rz{uaoUNYVFgtlr8IxHmD!>H<myoN6qXJ?tEdJ zc69n_>+UtNlIo&T9qXofnM{aI`FSpyFmk2Y>3l)!<MfG=N>Marh_U3;0`s;NWku4P z@rLn=BIvCgT6>{!n#b5;V)4oG23C|w+dgx#^IDzyYb6tV^N7~O@{f?c!>|I-?+2+A zy_+<d-tJwTvguHM;kO`GQYnh243XD4akl2={*UPVI?Qm-Nzr#||B2eN>r;R24W0~5 zKJsSQHEZ$s2?iU~kIu1|@dXj<@N-=<c=0oB;fW(+b>L7*by2BgmlC)WUV>8=H8MQC zbx5na@{o8uYM7)_6ipf8h0W~^+L^>BV&08D20tj`Ww$@QR4uw+yY2W3m6=<E46zw+ zf2b5?ay79e#;R3dWdkeE199x|+_Lh42bWYAl`_^P>te3T>`FfpE!Ku&ov7=gXlfhp zChi?!F`Jy^{V=nnx+r=^@s8LP%>yfSE*ku0J@eb~mq`1!o52S4<5-1Y?7Y+smhz)t z`(!q%l~oM%>n^D-qttXuLV~KCrFOz&pDbe&M;sOJN`y)(MbVTYBEzolWpB>z6;IrI zO2okYzb=Xn*QQ$%!`o!v*XFLdh}9jvRkU>qGuWVhH1OzvXsXfhL$wn3asAlE$2CQt zztky?u8T^Ag-x+&4j$Qvp6n0i9)i3d4f|ro(REQYWr(<psFTd>v0GG{(9PfnMQjLP z2|wz=kGEiTcxnjiKCh0rSZ%C<6=f0@w%n2tog4i_op?R-wXy~mgN4tP0XUh^bx|oA zOM!PeUWx3(rclwkz)-YyT^B`DhRFZ&bv3JU_n>wEkdcPC42q^v9f+-6lY>1OvD5nQ z+jxTw>PL+8Ov{3_ziq!(`j1NN)J&g4Qk)#r{GrE}P$@cUBU8w^BFx!$s`bpp@rXg! zbx|~Bh$uZ%tmaiYKIKZ(L_?emMc?1p4)3E%s{Vmrw`s#N?9PV+)?GP_HmDy5-gdS` zXaT9e{0MorShM}n!CK(k1k47yE-Lk}YhARfzS;A~(^1>CTCH1I-A_!AREnZ0L%hfx zyhB@^Z?W~^;0coIqUhjz<q-EeBb(LB=I-pbJGn%LW3<5r^@Fx)+^co;XGKmA7B%vZ zmQ)v&qP+{Nj4Gwr#D8*#6M16{{ez+@L&P(zSflv{&9nYkY4n34D&NST-D}nNuqK?; zlCnC8!wtt7SWzZ)%ty3H$Kz&~6(_8A$rB{iMWyKMgL&|H4z19_^VZ0D6AbeQMN@{z ztdcrc`)gwxYuzFf4c~(z=+{Ixt3CBo22QSNU7I%1z=|@VYYD{M&7G|M``e-vHd3uJ z^maw1jQvBjS*4Bb(a*Z(AJr1|H4a5nhIk~J`zt%$YO;3Lt0!NORtyn&)ex259+@Jd zkYTz^n#vV5cW7fg*eZd)+j^r%Evv;NC;nxgnq}rx>g$#S<ce|z+Rr=B<b_z56h^eV zKM)Vg7v>)>JT#vk)qzu8RBGVDIMfYyfQ<kk#suW%BZ?i<x}NFEsT4(1+dyr5!MfC% ztNEYnZSaF4On;Z;VPR##ssn7aIev$2XnIyVxVWEz6=l+7)?Yj>vk>Cj)l0oDj`P_^ zrzWiI$_P$%QK`#OTQI8@0YcgEa(=)%l)j<OYSWifDT+2QH02z7gOxd4MSJErz~Bc( zn8p;<G6UTZLmvzq=W6s~CClYyQS%}VtSFO`?pExvDu7i-Ac_}kz_Q{BYE5s%aH@++ z%^i9Yx7an(e&y_+dvy%k>%T**x-gPcDT+2QG`&9VY%UmERjYh*B7R+67e$X=+#Zh( z-Lh@ioquR<+O#OUVvaS~pnfE~^tbtDl))ENe#~y)SZr<EKohHCIMqd^re$uiWw}*F zt5m<$unpr<(t3^8ZpKVRT)3`_qA5ePk`u||@&R}DZQEc@bx|}bFWOMs5Uf;ovCgZL ztr^3ouoI}~PNk?H_E$&Yb*3Y}heDioPZbqs&tf5W`*5m@N<9lqMn(sF_|Y1Oyz4fJ zcOwU|7XJ?BREnahZS3gz3UTIfGFzV68@*Q7MbU`BMqFPW*iij^P@hz*ol6X}q6z_( zqJDJgmkXJ69I`zxnGq-+rLJSOstw~*7nL%;OZ}QrTNGPzn2iV<%&8PbQ`@NM*-&UX zeG=KH$Ouk#Q8azk3WUoPEqA%)tl`5^1{>6mwI}8XyfZ?NQtxXI-M^>3I+Di19fla* z*HS6^wioZ{-%i!qoKI$ZYYyjBiZY=Lk>w_HF!O1@m<`A`-0)7Aq6>F9g!wOT+OKgp z>UtkGXI6LiX~rmn4eEz&&1}^9QCa@gc=ax04NJG5&YGPX#HlVSh0_(hKUd#ewW}?T zeORMwE7<(dVVp`)G-Zg|%UyP|V*~oJF&hSPs*9rA_VGgOtMWtHSZ4nlyJeS?O_3uF zHmDzlvC<UK^$x3W{(|Pct{<nms1zNw5%1GBg)R1XWn0G&HjKLzO&KE3mSZ%#G+?Dx zIyTba2Spss3dJrpH(I-@R}@?70^4}{kva49AOkDPB=o@o?1t=sQ1f6y^d9D1_l$_{ z)s<6SREky!!tU$GzijnyW@|;)Fixc?nli+z#_&6$$MeeU-k?5)@rsTNNxm7jv*{J^ zJ$|<KJ6}Z4`_ZiF?T&`ghmI1-E)Os=6ahkg!M~0ck@r(tv*1CkfY5bOsTB!!sabAi z(4*9RKD%8mxzx8S^LrJHF;Uk=(Uc(~Aci~1FPcBw_FHRCby4)y#N2q#SqQBBVB=8z zYvS6N_RPIvAA=3*M@ak|%pZBdN+DWxbCAc1eb92%?8vDuqm+H>+4Q{VAF8g*=WZos z{_(|GP456sr6`&*L|pj8{PN@NoYpnwPUy?JE{ax}Vltw0ft9k+g#Ro2Hr>~@U+ZVE zLH$^fkb!uHoZ0Q_*rP+@dB6<OAVnc`T~sP4IS<|_nlLh`ic|M?T@(%d&ui1~48X6e z>!N7N5Nig9TP&br9)9_~r=&N0^p@1aV+77*aEp9)C|dop)(6>-cP04JsZ9)bsr0_K z=i%BoXV{GU+O9yn=$gsWjxhda%m-8&*L6{;;YC^@2gDA<;v5BH$&E8C2(>c`xVTFy zMbVTYVkQb-XVJ%6^4Eu72&#*sZ+vn@?aTv~JLz*_V|TGl>@L>4+gDXL*r0y6-+Jm* zBV?}yD?T6|HC)X;&++5UJ3C0Ki%NAYnvVR`sDu6Uw=(tL$qxL(_@iz`B$c9Q$`CmL zz2ex!InDXkd&MNxMbW4kj#W6KEPk@`WGh+0o;7%x6?F_Ys2?;20rhdFyR&Iiym<fD zm9V4Nbx|oA4S|(R;c2W~x;Ni7sH7pDfuboxoF~@0#a?!NlG5f_m~p*J*0^`heL$R< z2imS$Q#Vd;!!q(uw%)Tu8&<D$mD#$_T12JQNB>ak#7@n-v*|@Lt>M8@oa&-dG&?D( zfY0y6zPDU#wNx3$sT4(<2t(v&K(^2;>*ia}OzmaxgCZ`s$%${?Fzwg4d!o-8He??Y zpW}xcSWzZ4*DP)=$9-hO-!&KUUAu9ri%QX~w>YnU|Bzi;j}xzfp@zJ*6ipdoK7U`7 zw_UT!TI5?hgC7*Jq+~Ga71hOfrDlT#vr6$+H7kk9XZ#GTD3f~jt$}C^&lO_d?%I6z zsyw1ho~Fp8qwAtlc#DJmX9Ik5HFI9BRF<3j+lw7veL0n)Xvz?K&dsHGu?LaX0ySG3 z{Gf=oeWI`~sSX=zK3{&{o%7vU)`U@w4Xh}W`OBtb1>l~|>g5VQ?)==%8nDX+D*#;= zmFm)T0dfe{!2F?RoQB=p`LGukt(7-4;Z%yEDMM6=$z6*F-+F7ET)~r5CiGXRl4l(J zXp%h})ZFXJTRmr@Z82u}t?2g{HL$CfbCNmj*KT{~nMS<&;&4&tZ#PbLQK=-~acH{= zq5ODIrYgT4Xcj)XHBO}{nlePqu!rq<yGAdq3%eCD_(2iX>dizeX@p-_%~7SR2J_nW zxu}F3(o~8vQ8`#*oSVUOg;-x|2(Q1RvM3gEh*4cs3bCSSS530#+U^0J`0pEQio1b! zoJvtNwT%df$IV3h4rZSEttz5F^;kz5-RKsw)0Uo|l0AR;blN0FU-smECYHoaoE`&7 z<1A5a3h~tYvJp8uE)!2Kgz~sKHbHe!sr2+`c)Mi7Ja`W?j?<XwB0&1`h(IUI&bls& zrnXI{Pams_@`E|QbIR4=2SqG+z8#~e4YTt&*eKt4ytpq1@G{MI8(2{$p%2>IRwNup zgwO#XF3dV>{kA!b&n$9HP+e52<n{U7FXIH}sI@>?W|kM@NB89KV_yj>MbVTYR#b6s ztd}=?@K={T41Q1qjSxhA1Jl=(Gq*eQu+V&xN>L`~Ka|0%J(;~O+1j?eb^Ajv9-qU_ z5N$}MjPu~*5-qK(9{X^|4z7|)Q6|(j-u#p~#zx$lDV}!k!^bR+!f$aGZ;tmNZmb_7 z44<N=!CuSv%ZLFmJ;dKT@q10~`h}&p@z+Le@5!lD1CPF_!uCED<E+IybRqnBosDo? zn1?4u3=tEz2Xd;5O4U8GALG??ypY}s8%H|qV;^kgM2X;`$VaB@qG)Ox<NK2@?1WpA zHS25-PIXaqlJ7b&{0xTMVI%AG3+C3zs!eFr+hBwG(erQ|SeY=2?g7GoLS_EKx>4)= z&<FbuT^E%alClINoLcE4dfDWWT!Y`P^}t+i9phArqA5d@X=NuLUj2AZ=GmYUr@AP* z_MS1>Ro}3VLpAfVJYjb;=6<KS!3OoCOVj3FnnP~n<vaq!IY(E{Rs^#%^)*g)QK@G8 zn&4d2DGk|9fC$ve@Vv8Iu({DKIF+Jk$`Eg=5Bczu^-XNdt%?ReD5B+o8L0bOGz~en zV8b@0GGE-NGqa61vZ73?<caXA9#RV5BMk^kyC9yWRb<co3vjB7O6?js4G0%}4;v7D zvx0eKWKovdARoqdT^B`DhIqZaFPJa4?$)a8FJSP4B6=QPh}l{Bu^%?ly$A4Hzu(fH zMqg%BiZYp=ISZ#BWx*;1h%58Paj&=;DSHm|WmFfHT97smeNgRdRmG6chXVP)l)NnF zk|U>56iscTN0~eGdDpjUk6+mv{Gf>7d#f?4Iii)QetvrN2tI2_XS4sCeFj#P$%3@s zynHi?1EKaHeIiElzdqNq=8Ig4s_eQhDwVV58uX7M@I&>%%vS^Xhk$x1z5$n!?^V}D z(UhUdbalHA?{qXwOB~^9@Pi`i*>A?WBo|tV8cRGK#_$fd>eh&)MFv)s$*N<UF*`fJ z4@6;`?l}zN)tm3L9(Ov=s4gnCE7yMPadM!4Yye`37{gy(3$>o!ITv-@bzKxq8Dc)) z>c`W%o-_Bp>|*ePBIqcA8{W5r`N(CZMOMKS11rj8?u}%$l8+cg{{X8;hnsLyVt}Z6 zrMh9fqEd9MM6TlYb$Pd|0ZrSiY|5z=WkMNZ6n(Ld-SaOhiWUr)YZFT0G_wv?MVfc$ z;nT?f>WXh*_P*T40j)%>cUASeN#(Y(w=LI+E6e&yDz)JGc(7DAKh048qdG?F3P7t$ z0t+(j`0oXJiO?58lIo&T=RZuvEs!g0`v8%*&SEz5rKdRZM>rw}bX^opZ6lVm-%RG0 zlFPbv)mVcc6ft+%3m%lL_Jhig3;7?gHq{4PH;?aUU`3fkiq7!E9e#KN@v+}u?B0L_ z=F77ONvexVm5=kmSke?WR87|N;SbsHMLn&f>hzOTilQk)<o)nE%C=Um$C`~BXz+s~ zPK|Zp8^Rl-531@Bk(=##+u@avYa-adiZVfNWXyx+?C%k5&0=F3FJMl4f+f{OrNWC$ z#SNCKe4=XPzDhgAUKgs!UgaH#8+Tn7MN@|8RrSiS^Oh6Zyh||#KPX~}&m8HS(I5@= zsnl<kG@0FQGleBRA8uepnM^94Ad+1?;kl{{5VEp5tJ`}f+vbeSSwt6=O7>4jL}gQW zt`KEj_QdO*C9Koh;gU*GG-Zf6YC%_a<mqMBpjRJBby0NtWP!Uo20xm>M*JqhF7jJ! zzE6<B2KB>Mp)T_5S<p&URxaEuvBMo5xH+qhq`Ih7sONcP-)IgS4S-1fz*x-{_ZSZd zl~jtNDMRF}sW(q+*84J>&>Z!)$ZtXsp%0p%E`a)Vl^-WU7HT!jPJD0PAOkDPB;>Hg z7ME#3D`^OXQ<<eHFE{1pnGd>2s*6e`yTsWxgmc(v1VnVxEUjBm4qh?6o1{_{O&MY} z(;_!>by&~Xl5m3`6jAq<8LS#+x02y^XJ`+)Ttg<S0R~o-39=xd(uUd(HU+D*n>>&i zF@arrHcC=mMychviSx+rAH_@O(egyEV*!7TlvIkMDMQT8NjZdXw|UI^Xq3bm!vE`{ zXupg!RKaML_Nxj;@Cu9d@xn8#=Wl}zHmDzd8GCFhC;hKq_lJ3z*iyvCPQM66uhn%? zDVMl=xaU+gc+@vP-Q|<DLA?yt;dEahbX^op8KQbbr9g3L<yJN)afrbWiU<okfm3G> z*iij^WYB)GdDmGsvR)ShE6QX++5?+&QZw`qHTqn<eNB{`o5c2A?}YP2T^E&_mYD%R z8UmpK@vq%M@nh#|_G*7`Nu?;7GDK_d-$4{T>B$Nf7;Er@B3$AYgH^3;KLWZ7VgJLP zIn^9uU`3hSjXnlMZL|`_YICt?)@{+dth+nLBBO(@i%R)rEJ9nTobCC>0i{HW59&Le zi^ds%u8X26L*&z+Jk1=PSetoztM?yzyP^oQgS$=5YQM(a*m6ai^|9@>7R@!$z=|?? zT-6Ev!z~+;68}c?Z}vRJ0q;MkE-FRW5~!9I*V4ManzuO=vFB8ZqA5cl9{%OIc$bAO z?G<D2gCc0}!s}(%v)apdIayr7cmpfSgpTvr-PL@kt$x3RU1(<P=TwT0mDqQ#w`WgA z)?u|@jx)?SlnG^sTjc6@M5QhEB5YM(yrcht@wGVG5A$}3JA;Z5Wq<ynVPWr4o23%I zxmuUhI~pu*hn5m)V<PcAbSe5hT;eX_KB^kfYJJr*!X})*eopCLY8YCgu8T@xXAgUI zfbat1&bKFG{gB7j>Q_~65nY!Nt=q=Bq+dR{rQUT-wCaTTc3l@mKMQ;eR`q`RhZ{wg z6(ZxPgZAp<D1!~^2W`_B8OjNfL)x>4O@|<MP}fDJXzxOOwPL@COOd6t!pWlz{ez+@ zLqz;;_#~RHbz<A_8j$)y5%1khshNR|(QDQB=+J$daQRY;-5fv4z=|?q4j(X5t5u)s z=c8K}mBELwhw9>k_ffhoDy8z!UrjV;BcdWI%9J;wna!jj+ECX;(Uc)#Ym-XL=qg{t zP+JAO>@9$7nvYX)ZjbzG&dBg~BXw=UWXsh=6SAt@!+Fqn>?Zy>Q9z!~SyKA+EDnS& zmE>C;*+I^xdU?cH(y|I5+utSpJp_n+)ALFDPYyE8QU&W9T^E%KiNA=kJtH+dEDQ)9 zQC|M}-d@(IR0MD0bX^opZ6ga*ziKkB{dIArv(XQVh;hz|oPg?NYA$TlY+Xi<x^_a` zTwKq<iZZzy{S2#&FF3!N0Yv&}CY!o$6;}s3Bl=U<MWr0Be!)ns;u&xcX<C1U%aJ#a zh*o6^qFw2_D4H_F`;XlnWTRY@MCvOOvM1@fC|XrSxtdrAv-2w0Sn5$hMh4qNnIClw zHmDya(>08{>NHAup5tZ(S=XE*dQW!8tVVU|QX%nAZKzIxop2%$e~odGn}Td&!{WLa zMRh5PrVP<*lWOxGsh3%)l4a!AErHng`N6u`yFy%1oCpS>y*BoqS=<SyQO)tUnw=Lm zDb4#`DZ=eaI!Y=vaN%m)jtAfut?zx|!(#57)B-(9t#_OF+Vipj&)B!^4JFk@rRZwe zWIBG$j(g8|$NHo;K&~)d7e!OsI4NpSmiH;Sg{|z~#NY=-EJ$mCQyjGlSN;6ZcC6Ve z9bm!s!3I{83Elf3(rMavwmvO{U9H|3-$U0$rRXjUFTJal;S-u{XPI$L4ErdGrVLG{ z$|Jpa9^Ykb`}5)kKPaM5?ZJq%^no90&)GGvnYZj$pZ)o$nt>H%GHT!;+{$S99%{Gk zRHQw3d|H7mUR6j^T~zAxglL>6GJMVEK=gHN#?QR=WN8uAC6%IR$`E<aR<_^;26xa7 zHmW44E{cxOrr`WajiRcWV2&YWdBz^I_O)Gr!3Oo?`{gL?Ya3>>YP!57ciP#}8u_h) zq`Iiot4*_EL#;(s%*5j4V19Gx+?3WKj*?1IG-ZevxhH~AXY-D^NNq=h9~80b*fiuE zQ0sPO<K(9hzS%L!n(xAQL8T}YWEKOW5qg?JT+BC?mu`F7+Op0xL3L3n<9*cW0Ds;@ zj%emx(*@sL*G19PHg>5MSBUUk`DD>${<y2r$M7UyJLJ4lwZelDlX2Mg-t7YB5`T;( ze+0yd<vu-R-i|i~l}b-{O~oD-bA~6P$Zuox`Sa)Bm}@<1h`5$r<h*)0@j^k@MWw>R z{y@IIbl7ML8x{VUC<eUmDf6tqhPxtN7e!OsI2UzYB38b1kX>&W{h)|&ZHjGv+U=h{ z;RR@;I5EC%YdOAcegiAY1ZVHIXy*&?s|i@;+R|3o=cy!5cI80mx~Npjn!|Eh<}J*F zcztiWc6^_>HQ!nObK4W~?Yb_CrVO$6Dbr5|pQyoXRj(mtAqTS4mBM+n6|V*IV0JEm z_L_u@z;>AD%VKO-w*d3y1i8>|QA*9M6F=+x{3jKcneS)B4sOPNqCGsE(5}>JZOcC= z%GgKGQc_AhPNBM#jsK*QUF@*-sf4zxPPW^Ao+!UREOTVRkYF>F`d{>awo%RF&1jjG zBae7~cN$J=bX^qvs|HU|utGiy)1;UP*<pd3=$o(@{X=I${m2Z=jbFqLtklfezezti zVRJj-Fzh_eD^(q}U%IFior6uLzgv%yK3@umfUrq|N>MbmjrP1}po}=xPJ|6VZ1963 zqMg5Eb}kP;)Lqf01wCY$Im3i&;5`E?%7o6lcroJQA<xX+FEUTL;0{vPMWu}M`B}Vj zy83aT*z0sxP$`P04Am__6hH0eDO#SdAl8<iiutZO+SPH3y3NoWTz|HuzoTYhOss@9 zCg4Y%`a}4~0&~Uv^9xa9U6+a!GjMCAZZNi68ugryo1e1THzq%JOyDzlS?ksqn?`j} zDSGRGe0}wzc%#=LqFSC8Rw_l&)Hd>w6`#Pnm&&q^LWwTw2SqRk#jpxmiMsQ8bu^N1 zUUt!(!*vp)Qj`h3dqJ<w)rZfURh;ebejl{~bzM}7-U8vwvh@TW>iL(a*(Xz@QWQ;X zqZUM$3A{$rht`Gb#+j)f6ftVxWZX@t82WVh@vL_QUsL#vHhshz11rj;zvo1JL05d6 zQ$Unh+MUO*ab_dOe`Qn`mHK`;6u(t<eDjMy^llx&BO<SBewEiVDn-$hA>K69AI|&T z+$YMnJ87kUP{ez;p<d2Ob-+sbG0C+X_sMfwi%7_Y*bm)9%H;aF0ce%(XqA_M816ro zyVjZ|W>4sV+Gn~hD)sO}ke5rG2U_CaKzMcz=Wp}x6s|$lH7Z5X)Hc3g*|9v@7RYjW znMJAGWAVHDU{%z@`{9LXtattJ4ZOXrqetO(NmX}L>#LJuFn_$V7IUg}NKmO5=dpMN z699yl_n?Ktuv${}2i5+(R{tP=qvK5G_QE8oE-FRW+NjQzV<=y_u>!l*YrmjU6isa- z6ZEACyw)0N-L!I}nfgHyPF==<p*rhRYq-~;J^9t{RhY}4F9nsNOz3(Jk(rH0ai`Op zQ`nF-g6g7DbZv+I$DRTFoqsLX{KH8>r6`)(M&6I{G5qSJyD8SL8l!$tL|kSBR!bb; zNk#8Gyb#0p+mcc==f(zBl*wWLNw~++;JI2~^|uS*-F6KY2eY1_x}&a(O3`Q`L;@b} z!>jRlQC?V4_eIx5(Uc*w6zskw{02@DYr6H|XVY({{`fHh>yIdJ5087P5n8vOfA@&L zgE-{jslVzQv|dtJK9NntxN2=Vl{$)C`e)PY;!ZHiJ2CuG>LHho+4<Y|Jm&Js@l@gX z!+}#>RO*n+Js^ewt#ZVd8&Faf4U89a&v|hwMbXqYa!2?1SClR|OH8X3V(^0^G6Sz+ zjWYQsL+pgBnWbC$P4WJ{oq-i)qB-11bqkq_UqP{&wycaipO_}%V(N3Mi%NNTT*5p* zH{0{V4RDTe^{nvlQJL#?T@+0jVqJ1FoKKJbT?Bg<5=Eyr!Chl;8Y+)?`(-pkpI0?& zbEBX8U>~Jw%jN^Cb8RN_4S9dFPC3ZTRO)D!7iQ5mK%2bxpJHf<ZPBiB0};}73~$+D zGJD<Ko>5&?YS6-lm^oGLs{BB#$QaKn_BvoKxihDrQWQ;XBNJPN;rxd!QIwg|#NY=- z+~4Sf@v0+ya#XBlkK~Q>u48lhL}*lsGI?{c1#a9sz^B4Mv}-+)S1I4ldZcX+E7e7% z_N?~B@22WUIRo+3Zz8XdGS#|cb{Q*`qG)OxcfxknSmXCxo^f@RQTg|H%}@J;T%uLH zo6H*IWp?<2KH-WncqxAAclh^;urWy3w8MqC+_c?IQYq--ei>iUGAes7NYjuh{XN=M z1t6+M<X~>q&2qu)8j|XwQqAX#$9?Tv*i(qq5;@qTwaw%<&sx|=>AEP|XuD{errht! zQc?F%dAaEMcFY+?f6f!goq?92UYz-O4_vqqyVT<NTb(nU9#w^Z3+g3SdU)d8N0*}a z&dukjYLaEquGDGml{uC8@$Uyj^-k`R>Y`GAN2yr5lCZ5#AV+p}<(Fq36v2~gODaXt z)HYtS9!_OTGivb@g)8BXe7dDZ$aRbAoi%3+x8P<5bL&{|qgewH-+tHft9r!T*IStP zqhS8}`8`IZ-dt=4bf!gB(eVy#hd6yzM^W|jqUYzcHCc6d&3(1-jz!l+rHpkHN8Me^ z0=9Va^kJnD<E87OXlmPJ(zYF7<tn=Hvx7Vgeo#c{gR$7#-UP!au;QB+vRJ1Ed{Amt z11rj;fk$`CwZyydLm~39<?Qy_{QTA`KfJEdby2DBm%}X20{=x8GgZ;E%$wg?=$}RT z#EuqDr6`&*M1Il9ePwFvLu^j@1*j(Ifb-85=xfcq5#NJ3!ykV)`T2K}Z%ecib+6X8 zY_uG*z5|;vUe!d>rO>A_a<+n0BaC*A*c<w%{kl;+KQdN6Kk-yMHD}XL#DBV|R8X=b zDw(weLak&11uADvGqGh)Pog@Pu1neb4{fwv`R+t%i@IxWv9x6h)kV>oLm`}n2cUnb z^ThkX6J?nxW3(<`U4PcW()sFsWCj+-FVY6Tg1SXsb2wZccpNM8&l--puevUylwN%b z<8CwTga<6sn6u4Hr6`&*#Oe95;d0THNKxhKOk@tzbx|~}M1^^9T&(<dajj-ed5%}N zl&|hbe3}!!jhai;t-kglN)~acof21dIBGlT6|$(5u?|+-x3Mzf^(J#bgC81|qG+S- z-y<%I<JZ26#-F{>Kl1$l+aCIwM^yxOPBP(psQC8v(~?B7oLyMh%)y2?KlEKudin<3 zDCUG8Do+1$nMA=;dds23_Mifou8T^!#3ka!M8#jJw`65k&lOAi6_t~!w%}BXqA5ev z+Pd9Xu5Wiv*fn&*d3!Fj2KAb>sdre|cicfa{_HF7-3p*KWPbdu`bVFG4drL+ToGwk z6}M!%6up&GHPL)C3Im~9`{~L3B(K>|{I>O!pt`73`M5%OgH;gYt{U5q$JUjjN3Io< z+^gYsN!LZu)HYU@KYGaz>x0Does=`bMbTklsy7#be`^0R^kiijb8VDZQbgt7)ooBe zoRjjSTAF%UtPry+c9&b<U9}EhlmnjYx~P=;cZaJbFiNOMr_VzN%0C?+SPNY~C;nIJ zKPJ>R@-x&NCOh1&D?Io%gCEphT&5GMfEUbW741A)_Iw*-tygo|&&qQD=`}J@{YIVc zC{|VdCd#f2ms)$i9&I-2(xp};IH4kfBW$RX?eBvJ%38s-#mt_^gc=9`(?!vgp~>`Q z#38n0!Y%PAq=O-zy2w;}tV`};jf-kyQTZ@CKf;<p#d5N(D_G|uu5#n12AoQLbX$ct zwfC?VNwGvd3B#+(2SBJ(wXBYa$%s8+?pSjer@E+A`;5;RXI|l4)C$D3QnQ)%>VfD} zs2itJ6isboZThG;%U6_3X05=R+%AOkrTfs8YVn%0U4&~7;fJu)^?1vk2HyYqH||o; z4`VO3t<ju3qBxbJOsH+F2#QW-v$vO$^V@oJs*6g|UjZk>5B%7{XVvBGV@(WxP&BoT z**U1BEEw2`zda%h^#^gsf}W~s(APH9fJJLhc_rp72<9`ZCSc~&rJR!<*)pQrpoP1k zPFxPO#CAXbMt<r;mE_{yo;=(fW2h8MrD)Yy#8up^Df73j%kz8A#p$4~i`IIjwsB6~ zt|jmEwl+KRstn@lzF4|6UGJsp!L3O6VL3cxr<YnSCA)mFeBF}em0g8z@+iKdPy{>E zt~H}lxD)oi@<;#??j50hwft2n7gl5=(AsObjpd?zdlp?m!x^%!i%LakA1yg+R>ry{ z0*K+KM)AdKN3a1&eyC)o>!N6C8*9<2W`1Q?BevhEn!yi>2#J4ZDV5tkd!2Z<*$_U? zJ&LUwwB~<U=}cB6WLd^6t^mXsuzJ6}3_r1|75iN_$GcQr7nMr#eQEhTp$_~|mCWwe zZ^mC=F3(u8nwX<>T@+0j;*I-&a=hq{j%@R8Z$z!?x+wZt;0w$BjV;js)avzOjUoJO z;c;w1_!@i<-3I+dlU?3gkUSZzMgg%Tv^8H=Wj-r-)*iVNbX`<Rb9ip~*r6-dqN9PZ z^l8nb?k{1@zUIMOWL+0UQ`>l7>vlw|dNYc@uGK?)>@ZcvWvX>lP45D=_n^8*D~y~~ zz2`2gV@vY=_3wCx_03*$Lw1dt<}+q0wfXg3+yp5^1@FSOyP>bBHDgt<YL%6FIAd@W zcj^@>s4gmXH+lo!hWr2Qk3baR+TR1ma{siMf=W>|wT+XBzFW1w<NNSuvz{9Kpom~c zD`IH;V8b1(!W%8IPN~(A|2DG#;$C$RDU;TX18tgvFZ`$rL~M^y+QTc1Z+ll=Qe9Mv zMmHjVqIjm=uik^#`1Dy&DT=1HahEzc54%;p27l^jmQ)u-(@00;*s7Oi?!2lQ&soJ? zQYq?3Q1Vhlg*C^wQPocmoHT0>r<US&(_0&&CaDyS3dE{xYv+{3gWP%FVa>2+&~;HJ z)HX6S%}=l<jIGEY9BzS^VS3CaMbijDoTNT!B?^w_e7j2}gAMA(d$)9akCym?9`Iw` zh~>hyUm3o0t=SN5NTq00AhKWdsw;+IA9bliYed%Qx+oLM5NEMFQ$(qB<Po}QMii1B z>qyaQSs!ta;|o?QiZ$!oa`E@H+C2GFO@j^U2j+FeS*q9u)vi3ZT|ksxH9j%0GNN8| zT~w-iNM78ls@|o(U_kNxqH$tfK44o#tX_3p6ipc-vd6_yX7(@2`)(;^@Pi`4!g6B0 ztKtAu6zl5zj&ft(ntaUP-vpJSOjac1!)>4HQ7SIu(uum#C2xMdJmDSYT3r{FqI*%) zqVp;$tBo$igXfo&REnahZA7=N7%eup9>yzITq5W%${aRf-TrI5Vh-mKzpMUMwaJ?v zY9n$VkLJ#2ikYd@g0vkrv}|y%h$^LjB7&|pzK1Ii4xRQ0_x(e8|NZ3z)kUS~Y5;qj zds)_D2{F9O>Oxo@>AEPI+J+xJy@mVL0ep4!wEyu#=T5&Y&Z#fQi3_N9YkM@)z=|?a z5ot-j%8xqmqrve5!ftSTzH;(YL3L3n`ZaMkamOYuI|TCIU)~l}ilV7cCeye=H$-(e zZytK&i=etFT2)dH*VM{Mwe~K5eilb^w&!0@tuxr5ei+w2^TR618siJ`q5k%WVb^t0 zDYXg@*VMVF8r!XH{}Lyzwc&O-aEeaWa1>1$;=S6$uj1X<vhr%Q3;Ks%tBqD?3)jMM zf4(U7SJnvE=nEp?h($hnk`uFvUJuS#C(bu@LE1*dGbG}4ZU2bea`^M6vSsQcv=UvH zbCNEV{C`zld0bA}|9@J9ER!T8*-}YNWY=@f(<90jHQARTWEo4yP9b3iBg^QUEE&sK z)A$)0^_-K8ZG;(yvTs>Zma>ht-}}V8?&tp3tJnMeS?;~hz2|(+XK|a1irh_LTm)mt z!WW{$w)S#y@h9w~G?bpL=|+9jK^s{RQA^ge(fdIebix@{mdDD;dR5y?`&hkI)RH+) zs*mt8blF@7s}?@5BOhc|lv_M&=%%Gn6rE~@GhtR)R_j+=UWu!L3_48~wS-!TT!Uwv z9~k?W@LO3<zWlfsr(r5Our|Q|RwDLJszz;dz>eg#_`m93qO#k%MYiI}RdPk{2uDd# z^xXMf%tAzK9l%Zo!!@irkKXk{tm)(}sVs_8HL>x9wm2XB9*lsEt@!ZJ+hTu`%HGjr zQ8v|$_0?8?Zhre%xOsgN)DOyt9k&zl>lfHZErgC=MpWmIj=vJWA~%Yns3lF8EJmdG z6?SB^z!>zxhTHV1CJRyZOJz}1_`M{Yr9K1${q7CT?v>{@5mvITS93{GludQxt2VEN zJiq>d$gpxi7VE#r1#X3_cpm*-Z((K80oUhmL~2X2A|s8sPuHQN)Z>A$+3hG7O#K?a z4-M7IF9UDqPGDaPNXWi{w{|Do!P{UAPw<ovpS>2gm1^L7uF0aP)SzN8IzwLp7?tz9 zWq96ev8q=!#M?DlludQxq+!bdx#VJ+7$1K|P(LWcYjA1S;Faya_+gsZRdye9Mtpa^ z81E9zDr$+!pIDh40LCL&weipl*`m;0guUs4EF?`9MXgV=!v2$e@x#};kIbsJPdxCx zBPfcpscz&5zl@eY@2)0f`T{{^QMS?E2JyMhu<9kOdQ;L>9-4keT(o<x(?R`U_NBO+ z>eN~>{>+Y$^Vj?!M%Wz{R2D_4*x4MXZn&H8!LTokl(*}y5Di>+;~S;PqHJm*Vk!%} z$QS<4#GU9X_(o~6C|gZ9%6`=YI!d9V*Ta_bCr=xBXJx5Q2lWHLjjSkR5BTvf82?NA zTK@IeNoM?T3z=t{EQ)fAe~)LkH=aamv%!Fsf_&e)RBTJk$NpTCMcLFstf})`O783^ zeJ))WR2F4tzj~DA7T+7+!B4R2`YA8@e5t+kO(};JGS#6y;VMU5?a12sJp<$DUth^l zts2S?O)FrXsL7(JDB}ghUR7k`H5gA;xXORt*Ou4U*&w@2lSSE7H)>3(M9NJ$8Dikb z>AL$tJy&^IYJIgK$qLu%!n_c9`*Eol@WU3})umU#V6a7mJ_PqeopT<Gi<Ui0W{a^s zy>WG^EDfbPLaBS+%C8(4;mya$%(cIW1zAfFhtp7$O)bQ_&SM7m<$oF@%Fkd$q1NWK zDW^DoHRjh|Hs-)(8*qv;8Pnyh%+>l2M;xVWxBYG&e{|}JF|WDVqDNVqXO3yX|H_Fl z-<@q`e)(}JzJcRm)sCif`Scn-tZHLdBb7x_G}?mf&nolyuP<t{-~liEDT=bGZhSez z#_=mwcZ_bsPw4!h3`CI3%)Z~3xX<_Zrtzvje#4ANLZT>Yi9RNivnZH<eYG|-O>{xj zK$AsLH0Fd34}V4S!=D<mE(K?Gu_el;x)Dx1zmECVabue&Ovd*^yC0MhWwgc#Y?ZQD z7N!*}ir}N&eq<NdO2mCMtEeSKp;qRFKXo*Hj{77=<g(~rirBu~AmmwUvM9>W&)WRh zqxP3;b$s_!ZrL@EEg3i*S67oo*;F_3`o>P?^WPoJbpNnRcRwg2_>Ps?DJ~7qn2JV4 zXMD#!%Dae=HtCF_s3i&6R_2O(D}V9BuZJ`LW6nm)q#hwSnbu@cRAi*V?AZSb|D2bx zC1V12T+%Lc%@qsk=rviCO?4X#)>fOv@}kM|?9IRN?4HBhayZ@@-sa0&)9~#ZfxqkH zX<vkQ$w<5tRTL-4u7!y7o+T%*cM%k|K4}%ceGx!8o5w^(B8oE-Z-#nc*q)eZS&|Sd zn@0^jLS<1@LUv>9=tn`H+IhW?@es|X&6R6s*jgxxvZ-!V#kc=Sl$@O`uRV0Z)2{hJ z8Lj-{vI;{-z$&#j=pOkpb4r_7xo_-RBSle5{x{JPl@=q*t_Z#c`R0ztZ_SYBpT;sO zi=s@+a<Dgv!23!?Cg#0aVfnM~Tp1W#mr)dDQ{DJFk7n$`;puY!znvJBMcKDKibZ^3 zL^d+Qprhe{gT`I|7b7iIgNzhK{kYw0Bj&Y^1Vi1y;rlkTMa`zjQ*RC$sVp68)>z}< zl@ajV3ygnQFdOiGhRpiSl~ELBQ{DJ|6z*k%^P*%_Vxhl*$f9gR-yhLuZv?JYBk0(X zebbnS?&2Q34rNjl^}`|cp-f6reyA*qg$<Ul8?UCxIV{yeWl@yx4R=(msOQ)fj0bUx zS!wO*GQGks3q?^j)eS#v->^?DhDpzuC7IL@%9vTOj?Zx#2CLMy%DjJz_4OPn7sbBT zSw$`R_hU37(!=m1HUOjg*H!tgE8%kO<ETt3i=z5gt%6*fAzyxj8Dopt#-qb!;Jc0; zD2lSFg*cU2T7@_0(ML`UXq!o8QFdmujVUQ<2>ft^Rd<W?*vUDO^7#BS7K);NL^*cC z*K`=}U~Mqu*m8Vnd_Nfx|COM!C~B#*74k&~!w;43v&-ibyRmh!{M+dt3q?^j)s0Nn z%2oKCHa%q0r`e3z*F-+dK-}Aw=3y%v^6Xbb%YJw6*OGXX!QVoM`h6@-O=ZPXM#)QG ztzr~Ke_ixBMonCFKI@V(Oipall2KVY6nUo6kL=@ZR%z9@a`d2njG`!;>c*P7bw&Pv zGkVH4RTk^~pp3k&wU9@qu9foRjomvoKX8al8SvUjQS_<Q-G9UA!;ZY<U~f6M;%+0A zMN#xwz>3UNh5r!$jbz@Bj1)!LI^BjN&epusGJCmwQB&#AtOVEH1ACc$IK2qPKC>QH zta}3DvRayg?)c#U>I~BHst>RE`lXot`&WqdX(+lsuar9iyL%-`bp)zBvo-HLtW*pi zP%5Y_ii#cA1J_FB2&<g!r1GBpY1~J#^M<3OD9Wa~@w7*@;OA4Uq|;~{?431Pl>OkZ zark{S{h}jdQw#1|u0%X^s-)9F{m|#0d*AQK7c~4=<fXho#;+!eqG%4Z!4R9#io4hQ zBog{qVUn1ZLr>Y%LYzUyw&Ot;?PSsU2ZH)R8OL7rMl3_s*Pg?*+Ta?%BYkXSGq(#m ztEeS3?-^g`i{U(V&nHp$>^wnbQItNPTDS-Dap4BJ_r_UdKxi4*lua!}@15pDdF#y? z;^TomIzK35l4D1_OH|dC@?%2rY~J0usi<}=&q7hu68~F4$XsrR=jsX=wfc_YQ+$#| zg%LXhl|@lq4*8+Njp3fFSVr}RgL(P<-$kq64-1N-Y^ob8fP8;`sKH~A;qyu72W8Nw z5*1Z%y!j3D8`1EigQO^G$xU}V+`%^R<20;_G+6WeWP90YX;VpMQ55}cBA&R^n;%KE zmKTC6VS0oni?XS1WY^S~DEm+8XWZ_81S@?lH{#B02kZe=PGV<sYETvAeyA*qE_h#c zdN)f>!aRr(aUqPNRL(^1*1Fk<?U|iYzdE`yyAJ+VT^)VBO!CB|x@_5OcbuhavM7r7 zV#b;wY?>@+{lJ*JWHF;C%BH%J<2h!sY@6}g-y?08&JW5^F=VVL%Y4GQK|x2E<K2`c zEb!7<MJ=KIm$BX*)<Uj&w#oQ@QCm)B=}}rQX5^85(?rG>Jv3s#BWhi>uF{lEEktLd zyaDpYkVlqvU2Skut=$jG*cMd-_rnf;s2rBcC!M8eRynis?GT++v@3M>D+ff1Y;gwz z!T4C-Pj*VFFJ>=pi9SJ^EQ(4Es*P+I)d^bZ$oQq3JU_mvr9~B2e2q0(lua!}w&Bh8 za%|#Y@!ZD~S67oo*{MM_5L>ePVpV867x}E@Xy&)9hfW9egZ7cev-PsNv|1J=4mk!x zhbD`nXbu}<$PKH=53!!&#H3KH)3lD(lua$fI<enfHu_^b+0VX$jBtp;$^GV|w{!NI z9=-31zqcZeA7`pNaCX4ut*i0(R74Iu2AyHmXZgxKsF0>8Iz{Vj&QR1suEE?THK#h{ z^&@ucT}_!(&_q&M6jim^eB{>tfC#;s<DSy|A6ER(S8hzMiCTS47G+c2m`k=GhaC#c z7Zn|QN-B%88>B6Sj)h;W^03;%(p%fg8xOkcbWlI&+%2recmKf(d!7-;BKk-wOOMiK za2X7fALp>JBl)7_au3}EFv_MD8Vo<ZtjuFPZnD)0Z4gz{W-Lb;e-3y$w-er)CRB20 z6MeBO>fpmyFWSYL3~z#{fre7uzW;96AV8h=%yHTqkm6D!080&A-S0-%;N2HaVs#yZ za8j+wq9{7W7wg^N#{BT%ZOpMp3!HywvM8JC#$4o8Pf@2|PB!__2Jw<C^!;dxHPvA} z6%P>+R6UUY2*}BKnPs2rh5xI1&eJVg$nYDtMbsuoNl`S)eP^}-Z*A3q<^&iaypLRA zy+yQhED%%{MbR2eWVe;HmKCoSiTZoWV_&JsqHL-gQG@7b;z&w)=~KV8&JW69_P4TL zc{RjWZ6B<fH*A1(U$<R2oxh~Bidv##$XexOX^E?BwezYt+t?f3FEm*crLTirR_rP_ zrd$<kn|SLgCn=j+h!e%29<t^^M|r}7msL)l%^94Hl?3ud?Qli=<BHZocC<ArZTjJz zSPk#Q!S>^1h4Dwl{94X94W}r3WJLD`sy4oy6)~-#5B{zW#^TkZ<beG-Vw%}pc53;b zEQ(TjWMS!H*g>lLj|r}$q-pjAv3*_(#9lR7)Do&2Yq%Tj<o&PR<+X#0bbe6AqQU~4 zu?&I^<;T*XKC<}OE73T0xy~wTNxIudM39tE%Bu3G8^{g+HkY3&We6&ZqGmhYM7(_f zuA4m=UFNirx5_n=VKdetBCN@xY-%C)Y8UIvl<GdxJNXn&Gc;M09c3&*7E*Y&!C(g+ z$NavLZLN#NK9>}o4(bPTkg+Zag&*a?i1?<nT$y4cha_g<yjGJ%QTizNy}q60pfnqK zY)BT)wl!IlO)W%(J}g8gCKn0Q1dHz6fU;@C8*_frN6Wx-$s+w#qD}|(L!HFmnXOI% zD!`AM)uQE$24Ny2CPEiIrzm~Ay|mU?S@q3ck!&AbcB-$*(qiv=3)2Jbq$RnTJbBs% zZ&B?G;<eX5cz1=v5^FO(b-;eGoxMz1-%|S4F2>$KL(#iQuN!)cc(jp0zLn*%@pq7s zqMd(Gl>UBfO0FW4ANt5S2j1%LAZ1hC27}0`E$4o)<)s_zVC{1pvB|IT{5-<9{9YEa zHt=_TKxE`OL_FKUCw0c+`?Ry%bKx?Z7V`qpK@IiV>m^P}RTsH@pdKN=y#wCVFYx!Q zLvC_Qku#sN%oZy$DoaDD%=L71Vnd`BcTm)-E1yra=GDfzAnu}}D4Xg=#kylN`TK5r zUMah@EQel`rLk27cx0p*R;hEfZ}Pd^^YI=FmMU{tLs36k`Mrnd?28|V`h`pLrt8f5 z?Qe)WYqBUx{c7V2JL6iZGq01Ey36j(OPF{4qqtU@EXt<3@yqQ$PWnyT$F8m)%BU>L zR{yupHRDRFQ%j@wcQWY7S~jg@sZIy=BP{(B?q<ibJ8LlP-!fOqbFM5uAsiJWnk<T< zXRPoeWQ43U<yRJZeLbSink>qu7NXn2hMDq`bxY>i!4vxr?d+Gb3quW9@2b9>YR|c( z@i5smV-xdBv*>hCKXP(D;Jw=dj65**Oplhwx_GiN$L29Ai=wh$8SwS_8sFN#!N@r? zM_Pp&*sq^#8AVYxwa|bM`Uf`LWg}}htv9NjF5vusSy`U$%Iy0A<1+g~=1k-y-^bL@ z@%UTiy;kyb;&%u2M|YU6oT6yfEX_|v{;q9v?$v7pYl`mKR2D_)^IkvZyK&?1KQhnc zj+~+>o9f1S)Vo^zed;Av)ah%TAC!^qb}IncD)2+)*4|mpc+S!s=2%)mXBD-?KKCKk zj8pNpP$!DE(I&os%@Z~u{~1oOG+7k2E$UuCx?3D{OaY_5dpq8_!VQ+yrxJ4iHCdER zEkwSL-4b?WzzEs+k1WI)Y*Ck%jU11P0jr;+AVw;W8VqTsP0zkUE!jc*or2Zt>63Qs z@`7(=?_tjcMcs7wFx{P<j@5k+(}2YS$b(;Y6B`d~X1;zs<iN(ZnDwj4qA0rRM>U|` z0=5HvSk}JH6?&A$rn)h8VPrfzv%iCkd)q)aPnfdlG-B)xMqf8ph%?K#joc+gQ9tJK z3CNS#56=zo$Nu>e<6f8Y()v_?-CSgf($A^hz{|1Nryb<JgH0txQA?<9gJE2;KesR5 z@84j%59S#D7O*qfmK)Ai#-8IyKtkdsyuD4P$;LwgX&a?9`BjHi&Zm3vspHBS&-Sc= z-Gqj!7k@0E=@K`S$!`sOkO6_quFLt6kzo8jK7i-t1z3JFd!kQ~CX1q0W*^3mB{u8x z4pQDX^TPS={`PMgV^^ffqHL-gry0#_^V5HA=$Kchr_K+`IE%g|!$x)#pXXGsaca+f z0!LWdbobR+MJ=fp|7*bWUs%>>hW~`OEN|L;fA^)|Vh5?oqNuR+y#c4T#N#X{3)k*` zQC+@j&(Hq-zw0U~in6JN$Tl4D+PJJ}o-DfJY3aS9Ca#`!wyGJ69`h@HVb*wa_BWsE z-mmQMF_B^T4VJFUG8Wp!$T8;a7K(DPU56YzTdayln^Rn#q0++!k_Lj&yMLmw&J*;q zd^^}eWl>b`^iATGmtrU#1B3rE?phQh2jy2m_X|xHWmDY-!?me>EO+bU)G~LWh03Dr zgQpH*cd7cGheJo@Kf77xV={31*>yS{)Q^`RU6JpjGU$ea@zXgsksCHgPO{vwP+1g} z8SRHPwYqM7!T9mEzhz{@Sm_zO4D**YS(HsJ#7w%J<*a3Dn2cTcN$f~=3)mK=^4`46 zOGi9GWYYk-&CTO(KExBR>bX6kBRgg%i<yspOOFhaqU7dmlbRr?Y9EJ9mpC_2)qv{6 z<l?mcEGaNpnhnm9%AzP*Gmdl4jyu@Rv=DjI_(4z<WmDaFuH1iQL92($x9^YX{Gg0k z1=ayA{fbe+rA{qxuMcE$Kwp_w*+yp-wIm_sgsG+9i!Y4wnXirETc^r(s}ls3MNy$w zk0Va~6xXnp^1RDk<CRI@%5`I22#TU?Y9W3N9XE(`bNpo9dv}@r>VH|EYv(=8IXTy{ z!&djh$2{BVDORs9k8Vg(_v5}_zWD80J-O4*T~d_F@lp{%m7$)ywKB5R--Dq}-23$0 zE@XVL{He4&cH5dPit-v<=jh{5<%c>;JvsfZSUlWU-h1ze9*vqT%BH%JN0z!-^xoG= zo|x&N^Mf*qLetQXtOQo6)7K-{_KMNVhsf;Z7VIE3tEeTfy*_|ZgeOtuGqmm3TiBe& zu72KrL1pPtr?B5Cf*<PKdFtU-A`#uDHvD`EdmK#`WmDZa)n`>Rn>Md!DVL+4UrQ&& znuc|Tj+S^6^?{BR&zN|Yu*$#wO#L)kIyDxtB~;6{#Jy2(hL8<+EO~A3TP|Ff%c(4i zDhmA{e&-#sk$VNk%#2HxpAy<xTJ?+J6h+z8LUh@TpKOeMyU(&GB}O-gmon&tGwiMG zT*UH%^_DsP^;S_!W)_6N5C1QI1g}jujy+gtu{F)pO-rLFI@Jtop~X{-XI;`QZQ^23 zKd8x~mQV|k_Zqo_`5m>B?HhLGaaluEHv-(-XtVPb_4i%;Jsov-o$wwjEc+XktS-^a z?%Nz;+7ZDi%5K5b0Q=mFK+QD&`;Cf3=3`x=`T-1@hJAtQl<3}nH1e-BSroOq*cJQE zr+9W%z1p-P(d^p2<KkC`k({C^o9f2<>dJPO=jJ5OZRR>ZC?ot{XIS{G%s;Gm^ZeK^ zk>|yz1EX|SQA=$5dSC}o{Ka$k@0YMgPpZgPAG>lYi=r_13~N-?lSAc3)xR3go(^)6 zaW71qq9~hMh^O7bl@AbUnS-u&<8*E~on$t6<wATv8X}6*9Xf912l2lr#aU`P*V9c) zqZ8619M<B5S52!>=TQ!cCf=mlddq<oo;U^2WKooTZn8<umHB*v<uE#s@9oyXl6JZg zrzpy%7Gk$u)s^>Yk(TLuUGE2F=qHW4bn)jedN#Lw@77Fb6}4p3vqZ$IUGV!*e)Oy2 z!`n2v=U;WA5xXL7t~y20>FL-(o^Qr;PyUnfb8$!1fM~KPn_7r@kf(!0^NQnSr5nF7 zT9Z$!@PjK4%u07ttBep>)%3~_!V=Yyl{}iPtJSCd0O%ZMgQ0UHKQZ;;GRwWmb2ybn zQFJCV>b8#wQOCceL)BIKiO`fyEkw7ThqFb>%xN<5kfY8I%J8?Jfw-tzWvF-J><;_H z_ul`CcXN@YM?9pKAe-@v=e@yL6Y4D%c9<*EUp6#SSrnyTUzrD_TI&8jOJ2Cp3lSDg z7G+c22E$O)-3?zHBOlz~V5G7ro375#?X6&uv32QXamJ!1ziT?EAHG9pV`XUz&y^no zhgq``qoU>dqu(<si=yZn74NHZUgGh0v*dDXH%3vEO?6{8EE}=;s~Ypj0;a2jq|++q zJ72Lx8H4a#shYUKHrv>o)&^elN>52qwEr&c{fpkXuQJ*72rnL33-i^8EQ+FCi19u5 z|C?36<H9>XZ?5YjOxaYo!7%3SC^q^Je;(%CNaqJ-&}vX*Rjs?r3a^^@v8rzcMd>U- zGqTUU;#8fN?dV8Wcy0vWj~UN8Sp-FEd-1FN;K6Fw2;rmb9HoJvD4XiW*Pxb_yy<pV zOnPI)3g7@Do2q&-1o^u65fM}!NP>|&nvSn?c-h~G>08Y5+wI3izr=EQt~8YDUlEob zg1cr0;}KSw;bng#<9Abe`KrE){Pd(2r?M!D*-K<*4g|vl&$lggl)oasq>h^h7@91~ zrn+&0RZxj{%*gOx-m@>K6SM6WtU^C32YfTSnr}Bdgeswm@I&P@oDOTm|IDr7zu2ua zrzra7Y)~%^dy%SN7=>9ac=eDAmgW80a4L(URzEp~H?^9WuFlULPx<gh<8v(2n{?z9 zMcGt0;=6CZ;=UE%S`5Q532aq7>Y(hQy_?Q<{}2oEWXgT9YSnOeZoldWv2J5qomJG5 zuFbC?+wi~4fsUqfyyW6;!CQCbR2D_e5YMo0v%+;#evIo<i&r{eBW^eB&MAtrsZZFu z?JZ?-{XH}OI5R}&2W8L+<mfv%svJLI*ehJG2kWe&mgH|gjQyZBu5J*ldU@m_o4@an zSkXFEH_e=)^z+YKCKa#)B2#4b>BT9ET0$+v8*bZ9W>fd57?n6g*Y|@?Ed1%8<EHFa z*RkqT{a%+=dBLJL{UBUN_SH>Aq!YQ$?Y@S}ushffs!q4XwcfHr+pT5M($<{HqA16> z$~YswgwFM9l3AGjJ7)2;mQxd2bBdyDY9ZFUskQm#iK|4y2+rx`)+Np@(DP1J!Uvnr zZ0TcC)lQ#R8Q#&Jd`s3facFWqPEq~aha=jesy@x;E{DFuFG{_sRes5v3f+11gF#|v zK{ZZgQ55anh||{v&3VBuo5bXOO)%+ClSSE7H@*fl8*}Fky~RZ4uk(X4=mc4;EJt_a zkID}hDLou@R#8i6zea=M*~m70QKL8!X!Jx!Qf;y=Md|xM_Ot22?Ju?!^ERk19$M!} z%BB|LEM#+C8PIJDTYtZuRGoSMoB2SeJg74-RZI4{pMIE&wX~_Yn=KsQT{jCt)&KlA z;YPg^wfQ)YLMzEjQxCFh_syt%)nri=t$jBb;-*>4^tU_N=5gIocc;msY-%CaqW9~_ zw=vt;u3y^g{Gbe#i&Ge?`irW5OUDhL#9n@hO|H;MXBD-C)`{aS8t*M@`JQD(6&oOu zs>z}#ef@ct;wG|z=^Sg<tAV5_%BB`#uhyf7+`VHHtJ}*~=LcmJhE_Q0l&ZSpbNG?y z+(%wm_B%VU|1!>NHLIv4Y63_0D|7beE@`zf$E)qhHLUhsTg)EQWKopLrYa0o^VI^N z<KDe6X+L2#yOR7)P!wfT-3G&fNmJzOTknl~3O;vF`cD>R`}uu^Tm#h)K>1<*G+KIY zna?b)sX86h58B5KQJkYO(q(mD|Ei}?TBt0FqCMSk&o@q%eTxRL6;l@oilS_4Au6iU zr^@T$FN}>N63Y7f{O1Q{sEn<oBvaX&2xn3iV`S0UJpaJJH#)2ImN?+lQg!lGSJzZC zR)+TG7N2=5EqYlRO8sB;#{K*qbiX`Lns;5u?Ayi~C+>RGf0j@SQLlF4y2W8Z41e#r zGlO;}pj`uUa^_;)rTQAEc;dmr6_yo^rt$`X8&C(Sbw8k85oqreL?E3q{Syje`MSiO g{!|u4(Jn67pSSLB>GxeM4{&R0q$tX!x($Z^2O7-=>Hq)$ literal 0 HcmV?d00001 diff --git a/collision_space_fcl_test/test/test_collision_space_fcl.cpp b/collision_space_fcl_test/test/test_collision_space_fcl.cpp new file mode 100644 index 00000000..95165cef --- /dev/null +++ b/collision_space_fcl_test/test/test_collision_space_fcl.cpp @@ -0,0 +1,758 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/** \author E. Gil Jones */ + +#include <planning_models/kinematic_model.h> +#include <planning_models/kinematic_state.h> +#include <gtest/gtest.h> +#include <sstream> +#include <ctype.h> +#include <ros/package.h> + +#include <collision_space/environmentODE.h> +#include <collision_space_fcl/environmentFCL.h> + +#include <tf/transform_datatypes.h> +#include <arm_navigation_msgs/RobotState.h> + +#include <geometric_shapes/shape_operations.h> + +#define NUM_MESH_OBJECTS 10 +#define NUM_RANDOM_OBJECTS 100 +#define NUM_TEST_CONFIGURATIONS 1000 + +//urdf location relative to the planning_models path +static const std::string rel_path = "/test_urdf/robot.xml"; + +inline double gen_rand(double min, double max) +{ + int rand_num = rand()%100+1; + double result = min + (double)((max-min)*rand_num)/101.0; + return result; +} + +inline geometry_msgs::Quaternion generateRandomUnitQuaternion() { + + geometry_msgs::Quaternion quat; + quat.x = gen_rand(-1.0, 1.0); + quat.w = gen_rand(-1.0, 1.0); + quat.z = gen_rand(-1.0, 1.0); + quat.w = gen_rand(-1.0, 1.0); + + double mag = sqrt(pow(quat.x, 2.0)+pow(quat.y, 2.0)+pow(quat.z, 2.0)+pow(quat.w, 2.0)); + + quat.x /= mag; + quat.y /= mag; + quat.z /= mag; + quat.w /= mag; + + return quat; +} + +inline std::string getNumberedString(const std::string &object, unsigned int num) +{ + std::stringstream my_string; + my_string << object << num; + return my_string.str(); +} + +class TestCollisionSpaceFCL : public testing::Test { +public: + + void spinThread() { + lock_.lock(); + coll_space_->isCollision(); + lock_.unlock(); + } + +protected: + + virtual void SetUp() { + + full_path_ = ros::package::getPath("planning_models")+rel_path; + + urdf_ok_ = urdf_model_.initFile(full_path_); + + std::vector<planning_models::KinematicModel::MultiDofConfig> multi_dof_configs; + //now this should work with an identity transform + planning_models::KinematicModel::MultiDofConfig config("base_joint"); + config.type = "Planar"; + config.parent_frame_id = "base_footprint"; + config.child_frame_id = "base_footprint"; + multi_dof_configs.push_back(config); + + std::vector<planning_models::KinematicModel::GroupConfig> gcs; + planning_models::KinematicModel::GroupConfig left_arm("left_arm", + "torso_lift_link", + "l_wrist_roll_link"); + + planning_models::KinematicModel::GroupConfig right_arm("right_arm", + "torso_lift_link", + "r_wrist_roll_link"); + gcs.push_back(left_arm); + gcs.push_back(right_arm); + kinematic_model_ = new planning_models::KinematicModel(urdf_model_, + gcs, + multi_dof_configs); + coll_space_ode_ = new collision_space::EnvironmentModelODE(); + coll_space_ = new collision_space_fcl::EnvironmentModelFCL(); + + workspace_x_extents_ = 1.0; + workspace_y_extents_ = 1.0; + workspace_z_extents_ = 1.0; + ros::Time::init(); + }; + + virtual void TearDown() { + delete kinematic_model_; + // delete coll_space_; + // delete coll_space_ode_; + } + + void getJointBoundsMap(const std::string &group, std::map<std::string, std::pair<double, double> > &joint_bounds_map) + { + const planning_models::KinematicModel::JointModelGroup* joint_model_group = kinematic_model_->getModelGroup(group); + if(joint_model_group == NULL) { + ROS_WARN_STREAM("No joint group " << group); + return; + } + + for(unsigned int i = 0; i < joint_model_group->getJointModels().size(); i++) { + const planning_models::KinematicModel::JointModel* jm = joint_model_group->getJointModels()[i]; + std::pair<double, double> bounds; + jm->getVariableBounds(jm->getName(), bounds); + joint_bounds_map[jm->getName()] = bounds; + } + } + + void setupForRandomConfigurations() + { + srand(time(NULL)); + std::vector<std::string> links; + kinematic_model_->getLinkModelNames(links); + std::map<std::string, double> link_padding_map; + + collision_space_fcl::EnvironmentModel::AllowedCollisionMatrix acm(links, false); + collision_space::EnvironmentModel::AllowedCollisionMatrix acm_ode(links, false); + + coll_space_->setRobotModel(kinematic_model_, acm, link_padding_map); + coll_space_ode_->setRobotModel(kinematic_model_, acm_ode, link_padding_map); + + { + //indented cause the state needs to cease to exist before we add the attached body + planning_models::KinematicState state(kinematic_model_); + state.setKinematicStateToDefault(); + + coll_space_->updateRobotModel(&state); + coll_space_ode_->updateRobotModel(&state); + } + + ASSERT_FALSE(coll_space_->isEnvironmentCollision()); + ASSERT_FALSE(coll_space_ode_->isEnvironmentCollision()); + } + + void testForRandomConfigurations() + { + getJointBoundsMap("right_arm",joint_bounds_map_right_); + getJointBoundsMap("left_arm",joint_bounds_map_left_); + + std::vector<arm_navigation_msgs::RobotState> robot_states_right; + std::vector<arm_navigation_msgs::RobotState> robot_states_left; + // Now generate random robot states and test them for collisions + for(unsigned int i=0; i < NUM_TEST_CONFIGURATIONS; i++) + { + arm_navigation_msgs::RobotState robot_state_right = generateRandomRobotStateWithinLimits(joint_bounds_map_right_); + arm_navigation_msgs::RobotState robot_state_left = generateRandomRobotStateWithinLimits(joint_bounds_map_left_); + robot_states_right.push_back(robot_state_right); + robot_states_left.push_back(robot_state_left); + } + + std::vector<bool> is_collision, is_collision_ode; + is_collision.resize(robot_states_right.size()); + is_collision_ode.resize(robot_states_right.size()); + + { + //indented cause the state needs to cease to exist before we add the attached body + planning_models::KinematicState state(kinematic_model_); + state.setKinematicStateToDefault(); + planning_models::KinematicState::JointStateGroup *right_state = state.getJointStateGroup("right_arm"); + planning_models::KinematicState::JointStateGroup *left_state = state.getJointStateGroup("left_arm"); + + ros::Time start_time = ros::Time::now(); + for(unsigned int i=0; i < robot_states_right.size(); i++) + { + right_state->setKinematicState(robot_states_right[i].joint_state.position); + left_state->setKinematicState(robot_states_left[i].joint_state.position); + coll_space_->updateRobotModel(&state); + is_collision[i] = coll_space_->isEnvironmentCollision(); + } + ros::Duration duration = ros::Time::now()-start_time; + ROS_INFO("FCL: Collision time: %f",duration.toSec()); + + start_time = ros::Time::now(); + for(unsigned int i=0; i < robot_states_right.size(); i++) + { + right_state->setKinematicState(robot_states_right[i].joint_state.position); + left_state->setKinematicState(robot_states_left[i].joint_state.position); + coll_space_ode_->updateRobotModel(&state); + is_collision_ode[i] = coll_space_ode_->isEnvironmentCollision(); + } + duration = ros::Time::now()-start_time; + ROS_INFO("ODE: Collision time: %f",duration.toSec()); + + unsigned int counter = 0; + for(unsigned int i=0; i < robot_states_right.size(); i++) + if(is_collision_ode[i] != is_collision[i]) + counter++; + ROS_DEBUG("%d mismatches between ODE and FCL result (out of %d)",(int) counter,(int) robot_states_right.size()); + + ASSERT_TRUE(counter == 0); + } + } + + arm_navigation_msgs::RobotState generateRandomRobotStateWithinLimits(std::map<std::string, std::pair<double, double> > &joint_bounds_map) + { + arm_navigation_msgs::RobotState rs; + rs.joint_state.header.frame_id = "torso_lift_link"; + rs.joint_state.header.stamp = ros::Time::now(); + + for(std::map<std::string,std::pair<double, double> >::iterator it = joint_bounds_map.begin(); + it != joint_bounds_map.end(); + it++) { + rs.joint_state.name.push_back(it->first); + rs.joint_state.position.push_back(gen_rand(it->second.first, it->second.second)); + } + return rs; + } + + geometry_msgs::Pose generateRandomPoseInWorkspace() { + + geometry_msgs::Pose rp; + rp.position.x = gen_rand(-workspace_x_extents_, workspace_x_extents_); + rp.position.y = gen_rand(-workspace_y_extents_, workspace_y_extents_); + rp.position.z = gen_rand(-workspace_z_extents_, workspace_z_extents_); + + rp.orientation = generateRandomUnitQuaternion(); + + return rp; + + } + + +protected: + + boost::mutex lock_; + urdf::Model urdf_model_; + bool urdf_ok_; + std::string full_path_; + collision_space::EnvironmentModelODE* coll_space_ode_; + collision_space_fcl::EnvironmentModelFCL* coll_space_; + planning_models::KinematicModel* kinematic_model_; + std::map<std::string, std::pair<double, double> > joint_bounds_map_right_, joint_bounds_map_left_; + double workspace_x_extents_, workspace_y_extents_, workspace_z_extents_; +}; + + + +TEST_F(TestCollisionSpaceFCL, TestInit) { + std::vector<std::string> links; + kinematic_model_->getLinkModelNames(links); + std::map<std::string, double> link_padding_map; + + { + collision_space_fcl::EnvironmentModel::AllowedCollisionMatrix acm(links,true); + coll_space_->setRobotModel(kinematic_model_, acm, link_padding_map); + //all AllowedCollisions set to true, so no collision + ASSERT_FALSE(coll_space_->isCollision()); + } + + { + collision_space_fcl::EnvironmentModel::AllowedCollisionMatrix acm(links,false); + + coll_space_->setRobotModel(kinematic_model_, acm, link_padding_map); + + //now we are in collision with nothing disabled + ASSERT_TRUE(coll_space_->isCollision()); + } + + //one more time for good measure + { + collision_space_fcl::EnvironmentModel::AllowedCollisionMatrix acm(links,false); + + coll_space_->setRobotModel(kinematic_model_, acm, link_padding_map); + + //now we are in collision with nothing disabled + ASSERT_TRUE(coll_space_->isCollision()); + } +} + + +TEST_F(TestCollisionSpaceFCL, TestACM) { + std::vector<std::string> links; + kinematic_model_->getLinkModelNames(links); + std::map<std::string, double> link_padding_map; + + //first we get + { + collision_space_fcl::EnvironmentModel::AllowedCollisionMatrix acm(links, false); + coll_space_->setRobotModel(kinematic_model_, acm, link_padding_map); + + planning_models::KinematicState state(kinematic_model_); + state.setKinematicStateToDefault(); + coll_space_->updateRobotModel(&state); + + //at default state in collision + ASSERT_TRUE(coll_space_->isCollision()); + + //now we get the full set of collisions in the default state + std::vector<collision_space_fcl::EnvironmentModel::AllowedContact> ac; + std::vector<collision_space_fcl::EnvironmentModel::Contact> contacts; + + coll_space_->getAllCollisionContacts(ac, contacts, 1); + + ASSERT_TRUE(contacts.size() > 1); + //now we change all these pairwise to true + for(unsigned int i = 0; i < contacts.size(); i++) { + ASSERT_TRUE(contacts[i].body_type_1 == collision_space_fcl::EnvironmentModel::LINK); + ASSERT_TRUE(contacts[i].body_type_2 == collision_space_fcl::EnvironmentModel::LINK); + ASSERT_TRUE(acm.changeEntry(contacts[i].body_name_1,contacts[i].body_name_2, true)); + } + + coll_space_->setAlteredCollisionMatrix(acm); + + //with all of these disabled, no more collisions + ASSERT_FALSE(coll_space_->isCollision()); + + coll_space_->revertAlteredCollisionMatrix(); + ASSERT_TRUE(coll_space_->isCollision()); + } +} + +TEST_F(TestCollisionSpaceFCL, TestAttachedObjects) +{ + std::vector<std::string> links; + kinematic_model_->getLinkModelNames(links); + std::map<std::string, double> link_padding_map; + + collision_space_fcl::EnvironmentModel::AllowedCollisionMatrix acm(links, false); + coll_space_->setRobotModel(kinematic_model_, acm, link_padding_map); + + { + //indented cause the state needs to cease to exist before we add the attached body + planning_models::KinematicState state(kinematic_model_); + state.setKinematicStateToDefault(); + + coll_space_->updateRobotModel(&state); + + //now we get the full set of collisions in the default state + std::vector<collision_space_fcl::EnvironmentModel::AllowedContact> ac; + std::vector<collision_space_fcl::EnvironmentModel::Contact> contacts; + + coll_space_->getAllCollisionContacts(ac, contacts, 1); + + //now we change all these pairwise to true + for(unsigned int i = 0; i < contacts.size(); i++) { + ASSERT_TRUE(contacts[i].body_type_1 == collision_space_fcl::EnvironmentModel::LINK); + ASSERT_TRUE(contacts[i].body_type_2 == collision_space_fcl::EnvironmentModel::LINK); + ASSERT_TRUE(acm.changeEntry(contacts[i].body_name_1,contacts[i].body_name_2, true)); + } + + coll_space_->setRobotModel(kinematic_model_, acm, link_padding_map); + coll_space_->updateRobotModel(&state); + } + + //now we shouldn't be in collision + ASSERT_FALSE(coll_space_->isCollision()); + + const planning_models::KinematicModel::LinkModel *link = kinematic_model_->getLinkModel("base_link"); + + //first a single box + shapes::Sphere* sphere1 = new shapes::Sphere(); + sphere1->radius = .1; + + shapes::Box* box2 = new shapes::Box(); + box2->size[0] = .05; + box2->size[1] = .05; + box2->size[2] = .05; + + std::vector<shapes::Shape*> shape_vector; + shape_vector.push_back(sphere1); + + btTransform pose; + pose.setIdentity(); + + std::vector<btTransform> poses; + poses.push_back(pose); + + std::vector<std::string> touch_links; + + planning_models::KinematicModel::AttachedBodyModel* ab1 = + new planning_models::KinematicModel::AttachedBodyModel(link, "box_1", + poses, + touch_links, + shape_vector); + + kinematic_model_->addAttachedBodyModel(link->getName(), ab1); + coll_space_->updateAttachedBodies(); + + const collision_space_fcl::EnvironmentModel::AllowedCollisionMatrix& aft_attached + = coll_space_->getDefaultAllowedCollisionMatrix(); + + ASSERT_TRUE(aft_attached.hasEntry("box_1")); + bool allowed; + EXPECT_TRUE(aft_attached.getAllowedCollision("box_1", link->getName(), allowed)); + EXPECT_FALSE(allowed); + + { + //indented cause the state needs to cease to exist before we add the attached body + planning_models::KinematicState state(kinematic_model_); + state.setKinematicStateToDefault(); + + coll_space_->updateRobotModel(&state); + } + + //now it collides + ASSERT_TRUE(coll_space_->isCollision()); + + kinematic_model_->clearLinkAttachedBodyModel(link->getName(), "box_1"); + coll_space_->updateAttachedBodies(); + + ASSERT_FALSE(aft_attached.hasEntry("box_1")); + + //now adding an attached object with two boxes, this time with two objects + shape_vector.clear(); + shape_vector.push_back(box2); + pose.getOrigin().setX(.1); + poses.clear(); + poses.push_back(pose); + touch_links.push_back("r_gripper_palm_link"); + touch_links.push_back("r_gripper_r_finger_link"); + touch_links.push_back("r_gripper_l_finger_link"); + touch_links.push_back("r_gripper_r_finger_tip_link"); + touch_links.push_back("r_gripper_l_finger_tip_link"); + touch_links.push_back("base_link"); + + planning_models::KinematicModel::AttachedBodyModel* ab2 = + new planning_models::KinematicModel::AttachedBodyModel(link, "box_2", + poses, + touch_links, + shape_vector); + kinematic_model_->addAttachedBodyModel(link->getName(), ab2); + coll_space_->updateAttachedBodies(); + + ASSERT_TRUE(aft_attached.hasEntry("box_2")); + EXPECT_TRUE(aft_attached.getAllowedCollision("box_2", link->getName(), allowed)); + EXPECT_TRUE(allowed); + + { + //indented cause the state needs to cease to exist before we add the attached body + planning_models::KinematicState state(kinematic_model_); + state.setKinematicStateToDefault(); + + coll_space_->updateRobotModel(&state); + } + + //now it doesn't collide + ASSERT_FALSE(coll_space_->isCollision()); +} + +TEST_F(TestCollisionSpaceFCL, TestStaticObjects) +{ + std::vector<std::string> links; + kinematic_model_->getLinkModelNames(links); + std::map<std::string, double> link_padding_map; + + collision_space_fcl::EnvironmentModel::AllowedCollisionMatrix acm(links, false); + coll_space_->setRobotModel(kinematic_model_, acm, link_padding_map); + + { + //indented cause the state needs to cease to exist before we add the attached body + planning_models::KinematicState state(kinematic_model_); + state.setKinematicStateToDefault(); + + coll_space_->updateRobotModel(&state); + } + + ASSERT_FALSE(coll_space_->isEnvironmentCollision()); + + shapes::Sphere* sphere1 = new shapes::Sphere(); + sphere1->radius = .2; + + btTransform pose; + pose.setIdentity(); + + std::vector<btTransform> poses; + poses.push_back(pose); + + std::vector<shapes::Shape*> shape_vector; + shape_vector.push_back(sphere1); + + coll_space_->addObjects("obj1", shape_vector, poses); + + + ASSERT_TRUE(coll_space_->isEnvironmentCollision()); + + + + //Now test interactions between static and attached objects + + const planning_models::KinematicModel::LinkModel *link = kinematic_model_->getLinkModel("base_link"); + + shapes::Box* att_box = new shapes::Box(); + att_box->size[0] = .05; + att_box->size[1] = .05; + att_box->size[2] = .05; + + std::vector<shapes::Shape*> att_shapes; + att_shapes.push_back(att_box); + + btTransform att_pose; + att_pose.setIdentity(); + + std::vector<btTransform> att_poses; + att_poses.push_back(att_pose); + + std::vector<std::string> touch_links; + touch_links.push_back("base_link"); + touch_links.push_back("base_footprint"); + + planning_models::KinematicModel::AttachedBodyModel* ab1 = + new planning_models::KinematicModel::AttachedBodyModel(link, "att1", + att_poses, + touch_links, + att_shapes); + + kinematic_model_->addAttachedBodyModel(link->getName(), ab1); + coll_space_->updateAttachedBodies(); + + { + //indented cause the state needs to cease to exist before we add the attached body + planning_models::KinematicState state(kinematic_model_); + state.setKinematicStateToDefault(); + + coll_space_->updateRobotModel(&state); + } + + ASSERT_TRUE(coll_space_->isEnvironmentCollision()); + + //now we get the full set of collisions in the default state + std::vector<collision_space_fcl::EnvironmentModel::AllowedContact> ac; + std::vector<collision_space_fcl::EnvironmentModel::Contact> contacts; + + coll_space_->getAllCollisionContacts(ac, contacts, 1); + + //now we change all these pairwise to true + for(unsigned int i = 0; i < contacts.size(); i++) { + if(contacts[i].body_type_1 == collision_space_fcl::EnvironmentModel::OBJECT) { + ASSERT_TRUE(contacts[i].body_name_1 == "obj1"); + } + if(contacts[i].body_type_2 == collision_space_fcl::EnvironmentModel::OBJECT) { + ASSERT_TRUE(contacts[i].body_name_2 == "obj1"); + } + } + + acm = coll_space_->getDefaultAllowedCollisionMatrix(); + bool allowed; + ASSERT_TRUE(acm.getAllowedCollision("obj1","att1",allowed)); + EXPECT_FALSE(allowed); + + ASSERT_TRUE(acm.changeEntry(link->getName(), "obj1", true)); + ASSERT_TRUE(acm.changeEntry("base_footprint", "obj1", true)); + coll_space_->setAlteredCollisionMatrix(acm); + + { + //indented cause the state needs to cease to exist before we add the attached body + planning_models::KinematicState state(kinematic_model_); + state.setKinematicStateToDefault(); + + coll_space_->updateRobotModel(&state); + } + + /* Remove because sphere-box collision does not work for mesh */ + // EXPECT_TRUE(coll_space_->isEnvironmentCollision()); + + ASSERT_TRUE(acm.changeEntry("att1", "obj1", true)); + coll_space_->setAlteredCollisionMatrix(acm); + + allowed = false; + ASSERT_TRUE(coll_space_->getCurrentAllowedCollisionMatrix().getAllowedCollision("att1","obj1", allowed)); + EXPECT_TRUE(allowed); + + ASSERT_TRUE(coll_space_->getCurrentAllowedCollisionMatrix().getAllowedCollision("obj1","att1", allowed)); + EXPECT_TRUE(allowed); + + ASSERT_TRUE(coll_space_->getCurrentAllowedCollisionMatrix().getAllowedCollision("base_link","obj1", allowed)); + EXPECT_TRUE(allowed); + + ASSERT_TRUE(coll_space_->getCurrentAllowedCollisionMatrix().getAllowedCollision("obj1","base_link", allowed)); + EXPECT_TRUE(allowed); + + ASSERT_TRUE(coll_space_->getCurrentAllowedCollisionMatrix().getAllowedCollision("obj1","base_footprint", allowed)); + EXPECT_TRUE(allowed); + + EXPECT_FALSE(coll_space_->isEnvironmentCollision()); + contacts.clear(); + + coll_space_->getAllCollisionContacts(ac, contacts, 1); + + //now we change all these pairwise to true + for(unsigned int i = 0; i < contacts.size(); i++) { + if(contacts[i].body_type_1 == collision_space_fcl::EnvironmentModel::OBJECT) { + ASSERT_TRUE(contacts[i].body_name_1 == "obj1"); + ROS_INFO_STREAM(contacts[i].body_name_2); + } + if(contacts[i].body_type_2 == collision_space_fcl::EnvironmentModel::OBJECT) { + ASSERT_TRUE(contacts[i].body_name_2 == "obj1"); + ROS_INFO_STREAM(contacts[i].body_name_1); + } + } +} + +TEST_F(TestCollisionSpaceFCL, TestODEvsFCLSphere) +{ + setupForRandomConfigurations(); + for(unsigned int i=0; i < NUM_RANDOM_OBJECTS; i++) + { + btTransform pose; + shapes::Sphere* sphere1 = new shapes::Sphere(); + sphere1->radius = .1; + + geometry_msgs::Pose pose_msg = generateRandomPoseInWorkspace(); + tf::poseMsgToTF(pose_msg,pose); + + std::vector<btTransform> poses; + poses.push_back(pose); + + std::vector<shapes::Shape*> shape_vector; + shape_vector.push_back(sphere1); + + std::string object_id = getNumberedString("obj",i); + + coll_space_->addObjects(object_id, shape_vector, poses); + coll_space_ode_->addObjects(object_id, shape_vector, poses); + } + testForRandomConfigurations(); +} + +TEST_F(TestCollisionSpaceFCL, TestODEvsFCLCylinder) +{ + setupForRandomConfigurations(); + for(unsigned int i=0; i < NUM_RANDOM_OBJECTS; i++) + { + btTransform pose; + shapes::Cylinder* c1 = new shapes::Cylinder(); + c1->radius = .1; + c1->length = 0.3; + + geometry_msgs::Pose pose_msg = generateRandomPoseInWorkspace(); + tf::poseMsgToTF(pose_msg,pose); + + std::vector<btTransform> poses; + poses.push_back(pose); + + std::vector<shapes::Shape*> shape_vector; + shape_vector.push_back(c1); + + std::string object_id = getNumberedString("obj",i); + + coll_space_->addObjects(object_id, shape_vector, poses); + coll_space_ode_->addObjects(object_id, shape_vector, poses); + } + testForRandomConfigurations(); +} + +TEST_F(TestCollisionSpaceFCL, TestODEvsFCLBox) +{ + setupForRandomConfigurations(); + for(unsigned int i=0; i < NUM_RANDOM_OBJECTS; i++) + { + btTransform pose; + shapes::Box* box = new shapes::Box(); + box->size[0] = 0.1; + box->size[1] = 0.2; + box->size[2] = 0.3; + + geometry_msgs::Pose pose_msg = generateRandomPoseInWorkspace(); + tf::poseMsgToTF(pose_msg,pose); + + std::vector<btTransform> poses; + poses.push_back(pose); + + std::vector<shapes::Shape*> shape_vector; + shape_vector.push_back(box); + + std::string object_id = getNumberedString("obj",i); + + coll_space_->addObjects(object_id, shape_vector, poses); + coll_space_ode_->addObjects(object_id, shape_vector, poses); + } + testForRandomConfigurations(); +} + +TEST_F(TestCollisionSpaceFCL, TestODEvsFCLMesh) +{ + setupForRandomConfigurations(); + std::string full_path = ros::package::getPath("collision_space_fcl_test")+"/objects/meshes/9300.stl"; + for(unsigned int i=0; i < NUM_MESH_OBJECTS; i++) + { + shapes::Mesh* mesh = shapes::createMeshFromBinaryStl(full_path.c_str()); + ASSERT_TRUE(mesh); + btTransform pose; + geometry_msgs::Pose pose_msg = generateRandomPoseInWorkspace(); + tf::poseMsgToTF(pose_msg,pose); + + std::vector<btTransform> poses; + poses.push_back(pose); + + std::vector<shapes::Shape*> shape_vector; + shape_vector.push_back(mesh); + + std::string object_id = getNumberedString("obj",i); + + coll_space_->addObjects(object_id, shape_vector, poses); + coll_space_ode_->addObjects(object_id, shape_vector, poses); + delete mesh; + } + testForRandomConfigurations(); + // coll_space_->clearObjects(); + // coll_space_ode_->clearObjects(); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} + diff --git a/fcl/src/BVH_utility.cpp b/fcl/src/BVH_utility.cpp index 7381001a..39bf9c47 100644 --- a/fcl/src/BVH_utility.cpp +++ b/fcl/src/BVH_utility.cpp @@ -36,7 +36,7 @@ #include "fcl/BVH_utility.h" -#include <ANN/ANN.h> +#include <ann/ANN.h> namespace fcl { diff --git a/fcl/test/test_core_broad_phase.cpp b/fcl/test/test_core_broad_phase.cpp new file mode 100644 index 00000000..64b585aa --- /dev/null +++ b/fcl/test/test_core_broad_phase.cpp @@ -0,0 +1,246 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** \author Jia Pan */ + + +#include "fcl/broad_phase_collision.h" +#include "fcl/geometric_shape_to_BVH_model.h" +#include "fcl/transform.h" +#include "test_core_utility.h" +#include <gtest/gtest.h> + +using namespace fcl; + + +void generateEnvironments(std::vector<CollisionObject*>& env, int n); + + +TEST(test_core, broad_phase_collision) +{ + bool exhaustive = false; + + std::vector<CollisionObject*> env; + generateEnvironments(env, 100); + + std::vector<CollisionObject*> query; + generateEnvironments(query, 10); + + BroadPhaseCollisionManager* manager1 = new NaiveCollisionManager(); + BroadPhaseCollisionManager* manager2 = new SSaPCollisionManager(); + BroadPhaseCollisionManager* manager3 = new SaPCollisionManager(); + BroadPhaseCollisionManager* manager4 = new IntervalTreeCollisionManager(); + + + for(unsigned int i = 0; i < env.size(); ++i) + { + manager1->registerObject(env[i]); + manager2->registerObject(env[i]); + manager3->registerObject(env[i]); + manager4->registerObject(env[i]); + } + + manager1->setup(); + manager2->setup(); + manager3->setup(); + manager4->setup(); + + CollisionData self_data1; + self_data1.exhaustive = exhaustive; + CollisionData self_data2; + self_data2.exhaustive = exhaustive; + CollisionData self_data3; + self_data3.exhaustive = exhaustive; + CollisionData self_data4; + self_data4.exhaustive = exhaustive; + + manager1->collide(&self_data1, defaultCollisionFunction); + manager2->collide(&self_data2, defaultCollisionFunction); + manager3->collide(&self_data3, defaultCollisionFunction); + manager3->collide(&self_data4, defaultCollisionFunction); + + bool self_res1 = (self_data1.contacts.size() > 0); + bool self_res2 = (self_data2.contacts.size() > 0); + bool self_res3 = (self_data3.contacts.size() > 0); + bool self_res4 = (self_data4.contacts.size() > 0); + + ASSERT_TRUE(self_res1 == self_res2); + ASSERT_TRUE(self_res1 == self_res3); + ASSERT_TRUE(self_res1 == self_res4); + + + for(unsigned int i = 0; i < query.size(); ++i) + { + CollisionData query_data1; + query_data1.exhaustive = exhaustive; + CollisionData query_data2; + query_data2.exhaustive = exhaustive; + CollisionData query_data3; + query_data3.exhaustive = exhaustive; + CollisionData query_data4; + query_data4.exhaustive = exhaustive; + + manager1->collide(query[i], &query_data1, defaultCollisionFunction); + manager2->collide(query[i], &query_data2, defaultCollisionFunction); + manager3->collide(query[i], &query_data3, defaultCollisionFunction); + manager4->collide(query[i], &query_data4, defaultCollisionFunction); + + bool query_res1 = (query_data1.contacts.size() > 0); + bool query_res2 = (query_data2.contacts.size() > 0); + bool query_res3 = (query_data3.contacts.size() > 0); + bool query_res4 = (query_data4.contacts.size() > 0); + + ASSERT_TRUE(query_res1 == query_res2); + ASSERT_TRUE(query_res1 == query_res3); + ASSERT_TRUE(query_res1 == query_res4); + } + + for(unsigned int i = 0; i < env.size(); ++i) + delete env[i]; + for(unsigned int i = 0; i < query.size(); ++i) + delete query[i]; + + delete manager1; + delete manager2; + delete manager3; + delete manager4; +} + + + +TEST(test_core, broad_phase_self_collision_exhaustive) +{ + bool exhaustive = true; + + std::vector<CollisionObject*> env; + generateEnvironments(env, 100); + + BroadPhaseCollisionManager* manager1 = new NaiveCollisionManager(); + BroadPhaseCollisionManager* manager2 = new SSaPCollisionManager(); + BroadPhaseCollisionManager* manager3 = new SaPCollisionManager(); + BroadPhaseCollisionManager* manager4 = new IntervalTreeCollisionManager(); + + + for(unsigned int i = 0; i < env.size(); ++i) + { + manager1->registerObject(env[i]); + manager2->registerObject(env[i]); + manager3->registerObject(env[i]); + manager4->registerObject(env[i]); + } + + manager1->setup(); + manager2->setup(); + manager3->setup(); + manager4->setup(); + + CollisionData self_data1; + self_data1.exhaustive = exhaustive; + CollisionData self_data2; + self_data2.exhaustive = exhaustive; + CollisionData self_data3; + self_data3.exhaustive = exhaustive; + CollisionData self_data4; + self_data4.exhaustive = exhaustive; + + manager1->collide(&self_data1, defaultCollisionFunction); + manager2->collide(&self_data2, defaultCollisionFunction); + manager3->collide(&self_data3, defaultCollisionFunction); + manager3->collide(&self_data4, defaultCollisionFunction); + + unsigned int self_res1 = self_data1.contacts.size(); + unsigned int self_res2 = self_data2.contacts.size(); + unsigned int self_res3 = self_data3.contacts.size(); + unsigned int self_res4 = self_data4.contacts.size(); + + ASSERT_TRUE(self_res1 == self_res2); + ASSERT_TRUE(self_res1 == self_res3); + ASSERT_TRUE(self_res1 == self_res4); + + + for(unsigned int i = 0; i < env.size(); ++i) + delete env[i]; + + delete manager1; + delete manager2; + delete manager3; + delete manager4; +} + + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} + + +void generateEnvironments(std::vector<CollisionObject*>& env, int n) +{ + BVH_REAL extents[] = {-200, 200, -200, 200, -200, 200}; + BVH_REAL delta_trans[] = {1, 1, 1}; + std::vector<Transform> transforms; + std::vector<Transform> transforms2; + + + generateRandomTransform(extents, transforms, transforms2, delta_trans, 0.005 * 2 * 3.1415, n); + Box box(5, 10, 20); + for(int i = 0; i < n; ++i) + { + BVHModel<OBB>* model = new BVHModel<OBB>(); + box.setLocalTransform(transforms[i].R, transforms[i].T); + generateBVHModel(*model, box); + env.push_back(model); + } + + generateRandomTransform(extents, transforms, transforms2, delta_trans, 0.005 * 2 * 3.1415, n); + Sphere sphere(30); + for(int i = 0; i < n; ++i) + { + BVHModel<OBB>* model = new BVHModel<OBB>(); + sphere.setLocalTransform(transforms[i].R, transforms[i].T); + generateBVHModel(*model, sphere); + env.push_back(model); + } + + generateRandomTransform(extents, transforms, transforms2, delta_trans, 0.005 * 2 * 3.1415, n); + Cylinder cylinder(10, 40); + for(int i = 0; i < n; ++i) + { + BVHModel<OBB>* model = new BVHModel<OBB>(); + cylinder.setLocalTransform(transforms[i].R, transforms[i].T); + generateBVHModel(*model, cylinder); + env.push_back(model); + } +} diff --git a/fcl/test/test_core_collision_point.cpp b/fcl/test/test_core_collision_point.cpp new file mode 100644 index 00000000..fe0a988f --- /dev/null +++ b/fcl/test/test_core_collision_point.cpp @@ -0,0 +1,540 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** \author Jia Pan */ + + +#if USE_SVMLIGHT + +#include "fcl/traversal_node_bvhs.h" +#include "fcl/collision_node.h" +#include "fcl/simple_setup.h" +#include "test_core_utility.h" + +#if USE_PQP +#include <PQP.h> +#endif + +using namespace fcl; + +template<typename BV> +bool collide_Test_PP(const Transform& tf, + const std::vector<Vec3f>& vertices1, const std::vector<Vec3f>& vertices2, SplitMethodType split_method, bool verbose = true); + +template<typename BV> +bool collide_Test_MP(const Transform& tf, + const std::vector<Vec3f>& vertices1, const std::vector<Triangle>& triangles1, + const std::vector<Vec3f>& vertices2, SplitMethodType split_method, bool verbose = true); +template<typename BV> +bool collide_Test_PM(const Transform& tf, + const std::vector<Vec3f>& vertices1, + const std::vector<Vec3f>& vertices2, const std::vector<Triangle>& triangles2, SplitMethodType split_method, bool verbose = true); + +bool collide_Test_PP_OBB(const Transform& tf, + const std::vector<Vec3f>& vertices1, const std::vector<Vec3f>& vertices2, SplitMethodType split_method, bool verbose = true); + +bool collide_Test_MP_OBB(const Transform& tf, + const std::vector<Vec3f>& vertices1, const std::vector<Triangle>& triangles1, + const std::vector<Vec3f>& vertices2, SplitMethodType split_method, bool verbose = true); + +bool collide_Test_PM_OBB(const Transform& tf, + const std::vector<Vec3f>& vertices1, + const std::vector<Vec3f>& vertices2, const std::vector<Triangle>& triangles2, SplitMethodType split_method, bool verbose = true); + +int num_max_contacts = 1; + +int main() +{ + std::vector<Vec3f> p1, p2; + std::vector<Triangle> t1, t2; + loadOBJFile("env.obj", p1, t1); + loadOBJFile("rob.obj", p2, t2); + + std::vector<Transform> transforms; // t0 + std::vector<Transform> transforms2; // t1 + std::vector<Transform> transforms_ccd; // t0 + std::vector<Transform> transforms_ccd2; // t1 + BVH_REAL extents[] = {-3000, -3000, 0, 3000, 3000, 3000}; + BVH_REAL delta_trans[] = {1, 1, 1}; + int n = 10; + + generateRandomTransform(extents, transforms, transforms2, delta_trans, 0.005 * 2 * 3.1415, n); + + for(unsigned int i = 0; i < transforms.size(); ++i) + { + std::cout << "test id " << i << std::endl; + + std::vector<std::pair<int, int> > PQP_pairs; + DistanceRes PQP_dist; + +#if USE_PQP + collide_PQP(transforms[i], p1, t1, p2, t2, PQP_pairs); + + distance_PQP(transforms[i], p1, t1, p2, t2, PQP_dist); +#endif + + collide_Test_PP<OBB>(transforms[i], p1, p2, SPLIT_METHOD_MEAN); + + collide_Test_PP<OBB>(transforms[i], p1, p2, SPLIT_METHOD_BV_CENTER); + + collide_Test_PP<OBB>(transforms[i], p1, p2, SPLIT_METHOD_MEDIAN); + + collide_Test_PM<OBB>(transforms[i], p1, p2, t2, SPLIT_METHOD_MEAN); + + collide_Test_PM<OBB>(transforms[i], p1, p2, t2, SPLIT_METHOD_BV_CENTER); + + collide_Test_PM<OBB>(transforms[i], p1, p2, t2, SPLIT_METHOD_MEDIAN); + + collide_Test_MP<OBB>(transforms[i], p1, t1, p2, SPLIT_METHOD_MEAN); + + collide_Test_MP<OBB>(transforms[i], p1, t1, p2, SPLIT_METHOD_BV_CENTER); + + collide_Test_MP<OBB>(transforms[i], p1, t1, p2, SPLIT_METHOD_MEDIAN); + + collide_Test_PP_OBB(transforms[i], p1, p2, SPLIT_METHOD_MEAN); + + collide_Test_PP_OBB(transforms[i], p1, p2, SPLIT_METHOD_BV_CENTER); + + collide_Test_PP_OBB(transforms[i], p1, p2, SPLIT_METHOD_MEDIAN); + + collide_Test_PM_OBB(transforms[i], p1, p2, t2, SPLIT_METHOD_MEAN); + + collide_Test_PM_OBB(transforms[i], p1, p2, t2, SPLIT_METHOD_BV_CENTER); + + collide_Test_PM_OBB(transforms[i], p1, p2, t2, SPLIT_METHOD_MEDIAN); + + collide_Test_MP_OBB(transforms[i], p1, t1, p2, SPLIT_METHOD_MEAN); + + collide_Test_MP_OBB(transforms[i], p1, t1, p2, SPLIT_METHOD_BV_CENTER); + + collide_Test_MP_OBB(transforms[i], p1, t1, p2, SPLIT_METHOD_MEDIAN); + + std::cout << std::endl; + } +} + +template<typename BV> +bool collide_Test_PP(const Transform& tf, + const std::vector<Vec3f>& vertices1, const std::vector<Vec3f>& vertices2, SplitMethodType split_method, bool verbose) +{ + BVHModel<BV> m1; + BVHModel<BV> m2; + m1.bv_splitter.reset(new BVSplitter<BV>(split_method)); + m2.bv_splitter.reset(new BVSplitter<BV>(split_method)); + + m1.beginModel(); + m1.addSubModel(vertices1); + m1.endModel(); + + m2.beginModel(); + m2.addSubModel(vertices2); + m2.endModel(); + + Vec3f R2[3]; + R2[0] = Vec3f(1, 0, 0); + R2[1] = Vec3f(0, 1, 0); + R2[2] = Vec3f(0, 0, 1); + Vec3f T2; + + PointCloudCollisionTraversalNode<BV> node; + + if(!initialize<BV, false, false>(node, m1, m2, tf.R, tf.T, R2, T2, 0.6, 20)) + std::cout << "initialize error" << std::endl; + + node.enable_statistics = verbose; + node.num_max_contacts = num_max_contacts; + + collide(&node); + + if(node.pairs.size() > 0) + { + if(verbose) + { + std::cout << "in collision " << node.pairs.size() << ": " << std::endl; + + std::vector<BVHPointCollisionPair> pairs(node.pairs.size()); + for(unsigned i = 0; i < node.pairs.size(); ++i) + pairs[i] = node.pairs[i]; + + std::sort(pairs.begin(), pairs.end(), BVHPointCollisionPairComp()); + + for(unsigned i = 0; i < pairs.size(); ++i) + { + std::cout << "(" << pairs[i].id1_start << "(" << pairs[i].id1_num << ")" << " " << pairs[i].id2_start << "(" << pairs[i].id2_num << ")" << " " << pairs[i].collision_prob << ") "; + } + std::cout << std::endl; + } + if(verbose) std::cout << node.num_bv_tests << " " << node.num_leaf_tests << std::endl; + return true; + } + else + { + if(verbose) std::cout << "collision free " << std::endl; + if(verbose) std::cout << node.max_collision_prob << std::endl; + if(verbose) std::cout << node.num_bv_tests << " " << node.num_leaf_tests << std::endl; + return false; + } +} + +bool collide_Test_PP_OBB(const Transform& tf, + const std::vector<Vec3f>& vertices1, const std::vector<Vec3f>& vertices2, SplitMethodType split_method, bool verbose) +{ + BVHModel<OBB> m1; + BVHModel<OBB> m2; + m1.bv_splitter.reset(new BVSplitter<OBB>(split_method)); + m2.bv_splitter.reset(new BVSplitter<OBB>(split_method)); + + m1.beginModel(); + m1.addSubModel(vertices1); + m1.endModel(); + + m2.beginModel(); + m2.addSubModel(vertices2); + m2.endModel(); + + Vec3f R2[3]; + R2[0] = Vec3f(1, 0, 0); + R2[1] = Vec3f(0, 1, 0); + R2[2] = Vec3f(0, 0, 1); + Vec3f T2; + + PointCloudCollisionTraversalNodeOBB node; + + if(!initialize(node, m1, m2, tf.R, tf.T, R2, T2, 0.6, 20)) + std::cout << "initialize error" << std::endl; + + node.enable_statistics = verbose; + node.num_max_contacts = num_max_contacts; + + collide(&node); + + if(node.pairs.size() > 0) + { + if(verbose) + { + std::cout << "in collision " << node.pairs.size() << ": " << std::endl; + + std::vector<BVHPointCollisionPair> pairs(node.pairs.size()); + for(unsigned i = 0; i < node.pairs.size(); ++i) + pairs[i] = node.pairs[i]; + + std::sort(pairs.begin(), pairs.end(), BVHPointCollisionPairComp()); + + for(unsigned i = 0; i < pairs.size(); ++i) + { + std::cout << "(" << pairs[i].id1_start << "(" << pairs[i].id1_num << ")" << " " << pairs[i].id2_start << "(" << pairs[i].id2_num << ")" << " " << pairs[i].collision_prob << ") "; + } + std::cout << std::endl; + } + if(verbose) std::cout << node.num_bv_tests << " " << node.num_leaf_tests << std::endl; + return true; + } + else + { + if(verbose) std::cout << "collision free " << std::endl; + if(verbose) std::cout << node.max_collision_prob << std::endl; + if(verbose) std::cout << node.num_bv_tests << " " << node.num_leaf_tests << std::endl; + return false; + } +} + + + +template<typename BV> +bool collide_Test_MP(const Transform& tf, + const std::vector<Vec3f>& vertices1, const std::vector<Triangle>& triangles1, + const std::vector<Vec3f>& vertices2, SplitMethodType split_method, bool verbose) +{ + BVHModel<BV> m1; + BVHModel<BV> m2; + m1.bv_splitter.reset(new BVSplitter<BV>(split_method)); + m2.bv_splitter.reset(new BVSplitter<BV>(split_method)); + + m1.beginModel(); + m1.addSubModel(vertices1, triangles1); + m1.endModel(); + + m2.beginModel(); + m2.addSubModel(vertices2); + m2.endModel(); + + Vec3f R2[3]; + R2[0] = Vec3f(1, 0, 0); + R2[1] = Vec3f(0, 1, 0); + R2[2] = Vec3f(0, 0, 1); + Vec3f T2; + + PointCloudMeshCollisionTraversalNode<BV> node; + + if(!initialize<BV, false, false>(node, m2, m1, R2, T2, tf.R, tf.T, 0.6, 20)) + std::cout << "initialize error" << std::endl; + + node.enable_statistics = verbose; + node.num_max_contacts = num_max_contacts; + + collide(&node); + + if(node.pairs.size() > 0) + { + if(verbose) + { + std::cout << "in collision " << node.pairs.size() << ": " << std::endl; + + std::vector<BVHPointCollisionPair> pairs(node.pairs.size()); + for(unsigned i = 0; i < node.pairs.size(); ++i) + pairs[i] = node.pairs[i]; + + std::sort(pairs.begin(), pairs.end(), BVHPointCollisionPairComp()); + + for(unsigned i = 0; i < pairs.size(); ++i) + { + std::cout << "(" << pairs[i].id1_start << "(" << pairs[i].id1_num << ")" << " " << pairs[i].id2_start << "(" << pairs[i].id2_num << ")" << " " << pairs[i].collision_prob << ") "; + } + std::cout << std::endl; + } + if(verbose) std::cout << node.num_bv_tests << " " << node.num_leaf_tests << std::endl; + return true; + } + else + { + if(verbose) std::cout << "collision free " << std::endl; + if(verbose) std::cout << node.max_collision_prob << std::endl; + if(verbose) std::cout << node.num_bv_tests << " " << node.num_leaf_tests << std::endl; + return false; + } +} + + + +bool collide_Test_MP_OBB(const Transform& tf, + const std::vector<Vec3f>& vertices1, const std::vector<Triangle>& triangles1, + const std::vector<Vec3f>& vertices2, SplitMethodType split_method, bool verbose) +{ + BVHModel<OBB> m1; + BVHModel<OBB> m2; + m1.bv_splitter.reset(new BVSplitter<OBB>(split_method)); + m2.bv_splitter.reset(new BVSplitter<OBB>(split_method)); + + m1.beginModel(); + m1.addSubModel(vertices1, triangles1); + m1.endModel(); + + m2.beginModel(); + m2.addSubModel(vertices2); + m2.endModel(); + + Vec3f R2[3]; + R2[0] = Vec3f(1, 0, 0); + R2[1] = Vec3f(0, 1, 0); + R2[2] = Vec3f(0, 0, 1); + Vec3f T2; + + PointCloudMeshCollisionTraversalNodeOBB node; + + if(!initialize(node, m2, m1, R2, T2, tf.R, tf.T, 0.6, 20)) + std::cout << "initialize error" << std::endl; + + node.enable_statistics = verbose; + node.num_max_contacts = num_max_contacts; + + collide(&node); + + if(node.pairs.size() > 0) + { + if(verbose) + { + std::cout << "in collision " << node.pairs.size() << ": " << std::endl; + + std::vector<BVHPointCollisionPair> pairs(node.pairs.size()); + for(unsigned i = 0; i < node.pairs.size(); ++i) + pairs[i] = node.pairs[i]; + + std::sort(pairs.begin(), pairs.end(), BVHPointCollisionPairComp()); + + for(unsigned i = 0; i < pairs.size(); ++i) + { + std::cout << "(" << pairs[i].id1_start << "(" << pairs[i].id1_num << ")" << " " << pairs[i].id2_start << "(" << pairs[i].id2_num << ")" << " " << pairs[i].collision_prob << ") "; + } + std::cout << std::endl; + } + if(verbose) std::cout << node.num_bv_tests << " " << node.num_leaf_tests << std::endl; + return true; + } + else + { + if(verbose) std::cout << "collision free " << std::endl; + if(verbose) std::cout << node.max_collision_prob << std::endl; + if(verbose) std::cout << node.num_bv_tests << " " << node.num_leaf_tests << std::endl; + return false; + } +} + + + +template<typename BV> +bool collide_Test_PM(const Transform& tf, + const std::vector<Vec3f>& vertices1, + const std::vector<Vec3f>& vertices2, const std::vector<Triangle>& triangles2, SplitMethodType split_method, bool verbose) +{ + BVHModel<BV> m1; + BVHModel<BV> m2; + m1.bv_splitter.reset(new BVSplitter<BV>(split_method)); + m2.bv_splitter.reset(new BVSplitter<BV>(split_method)); + + m1.beginModel(); + m1.addSubModel(vertices1); + m1.endModel(); + + m2.beginModel(); + m2.addSubModel(vertices2, triangles2); + m2.endModel(); + + Vec3f R2[3]; + R2[0] = Vec3f(1, 0, 0); + R2[1] = Vec3f(0, 1, 0); + R2[2] = Vec3f(0, 0, 1); + Vec3f T2; + + PointCloudMeshCollisionTraversalNode<BV> node; + + if(!initialize<BV, false, false>(node, m1, m2, tf.R, tf.T, R2, T2, 0.6, 20)) + std::cout << "initialize error" << std::endl; + + node.enable_statistics = verbose; + node.num_max_contacts = num_max_contacts; + + collide(&node); + + if(node.pairs.size() > 0) + { + if(verbose) + { + std::cout << "in collision " << node.pairs.size() << ": " << std::endl; + + std::vector<BVHPointCollisionPair> pairs(node.pairs.size()); + for(unsigned i = 0; i < node.pairs.size(); ++i) + pairs[i] = node.pairs[i]; + + std::sort(pairs.begin(), pairs.end(), BVHPointCollisionPairComp()); + + for(unsigned i = 0; i < pairs.size(); ++i) + { + std::cout << "(" << pairs[i].id1_start << "(" << pairs[i].id1_num << ")" << " " << pairs[i].id2_start << "(" << pairs[i].id2_num << ")" << " " << pairs[i].collision_prob << ") "; + } + std::cout << std::endl; + } + if(verbose) std::cout << node.num_bv_tests << " " << node.num_leaf_tests << std::endl; + return true; + } + else + { + if(verbose) std::cout << "collision free " << std::endl; + if(verbose) std::cout << node.max_collision_prob << std::endl; + if(verbose) std::cout << node.num_bv_tests << " " << node.num_leaf_tests << std::endl; + return false; + } +} + + +bool collide_Test_PM_OBB(const Transform& tf, + const std::vector<Vec3f>& vertices1, + const std::vector<Vec3f>& vertices2, const std::vector<Triangle>& triangles2, SplitMethodType split_method, bool verbose) +{ + BVHModel<OBB> m1; + BVHModel<OBB> m2; + m1.bv_splitter.reset(new BVSplitter<OBB>(split_method)); + m2.bv_splitter.reset(new BVSplitter<OBB>(split_method)); + + m1.beginModel(); + m1.addSubModel(vertices1); + m1.endModel(); + + m2.beginModel(); + m2.addSubModel(vertices2, triangles2); + m2.endModel(); + + Vec3f R2[3]; + R2[0] = Vec3f(1, 0, 0); + R2[1] = Vec3f(0, 1, 0); + R2[2] = Vec3f(0, 0, 1); + Vec3f T2; + + PointCloudMeshCollisionTraversalNodeOBB node; + + if(!initialize(node, m1, m2, tf.R, tf.T, R2, T2, 0.6, 20)) + std::cout << "initialize error" << std::endl; + + node.enable_statistics = verbose; + node.num_max_contacts = num_max_contacts; + + collide(&node); + + if(node.pairs.size() > 0) + { + if(verbose) + { + std::cout << "in collision " << node.pairs.size() << ": " << std::endl; + + std::vector<BVHPointCollisionPair> pairs(node.pairs.size()); + for(unsigned i = 0; i < node.pairs.size(); ++i) + pairs[i] = node.pairs[i]; + + std::sort(pairs.begin(), pairs.end(), BVHPointCollisionPairComp()); + + for(unsigned i = 0; i < pairs.size(); ++i) + { + std::cout << "(" << pairs[i].id1_start << "(" << pairs[i].id1_num << ")" << " " << pairs[i].id2_start << "(" << pairs[i].id2_num << ")" << " " << pairs[i].collision_prob << ") "; + } + std::cout << std::endl; + } + if(verbose) std::cout << node.num_bv_tests << " " << node.num_leaf_tests << std::endl; + return true; + } + else + { + if(verbose) std::cout << "collision free " << std::endl; + if(verbose) std::cout << node.max_collision_prob << std::endl; + if(verbose) std::cout << node.num_bv_tests << " " << node.num_leaf_tests << std::endl; + return false; + } +} + +#else +int main() +{ + return 1; +} +#endif + + -- GitLab