From 4a705d1e03d52c384fe2b65bbf7486ad291947e9 Mon Sep 17 00:00:00 2001 From: erwin coumans Date: Thu, 14 Jul 2016 00:05:57 -0700 Subject: [PATCH] Add kiva_shelf to prepare for picking/grasping task Fix uninitialized variable jointDamping/jointFriction in SDF importer Add SDF parsing in visual, inertial, collision elements. Slight improvement in TinyRender loading performance of largish meshes (30k vertices) Reduce #define MAX_SDF_BODIES to 500, due to some issue in client code, todo: figure out what the issue is. b3RobotSimAPI support SDF file loading Tiny improvement in OpenGL hardware renderer lighting, to distinguish faces without textures --- data/cube_no_friction.urdf | 32 ++++++ data/kiva_shelf/0_Bullet3Demo.txt | 7 ++ data/kiva_shelf/meshes/pod_lowres.stl | Bin 0 -> 509284 bytes data/kiva_shelf/model.sdf | 55 +++++++++ data/kuka_iiwa/model.sdf | 45 +++++++- data/plane.urdf | 26 +++++ examples/ExampleBrowser/ExampleEntries.cpp | 2 +- .../Importers/ImportURDFDemo/UrdfParser.cpp | 57 ++++++++-- .../Importers/ImportURDFDemo/UrdfParser.h | 9 ++ .../OpenGLWindow/GLInstancingRenderer.cpp | 4 +- .../OpenGLWindow/Shaders/instancingPS.glsl | 3 +- examples/OpenGLWindow/Shaders/instancingPS.h | 3 +- .../OpenGLWindow/Shaders/instancingVS.glsl | 2 +- examples/OpenGLWindow/Shaders/instancingVS.h | 2 +- .../Shaders/useShadowMapInstancingPS.glsl | 3 +- .../Shaders/useShadowMapInstancingPS.h | 3 +- .../Shaders/useShadowMapInstancingVS.glsl | 2 +- .../Shaders/useShadowMapInstancingVS.h | 2 +- .../RoboticsLearning/R2D2GraspExample.cpp | 107 ++++++++++++------ examples/RoboticsLearning/b3RobotSimAPI.cpp | 79 +++++++++---- examples/RoboticsLearning/b3RobotSimAPI.h | 32 ++++-- examples/SharedMemory/SharedMemoryCommands.h | 2 +- examples/TinyRenderer/TinyRenderer.cpp | 1 + examples/TinyRenderer/model.cpp | 8 ++ examples/TinyRenderer/model.h | 1 + 25 files changed, 399 insertions(+), 88 deletions(-) create mode 100644 data/cube_no_friction.urdf create mode 100644 data/kiva_shelf/0_Bullet3Demo.txt create mode 100644 data/kiva_shelf/meshes/pod_lowres.stl create mode 100644 data/kiva_shelf/model.sdf create mode 100644 data/plane.urdf diff --git a/data/cube_no_friction.urdf b/data/cube_no_friction.urdf new file mode 100644 index 000000000..aef2bfa15 --- /dev/null +++ b/data/cube_no_friction.urdf @@ -0,0 +1,32 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/kiva_shelf/0_Bullet3Demo.txt b/data/kiva_shelf/0_Bullet3Demo.txt new file mode 100644 index 000000000..eb396d29f --- /dev/null +++ b/data/kiva_shelf/0_Bullet3Demo.txt @@ -0,0 +1,7 @@ +--start_demo_name=R2D2 Grasp +--mouse_move_multiplier=0.400000 +--mouse_wheel_multiplier=0.010000 +--background_color_red= 0.900000 +--background_color_green= 0.900000 +--background_color_blue= 1.000000 +--fixed_timestep= 0.000000 diff --git a/data/kiva_shelf/meshes/pod_lowres.stl b/data/kiva_shelf/meshes/pod_lowres.stl new file mode 100644 index 0000000000000000000000000000000000000000..6e668f1d7b4d85031846f8caae50625788dd040a GIT binary patch literal 509284 zcmb512izS+)&Ex^3exnInxLR4(v_NecSDg9N(cn-rGqF%kQyLBc$Ovz(gajG(xklt zp{6{$AOZr?5eR{RpcE;hSU?2+=QlII+28EFH}Jn7$aAvieCM1qb!T^;oAt+UHh!zl zz`($=o3A_Z+gok2?q=>UxPbrvzdyhGMkb%KSoi&BtJQA$bMgGx=kxFH_*nJ1Z@%Va zTtEJpCC1{q09jdV`_V(y0XHu0G-{=Ee?qNL(#F4CD~~=(&!thRmC{+Z?)IZP>+k-% z!R?PZy69NE3*Ge%SJuXdKUQ5ZdWHO|2j=8Tr%`Fis9o zsU91$#Mlq_n}v3Fk(hOU*04EFzU`OK#lBk>@TM9i-ub&HKL2H8?mvzwl~5}y+xakk zN@S{0!pe4pT}z2l3ANH1NuyFtFG5FDS%cMD)ZPx?=vPS|j!=yf@CPF1QKI$WLkYD) z9fB}@ler^QqXg;=gkAGQ^r3`WSr2ps+8?pt(;@I*D~wlQb^b)X*c-i%vx z6lvyKhpzmh*zlD#Hdu7KHPi=Wj7RIk`D!M=y5VKTe=m8;MdkYx*nR}AUpo6UW0{BV zw#gp)AZks71}T?ZfvFcxgw%Z0Am>75#M)#h;eBd+pt}8h#5jw7SOReKx+l z*x=sB-Q3mWfjav0GI!sy`&Pr(*0S0JOUkn2&px^yH{q_qmoHm;5Cm&fTNBqAZI->h z;bCt4y>{I3$;_!%I##l5onw!$_W!}9QqlG zwtnkmv^iwhH8TUPNYDz`A$uRQk3HUT3vYB-jd>T|F^4k}lnWVc?tLhs8lAPZBv-oy zVnZ#fMhTsd`x9yf8PQrPmVw3Zd{}gqYLu|}rSC2hh-ZyZ4P?%bT2hv+aN|Icy?Dy> z^B&%KP&G>EERkg&&HjDoij8;7hunC0a=)whL9A)t9$(5X?OeHr`LT~`dJ*Q=wOy9| zVD>=$@*n2wns+%;t!&AB-#2zCZv6VY6@2I##U6ulDf_5kdE_p$s_*`8&l+WMWkF#t6ot|J@0Xg>fd%R zz4+Cu-2T%yP8_9Hno~+(H9#xk1FK~}T&kG<<{w;CL%;Ib;`$9Ab23{KcFjEl2=pbJ zrMn20lx2?}d35p9$L<@v=Z4W(KO*t@`{v|Zk60levhBzDVCJBI^XD^)h5zt`^Vj%j zN2LUMzUQHR7U)AC6e~tH*S;Icq`tTb4~WV!Mkz8u8-h$IVa;d@w@oJxv}T4w!$GmbO;o|t~bOB7FB2df8F-b zIiDKcE|-~4-DFPw#yp=Z?z!WMkon$^oV@m#_ir--WzGB0&|>EIpLVgcTrCN8n${J| z)tn$Vb!9}-9@Ml6`g1;o(IE696({ncXJSDthc{_BKA#x7a0cERBTD{9(AGgJTh z(4*@getW{0BMzF=(V4pKk0oWTrD{j1LIy7vLHo=mRZ(6(b4qAJD7Xj4Ol@eOJO;qhRSAtgR z4<$G2hh_*_eXwOgV8r^qg|!quU`-k09rtdyZg*3z?>eXesTw8h{@M}#E?j*mp;jmx zKKy+mJTNNND1ov;;F>q@MW_|>0^#o&91}8EjS|Sdi*REE1ltx?kg@I}TF6Nrj!=yf z@CPF1fy}!IwL;k-P@>O*gld#P*&uMOKcQ9|SS}!tXG*9>3DhbGP9Cl+?`n1JE`wTlpxsqK&X|{SvKv3r>goZd!g^*zTLHL z+Xt`vJYITnlfjvb&l|6_LoYPG@ZPv&EWT~=g;kBSjy z*>8`0W%~2Se&zO;jZiD4nTPjr&zu8CA*}aWgj%Ih!P zWAF|V@k8bvd2@e-XEDf}QL$Y0mqvx>Bp~opHA?81Pxj{tp;nNQIZE--zz3pJjS|SI z$pi6&KrJhwR*>NXbp~60O6*eODvTbF)`Tvhf*K_tC#za;(oN6`J}A2< z6K>88PbOTvm`zbGV~32^^m#0C!tvGCC#*H~E_=GB^RCVYumlY<^`T|y$^aPzO7zcS zkUgHss749(9SQdoM+vop3?I;E88U{C@N6k+lt}YH)vkZ(k;M&Lj;XY5+xK&F13}^nJo^sME zov&?huZxOS?R&U}Sbf1m>)-zIyfH_A?$lhZ)Q9@cvd7LosDA4^4|bN``h3?jcu%eS zGepHZKt~jR{mz4fMpSJp(kX%3edxz;SKEKETdgZ6taN-(&a!>%dC$)F+{eID=U2)g zwbtPw%RX3Y&EoFAtW#^N>6if3jE`O`C#>NER)wa|)345$GfY$2d(}L=cdpp4 za6KiYti(#`{)Aew7NU=`S5#`Hw0rM77~VVAn8!mOt?Zdx9^N}wN~cjFLuRgYO4xhn zD!g|t)VtF5UNsNzovp6yy>lMkJG*-y`cOJ0nz-CseYRSR-CEGqH1dO-W%k~AFuZq; zYb`XIIU;Nbd+$8v8UNndKSA?7qtZz1Ib$B)JDU%C?>r;CcP><;1bc~(O7d`-hxs+} zf!YndGVNFK4gh7TRhozSDD6MDvYDlu6U{Q%d4`@yOg5l2+^sdZK@Rz7A-apU%L@~@n{_}J+${2{3;twXk- z-#=@;>-dn>r^y2=wA*u{$61|KN+3d9x7tXFOv_R$)H(>$w+PiJftm(k*XBZ~6*32b z-jigWsYVI(n1--7)icAJ>a}&;Y35po@DcYPC47W+qS7`{-&uyIYUix;?yZNPJZ$>N zjppPhkD6!f^4CAnMX)6I?A6^Z?Q+S=`W(&?Va=$tBp=nCBkmr4(B8v`s|Jyf&E3^EHqh8pf-?{NK*M+;lZMO)VdqCI3AJJ* zDPeDsi|`iNMa8nT-qd%pH*hl8`*ZzcB zK}KC!DHauWD#+UManHc0QNrSniGop9HD#ZhEsOCI)4xR!UqUH6|TSNj4y#CO8(sSw9GvZbtJ-n|p9 z<(+W6SJPUc+~hHPo}-G@-&?cNSq(mP_Mz+nt(Z^^3gP8c&>6`naH z{%m(=Q7yjPD$_pu#id58mF@JZ@J_gT#^@uKy0rM=r=PMs?loeK?;Uje!&j~}L#;qF zrL&Kuxm;`LoUb_oeaYrrN09C!3e+w>@Sy}V zSKqKpR-7vAww;gge$dJ6V~&XPRojOWEXlp8uEU#ZtWhy4+Z9*gP4&n4(AYJn#s_K_ z$sj)XP=Z#tp62n{1CCqy*=@ER4h>sPBTQ@8-U-*?o$&N_o7126H}_7s4)26&_vtP{xEf~;xxF0}~nQahL{ zNN5YXo_7%H{*n(|>CHWS_pZKT`Ef+Fd7Iw{i1r6hctZkF{NNQIJ zZI31o^h9{Vr|pAQ>JN4m?1L8YS#b z))D@G*SQEjlu#>_4IloFObOK}fwDp1nzv^jN~o3AVM?e*31kl+el9VlwExg1B?z`H ztRQ1egm1_(4-%Pblz=}FNgmFJ5^9CAK|pV@xR38Cs!;-EgTS?fz|)UdmRi}9bax$j zri5ygKpnvca&zx%*ADM%$LQ>=nQI-=2Y!~tl_Q?4{&DYd*h5$9&+ZdlpVp{60S$UJ zG)ng*%C--s)gQ{{rz}*X1be=Z%ARcJ@=n}IM)m*qg?eD373p&dJ#UVg^#>-tt&@taEtlEbJ5tgS4?`k`s(7x75@l65TPel zJo46?jaVDesg=^|&jl0yNPVzInMdQJVLXA+Nh`EJ<%X~~yq)ld7dtQ4e_*9Gtq~@t zys_JMEr^k$QKf{vudT!TT0F~ebp;ZBFeZ4n+}!)fN%Ew2bwsJ}xUY5Z?o^|M`i_Kq zcc+9}L2hPId;98U9z>@aC6H5-MwnowXr@MoF$coDV!>QjHQi zANMEJ3Nn14lq|Ei$T{+`x5#*25;aPsa|tru_}I0k;w-%qYQ>(9JW+a9hWE8@xaFsEyDZSF?v^wR^vVj(eUovy{|38`&t(jt=e~e4PozV zi}1d-QY-bLzFp>gms;qmhDfyUQg-iBi|{U0f14wj+qFi#kMJ(F&>GeL3V%)C?X}{- z8lwtUu%?Xb-UnI{<70`_=2UM!d2_zQ$o4e0AJ>Egz0hjS_2Y^Fkj&^RQfc=H#L(-Jc<^MD6`D&HlUhaBjN~lJOkxRZ%oxk75 z5o&eCfzMZ;x%aY<@u60z!}{1>K2*~t7CO1*qr~{o%pr43XijP7s%aCX9bx7BU5i9j zK@O2rQin}1F{-RpqlDzt5O9+aY9%$@^s6pHt)xa;gld$K8fitPnWN8!R!eHZf{CB9 z)@+r4%zAU?C9*cD6pfoj+0Jr3M&?__Ez4BXhj4Y}=R*=)^_6bV?L7&-7jgFwAu99n zg6(UI&`Z^bTs;X)dyEm)DACu4TWi_FbxeS0 zW}n83U!AE@0y3||KK2r~IzxjpNl?Zf2lH7%WU!*9O<<3M(U1_%hZ3{`jh={kIU$@6 zYGBnS&{Mk!&4bx$gxv&cm)W)nkdDBtP(rdRxkTk;M1t$s<6wn=T{4SC4QUeC<6!L1 zouCzH)|5ldU z*MxGN9B8-4!MzGfPWvu)KhTgSfjtgpj)XuSu`I~6f{Z;5=7C6*klF;Ta2;bFy{DU? zM$3hanIR#7Iv-L$aZG^ds;h)xw$dvd9cwpf4~Z&gB<3S$9ir&8?@|LRC0Gk{Cujwl zH9dENRv=g--2^pSE{U$p(XVpN9I{<=eU~|P`=Exj5|BaQ<9j2nfCyHxo$c?g-ns}E z)!Yd75cd3_B5I%&f89~Jo~&zpvb0>t&5C1tn~~V#V6W3AXoc%sgR{)`Hq)@j!Cpr-S}tU+5BJr4Fds?l;G^Nu6S zY;Q9idmQX_+61j|9X*uuuAMQlJr4Fds?l;Gr-YBKbOc6`u4+McqqgxOMAWqXr9QC7 z!CnVe;zQ|Vjmolqgsf5V{=vtCJr4Fd@F7;QTx8BQaqa}IP!eTNV2^{Hi)yr7$XvVT zPS6S^Q3l~gYzYAxSpl5Pm4RzXBp_rg3qMIK!BHFUGTbw;s?wnJ?`9QqTz^YByh-!$EQE48bMw6UeFv*>z#@;62*AX@T#K*31RYSR) zKb#!as~!Y3Z6eG>A4AXzG;0B|#NC98N`24@1Z$+5phnAu%o^z?q&-~k3vCl?Ard7d zl*JwgIoxHqx?-Pp1lyxDD>tjL&1r?};clsEbBC&iG z5SU{yZjwBl4{Eer$YH+fK}h}NQq!(RdiQp%A0=4pE~=#ON>rRVU3(<83!(&T@$xR! zSuu88XDz@k?TIW)tsp1ukwm2gtw69wx_wZi<&ubX#XQijxB|F5!pe~3)a^sFZ4*|a zYr%%Xm9Vm)+}O_W&Fiqnr@6DFrWe6}<)1Ntf|W#~{#<_0dk_9ke_zs%pl=d>MW7F^ z213U=>>{FuG=AFut*FATsG?Qyp>*tT-bX(|dQ2S6o(Q`lS65;c%SBY|J#!~$g=i@| zqO?Elf8QQD?q~%cyzYqbhi?yRwA`+!%CL`ec?c291;IJrzD>p65rutJ7eOod&9Or`?M53~;YFXBgpcQ;j_CCTM$F&DF@S!s1-Pm`tegv)HgED-i_w6z} z=a4yT>)aj*cV9vc%54*j%8l3(&JcUMCxXOv9p~vC05znQfQ&r&ac_P&GgOEmjHt@q z-?;e-rO+Bb%UU%`*!vsTr{_+n749_A6T1o3D1qMCn?NLC&Zv+jWsT6~QMx}Z57j6E znYG|;?N6iJnId|3VSWa(5Z#uZn~T z?rc=lC}Hn!-0U-VLaprmjhjmn!bPRt)e3bO#(yg+)wGE){#%4*E;XIhLYlc|+a{9n zVL9OA&ZIJ4H&1aUlKgy|d%y_QASV)%(_9F(lA88J>7ArL)JkfkMW{vzsgYJx(jKnQ za@N+ILelPsuPbJYUQPlsuaju*uY$(SqLe=oq3xlx%OjcF8HtP%Duuck-;3vubf> z5UXVF>Q87N6WM%(+J%ro!?C7Ta^2N#(;lj66V04x?{8{3tCslaz2eyWn>w6T8!0|; zqAjjVx@x<#Y8Cb$c%P#hCD2Y`6}3F<{Y@oj)#AN@T8ZrH3boXX4_%QdqgOUQVBdpq zkU!12)!3k+6a4pQ-rf>T|PMObS>#msFlc8yY~L3 z2xrxB@+{teh>TMryvwkt`Vnd+viY$0H+eX#hLdM33uoXcyRp)&QT+(?D_V(cKAMkz z!qQ^}aDA7nPh*dfiylr5%2k@z69T_06Gx7W4;}MXSIx(-&YUxpfXwT(_p{Hq1wTEw z=`}ay*_S7DDF12E=kl}5vGICJsHPVI8bq_ZgVhI@-kd|D1h2z)Z=xL)X%c?#0TxlI z56ZkAi5Qt`7zrZ;?THhAY~OnlR%a5dA6h-M+@^z{9`bR7T2T&lwa#Ak89(+X$yGxc zkzD=7EeFrLVQPrVBI-$~6=m<^Lp#B7dhlVI4$6Xt^6$1=r(^y)O&-XaQPB#7T2b~s ztgdp_m1-y>539ot>&?EirVpW3l)Vo$AN!WInkx$$wc_>eHdl=jlu7upVZJgD7$5LK znli@??79h*)h3$E!H|M?mPNUjkA`4WtWk}Sa+bYf@6JCAXN0v}%Amir#m2EOq=agE z5x%ZowcjrN$ot5QaD5c9Q%1isTILdqst8dfgj!KXNv@*8A7!CY_3D)gQKF|P!JY^! z=9CcTrz}*{CeVVBu=4RqeZb#WCS93~u1I*m2#vi>kPgP~M_Ef$732^}B@wpPC?(WN zYNSP|MhS_wMW_$1b|(n;8b#wnj(U@*C{iccVrLtGB_VCk97lp=GI+ z)xu!k-X49ZmG+)A57o2@_R2_w^oMZyF(C&v0|6TDw>gq836u0(|yhvNf% zm-#hqZd6&TMhVHOA>bw<)JkgF6Nt(_DWO)#DfERFp&BKmu3AxP?5$ehnC~W{rcH3% z_zaMQ{pV&M-c5ku+Gi_+yWj0z)nG+Jt+X|x54geV9D9Zm$UJHDfTdB{ni2hJgwDA1 zh$k4k5|DX46z@UIiS&-yAj%S9t9F%8E2)tdp_(?q_0fl8f0p)N5*7ThFKL912!FWw zD#qR>NR#k)u#C#??glAiJ!ie)dP0<{=|zABk?sdWFLC8ETP-OPB_!2ARswPom3tbc zR*33j3Fm`lDM8u$=(QhYUD1cOrrYCm?I1y@73GjekKJ9HXtjACLaitVAJ(6&Vo|## zH5kv7&C2aLxptYICm>|7qNYupc+$1prS|Xv?Q_* zk9RL3=UFB`l1Q{%k&XC=?bGl-5>k!GxO3t?gN<4tGO^0lN@VjPd6cRVSyyT!{KvPV zWym!umu%f`g0*+Jj}~B4b2#*vI-4Y9+F3kEFN9vS7t~T*|h)_oFsGroZfS4!&GzdF74UiH-QoVsnrsB90{347_%;~E9ys}m(WUNmm~6Y*}J|gR{BJTbV|5U+k-$3Hk_UIZZtV-S%2rpFMh4YjqWC6!m87xvObfyPqXS z70U|ihl?uA^HRGF*E}`oMIb+1kM_<7Gi156vbCLW`;2&K$HVh^KisSM(udc&vBtJl zE6LA@-=DT?{ki=g$=}-XSnW%3KL~#@a~IWG&rEXj?iJHcO9-`s+^hydxY5ZTE>^g6 z^0jL_Jv$k_?@QHX@9thK^Vxa32+$T)>phOumemtJ?%6BrJts?VrO`GWLL(76pE2{;4`x@Q&C)=T4b=1oG zRflb3Cq!2LVSU02Q}RD;a57pjYLu`xch@n}vMltH()v|Gs1-_T?n|U!<)T43cAV$`K*ngpdf02%i$;T+31`sl$da(9el723e!={u-l;F5**8wqRm~)?`VMa6VKc zEg0{w)rY?W=vhBjmR#>-*)`LTs+ZsOOZkt!vkK-xUyEiXHI325nr;!M;S8X&XfqyN z67ca2?;~jg@zJzk7hzU|VJ-npe@=ES>j?jc&m47udlA$b)(XnJj`|}M?g9bY|)oe_O7D$*=TqY68t;G-WQKJ4ioc9QBNDc4Gx zzU&q5_+OXrx@Mx44Hx|MJ9QM!e7>)Cwi_BwTw0&7cs2 z$SFiMm_(HjY9-MI0w-Va3^vhdxhA7+tkyqABLiM;H^)hbz~7@H&0qr;QQOFe(zES2j_(rv@b89R$i{9&I1#7-SwKNIQQn z96QNT;4YRLEtme#7cg_UJW3^^CgemqUUx_!VlTm5g`9#_oF$CzI3QCZ#GVjRBaVnq zKT705@02mqLDs(8JpG^*GE^(btT$IxxQ8ntsisY6PmEDHLZiZ5OMkeI2vKr3!Pu36 z90~Lg_pwNF#tWH|Ku$96OVA1gqeao7Pno0|Etl83qC$HlQ6a+6D`SM+J~Z|=!M+>o z3O*{V^z5&=Bcr_h4maVPNsrp42DB0*cD>m>A9qoq&D{r9O3(_|e}DB&c!Hbya8W5i zD-di=6dm(G?M983%j>arlc+TFAiEL8oVtBbgK~Qieng>{lwi#&XS|d{ugsYr?9yIB zO`BjX%$=YWXx4NjN=VSC4_e_mYowc?M$3iF8i@piuFN?mK=dDj)WAxK{^LB4b1msSjF# zV2vb%^FfW4O9Jg5i4qbt(jJrtaXo1d)|Dfu5n72s=ObzJu;L(d-i0|itR+3#TnSo% zW@~o)paxcLB4&=LO8gHi^%2&OB*JbVVa0J)ZNgTZrgj}_J~*~PI5~_#uC*!QYFF}z zR-hTJD>`WpYG5UqbLIRPAKGKO#zzTn?bwxo%-Z!kZ4h?n<(_%tUM-0|TxVUuG~SCk z0vaVKN1_B`|KUE-)d>l-jkD_E!x*ffq5-W$lwoQgzuu}9Wq1E+CG{rYgPLB1qrHo; zyCcE60!^8%>4C5-a!=`cTAA;Z;C>K3s6kXJYnx|TKO$OLNl^}A;fLSjP$T<6H&&8f z5-4kTDGO1N#`U!>{J*4Mc^|4#0&d4YS{V^ni4c(c(M3cn%_${RbLN@Dn)>O= z`3_tB4_6-uJ)6R^_>IB(#5P^0BS=IY~p^do2mAC$chJ7rPW z84&j@gBmRtGFJ)jqaQ&l_@L|w*Lo(3W>91|O9WytAuzYodq2X>iCGq+a?cr9R*Pm` z1t0y0Pz%ltHw0jw(iC(I!Oc zoiwW&%0eC_AV=RJqR=K%mRgzYW`^ET(Rd3LP?Z8!K_8o5!tm3cVr3SRyAt+ z5FzuBhg;QzVC?Y6y6Pl(bP=-uWL*U!)UI1`#445xAE94;3_&a8M46eVD~|Oz7klV2 z9nRpm9tjiNo&F%LP%dQ|QJyG0=ZVmFU3-w|8CCS51Y_^coIX^O#NPDw9(mA*5_Xpv z^Yf+KZ)X;EG9|82?YhE@f%(zquHb`D&sBp6CG&L8ne6Df7NLG*p09$BK}6-pHzZh5 z(~IEx;pX)+5L_W$n+G3G);z*W;C;k+kw=>_AF+0QWLk?_yC%EZjr&?F-4m)&BDw32 z*2sgk>%3bVFe+YWd${sTC7h;3fKCVpBxMDHbh!Jl%%A(<+G^B?d)1q6e|XgWq`G`MGslH(+Aym^QVuTh?(@T_q9IZ_5-LGI3H7z1(kN8ZcO+>3u5_@7A6?}wV zGN=UPxe~YwbA(wrIYjHnV6UjUh~V!N5Z1389qR34h-hUIhIz#ZX+iAI8;!{%q&1De znJ6?P`jrximC<3Y^hE55Mz|h_I~F6@Uy+BCaot5#g?{Cp8Zh2A!3fdM(@{$TtCECZbg+$+f=~oJJM;mCIHM$RrR>oZ*`Kv8&7}sp-tlt_<24 zmdehVxc)^ei*S%_kP^2HJGq*&$}!bCFYi~k=3UqRZZ>G>PL>&w2cppVmF?kHeapO= zOK_sbPQAFOXl3QP%o!CjjnT%ean-(Kr^5FXO@HJee3MS~+U~+tqlCrpeBk?vvMdl;n@}sr@ZkyMfEu$Og=H4YQY)ps zt^YG6K(kz>?cbTSodk%HmWNuYKg(F^svn_Nkej-)vfZdPGFOcf>~H4R>Z%{1R*>Pt z6BpXImm!a5j(HE?_T)5{Y3#3%ciYcLwe9K;nhzyZLmwp2V?1%6{i`bQG0eV^O$o@f zV!h$phqA06p;nNQhbK_J|CBXb3L3S-b@+=!sRT7jsJ|>*^<@9OJG1Tg4%CO1%YJM> zEsuVLT0ur0p0KjrI5)CVjS?2W%ftMdkA8$&L52@cykmFy$lQL`Is(RakdcQc5I;QNr)re=^((%1k(0M1p_(>=(4LSy3N4EStn7c6xm`>1C{)uX;KLJ$%YXa~hgyV2X|_!y zN+np95|DX4_L3641!d8PmTN87-4h+5nl{nY73TDiNc>K6vySVPMdalE1jhl#htiN; z>6W=~ca2KtN1ewQk0VMY)CxJVMp8mGy$FlcM`f6gN(sua(zZ!`sHPXu?L!I5u+mv6 z@sZIA{YS0r@6zU;@p-653G?#_2(@BKmRqZ?RHFptPe#Cs5!(7Y7awZH8nHgnB2?3h zu)a1If;6nyn%zEB(~Ic#p#)`E>D`BGzp~vE;a#mb3ape?9;#8o{J1uc1bxI21&vy< zB+IRj4``I2oDgn4LAIR9C|eJ4_ddAp?_@&X?IQF}20nE50psT^mTNsSxxYdlJqedN zHCiqS)QFFXK2)OwlQ;FAJ8a4ITBqy zlz_|#?dM#4sFhJJ4~wovsHPWT(anV*4J)>0w-43yBBBq=9G?<*OF8Nt?TpsKicFc; zy{-S#6KX|SOLDelAaK9ye4v-W3It{N(7p@C?O39f(u~j(*k!}scHPbg$_@47{6WTO zg%96?{Rp*!jFLQoT{e8!uDeo=5~wfuKyI1am-iyn3Nn0nf};r(t&pi&@%kqt+O*%7 zTk$3K&McQ!h#fL>!p}%xXP*#i1sQpG0+#TBX8@{E0)F5RF}SA&Aly>}CDaNse0T!; zauBxbc72x`)CPICCY`2|C`!XLN#pyw67~|4<#VeiZY@@22Bh0B4EYq zo{*>t)o8hh26_0oT?y5+2}G!?fr}1%P8T~gtWn5X5-gjigRo**ZGzX+eXUw44L`^O z*HS_?Z2~?#VL=s)j0EDQ3@gYWaNVT=!hKZJi%6n!&r4`UA1oJ^$OAPV^WYPfs8N3) zKzqW%DSb@txsTJJSF>EoAbfB4*7&no2cbb^w1SMNl<>Wg<-$8<%$z#&IS(buheRt7 zYNa*e2>Zhms!;;bAS$*8GIvC&gj(@BV(9Gy8YL)4fBEa%efu zQD|$*dXEyLaxWQi3w9&^GW9+q|^d z$3;aecvma@o%NQ~Ri+vx;3pxX4<*!!*O6OqAJ8a4ITBqylz_|#lX31cSMO@Y8cAlK zq^>wKAX}76BAI=<2(?0Fpu2sjrWeueLkY^TLS&3EtzBBdyISGzAfQhP)hNNy)kV1V zgJr1|OG0kFeL$lGWfILZed!Gq+WbBe{#hSL>X+HW9Y6Tf3c>?=#_^^F?+PxSk0Ji zKSHe_!-prV_!2&FH)EN_veZgxZwvD_0h;A1o$Q3;9tYmlA4jmyJnXiycTNbkg51;< z_T`Ap$VxRzp!YQWsvn_Nkm19(Irinq+;-ilZ>OucsC5P0LB5NZV(QF#LOL3bOt0@-V+m9?8BI8b(M0 zK0MLXub&f9C(vlQY@0}wo@!>%HUYZvA-yEda3Hi?^ceU?gh{``Nsg##6Y${)%+Sn* zJskC}J)GBj6ZB3ir6IF)??`d_V?JbY38a?!u+HJedsfQq|I59<<_bz)o8htBS9Z-oTC<@ zQ7cAh>u>5KMg>BxSRh__UUPQMKB`Cv6?>>?| z@SZbzS1XPi)3@?ajS}X^l{9xktyq%f*2f1lN>EM+H@_nf&SaFW?cKc(uKPO~%N@O> zi_kk6_|W+Z_0>(N74k@k=tDKVh@`GuR3xBLf^sCfd?*1KZG))nXH&afKGe!6M_3Fk zLN&bzi*7CiX;`5jBdTs6s_8{^`%r>1tS}yXXHF}4S1ZghAk1$o57j7vd8H@e<`Qbu ziX~YLeSAQp1m#agz={#t&(ueZs%>R|cX?QJEkZR~F0Wg3DdA=~WR9}bimlo0Lp8mK z=)-zDKK^Vie4w4tTA1f4^SZb7e>SIaX+^^PRS8iB0{6R4gI)qF5R^e^-v#6DccYck zjL;LX)~P{;Bp_q7!iR6ceuP>?B3UjJl7n@&!W$8u?f*da3~{OnJt6=dY$3GB;}19tSPQ38J85BVgg?h`_- zAj5|zurG%XoLXmJf(A0n#o7eIRw47DglgIZXis354IenQt^{OSp>IJ(bng9mPeQFA zBPvgXHL!#qY7h}+Sdqqc*fl#Z)$}5~58FEGPgru4_0ooI~ukA&^iuw7uT?y6D2MPFytAUHiqI2Ve8l@rgI-=*NncGp8 z67bUy7L}W?@Dm!;I|#MH-*Fw+(tWLJ+5~)f0`W605{QU0tRREHb=al^HNA+gsNy+& z`XCKU_O~PtJYk6%jRe<0qm5h!rTf!*3(AHDy_z&-UiY>n)Jkc{h{}(TVD0LQ1iVwm z{HXI7efavK6$rIry}?&Xs747ygQ(_Cs1-{>4846oqXgwoM!-sErT#wD3Ka4{bSa^l zUIe1+PmqQcTd>=QYI+gfK9rygE3Uza)J0WtjL-_+)e3z8nZs|Ihia5S-%1GjaHoo? zQ7e{&7<&7FMhVK1ppQ83Dgl`h;%DL`M%A{$-w`dMO9|Czxx9|(62hHzW?5>**6jA7 znqEZofy}X{_k+ivsidOKhR`@&XEv+lnC;>k`3D>WvQ7e{&+3@$^?49E%P@_I7+B()1dt>6=Mw-43yBD#GjK^azvj1jupE!lTz z1@CHwzk`6@5lGtQp&BJPx*`#MD4|xoj@)|tfJO<*2~m@M>Zh9(uYWW?-+qs$@*r0t z=d|c%SR-{2O>=9=IJ0b=RM@}06|%Wq%^yDOjDd@RluN-|^el$9-l&*GsOho~~wY;`6v}#M9NcZ`iE3 z_x16WTsI%@JvFR;cganQp)>9sB^p;h%v|X#d-kfIRR6pDq0Wb7s6>?#k3R8X{?7b6 zyI%6m<({q<-*L0zOUrNR>W8g{l7gIP*~?E2D~2t#X}!~mpP#Op;hR2PZ7|B`q$Oq9 zPS*~p@`tB5AD2yip<4Q^jf(%fc*9EM{HrVev3l)1e?28s(}%FAu3PQinfET$sg^n6 z$Xcwb1-E>@y5!<5iq}8bv^sT`y@CC?m$Pi*!&8diUp2(Fr4ni-*UiV)y@^~2k&Q4P zwfQh9%OsK{TglJ+=tWdwr8yaK_^S8Lyw5UU_Jkt~vC^n=^_^wYR@`&OZw{Y5<_oV5 z6uZCutgDmLKiV{Zaq_dSt{^|N+jG@c3y&`r{`;op1pR+F<{n(tvIy*c*P>Yq;PxYO*pQ~Q~`xeE-w>GV^?1#fG5C@ReEBTGxy#-d%n3eBpCu zRo6}P^0lwesy?;mxZ?6fH#Z-j9z3`nGwFi-@ZHxOqZ%dFT4Hu}?mFX&?2(@g&$560 zYDoT<`=``HpXiLysMJd8(0pw3*^>r$_`yJZ<;rW0QH>Jn&#yR^xv^O(MA8Ow9X@Qu z2}GtEZ5xq|KpwAK9`8KRnJIZxLRT7Lmi=t2_3BN3wS4_QPo6bHHA-Ck*fZ71dygwt zcz?4h%P#uA)#@F-HoE@aK|fCjwYq$hXR6Cq99KNOz~)9=cFx#()FXB}dCL2h)Jb*1 zhO??YP8nCs`@1cwl$iSAg@d=ObH>bL))=UjP%HJ9Wgl#^ezDw-zFvQ6-@Qg^x!Pm2 zFJ#%QFAgo{9I#n^!R_OxE1_2E&%QV6pC=4naqvLB$rA65)VfkDrL%0FspIOu?6kC- z;gpcJ$wjuh`py5nT%CBz9&Rqt%r#rNZf#!u>_?rq4;&~Sy=J!=s!>8((}-_=d%fcA z+m?4eRMUsBsODeu2lXC@p4Ium-S;GSsakL1+lcJy!|O*E`QQA4L!RxxYQ(wYiZ`Zj zo$H;f5Ej*o_HW*=cKq=sWtnP}5ZQcu0wU>eS$5;bhZK8#`P^#og&Rid9joS%-o0MD z$zjFS`yXGell^v@_9Z2>q%12Q9$);vT+G$3#hdd^U*zh5kx%DaU%6Rv$AZ{RT)NOL z`E`@_FLu9p=bKccdk)=M*s8YmcE#99pDSiWi|>qb2C(xLS#yPQ~Eu>I-i ziLn+ncBO4@|6o$F*U^V|?%Mg}BtwmG(<^4>zZgHRczZ#YB$zNJ+Tye*Lu^KEi=|7`4ynnyW zPfj1eT}B@6Sa6q-hkKDKB_==r^Umkb{o|NRZEjaWt<<0Gysmg|^f~)))p^J60Hj>p zA<j7XFBzp8C8XZW z$KDsNTVHd;H@JSpHc%_2vux<%L+h3H->g1&R542HM|-8#LY6&#+&1;x~Uh8RE_o+Eh)=Zx~?ex zFm=Uxk+t@lEND4k_n3ZWV$#JBkfcdr&-mZ?=Ae`beg zGGT9^gw7?nTZ;2ak_UDyu};LF)|>gTJW%zR~_KIZi2 z^6_hpFMj;yrr49Su5b?@eP`Kv*MEP;<)5BCW|db5YTNfYO?U$32*`{7cuu~LJvBJP zO0wB!iC@e-?0eJ3y#CTats2`2N8WeV18M4Lao(QunJQ0quYe|m46Jhg~m0CX{<4Jm~ z1;2jq$+lP}btQzwvYzGfJOA`N8Ru#xQ5m6`i6t{2uDFZ{J_mOW;fNf&HZ z{Pd9tt|s_41GUn;Y1n;%vu-yQ0@qhiQLI~cLA5UK&qa&evhtoJQ&P_fGcmsUsZa7O3d-~2A0{@2Zly>@sphy1{c zn-$Yu{$u{b%O1=>czWyN?Q#4*fXm;ST<>zpPOz$Ir39|CB-Ce?DM3w(h`zIIfdvk# z53s1N+ulVL%d$u+Mgn=^-)~)veGpjvRjt&2b3 zfbW2?+O1f-Rwor}5i$vs#9DW?8wu643HtW;KBq1}q$WH^J#uS{ z3U8NA5`r2fATwImg7r>TS4a33)b>c~t*I-t$KIFjRGnn4s4b{9s%_(Y$$sWzGiwj+ z4Qhq!iH~xx;6pVnLR#>VC06S!kWH%2widJuV;|MAf_bcILEIsuc0aP(RYI+By{RkQ zA)jo-JAt4^3COJVEIVlVd&itO-^tbZ0}sU;#aNbFA;J@H-lF)+;cUV4mmiXU@w=mD zV%)L+s1>d^y##H3u@Q>|f*K{X7P4&f>xSe@ZE;lbsp{E5thKjW|M_V0)^0y=v_-Pf zVO!^CeR@vbu}$N8SDtVEYUvAyR4;6GRPp%nvj??Y&7+(6{<>3&O}G5fpw^E@k`iZ} zKO|ppgDJ%?7CXU3#gsdFeeP^1@!H0Qyop~n~Ta0+l>WZrY32Hzq@!EnDi?LTd z`!NKqK;OUV#NyIr#Yfr82dzMKR+(75@~{v9TprYDxsdPPb7FDS-9nTGlv?Q`-2cwUxHR3?lofe{JjWjv|Pw1Za=a3$$=k7&@jmEXa$VsAwIBpWcwFfm?E@Y0CEE_fY;9EaaP8~e=GXu5FS8)|S``y{q z1uIP`mK*X=zUv-ys%MVey4dDItj?>>Jbmqn15-N}d}g3fjS};H^lbJ1kGC$KJrBf? zedbyF&ZDMwE;GXBtLQ^%o4cxJ_IZDa)dp9z6$keWN~jgqdCtfFE*vxUl76O+nl`~X z-+tF;`Fm%cYwO1rwtm0|R~Eg00G+HK^#$f*LGz)SHqqqq&(jVWz0lVV9DLzae*%I& zlsxWv|OkHs;$+8pIo45Yy_S@G(p7=!v zEl5IJQ)@cQK7ZMA^`BSWpq{zJ@g3Eu4=u@_4$iY#amd0$>t9{DT}RtP>rLq_`}W(r z7svkX^=k6bt0sh6sc-aMdzw0QcD3lPdt$|jz1rktW#A~7J3%XyMA;Mn-evdtzQz8E zRVHfSgI16^gWFrnCw???$UXeH`cHq@(h<~XxsZ81%XXez)R%9#Vtv6s z_U-7ZZ!H+_sUY*tAj=LJSg{!Va#8Q}+Y`{Qq6RYin3iNu?*95w_3IaQEQbB!yg|L2 zP%B(-`fmC1BE|o_u~o6nC1)k~K1$eFk^7Pju6kwk6T{~pJZsi~d!ER$G%7s(+~c`% z#s2@sh}vfQE2GyR;R)3!f#-=A|6yG5jsJjn=Zy2#-rZ)n^KHHYvFEzui^1(5a!)od z9XY;OYR8A%{aiE7cfPqHG;@?oLhI1C;AIEDm>+WP_mcZ7w6m^*Tt&0&q}NUwdE4g~ zExz*PmTf{;=SX`WI~}}5ao;XWfQTCO3|Y@*<$U;+lSV#p)VtntMOzwmd(*UTPY zeCaD*<~kn<2)F}CW=57~Zhiz~~amX9n=Bpn*d8QJY zxzbs7#PnBYEZfXi6=yQk8|SE$So*40X8fy}6XU&s5~y9y+WraTPi(jSf$g@{O53KJ zm}JCzMyRGuH0uX?;Puz6F?h+H18%;Oo}s-m_88bFMAWqUalA9|PlP3^xJFr2$-J9n zULf-ieI9WoQvxz;+P}No$L{(b+d}0c zoAxSxJ^A86eV00FnP>8oe!E5SvjZN=w?F=we1%=d74!T9Yt%Z`7jF9X5mP%?wbm#l zG$&uXbFNvVbMc)6ZoZOHn~Pj={C5-7pgn}hc^!m*S_=tQ)Iiquzwe6i#rvOb?axbC zQPU=t-e-KV#ab=G`A~vZpl>~Je6ic{v#qY$QBeacB}T3?zPMudk0WRW`k~3=i@R=k zriTw|V5P+Ljm8&;Px?55R-j+K)!yB$-;1CIR!SUp>G)#h$7lJdFjJSP1GB1xsAz@j zj23qOEdT`7Kvv?V9mf~%ts0_Ae6TDKw1T|HH^&zbEfQ)sSwEDZ6$rLdjH-mB8Z8$x zTQd?6x(HfcMUsXozHFD#TD*PpPOBc`u!F~zCXUn6K~ux zmn>mBNS(u#wpk+1`C0bTFNfp{EjXpVe~$}0D3|k+TBSa=eDk*In7{2;4ExiygR_1z ztIFQlyqGig7MyyCXZ%uP!kf3{M$|+9bZv4HQ0bJocab&fdqxefr{rZvHJZ6b>zW~3 z;i{GDKR=qg*+=?Pt}^?vb-xd99l6%a3)IK%v27PYE3^muSeE5iy?6V%2k%$k^PSq= zSyE$GIzFT)o-+Hr5eMxyxjuLMJslyvPl-5!?d0+w-C-y@2cD#vihJEN}}wEb*sm!e{He1^Fa-KsND2KF#QNx!3SlltN*@|pRmPu z>kqHEw4-Z=t}@nwaTT>wlk+W5j9+fs`qUTBK~IdDHo+d6WlOyHcy;;L_Nv#~=JF0s z1+Dwl@x`}xeJDA9rF51ZcG8mdxzBA@FL}(#387XRZI&&6$C_jQb@SvIXTR^ys>$6_ zT*H;lvJtxsuV?&Y^sB_49;EFZXG%i@rs59KLw$JV>8bJo#QI~N+E8k{^Np>^nc z$%-%jIDg>eL*4k0`6^j=xjtsu4-UR(PUhSdi4qd5sA&_4k7VVPax3wd zM#YsAQAG`8CFt8$oOO>Zj$VKL{I0bxn5i?ht{=MkWZAbCJhZs$uAfxv|LoB*x@K5U zjK4p4>35&5e)RB`#TOUDs`k&%9a!9U-nG?3EM~{|^1Glj_gzb7r;A_Z}D{=XaCYM@LtdJ#FXP>xGW5_85Jm zBRKB#jyxTMoBipiqI30^@+W3rJyWgp9I}q)EL-lc2Ns{HuFNm$yf#xcO6ZJXC*r4_ zF#N33rgjdrnL*=KE1ad6Z~h6zJPV*bhWvY;;pZGbwR5Tws%aBvY%rntMHaqcyu9d3 z*XO@H{Qx(j*hkSeB3JC8t~nBdnidhq3W)eD!;Pq?CQT^z|IJfw6zzKBgks*?y}bHv z6N<|wKJD*b3t(VTE;W#q`2J5P6x*C71OVql30i^XSaF7l4{Bhg1oLwQ#~`B8o*3%~ z*Xg^Ppaxbf7c%|LouCy6)?qh6jg||U^=2nI?ki^=`S@Y=QcITkyH7t^{dR>3#j!6u zlAp8rlhypkPbhwV?c;emYM)$ZN`3B)i{(%L=fs)Tm*Q_o>p0i(pJktW@R0hoZO+N> z-0${;P^;9(^m15n%&*4PcWilLM`s*8$)nNQX^{(0&G#KLseb;X8#=1dajrxE&>$;Uwd?=ChMElL$K7{nj*x#~j z%5y{OnP1qn-uNr0xzkjf0Wjuy<_a?gf9u=s`ko$EZ@Klj`qSm9387YyIrC-N%uPo zuUHmpm;DuT+8&d?`Hf=7IqPD+(vccRkzJ3Y%eO~ALdIY+UuD^UcQ~{d`^{6_93|sU zql*5#4<#h_IPMS?OR{fA+hZ-oq_6K@$5d_D%Mrdb*4_RVO+ey?n7@-;^)Ss_i z__)4BXe4Ro%YSs)ZL^H{_1b%#h2ezF!eckgnE6zK2LWOIg zmpD0`{&cd<4$BSH=l%LugKdIVmIr+pVLsgIeD!&+=O~v}>Z4s!<3kCxLR~c_$@#=V zdH0X=%{+I26TdtOXi?eePo7U4R85-*ryGs1GpU2&Oe%guf$uzAxwKN+orjwl&cor9 zUi2>S=-oFjg!2sM!#-s={aMNBKgc|*=&pw|UOfnES_IE{8L^O^7sdI+VcVZEs8;Ap z;qA0rgTs4HBkY7}5l)zb;0ZHW<+OrK+MO`%gcGK<)d|n_3fW>o?`D<{$cMw(EC{L+7m60 z*hB4iE$zHdIAQ9(9fmzzd%l+B-~5CVrZZ6%3AIXnpmxLQ&oS0gJUyI@30x0nib8vY z)1Qu@M&2SiI=sg*Vw`=G&Y2q=ReUh%`Hno_tq$08PBmh?3B|rwobSFVB)pF@;(`l@ zzJ3G9SpS!xA2oG(fVx38t9O@xypDdBu5K`YSBOx>@ksm&_&P+G<#)2xTw?ztw3mE^jdFD3N^(VbLQ#DH1S&BTI zFg0Stoo`ngud-YH!F*>ADxp?3qekCZcJaqWE$bD# z|Mcti9(V8Qe&2vr+WskV*yxq(ozL#nog0qV-)V67ZHzr7tS^?~yeQU>*hfv~36ZY3 zJ)SV_BDCjIMsLr`a9-5ie^LVNfRn);b4m9s+uU&k4%9P~ZN6WQdDR&um`g2A&{pr4y zE1bDW?y2O>hK*V~{W&9?{=`{MzFAKQc~fnKo&LNfoc^pqgtvY89e2Lf$8VEMRCf9^ z5~@)`Ys9xlIQ@y981H1zn!4gN>!6+foEA=hwh3K1Bkg^J)1M%s2L5EN&ADD>nVtTe z7EXV3Tag@S!r-tGN@jf)C1`2&X??Z>I)6ROSjd zcY;>%LD>`GET{894ScBFtb<_s5wwC2%CJxGUc=ja)HKhnIGJm3H$hFCNPO_V#I5Jy zEwXD(@s~!G5G)I^D?#5`W~V>b4yQkBIXRHr0qDw*Wq)6(%FlRq-(ugbF6!uttSbQ4 zt7iZ4_)4EHmOFQc;)SW_VlIiAHqoq{H?91s`i_NnELNNU3hbkJelNKfQQvktVS^*; zL+vc*nukvwql8-NJxZ2s+nhaj--{E@MkFhz%`rTKV6)F=cE0^_f0omoJrAc75<-3Z zo$#Ty+n!^)ZLM9cQCz2Qzdy$r$ffKQl4_KI%vBrxDl5ZTPB)iGJM&D5>oHB6w+U*{ z6P4z5|Gb1znfHp`A#?v}(eeb8)fIlr6sJF*^O;9Yn+T_kjj(f;RXAtqPCD_s?d(l# z70y{!cB-Qa=PZq|^CdIG`I2P)&`44O-%?=hkz0GX?;Yg&p(}%~M7{<0Hlhjy+gu6A zT}7S#b2OvLvrLFM1GMH6o;9($3iDM7sb!V4 zc{n-J5CE|MsHlOgy(FA^YKRg@o1hi0hqER<2x?%ZL^!?G5OCpqC_yXG;jBqRlq9Hu zl@j6HT0;PEK9ryp=&UOf3Y@Ot?`?-zYgf^+JvLNQiKJK52e%9U>^J3@PCe)Qr|h@$Ac)BbGTZi zK9+rQ#bWEn^7_HkP8d{;Mx`Yo^Nc4m-JJ~kk7di#H0~~gea!mEhqq1(Co{VUTA{Ak z{_bSvh;TA9R}Fk9!S>HGJDGWVIGO1PYFb1bUG8M&$Z#^#tx-zo7-akV%)`k{Hx87b z6{4l=h%%hBbUvs-R4O;U1WZ4IR`5aDtmj*x4(BY<=5bYn%zl-wIChq^3THV7bp=o> zrQONQJeEdRba4y5ioRt#7t(??= zRwD6{tb=03^EYn%_aqQij2E&*7}vxs+b7$gUU=AY^|rU%GWh)aPvw7Db3*Z>c^-1# zfXcq~*YjrO_ujc#QLcd1;Oko*R{wYZ)5pKx_|iKV$&nfuU=jL`I-9dze=Zsoy@Gm$xL^O zm9v_hbg6XAyOWu9IGH&{HA4b2q!)n(~X5JP~X4a}{6XE1Y zXpe9*6Js#m54L)H?4f84`v!1-meY+|_UbmlQ2_gN42F{@uFb>ABPWM5Y%Z!uxG_i# zd?*o4I;Dgg=St8DG1>j-LKr3C#&qJ*Sn zL8cXC)?qh6O`Bl7W!V?b{d>ORoGt1pYu~s}H(h zT>a+Yse?La=-C*J*8Y{-)Bl^#f9_88zVBV{&XI8(XzW@N>MEYh%-gjq^~SStVSI$M zoFJkGvbH8=?<1VEbTb?^Eh6cO@nmKfA-yv8w=A1pX2nxy?pS|gi}R3qoB<&79Ffjr znA?XH6aRNyeZ#h=B!pU}Gu-5jPOdKb$)w_tN3QLlT%MqU%=shzw}kex?+ahsPGE;X>6H4&>U1&ieqQ=VA5f#V0 z_Yux=x;asNC=o~S+zA=y@%{m)kd`R!T;`04`DgEPHF^vpak5dUWy7 zw{PfZ4_8{hFFwm|-)ej@;{3&mEx$dXqoY>Goqqefy%`<0LGk6kEmusvZ}*OBlu+OH zF9~dPbNXZW^I63C-sjkr8!hCG}PW(Xog zg?IOSD{FOiM?I{*{JnAYA;!7{xGi)LU-&C-P5<2u3e%b z&sTE)!^>F5zo+&LMc03xd~4>au{8HAF1$OcO6XF@Dt#JtUv&yNs7b4@|;!-OUDFMX@=?_QCVq}Pk`=x)Y|t68ITAcg)Wa{e^!gTU%kc%xXH93A_cZj$I5k$vUr>`_WStWUW&9=#%J&jg~h`G>XXdl|S zOLE_Djgp62X6awEz6{0g$mPo*y+|Ye%k~h+h5Zx+=N~JY`1_V0b6<ebM>@vh823X zG{4&x*nf?;hk`&Z?kD*@41h+3GV^-;h>NI<)?XnZ}&3>#4xzGx}4Ca#7vJ9cW zcH@JsKsORfeqDS2iw`WL{@@W6Bao|58F9U6X+(=w_SqJ>gyu0{AR-$}5aIWEv6aL1 zrgCSfVn456h6v>H+p(fw|LEDXri7$lHr6Y2UN4cBI9r8tE@`drdvQ1Wl|s6E$5!U| zAh>nqYi94(v^L$Bfmxps!iDIR1nCdp3Xv9h6w&zbN2U$Geg2S{6QzXejS;@L-~K~o zU9{UyHDOU{ug}vp9QSx@ef|pm%1!-aH-(D^-4>3$c%VUy`L(4f!FC`z2v$9@P~B3h zkt+Rl4}*}pkSkBivmbrBR8)RV%XAs>xZ^g7Y-6kJKWnuPN4+#84??)m3f8&>A;7wE z-&jPAXG-a5tBqEnw1ah*5yiCpZV|uNXsxDOtvrNqF+%#OaD;GiJA@|dF6ySsb$Be? zHSb-M(^=*W>}N)Z6=+{FvUSv{`%j5i{wcw>LapL@5l!>%j05V46LrIte|0tpsSCNd zCb1jc1sFUa>hRIE>g3j*VLBJsDwbWSb>n%3WW<)XhyuJMo;g`7u}BaMexyXyJ^Ukl ztju-BOQeMBl{TSQ2El#P)`l;<_<$~UcB7EjRNl$(&I{YbzxO-ROwYQ|jE_O|&CSIL zow4amvwlcPI$}ejxqkC^M)Vo+a`@CAzpC6CZ4E+7(h>gp(Y|P)&scD`w?^U0z_iq4 zZB-CLxVRlcTg3XyTIwhJUFd0r^)fB(D;yzQEJJ9E2p$}wC+u%$tScp0FVkZ6!V$v7 zGK8kQWcPij7M$~-{-x>7A@(iSi}ENd$+-*F7gZbRnk9;RGc|HCowC&>efq0$v;S0` z8+Xiu5H3deJxKGq+39nM=qt3_>6>;i?OL8cBIY7Aw7l=6dEv&>`WPAMz6A1OG|Nbx zp7WR(yS$a&mN2^|^+m~6dioufmYrW?}H4!fU{qPU1&C?4b;xqkh zF2U9!LhR-tf^>v%@$cAj|2Yb|P)5O8NeS00PeM#fO?g`m2yD5M-!0aD|%Um9X; zB_&jE%*C|GD;yzQs9~&?cKs2119ORen9kFVd=bLMS_y4sTvN5R`qs81F2Q=4PCeZ* zrXYlHu?(S^-yeg}YbYI047?@!?dJ@gK9>j=&pz#cZ>Aq;$4?WZ_Gha(GtZ2EKY3dogm5vUE9 z{GosJNj%oGNjP@K5RD~F%d;%X=9UM+rd3VC^(BWgLJ1cl`1h2IbcB?oAwVleG_QM3 zbYN#YBLfjgOPiR#V1#h7Rzh1u`CaXzAM2cBWJn2X1+)@N=S4_K8UlKdF_TITjf$;n zV$P5d0d#yyWn~~DKhI!!@_P`}+1M|6agQe9m(z#n^tBfH2Kr-4v3J8~SNDwOO|56N zlDg8-qG1rc`|ONx@3Xf?XT5W}v6YmhBgAg><@%c4!jn&*70tP;rDxrAg!HCuxr{?; zp<9uSeUP^2a28`nt{~i5Uwpzwzk_x6*B_~(vmP~Pap={8mK}gtgeAmtdp18OpO|%< zKDd3oVtR6s)_QvbOLr^NgwIpVo*`Rba{0WlSq~ z#*!b`)G`Ps!ysI}`5BdExR-y_2UaiHgx??AsYb#rC&5UZEQKb%QrOFdm%Oh>| ztP8f9HVN8lRqojzYdtk|`l56$Z28XzTIksqu#AU3-x6MO(S!P#Nwbsb2;o}Ma*z6F zUt2xwa{gLq{oe-ZA`j2ax%$yw3QJgb(FAL!Pis zBpq=s!;U;Q-~h@Nn3sX^;<(gSnEcMnq0ngXP3>3((4ub0K&H1jB%ERB}^ki zEN!*ofBCNfL_S(seh*=|q+YH`+DGv|od-vwK3J7At#>zXJcB&X3S4`3bXDegb#{%a zzZhGNmS(i{tU>6zCofrgb*UjW5rJGxi^o_Q`>HpqeQ}rlH>UT2=niP=k77HjtILZH z)%$xdOr#^kmvC%S#N_|7qG~H2$~?VzMjft8>iwRcbGAKY$DJ?ZYC;_U^r6f*v!)w_ z)SHeFue9ypfB6sVVp_Q1_mr1pry-2LA_8s2ymrNb@r*OILCcK6-27(|EL}O^ z<%>TfOY7?vCUA73MWG$kANJ2a=K#XY=VCWNI2kfKU{hT8>u0Hdz^2H`NSheLqyA3_zGRrRI`5E^8ItlU-78c)4W) zJ>!;IyH%wMt#tS9>qDkDZEWV|_OpY>qS+%(B$|F-H4{q^F@e5C{>DE|b+s!wAN`T8 zt)k}d+5EMDQ0ekgGFJXOJo@|ez}Ns0K!?7Jf)L0BG}X-Qc#GO`%lB1tL3af*l#kd= zZ!tFX&#ZIV>!;U41ak534?fjGcUZWdWR$6NV)3Qf3lmc*7GU#xyVWh3E%cRtFYwLuP651_g{@NuwI;%=!7%rJs7f2LW$AD$w;#< z_uyZr2YC?C4nz=NG3vqQBTgh|m#AhuQR-!R(g%nRf`#K6MX&ZQukXFAbAq|VCg_PB zuG^y?UfN23-f}(3X!vfH9y9#b#FR>1>tP8Z{2siSY<1D`qPl1C-cNSFJx@gML)k&F_W6POo>`;Ag>z3cGQ_KyOV)Gr&>*<{wQHgpD|A%x z_vcK1NUs4xp}Zit>8#tM>KlqitM6%;WPQb7v0gw^53VI!ZP-{e+SWrSpu~)Gkq0$V z%hB5bVdnFEyq#poO2E|8Qq<>N?I>b;Q*H}AW7hhR>D52B)aClIUpYiJQ|Sod;@_)H zmU(x4W+VN|n(|T2!}lk#1nXUM)?QWQTG@r)@K0xb=g!~5uj6Q0=a;u{@8cTDYa@-MA#d&da?|$D7QnNCeR9W zCiBzGMSUsuiob}6C5S*P(ETW~?yF?o+K2B?00P^ge67H`9s;>Q2DRf5$=I;EyuPv8 ze+@#sgc15v^PFkCMA}E$Pd{6-*tI-Dt*~DH-62RudJl>W=E|ox2@z5cPCnx*%~0k- zgriN%orXTb^Id2MBEq~{p(f5NjivK#htUcV!UfurR$yJ@?V>x{2Q{QGg;b!Ktzl22 zANCs1_}oT(1tGXU+&qs6(yCb5!TQQtJ;Te#&B#r!SH>WsJwzsyn0=ef^H3AX82{vh zHTzj_H~U06VZoN8$53=M%?$JY{$2eu>pHVTmf4xPa73j%@uDjR>#4e@T2}2Yqm>{) zhM7ymkFAV%Nydp;*O~s1UIQ7XO){g>_cEwIPB!XEEef)^g;E#L1tS9BGJPQRvOLi? z2%sIgP=fxNzb9t1R*VQ{r_Qflg!8NJ-uYEWIKOgSMk|N*o?h+vm`~?d8EftNm2j~< zS8qND#_?aeR-y_2UfnytI!@o=5x>OeS9-&i z@X4|d>b@`JJ--sJ4{0~>FP&dKWX`YtJw8a+e`IdXxS_oimY^o6q1Ec9m)kA9KcDj} zC&O4;tZotfFaL49QUbag#CZjtUr8S@0{g~UH{_b_)1$~hgm7V-3PdR8LWJLgjH5r} ziDFSkV1KxFxE{0s+j2w*7o){)rfOaZ%paC8jR?#Wi@6XXcC#}64}{szNk3Uc+mqvK-POD1B9Lylq+UF$ zv8PdQ7jPOS_4){I`HFod>b!Zpfp;2(c4OJnPevE_nrcDk_?fB!;R?$H^TN*dbo-K*@@zd7zaJKYme71BMJ<%V{ zI+6JMfIVB15=8J5{abXl)Tcb3EsdqKr7z)Z$sx?y63UaBg5U!>XZWOO>TF36EJL__ z8S4nqg-)aTc7CNgaGBEx(S#Ax?THt){5)#MfG1BR`W>=oORlx%nN#HX2tHd{PiIS) zy0axgAQ#K-5uYuMo;xI({KKx~4-Zrc`RTVQoGpoUeNW6;@l|*Yoh_YoXG&02y zo-K`_v!zWN?AemYK>ILSP0TJ8{Lqm9(?|^AT09qEAIoBIpvaG!#3HorKWVY^qD(baxzR0N+0+#D$vDTVp{x-PSu_`CtN^hOGDh*l9ZtLu{^1Xau57BOV2xFY_i9rZE{gx z@Dgtn&|QGnuZi|XIy(I~d$uIK28aUAmVS0;OX62Jx&TeH&ls^I!^*-VP_jJZ+(dBAd>_)6SL7XG{Ip zl-KR5+p{IHC?o2_*^;!+w0sGkEr|@Qms{=-BqO~CMF#j1_9h`*fAHSNoZ=wD(dNn9 zY3L)&*^(fj9f%0?Y9$thUNc(d+YX}@B7}?4qM>J9bCw|`Xdl#&;=AZ9<3yv>*^(Ov zMt2z#Y-u;6QacJlAQ#YNtDi3#thd$f8MYm7&z7)W8H0cz8G>jteug>4k@=jtWUfUY zqc3cJR=egbI9qZa?pYMk^esI)TY8_)eXf~p&z9ubiMeEafZa%|>U6fWKhaYizrmg@ z2?Dvmx`g2Ks|6(EKeO%GlJpwLz~^YP)gkJSTN|d%mSjvoy#*u8*^(ewhRpLo`|U7i zOTvXRpiQLJzweI^Ke}q5c{1WStA23Tl4*{n>bd?)_5I_w>Y|Owe!(Mi-cSt>_BBrv zSi9(Z1AE%nSJD5f(V_Bv+l60fHg~@cq z)a^_ULGNr!99~RX>GBN!u}_HI&E51>68J+R=?BDN$vw44~XzvZrecrQaccVTpR%? zH8H3BnY)&82_m>nDeHc}t$$s@WdDz>%O%oN>DEmlUOwykI#v2^Tz1kSqy!PZR;!L| z2v2>ZRaEAMt={P5zM1RpU1F4`ZNu_Qudn+L$-ojsu+;@kIY#zVXBDx#iyd4@9sHMYcseJo$=x zo19k1++9@Egc0&PJ#DYvx48d3-HldQf(RVJLD2t#uWMg6Rp;Rc&NX|da=)a8C$Msm0NW5u;d}e;uJx1u znSWuD=3TaKJfaYdb_;^{|Cgm-uGcm5_B{iaA{W-{BfeXIMRb4H#(M6V7cWiIByKrc zgl5sd9t~G^ZI#$|<{)n_L9V>kwHC8C@8`kYSEPIXf8Bi*F1CoEr9b$;_AWATg-9d9 zo>wx4{Z&esMnq~1j-Z>Y3+X27NOzNU9Nc6TgzvlOj##MvxUiA>=qr1Zb-cS3i(Gly z;oW2f8S#i>4dr*%KJad`N(pjdn+zhro2-bCcCc1L#|Y(a%ZAbp=0aL*SU5tsSSz6! zVfrJRDK3F}V=n$Z)gKPQ0E57G2p1!;9e$r97tUQG+f*IUol)&>7JFI&BDO*vL|np} zAVTOE5#L^hcEl@y-}2wTudMHVV5d@x?JaE4m$>2;0DX+UJ4iQKThmR}huuw9Xt@%3 zKB6bxWc`6|vObw%Z?ek17H3hOgZsxfS^LpV)?X|IG%Oq;Tr5Lqi=Z31@!eO@-LsqD@`4b; z#Tp9DGE!%+Tmmv;F8*Df89YRGIzqVkcdtOk>MEFYz=v>hA3#I+l^m6qm?T z5!RcI2m-t(EH)vo*q4|Vd0cbB2;pKGLR$phuay$4muazE;RxYk8A8Vhiz}_jP(lr@OC*^11seT#UFQzWciB?>>nI4>bt~y1TDZ z!d!A1fvc#s?x|~Zb-hD*`&`R25WgtRISOy@#R*b>B zuZRFziKVR!L`VtC07NLiTLj)@l@dk(9iJNJMdarhjF#W&%k?WZCL6459FE#N*gI7t zE(Lu9{ZVSe(6ICFGo#O1x5$G4TY+_}y#H!=cyX`jvR@MBwya1`U)!ZkbhI@6jqsU2 zZ;ej;YH!O*NjgI8W?L@f5L+m;Tb+%q?CNYWb{qTeI*{t>B1XSU=o%!fHQntme0^vx}!o3l%qT^}Nl z3utQj(X$qXRR;Ff3qRRg4Q+z$z?y=f#?#ZnrpbQ#V3n?(R)|0i>5D+`olvDp-V?E% z#+Kh6wz?xyJFc~TApH-%Kw2HxR!(1hQL`wSbMA61;qO3hC}q78YYKw9DfhCX3@a>y zzot2K?IJb*wZ@!1TWIse%~IR!?>>URtSKc0AV{lu^zF~J7bU{Wo*K&E7me%XZ*hMA z=}L9@-)4%x{rTkAmNq%P^@dp))H9S-ImKo2C<+2=ve}>n0VRm=+GO)!5rXuiTVg5c z<{PHcCTJh=;WtcCE8sHOpxr+`%LM7>+o)n)AJOaC_R-;Mi|e&3|631BzzPaw2SKe} zuhhGAZ>hvxTTG@{>1WSAxBs*!EIVqIYWHI^vQ_rQyTU8(>858^+>irWg(%NQT>s<6 z(U6;(>JJutm4hXS*muvK@UK5ssf&-WjG}+n&%JK&#>{mTlYSC`U+DA;EdWkNdd#jll5CL?EXqw?p zZLFWEf2Em4!HVdwAzGTEGQ%pmOtm_CjJmt7hk#zgHU&YJnwuC%&$QS4@LXN&XXNr_ zyp!7^dg<>AjaJ}S3eoU8S-0WlgE>b_bxJIFEz9If|!&#dT@>#CbC;mLTG_&v%9$`{$@@{%%hF@#_4_ z(Op;7i(2-3(L*5Dj9YhxV~#IZ+l$>sh|gZQDeCyy*Q(O6zeBKz$!c}>(j0Z#$1Or1 zvF5}p$n6(It-P##4<+}co=ANil?rp^!6;qOpOz34IM3;dn!vU>O<&7--? zS}sQfa-qB+n0552dS%{s;iu#7 zH**QL99s*&Q=k7ab!6gDpDf*J&V4ypf(YnMLfmk31O3yI3PuK&6o4SDN>}e0eL8Sr zqQdGm-o6&?2C@lJXV$=I#=E1{xW%vM)*8Gc9Mf)vdT8M+g?n5;kXDBpKN_7eVgyk^ zfF+0knq(X##OZ}2Jb$C_>9^>w=l?M!ta0T#b#TXu?eKT6GjDxVKhb+c7@WFl8Tt|; zu%;k*~5&rW>-xn6CKkn+Sn^ym-IwFt@pI*pTlw;&l+P9N&y(dW8!^_iTNbOK= z56{+3Ap+nsU#k}`Ku|lT9e*cLG4stZ@phjGb*J7`Zl(^&hRV(0B%}Q)19Y)RCaHf` zoVFYhXg5TgKG&|#v$3QA1ZmZ7<$&l=hi6F|?HQqk)Pu^+64)j}eAl*LwEE*0!{M_- zlTk-n`^m#Q)K#bFsz=^wo7N8Ul8C+JWRX?uSFshbwJ6W5YME|T;|zJRO|VTgmngTY zk@kzLjZG}h%1AD2k`-YIBD%EQsk-*eQ5A~wygTwsm1z2KwcKAm@Da$h?faeT%#+L2 zhyU>0{{4Uds(01;hZ9dfo5gzu1$zc1dj=md_^THa=f3n!=5(5=5rJGNkDk>g@2Pif z?>32FX+5X8PwM6Uj>uCJ8tqbFUy`GK{gwAVvzlcm>UO^-v7$+q#u7x#{dA{#sb7xj z^EV^D?p7<&u*2BQA3pFA$VIcZa%&VJXpPctjpCh!_^ZNR^AVr?`buI=n+druRik_< zfIu#k7XPK^iTrI0X+y}^oXtQ!gZsn|t_Cc>iE11NGax{wQfjB+9muAr`%GAtT8Z(1EJL65GlgbhZ>;IA*UZ{pTt*foh^%U+F2ikN$UA=HYL% zA}m3~;WPHCjxW*4i$NSZ+GAPUspWD$rHCy=AQx&&U*>-F^~_;4re=Pc)(%9V6)4vE z&UQIvUtX8F>2Q_?P57k9cpsmUO|H9FZ6%8gJ<8`k#Ws{!UiIdmGoSr7ORu|Wk19be ztpB5VN|pXdL;PE+f4vWq2QynAFweE()%-jdBd{i#6DPNd&g)^n>4bI%TKR~lFRK?t z?^o9Qws&2QC1@W&Q-9RB@44jMJG1m@d;8ZxE=2n+e`xx1iPD6a(xcxpL?9RTQxN=f zO+7txc4gh6OV_$sf(W!UeTRNxD?P85X?Zr3c)kR`Q-5TCUnM&C%sOWF!G4C`fZ(H3TwcdL$?AY$-y2yo^ z_y{@?R&XM$+=;Ns86~H~be5^y87Z{`5m-X!u!81ORY6cYc=myFQ7Pe*W}*3{F!ucT zM3|(R)7rSC00hZ!XRkyB+1Og3`9wI@(5?n@h74R@%K<^U(1~!S%WCC~TIBNEL1*Ea z?kt>hRK?Ok9=4pcKeDJo^un5nYTW$l`muqd>OTHyq|c=;?PyZX zWVMnKeoiR*aimsPwO=}w-{~$ug%L~k)y#@kw0S*&GO%7BeRNR;{o2kQ$h zkGU8j8e*G*;LFmL6Bh&n!ijAMaV9f$;A6_RuwbL<^G{lZ>fUocF<#m3-cX%Z{1fW) z=VxT7THA+3`~P@1!QR)m>0)(Tqq{sV?%6|i7psgWcM)PKA!-ofTS8z7qorQ{UF6Z+ zUaYUaVEy!PB>e5jUv_l?Q)soHK*KQ;Y|Wbj|r9|uR{ zX5GzPp>QFBf0vr_BBUe@5zD4=SFCSTp0s+tv(YM+!8z_k6Q(=Y*`#jT%J*3QE?qf! zEm`+@vM#kYgw}@ATJrqx&Se|afp<4r>xN=ovPmdbWLgkhlUUtYHx%n)NjgGg+qvYm z3K`*fUF&9|bVTs)YyMiPrVnjPTG3phrxBv0Lr4iCm=x zYn}%bY0~7;wrXOLy(+iaI@RE|ZHDQuM(j#rz1R*P@gyNGuRmPxZaFfE z_CZa2#2;^Fs5K3T>r$njGFnMbAs6qjWFE8Q{Hp19tEYb)Z1V7eC&se@`izrWs z@o5P5rToyw+as8-;(F5&=)0*m`t0q=b2h1;f81?mwc{6TQez&q^o2Pzm(1d?{L?bd zPr=ztr6YukfB*KoP3qn${FQ%)V8S4zgt-v0t@dU${c=EL=Z6q3MsIv%vl_M<5Ddsh z>Bz-&ozbBS*&DPb-|NN<{|%{tB$am8~u z)568H$j*z9l61tq$7qfE*R{iwfe7JZbn6bA)%ZUD7ecrgAw8Q{D=EQxnf7|n(+Uy7 z#R%ztPX_mSEFHO+Zkx49eN@7Ei6=u!(h=g7d1W9%xEL+t#zUAMloIAbgp4kVVR`S9 z#iOzpCa2JMYiWjySK?h1$g{;?{bK_lt@z2TozHmdfo@akN2$>}v8p>LRS-eN34 zMA4JG!#ayLs@+o=@y7L;HOCHFn3zonn&Dy@h^E;tOwCs%FRz^Z(ydX5KrUYAWd^r9 z{TFC%FJ|ZVxFj7Rt3(jAuDv$5yIXNshO9-ne_(WK#o<+rSDcew>gHleIwIAMvj_CA zci{3q$$d}T2ndmZ=*KSJ8y=y!jM<%eRjYPKc22+hdM2w)wEZC~4sy}l9?I%Nc`X~B z7M*kFozciGQxe>Rg23KHO9#QZZ$Ff5|UJ~6f zb~{)0zUv-b|xE9MYbf(Sl=e7t$C zy816h{5oN3jV^A6W5jt^tyal9H}QL5HLB!lby25HW(SxW=WkXSS+j}#t}{oA#QGuv zZD@P&e*^ZZZ>Id0Ju!YZ;9kRZP}bcbm~(J+ow?_g)C0b3m5#vmJVpn>Yg4nU&Ftw&zPd~MF8t=m5RhTuzJ%g-?wjI}J4A<>GE|&)(TwIgT z7O|^)Up-^e3^Ssngk>O&Yi$q|gb*&4A+(io^z^Fwha{YPfwZiNg(HNEWe9B% z8*hGAeZG2tks&241L@RS%b0=?!o@O#X8yE2T-!D3sVR0>Jo)xD>XIugE$e)YV1jo5 z-aLp1PlmTI0j{ufN}jKkhmg8hcSNML+Vt*qi|=zIipE4JqX_p5G(O^;0gb`+*G4UO zDSh4xPw~tUufj~rxbxSKT}R7C#e-&g`2U_wVhOG|SQBNNI&*rmntDtpy1(loaQA{} z8d0zRPmLUXj~;d9+ezfY71>8T+GvRGf24zIH)wD!BCzF%rtf&YcQEIY)O;1nOvZMT zIm$&mQcPdSIu^Z9`;bxkyt)Qf%NBY5vKk`M<8fhFmP)cV05 zxL{7TdeGq4lKA$u?qxew z+ls5yjRi!OEtX4elX0v|86#^m@F8*E6%xCX@zR|G))pHc-GBcp39eUW z8RYV1R6Vy^)VXf0sD{c;U+2!7@B@4owXCL7{S5Pmu zDVApt0U+WMMvEq_q0n^GyW@bU;xo^MJ)YZ<2{EbOs6{^xfHR! zBST7<3lY*jgJ5qrf5e4e65EG=7un1hdppaBOPH2=nHG74BZP|)V#B-$DZzS~7P|$( zis`G>=J^js$>*+6czXaNImpMtIahqFR+Q%5Qi*qlL`A-Bp++p6kjo_!b&qHt(Q8Lp zoppY*sK)Qla12Wv$$>Ix+{Cw9gP_!c`}M@}2g1xgMG{!zA>gh9x19EIod!lbuN!A( zYG}FVW7r=BBZP}>CA5{%^@gjXNA}j|xg;(jS_v1^;yr~Ugo|quItcFET{e1&Z1u|( z##ZsDefG(>l6VUOZ$9{li{{i)pB)*Z$8?#OL@u0he8iSx#dWdgCMEvOY^RZn zEh_%XwDhdC?%*4))}8j&=lKdpYCMYAx-z;7M+g_!B(z2RbJsw9(+%Uy90lVJwTk8C zMS$+{xMQuPrXbkSV@KHNwKo#`zI{NyaNE}K=4$Iyk;PkBUOcv$mYRZ~T-%n>yHiW) zVU1cRaSYZU}xR-%cI zsMK%c`@Dbqg1$bCv17=EzF=*|h>r<@T-aKoV@n6YRU6-Yj}g=JB4RFIM!D`ebv_}) z{k;}?o{06LzXieT>ncS*9L|geUHQB>U!fIHTgod_^AdI2hyhWhoPOR~i}kX+l>M9hWqg5Ze{hNxc$?N>|h>J%LI)M1B@Bwv8#;5zPSUDacN=Z!S{Ndl+u@=DO-(`Yd9$qO?T=neVhJLA8KhPC+o1g+ zX{G&=lvaqQShbAqOU`Yc72P=N#Uvt-i*4v;ZKsusX!H=s#dNA26rU&&bV+zS%@Mfr zW}M?*C031OP<*09&?T`X9pU2d2tiSkNf$NAQTK8xZ|W5;M4K3|To>bIz5(H)!p!#> z+?#RpZ2aKmvYfY9s(kr@3S9gwY z(5e35(?J(CnTrUN=gZ)mNG_r=lk6_>t=^d6-(A#;v#yJ1Gzcky_gtQabn|6uMtJ4T z!}Rq7zDmHEW%x+9z2U-^>(oOtU*?-O@~((v{5>;6z1ne@{_@;?NEyBe>rX%8+i2X`x@?y5lIG4KE6NL+Xnq~M;ckbPm znLpe+7DKx?%G4i)A%u&ya?vUIAf$x35aHg8{~rk9Vzhf-?<4rxIhKxGOuKj%A7P$r zr6e8Uq7(iPgm5w1#X0y0qZP^!E=I__lGnOYg7q>jy=f5M82}*SJ|~1k@>s1HVg9g$ zX{ncK(U2MaH~?rz%*67^Pd*_hO z5S5FX4EL?tqkg)Qz6?C)32Mhv^@r$kx$VPAqYvd`2_h&yK)I+%Li}&VPhsin?u(We zos>iba`9R#Gau!He5c;xCv2Q$ge8ce8C;^1NQS1n0NZSwrMJsKw2$Cb&Ba;riWBck zkc)p$?J^j_tJ(>Q9KaGpFrC`HOS=G%%-3u4?zb~V9 zW~J!eiHT_Cf)NYVOmBJ?jPv9fabWe_;*%%<$pf zZV9=_E8{&8^#w)mxQIscr70Ij;_brVJq3+gifGJn5se)CA@7$x1iTX_1VuD1auJPu z3p;f0)y#LCTr5`T@0KW{aj}bN zSTEDKa>g-`c@VAQ z8Npk9Z_j{h3Ek$c7^(@oAJT2wyqdr@9M=q9;pF)$2r?@b(Fdm7r57!HiD#dt^XPWt1bGx=FfqS(B(4`tJ-R-+*iM>Mt>G&mCx$c4L_AZVJ3z&78Lad8XY zT1&H%#0SuP)rX?I8`y|O6W!(_2RsDIwsC!({VK?I5shZ{K~DtQ+gbVu@doxpK*TGxJueZhNP7Gn&a|viJO_)mHrfzc9+#ve zWY!LXDPf(c(ZU;|_CX7dHjKZ-M&GXqC)LhXzrN8nr1v|ai#(+Mm`Ps?T~%^;v><$m z<1*qE2Q~2#d^>X>?fTZyt`AonTuZPf`z<|=raF!8jA98Qn3na?#6VVeF_7M>hMKU3 zsg}DQQI>1IY&=C0H-hE-EaAU=cO+( zTpL#0(j#gz@y#TD;cdtG9jd|dRq907O`(riKIL*x>`(RuWORya%n{5?GO`4sI zcpTX$_CBVi{|iS57h6|oi*Qks=6e8Ag7q>j9#c3%xLAhJ29fQeCe0cpC0H-h;xSf6 zK?vbu8A4kbE(X%bkP@ty>6BkFrXYlHu?(SURr}{)IPCVW(fOCX#$FPyYD|kK;yfP& z#YdOXyEitE+P0pMq!_5s#Xx%BF!d1wKe|wFy10dYs=8lgsYE_c)jiXMd#BS z%h%|wBFaE6jyu^=?Rr?-;KL)aSMmQ5=4A4b$gikz{l#N^BBQ@EQ?3!ZH8> z>j%XrE_3mT#!I9wM!?Dt&&RgqEs1gue)5Z22Op<5`s7y}eQf5xnb@n7cd(7ft0O zj0~xZ(Za>F_?V}aks&4N2(KMHmt-@RxV+gwxcGOG&3yjuRZ5r(5u#y?$Yu)bVp_PE z78~Y8NJ%^o`^RvExv@~KM4AcomESXUziw_Hp3wTXS*QSU1_i` zb-cU!?)ABuIDg)ZKV9*R_Z?x@O5$&@ zeRP{+d%37p+osVkSx<9>P~38CEz|xC=ORoMSrk1n?gRc^tj_&G`)V7L$_S4O`(J2_ za1o|v7L}4Td7kgmmm_RUY90jmaqOWK{kgrIZg)r1Xmf{gCN@g?9Op-WPCQxm%;@2s z9rek*&n0li!3;NKLzsPzeD-|!ajX7%(#bgqrz21>qwiQoQIe17e|eV+Vw=Blvs{vQ0T`#A3o zKjTO~9$uZ@zJ#p%{AbXYUV?ub+Sw=lTDCm z%KB$=912bE4Nkj!NtKdW(duV^-AtRXP8kt@|^s$TWcXD~pZg=9y zg=j`GnytWe3c>$JN)W-T9sfSnWGo!sqC@oa8E5PLedjL?pV}Vo>pWVY^La}(yY}|* z?xCY~bl7GrEOU#<*xGh$IAQpM`onH-)kOqqi0B|V<=qqNahFZ-ampsBT94L6E81*= zVo^p*-vq(>t>yIZl$E5(LYqxcO4v&}-DEUTSQAA$QH1GwIu+(t^St!&k*Bm|6Ld7s z^Wi%`+24HxmH-+Nu)|;VbC(ZFiKXV{JlDK@;$N44Fh&3u^b;XI>r*m1JfT%|o69CBeSo_Ah>?`Ba7!7JvC!m+ zlRn3O_7ReQF!^7be^9hSgx?>nUu>_Ry0m!oAD4en#vN+qBh<7@^w-N%`3D67eQxp( zifqaaNcjhALjFPVSF|WvI+cI0QUjZRFh)SHVVi=W@{My7&r$xtcaGTngW`$E<;&A3*F>Q??;!-gA6yOj2gR>I zE0m|~EV>5r4~o78AV@})kMGL8x9DxjV=n(-yFsJ0|Cgap1(LmP1fah45oH;T5t0YNc{cZk1K_D09`3Z~F9;I#m z!BZ#S6jj*#wHhg64>c#Q8QJ1PHQIm$n{YUX0rZN_aCl-L9cAQBW3-70=qMj~eq3mnpQCJ|8k# z*X+zUTyH5lMqM*|puS+*tZMkwfKL-XqTA?>de4<->AN$pGC2-K26FvXpPo4fjn-B7 za~}7-lcuQ>x&8F=vufAD5=5Z9AlR_AT=WM$8yugit5XY=vlZuYkDuu1X~NLr(Lj?{CDwnQm_^UE?e_PG&_2}9O8l6gik;QTR@CSEdfVsOhydE;j}x>- zI4?073#Ft01ZkC?u~1shPxsDuO~yj;o*?*^G8TSK84Fj>vKb2n!B6phhmF#bu`tyR z@~dbL`BnA6W-Js0wie}?buiPdgC=94)P=U9*+;q6j%@Xx>SGhX4$nv~cNq(%1QDF0 z?xXgjw9QyJo-!70>s~GQXP2>15Xi+D+2+^=dxSCh?2QSSYJA%~48bBF+YPUxQKFW-MHN zTXv#2Wh@L`#zHAU1n1QIlvXvHvG6a-Sh%otDr2D_kc;Md<<=|v>lh0+Jeh3FulwKj5Vt;tv@_CbF| zE12~>a_hOtSSSb_ABfJIu~2#nxzNXgVBPQv>W>$PMe`QgjD_OW=u5suXldftsRI!D+Ix| zKJ9WAytpp&Q?c+l+0^Y#J|=6$WxmJoD8F9?1I8TSF8 z(N?6@@ZVc~z;E0~&|74FhyBCfV>N%(51%>s-9+lG%)|eCbIA^R@7%b%eXAe7Jy!FV z3h@mFzI6(Mve#5jyhit(C%8<1SI!@&CDUKI5~HoB`NnI2Yoz-Ia@{qkrn znf_jzG+IlhzojL{>r|${@uel%ye){7z3^^zEIW zD0|(zEp4Vhsh48{L=&d#pE+LJOn;YNQ#sj{tUJkN`h(Vn(pu{O@TS@0w9WKK)(yqF zWW`Wy#k3&EZlPG6b{T{a>tabdLS)-}Mf}D0J#-TZr6YoWe|hj2Z8QDxs2xj)jSe9t zh+tZ@rRVcg*5-a;V-3uE97G5gjsI}?@G;tEuOsVfw(exIE_=IJ6#IjJPg$3H@K(z7 zH^$`#loCV`9ZEkje~{fYe?-jX_u!LfR8I7#T#Zv*Zb0b+p1WkM@CZ)zAm_p!OtxA? zwj!G-K_D0ZE>^I6QMT@{4k0CoU|MWQU*rnbW^QrT#k!D-HB4ET-}b#jcgX^q4N8gs zAQz5DyBDRe^{5gKA^w91v;t+-otL35rrdxFU2ee1;MO)bpx7NX@ewP=W~dh%4cA96w7CHVfn2hzQ|g4X58YUgw`1P)e8!5trRMUgw`15D~(~=!-j!*ZJoL zM1*iLqSkfewU-;vbPSeYy-W{pHD1RV^1P^GsSCN7UQv_Q56Qx3P9J%O;1Wa#7ymAE z3@hXJhm>HwOsD#s5GDqIu~ZVT6HE&i(<0l*@DNgxjt~tCM+g_AJzEthL%0|r{ghXR zlwiF~OK%pA5H3cD$9M?tk61c#F&&m2uk+6)C?)9#@#DNQ5FuQQmT}`DOb<#4b0I>; zBi%$gHf8Z>mqX#M@_WMLtHoxfah%9K3R(p{p_JV z;RU&4^o)BrA4`W1#^m(4ze_UnWt+E8Rs-asc{h}mf!@*Asuy+n?)s=}u^|cMqGzX2 z&}hRTxZANUm_ym^=G1zGqIful=k)+q?SKW%u_VzbS{Cne;G zalK5-j8Qm3xY&<{wuph}my8a4VYBc_3D(QB%zT9-go|YeO(zqBbkwuSwb8=gY!*IQ z>2U|ZwDc22e?E4t?oCKz;w8AY(+-)k@ExHneC1shJ{fnqMCuUO? zzVj&yUwfB@PsRr#$n#;(&}i1ddSBE^W#N;$P%Az=JM!EpZL{z-B*Yenz!F68soI&( zjM6p>-~2t37q4+S!x(XN2&5UU*m_c&ayAXuK*(DY#ToBj5w z{x6vtR=S33qlAN_qotk#@+o|=yjcK7CtG#dYP8h$I2)OAzUm&Xe$G= z@JR{Q%e1UMRz^Vx;bIv=Tf~Pw`s%x%wR!ub1nXrQSG6E02q9c7Lue~w`Ds=48OLni zJ}JR^nU>Y3aD;HN452NeOOt2S6qmP8O0Zt0Q>z+d3PK1M%MhCR&2A~1DXwcpiLqMp z_LVqqtd_ieGNUq|zrT_aMkB(L;q7FAD+GDIRvtp?V%-rTvV)-Fd#h_c?ACJ{MWKu$ zx@8)UUOHBDc3^+~xU2K|(RFoO>lu$cZ}RrZ=)@HVS5f+Af8QI!bE*v0uU+|uhroIf z9R%O>JXa5$)JFf@`uQYs;ri+$%6>FZH_RBV+P(CAE+ViUhziHKm@jr z{fge~Qx?A0Toyj)XI!1*{?CJmOV|^|GuUHM9c4t@aGaKVFdR7E!)TF7B}XXg%1(J#pqJI$LKs+_{qnO*YB z!iNaqV)PYXkJ0&O;gb^PLd1n@$LRdC@F7CD82!!(dLNZ<7CtFqE<_ACK1S!Cg%1#+ za1lBb*`_~a-Zf8mQo>w_5P2~on<=b|Y2jk}tF2@7qpkAGsV61r2(eo%g9#%85yHjj z4-Svf`RDDE66QjL^nYF%h!8GDi@)VXNC|TxLj0J%+ES!b&F*fE!ug!WUA$g#&ZiDz z#%P@ z#j_F=;}g0VA4Rv9!@;x1X!>T2@)3Q`s}@zPQ!5&pu$lfuUu*}{BAaa$1Q)+uG5Ydz zo9PdHNg*vBQ#eAn*wR8<#P|0Nj;6KgW^T($32}MjL;AmPgmAG8p)KOczMZ0bDiq(_e{iY^FciUva)WS!EcJ>hlxdYzb#mroWQyZKl6FKNzDW)1RzYh^FU3%Jg^7 z-saI9m+4Os$c5__-SnnRe;wXSW%`4?Ppk=|gP=BL`pcnAf4{g)e}X_RTp#I9!-@-| z=I6H1M_r~rdAdV{uT_V)$JDC$#KOcRT5CBnuicYlHD{LMc){0(j@9(N9pxj`eJ!e8 zV!yp(asx_#AcCWX#3I&9-d_5-s@KZq287uMci}K6KHb{S4G1$FB4FkGxYVrLO9ph( z$1X2ob^wTgH4*0ajXnI_fG|_X^|J5Ex?TcCMa`PjL2q+5mLf5B0L$q)(Rp7 zt`Ow;T6wFp)Wy0ZLSzTQ-IPu6n+6S4d6!L4W@=mwa4iXfEnD9VX*JL&baK*S|!eG~6$g5bt`2SjJ|crHx*cfHAR*vZ`) z#K=_~k3q1VVzwjtT2E%Z_Y6YDHX{5{+njP7CMd_@7cR%4%!3%e>(313kM+@~hi|D@ z6W^OmW->D%0_PZt7CG3W)}>=99}>+zs4sGHth2-*7*l1RcIg83tjmfBeie@*_A&9$ zya*{_>mpiyXGDC?U`Et`_Kww(6;a|R82$N{u{!^(h*H8_htOpD!uAm{HJ zm+*IS#*>$D6pDBQ(@(4(tLYm{${&MYzcnbjBkHT_R(c~BZ*$<7_YpMCBO2#w%DU~j zSb_)~|MV4e{g-Ol|DNda?XQ}zUx-$S#(9NXPH#;hDskvC8o5y(Toon6U+sE1&H@A4WeqFbkZY7+wU_-^cRj599==M`t54b zRm*DXL*MsJqK6|FqUmeX{r<<_NYRvw&Wk)_gvdj*wbjdn$j-7~Zozg)Ytafp@KV1H zi5_bn)5DI>N|zD$Gxoog@g_yLC5GjRZi^9UH_C}b*1eCu4)ct&uJ|r;`R(|Pz9-X$ z`r{>wzW)MQzmdACm zMbS%y4uY>H9a4RdwbgeGo)vbxqha0qdym$=O17q`!qk@+{I5p5UqaR5)$_+sSJh(a zuAf7uY1PDK6U6T&INkHe4ubM@hh=*8>E_!afq-<3hBF z3d?m-VdhH+B7@(6yEo$;VJdI?jV}b*E(X%%26T~fCO06^5&@MD!o^0VBP5=Q5D+zK zasx`eJOJ2#T{zxHwCbwFmk@;_u8&0{5Pi z5D>*`as!I3AY#u%M@!F|9+W6nlN(S<(h(xtp3u8EOOxqOq$2{}bCXtlLhs@%4MKVi z5loA=*4teSq={8STZwfcj*MjRAICtt=r)Oa^el>fW8Y1TqjwX>>AeB_lC%T;inNmG zPm)1VlSvmfX}-54Ud`SoevCC)87^wl!z_otbgmyCOrociv`v6pRoq*49Pb z9|+-Mw2Rm95k@PN zAzX}*nTY+$x2}|6y-cUP1fJ-*9r3Ksv~V#kvW*OFJ=mU+Nl7|FG>j41OkrJ23m4O3 zg&4s^9)xf)LVO`FLQ1e+roBGrc4RXa>q0K3#bcPyKTkv%!o>&|UuJvIlOZKoFVo`3 zd1W9%xELWL%|n=WND0=eIz!D5I;?NwB}!Q z-u@izd9ef$GzUvm7$N4-?STb0mebppAlgUp4Nw=$X>tR?8Wq<|tD3~`lMF^Ipm%rw zp)4_2g7q>jD-q>nJ!Ng?pLBbmiOVJkD`(8b8p?V_-@ochF&UIi@N}0=P)e{~&Zs0d zq#U`EGSuI*hUzC>HbGfAIT}J%OCPaoQ3KtDvI*Y5+GZ0JE{LB<>+?tJRf_JJl!y}V z+H8X2C8)bEg9nI<<>XZ@_EDlGdc*94#HZ<7NR4;Yaj~2RAth;ucs^!tk7GIWAaFbi zZ4oY(Q?XW3!ZMJSd8}}RaB)pSTZD_{)L6nYgo|mJj|)c#7uO_o-fV*6CDb4Bo)LE( z^p$_gCKz7dKKjUI6OlFmc6N}jXaB-H#uVC$qS4-|eS+5F52p9LD&=%q1ER75)!FrjN6|QiEaIp-b zEdsL%N(t7>G_Hd|P!K}6SccG6hKsW_BT7oJUZ!PDEF2+REJJ9EaFLm2L`ezO%e1VC zg(HNEWe9B%F3!@(kP@ty>D0=}n1T?(#WI9uet$>i-rk#Cv3uKVXj!%MBBX>hL4+s6 z+mQj6#22s(Un>tGbukxc7|-BAaN5(8Yjm}-&L*3nj3V3t;98Q(CRoR16O_FHt{J$B z2EkjDP4F$sCOF1r6O>V#j*wX?2>z;cO7tRS6FlUy3Ciq)2;4tVUI5A_xPh_>4sh87 z1%X`HCKH({vF9e6po@(#xdCMrrCCY27zCQHnx|sVO_ZLLuzdtU&w~;>NC>_GO4;ke zvnWCcA~uW+nWG>s!y!1L@erLFUZ zq7_MxR{*A=9THPy+rd$j;hDDOaY;Ht{LMs7hAwI{LGNheZ+Fof*U-IJ4JoQ4bnz@C zgW^kaU3`hR;_zx9z3C%df2a>AUKCdxe2T}l%l06(TupKa>2pLdE&fKk*ITC6bg`V? zs)p@g4O1<5{lT%EJYU80QrgVmjdK%?D~Pxx9U(J@agvDt<-as8i99kMQI>HOU7dCCr5g7mJlbum~dq5yHi27ZZ{~WD7z{m$S7Z4HwVPsePym|g=e5yW zcH7V8)b|g@t=cf-ZuJ1&KX~0W-u;8Z!Fn()y4kxyE~j4mNQ{!NB%4O}b7}vpBSeZl zEwqR5b2)9~unv)8TH62W2$ABFgw}|tpUbIdHQ`{nOiTNFI`Tq@6zdS$)8S`kY8}GC za+!|D6=U*3h!pD(+Om3GSIG4qBMB~&`MC)8m<>zu52$VwImNj+LZHn_O&wVpBoR<{NsC27t=jtk(ayfr3 znWk?=l&3qKU$G>*b^4i4SKr~~S?XI6r5q5J9;V zj-TVH$16H{$ji*s{R74lT!q63N12(%t%xvQAp+(>%FO)G&&sW&@Ct93SnGD{m*KA{%?oqtizeiE(fjS@~$?qS2W~SFayxdydYFG9Zw;>|11pyJv zJ~}f~ab{+!e~+S{XX#KjrXzjc?B|crJ&LP3z3WUkcPtxE&Bf;g6G6G0uAj>pLMa{% z(P5R^7^>QmBauN}K9+2N2 ze)cENQ9Tqpks-=hk}~?XNb&EYo8^L4xJC$vr4S+d0z{N4 zEQ@K8Vp@Ed8zG!Tg!oNINp*-4$y?%_B3mMZB1SR<$-9tM%(vGC2$bS}F8!bGaI27} zikBflP86kBfSX65)&b}B3@JGja)fJlIg@&b?|bz zsUDCusqbA94%W%62m2T9IF!6lJp+KJ9ids?Km;vC?O~uL7CeNXVXDVO;Upl8*rj`< zy`0os2#Dh#Lg_5ML#5QvwvF6~e=DN+2S+;`W9WvwZ^k+gIsMhd%S$=K)W|#wq6F^z zv8?WNYW8E#H&Q=8GA4}o`7k;_7^@}9>vR3QK7A{qSj9D$cxBr3uAj@9IDTON2zs#R zT|dKAk8s$Fke2>LIy`6p55!s{9O7-J`@mR4zsgAm-1RWViXG zpL(#BZjYd+;yLSh20GosceI_#YLs7KPtMjRjZRq&`J&FjnU3AmUa{V)_ayIU6LZB3) zO!&bF+{jdp}m2+_*FM^Uoz@a;RkgSITv zk?rfyw<5~>0Yb=0jtTjqb?8>B#&qgwX}SlC^WNkXQbx$lS^QqrKiic0`LRZx4!Ye@ zBg9_Np--KX`dL<)fu&T#*^S)!&g=S)Lw}AkP74K3Q_Vkao6lX_s)Jhg+~W1j!CY|3 z5jHc)o2-0FUFdwhYV<%&{Vjmpx`0{!(C10VLZ_5FjBZ7&I-*FfnN#wGIj$t$ENjOU zOYIxo!JXpYSSWGD777AqAIqB1rj6UXZz1*Jjdggu3f9p$m+q^V@Na zLYaV{-|NoWUEaB?i!yFL;pY#zb%WO&wfg| z{E(`Vh!ClkwU5~)|Cyj#s>6f`4IZdo9%RP~?vL7)pUAO)A23?A{rHe!m5De{I$Av% zPI+`$GzB?{_3(X2I@Vo^s3ysKQjc$+kc>WIgm0C@wD>T$uY{9`*i84B6#34(c`^QM z0G8--u{C|~UZFj(oka>tqIx8@ppVeLLWI$RvilJQ+cg4P(67f8bV#c)TBM+)E7Su$ ziio(cs0H1lC+nm%4~n@) z4A}nCPM*9VxLn}?I-!3sW?_Md`eN(qu+ckV1^{cxyWNZ36`uOVaMiOxX4v2W0^2FD zN{=U?LyslsH)($p0Xp(RkX7%5*VvE#_L4fiY;G)ZY?pGmB#Adq2e0%O(Fz$kXd&v> zh^T5($0^iwhzlMydl7iS(^39HGq=E!+f?F+BP|FeQIs5iaJV}tqip!;5hue~53~?V zq9?D?E!^*-#Z-q`&BGY44XPitTT~mbdi2=kFkPmg%s4k$!`-ykE`^(Z_h<+?h?t!3 zs6FBRF{*MIzRzoXmlp09tBdIt1caTaFRtU0e}=iw{L7*m(P`sx?KaSksUt50N&!tJ zm!x{U|N5oyyB#WK*DZI{9-4o=x^LJn)M1;5@g3`}AM9r#eYX0j-Ko|%RmS!FBfer! z%ZNcMvI4{1>xN&9wcFJv8xc^h_O75U>-?o*Zs^B9SJpO#MA$>av`7|h# zfW76hLIwh*&~J49Zt1^MUmKPgUXeedki$A8N|+YimUZf_0V*whtYaKEfd=>uTt<-9*yq?PRyjSVe zIRbQ;7(X;@?}H8{@C^Cx+^(+1tyy*PMMWh8!$+d%9kg>kDMolsY)0{7|`1gkVcq)Z)oAy5iv zYQg6}cGm5oU81=(-?9$zDAohLKyLxaS2M|1m(DyF1`b+fn>xT(1_Gr(A6fO*Jq6Ys zrP-gq_C^lV5*eu5vO17e{kE4?SH6WN!iZg{2O^x@R-q++RO+_5Vm-7~h!82TmaGEr>S!0+ zSxOLSAw8d$PgCpa_0slXI|Hp(%l;Tla(N-RJwysL8-Na7C%+`B$9L2o4eRtG%8FuH zK>e*RC3^{<+~8w@0P-?JqC(;T~lnhY>dw8mkx~G?zr<)lWOP*4E3*dbz?$EEo0B zEv_Td9Y)kT-J1~(Tg8Z1Ivl3m?$PRoS94g0Bl=iY{-RokAP~(u3`Eq!cnIMnAo9@B z{`1{-=XK+BL=x@HZ8Sk>TWBslzR!?=2&DM;=HHD|!%DMv<9|^%v0T(AH0>c*yE#m^g)Jp{vfjT@g&af> z9ki?`TW7=4_2R3d!^f)Pe)I{A7Sh=wou8_9d45hcLg*G;U4DW_pcL;svsGLYea~5_ z1)X2Qe^D2u*eXFY-R$r@3@Q|Qx4nb~)c z4lE0$P`A{>Tk~SMLUU9i+CW5+g9wZ_%i5T4xGJ~rQuyH(Wj7!KrA(`~41Xw;|JK{G zXH!2%4kEaI@sXj%u)*&3mVBcLJ$d^P$F>X2{=s;Ydhma}*u61xyn1H(QJc#}`p0J8 z?^;sN1WciKnHDKTvz+{C9Vq1h!V!HeZH%G;hsre&7>V&G7S=8trX~8AwvLZiH*bPd zv!kqxIhXJ7I81|80a{yS)LhC+)PeP|qE+9x)t$AixsF88;eb_+{LVV8=!NP}IAh)! zoC_gRq%ZJ-Mp$_vupUBt2(n7~RykM?^qc%1=&*gO41`Fr7mS*-RaZoa6xTy&)?v0e z`Uk8se5Dal#&TI;Nl-5TE@+lBb)ZK@iV^=WUj^k7B8WHELAe=MZu20PSclY)-c%o4 z<>bHIQ@y{XzQeOHuS<9xg*}yj?|1uHm2n%#Zb>!Yd82t4ZBI2IfW7YiM z8Bug*Cuim_f7&lU(^eydlZcR6!mCG_>n-)>ijEo~92}{cmXfZH5Gk&Q&>rGU>E`Og zezzG`VYy68{jQD>Db^vhhj_aCU^OJCmG-W1uw16a>sLpJ6zdS0#@dV(bRKyxl~JOB zgCjMTi~8ua>1vDZVMFSu7px+==0UVD?yH-h7-Y|U@q(Rs<5Rg1BE>qSoxFNb#OpCD z(Gs@ZU$;X&JWPNHID$q5({#$s0~yW>yL)RLiLoU9A+#>ZLnQP;I~pCYzNB|i+=~`e z9Ixj6+oN%XZ1h?KAySNPPv@jEnrmSqgu_yZSXE*ItilhLSsLC+yUr{HRyjzEg`TJK zLWmUB$wQQ_R7}<0)I#e3DF^7lLJx7`-legvo>gcGT4>aq^1SjufEOI01FKx$s(^zY zW!m%=)#Hi?ks^d6H0v;CXRHV63!W1U1kcU}LY}txck!D>xco2wF$bljwpX_b5fCM& z4vzGw=#Z5cmx~A~iRI`GY?UXRkKY;0Z65f9=)j{)|Njso#U%;t>A<)`OT<5nkl#H7 zS!MfH1rdi*OiTT)ju0tAz*;o14~o4kC6U2&+^WZCyl;opOYSdkg>%h)uuI`I`gx3c zrXJ5~Z+tk-p7law_wDbmQ;DOGNb%_NeCe^OYbzcZetGXnd*{Q2+)tXe$b}FoMx1*ZWjwJYhbyV&S}a7oHO@2?JMCVBE)ZWALOR4&W<+=x=%jS-0*H9LR!5XB*d8T- z&W#$DvPe@;2ZmwCKr&D9TT#K0@zu`cj(q(T-&urChZiUQ0_U zIOk`br6(Ll3u2}^W?%o*V)gofD`n}SRbmOFix*xH&(c%hz429zT0`3=Ge>MssejBa z-*z!)IwjQOB3bqHyl~3O`>**hQA*HU(jNyG`FVYxefhH8tWQTb`{r2duHTvZ=(r?_qy)j*9&<&*wy89@uR`?lo;zJ$n z?zgG6lK&}KFqO-a+M*8BtzE=DHp&!AF)bct+O&$L`42gX2x%LZi?6BkKKL$mH?XC{C>)ZdxSFRz9{5n(22dAGjS%v>qRCaF@sLxDiI-3ncKU9 z;BrL@ba>Hjv^mxm5%HR{7HJdcoq9Bo$Y34Vf^h_L0Il?$Cov$Vt#Ml>U@*CIL} zPU>V?52bF&YX9+)@SC&;z*1{676timGUIRtl+-VGPLY($w##e)`p8!fdH3z>;`wlb zKq=E#`v_4n$#OQmK6?#FY1^d@&bTZZ= zf;}QJW?Adgimd;czK7$?8s>;qXo;y~C*^p3wx@u4yQ`N$Cu2BEi9S=u-;_Z&kuvD6 zt?Fga2?C|iZ*+KgS~0IefNO3IxNCsC4!kQlS9HPnJ_UMk>r_{htL6AmJn7BBF)8{fa; z43W{(y`IW+*R6|!e7I*irst6lhX|2kbn!=J+?9N|7yNuU;jok-I42}BSP+*lc2)%_ zAFijL4<}MQMoL_TYk1OaS9pEdSt0oAv1oROC@~<>P{KJUS&2qOtod@*5l(Ka#G}v#+A6=D z%zEhTHbjUNqs2nQyE>anIOrd=(6UZbHdTW<@$5FgA86a9Pq3%`@saA07Xqb#rg{`A znWoBA@8#S*!OL#La-~NBf^+~v=aI?i%u+IPVvJc1Qe4 z3#)$b!XO`xY2NYrtL0w%#G(ai^H;owe752YyY@@{^z#RD82v?44xMm-CFuU zullZV63Z3c{5ze5(0MD>#vKzqt^BK2yiYPCeAJg-h&N-3Ayw;eGs@?@ZUZN=%pibCHg1uWVMp6my;0^07rlHqDGQ~rHL0z$2W3@Ud`tGRza#1| z%HDZ+;9^}5ltQ$&it50BQ3HWeoGm0Jd9vQWUOt>~5J7a%PIN--sqe$A;Kl~S^;=8v zd!l#aH7~R2-q5L;Te7V)-n&%cAR@O_gZ3}qAnoz_M+hnyQe$WZU; zEWMLSjjEm8+cTN0a#0G=WT7n<8s61?P&kNS?}}~@F@MRaloP&H{d;8SnxiF*kl!h{ zWZQhoG~~aiZV%xkBH}vsm#ajcxPj{Y%g{&Dd^>)-15(8hnL=BR^n)i^4-1x*Ck+57YI$fSmd!1fQM zdF+j%6!xw>5f*X~Va6_vi7t(a&YW%o=v{Vv>_gkpBbGHTG*C78&q!zg`+Jj72bOCh zLWRn>%O9?%#y`34L$n0zgg&Iq{=c4fdMwEZ^;?x@j0`AcwxD=RqGbQC=|LtS(re!I zerNgkQxVpdX^~=D&~XjE4wP~L;UFTu>r7<@9HtQ=u@G1lW%F43md@!qXwQ zS$bEJVyh6L+at=_m;;DFihmcsv7Fh0SPzk61lGeupcIZ>qMLQ-oVy^SQ8-*KAZ+

HK+DR%H&zY9`Syp7?R%cs{ZmQ-Rb#<;9ukLsS zi9MC)#2OtI`k8>|8)P}(ZL6uuCEcLciNZ-l93Q#R&jeg}>*#QoipP_m?dz>ego6ki z=P7rv#w~95A^))lcBra#2m+;WruKX__Bu-qU+Luz$~=g(0n<{_)e$1aI)wHR%kFNj zn)dN>2Ze*>GA$mtIzpsahtM7Za|eZk&s8p*p&wKRLz>#cW~6l za#5dU-MKhsN1m&xx;ce%&9!Kuc*L?g&zoZJuk@Rp@9|c-5F*7oq@BEaP}u7DO|*n< zmpp)YJv>Z+2x=&3M0n3QQ(ynk>9g}CtplTv5Qx^ahe#Mp?7CahgWSRHucQaLgYsm- zHW_1yfeNJ~jqM~D<#CA5dY953OJlmoOa z7J7*D<(I}>KX(u;F}#2^r%cv75F*9;gk~Ma%xTnCq!=Mj00x4`L<1pGSSJIaXB?E0 z+U7#IjN?D%pe533{JWIIa=IQ-rkEqoI837sM9_ZdL&e;>n{_TH>Iho))wL_@Iqi!kUNM7q{W9HLuf{ry%x$1 zq|gg=k5HozZ0B-M_tAe+a?O^oqvI5LY@we!_}j+icEgkg?!HfwRO09(Qalnp@XSI# zckqd>uiEuyUGJXwxoIwhNHJo`f`xwWVE=!|!kbRlbB0{w*v5Xj?p;8zGzo1hgPyFcT0F zK-<#(o(@C^hjjo#?|ykZckfi47Au-s-&xjeuu7brp>3c&=HKw9Q+L-Z?z(rB&K(pT ziD=PhS)Cqx&w1;WM()FPz1%_JBqGFb^iB1+{?0AM3c8gSHq-l8!bwC(YkD=8Ud6Q) ztAzGv=LBE*2>qS#)ezq7+@x@ZZU3jY9(ysW6LbW+4XdJjPGXOh3)R`n&1rwfvV2;f zzbv$Y(ElSGMDy8(^1F#ZP96xYn^E4(#)w9H;#T>zzG+_QK!;w*@c;b}gr_4aIuOx? zyuj#i5%1(cL&ud64kGIN=ru(+FJnv7Hg1vYZ%`%fSp4C#Q3sv5^A@U?u5V$_rt^u* zISbXTKQwpv?i63lyUo|$xDloJ9LT$0^V-HljGCF` z?4rA6*t2{h>BNWUtL1a*>2phcn$Jvi`c(0Lr+0UNKn|c0VNgT ze0v%DXVT@yHsAWibz=JPGdWKA9~P-1zci+L^f;d89I7=)wQcln>Z0z)ocE3{QYk;0 zQYFS5b7uUtNLkTm*U=fjGm`9ayM`%ePHG6W+u#M;L_9jVwY%;9!s_u&&!-{>5vZG@ zZ|CgP>EGNMZuhyqhgTxQ@Mznga-6dG5Y+{tkP}D zhX17fT>}ws558Yd+KCY9FBfzBztzI6vgxi=Y$-&Wh}|c;x<^ap5SH2}UY60$@H@$M zK9*)*tUbsbJ>w6{_?^7lF!NN_+}k>YSI&v(+i0cVK^xe7uh7Pw3)I{LO>CO? z2=Ts;Kn^1K7Nz~$1pzwry?uUJ`Zii$O5aB7>n5u}hrW$gI8bgvB+{+Z?lx}}HR1}a zLVZ*Zy0OsR?jxXFI}Zd|m9)BjcD=$)V?U%v6rX5ZB5Q%V@Mu$;PEd9}-|W##&mMAy zM;53B#hQ|igV}xEMgwNq?Vqg@LJlGxD}Kaj^y&g-?VU&`Ka`%HWDnXk%zf?ia0snJ zDfBw60E&){HS85}|6QSqzIjnv3K6K!yLpjnPWD+*D9dOA_?_hVPH*xqBP`@V93z_K zxE^U#j}E)SeA}i(gTC2V+8-^Xdq!K};O7K;3__i9UvzcSrGpwxnfhn>#`FHi>yH6_F~(`vf?_kC@@JNTjlKGFAity;Q3<^Q;u zVFDYCnf){M86J>ucKk1B_@SGlfK+0$}_?@EUkvXHo$9hLp*JaOSAqPDQ?N5js z>eW_1uPd*0ASVw5)uVisUha={?)jmu+l`eldKz>S;=ybByZ82goX&a@6Il5vfTR+;PFISmJ@#V?O^s##k%px+UJ zB~gBRqYkQB&wScfe15zC44_YWm*;^o^$yz8V++;D&b$gAd2Xy7TQ)$w(Ce19$iZh0 zd={~+ZeyQPN6HjbCEDDZj5-j_XX{7kOQbHx`Kj;Rlv#Gw?7pgF^BT#>L4>K}Ukffd zKNa_$CL(1I+WG0J;lT%6@Vx-R(G-}Z_%>-F`sl$n=8M~qlf^SXNCZ6B9M~@f_zn@SwHvgi!+?v zPp{a3wo{wi{er#ss+9DQ4X)RxcbujVdLudHa9P!EbLcL~K+6>BR; zV&EUFE$Y+rV91{b`8L78Cs-#MeQbXoBwu|~Wqf!*Bq_GOe#Au%BA#t|*d9G&fhu2^ zN9u`R*x@gGRL=hS0~3K#U!Fc}zdUS#`si<-4YsuTEA^V)FNP;fitsAKmRW{IHCt90 zCZfRC)5A$Kz6s5tu^ka8h5G1}v~fA9)n0ir{0prBpj=)di9UOB-6M9nQ47@h^SoNB z-Z&b*)Z_l}=K2wZ97HVLd)S^rvs&+qjCj3U_3&S9#)r;+U?Nb8#(CSH)d)een(}8g zj5r%x%|skMKRaB!<>c%cl_Lt;z(y(5N4d4PJ*Zl@R5G?pRNLquD2dwRiP_)TTMIv@ z+IOA15jZxMi)b3#OW)*HJ@KTvcj(*{2N75jeF2#Kl**i4(B(M_r4S7?#g)H8CQ7gR#JjwP z6PllQY+0S_bt13AH3B(#AV`j$4N~R#1GUpC+?M?SL|fJ-Kp+PZpqq5~t5=8Xfl_(s zBRRg!e22d$0|cLMeflm+())IoAaZ>%~C}Z?NgsJ1HCEZh-<;w|e zJQZ6_S&zNhHLFs-BcX@Bi@5aMr#ZA|#d}NIyG-9U z?wGxXb`2&|Nfa5SW@O*lWkcx9w-FaPh&X%QF+1OJ+LO_U&vy0Puw+`Pti6=ug$R^F zYb|Tipt+%^tIiDVO{fPV&HM zN70QNYX2O1^V^8}q-Ku2nrc|lTfxwbzWSHK< zP4Dh~6Ni2W+BOjf?@D!FSyM@6ecNRta?n43ruNv=;LX^#?IP;Nwf&M&3ejdg{u%dX zxEUd4*6O?jZ>rC}P1ak5~P(64L8Fo^GvH;C{ zi$UZEyUwId?+6E+JP@RVcD6%upBI#cw)3uYP$zHK+27fYqJMzC0z!7SLCVH*fhOze zmNBu)=;tT}))E5i0a6%C=qsxE8%57-a85tz>>M#zN8?I*AGPgK<4uh5WI=lwZ!f5R zkiP5tqK9`2pCI7L!oG0ufc^Ae>1xE+d&#QTi=Ih#Ptz$hBL*v!;`YJ!Mp6=G<4#?$ zUUX1dj+8}cd3!?TT2>sv|9APLh&yRg70%rbIEXNHm%P7Hc+Ta1&g7PZ_|`Z3@)zDo`gTr9vbP)@>h`{{D$JaQE#|AHb=wE_zWTY{z|d;eeY6j9q}U7){)v$FL18?K0}>Y zwa4?Wvz5GCioDBG;zdMoN#b?wU5CB9jJ%7SM1<(});@E}CpkBDNeQ8LMDXvOvKOg& zL-UPou#xio!~vTzW=EhsI^ z@>aCbl@WoI*&Z0}WN#3082LOZ#oL4Tkl&-4pMEwagb0-4-{UoB1pBHS`3gCRU|M{r zZ(a;;cT7Zx6kAy9qebe>AZ`y{i;gXyWS8%flFhwHq5-A&_grmm7xfXsK?Hh%?f@O1 zWG6Qts;b3~#(3szN6~OOt)*Vwhscup16$ft@*T5h-I$?jFM5}(I=no|dE&{TDrMA> z7?z8*H4$eBair!jb!YR@G4u~wVj?;(OR`7Q8K&wK8>Ow1mO?3BEy*~hqr|E`ucJNw zTpHgF9Q0IA37{^$W9DlvBB8FXB3hgyr(&*zTnQEf@> z#cJF@kM8pVjU^cg=ho`Gun{3rTvAv1hT`cN{%MH%DVS@79HtTR?S#c@-razRUI`&m zjQ;wa#cJp_KrkShs6(Xq_lqwrRwep+=bp!N?vR7!GTmkLV&$v{M4&^;LMf(Y#L$9V z^C(luNkqt~&2sU~Gm;9%aHd6yY0;e(2i0}kLb8qZ7%9ZiD8v+5)l%Wxpg2y zq!=x|z(8p43Wuc-A-#*9qiVgo?qoDGHl5aSG{Ob5@YD-OoF*63RoSFZ?WdnR=A0?J zShb$bvvaw!UDkH@Zq8E3K}3PeN1clgE>=fpGGhMcTdOr1k{M2?uYPHS3v?iwMmr}y zUg4Sn5h%s;yo})94$EAc4eEPid%#IV$Sk362hR3y2XG=8C zlx*ZABI5NZ*S=q>b7$|^iPyah2+@J);ddN!GAJ)&ac7>@=J$(cz4?5vSfwdmd&rD~ zQZ%+ZGW*buaP9o=o9)`U?&mYY+=7C@)tR(Ud3i)3fTepU*lE53gt-PzrT(?9vW;-APWd?fvx}1+j}W1N5ko z^$u;Y&fV!AAKXwQpno93m<=fZBVQBujzuMNA+XO2?OAm?|1h`NXQlM*^1`7W6_m@g zjC@x|h!ponp*_Tan~S+8_P216gXJ=fV>|5w7* z1%p)>)3TPZtp1S)lv`T4cW)iVaTRcwmKej5EbES+E;}!O-9gu85^4TQ|1bc^e$vB|qu_f>25&*D{BFblJVvKC=l=0s0N#iU`X z)yJiBAw-Hx652z2)U%K3IB9|IQNqD;nZ~)+vhqTR6zdS$)3GuCqw2aJYv>*&94wb< znG>&$5GmFnw1;@M{v>kyjd&2{3aC)3ra8Q!XRU(0lL z=RF=RV`YF~La+LS!$sRb-4Q~1A(g-L|c}c_osc!*iNc?ne-S+;f!n|`qUk)c7ET+{(DebHX^X*h_d)V8eFw36vb&*vBDi5{h} zZA=7bv2G+petM!uP9h>ce{cjITT(eTXH!IvR}dLEI|mWN@&+Q{aO_Gfaf}J=?a6>u z!5l?a8RM=|bJc_D@dwqM>JiLjh+tYg?d|U_r&S;A`()$%finY-`7#rE?+5!6;!j#9 zA}0|caZKk-WcpRIvIaBP zb)p_cH)&%O#cOd~?{1&An9i3pM6-{;+)t_HU7y=zz{9F{_acskI*gw}xw zkz(|qO6h8T&Xsfshoul9?Vno*B1DSO5^uQ?!eJ>yNF3Ao)cHD8>p^{R7WF|K&#B)9 zGu-ilN1T$o7b*MYPpJiY51Gf3xipsG7>;P_&B2&YYthUk`_)3j+)G_%hq+uCmr%;o zvHQS$d&Jz{?uTcGrkE&lvrp0(36a-4){7B!JY`V>Da$_^~!#7hkLZ0prVOsUo;BTsL z8kre>o%%WFBo^PEt~M3_)aI61YSMpQaMA*+Xt9&P&dOC*?$Uy}9(2J5bv3+)h z<~?+eg3$-(L>Lp-J-%$iGpQxi!v8eY2pHiI5zLR4_5DK`HU93?LA_ZnUoHg9i7>YB z={aD-?X@DR%44(m4OYP6cm;$pbJ97D&!(yEO}pvmK^WTuDJ}`;C@WfO(Ss`Mb6fWh z;jj**Ww!Htl@~&!SclMz2-YP$589vqnXZnkKgbr^h4N>p2k$?mX&Ji$M3gC(5>6t* z&|%DjP_6^|OsnKMimeJbOd~>cTh^FH->xXH)Hk*3 z*k!BE%EqxB=MS8H=$+Sr`3}t=YWf`+F)SD75-iEGGTZf5?-yF)+j3dya*qXsQ$g(Q$ z@9SoCde<3x?pO%3hjB$tRt0^YzGI>McDL|ICzQH6gd9Ye{k+NXp(?!iPJ926#n~vu z+RFo$Uy{-N|rV6;Ahp3j?D~@peRABQ0k6VU)sef@{8u< zb;*|pS}FI~1-tdpamJ{IQf4LxIX9Yo=Sq9+q*rvWm43i&1GFQ(KsSeh5KaOj=#PvD zc0Y8lJ$-kEdU^Agx~DF;GgST$J$f3QUoyYd!T7p8%2+N}I7}nrk%u!>>nVU>fYyNs zkz%y;M=hvWnknQkjR>h9%LS`&Mqnfc{^8$6cW#7mSW3!eTJ&8VAySMGALd2~2g_wz z{6=4;oUP+dZF#3EbfFIC^%%K0^$KLD8J3us@o+G#fdHz%hot&A2|te((COZr5+- zhOr(v;xH{^7yF9dFm)K<9)4(o!#=_G0KeHn=RyP=LSs}0C3%R#kKX5AK3Yr9&Y%Mk zMkG?6R~`t7SGHDY%8P1q%-Oa1dAD@W*xml7#jUf43i?YCb$ck2uha&?@L3jL8ELNU>E?65WeD_jY&f z?l;0`E;m*fi7X|xWm>#oS@{o@a@(|Tr0PFAK8F1RBOiO0Wqtd@HEz*Zd-dd|cVft4 zT5|5NBsvv%bA6}GkTf;F_kWH4ftFxNp07TlKHjlUrlEs5q676=*36YTRd{v$7M%u- zWs#1+yBINaPs6rw^=}FB^YfXp#ByaUF%c}afDrc3Tsi`eqCU%dZOrM^;dGD5^yJks zEDNPDLTP7v>veYalA&tN(2YiqLMcW|YqCw2#kV1Brso5uC36w`BgO*D(0gHiKR-0n z(1GO=9Yl}u0$<9llss+sRR;qY&G4u_mr!N1dO z&2&cU%oXXnJ%q!pDYRJ<>Co$4(xK;Sk>a96hl$9UIeGoH_eR|Fi%lIUMfz;thuYd8 z`!mt1K#CD@-IUAe__>@hc$3c=zmi43`MZ+WM>;5%Q)e4eE@uomi3mTtkr0$~7xObr z`FjI-gQ3e6DMaghxa>{^#yib>576gK__=kQzblyv`Wyv6JArgizNqA1#UQWCft)Kn zclmD=Jzqurd{LIN{j5R*!N2>tUspf~2X!zlzZ?0Y+A7h(@#?>wPOyqHOm)^IWtcJ| zu!^HyY-d`~I>R*VXPCO=MalSM?@D%~&U^OXO;9~Je|M{wVahEinTrO3OY*Zt2qF2q zlwrzI5^zul>h>~H{0!4tLTl%{j_Jv(I;NSNF=MEe_*sTM^4sgRh@4-9L93dSBR!JKc5`5-@m?_TK>WNT8C&y zDb!6nccf!OnBKT=8-tlOhV6)^`zDqqIW-y%Q)~Y{LT3m`3!)V35Zzvs`1zvxXsgr6^(hzO)OuB0R*zg_opDT^afq*$Mf7_7s5j`H6F>hZ&WAEjykO+2;7 z)es`ZR{2>yS3n4dr4Zp~6#Nf_NHN;ab1)J7%o%7$DW?4lArqmWAcd2N@N+awgw}xw zkz%xr61jaP9F{_aw2ej>Pr`r*T9D9^8|7K0R~d{&4%1RD(|)E(91*<|LZles=di>P z49KNJq!=MB%W}c)phgG>%VpYVL8In~5Gh7T`x`pAJp%10#k8Np7OzK?vB*h8NL1$5 zA!RW_q?nd|V<5B+;UprYcUjiO3j^I=ONZJQ+nm$y&t)v3Jw)5j7j^!-HOKBTI$eFb zWCYdY)mnp9pX}DohOyseBL@+b8DabRqJ&tp`6uT@g=gGB1*XOjfl@T0%G-WIoNv2m z-Kv3^;nlR}MGhipJeE8%LcmuL#+m`qCW7V<O$#uNf%ILXD>x=RD;a zAO{gl$JcO~4R?f+Y1P+~R(**GkzxyFWk9EROign3&K{yh)=9FFgXN+RE$i*RNp`6v zL)3+H*Wz~!`fFJ~Pa>fOA6ZvhUHeu!x8K%o`g;SB;`|9|e^bZBPzCqeDPgzK%8~d@ zgIiGjAQSv=_Y={0q*`LXN_NPWbv?C%IT{+r=?9W^X?7>2N2tWJN zX6?cuIw+TE8C|cA5GgK6Xb<7%aw_CtxlGIGdUb?IaY;hc(?q@Q>R&G(a7NyG8@EUB z1i`elAg%`JUdz{Ra8oL_cFR2WHn({oh3g#?F|+n#Zns;jsQ z`MI2&H7R*Z#+nM=Q&6v^T+S>%my@$zF{$ob0I{E>m;;?@G~=Y{}2xAKpN-4AeS>2LZn!S z(4G!Ims9r-;jj**Wrn*tLZn!S&>q6i%+xxB!#a?T&x4G~3n5ahLui&aSFirtd-k+s zp=er0zT61mBq9tQ#`?;Ci_GOpeu1X*MhGVnA-Z)gr_ObzTuzrW1pHi12j_E~87%9U z2OWFz(HB(mlkbIbM#dQc=S0g|R3V>QG^4#5m-!BlCBeL%h>$tavfi(FjXS4s2i2*- zLVk{tY&>HoL)~<)THV2}pP3m#1WI9@=$i)0B;W64lIv4${M-m*=Hy%hKL>$EpJ|k> zp6O*~>MT9suzzG0Mcwg?#_sgAjow9%^6#SC`wo&b8mCgWA#xCb`Z%tvsGphXjU`@I zv5r27N@Ja9A|x6(5&;p+yIu|?TlE%MMcRXBWTs`tA!{X{iG0Po9~%hK&8vC9NkmAz z>8we|&zcO=yVT%BIeJU#_*s(h7&=M2DUzrY|HQWcZhT|DW z<`0}1a3=EhGFA|x0qrv&2N6vB`J!YM<#JZ@b2*JU3hTiZ#%s>eB9!@`hpp?<(em)b`!yn;iB1DQ2{(J5?A}R>sV7W~DnF=1l z7^wjv*$H~27TsKO@RZ8FlH3?ACFSz(VxfWHdKd_i;@|xoohw)+94wb<@pNt-h!818 z_}NKU&>JO22#c zz+rpr>V@i>s?(Plun&sZT->4wlQbM9kF@BE>Bzv_?ezTuwc!2?xt%S|Y~NkrzUwSclM_4nH$f z>ktl>%XB=h7?T%5q*#a0meuRJLav{g$x#x_gG@^#nsXFoe>#5lXAI{IltQ%5<+S}= z&KTtQ zwPactIZVsS2}`o9&@-Q|zQfD2%rfw-|Xdby2wEUyi3>P73~^$ znVGtOz*vHFB8+g9nVIZoW@-eCSBMB^JDr*Np`V$V3juQ?jMS8wne1m~a&~mU;phW| zF%JfrnR?EEkvfp#l5obcEI-duN4s!X2huWkc|9sGgh;Utp&1c874fVlxhi^{;OAm! zT1F)Up=W2|Fd7kt4r4X|DaoeM9=Rey&$Yr~+x=`BjS$_GRXo3+8~W*O`$+q1Id+3* z0GthQJf^eT+#NQJ?TW^B&VdZZa~$VQ#7FDfn4IIStioK|gC!MH2w=A(Z02Eob~HwS~AndL=boH=o8Uy8qloP9nn3XYofL zKhKi;V6f&)h<2k#Sr#AyP9j2jfzhLMAM|robiea6k2LLPq-m>yUaR|{a99T-{7fek zp>-faq!=ynW>}?l2#2K*Vbp{Bd6cmvW%N{$;@?F#%LQv{jSvn?Awu*8h$vH77Skfd zwD>SLLO6*C@f*G2T{orLym*w@5zG@Y;Xx+|f@>(D`uUMMUEmL%Rkw$2)Jn z-e2|l&(biLB^gvqOO)WPM08)#!BXz6&oxpb9vKrx4kBIjiytAx&Fm0=0gLoyF3uBhe; zY97Qcl^gVJrUh+TgMV(PQmW=x<9~WMj6DjY9nW&Ntp8?IRzJt8sm;A#3L^&*)HXq% zx2!JXC)qFT?x#vVwbVeM6rM?MS-(*W{{G_7@VkBsN@TEq#CC3fi8t-5DCG`v)};RC z2c!Z^%$gG>O8JQ@ObCo6vKsUj-9QJHbX7zU?TnC;bj{V1FAWX9Lp4Wx z(JH3nHE;e;o$CB8XJz`PlQl|N=ut$|d$q=YuI0IWte3?al*LjqCbI5$|LDH@zAF4? zX*MB{g9xG%+JpDnBavK)K#IK^*Rg-&?^?&ler~PQ5OrV%rDc7*dcpc5q~nk7nK9(B zB{D{tR?*E_A^+wq&QFx{Q1uCza>gs~-18aOd>fc$?Xz}-KBsrv&3X^eXD<7D_ZlIm zGI2@qQv|17vmhK5`tfO%*G3O7uV?_CPj2PdE z;<@)QR+6u_EFYo{-+PZewJa^)VO_#sQOO+>xJIFK&!_(4bUhq(CKqgL+{eOC6LJ#~ zdfl>qKXseiw$Wgx?d^}dnE8%Uq$Bupn#Y3ROC+megJX8BVO!LxgS#B2e}C*Fbw2Wi zrVBr~O&zSgi=yPK%Mmr8(n~3w7M|S5Qo=#RKkAr$;GONN(4fPFz_ln#rMKLwzJ7g| z4G2viX}(E4)xkTLH>&mzI#r{?HkFKs)cVKlGc&iVRrX;6O_|YT)uJI^CQo^^&$>h@ z)VHzJR<-yR*74|>m+j@ft2(Pb=%;>rD#t!d_D&pRmWw6P9XyvJs@TXqsjdH-kc>5C z3;l8ve3e*p^c5l+UD~XQeAoO6zQQ)Zw())SKM*2?p3dDKz7A{yT@SN87)O6msI5kz zcl~;hcN1$aerL2uK}lDr#})je^~HU4iq4-;DmOZ%>%es>*n&fw=SUpeOiTT=Rc`9c zziNE^Uh@si@ojfTw8+tMwcI}J0D`PKN;=+2t(E+7!GfvG@mo-r>$iuEx;-6SeWn;8 zQcR0SL5Jrnm!RK4;-4j0e!*AOhPduuAVjf)3qNrCcaU`-)NC?gVlGt)o)VbT-w((y=ees=W;|V>luM zB3B=z?~17AA8cD4!$?E~>els$HfU1EDb#d`%TnTZmJ%Ah;MM%QPIa7nn+!4L4?t)y z#M>kLt`_crNHJx<+dPcX*P!}Q`(V~q)uYEQhv~(WWHz|V8t(oOxfH(liC2Z&;HA@`*faN z1*B}0V)|yXs&W~gYfDl+X1{(Ze7Zx$?7HQS+WE(CRre3uWhbKJh(1qlU6OjVJstPeK0;JXvYbt?&t8KFYyoNTDFn3VJOR>h?{;eZXEI}#MN8dq?uj`(BrL5X;cjqwc5Wiz2ws|PW zzL0;L+Si;{mUUJ|)a}C?h7VQfl8PKem~H+zdH42T3#f1N{jTS88J!Wqy8UP;@7^|b z?Yg9>K3&X3t5Bb*W9JQR-Ou(EP;YltG3Lk^&a~(=b^KkUyF2mY1NOC53mFKMLcdwo zyEFezEio)JygYwIA%}HHT%m5u+VR!^)hT1Flesj%)*=0XrDQ(GUSL@@3$}Hu>@MJL z>r^MkmPmx76r#=8MGnw9Vx%OpihQ+uPXYJKo=Ug5L`fn-V$8Dcr53FIashYRCR-zf zg9xU@3*0N>JKG=LN^Nl1>#0mXaNSn5AY+%qbh)`(RjIxlS3V-jR3bv8`1d1yW!#+@ zs;g#iFYCT=_PH2xu-xqhkJ)u%g1CIKvnp`pcc*8lhDJ!aJeT+p75FHkcbc|&_U6jIqMD=Wgb@p)|7F7`lw47bzr%GARQgZSN*n^Rd-i;K8&_A;=hw~w+%Hy(J!j`R=HRf zTjj^G_JVIM>0nN}X*F(=Z%<*GXBd!o7RFBi; z(^P{xy>yKb0kmG1`lH=d5Zra54y z%#TXy)vJuPiBTe+ruUpTrm0mGdpXy&I}(Djbj?KybdyyRU+Z42FYP7LPN!moKg#IZ zidEbm(r@TguD?60Wfy<9|IT1sm4sMK!XbSQgNFEqX#x1Hv&*o08F8Md6-LggHtM7f0 zuX`28Zj^TfeS|%@^U4iOXAfznZ)%c~SepO5r(u-hUquQ^(sslVD1~U=zZ5jf@Smpx zIe8$c6Y7a&%BOR@Lx_=RV=7?Kp zB9Ma!)JHXVCbLG{sS%ZLdCxFL14<#9R>i&BxbyZEQazrW_u>9g2c0G-HmkvIbNlY( zgU&u{i|SaWg~PkGbM|=gM!SPG^SQBSJE#edk4r%W))vw9bA&c6J=ttp0kSg#+!3G`0E81EtjObZ7CotQ$9i6rWS&9N(sG=e_Wt zB+IIrP2X*QI!ur4yhGo-&qr$coO=8nz0i8MzS;oqcN4+;_`=BpK~^0uwj;Y_$*^IC(pdeD2EZ2vuuz6C?90x1VeqI(DG@5ml>d)T=vq2?fk-X$HJDJxb% zxrToL?a&R9MZ0BH7gLhLGbwB1jbJtdt@}ntLX3R0CU3e??>@Mr*cE=e>_PAZc)GzO(hCsW~f+k|= z8?D`2Dil`d_C2499Be_GWRW{v~iYMzSyiarF~vYYt6`li z>&(qd!)IxCWy|+(reHgxl&Ryq)65-u;Wlj*#FdR`_?^5r7utf1SyrDD`==3UuhNGlc`? zCPX5i`$2av6V{9?unP52J@{;q?LGp^wevtw$&c)6pIxy~)7Uw>|D4}D9{FdJy6|XI zzIEK0p0ruhbj!6pjcDVaWK2D+i1WnyZy6OLdZeHW5tg+MYe8I*4~NLX{A3s z$sV+8nETr2VSQ%5coC({_SjN%Y^-6gi2LsfRrHrg(jJIFecp^iH7EP5D3oQi0sKyK z{8hZ%Y>ga<7(^3->ybwF=&&oy->XS9@a@?WOAcB{U+T52?KWOi-VN=al7$>Z%-MI? z8J)99-G7nqyuW{0CHKQ}sqW@irW**9qI<)gDX~rJV4gQ z@_*dSF%hp_njNc9V{-PZl_M@9Pzv=~RafSQ6#QH0q$DJ@RSqa+Zbv3}6H8jIDRjZb#1vi#zkvOQ(Ov+RK&_X252ir5Hlj^LzSWnU>czZggJ{`<_I7$UDDa?u1`M8Y z=?Oq+vTE0XQZ7FmG+23K3Ua8nw*PG4U`e#8wrgKFW8qe()$yJ#SjBzb_D5=md}#Y4 zIO(7kR297zj3NSP9_ItJhw$4xikv(UHf72->*pS#Hvjs?6&uiYYC+o{C2X@E-?!}R z4)}Pwvtp^Evv;JnoE!7kHJjBdD_SPhgQCPOL{ZYE&{mGCz&}`9)Td{)kUy*O*ENAp zuue3V*#4|WzB>Ep_;6Mfu@)#)r;)U?Nb8Ms3@lqX~|_h6tsbjQmD_e!nZ%DT0fy=Y?r9E(LYcUwa0hwe`n9U;W>361V0Z1 zeI95+Kt1^RBk&2L!CFGl6HBW9RAh`kh%j|LwWND$vwS(Bji(~+tCMo<)3vv%aX&QH z=S;{GHtMGR_NiU73MCy0RroHVb8G!wC*CR2-lg3r=eBXj>;bd~FqulStQI9^WWUyR zL+JFk5f?d#ID6eOdwY4>VbKWdkDeP|f2UN|UfQum1WKW`mNjY6+|biiXNLAB)B_Rd z1^OngR;#R5vp)&#Ije7q72A2INPC)h)uyE!vrm#ohWx<$J{^86y7BJ%KZhoL8&RLs z%(44X4Qrii%+G2;T$zZc|LmJu^P^Lt7AL&B8vUp?5LgoJMonws-qh2}7D2xQZJUTg zccr?otf{1u4s_Xw9P|&MsXhMP(K|>8RH6Q zLJTPWh`PMjL!c$tfUG@8++;96y%^jEXlI&v!8QM9y{f1X#H~vN}(kt zg7%PY*h98uf0y=Qh2~vV+uv2CdLRNhc_64Bv@fb)Uowyyf?s*;v zqtEO8_K?5d&RO?CxqwDrQO#TKJK=0?RL!M#MJn-~ki63|-ywbW+m!W{Xml&mYC$R@ zPzs(hs2;OZ7FIt@-%b49Ju{35lw$hvire@LP(pn8)BN>^2r;UM_pQuR)wZd(7k_5F z=faYVlM4Bp275{6?P}c0J=(kTr*2kH7um`C?e^#yn^pe8J4pwhZtS0E9cE79DIck( zb=w@gH>MMF+_ICACqpwH@|M{m)vy>xJh~VF)q}&MMBp?FamUTUyfqi=CJg4~cli8|32Y(+U zmN5PC8{1XQ1AMzY-ZW0Nb;OHQTSsb3G3M;3v|XK8#kZOBdEx%q(d;Wnyod-cNxU9E zFPzSf=Jp6Ui3ri{tz`VOqeG}25&V0Z%UjgEA$%Vsk0t)u(HbEfL@+JZT2=u%XZsBK z$|7I!mq_9t^e+D%_Z7FuXgWK3^tm+sMU`+6fnL`w7#(wEgwZxqk{Rt}ZxC@9`P}E@ z?ZNxI{@KwXM4%M^9Ui2{jxBTKL8iNOVbhVWyEc$f2ns+xKqKw6|m=-Cf7aZNLhHe7{1EPrtk>cOo)!S8xzC0%S zRz;aY4wlRGeV=Ss&U!#FKShzKTp&loJ53-O1fyhs$`0!f-#(Fkz%@GHqAKy z_*UhK5Gh71B*c;HuY?c|mdkX~0s0E6_y0nO6eGmbMm^Y9fp(N)`skAFs#y)c1&w+L zClMj-Z|KmzLWD>$T4KyVXsZw*QjCyZU?8*(;b6H;OJA|9J+&vw5y9SGLRA?v&q7-@hv4AcD?oblexWtD`d+G5_rt+Kzf|YW-mw#}d$|Up1JQgp`3sZ* zvA8qOQSuE_sw?gT=(-CVQxV|U~8hM={?T; zvhL}Mb=_$3kzwSZ4lIfC`tmnX$8RX<4qWh*zTZIR5A++NDTn2!XVq&zpLHG{UeQ3H z6zb;KwX6wu9C60{A7NJlu2a?hPliaP;X_4AG^dHUF84j#lrdA35|vMx8pu3$--=9$ ziVPVFNztSb?mZ{E^q0~oGM3?9rMW(l%73kW_S)}npZDI|eV(+Qv(|5~wbx#IIQy)3 z@4I^G83$q)$9d?3BL?KG=F_GRj%cY7&_56XWBW;8Kc3m4&w%ig8H;!&Y|A3rO7U|U zW5~OoJigkTHm%Q25KasMBlU(+Ihke0_+j}ISMrL?mcN7{EaQBT@gkyfYKY?>NwTE3HF)i)nd4sdBP~inCtd=*Hqr`HUmWaWU=rp;X zPXztG?yAn7IXf5E1}KHA8k#-w&roN7f3v#f`DdJ!3?eAb$O7^y)0tYp)^12|DYA5m<9Xpbw)KG^b5-B-(X5w?EEmGAHWOrZdfH z({Y5I!x0_nFsDs30?Ty}GQ;W9rZdfH(>mIP!xqXqfoYrvDfhHA-DC29Rnib5#kz%# ztUA)0-dbiY()~j?ST55t!xfJZDb^u$gm|UQ^(y20db)oI2g_wz=EUL=BE>p{ju7>l zPVvic9ISN+2g_wTHFGkiD1=C{4xw3IuU?Z(aak><=c%zXqZRA3&*rJB7e%y;d@NV= zdKVFn4rg5gQUU05t#S}j7Tb=9lvNutI;^6zGWf(S{t_2RFTxc7^$$DGd)~|st_UC7 z<*RR}kL8iU&Z$gGzjJ4UCn_(d)b>2O(<1Ck@6HS9JY)yigTY|m#xPu zhzy)-ZN#v=gRmTqe2FEFF`=XPbFj+JQDl`JsmWS9U+J1FKGAwXR1eER1k>Va>nr~# zt>JL~z?p%(Zr|0Tom8^QKSl`T#1Rt5`V4H}oPnK-UoGhbJOAWU^VGBbxA=5srvK&k zb*kj=JV)KuW?9{Phb>RM9-E^Ofpv_un){ar^UFrYn2;p#hAX=U? z!X15t!w78u#Uu07ar)J)gWxw7UpR3@^9S-&-hDBI9upBEQjDI{Jx_HXv$GH#!eJ>y zJl8Bwg|EjDS_dLTiqT8%%~S8avBTA&5yD|9M9jM>PYoOVZwQfMbe%Eum8?l&2;s04 zBK{tpr>^?^tH>%Isgvwyk_rG3h!j5;YgsP(?FSRcVHy#l&mxjc#StRK&&7x72;s04 zBE)YN!GzX<2$5p6v}W-Lkz#~IXgWeTST55N$8^3=<4G%*m{|?SbLw|?hT}Wd_mt05 zen0+hz;_AJ=;Plh!Zksju7UwX`aa z%TNp2SyZ2Bt#;J7HT>}F=^Tlc6Gupd>hq}sb3S!~^KbTL=BexM-r{6BAzGhL9h&p0 z9Ry0DwVrqE-P&2zbB3>d_IQ*P2CF4Iha;N4{B+9*uRU_Tda&y7T%M5yfl@eA)2YDg zDusLo_7C4o(+GJVM1*VA-Vxtqtc%X4R-7-mv+M@7?i_uux_{Y88`Pl6TYMMccW+y( zDvc%cX+B2|=lBT%eHcZ_gaZ@&Arpt_9tGo-kF?B>l%@B;Mmf`I2`L4QWp2DNk5c7Dh8KW?@`U3vLenwGK4B9ct8lyKq*M~5>z zL%9LybFGp$FSg2Zm_~%?rkmdzjZ|MZZsK>ZGbaZ}YMeiC_Mu*T)(|!7=_i6lw{O#D zF3X%jk!XLZM`v3GCzam7=Tpd|TogR+;D;4`obopD?QxhQGQr{=hFyeqb2 zo!F=JJH_)~4?ddGUq>R;7Cmj(C^XxAF)+OPuIGZ}PkXX3>lWA7*t_(J)*+v0oz>vY zEaV`*XAj!W?1j&Gc>ir-#&Y!D7F^|7{L(5P>5G-3@rsq6~9B zwL+^<%FRwF{YS}+>1OmnP8@Mc>kVqA$1O;INpsq??okq>+%`Z55~1k`;lvQOuV@vD z_3(cz^=gj|s^9u;x)(k4$OcvForvyo`v$eJ)AnffDhS=9gu`e={Ql4eb;~n=(8^c} z5hBIUC3>`=qeD0>g$SviMo1rItDJr(Qv6(Wrz3>JQiu?J#Un(D(c;5&gm7325#l$> zBm3u?@Znw=Dm++T=dEB4i$sRoYsU;48UAzJ_q`e~=HPE7aAk@8pY9pGXK?su=coKn z|9RIzpp>g)O3!2dyf^L)H+l2*DYRl0O5sSvHK%VmUFkO;|Ni=0T5$S)otQe2YI5yG5L9UngeiEz}Njwq~85W-qW+3Ndigm+v#A@SIE zO}OTPL?TN`ZJ8E*lsow0iD3PAUDfyVX6G_OyokS}$A05^8(yjv-mto^8n$OZE=D+_ zUBsfy@xg!V4N#Y_&T@J!T7qcL>wT75#rv*LnRA52D)xzF(4mEquhtQw{D9@TD23$` z4N+45`6e0s?PE9Th#{;L##p3-zXvDjJY*~v>p`@Qu?WHEIv0YlQm$2e`ggbJ+;bhf z(xXs{bx3P^-Zh=Ky+!p17tu-_^Y<75Xd4T*9wAxf^ja*J>y*;*`R%{FwSaW|5uLMb z%S9>nh{PLxKfkVtdgY^vYVci?{i05dxNZ0&^{)7Rz3Q=rf9KWUrkZNOjSbYEti1{3 z;5id)d+OYegEuaGXCj?Uv294-1WKVkw#q~d>7c*liFdQZDN}0eHkYzk3Tbl&2qCV2 zc6i3cDm!fL&CNxtxTwMr-yiA}UNhp<@V>S?9UW*@yd*jS!&t?wCfb=69jK3TIcE=F zRh_JQ?4-FIi57uUt`5!}G?|&X@Fkx!i6x6bpXgxn%c$m*nHjviZB$5^nYom!Ci#15 z2$QQw2)fxicm9b%!PJh!IOA8odFXOQ3iaviwj7h)rq8kv?eN8&b8F>G3h5|Ad6v5< zcksHNQ*$9pD}d}jJ)@d$kc6PWq{;qdDajFa5d7TaWfg)D4(ec9o;%r}+A5RFr7bbv zxnovQzNj+!qKvRsaUT@hnHIFp7frliyh~n`{5|%r% zhLE%%TEaR69Yu-B{^a$p?RVTCrEhce2pu6z_GcVnr8usn2Rqs7x}Qr~aeWfgtiyiI z(C=#I%b^}W%oi+8n{W5j9>pOWGapjDSmG9vZ8u8I)sDeGA&-Nx^QdT8d8*<_Z zi5Ql1eI;cvLZq0MsB{q8Dny7BBc$Ir2yK;cuw164chMfe(V^jeOGo*~Z~c)o2jm;Q zzG>X#i|YHmuiliWw!HEv)%=l0Bh-MLTY}Z&59RP(;liPPN?#CszqiR3CB$3ne+~{_ z)jb?mc3LhXP>M!WtK0K_yKV8xH-;`xyh$r@9t75$z&)9yA%I zJb&0#21@bs)S7|64^E^R=QqkuKn^09HW{W=^W`ny&&s5n)Q)t!N*p0lY@w_SXg_gU z>EM&OBh{EDrTLUB%fWKdhjg0Nz|ww|S4OI%KbFK_CFozWnw*kY3tqRfu`2oWCE=jF zUi#MqB8Bbm>NuWtRao+wMA+)}G58Awy$TcCT?B`_$^O*y2SlP|i0Czn#5CRQG$1F_ zWPfUea4238VMkZ`t^U`KuQu7APFakAao+Z3o&A|av+D$+xFX(ZHV4QkMeWT9U(Xe za+*O12N6umtj%%dB~31;9(|ylC8tD3OsdV}2;p!fB3hnDS(9wl(_|HCx9`YI%N)gH zuvi-*pyrknN64t{c~1qIVe94Bh9kYUoM&mzZle=#f@jOGSHHc`F`%!qfyud~_82s^ zwEt|y(P7hfXL0U_opI0-7s0<7C9C{$v}=Gf4$dW5l5G$F5Uu);iB1DSO=6ih#krae*SPBs) z<03*hV>=)u%R={a(aj~>cTV<|VLYbKQrUh_wX@9!L!%jL>wiBhf(y1_o68|*{6!9EwyouhB`{z-H) z^FKYd1TJFFjB0Af>}KJOCr!#l4%P#8v#)ISr(P{VWJtyiM~sci;t?1nLPrRb{i#nv z5Du2hw6uTm2$A9z6j~#aCi_#*gTldbnU;u&bQFaUDb^u$q{HNLY8}GCa+yxW6=RA* zh!pD(n%1Gm3WDah_XtN`IG>}$&YVn3B;w5AdE>^NtNblDg|jnf?csr5@ot&ty&NNQ7RCvznb(bk^kR?hVdWFMir44FR){GhTU~$(qy%7_V%(+=B8v ziV~9p$(hTxERnT8N4E=lM}hslA|aU~oqmuVUEi${nQ>kyg|_Kk&S1IcdD zecNPjXj=NegV3{@a2SmUM~5>Ls!eQGHA-d@-?}dZHnLkhW`*tnK zk!Z(P9CvZ#qu=9%@B1{0DjG#O2hxt5IHJ0UcUKJx53iUW4EtbvPEiQT3Gq#yCB^RT z4?Ps_@BeaeblHg<%f1+>e!cU#;PjvNdMyh%h`>>T`uXD7b$dOwJTaBV5=T3%uQ|8D=~12s2+N5hq!&0nO7}sNd7}HB$yL&{$zju0*gNbz&g&2n}vsu99rDMW}q zi%2qsWic&MOp6cG5yFWh#BVy!QkgtUz7xeac|DqzSi;`yc{DPp?^jIshkvj=3;Q;X z5-wueiV63pXBUX>j;5W&QGW`P(*6(q&v@ExW&CJvzoN!_YClZTBKvddz zqw|o}3ID{|-NL$SXXoO0g?*c8@f)pmDbJE~IUndeNoTjo2!Lp3jPYjPwLN(Hie73_ z)%gh=m+(Fw)*%r?U&)qD31+=NNX=}vG!d7QEG-v7`EcRdC?76F+u2tVuS`qZMBX)d zmU_&9K7k0yzcVce2+N^zu}9fHAL%gpqIygO9f+_!xOfEgbGv@fxtz-6a&paWA7rbf zwoHo`$h*IEQCHO|r9SxiT784P^eBvWJOiCpd@t2f*M)V}=7A3;kb?-;ood0qUzp;b z_`gBwyN*j81WMt_>^d7aG#QP$1*I%*HL)FAR{JW+nVBJFG@=xi>(;#5xeYUN2oVfi z?%Yv@Xx1Sy=6Nf(Zd+yYML7r3a^eWFmNJ(!$NMIWRgVT>yY&xyLB<%$(%XIJa?WDS zqk6<_w>8JCKsqm@)7CnScr}LLa>Ww2=H#s;XJ#ItTO^qyk%5+Qo#Z*?-2GGj2F@3K zm-1dQM-UNAr$&ac|K*#>SSiq z9d6USaNOfv!z#^YbN}!mlUQ<6WA_5Q7*q*I|4BD`JX$_&c9twwE-4jPn@;uA$RXXr zwxg=(8Amu^Re-Y(o$R!^n(+u{*U>na;7p|N=1}A5ZjOSyjm~d4X?<-^ zn1|H|`D)FpBh{6cT;yMHN$8BC^lo79A;2|?=iTtZXSrW5$_tVQ`tn)#f!w>pZxeDK z4|?76`t^KJjk)yA;O(;Ci z`J!$9#0Ng{yB=Dn8tvw@+x$5*{BOn#((j$fVZ_X->lGt}=91`Ks>}A zMSY(4&G$puBJady*#U6^wu%u`TWkuJ4yF5YJM3Z|f#_pd{gvK|7i%T z&(-mKm)@#>!`J-N=ZtiGa>wT%`djbHQ|COg+h;nzL7u)T38`ZBu(f4{f(|8q{k$JuH15Gh887wCJ`uLW6?Hk8Y)^lmom@Wodc zV`y!fRThC#Xf3^e^gBQ2#~&)?H25=HeV@HG_-*w@?e|aew+HR2ysP@0v`5F4=+-)@ z*8G=r5LoWFbmfPX6v;;aCKYlJffjn+IsZ93k-YYwoZOY!3OQJFEGa5|?$-IM|2Yx) zYDUTTbo8+fp%WK<67;Y6uDT(~y|!ifLs`L*tvR<)d$10P*VB`c?Hs$PkIu#2dG9+< z4eXJ5g3ga7L?8$(cYfllV9${aY967fw+_p!yL(#aOpY&6PyDn!$G zHKKR!nxEdz>HK(hh#d3+#u$C0-~4^nxAnisd2UN~h<=ZG!L}3aa9%uY)%JU9t~pLM zM;*VJIF`{TRS&Ln^r!1#%R&UUzm?XbHA-P$NsmPKEMpOYQm&5qU3!N!iUz0785wX( z!DwJDM2~o0&!>l~7Ofu*j+|AyK9+?#Ttx2`7lmsEH&e%cSy2ydM+?!1o_Fx~Zb7Lf zQ?nl4JKX8#DCM@GcuS&WM#cu!ea0?510X&03p#s;p0j*vPljtQEyc7*F)iqn2BQO| z0zd?aaK?7ap>iFB=(biR**w-hZb6565XtWexdnfMKx!GZV$&QK-iW| zLs$-5f(W4_L=kOnV=1lXdK@9FjzqDSr0jUkwA7EzNnN=&cq6O3sySBabt10^dCeJL zC;l~Wy;@R<``~N4b_6F>19e4-vU*)2oH%01`|H)hBaHa@vCJ^z)=KK(neXVefp8Fk zM#v0_vjNjmQt=3pVjV(9h-KB< zsWt;DIaXo0Op8Z~M~D>b5IRCU-)n?gc({{p58+_BOiMczj}R%=A++Z$`gFO!V?kea z#beC_9QCnW)aQB2RF41DyoPG(p;Oc5TC_0btM%2M_NVmzpI>Tdr!<5}u?}gcs2&uy z9KZTKitROTLiQ~MEp!kba)?F*)ck@6rUaGV9jyBZMxP+edz(eG4rgTW%bdJHZA(ON zDK+29Qwwg7Xk6(RjSwmBgZpmVpwUr14qm)8kykldy@HMaY0+0aLZn!S&=I1>H5F9j zb?x;UPBabFbNWB#Sg2zM$ zAyWKYyx{222;pG4Ok>Smt6)WDr4SwY>YbVu!lvtWd!X$$G6>;|g~cO8DqY7FwL1j= zH){m9x%CN_%QU{%dR|cok>Zksj;y-$+7A9dkq#RTEG7P7T0BxbLZsL#p&8-!D2WD^ z0v(R8T!h%m2=J9f(|hfZyAn4{d@J$x3lA$C8F0mlvkztbCKdlBwO zWic%Xv^MhYmb~V{<_aSjVc+Nx!Ox|nbcAqX2&+3n+*H4OcyLE2tpgEAix-MVh!k5T zbcCp}vs3tEW_hhcIBXTr{%1qhtM1Ksm2uKVCF?DDsAE{W!Rnses z3{TtCoLkD4g;M-ncJv~vf&(MM7anP?5yFWf^zK)*bGPrjXL55IHV-yFI6}qeT4_Pn zA%63`8vUmR`@ZQPu2`xZ9dWeOk51pKIyboF*;ZkzZe^UB#}VQ;I+g44fx*tp%Z07; z+B)8iBT`mT-ILM}(I-UP+6v9HcH}FAi0_Ny?x6N=gm|KJ)8OQWBSXd(=22Mp z$jVOyv+ECGgw|1K;sLw&$}}TN*Zay}*KWT$){^_+mVf5>rIrrVD*)thoj!XjLI@qT z;HeezbZu6Sygw99yj*@R`sn@U=vM*Pq4T0%j0lAD`f1yOE2{5TKQ)N<$V4B@>c1rW z3w2<*SdvKd|I-jwA0yIqXatYQ)$Yo-JE{Nutw3mBXu9!sP~F_i=l-1Y(t>DRA{-t? z&wMIh?`)zEJ@2OzE&czi)W*N+)xiomh+tZD(|tvo!j(B&D%Ag*_Tl0Pk>Yx^=yK5A z-%V1@Id&}v%O%>@&-2QCeAe1oYyV!eigY071nv7=z59?Z7u$xt>Lu57>%Qhs+9@I( zzGz1aQFnyU|B_W$F6ui%yPTpgk`)AU5J5DwN9$LATQh3YS!-9v>VdYqRz1+I#OikM z&*uF^z3P(|#Co9a$exvx8muzj^*_1vpxqZ0dPvtD!Aq6*tF!c;<#{bT`hPwAL(u5S zt|4;R5<#Gal<9P9So^1Y_RyYU(m`;|&v-0f^jY1GuXKAzxrkt22|7ZYdfmd6rsl!G zj|+6UXdxryIh{z_y7$}C9>|F!QaUdF-#*zF4cQVYi)oQUwCDXX;pD_+SNxJwkIt0A zHsBb8Izc_klniShd3#KnuXrDhV@dWbMW5>{u7_|Caoj{Aqdo8Cw@W3?T={#>tz;D< zPztRT9nrfQmWz>(Xb0gT2N7;0RvtAHNNu(fN@V^o{0slN|*dM!%1u`4y<*yVQqv`c~AvqbvMKk|#%vy}E=Pm2`O zf=+2LI#4PAgw@RmXT57VY#|~jXnOl+!I+!wQCFYcIN(`^ z*EqaZ!=B2|>#RRu_AJjl`av-NQeXYAS~;FSEGLfG_uT=rXZb**8Noe^e)nJ4)KMdZ z6GzCX9o3`yDV}=jwP*)YI5@U5EhQC?5Gl4+=m_!M1?|*3gQ6Ws;b6H;r)tiaq7Wj* zI)sjN+}(SG8o4{#ffNpw%d~jCc!Wr?4xv5oKi*QmXPNuey^C4|IEG`nsL%7R>i?2I zU~Ln%>zeXuGbdUo9`U>iZ;tREXnxe6|I@8$2$5nP(oRu5sE_DzF>VRlF7F?ydPEqD zur(AkBAE8P|9dzuc=F!+wT^f!Nx6j9B}Ir>uk{;UQDAohFHQ3XZpK!T0{Y0($e8}}>=lVTk%f_A)=+3~U*9&tp95n`d$VRr{Xhf}AtdK8Kf zDb^=+q=WWFL$fbxIc$kYG2)?h1vZnz?)C9J==cW_^7g_yEJBaeP!Ic-!X=3p(h*V? zOQ8N}{=0zbyiV(igti$bt&}yj9dLbPFwY5^L zBUO*5zI)f-_e}4wbE(Yqxi7U75}Z2wfY~Fvv{jBj{pTCQL5)kP_~;{2Jo;Sv{sFyz zNw)*vH^r|zu58%))|=80BE^U$9(1&r&#Xg!s+#vTF1V zIu0rqwyD>SRWI=PO{HJHOBvUPF>w54nkpiLNxvrnyL)L2_kkTB3&^i#ELSR|9kl$G9v@_cK zLN_kYXB9_(srgpQjZ39;%ujX>Ph3+@eRlOFtNS$D9=uTFpz71DgTJ@Y_TZ6=4yrP* zw+lF<`KzA~a66HX=gM~tOMYBJ{n@PaDny_Z)8&6Tpq{;?J=Jf^lJP;$l|#~M4qgbb zB>Mf>BXfdl!htG3v%X^$BG5wm&GuJSRMT@?>qz8m<*MIC_A)|R4QR3o5y%0w4>Z+$ z?CjFPW;#WHz04W$6Q=J|ug-7AC&UWPS^h!4S zdGiO)$ybN}ZtZja{^lwX9i4cxW=UzX&+|ZvPkXZnEGa^)HVEJ#!l_eqIt(GmKDxg+ zrCp!7EVYIDkzDzT@8_Hs)kEL!Y;1QBSW={e>Y;UDSs;Zqr~1BjMz6J3joO)Y)}d_0 z=hU!{DJNRrTqz;N2^A28)Ts+=v^1F?8#fgv#&Z`jeGCj2FO7K>ZY3n zKAPL0*MW+O+dhx(sTN;>zTmc>cL)7%%vYU$Y)v(9e%{XD;GMlxwVEHUMJd$hBCh`N z{BT6WR_cv6_pU__BKF<6J6O^^U!DIw>$vdmMmb|ge3Z2*KRZMON`a>d@yd~yLxSz6W7VUegKDIMT zxjOphvt%fJSXqATwbvD`AS_Aug}-FHQRm%ZQ%2n6YpGiKt2EEO+MZG z`hCIL1{J#|-XH{W5W#0>d|FcwZxiB`2%*ngGG*y=2aS|IcaXhomP=WiCQy)Lp! zpF1cVC^r^~d^*e{(U|DO6Qmd~{`gY1;@{v@yy$>B zdVL$8e`)jSq6zUK)%*^sd7Ez%d=i^PLjdRiEu=L=$HrlY#g~R-7Cy5U zIf$75*^b~{?|{1e_)XLv>z{2Hw*BO5zs`u`0r(`~UpT#X)&W)O|JnwNTJ8uw{CdCI zerg*+eDlxTT))oLoJVS9hloHaSI1eeUlX2Gqe1w;7Bki&2N7tk=e2FwME&;oCE+-~ zcP3hb5#zSU*Oe-(84unRp7MITHHbhd)JJn|-?6zL49X5K@Q!982NAAS&(CWWo-*`& zJ;EUe+J^6Rx9vpUeKkKAH|ZWdmY}cD3-FxU{JQy%C-yv)t$Hr&z7{!%fYv0$Y0Vm| zUshhKbs(n*1hruG+V_PM>34UB@-{l_TJ#&}CdA2GhJ~*TyVW0X*)Dyf=ge~tsPETw z^l^;~2(l`x_0aIO9%K9`_dmW8If%g3GUY}!8ya3SW(;9z(F}%{zeq z+1Ty=<7E%3C&G5Y^_koKQ!YNJF20#p`iuM$s@gqW)y)|b)*uHF?z_mYl9T;T=SA-Z zh(IZ!`F%&P+e5R`Ptv;GzCi*VP(6I}2H+yRBBWx7bN_lR@j+r?@Xg|fLbRRQz&GO~ zpAYDp5j>z@{hl;fUEgn-KWKHSHHbjJAzHV&GHsqjP7w&I2eo+!Z7wzB@ya)C&TlO8 zoDd(i7!vm1Gci~{=6^ZB2`W7MmEYxtgX-F9b7J+NCEC3%KqEDc489;x%GL4d7k=Wq2WsW~ z@^*HJ97LeCp4Z{0-3_+RzB%zR&F3`si6y+=5q*A%raS#}4%1BiJFk8IH#C{}=G@B@ z^O|QXbJRxFFH)knN^E! zodN_(xjJSJ%t*9LOw2m?cD6zeBG6ij#PhCHw{%c4wp**vZ=jpnn>5+_nE^wfN!Z>mvsd;5X7yeSV|xwPBaZY+%~}r4UW)#G04-H$68h ze81M5OspZ+9NXXXXs!*-Tw5Re0Y(O*^?V+h`Fu4Zu&*GR?il&3RPOlQ*S*BF2l~`w8U^A_Aq* zS~?49*z;L;*O{I5Nvs}-Krc{s>^VKw)>yGEYai|VfF-;;Bz5w;ezM1(*dbr7_=Wd< z>eW6`@BDAJXO;cdMW9rvXLtMK$%nW8z=#s7cGfR*^k7!Sd>4UIU=<8VQF)IAGEQHXwMrwB{Lk`^*TLXVM_t+yNC~~H3$bUzec_A>ofI`gB}Gmwcwi< zjq%HL8mgN7)3rV#u;$oKl=u3|Q;E`DvQ@d)YP^HxBHBfieWty-x?cs=zud>Gk%Ky* zZOE#PmAk63Yf9*v0|#3$Ks24Oap=16*Hbd}c!iMx?T>Lx?NRZnit3Zo+G_-~L4as@ zPKc-8+rDxv#qHBij$DgUpu=fRy}#?jj<9cbg!O4HvO7$BnZDU0B^|VfY!S$zeON*3 zQ(R(?T7HHlPwiZSR*+T{?r{;j5nx9_r z{j77%&UO(9Y=1(~UU-(-3+MA>tad z`XWPCz08(~6j~K8$@4-wZ)q3Z8cJo!7bSmsn=b?J$pSTlEJQTZDXW+k9at`xB+otX zu`<^r26=;n*&T-|j*vuNi*0mUco;|A6$}zM{0hlx|+U z^^Z3a%xS)IpK87M2LRO#k-5Tewy(*C;bqr(12-$)<_%jM^y&-2cp`v>=J zUJz_-KQ+Pkoo#P&Q1!lJpU-sn#6h(>{~MpqTk=P|b4dN%YOnSJ?SlO@JS;c08%qTu zg$RBwC9!v0gm7XAtJ}Fpk*%^i_~a+Cgy|B?52=P<@-Hn`m$@c)IeB+Fd6#M%h!?50 zfz+1bI5_F%L+aog9}(g!X|gg3IUxe&is6X|a~_+o=V=qnj|jd#5I_rO>QPPFL(*AjEN2!j%E`8%vXNras!#nELeSNZ|`OuF3 zGbQ%;vxgL@#*3e$DB1C9>7c{Sqg4H|J9DvItgVaqju1N=j#gFMJ+AMl62GG*F5)h- z>d_{nRg(&1wN-*ZDPH@?IHse-E4`qbKl#Vue4eH4sT@n#=Y@_CB@Ke3PdFIISdt#E zLKv@XxhNHn-Bi{9m)qr~L+Y0wcj-~>r6n{54~^(bTMntV_4pSGCeJ{d#|YstjfnoA z(de^;e+^h1LZle|^)H9if@+{6$=J9Kk>clj_8w9@PvH?Ru0uFjF4MbD98#k;6s7|a zBE^WizdxjcRWTh&)Q(b2xBc*t`tO3m5W{p>)aY;!BE<;tNV*Q;V7W}IV~5le4;7{Z5hBG1@wB6Zy=%3j6w?xK z4uXAUIdOzUOz{YjVzfl1gV0uqc9ddT`i+CoRtYDLkiJ6uqK%$gnV(#qJA+Pkq;~*2 z3)7k8L96Zssz&K8{@wTN2@Xv-q;8qZv-2f2daUS8x5V&0>&QU_-CYzMn|es?n$3uX zpXb$WHFA04B|^|RXmuc(M!O(2UR^-4B+jqR2b zN60Ke@6N5>x*NAirrI%Jl?^#h|*GY-##6G+D|qysr|M5-Q_+%c#@Q1zkQgOj6t z2GN1&htJ;=ET$}rm+#_P?fOQ^wUxTumz()a)E+Y9pcIYmfy_R1heG30;nQ8Zgr&cj zncx-_1hyu6nzAew)d&~VY#L6lG$w%@)PW^=Uh7gfsRO4~4u>x4tnd1j83+A_XgW{k z=l`n5emNXm`|#Bc0;Nzl$1a_3c>c~{++Dr&90jrK%nZ^CibsePN50SzVol!x;g~6l zc$TpoqJ5EKT1JfG5hBGU2^}F?ZR`=2T=8vy94wb<8IS3Gu>Dt=`^Wm>KYv}xYdBjL zO7U|Uk0TwgKDaMN~9Rh>O^b}p_zP>P?YVmFz8hC2KEo7FAPKjW;H z5J7zfRx(YO6g2oE6(0Sb=>B|_+hq%X)%8E@ov+U8x<#)5Q~jK7cdTn}cT`w&M4%6& z7Hm6gpWk-oy&UcKEson6=Rui8>8|*L<1^=-T|sU7qJ11;*9nNG@3o_nwWsuNtLF4L zhY?t=gOE9q?$rBpeCFmi2dd>?%+dWrIBcP;MVQ8!lVa=S(W>*CRnib5#kz%#YW{BD z0jk@SMY?|o2g_wz=EUL=BE>p{ju7UqM%_PzgXJ=fb1h|UmAPJJd|xjOAyTYE=tzgT zc~K*TgXJ=vnrj(T6hfp}htMqVu8<#nCtr=78Lf&xS)H${UKG(XR$2rTyaI4WPDD65 zoD~^J1)$Hh%0Wn3Y&#-SR?%IJtIS=E{CzNxUW97~>K}Gx;CVAYxFURPm#@B^K9)xY zI}0-{{mz{~n*Ufi%sJ6Yl{q#g7dbfNU`e#|QF%dbS^r_RqxTyQ0#`4Hrf(Aqj`{x? zf2Yc*{!%VV;f(Ae1~eU^%iEMI3#pVC{JZfgD7z zcV*P}yqjqy^D4ccm!LO#l)|=g5xg%tm=MS4jUG91L~8!v2sF1l^62A3WMEX`3< zHF?4qf8iH{!-5C5@;z8qioc~+>6WjqyE~59ytH(1UCUA7mzV6(w-3pzhUKCcqV_O1 zFX|Bv`nes|xX;Uok&X}!w;-bBIU}MSVWwD0I80;2d_6B;9WN1kqvy9GUpR5ZBUAHL z-hDBI)`19-V)U0|=(qY~_?&I9O6w2~OCe%wpL`X*9z$pyh!818?;D@5-g{$*t3xA% z!%~RY-Y;Jb8~kqwkz#bem-5xfCWRq{!%~RIn47Pz`uwZNDjwUD>;sYt01=23KNo9R z&h7!QuPldYM2J3%NHP^ih!j5;AEqOO!%~P4zgYwmS_dLTiqX=V#Un(D5fY*42;pG4 zOiLVlUZ2L3RxY8NBlrdhoB^oc**Wn*xt+newepqUZws{t?^&9=8hI?S?|q1-amCIO zo_Fq3r76E;blCjfxd|>;MlzIgb>tmh6>RzC0adVnX)fIc6pY+(Q0-~BLTAuPj-QLz zba<6dh%kTuQYRA-(Jo@+8MVTV^)tfmelmd^tT|fC-nF+o>d^;c$wyk+zj%a5aeD|I zA1;Sf!C zl1(ffENwnItpEIDdX9p%kDZZS#NQ<@4bQ0FST*^2TrSVAf#iz8M&HF|mC zdFq2Wb3XZ>?S5w00(I!*Ek0TsdDq>NNsO-Ohbqimn5{dDrs(a)Nv&o)`7Il5>Y*h zLWmUW5SkHo1;F!%|H)kiYUir${5I*A?OUL(y!7JcYZj<==WOwDOziRp-P_lwKuu}NV|%wo zBh}Z9oA}-9%*nwq5l3nq=c%?o4_5PEnH(&BVPzKeqCiGx%1@Qw`T4GnQ!ehKGO|Al zmb9qBH%Jybwz~*&YI1nh*Mpa*^yf%)+CyrKUf@>nJV2m-ux;#WfbtXX92_Gb+k+Tuor+1Bzn>j!igbl95cec(d%e0c)URMTfa?5_|ioMs?<9X zJ&n%fSlDTMYMq#5ESD=BrV(+?^a6FuGk{=#)`19-Vzk7u7E~Rw z8PvlE+VL*sG;|#j?x;D55h#Tb6GOan^=0ASy^ZvY1MPtbCraqXv?34^OYB{tDZA~+ zSBZU-M~5#x`&I&bEoJZcS^W!CiIt!8FTL$A7w9*NeX4|Kj%yVT_Z7e|$ULyEOLY+`@io!I@4jqDQYms`Rcevd-8r z!^hkxtcQzuyYE;2-uW*i4(;!$5W#ID(TDBCu}d?;HJ7OldmHiSgZ<9-3HGk^mEsX1 z#U%+HA$^dNf%mI+4WG+J4kAz= z?XYzDJZOGTZxyzmnTs5@L^98?B+uJQH6Keg-&aV@rM8Inyi5PO;D&c;9lDaT+b~Ml z?{Z>+ix@@-x=m1>F?x9}a@f0~BVH2ibQ0q9v91n8aGML7Zi=0HsejKaBURmv%N(mP z!rfmYQO*6i(_Tn;2Xvd;zKxc!4rzb7C8pe>jBWJIxl7;WPVOL%22?*=QWS}N|KJ9C zf5u!slwyxaylEY)3e$m7I0n-%Ss%a1AH9ce`TKbpk3Kd>&_OtBIJV2&?wCMJu(s^! zRLzS)SSi%!d3T;O+3z~tQ;R<95dJ=F^_u^kb5PAJ(IMcH%zCe{cbxVL~sGly0G9_=w4sUP!g3hxv@obUe7xGWwe{Q;rjM`Qi#j|fm_nJN5-vsg{-Q4gSN^dP|DRonVEsf%*=)F^7^y| zlP$pcyOO0xHK)wXz+`6TA_wvdG{WR65`ywYb4|V||9U{aM>tZ5_B_gN%gKy#4LIk{ zYKQOVoWCnyIY7;|d0+@VJjWD?%4g#%>`iIH>RB>O4f3R&LgvtJ7gk*ej8(5F>=p*Q8KXDR$$N8PU zO>p#y7cmmaDjT7+V?en$^C=f+YR6%mnJGEDI$q5e41HdTloaLGntah5M4&!b2m8w8 za%Pd=C9~J*6Z~9yaP(Ei^BQd0?!RzKFZJr%vFzx z8|he`7_B;O7>9W>j&~7F`wUc%dM!t*6}LaC^L@ncD22MCC^6Ze`i)-t9mkmTZH^wH zBSfhv`!kNPQXE%Ol9R2j`?-|GktkBEPeu&Z;l4qduf=-&FyD$aZSr!cJ>m%AuqB8v zU*i7-AySMs`2qie5Gh8Oe4j!P!ohNxHhB*Jf)FW2n2ZY-!Ef|dJ4!Kaa*7H;2q%t6 zjSO+`3MY<`*3|96y9WA?q;SNsZO+e4K1*bkv(ErJtP~@}hg`JX9n?D$!ohNxHkm4g z=s<)>F+x1;=wRkv*H zA$^7Jl{q>z?6Y)~-?Q_N{8eARp9i$-=$q`%U|-&DzvuV)YRfB+l6N0zG(ru?xh1GD z;ZP285J7nkzRCV1#9Qls4h~+`J=|7yS}r0`ibhncn{L0nZSl%ChAvOMNh?_7AcDqY z$qFMK*_U6FxRd6nXK0SXc^lC#g1@Vod{Lf1>?#AL_<3s0zzCkB_%{v6K?Kt#UzDs` z-ZJ`4Lr1!sJdO}4woq0Eo_86oMZcU&H}*6x?IQ=vMITZN(n{v|l9B4MpGxAd67+9h zO}h+FrDB2~jQ|plauMu8R2$ABxB6Nf>xtu<7 zScgb4Eu*W>uYIaM4XQv6&-zDS43<d>;9+k-{3*5C2 zWoE84nVFm~YVC#Z&RU{)IIII{nXigRh!pD( zIzpH{OC9aPVI4^0JZLjB(-0!XI)sjNm^@335Dx1=IyDb6rYM9+u@0eG-d(+#@8s-h z$q>=BjC|<`;lvS+4rhI3zB}vI1bwbm4noRe+YuqUDXua)WSGp%5Wea=D*&7sXm-9b z@Tcy&U(LIDUIJ%ioB?o7q?%t@Ld~CbhstRh3hkGOx}VsbJ7?i83i=@+(fzOpGUdpIxpPh z8aN2l9sOo>2)%8;O>f)iUGykF7v0gj^J|1?(IY|#2N6umtj%%dB~6}X7;9(A-p~<~ zYV$ZkI2?%(C3dEcc0a@_(r(|8nU;~0M^v#k+Wml#g4Ewc+!1 zPLZ75RsX^rLBnhE)wBJ#1YO4L2+sU#zbg5AM{18_@7B(#o-=&yv&WN5Xh?A+ALdn@37^G*J<^NIx*_SzeDll&fRUjB0Af z>}KJOCr!#l4qAmJv9D|nq+ZEDJ4-eVx4(_C;t|;9LPrRb1F26b5Du2hw6tdN2$ACU z5LzRWCI?c_QNqD;nU?mCbQFaUDb^u$q{C!1Y8}GCa+yv=31f;vh!pD(n(hWHb87fi zja$RbUr*;Yx3e145?AhwbHTBKpnba@VfNw$xi|x$6rw$^;G56=*DvlJe%fhKE@d^VYgwT%ZP3-a>uw>k;3q zT0draVlp9+g9!LuuSZeOGntvXf56Cq^Pru(bY|vilbM-@fEmsi6FtvlW@-eCiMCvh zD|sHpuF1^gtYTXhN->RNyUol@Lx>cYBy^<1%ow9G5TBSeaI2+aulj>9vK zyryzqsC!kIr$ z_xpA&iCM+YI}VP=k*`cfV-zJ(PO7eL;W`+D2+_ctADRtS)lVN2oKpWy&QG*` z8~Y0O0-6c#9;{yO`&2Nh=Vm^`R5CuDk-jh=i(N14d{J3bb1#y6EU-m%6z3X94g!6B{iEcn>876}Cyr?H zV1b(H@yNh`CNq4BHC#S8l2p#RhVI7Dt zIa4k|_b5b&6r&}^9ILbr;jk1UoO*DNN-~zDoIW8^{9JUioLyOJgm7325u(o`l1yP) zOp6rL;=^==aN-E@n~stUh!S7ohqFZ_GALqvlV?fZZT;ECU}MWZ;Tf$@(>W!AKq)-$ z*Ym1wAF8grCEKrFD<=!jDn=IL{$yGXi|C_1C?^k-RXZ2-3UBZJ zRd80-k{TgWsKZ6Dw@falPyUgdO^!b6QGPByWO)bSNMUOV9U)9Eryk*i6VvBJqRswH zLqJs8c=NoAw^dP>cWM>Blboz`ilpW^cDdu#)PB>0mZuF;rPj|&;H@@1N=T*?juLbS z&$cSzoQ|zj)u$&Xkb?-OC1O19XsJ5k+99J7PjtE=L=M+nqA%UMCTlW28ep{B{up`J z3z328Q zw3no8J(y1QLGogfb2-C4Fk0oG;4XRpm@k-dj%H28AceF-Okv zfiJN>Wg$tnn6FO+$}%ScX&vS~JADeNdTAv*Xgpxl+@-kilc#3z8@ng`-T_bepP&gWT*Rs20#zBH1r z8eQ;WuyWW#YFP98G1vx#uu&5r)={9DwaPN%DOm+PEudxrvM;A4g{eGgt&C4Bu@ ztMIB}r{&@d$q^&@sZ6ILvFq?EYUXpT!W(kk8HcSB1kOI5_h*mW!mUlqDu1r8=MPyG z|R`JU+@D5%e3A(?+SPYp(Zi|8S+V%HZEC$-N1< z8laOSH-DD9_{F@S?r2 zk-V#0?D0oFe^3={-yAS~?QQ$iZ`oTl-MmeK+TM6G%^!PDWUIb&AEd%Zok{VY4ZV9W$9;*RW9Op z($VhvME#n}lJ$`juZQs==~(qowz{OuM-8%GoRo<^VT7?NU|M|0^-Zn9krPLZp}Ppn zA8Hq*Be2!5HH~-w1tC(b&y+;f6k{l^?4c_o!F` zXllXBk7b8P-@89+arx4j%n_+?6TAIG<)a995tk8S?Wgx=?ayAI5z^*ygtR|^c%YaX>lq=#cv;s%4Vy} zHoTd@eh_a>@d)h*m%lJEW9!3eZHwgzs7HVZY$t1#?zx}?$66g@(*7<2bQFc4HeZ`~ z%fIS>532pkp3jYsqEarGB=HvM;5GGPS|=h0EkxZKk^HSyli>U|BSY}0wp~1pUWj!3 zbJ3Ij74+L`Y+EkZAatFCrW2YwJ{;aSeO`l~W`3K%dZ2|^68%Q;!uH{p*%g%kT)PCu zYm1Cs{@Hu;Ri8ea1E%*cKVZi83%!TKAF}^RT%3P>7IF|VmCnOy+lubTslhkiwz;Q$ z_}&{8bPEE)kLye6c>C|s;Rj_s9bt$7I&gJtBE)}B_WS{N&8-bmK1wlt6IoTOI?v7* zP(ALgbRzNHs=aGJesh<&?$<02q zmX1Uzm(k)YMAPp%CpHa#>|aBzu69>~rNk!~iMQ6=?bo`zKz-JZSC&oQ$X4e)+%oai zRXrLY2N7-y-blVW@AtB5e~BY{K9}(v5v=^^S)x)pl)(o%YalNe=$ z%;y+y^!tyGZwNp5&xPS7FTSeVS=xZDno1}4{IGemv#RyHhUIPxYkyca+;C?TU2};( zEEn~8-ePJ&)u%={>cx8!ST1`(^f4{5;CUFkSQgN_&x>xlv$)J{;nN?K4WI1LTt|tN zg$UG5>-JsQVgHlM??BDJP|ry{lO-%-C~y2q9IYSEI-0n>NAm#?Y} znAl; zs_eyjWB?r+AyTf6q7WzrH1&@L)2gp}an$nMg*4x?4)G7qqVkr4b)xrks`)&s`2&aV zNdO0}@?9M#j^Cxq?mQCo&8p`hPzv;sRZl$Dd*wiy{du=VXbz&0(d0gDAGR~l0ejkv zyChc>0;PZ^t2nO8P+axSs+Wu9vQ^S+86k1(d8bw$uBvC;7gU?HCS5{>@N=;+U59W0jfg-a^i04MNjVIoCt~F-Q6u(^wC&mIaexugUZ3Y3qAx-`x4wJb%8$=YLx>b3q)ri{>3fUo-to|lX$X;Gg!nB&gnn4J>)?8I z;#P?iBe+goscj;}H*=m^ad_OCG#wbnQl|((|0bE@vV_AlBAB+3=y(@Bik`l%*IK`2 z?d=IJIkn!Ua(&@2jfm6eyrk8)-Tf~Jk&==u!s+LrBVYtu!gUgT+N!WouQhecS3G}3 z+`Hn@bOhu04>?RDLUc!x99x2bJ}BcL_d%g`3$kn)0;RCmrVzSKxGWgqgw_aoZmkjo zjwOX5^vFQxi=4PY^(a>-jOjqMjhIMBQ3!}DUudz4|DOzF?SXwhrX#{7*(%Fn3#D%} zozk(m$F>aK74GuR7n#h#Sdz%#k|biH(zDlPhu>|lrQ=69j7Ege5dvEfbpRdHf%V|{ z;izUEKx>3VdrFVkTL{9|&q_<1JADv!q{Xfv0^!815;X1nci(gUe0opYN2frs6pRdr zwtXeCiV=I$5on=Bd)}az&t3lE>hg^m!X zwC<{^_bH*c9>R$soUxs96pKK>*zU}Ov~y6kqFPa@z19Izwp`XHb4g@XQ3#P@YlV&w z_pZFzPmUd-bqEK`Wm?Ak;t?XnI)si8(Z5O7q5B}u6D%cjMw*T!BBZPsBBtY~N5=%G zHXo|%f#o7CE2pURq7Wj*`h<=UtxMMlXH#Yha@cl}Vp`U7#Un(DOAi;k#gxRRoBV%t_TrEK91f$pj_$mx;?}~mUY`45h6wUq(`N6BpJ&bM1Zek#Zd?X zTF{ouB}v8`BUX z#RxO67{oAI>7O&W9;~>(a1kr`Yu0?Rq;c^k-=-_ov zlK&$q>qVx~yJj3qjU|j=9eU+O?;Lg=MDJ(1N10Vr5eORlG(yVdlFa%lgJ|k5KdJ{riOjWDH>1-LSPw+Yb3sJ2CtCtinl_Pd^`#*! zN6?61IzpJYi3CeQztd>xT@sb_OQ-I8-ZXC$jBrLZk;0N99cG0bGDk)LMk6gFQSk_o z;*x}p5N6%3bqI%bAT8r#@d%M(9YRM4^ZucA2#0kbEu(hv2$5nPLPrSm=B49DIIII{ z>HnVhz>;%onK!RAgh;UtY1v3e^sj!S*L_e%Y8lTNA#I~&lZX%wTLlQ)ni0aR!u5zO zYXe3gEh~I*H@ut#^({Bc&fRly$>`tf}0A%_vmK5nfTAvBlddEZT4rRSaVk3Xn{6E7F_(QmM_ zKJ}^iWbk4iM)+(MBhFi}&2RQXOZDrel&Mb7MIYNDe@U%F5Qt_S4k8(0B7|^ah{AP* zzf)dw_v)Sai(GKW=O6l;+ukg6AT;H$eAOza{g*%IEZ&nHM_4IB2UkpNr$%3}hrBf7 z%)b83FSYjj|1mHPAySNJacMiPPioEoPpY^jBE`>zruzr$7vy-I%jJ%GH#=mX%sRh~ zE(=?;NF5FWrPyy$l4BJkEC&&6RmxXQ9{9RJ>4i71t@e+$3K3Qc+n>g(@iiLMynOxI z#e|?db6?s6rCc5Cq{z0UgFq>4Se>bZ|Y~n$Lf}mw)!4AF`@88qUAmussT;+(?wVoA&TusoFtx zpRtR_!~p3&o!jf@w2S)Qe7#z1RWDniy^IhkM5i=Jn}d{(wCH0*YNv?XSvX81A{Fho zeRoY*w$~1S>WXumNQ_%J>5&fV>~*^+5*z*0&|fjEO)&BNAsR8^w|1I?^+2@e4Lf6mu^HA2clsq~r;om?@jv9VoThwbNFC(#}G>S#uXVBD+`X$X-*FBFdeU)i>a z5OtocsOD_YR{2s7wjFv`AkQPjkvbjx1(8(_LZs4bUK9dbQ)t%VwmFpRw12A24I;@{ z^di$D#k6>Val^99ILQgrc*U%Oi>7tVjV(9I=tQ^)YJo=w0DJr$m&6!RzIFt6y8)=wsVrxu}nR&2i@P;EU@UtGZ{L?u@%A#dOM7RUaA@OnUjKe^;~4 zX$X;GgtU{Xhv_5C5qpI;?*_UaOc#r=QiO(@-&}iwfAzv4dajMf66mvN*5UNpVB(tg zYFlEro}<2~&|WRLJ)&iOT|7dhxYstkyMsnY^*DI((nMb6Xq^Z;e56HR@d%M(9YSkF zl62%69ayeYr!=byMTiuSB|=9!`dwWi%v;w!L=M)LpCA6NgLz{i@9MWl#xe(ME9LU@ z)Jh)^$v8r!_&L_xX+c{SOQDXUt-^Al1zjCZJ>-3fbs$1YO81p$Cxnd*rsa8rxT1E4 z;QwZg(B2geN-^!|@QOl+6d|lfv<{D2P?;9A@xxN$QKqF%#Un(Dtr9vyTz-8Ae}7aD z%fWJ)79SRm5GmFnG$WigcRVVVFhYEojsX8yDMkpI?p!Ju8}#lxAUymR1Bdt}>PW;AFvSWu}K<25T-?e=jLZlec zdGt-{v$DJgFsAAAxyLSR9=zIaM2H-wpzTgrqyrI!MFykgIo&|~(ZIy{eVYec7tndauzU9ZjC}`~6h-s? zsGtZ25CueniYQ1>IN*-E-5C`GL{Ne`AVv@rKC^&u3nCc=iVcU4e+?up7*LWv^8Z;rE~MGyDb*z&5u?6}B>Q!D4A8G{u%YR^p;xd}3a>dylI4{*@zRaG1 z5#muUqo<9p{ttw3K~2WHEQ$Y+!evC*?Lo{5{vUIR7rBhyHFlIB0};XnHI-mT3I0)S zWBJO9_qZl!Qui@Su>~n#O?<_9$>Kw;mAAL?@a%Vve$AQp{@UxW6s4G_xm5TUe^o&jjpD+Nuz6W4s8TfO2F-puXu<2WM&!kWRg9dD5x%g!%|V^2gx zajl-c#q(bpI6!^z5nrL-&nNM|{Pe z&dgVIuYos=ZV*_p?%^0BqFM>saeg^E(ChQ-k@TihAGHvmNyPFVi4}PluYM=~5}jo* zSI=jz;X4x4D3a9x?NfQ%9^5$~7OEaDs{zQP@$rFf4>eMNqAVAWqD_wT{_cFQ_YZqg zsWImz0iir98roVFP`>k9ed~DLYu~{c>tXN1UP2k*{)0<9@eKmhH|Pd|VC2B7;;%Ni zJBbuT*zG|#2zY#hK<`rz@O?7jJctOEZF(Zv+xGc$vwP7!6MXj|YK8J_8Ea3u$@_SH zIq&8BJidn|TvbRw)+)Qpo}AmT5vV_>ZA4Lf=#_V)#lQd zq6q0RbWTkznBBKrFn+nK5JEu&m&FTeUJp--C_~n-c(kh+HN15o9aKVQrD z0gzU*qH!sT5H5b+biB-obRR&#_W`ufS@9u-xdcHuvHtP(Wlw#{;X8s`wjA)k&Qn?O zAs4R(W_{&6SU^OzGSdC1h8e9W|2%*j1Vk%^5H4FrX$a(kGL4UK>m9cwhw@7%Q#3hi zA|7QsOdCYJJK)#1n?G!_`_Vs$Krg5}2LirxAV=S}AihF7d|NB48WXC>g z!H-tf@tQTgS0SXAFv9ypy#p#c#6G%v=hG!EjOBcHLMQ|41&@%7XbXxA<|?5z3E@)< zjz8%FwUc2kM3}O&+-Ue82(SYYZgH(p6VrEyxr;=SU z)I>7iE(^7XlX(d(=b8kqa`gjqAAs8L%IwTsIHEE=@$B>Z1rxm9?y{!0Dy;+oGF1m->f)gICYAVb+Cy8*}fn7n(ewYm?0v-`s_0po)p74!+7O*M?7P^WK^4ci8)|8c|4L^jwIC zPvc^et`Jpc(T%nZtW3xMWO*?P&7dpO3Y?4zo3!z{HR5FATMTl&=8ULQk(uZ7mC{=fq13+Z29U$nAj?M6gYn7M%6fqbg?UAbA(9je0kO z_`H0hWsf|(UbP3-g$R`GIOBf$$o+Uyr=ZICFRk&+Z8O_M?BTh%w!ElTquj%!6;cqv z?IdW0NNAjnJgb+9%nP|V%1Xux-*tc6lCAr%IaR)P*|_wh2iZPWTj zj|ldNpf!U2O|T5+`o%=)p(c!w=fw~q1ra#rDeJfL&ZV_qy-#U{bs<+VJ4hq`v$bLk zMR%0vIIjPq-zT?LyvFyB23Rk)xh*5F$#t>Ure2=f|5v_>ZWF&_t6|UA`mjb^Lh0D^ zQMQdh3L>Z`7#}o?#%UH!(=5vE5zbMFMw{rju;~ud!VB+?-L(Dj9OS}!ZA9;!0p8!g zw|4Jo`*2P~ld$)dWI5ZT+hY#I^ z=vyj9=@n3v-Y^rTHyWb!1Y!4*ibD(hzpJ!%-~U=i>5VZFf5=tb4vg3W8DZaL4duDE z9HaDvf?R0ReW)=J7D!ZneAuGqm`SQa1tH$u2rD=9O=ZV#w80i6R6YBErZ_up^vn87T=?W{ZZ%3Wk@zo}-4`jGl z7I`egaY{o77t4^cMqtF2P>9RLvS|3<2;pKGQdS5nb`W&8ykJ|7(T0c+F4j=WEF<$( zpDBO{x%hcz-wp^B35W>cVuX0XlA#bn!FsujmRoIZX|mr$F(TTMq1GsQQ^b0s2q%G2 zlj0NN3i}e5MIOs=I7%;!vqXe&u?#6IKmsEHg@W~RS^TCDR_q`mgo|ZJIYhW7J~8Y+ z%q1S>vUudb5yHh`P6>5kiR|Kr6;zTpuE!?2AoW z1|o#QG5`U-VhqOhAp*+2cv{Oqgiu%pAY6H_5g4T>6h=TfJkcwTD5+;KTAtILQOnoI z-4$*8VITLiPP~XKJOkpgc!73(>jt>px1Ah(*7=%Z2;pLc*hIf2RPdJj$KpQ01;58t zB%nx-uI*wIt>;rFyW{@3Dmd;>9SJCuC?X?6+pcG8v{1@sbymKTwU#j@B0?^Le9=bwmbuSL$a$>g;G%Ca&)li0ixGitD=(;`$7iI&XJ0+KTGYHoQx5 zePvhcxIW=xd8XbH5Udenqgsh3{5;Ew>-(JI`bL_#KG8iI)gfrEIT5s>xW4Tr#Ptc9 zW&9q-^_@!5BDE=6WOxbDBEp678afj2CyE4ori4g9(F8TrT3z<~bxZFlArjEYP@WdA zYXtwxf2^-iKzD_xRB9xkv;iZqZH#yM6dZOL%!LTyg6FieECr#yE+E2gL5A`FKzD_} z_AqvoAVb=K(ZU5am0$;Y6cLuMyc;MIa6t)?fW}uUMnhVYw5PSU+JQ5(dziRB(Vf3% z3&QRtj9?u9As3g$KU}tDXnu_lN)#cUW?oxH2?!NAVxDVXd0mf<$-cF3i{>C*aY?-x zC#U23W|R`wC-vG0K0$3maeXHYDIV7+t;w>*hxE%16hU|B><44_o;b4z>*CmtuOQ}5 zTGnx*F?T|VBBcF``$`b3iEwdQG%OXNdIlmgb})w8M9tJNa@0u0wh_N+euGfaZ9)Nb zv7Sh0aTKdo-Nf999T;r}c2JwAzsmB@rx?iP6a$GAM4;D0tyKSov8G0?$b*{Hs8yCT zLfIi+1hnd7g4Qx7k{#nqh`AGVaT&8I=5E};0qWa|_=>rtj5cW*Pm~gKXAsIJDLc;J zwK{owDdukU8#?ArdLKvGG=iABPr{fx`eh)Ge;MfC-8$w@D2U+rtLYSTN52e2?JHG-1RP9SKM+ zSe@*6eeBWr_qR2Qaoo}{in+VU#N3HI8!=*be{cK`Thl+>cPamBkKZ0*?!;Gizv7s? zp%ins;UgV$CkWIX{pL7dP|V$Fe;-MAI77$W34*yE)A52T=1y#)Tjd+9$Q!!$o%mQ2 zbJq)E?qsG$`|Q{#te5+h%+&Cld=-tk6HSoI_SIL^9^=Y5{_$hgFEv@ZOBMClnBDoRUivh5ghY@pY+;nDP+_uZ_bKLvqYwpJHXTwfddWuPn0)p32&YB-B> zG+m!CuCM!^eD8v}-^F&!?^gn|gW%@4P`$s0v+eP5rZ=rX1u1_e4Kra-J>oW*tc?lYlR^VL~r6&l~9b^!Ke!C{%Uk17^OULzzM;UQB#Px}N z%JOWC>k}DRFSoxzkc?;xiVWyW*qVee?VzHXOt`F;#F$f5fA&4$xrl|-zna`O^=34AyjzhY1 z>dtDY+C$m^WT?HU>^Ri#`~>EAepFna)P=3a=>HpmTu`>{P;q@y7s>#es0F`&@HzLN zK%YjbbE%`Vy`HSWc^NyUtaZBSGPxd$ctG`Dfh0&ENjF4|$s;s|x zJ^Slw!qK_@oZkE`HROt-MIQaSz)db zgcn5!7oXM(8US<_fE1R22q`OV)a=Hk2*MXGetzw~k>Sl0BBz)gp(ZRZqt)sbXQUea z**G4h}uk50>?z&A!U5;Do-E54q1Gx~bv`VlMYzHEcYd^&;Nlgl2{z=ep z%w{NvK$|pk+eRyvimy%|G(v8wbES+L(yCVbuO+WJ->P^xs>{7*%SeSlF40!s4>z%C z+eO(UdeDt;2@kmt%`GePLOT+SKnfz*4v}pmm}|j>qm@>u2_xirh@e73MKlT}im+sm zM*OGauLOZwA)59+|N9_S>Gb)jGCT4;?5`1zK7LS8_p_t%OFGqQi3sGfwOTQ#VXDkoRZ?%# zI7bR1*uKonuxMa^@0Rvm)ohKLNSXbE{Y~uP|LPX3STHKQ84t_9T%(^W&hY&My~}0c z;>Z50mF!$X3 zl|9uR(W$l9@O2XpXDCs`c~^`u_uMTQ)6Kp4kAv=6cip7cbD=~L_KI`<$&UBJTz$`- zP;jQ^vecw4FAX7FY=@LJ0^{L?g7tDaV>x3=LkJhkkg}FxMYkDWVZB@yum3kfxLAgi zY0a29*ROhaZ*OL`b}r7;STD+>xbPOU{DA{nc@H?J6C|33k8h`{l)#B^Jls*uYX9boYB4nXlvhY zjX^(=7!}@gH?7gA@SZ!|A(xI2E*g)NZKKg_g^dsjb0K1Wwb8H(|LXkN@wFy`4zzNy zEE;N0m4*;5mM3M6sMGjN?+SfuT}a`%M7U5xg|On`KoiSvVxN|Q@o{lh}&IoxP$_OLq zgo0dL7LWWlLbwRwOPLY&7zEud%SATb?Em~^|9_YD2{yhMFShpa34+AKwf}9nx##YO z`Q!Z;AG|uaeE&&7boLQ0n!DV4YmG4X-1UCGi=T68h2Vi}Iu%0*7bEuEIl|m?=Rb2> zdP@Jc{tHWVJe*LNOWul6w)Pd?S|?nHpt3JD6-Njqf&i@;gVAk>z_Qq+Wt4^xF4juQ z8iCPmLSe0-?2D(1BZLw`xbj>hFdj}QjDWH_{nF=Gj6p<6J%iEmobtRH&xqHl-qyd; z?QgwD5m$J2!e#LreJeWSO}FX6KEc)tT^-$KdS7&H7Y!+sqwWOv`$O%6iIYy^(~r<6 zQH1!-an4(QpS${n@LrM7sW!eB8R7gEIVU4`znf%QN&z`*4~Xx zf7Ks!>!a$;2zzxz9(Y&kXG#2?T=e${zUNNGW%QZ%jLKo-=g&+V#dqG(yXn`In|R}< z2Xl|_yeAhaTo#0L*$%(snPa^2Pj2D2S-pNFxCAoPnXW;oa@V!PGPl-+b9)qFG|?x* z<42l1=ys7-pMLynuG7d<_uLsfEUvCs?C`4}8SQoPw)l<{>;FXHJ?W;)ev$B-cBWhF z9v|l2v}UuVm5un5WOQp1&&{5bC_)NYuFxXeaTe3BMs#SoK5y5m(aX>$jL6cuyIjtA zH`*RTi6Y*AazrWj+({cS0$bB~H`5;69I8DKAzX}>wqd?-2Y?7=Eh4NIWlPp!ln8ds^jQ8+)b*+nm4AN~>`>V>w4`6?ONP z?J8KTZZH$BD0=YT(cZVmKGk-3l_wm^+49!4>b9P9H;hy_;|=Mw-M{OsG2T3Pi;DLV zuPe*L-pZ3lVRk|7o{7b2uJx#s^9@qgGM7J>|g5RcIP44*vc z_8igN@Abu_9*z&t-9^6@*GhcC2g{D+h%B4fGc)gu?i zvzl?R{iU5WzZr)rR!t~?_F0~wHRA1Z`QFA47U=JTW>$-~rr1aK0i0Po{nExkUaxjK z<}Rebnt|;UYNh%w%m8X;5HxzkLMS^7S7``p^C#nle)eB|ykF)_ibv;mL9-0$Z(7D% zbida0K?Uk=Dxsi;#kKM}wDK!-)KPlkUGS)je$z58{O6jW+&fi*=!_$6fNkSAyDlE& zjhV@-52NO67pD6a1|6W1p_oa22uwHOuNrFVXLS#c^+JY2u0kH$Oh z({X)5K?Fxrjh;N*+@%+d>oW)y*N5_?Cdc6@y*uG9JwdPx;j(1_!T~N7*C(0)f<_d_ z^-ZR@zSm7$-&18qg>ii%&qj>8y-jw1x>xOWYIlx2>UR0a@Gd>^6?$}C=r6&le*G0e4X%xlv#eO-Gu4L}g69jYpnKPVsNGh&RY;v6J(^uq8S@%wSl!@#6 z<=&CuU3#)!am1F`7kXFCDp)U+(Qm}Z-tB&(Qw#xiAi~vAdY}KeCw0QJ`Yt`AyNbCI z4Q;K4Q4UVSk-K(SY1c6*A&vBx+?@1fryvwn159N=7+xN~MbXEM8hWhqBp&-I; z!9^6M_b)~1tt+de^kjBM1p7^T4CU9Rn`VDUy<~#9eNVJPO>7x4iadLlqVzs8QF=0m zGndG-WgMg^y>WE=-il`W_B}x$7y6BU9k$lt8&(TdeUE!3(>`+^rT+kQawg$vJuc<)y_h8GVq*wti<&- zHgSE@uc9)fS7ze+el~G^LO}$V#cw=QXLiUO74rUddZcoB%HWaVeSL3MA63eIeTWb) zMql^yaI@2w`}&SE_w@;dxdg${DXDCksgF`z-^mo$caDkc6E0peOgpPsoD3prhmoOT zu24gf9Y%%mZeK+-B0{)qt)g*#f5^d)RfLPX>G5MjzH(#>f29|*7m5pHp< zqz%wNTrSZL71xId;bMenXn9w~kqHIsMGfiwoZ|Wxx5>oynQ@?WmodSfHgho9Q5pid zpiI8{lH&TF&F$?E8>{2`uwEI1fFK!ycxJ4Q>ys6LxulO_uT(v8vFV8cbD7?!cKRX% zyg)LtDXx!W?mC*dKACqBZ6hSE@3KpET%RD23%qM&%q1BeOkAI|8pu#Pa+$S@$MwmW zfO`Kw5iCRMg)(UccBr^M;X)Z;lTW9Eo!2h?jNT&uJ+6A*zt8VZ?ylF)YjA92i&NHC z^N(HB&in1uvzu;e*g47N*BaNjdB-!{ ziuK!>H~%*uZ?0~7(%Pe5~Lua-yfS* zO^DE_|81z|cbrk#W6EjQ)(*?{)^GOr?|RQIj-cO@$P)yiT`BYP??<#zH95|kS4?dB z#A&_A2MIp?3n_>|FF4M?Mo(q+xTa;6K_sPKY#Y`#BSRUk{z-U9;j*Afc34w}KPm$e z#Vk)~oU$XV3%SrE#bkuOLIjmv%eyE85g`|87Hb6y#~QbXv@^E9<4l`yUGsPEd5-TL^w3(=#I}5F<4we^&hGQX`g%hbST>AV)j+6g)v&FY`|B<~L;QS%FGg@RgU%fMfZbJC`>3TK) zetIS&*t^oNP@XO0tdE|q$Mr-J$i+3WeVT7x$J^@tx#L07PsU*#WM1I2&+#h)o)$|4mp3a84fnpgg+WO~5j?e0sBuJmTzG%pv? zHlp#Un0NP0UES+{xWGfogr!^EwfkCoCyrl}hc(ezM&HV@0n_??I%H?{8-nz{__m8w&Zmyf>?b+t;J)oaEPM@bg zFZz+bT$bS7&~IJWZE=Uvj_mQgqLvhy(DCXZc4CE~_B*3}@h-Oka-lrO*;22U*K7Ns zNfY)y(aNaVQtj&3fx<>LVXQV<~?(LJ%*&MN8p*Z-0|{PTQk&w#Cl zeSun`d->qq6)&a+U3a5p2ezijV6W4BShjg^^qY-&bB}NCAs5Q95$$T;o-^@SQQpr- z^SyVz-Rfq2+|hgg@ekc`3%9yGPiyU6@#2T>b${+~$F0-P9p~Ylx8*D(#4m(E3L;{w zcDQTGYqaB>wX#a=ixcv_33LL2h$)+Qxc{r$&a3ctMHgk$nat}|VqX#>NeHAM;_ua4 z)&7CebU$_Ds<9SF@_DUJ2v_^D-^PTC%ksP!!a)imq^uECxA{v1()+kx@h-~XvSLnX zNFop!QH03Qh+6Zjq&A+AA1tPCMGqg{=H@h8?e02rySw_Q&2GOuU6$TXb1_+dtwAgz z1X2(oeL*8gBhku3E|hnS+W%3yiIZh(3yd8eQV=nV+Wd?21aWbrs}dw>jH!S_Hu@h3JxHeE8Hk1xP`J$jiu>>s3uXJA9gj zKrZy5_SHR?X*-Zo5<<)PgvKD-LWU<~Ot7_5W-dYVb6RTwfs~REp&h~47FE^Ql99u0 zE@kFIw6Y^;kykagrNiBY*xRu$+2ez32!7A48XK~2XckfsfxS}ol3 z<3&O|-k{EW;bPs9OKj4!Pc|W1kybAscpwWYh`_m0Yjq-7{zTczO+^N4A~uz*)#-%b zzKiuDLdtqBncb>tipB`<862T-z1S1wdFhB~Zx^&iTu@ud@RHLiw4h$%^WNvan@4dw z`?6bl_thQ#z4Uxvy{D;PeMJcJm-pEV^;;kX5pBNS?q9a2wb#Mni<2z^h9J+PJZ9`wm{Tv(7W8A;)b$@qLmeZQ5c96UZFCDejfByTxo&LwfTzRhF zQr~H%#z!#mirgjS6JK^@WUVi|u$c?D`M3X_aM9>`L%Px~= z5cQX!<-?=Z*@wN4FMA)9E!_NHIu`}4Xr2!dC{OK{V!XdHyCpU5c$N{%xs0+MhjwHk z0x5_m<;bD3^vB47RbdY_ysvA=VpXVanyo_zEdeglMRxh-SjYbxD~yL@SZO&$KN_DG9-xs$T^+ zww|5S{;?)WJXa@l_$`FXCAT?JqKK015H91HTh3BIzB`melc~N;X^L-)(+d}u72ZBAHQZq zM=+zcjMBdF%K1LqA!UtdHRQ6O=J0)P$2b3Uqb(>};a6G8AIyB`Oi*2FPUO0zT-;YL zG_Ic-a#*iX(_e3$_k{bN8=Uq=Ov-)FXyvY)&^kH3&3o?P>7UVjrT-GaIsNA^Lkc3^ ze!X>)YhtwK=lHIGc1z4Pr9uZUr}=W1%N##3WNjyx5%SzdASH?rv{B0R6y$=k&oz~d zKuReHU(29q^`DZ6_HThp8ieN5&erB-B)iT7N;`9&a*Y;raDnRo*o+@^GvOTE>U%D?uO^ zm$6?_#K61nH9hhDkxQ_pfJ^yGS~m1mf=kRLlqkZCk4&3~2%$s~;zO?4wgVBu#b_LZ zB_fok5g{H4Wkj_?L>}0e>4_l%d!p0}HfaRU*$Tm9P&9!N>~q<&!>ii!f)>37RBg_b z^)zZ}bo$Qd)_MJ3xyCzx=O%?PEvUWgo$|;DS&I)Omteh7gtQas1M46nxGY>;7O(#| zLbw27EWhh=zs1E_*X2OH*6hR2WmYOxhML=DR%3*Cx;R28%!LRuYSoErW(R7EUuMU$OsvCT$bKb93hk_!tN!E<3HvSN)#a;VLsb(L#n)zE7f-$XYMuqf;-;qsb&M= zVg$CJlqovlpWA|uuQ)DfGNxe>)(h6Uwv01>&kufjep;;h!2c_z4KB<1EioiWF8;7idfv2-Ufv?x z4n#Z7=a*lees6itw9_%)>+?gM^wyI)dQTntQdukVy1rdI{p8Enc&!?9PrUB=GU?uj zPmVvjG~YuCYa$4=&v9lPKQ6B+_1k-M=cEyVT(;#$Ti=(vp=`d_ZdHMWKrXb8&KbJ7 zOOBPx58j!!AdVKIR%joM+DcCa?n6!eZL2O#Ap*H<8Era072N!3L$~E`XT*?#2((Z4 z67wFVMij2$rf2x9p**({NP%9W5Q5eS^Ny2dgsc->He*|@sPf!KaJ@o_A_VO?XK#5o z*BLf5`*)70itLbN=fr4v7oohntMhZ~)p;`eA3`97wlwxXLnGpme`GCKTFC!XH5&K+^?`=r%3 zvBj|;@0*uezEfK+{%K4rz<~GHyJtKZeY?A0Rx-9M`^(hbU*!jA2O^GJT_>J+XRX_z zJHHQBd16!1c{Dy2{ZT5GBsCi#O9Jx>{ z8`1xCR=nX`b)-^Lym0c;D%%X62@(zpbs`&r9Muq1grL8r3^^$6n@sb$EI=Z_~&F z?i)k4$8mgMy(rIdhRhtE96)n>x6Vt|sFjh!y-(!XGCB@9BYpOom9gL7r_~emy|nJR z=`K?{dbdnl?%Rk~vx`!72Ca^b-fEA*(jYE986kPo8i23ejkv z*BC^MlEa7o^cb)QbHkK6ISdett6er)Mv}##=4Z$c1QIt7C1R3N{Y7$Zb6- z7DoyqP(#OgvCUPfgO{#ZcFMo`0lt~ACb-j=HyPa%^}h)vc=LWv?WT2U^U$_%4i zvLv0osyr{sC0k5qq%P-={c-Bq1#}LZXL89%2IZ2e>@&(G<8Le>1rcY9u(LQpQ* zQj<%TM<>53UyZWNlJwQVH@Rf|B_(Nc$qH01S&qpiD?$n)C|+Eh$zHwYIm%0*T(V+u z;g$ZJGM!==RMyT@{k%nTB1|W@+E)pFC!}1mFfN=ah>&RP5MkV#iEn2LorSAdcP>)| zgo;`E?I%eB@2*(2=s!=B`Y+!WQ$ewB%2A&`sh6M0;>`b!uYAq5dsmI$b@1sSEZ zLPW?#8p;=w2m&csFMQb`1bhWh-#oab>OTL*h0G+0jCyAQamQya- zBGn?~U8F=2B2V)IBGd%OojsyT`i^6KrO@Q*>4+{}2G&d3hW)rWLV6q`u#Y*;W8?q5 zD4}!7JZV9iOD-gYYRylZ+;9;^po-*kfCYMafV9TQj>G|!y z@$1q}h-7(xol9mRkW0o*cEj-`gAvVjeiY}WD!&uOvR2xIWRtI+T97^SE}cupG8BR- z=pXc(_bM=?@bWG z&h7EjgzVS3&9N@zLi^~qmv4A2%jA+-zCr})XdOUBt?;k<;JpoS`! zEHJrbamqyUO)eQ{qJ?N1LAhjs$t4Sr0`WIVtV!jPrA#ha7;Q*VIu;kARW4aF4;1bOXiteG8fwexlo?UB@0Y0 znTr&(R-%*GK9x%rm|QXofn2s7luH(vTrv-3pjIeP<&ya(m&`*7BCs`8E}3s~$vmVW zLOh~Z1Ii_fn_Mz$&w#CleS!LJ_wt^}C9~|n))X1sPAZqoGr43Kd!9rYHUc6u1Bi$7 zA*RfS=tg=Ird+b6CYLNg3L+p@kq{D-N)e`UL`X~`#m4z4Tji3em{iIoiz5XQ5<$mk zJGNH1D55PTTwIptr6ZVv2q|lXnN1QrXG!nldd0gagUgDaxcM*PiS#H!WN3s$E>kX9 z8X}i{h+_1mx6@oqmQya7#5$*uf(Yp`8o}zYPV}DuxlkTNP?C(yUm`#XA|TF|5D-Zo z!`^_sq;v#Q5P`BG8uy%M3dOtJQrO2(wnmt!;w;o1{f4r2K90#H%R&kwipzjpGRYE2 zN{``LP0G5>DJnC7Tr!Ee4cnO!CCi{(vZhE8txA?*a>*`V6e;3!!Whm29h zJ|eJJ>S$b(OU7ArD#MBOl`>mvBUpyXCA(C(7=c`9AKmFh2$M@zh!jNNT&cA(xnu<* zgEbLrOV$c<$t2IiM}(C1T!L}oLg9L`C(85E5llgZlr@5K$v9e_bIBG{FHw2)luO3m zmCXAjM9uE`}MJ1CdTH@Re( z8*Xu-Je5o4np`r@L<%iLJ8T5ylDQ_A%tHzyY&$5IEM{`a_>CpB5E1A@l}qNCTrx{5 zlxJH`xn!QnC9@F7g)OUc$vl%w<{||V=xLQp=9yfw7$T4h`~^$pWMxLVT$AaFk2tnOw2}TM!W_Tji1kCYLNgF6?8r49X=7OfFg2f-D^o*fwfC zm)!6et%H&^&U2#VocpvA$qfQ}2M{8Vf(V+s)?E`wHQ$)o4JkL1z&C|m7H5_)e! zXO^H9B2b={dC$8gHSTzp5zD!ZvQ;jb%I>G^Gv1MfS|I}Esa&!=lS{_CK6PIL&+Rm8 zyZi;5%XYt_T(ZFAl7%;g@C=6tX<0_wcP9v!SqDQIB3tiXOS)~LG=!ERcR)}s8Sld7 zo(bL|D;bQYy_VcFK`ltRWavxB{lK-s1YWYtPr`-CfirMXE3>BO|dRS z+x?0WCYP)!QV>yGhV1$ffm~A7y#%t!Ig2h_$z*((-9YFOl}pB1jhw|3-nM{akP(8` zI{;oaWnUr`=E63Y=NSa-;nZ5o6hzoF1IsYEWO##sHN)BCoOT$2$t5eq9)~ip=c_hX zHwaKJ*`-K9ggwq#E661a#~pG>O}ahUvnH3UKzzc!5=7K*`W**y$-)^K5mMGND3>h8 zeT!QVdkJz$ndRx6ACpUFeM_S@QK!JX`fyp!NV#Tp&X?d4Qlf~=88YXqnOriyO*8xg zN{H|jn9D3fueJPM&h_&jQlbc!AqeKxDB&`?qm0ld=H@?zNDv~V2%68P<+(l!r(CkY z=XW)!DW^q<&u3R2(CAZ5DmFz z{?on^t|&sZ;^&%Qe1#N2vsUt4+re#aa>?@WT%EYomkr{Y&gGKrKuQ!*vK_)@JQ~U% z4OO|g9Y_&0YbDS5YmM@gnh&|e6wz0>jNjCA3z0wsQ=$mdnk0jA$vl%w=10ee$ipwD zDwixUxnwSW&A_jr+;};a6Gp6*;_-lx4N)d1rP`&i{Uxw|DU8O|jA$@%ZZ1*~(T8pbo=1p@3h_(hE0)o(XL%KFKbGt5>6AB&D9;gvzN@%* z{4h-AqF#A*m%M%S{FS0HbW7h^=ap-D3L$=#V)9Hby(CWve z<*}b_b~m2aQ9aM_^Tu3M9SkLB%;3tu?-8+G$AwmDjkt!c|Z3L_7@4NS>e3Dr1Sh-B>8dRjdUK zNcEDiZ4p7<1sS`YkqcY3KTAa-VO_{odf&xX2$9ES{ns(MUfuCa^%k2y zn1f{aN=CU_bieK8>B_U7`feYsB#8hiSTD+RoZov@nzgO*NyQMzB`xceVHy0l{^^Oc zSO!uMAw5QOzf1R1=fM5c;&;+YwK;PUT8&zb7bKTDl+h~m2_kG6cM;-@O4G#h z5P@9wT3ajq(ZW9lm*d$dKnfyo)mFYr5Vu;9r7!U+ETfjo@?3jX|7#=o86u<{A`+|- z{lA3t46au!H|5ZWg3>V)g5Vw(L8$pykHP6<=+`3#9CY7oI3|hn63!Ah{vGF$t=+tz z7X9N^Y&$uPJsfpEyZjD!WbJ3X_x{{Rceky4w3~O<9Y;OFZJ<+)XqCw z1jvPG(N@n4Bi<==w_iCk`O=cU76Q4@>yGnR$FtM_TYi2{mCy1$^r9fxqv$vK(y%Ve z+t#s-+xGTLJk$!&HsU>}d2r9L`mrW-vjf(P9<>plKU<+?-M`O_wWpJV_P=j+??{jI z8s7Jzn=@;xd*=3`-ph1v?cNiaiDw*Y*CO`^d2W2p7uWvg3?M_DM}SHYnhjiDysQ?zU;$ zN!F*^as_eT?QXvZLbeKBc$E-HL4>rXM$jls(EsQ!;UO2wyXu{-?oGc8 zE#Vegq#$B%a)}8@0o>2K?M3xBc3A!drK&E7M6#tDbKZc|0S&|5n}46m9nt! zqCD(9)DsEu9wGX^v92jn5K&ylN~0AbkV~HHe#O3eJ?NVnJFC$mq#y!qqSfGs#$J`1 z&-GqC|2-dP0PMRqg6s%tru)Xe9ndKY`xUmD-4jWxU}(@cmaJKI5mFF=?XP?lY)tlz zUH8JN76P?GZB+{fT}Uf#LE+-jDP=VV&H53xU~nfPDlL0O-S;YU25N|NjFxd0A+CM< z@@7auglz{~KHg}BT&TM|=l(`B+=jj>_AuLl6lp=`lIPlvk`PQmgp@Vn|Mqa1J3b&yyI$R z2dy~ajz!A6s?B+AtH14$4qnCMzM@^mvlDB_>fCj4aK$N}iieYxo^N_1u>|ijAOoH>8w=&@;7J&%O0}C*#ZhN)SAE(YoSi_E)s` zNxhxfErk?Bplr&cf40Ih*~4MmVyoFQ5P=j#(99QVt7q!Dv_{>~^OQpLF1DtO4?X+v zocMdHZ|d#DqYIIO2-MbbPB@q!%)9i#)TZ|j6yX>Yw3-u**R^+f28ESVwFgrWA!V%< zAQI?BDI+>#$1<{f$)pZh!o{tI^`Z~M^&>^=$3mna!nT~|_84o%BSg5&3J}f=@?2|G z5`rnx+Yuew;nkouYFT!bML5=QOkn%#-O^}6d{DDq7E%x)@-i}D9aOqUwZfTC^((J3 z%UJq$7WO!lhdo~-dJtma&GUIZS0k0%0};iwf;~fsKrX2%>{s4rv@bd7w^J9PzQ~1W zikiH&OX`8Ix_h$=|MaDoa9xPNK22X5KCI&Qz3djR!kvz_;vfQLJI*{hZEihlWXrW{ z+UMaJGI=;Wp~q7rJ>S0aWoPQ z_jn&E8Aw5dl=V8u7+wkZU!+Kx9=}E9&?e^NzYq~pNpr*#^X3hL4=gG47Qv~3I2b0W{Ibc@?0!0j$ld@At(1-GyiGJg)52> ztwcr!ffPX#^(}eMoT^_1Uris`@`v^9lXzxHT)sK+bnvSKV-i8rmAYRc1rbs%Q7ct1 zQ-q7_Bn`vo{Qvncv^=DggwVXg9bfbOGOkNbov~g#hu8HlS#^6hmym)8DQg+Ge7MhT zy7V&dSm7To_7eOGg#C?n`v1pSID5f9f!y)y@!n&HZsqZz?&Xv(4aBA9E=HiXj&s%E z9kI20^Mk1k`xSLRT+OevrGt0s(;M?TQF+3K4j$he*yz04s?7JFXQ@Pm5p7@Y>gCaGn%^C%<~OM| z%5&*n&I;$&_J66-#p|MO*}P@jYq{I&z24$anzxXG2$r|H+eoiLcrRz-&BT(~D^p9E zvhuc(UQ@b7us+p$@U$-8CEsmQzA|$;ub<>Gg8e35Fuqb> z^=++$5=Dr8+-{{Kgp1Low}()e3lXMl_mTwG1qjuzq%RcLN+?l;^f86-#^kTgUO2a0 zOYGq|R=6zfq!Iit{~;xckk({Ay>^s@5H3cG7c|23_C-uFcDT_QRobbz4AagjK>Hv= zdsoeFqLuhPim-jf-28`iaap*yY_5!!X$%wyEj$$_T0V4ovnKN)?YtKG8cM5`WtI+w}()o2=PdW zNN|a{5FuRfT#qQVYDN%h9YlmFyUZ7AmB6~VEL>cczF;AgRzis)q>ri9Ib~Mo+~~|{ z(5jb+-&h9!sj;rK5(dc~{fzl;1s95Jx+r=!~yAHUBy}c;%qr+kLC! zs5>HT8U0Q@obx*EmNwGul&A^XWLsXaV?%ajx}CCsZl^>p^qY-{(e0FFUcA74ZdR={ za#?6-C&y_(w^JU?sqa^y+bPj8>5H3VJ&g~NGe>&4bUP*1i)gyZ)4M#q z@~fWdpE~4wx14;Xzw+jh-T=Ct66IC-r0w^Jeo5vZY_ugtrF8c{eq%Sy%? z%5%qAebec&dydcd9<5%e+FU5mm(;#Q_Q9bH-sz{gE}1#GY{qst?`CFE(n=w?-qH|) zcAN@7w#!>k|IM5QwEK&$oU&T7yo^=@_nn(}pxjeA8wi0EmL~|@!)rTUH@8zVmq@C0Indlri4;UU{LsF1v$HyT`gY3C+APRhK(|vqv^PkjbmT&`UO%3v^CZY=GlmpIpnY`S{_rcwBTjxW+g+%}hxAd_M8;sE`jvjoT_e0vqxr7M z8r=t{_Rn6GUikhX4=ISaa!L(<53LNpsrxLSe)Tr5YT}5y`R?!HI6jaI(Ui~mQ_b`P zkKP}jc~8EFTB*iLG598u{5t^7;qt$5jEn|ze* zIA6|gmtIl-X7___{j5=oh`A46={KWy_2*XbU6cQgI6E(&X6ie?D2SsbSg(!v{f+v$ z|DKlb&FweOvK-N9AIDtzMc-D;59Y3zn??&!E3}Wk6&%+uXwde4e`o*fG;$%@)@s+& zPX*6cI^S)aY!OEaB2Yue>AOD_D;(Bs*|?wS8+YWrR^Ej04N1>e=bkpRh;Qsg3hOQi zZgVMXgxT*F+vy7zpp!NNDOfK&r+0&P`%|g8&nP>*=o^cXk;L7(mhtVW$_@`HAR}`6 zv3EzyVEeQx!M3`Kee_k-3uZr0=WvAZ48ldNqVf!aB3CGHLS;cv-b5~)>F1fei3N0W z>vFEd?UNFP^mQQ5(F$4kS(9M4`%?SZ4Aj@{ocEIxqD(Z{nm2>(dRG`cJ=o$@wQ|j7W4_cGe9u zar{})On;@+yZ(^azn+UM)Vt*~(9wu)>-OFjd zr6dtS@?3cy+Chbcg+Q)iEofk>mxOJL2=Xq-puCA@CT{}cUe(R2qDhH;S80W<244YG zo?oT~DQ|+t2mfVa=(+!3y|z}AHxZb;37@_wxF&C6F^(=qWMoj@M01lj5yt7W3`C$j zeb=PPn^1R6^1hw3%)}-d=NCyV&a|B!DB_&*CW=hngoj#*?wnC4@_5G3GCJtIi7>Vn z=MUzRXxwSebrjiu`lVU*7wfzU4=GqL%5$9ewqIKRkj|U15XdFHq}zzDB%|Cb|6XMB zCcI66ryHMZGr@|?VIAzerIQvLczblyamE5j5-*xqf^ zqkespH(?==i)C=HyjRKS*tSW1lQ*FdLP3PgMBU!Fm0Ga(q<=4}s`Dl+1agt(N`}rE zUHaO}X8+T96CSQhxWd`K;`cod?N?tvW-&LLisjf^8=Md(k_C zRo;Zvf{389`W`)QEZ=AO#VtqbnY;-`sCYQ`3D#>{UY@ivc@yd$NMpx^h_GdpBZSGD zun@>)ueFpn(ahvcct}A6uG)GQp?O4|rb=JpaW13QjQOxvT8J>K3CB62dCZ51fJ@>l z<`T-i>cB93)IyhoCvaeb3FLAyT6n`mkBCc=KjbxBkZ#ryF6 z3=%CwGAM7tGkFtH?}i>lw915z~oJEZbqmTqHP4_O?W16BEWjlqc#E}=mLma z@*xVzhuANAgQUC(iP8&@f(VETBLwA5q)gsK91#*>Mk3%l0N%t#`Ni}&B&5?o#v`OVn z1SW67#Tfwmu8kneJ(D+4i2Vv%&F+b$m1puMnj-}f*#0^O(&SB82-FI-)v=r=22$P8 z$ZKD8)S_%H!{kkOi-m%c?6TVGSWWQ_jCTN#Ic@rs3`C%|dKNW#6Itk8Y)u&- zdiLQt(d11uLkc2LTa`EAnY@Wy9D{;ZbE2_adzaTJSUHtXn1To?YpqH`a0`k@5uLHa z zgb3u4n!vp%Dd zQV&lv@zhbCi{)XIp2`xC^XMpo&&~v)G*iA3E~ZGCPc}uXVu%D%NHKc7b8R|l;T`mA z|5DyWOGbcq!+P-?ULzoHBK&TE@}#U~P~L=Z@+N%jKlt4U`#N62+U_MLZ{p!2)!bjhyouW>Z(@tdn?MR8Sl*fv z^Cp-gQ7_j~y^=S<&n3!=?Z`ykBLca&Y}!NlDiKKD1XGNKKE(m3K1R7Y9CPbR+(B^} zjNl#zXw^%w&2@Y*V?lb@U%B`3b8HXW4yg;dxQso~MhGQ}u)RBp@+Ll}yb0zK3L>zb zbl!xCBrl=}2$%CFD3Y9G%EEESW#g;7;=U3}6e0HgH$u2T2A|MJ+FV+Sxe#H>rp*~g ze;l(d`l@yoF40h;4Q=mAF98{9)LK2!8&7!?Y08_x9*$#$%hFCt8MOv-2`N#8)k{i6 z2p6Np3tEQcO)y2qb96?Pb}Fuw>Fp^%b1bLG(B8GQ5|2g^wy#(c|6yHR7A`IuUl|#a zH-QvHJbZ3#x8%GDq#%OJ64$BoCQO!4E=35b-cDIU97iO*U3o$J8*880`!JVKq6qOw zh)8fLiV!Y%u16GmH;Pc}AR*hLIg)jhke09D6OQIFqhQJW$9yf-b8ff zl(8Z*Xs)F12KrCWi%7w7C(mUJI!<}Yn@CdL1kOv05KU~Y_*dCqq`23alsCZ?S)-o3 zqP8n}6E@-z%A2T3c@wu&-b6>|O1CBDP2^MF1af_Rpp~1+o9ID#6TK;KqVVMW04az- zdGrnPJU3qDu3qkIlsD0{+?6ipO*}|>6R2S;l95Mw6IGL&s09}v{U&ewDLQWgDTqLi zIL@!%yqDLJ@+R(hwjhpnMA70mirDJ-buvMD6L)^Unq#&@k0QdB@!=H*b2u)%4&_at zCTNpwd4lpL&ZNAFHz{udxzKMmqBZ4BbRKts`|^xhY2-pQ+UGcxDQ}{DUVZ=h?`l|< zBLZ!5oV&ZHQlCFOK0TK5CU*7Q7hgqr6ALMCVnw4GF6T|uro0L6V>naOjYf&N>31k^ z0x5`Kk7N+7C~soWxtrVrrv~ZhY9L&QcAWiFh9n37H7NME%Tl$6lhqkDMA>xe+@)H2 z*G02p^C@p)Z_b`L=S{>YZvyK@G`&So-bBOoJ=1?v-bCAad*Z81-UQbx@;+<7Fa8qc zO|({d6S?P>Nq;~5l=xMYH-QvHpndeqi}UZx{gk3{Usy>u%7IphMh)p)^tf?(S(G<1 zEO$;CDTuITRHnR%LlhT&CFM<^g{T$UM_N(dMD<6T`jysPnnDC}p|+0Gp7JIRQQpM; zzn>993L;QLJ-_kzpe$@PqHuPWm5eo%=XTx%QlKxXU54y~Lm83gH1k9fBw=S z4=IRPxvQ1il=3E?|A8ao-?>ERP5h7YCQv$ZA==KHK;2P8luhxwlsB=h>BI3IlsADC zl+pR*D_x)RCPt{di8Cl~;$D+CfikY96+rSPP+Pho_JMTl!XG!LYEuk7QV=ni)~+`x zZ=!?Bo49|@rlJdIe7y3*f;4J^XdCfi%fD3K#AwQ!Ks!)()Yfr!{_jZkUh3`R?Hl0@fA96qO!M;bNj+R z%9_X+JXm&5{2a=g7_0IoZoPYO>f^bq(z7UU0x5`a2b|+_-o&peZ(Z zwalv#NCC8Z^A@zq|45nq4=?)0Vz`pHJLmcx$K-!_NC6p<(+|v>Kwm|@VBQmBcHRVP z6_sZY^lmWcRQ-DsKOHxxXkGu#$wwPb^E$LRv*}6iSMwKBdGH&BS;rc6O>+65`qc$O zs7#9=kDHT=6hwTnrkc++O`tnj9B1m)moNKV^)h|0p8}L(Ub1q9?&@%W*=O5pr82>~dy7M!v zSK8c}^!5z;b@|iA*Nd$gMc-#AE5%sI6bnHe^+}>=gCO z4rS6i+_@ul*>S41X`Pz;bqmI6c2DJAOi?{&Ez!>% zr)QbE!R#fiO7d0cA4F45^&czT)`!1Lo-p`<04d^W?yuO7>C5XC-Mn+&nvmN3^${Nt zXp^l~#~OXS&)*u7`fzK~M+zcr%SRu#BEJ6juakve3<{77<=I-LYMkSp*sOv3#W`&) z?_$3~Pt*M+13LzT-l&nfd1f`syJ9)FIm)B2h(ASF-0D_wW_XWx`_TPk>Q;Aa?J3?G`n`$T z6~1+#E3;Z+<`ST+Hv+JN5?808RUIK5sio#OEGXO>reAK zJz3F3*^cwT?$NOm2{DBbNI?Y07x8FjG@U2*858SvK>yx^a8cZn`n?I};<7w1hH#J~ z^&(m$9@;%RRrbiBU^Sifon3jmdsCZH>K7b_9=F9^e3dRsf1^2!v_b?@5FzcP5j^Yg zSms#{xlmrOx3{{NHJ?(#uSXyS5yuwqaKCLLh`)P|i3LB=DNc_uDQqch!T-nDb-+nc zEbjsF$piHXqJm^W1u-B;xVzn*K}3;^3H2Gkgn$7R1Nqj3By+$VNOu@e!VzwFXUHO; zsDPj(0SRVBKn&o&s=I6U>)FHizu)ii+Nu7!s;lGn^fz^Q1WFKrx`_u#ZSg_Bap{Yy z{?HN;Xcg+FQv*W$MTiQkTg*fWBG88#v6c|*Es@X-!x)Zjd9J<7Ixf3)T)Jp`mr|4< zLiz%?zpls7zT?s#9Cu|N_Fc445W1JJj_Uo#rKg;H^0_EM1nSoHUg1yAp%pKf90#-BeLq;y3<-90&_{7 z!uANhBm{dG5$HF0&b>$LSZ)wlmZZ521flyC*W+G7T)w@_ER-Mu_0e~6?iiP5f1y>Z zUD}+}SW@{2){Y2CYpbfS&SajhcCXjB!2^Y46@yqorR64|IRHz@8J1#>BKL5lpq4@=QxcYnCv%S{cGxN@9qE* zSP!vK@0K1e=^VU#WaspeHELV?D@5Bmp5JnzH+|=+=}*sUXw?G|qJzDlR%Z`Z=dk9O z%l0nq01~hRP~OG8A*XEw&FyKK+iBkQW!9(h=*yZxGm)QNoe_Z&M9_HjWjDY*R{bS; zjiTAvhjq}Gbr5w+ZvOwIhZ34gLImnlD`#BRT4`tQ)zV`)jk;|FN)Uni)Se-2_6#cC zgzP40)T*5~k8_$6ec7Yf2$YnE&@=Tnsj=y!X(uyL?__-0UkQTeC|Xzi?EdP5uhlNY z+pKp>p#%}A+i`|`=gs@d?8vYMvDIuHwCkHEyFQd4f@ajvT0JN7dQPjsO!O|cCbpAW zIfI{QRjWC4PfL^_0^~q)+VJaZUadpI*X`4I&OYuZ=U301eS|F)HN@naX9kjt4dLV2)pLA8pLHakX&X3 z2xkd-uB|E$!4m21h}HUDHLyP(TSHB&}v?=Nvk#JpYHS1t;&CV7>pK zT!uta&IY525oOqBiH$q4;tYZ$jQQV7Yh>&v}#H15;+J zcoQf=grqsQ<23(%x7+FCw%+V6zq;5<@XZhQxBq>H%wE9LVaM73Lq)H}U)gvQJSVbl zIiY6+TI)C!XKak0v%4r*ed_&XedtSmt)Cp_EiYTgZ;t&($BYW&O>jDwH$m@#RW5VC zJqMA?o8WS9t2ZT#H^CN4ya{>E7H4@AtV1M>Muem_LfRa2L7ML&hiDstlEWbAh7kX~ zM&FcuNZ;76|yz4ttw4SbSfUuEY+@elVaNwcpwjcuNt6HyXH zV0+j)q%1~AE>25-%e6`*QH1T?$@9OTbCFY{fOCli5!g;dm7$gM^cFAA8@aSeD!*2J zzth8`y_>sz$~UmX(Zy-wE7~(eeI=48LhAR=2+0LH%4rX2Db9rmlQwP6n&^*jl8e2n zoh6r8D0jA#!SaSrmTo-bsW~VC9agVYMSGcgjq~4lE>VCzoJW_86;4Y#X$1eve<+C} zr2RRcUOUP|NG?W;7c|23b`@_zW`pRAD(#f3!_2QL-h_-5(4oDn=5n!0Jj%HcVJ!R~ z2+7508O_?NeNXjj+4Y90D&B-hIF}&WQoM;SHx+wBHc7mR0iTU+bMKmDYm^{@(;I0X zYpvomVXb+U1hNUcxLP(SZoQ7cOmMBa~IrOE{O5%W3IjYIRPV)wwV_b7Grw zn&wJ%4y-H-*gVnB5*%IfT*jc|{F`_al|K0}f%6h0#1h*ojyKVacoPFmya^e1`~~eJ z2aFBlO$gd?MiOtL&*vTdZp53oh2j|Wd~b~6O<=jbDc;28ca8N5Codph^`DrEAFTd% zW)|@#P=W~5=Q#g5)lJ-ReSdcX@g`2AcoPeEkM(Xd@g~H={`9r+D^DNmouGIV+k0+{ zy}N2>>Jxf{g%Z{w2=oZu1NdrwtP}Ajc2m3wtVa}`t@)PNmeg?KP3$M$1lo=WTgQv< zAIN`&Zpv0M@g~F)tdm{y#0?wUR3qNRwU^JxU@r8Vjp$Ci3Gb=K?w*o*8O()fte@jF zB;Lfzf~Nj6U)8Z{jtHz1earhAiZ^lB^O>iJH&LD9O^i8piZ_FJ6BB-_?GN8E#cN>V zP2f!JI8BK+@s5c%AreHe59PVzTwdcA@6x*K+zG$>ndoXDxe!fvZYDjLdW3ir(@eYx zS)I{B?)ieI??861nYpH!=1p)!gkQg%qT)?pxrnB(codwMIqL1cnc7{8yq*+qV$3U3 zyrhXYA^Iv)yosxCEcVVCWD#<4s6CEQIANp5KHw!My=zXVYr9(^uRoOaJ_jJ03Xnf5*U>-ZvJO9X-X9B174;oh6;s--u4R+Tv)GM`&}Dwr9_ zs>F+p{0r(13s(IwMnyz0^SOmMjp9vw{O%a<0>zu))!-~z4Vs(i5n>7Ivvmxbd0yha zX#y3sZCkZ-=}@o3Z~6Y@?RDcQ zK?K%M_x6G@rI|{HMtI!gWE`+1lKyl=9sgpQwQp6Nh8?$0N!N2GWqzw)WFauuqS_bu zZ_%88=s9NBJW+g|cj>78?j3_RC9t<60`)o0{fiz=-A^<1qD$tgF(|zqEwpvKKfHQo z>g*-)0}G2hEVok4_I^8>wXc}8z_$^1l$NFU_1_+!z1AL43n<=1?DZ+$_Y`jettG3@ zxG>Y=@}BO-BZpX{77<6?bAf-5eyd-3Kv!_ z^5T=;w|s?YtRH=mbpKg%dQ>S2UTrqr@)gz=Eu{CgKMo46=-1z$@LE9zC5W)CdiBC# z!K)9S?tU^ko}`| zMA8~TTV3Ao=Irz(7ogSeTF$ExD8X{!IsG>H*Bg~Gx7Shi@S?w1jE)rU&bfTLTdV8g zp#*e9PCu&OSrD{5;-ui1>9c+GRn!Y+r%!hhI^9{|ZLWAy(0=-C7p;owGYI-^AS?*t zO%&3Ze$4PDX3)v4Yj_hg>Fq$w@FvJt!n7dXL>WpDL8rK`;Y|>NcoPMNH&I4s`YFSk zQ1K>s-K7&qemjsdya|doLA;51hBpyI37w0om6{QBUg|S%qC?Md<;0uda{22pa-;1_ z6K_KF>GqJ{YjR@BAeGOxk)B_Qii=Ue_@(2QR z!Kt&Vc@{yui88~R2t_ z(9{2jQ185qr`3&CPUj#(36_g};qVB|MePyxo(LlQ7AfrQ$|?&%yotc@CVYB7;2Pe9 ziXI_7pLJwgFsmhd_ngZuZ*-MYbI^|Cj@l#i2z?3R*okF^H=*K9m~nm@-Lv%#Z(<(Z zt@W8VF@N(``u-L1Cdv$N!ozxqfA|YlVj<5Mj&mP(m1Jd!f<}_Fc%q8v5 z-wkt|Ru_ya-l%yKj8OM|*j}^*>!<5scoSC55n<~XL{=HzgoVIdxUMMPL@UFa@KAyX zTuanDFVFBMl2qGpmXW!HysP47a8IPxB=5G)JE!Cq&6`ks9FZWx?j`d+Ih$A({HGZ_ zg1}s?o9AP#qsoWPOVXM*5psT5Vj;lmj`KA6>Ke_0un^cbCH`nkc`0b=x z!&!m|9KoRuwTF}1syPZ~19`5;pvLGu97-r1&L5K2V~}_g9`Ghy!<#6>*+l@w#tp>!Kh#TGn-@2C@J1M%&?;GAk zncUu?+aiP@-h^j(6CrEE_$nOph*rD_-|!|pl%U_RA1mHOV0aTQBCt-jRm7VJ3~wU5 z-Ng1H!mc^-CNhRM!7PZ-SE$dnig*)&;Z0cH#eRjJR=f$%@FpzpO3m4Cs88`G zxv*T+XWh)iyPPRRU`dKMAvfp(xas7>y(J&+e$g*T;!VsmyomrMh=5yRgdpBT+VCb4 zh>-h5bnD4S-HJDnHoS=hN)RFUix^%0jYhh+q~cBRO3i6Rmyh7Gq+CR69mIl=yPO%g zJLtnbGUn;1+rKo2kyVI52_j^qX#~$~GM`{B)CafTNJsWB8K49aa95EKa8ovpErl(3 zcmzrifx7kGLBpGvg$T3?b?cj%hBuLi5=5X6HNx;Fk|N=8j$>P%Ywz;iM8lhCg%U(a zFX8sr^)S4Nnb>#HLP6+WA~!RMH!&S0h(O)C9>ANBd%9L%l9IGl#G6PP-h_u^8~ZNS zN%1DqhBx7%1QE6lzMp7#6Em@oVz0E@oDqgM(Gn%tORyy6UC;0)N>PFc9RK=8qv1`= zKm_KJI)&}wnLCg=7KG-1_~L4|6k9#kAo0BRVq(Lia1alWKSqEm0ztaI2v{ z#exWL$_j$DOV8l6Jl8t#rYuSjA!&^u-bBLiCVaY?=^EYyuLi=LOyOQa@g_XOoA71- z!Rr#{LbT#d1co;evP^l8L#s@<_aP>MYj_hBZ-RIeX~Ub~bTM2HUdp~Y(C)j6y= z=CZvD%t_t>gdWAVu@S(Di_^R-Y&oCCqj2qfnu&zfs8<7F(eY{!N)SQgQCO6b6^CYL z;ScgUDEvVmb*mLBsn@AwfD%NYK8tafk#^=@Eq>!P>b4OmK?LekJAjaDNh8&Tajw!l zYH3asZYR~eJa(p;8FCPMrY7D*-0&uNCnLO66>mcH(YhkMRMJ7b3EpKeZ-RGAp#&|o zts>q;f#FRA*n-$cV=XS%Jn1vEVptXuO;ThgU z0gg36^PDI(*WTrM7kCq@rC5RpN$WY0=XO|Y!?wk8a}kC&F;jAJn`18Yp{}{%O|(J@ zBJ7$2i;j0P;XEjP*Q^ZcxvmEwLe40T53_!#IYuLxW5Vk>Gg)!0;h4bo*ZUH~o0y3b zM2Ll19fmhC6Z;RMu^($4hBu+2N645!gsp>GFaX{}IBGGM=m>jBV0aTPakj)3eVNa_u=_2o@?=p zn+$+A5x!$Vgrs$x2I5V4hBslo|DaqcK7ryBNPO#{ba=p<2;Z?FLehF2G%Eq0;vhdF zJlSR)VpR?zi4rLn5xO44n+ObVB8F%Ba>~W!;+d1GM*zHu@C^?lB(2ZL%t@50j+_qi zIUJtW$#bbkcuP;Q1mpxeija3Ns%ZL0qa+uXC27_tR*4Q(7j;I4lJXF`9?Zuvyonf| ze-c`q<5R9F_kQdyb2*J*+U>zbk48rVQg*U+nxg9C~ zF*p0e=h`YkaJh#=h^L9k`tiQ}<6CIn1S9ws67wehs8`?JV|WugDJ}%_CVD9rgumwV z!g+%=ZvrKVU<=0(JEEz@n>gZ!ulSa?%Qy3wH*qzU`?BFp@N>B{!}Ul8|0UkUgT$La zNfcpxsC<(!Flp1~tcm{k&URQ9Ak-L?zMwLOya~=F5=3AhQwVPc z@g`m(-URk=94nlbcG3v`m;X=_MM!IMzU*2XMMy4wE?&?G;Z3ka#&dK=m3GS2!3cA| zUC?~{Q*>zWs(lY*Q3CoD!dUn}5R!}0);Ra>9d&!l`}WVAixN%?;%tgH@h#o>O@+LP z%u~;{d4Kz;)+j*)r{y-K>g}Fk3B~A!kZV{%e2++ayNWj<{Vms5B8eibo~U*);wwZ* zE=K3HM>2v?>mVZRHs{>*$1I_+EKW-4=B<(mHZ{lpaDf{OeI^Kk=QTzpM;Z4|xj(?t+xSn_u zT}`|R=1n9`ya_4yQ~DA(^Cn`7H*p-rn>a+g363{`5-b<>(cQtuZX!wXCY~bR#BCIB zVu9gJFhVTsNIJ5-i4(8g7Tfr?=1rgk5$F-e>1=otKND|)<1t7*qG+j;Vg&If zelqbUM1lxg$NFCnE}fCVT7QXseDlAvH$?)`?EMu1=?S417K_mUt7NQ@jc0O-v`=#43t6 zF@kR3O1uf2sU7F@2c~6;O}q(_AcEUQo;%J~iZ^ji{dMlveSRjo8b~fgJI>t652nV@ zZQOP}bi4^!ozX(>`GR(w|5Ch(Z#zznzeVvTc2H!8J#+(?<4s_>h^E`ovGX#omi5h4 zCEi45iZ}5n@g{~7Z-UDeeH$p=#FZg$;!@&G{C@heiBYqQJd_{;>ql|iH{4vfjBev5 zm(9qaRft9l9cR(^PsPq8-bC%hI~mM{<=Tj86MviiFB*Sy-khGm8lqKLKgYS2coVhn zZsD(9)I5y{%!SrE&Sk`#IJD|a_ov^g$5Da^v{uh>!kggUfU~n{HQec|bui1DVA~Ie z5VY38yoplcO)x^{THK4UZh7uFdrs<^=}o+eqlq_xk|@HAf3m95MdM=6ZLCmm3;p(t zuAH)3vToU(J5CIE6DVPQfj@xNIf01|-|03Q5TIe{x-?%V-?A|r$8;Li85=7idGx%uYO|(F&!8oUwhB&sAek#sOMr>uBD(c4p(;CW#APEb_42sekQC%%oX6HDiHq zBW@p@PS^ZxTYNb2CU8X6>asi0ig*({?^)-gwG``jYKP4FrB}EsejaR%T10$**^UJB zCK@hg-oz{4)rgItnR>Dl!uFYeI4Xn$FwxU-ta!e;{It|B*5L4=?(Q zMbNlA*BT7}!$S$!9y$FW7DQlJ5I*`U>IJi(r*k-BT6l(O;i6Sheew&yafS}LIsa!m zu|4_KX=TeP-b9-L3%vg{)A1&TPnvFbH33gX+9SfeU3B8nO(}i>RVno zBp)S+sQk+p{?}AeHC6KuR#czW@!i5O-h`Beb>jC4XZD_%jk=K3EwAHEh=kw1@7_OI z<>C`z@)018I`~c)Z$c3KZbH(wcRNwMiBoo}@3(s>K?JrF-CTa9AlQ1*gv97m&f&Y~ zVH>a|t6!h5{FY;tt_JywZwpAxqiCxhBt04kCoz2gED}o4Hke>U}{yB(Hg5{F6 ze)%=WvM?8U8W0b)cB!}XpS~B)?abp2d$^5=#+#_UcfQy9X&rAu+Jg~NlH;sf-mY{w z{V%EmM;GdIoC`jjH_N$j0DtRV-6WS9VlJ#7F~g3VSa|8`8xq%>coS?1*Xl)zH?f~) zg9i$Ayon3nrhcsAO&q=OiNeu)v+*XR9#UIIi-nxlf7e623AT!#N}F?9S~iR%;2izJ z70sv~D&B-xh2`>%UuD$`9B*RPhc7kh(&P!cQ=SY^f(W#b_|7-K(4@hOQ%{W|FqimB zf4!CM#0VAK<5+?S=`oy_T96`CltF|Fg)k8+1TDQ%BlzD}AVP)s3N5j9Fk<{0*$5Sa zz+AWzInK-9|GTuciBN$OMBwT}j1h`A@e{#uPID$hR0j1PU zK$$J2U$H*)f`za~X9S^US3N!kZtN9&dG!Hz=7`DGJcv609Gi42?6TdlBPn{sdlWqa z?d6*lt5yYJ^oYAw>a^pmrRWj={i;RqcpV)*qRqicVf2VwUzqG2?4_eeeDS+}PB%G@ zJT>@ub~bth)LiWuxG&Moepk@MWTjXTr4$Qdl8FT&610%-0cCZ(K(QbyzW!jk)0a9H zgh&uU_j=uIJ!(~4lsJiEK}@Gu5SR-s!Jbd&40{&2)BgNC)qrAJpacSm@Ouv|nF zyM}JiRf6adU$$EuMvr*?h9Ha{G0fA?Ne3YKj+aRI-jX2rj@Nm;G}>|QCicKl<_pS* z;M+o@Z(9&Xj}YCt(IZ5H2)-@EW0P*A(VjGVKatC&J5VZm1n1&3qAi5_X1`b>;d^9);M-K(P8z{;h?*a0&ca-%kMFQm8WbER zdW1+2!8Z@5+#?9MDXXGKNK0W09v*=bMA%lDZxx5pBSbq|W%m-kpNP>T#41Ff57k{Y zzTd9i8i|DNq^al;G8@Qq?OoQehbR`rohEvO%;(s5u}*X@Y7iW6 z0wsvBb?|LN!-7!JBczXFue95o5g0u}dLs4`ySMYrOpG2OIuOCPDP{cY`-vDmLJ*is z>J+wz6+J=_I46o#+fiLUbSk_2tHbU<7NIHs`dh1Mj_} z1QC+fR(;g2V{lc4THco58u&vfl0f~Xf%o|n7hC%Wd(Ti|$u_^!)C%sM`8Rs_y9Uuz z4`2EleIIUXZST`+oq6xWJDG6DB57Wuc6Hk5|9iw_@2?wck#~Ptv&sMT`d?Ew&FRB8 z`$GigvaPE7Lfd%jN6ra;y{wSg13vi5m)!uO=}zkQAN{J%uGD3>-eCP=!CY7;$Eh~{ z?x51A#p$|v6D?mMg1j5*vlxfG)`nI|ow(+?sA6>`0 ztIMV7fulQFHAky#1TfsvG*kOB@6t&1WjxYM<7DB2VGvaVzqpl_Jy5h6hZ>Q;NW zd9sJY7Q|MwbFce5=2N^&xyQ7Ve|-TTP!yhaRfz==v}&9MUM~!=0YFp zn!ikYh9@R>RM8`(1rcG_92sts%d7z5yduwaJ<3Di_&~Hqm>pRdJwj#!92407dVht{ zBV-0Z1dcAfTf*oO(%Z3I?8jOMMvss&hzMH;@2_BWR^yIG5#|ydVK1?wN66}hxe%?b z0v1HL-eE3Dv!{vMclV(5#M^H01}*tfMURl4h&r%O(;4!rZf>o-E4>Oo9kf;)MBvJx zqemP%xV2#2hmXbZl$_c(JgvnuCq3V;zgmCgA0>#8w3?n(^oTr)9&y7?9X&$cb5Jhz zu7GplI|QX8xbaFIJpv_&kTkD}S`V)ToI;7D&GWEMIfzhF9zy5l=n<1Cdc;X4dW4+N z%gGd5VxKLsMZkgx-`5~Q(xF9a-^2gKXJm2?XPuYP^X!|37wVi7jNSfr;_sq@fOCli z5uzj4S12hDp{*iLL-0Jsf;ig5f{^!IgjQ$loD1K*IL_aMs0Xni>km?1@PsJT$g_j#DWkBA|$PKJo(*jxBIHL z-tnDuEC@MI#J4iUX>g_Y)KHpjC?NoyU^SP(qJv4nD|xr;q&*W=Um8{x+cm9ILds*&n90Wx{FTT+Odv6vl#J3ndnW zJhu_7LnMqwgrqe>+8lF1ns4=lXd8i&!yx?7s$iXo1@ZLG;xHD3_=?f;+(w{8{KmfG z=Ypo4C2<-W8cqXC-e^8Gj0G`k;^HtC#C`Xa7*4}N;xxQ(I1T(&X_4?Zeg(n$x_`Y0 zI1Q617Q`Rl>sSyhkysGd-BIFAF|ipC4}F)RJcQ(8wDdR5XCp+y zxeyWYuHiIrE|DMt+evd8>QO9+F(wwoF(1%3S4}Jk^n&q~TGec;M8Y}{k>e|_kn$BG zBp0I(-yS02T!=7f)8m{wC!5X1|h zLwi@vl8ezYnzdE?DHcRG6AMBloJ$b=4cnuO7eg$F(G&~fHxmm& zB#7Yjn>3HzgWR2qQVK19r62^iMwBx)% zu^=w~yo2AJI1Rli7DTN*#fsB_<@Taj5H)9&7*0cD;xw!|{_V_kx>Jo3M4&#pPfeVL z<9hXXmk_6+8O4Ga*=%YU3qmZsgT5VJyMKvSL&bvFdBe8YH`6tz0VS+M5a<#5t+r%- ztTV-eU`_+pBZ|(}eE20>Qc2=8WK1jwks!j>v1{KiDi%al6AMBt!8+MB-}=&~HpdXB zVO!4`8O()#vk`^FX=wCJWA_h=1%bH`jrF57gJMBEli$>Lx7D#~jtHz1#n`4;5cir` z5GPVBh^~DXsaO!N{#4sPugT&t76i`Jb}R^yAcEUQo>RY~SPmyFXyPY(rp(@3KC_QVjmmp39mWybLP?0z<)92H^ znY~?#y#G=xh%Q?ec|%Ps2+>!A;v3YSve>&o#e$f&{)o(@O^!{Bo?Yajge?&S?&pZj z@ulW8+)tbav3WY7`6N$)Ah8_93TXAFT$xCX82WpIE|Hi9Rfe&X8xEmskL?Ak3QK zW4TvQEQk%WOT3Ya({LQcf>_=?8w)~oTtoAD=d-7Vu^{BP2*nt=d||w1t+naiCKiN9 z5OI)VL3Hg~;&oP>hPpRaOYI;|!=^u`XV4O?xsAB>>M!SvCx*g~q>cq4^+4OPZ5-#P zNtN=yBE+ITGZL5!t+Em0DHg=VH#T)YC~lg@T!^-p1^`>X~m!m&Er|EC?*O z3dMprie~MrC>Df`=s2@1-SxI?EC?A<3n>hU>Uh||#gEFB9%>VdUI3u*SDSP(Ia1=02Of(%L!VO#Yf#eyhKp6=fHW;}rsM4*L^ z^8m$yXx1MQ@e?$QY)GZ#|kte;{*5T{|D z;WVgkA&G>}Mb%2p2>u2PpO+qUMR~CxxLp2ni`;ILFSCn2#c5D?sfp7tS58d1Ttv`Y za@TMgs2;>=XlXbNDi(y4g>|Ag0`hi%5cHQ+|I)87Ica7c@XlO)Psp6ZYlLGs4UACt zTNxp58aQoxmpBcjhSQ*8L5SZGf$gL?4W8jN1aJzhEaCHH`I3@tmDGd$6ShGV{l5`> z{w=xC3yRZFW;hKh7KAzTwt5NrP}?I`p#*zLPJ1vQ$+H6@FqdtWE?I<=^XK>A>$M9FcD24(>kJts#BNW0!j}Wx`PQ9r9*!oPDR=<2$UcKd!_EX zhSQ*8L9h-k3v<~kCvh5Dr8K8O#e$GE6%qF8Y~~SlHYy(FQCr^1z@By-;xwpO5X5Ov zu^?pBA_7OS*1&TWr=+&5L;96TtJ{0!$AXCVT}12gF>qrq&u|*783%U&I5z1`+-18{ zhSR_|`@-4-Do#Ayf&r$NPO5bcPdTe^O>9>i(L7)}GT2f~`8CD`*7 zr@=Rz2A;1JpNmHkBBW(?3lgWnin_op$gPIn#U7(L4T0e_SnYwi5Un^3p5ZiD?ID)1 zKD5xfXNh+pEvpc1-G@_=9n38x71_buVN#JD%)Kny4-uz9?!&3b4kCeDNc`<+xf@9c zxYws5I|xGVk_XYch*pf}ZUw=TRb#0a_j!|C#G8`6y?71@DDFsD&p`3Ni* z(OL(_X@FakDzbyQ%c;J`Z*K3ARfv#YO>>onkh@X*T+Jm(^)JmQaCeNqVl8(^`77OW zKUE_%fDkA_1l%Je1l)U7ksZwaR;$eqk3b2wIqKH;`uGkceMeYDb}+YCt$NtKgl`*S zWCyVd>w!L0H_!OCI&&ISWCxiUa5l(A7*2zV>>w?L22@vm^%c<8eGF^2=I3eqNyIjiKNw;I1Pc}G$dueqxS9a ztC4QtyN1(12;wxjhSLzT0U3e0Y^#XVkT#qKUI!He%=k*Uk10eePJ?SW4c6}u%!PGQ zoCeQu8Z2KSg1j5*Q)_K->(dv;pF6S@ueG67;svuC0ACTOA!9fVmUq#kh*q42z;GI@ znxj=Vg68%xP6N%lwq$Dx@)As9_J;)NMXI&LEd=)dSq25}lxWCvMs5J59F zSOvUP71=>nPHZ(>2O>~{2%1raOGZ|i)gZlf#FZ+tgW)t-?TqcD@3&)Q2U%;eS7Lut zoCeQu8e%v)rCc8KQgiKHo_8^_gSknrB0I=#K+t+lpA8^ zAL^PLPJ@cJ?EX^0z6gNp1RJrOOzKCL(nzTq@jD-I%XWzdlw45uN5r{vVWF+Mxt6$j6p zc*aczz-b8Im>@#Z`izVtI~Y!b^)`cYsWW6gPsDc!N{0uWhVYFEA|%Zg>UDrDQ?~(8 zB5Bq^>99@~LPd6v+LnjV_29@3hSQ)TJID#WoJ_GL_Sq8q3OEhn`x-<@TAz4H9oRlT zZQQhhSQ+pG{}1{LaQ@&%BA8o z$h#NCY4Cv45WWpVgrsw!Z^CU{jL-1K|HckU^8dRJHIiW{1 z$2X8Oa@LRxfYT645Fu%;gE$So;WVf?4RW4{Z)G@6gY=%kvs4A!v<|F@m`u&3Au7eKrCmhe6QD;y!tve+tBD;M+SAr=iqv8g@`Tg~1`GAs|k}hCw<`14{V&yMkbS-7HQ+R?WZd9K`HC?{@Q%sx&el9nXxE|R%^oYP*oHp&De5KqFoOui_y|*oRi5qG$pt#p%4z#b zT8eWa!lX@`vnKlETi#+X->eXX>Q~YiR7UkCgHxPKBvFLb6BVc74HKt9dN_|R87rKY zc2YXj>dz^ZL=n>d|BR4aj216wgm4;IV(Q^WXH;pYTpgyjs|W?+1<;|rYt=*i4*K{m zr}X3hfe?=}!uZM{lJy3*+t7a}AVJdYg~5#wBlFljeL zs05Y;2(`kQ*0d4IDv?AH(#LF01Al)NXHJ7wZ7yD5WB5 zYd%ciyu=8xgb|XaFT@h3;WxU)+H8W3(;(xHzdS9R1{-nKUuPy>{Gx;3m^clC>Fd}h z6Q|)p6Q@DS{e-@`eNxD2cyLlGzS?jaP=e*6KKib6ft&dD&i-!6w}ZTX6sKV-aT;12 z`dqbvSU8h()FV#Ak&4sMVcxdbv}1RrKK_fo5(^U6Aqez{<9xqieylBV8g71OMgr>* zMN6IN`_vt_r0yn8!*M@;kU-lJVe8mFuWIWT=-%tAN&Urlu>|X6*SyW9f8`G(#JP{p z$Y3t?n~gYO@Gx)8yN%u37T3#QE<|Jf=nT2rFz=x+oA{&Osbkd~5m+b3DWo_J{qB1{ z^9aRh*hX<0y3zesj??fB#c5zpL%m<-tCbpOYSQz_w9IQJPJ>7g!9JAdj??6XTfDz& zt#haTtm8D`Y9P4~?KmGt;xx$Wj23dw7c|`*=utD1K4WV9eTviY4aI4gO}AqUh|_@O zBHD3oEjTapPHEpvHHy>FgW@!FCQd`r#Ay(HUsIfhIw7ZF1#ucqqc{y?W*2!VVM_#o z`#Jh1=UaVLoQB@SX+WzGjTX`^)+3%)aT-pgI1QK!%e4{P`use*GI5IDq&N*&L$nI( z=Q!sPr{RrzTKKJ&G*4Ry@B&)vI2RG8A^z!^ZprV}<0!#$(ONyf38#U31J2H-)zmIS zo;%KwC;TVgr(%(J#>q1iY`aLHFDZoVgF_v>(^ua;m${bFW^9M^Zgv(mzYSEJhQlEQ z?KoG?9UZGU>`?x#wEK&$oU&T7zN}Trc^hM=PVHRq5OEq%!u1dY?%{Pk{?+WQ#0_Qsyqm4$SH|)|i7ah0IJbw+bAdaHQ4rs08EWUYR{JY(2(tU{qff7XAL2FkRVnMW5 zEQphysFwQvsG{IRitK=vAlgR!K4nLno-|YMrN|CwFY2&s-Xib7oRt> zwm-24D6&J>SW|c6_@-&hh5Br(oFzlOy$uTd2WQodqXZFHKe{Q~ZhWdjg`!|mVwM^o z(noPb{dVNe#KeA!ym4ch)3EXS2hwBTS(=%?aD;~vL|ienwtG9R48JJeMAMh9@qQh0 z(5-&e_5_X(%!O#j>GxgT%+#CuCFa~zO}Adk%F^4f*&P4u zb9+P$>bg5IXX_%bj5rOb+i_M@x+qhUf0a9Q<6vvlBI23LcO+8uTm7*`9H-&ip|xV; zh|{ol)r*qKPhWlk-99I-fSvoC)mf$R5*Zjl^ zg9E2yKmX^UZ7c-lvaM?J@UY;Ts;9Wm&S{-M2_n!!#RW(hEY?H^ z$i5wPs9(i`b{t|T1cssDqpzY~F#CD>0w%E_Ji~%eaT>%bw1oA^F964R2JrL5BxTbCwp6t+Tct2xPfWQE3eGs0!7xZJ-U{L)>waiX`lXcJrL ziazaK{cqCNVd`Y83QJOXlZQcsxojOBd-V&xp756Y+Ku;FKDm1JO22yDV(+8}Hu;=x z^!pU=tcx~N&8Z5?Pn=@OO^=l*38(M5y2Kk^Z*vZU^YR~k;b`?r7ZFk}KbJJUmAUil z^yIfIXO37%F~g{~o%c>wIN=Hi-5N!k27s!)Omwo0sZoEwK6n`k-j zk@U-}lvQC_m2Jp`N>})nqCr7fh(O)iss-Ki z%KoBVAGhG@`IA*&VoysNz2G>*UjI2=uyIrRofSpgOTyk)F{x|IJrVWMd1Bj3=M7%k zu7JKDrTUfhS1k8e<8?+m&ig;SKYRP+j|%wPPMC}Ixq?P(L+>WJ@1g_|XswOlT=(`X zQ8h(c38(xY^Q5-b-z+Bk#505|zBJ6%e^OZ;QmH*0(_qlAZ^j)+a>*qLb{Qh9z z>WBU3-uz@9>cDbsM7K4Az2^q^a(^FtbOBm|b;8~wHRu1=?XhNWv3LFWjcOjm^vtL9 zbCpxAADlwlIW4(3Eojasf4V&&my2mcSTnUN5-Qh1V4H_$;YrrMs8_L9eSxkA=m`4) zTcpq6IK_y?rIQJuodk{AYyZVyh(02)jL?+%Oj-#BU)Y$tjj#Z6y~!$9mX0Fc;1e zqMJ*m7$A?I;Fo+$RRC8#5dn0>;V z?!Tws?&TfZ$>mjs_ffo8!;#9*^RJogm7KVdR)e9lo^$&if1!8AmjCeF9!jE!uOFW5 zP2A6jXIgY|AN}?Z_x;#a3L%mxLS|I$t5HWe-iY_ERS1#bTEb~5>7Nmji>;NkM!eIY zyVv#Z6D_N-Tux_e&X~g?Bp2(DwARtP?+|b3rpuIfMS|sWTD<?KPR;nY+|<^)+^?Fms-cBhUlmMz#()3peeRC-m*pTN7weFA z()Ey$8?}UOmtA z-nxX|tM|RL*qd;bPRov*^I0>4g^*laQoR#P6gn4y9%TLz( zM6k-mw3PJE2+74(Nm?Tson6Cgx1fjGEs2D3xsdk7LWM~FdfMBWKwE{DSYE)IJI>({ zl8g08nstQpm71xswvvkx**!HNk}N@lcCu5+Z+V`RtxRrT+(WsmXdOH!2Zfb z9f)v}bI+_1v|p&&19gObiFAa&4Os^<{11abt0b)e$)huH_XM)v%YH3 z|0#cF=FZ@U$Gx1j4^BedV_Q!4uD_61wQFA<ZIqK&6(p#*> z9sCtFhB6|11^@_tp4AaWhy-+;IlBc|LJW ztb;%G7HYxBFGy)Yu7~*0ajrZ1DYxs2JA=%Np0Y~HilW6r`kGbC*WA%}b_&jDf0Xi- zNTP_WcejtZ*R5KkO3-+6H`}`r3$s?~y6f2*Yba^6I!AmZvo+T+tcURrBJ}D!x6&y8 zxR35rzwoeEM|6O9rF^n3$>(gt3#WLy*01n6-Emj3x4xZDx7ahmqu-%4q5$Cl!sWEd zrP2oNI?k7L7IVbNWZ@~_9w>xzEyR`HX20?kQ@zUfeMtzTBgrYyp{x>1`1wi4O!BU{ zMsqEb!S2VmjwDU?r!COSb9&e?}|>w5HNweDyyNl8g0;r@7?pE(0Z;MugoS4CDWS?WzsX zyQUuG-KY-nJEJ8RlvGYV(4&aR`f3-QznyyO$ik=ZpIwG6IIR1ou;+8ys=0U5+I{&w z-|k$%lI_P8dtW`a!X4gYli!5;RWJ8T7Z7CCM$)l8c3#23DpgV}k=k-vMi=TOG5=BVcaK7v={4j_}Jr09Vxuje!NjyTo?0&t)Ey}d=cQ(7%!`=@1 zEWbI`i6eBd|RSNk&QT=5PLtlE&hGc1ci`(6-7uN%k{1xxLnBvI&^Qh+8k?( zh-}SSi;NK-2RP29XRr==uJap25+#84;kmNPaVAzS@&+uSZ?};SsYkRm<+9 zF>6P7H9F47Kn-0)U^|6YsoH}MH8V)LP?E9A^hQ+=@fDy|uM{-h{dlcjViQ^QK6j|B=d?O|Q-10)cl0Ish3!w>=(p`q>@^v_!bh}?xcidDtvAsvj+f{* z$ExWY{Zk&E;++y`|A?>H(=z@Y$FDrXJ7UD2nQ<%cjw2#!m7s}ve`vVZ_Q1i+x7F{l z5MW89=4Zwh#jalVR^ll-1K?aUOQv`|XRJ`;PF4e~pW|HE@k;OHy_Ey*FIX}UK`NJ>s`NB zh7sZu>?J+V+~l`fSnPe)eFgQ6^WQHD4h-vZjTG7=C$@#_O@5tuhv?b z2NA)#O;4oy&KZ1cn_q}q%lFmLD%5A|Sbp@C-l~r(d(ZXp5-gGVmD8fn*6~+8=S7jq%n?pG**v}%7T$#IsFuU33iIXL@PPqn%9r6@vr z4BeTa7VLRP<=~q6u0n_e5u6q;a39a^Ea#p;Z7^QV04}HdES};`Dp{e@*I!%g)gH+G z>Yosji_s^YD|6zwc>CbhrHz8yzPl-b5>5+ZX_d`>(GWrW{b#SB@`n9>|9HMaNG@It zOpkGGMARyy-De$Gr>s@yj%^=!l^d&Z4pu3IUGO) zf4W)IFpzq9Xcd+V^&=h8_7EMMtDLqWgz>K0mvAmbn6#?7vG5-dP!B}7xmKYirjIF4 zn|8A6k&N0dxxiXNfOl2j727$NAkad``R262!A0lasdNCzO&AhCWyLP@0K#- zfph>u?crozf?Sq9#~J@uub}52``x2U&Qv>OnVnG|ph-tw!@ZNgK`DP!^>Bp9t0=g%|GZ5xa;aPmqLIziz{4wlj}D*1hv3vA5`X z*UY#)`o+?)a>3Dr*faJ06iN`$`NNuSRYJ^d(zFHpl>hX3IP-zITz;}+?-yZOp0hs3 znY^#Glo9n>56MRfB97fJ>%&8Z&)eB;V4J)VL&n)iJaR^)Uo0CVNEM~FZPBFO89(Lud0923k~ zm+`^vlx>f!f9d8KATSrUW;Q?jinU8wXrXP@fr7KVV*1}BuRiMzCq$Q%wtKBBzS$bb z3YJ7SWo!MX^uP4Ks18KfBWgim<EQ2EEC29Q@dBq; z(HFCZe!R_dcAr?{I29XqDGatZ$mg?UtcTQ=5n>^y_1}4AAHB^wa5lhPq{CM_D%Wd5 zJN?Y@Q*YnCo4%ru3{Zjy)aN*R`d6E}`Rt=|5SUA9?o?tO{P)pAuTNziC_#kuF`c^( zeJN{srB-Slq+DVDLBGj!jd;3Ym8q9BtkRTqpac=NcL(kL_tbfhJy<`Az+7Ask0{dd z8lAVVsW$bfbH<%62$3Ly>ZfK=r{-zYf;)!1`ewtoibJaefw`#WqJz{tKYq!qHjnwiU$ws1FWJ9#AGN+}^Ux<)u3hsRPQJSS-&w0dpCH24!H7x6Pm-F42+U=#wapi- zob}klm3h<#C_x0S+R9f+%B^~$^d(+}Wz=$7o@>wQe{BRmLxiM5M3OC{|4K^F;Buwr zCLQ`vQ2Mv6Ah^dx5NfT}WAOWNy@Jvqzq_q29+$#73TFu%|BmzA=NA+p{o( zJsfRsQDw6mTfWtEDt%K(=Slh3c~$ZbseK|!5Fu%<6WxuvE6+Qy=K^|rc8;|gyz<@# z_sCzj@^=nnSQ5=6$FylJ(p}No#{T%qa<}t=>Q9Xxv-raXK&Y9ncEkfl7Hf7 zbUPZ>T0yWE&~J{j%xM+$8`(78l;&QPAj0<5>c^`Vocddhc&CF!UZ*`9+y;GidS~|e z(9NH^!Cm{vR`0oIK6G~-vBhnBqkc|S0Rkn6SX;K)-S?nI(-#+a+!24{?-AbP^y>=| z&(XK-&U2+rO4}_8j!}e#WuGQD?iYPUW7miB2c&E{6($zer7=W@~>~3 zg$T3?b!)^Eg!rItlbI+%1o}`To+bp>UL-t6VQb2B?OpCu)d(^1(`tFxcTpeq9=bU| zh((0xJ?+C5C_zN7jt`Ahh`?O(T=y&X)hoe(^ynIAm7)X@SSQE%`rEU;)Rhgqvrn1t zTG0YCydEQ^!~c zv^wqVeU5G}V%$&*}+Knrn>QN1KMfe>qVUeFRHh_LIy zHK%^1tioJqyFBOq<~Z+uJRr>;=6aw+T99+eb6t<}5G+B2q&4C{r|t6J{-vV(NVOZh zi^?|p$86l{Ra@4B*9>1)XWUCT&WXXviBV@3aCqR!|q{P!{|QU#e?tY1ZZB<*1Sr8e+4Z=y z$2CE<`^Kk_=u|PlT!=;s)#~iQ>KwKKwX-jE5(~9=x9_~j>v7Hb=@%!|3x9dB1QDo@ zeD%SAw9M2ri~2H$(-`z+1)!P8&#uliw=2YTdTtLTh@jr?%Wi;stolpR!sF3g>%*$% z%c_RDB{%u{E)s^enn3Js`cm^!8aOK?GV$UkdrXC`dKG zJ$=>u{be|!1g+*o<8|#_op77TX07FYV%UO`MsyaDA|2O1(KSzU zajRju=)-XRNYnZ;3nhrKYff`J?_SlMD7nlE5Y7zpTw7Hhf+f=15v>utXJ|-k)D5u{ zOL45>n85beyCvFR#c6+)hZ01HzN`*d2bJwnt8gvRyQSkvNBwcL^03FDKJ57#aWf$b zSNpu4hocq|wpBdFVb2gEFqf1R_A5{JC1@|^LNtBre$plB3)c7c8qeD6OE2NF5P^M~ zeme&zx^vt9*Na{6SnCHOP`Bf}N9WUbzcspG%Zg4hJar}yho{4MYNY4e;?ED{a|$Jh zkTmC^^D8>5T=T~0f{WhlYrX%VT;b^up2IUH88p0brP6^CL`Yh%YK-BPfd55_r0MZ% zln(2}`S>qHgp%?QI`4e)Ri{6ewRvS_%M_m7%b68hf+tA2{FU$4FW?kP5Fu%;gKJKy zB>xwlS>maqJeQj1B3Ked@EM>WxO81}$rVM2Rk;Y12%3s}O`dbvs$T`Gri?CF`%$M9 zo>@{ZUrrelMce^d-w)GCp{ME%?g71y6zp3vC|KnLWd%-?| zykk#A@6q3{=JAmviJGriyQCR`)=~>TyE*;=eQW9Jc7w}$QzX^pCoH0OscZR5D*my@ zE%NwVtn@V!mCpT+FiOfpFk09Cb-GD)6P?L$u6_^i@bX(N;IGIj3;8?3T#`Ju5h#fw zc;CfnjgVHvT#)83e}(#N1WFEr@HIldBg}}NO_z8Jhc5{I!?k6!Jhu@jVYGOcpG%tF zB5z)nUo!Z2>Q_mRB{vOR>J@HX=Wah()BkblPS5>nom;g*eZS3|CElg<+;JXU|6<{W zdat+MOY;^=5W)IJAGOnKrVvzi@Z&YV&3<8Zi&B=1A_>P>f1k?r-e2OKwSArPm1z%E z^JH+!8O!o!JlTT3FDfmSgD^EW2&#XQeSio~OD;~E7Bq-$&;3@qsp+&r$F~ zW%Y;F^4Ed<&nB&=x0;`%xMY0}E;<;&eH75DZLpVQXHn2@wIDyo7PNIpS(uB{*mrG& zNTLY4J)V62i8-Y!Kg;J_B0&VUES<^FTKnE-ZRUO4>)W#DYuESNS6S?B{P`39DqA>G zIc0#S5G->6zYM$`Vr#H#!GPJ81;} z%YTBP-kz2;f6owfXzyB9iQl6L+gDnH)`1Ag#b|40@D?pRuH~9W56ndgrv-5o&0Rly zxYK)gGjqea=EF{C)u!bar?o~2A~?-6Un`oGRB!jD>E2$rt3oZ++c*6D34e)8db{$1 z^f#>o>miaTLh2VHlAPjPh>%?HT#qQV&PEVw(WFd}HS^1}qqONk&m~ zYo2McB{i15JltsK2mIC3(2Iz$b)0<5@A!J2BCt-5^YFFl^iB6X zpBYVG9e6<>B{#s_hTyywj^sUmoT@hBGyNGvmQ&nJM(;VU!?(eV9e` zKmHc)$NKBs4o3%>=xQLj5KUi#p8sGfxo<@9$0c+5OVHu!j25D9$0?>S4}X37)cADz z@^F<37x;U6?DPuh%fnbMqUnA~;=IhVbl*&6`ttBq|GvN2J?X4TcCf+hZJ{9R&t?48Xcf}_6) zGN>JMAv*iz`aSgJVYD4BMBNl?Yx;SKgQwn|`04y2%PQ1yS(BZaXMSJe6{#-|ms~nK ze%xOZ(kr&9Z_0-LnMf-@gS(b`$IzFD(OSCYeOV@cam}^q9_xz&lpx|!)6%0cBaRICJFDwA`i=LSie0n zHg|euGZy$Z;;nnr>8mSz5uZZer$!z3{dT^ecjQiQ=RNCuwAOLHxZX&SAmim5tm3L4E=y zh(HS+=cyml@p&V!oA=a@MM3nJu>5wy-&DFM9z3?BY!A(eC}G*frdYne+xCX1E#T zD`az^1QB#n>>6$cA&8q%V7M7&^xhz4xEU!rNmXk&opSOUh?L=G%v9Wrd4`+8tc_5D z2s)GX4L4&(*yif@vz)PVL^ioi*CwxLu{>veikqSCgcCPoE=mwVcN<*8%^-yNOL9+< zvuQ31-e9EQt$r3k!0dhMC_>(BXsbj?ISBPuhI5e)b-OV{kVX7wTZNX$$#yORB~gSq zRi}CoHzUt*GXiWutU0!gwuen(t5AXn^r7Nrlo@V@g}_{N-tHT223bYij9G@85nxZm z-k0lL!_5d#f(X**nzu5M7DNQ*%4rW%{p@{e_B$fT>xa=ny)PUS@D?D&?UZeg(7)te zL|`s#&1`;d57sVaq3yO+#LWl{H^ZlQ5U$~7%*L^TB`I!3E5psObRfbWQN+z?Ww;p@ z0&}5-6eZ^QKTkK@3{U*SF&V`RG|o?#+dGrK>O!~LiJMVoxEUVSLu$)WBgI0VF|>}h znwt^c#>M%AbIJYPNzP@&9{5l5yr#vPo8h4Z%SC+@&3seyrhjQ}hK0afQuFIZT}nDC zkN@*@!_5eJUMxX`^f8XrX~nhV_?%(?LBGj!^1^8p<@njAO)u5l3=buUu)TZXElrym zZia=xTwD^5sGF6JZXM2TYPcB+AreGL-@WdYtEmP1zwzhkbu~A`LSQbcxzeHIr4l!z zrQv3HxGv!eXZz}Y>Q`54Zbry(V=p2?#=nk6%ZRTu3&KKRF1rOUeDlxK-_qO+s|683 zY4y(g>Bm+!a-22)J=nx>GZ>+6r(Ai~zch{>9pVIeS=z19*p zqov_ycql;xuG%vDsMFN&JtxnJGHN-Eeau3HZ$ojMBbvv2hzK|(zT#X`bCV8zSUv*1 zi)cLtiJRdWZbl5}D5{6crx83$;P_YEjKFX+64=9~=4?B$3Vg%OC{x^w0Js^U1QC*E z3l%pbFx(7lHGn%MDO(3|Gkn9%NT37}bVt}X+zi?$5;vp3a5KW5$lB$u65T>d$vqiP zD{h8oxEay*2-^VBiklG_ZU*0omm8m!?Y33K%?J!P!^3(YTKa;XONg7{8*YY$z+Bi) zikp!z+ziXRf?zM8->lo80ZI^I`wH&$1#maYhnr45+%KbFki^Z9n}7jI5CJ#O2m$vK z6Nr#IOmx%DN8O5>!JG!>W+YI82)V<==<;t((%q=E*0_LEMbA;bwT) z8zdL%;IwsLGy^vpeYoA`OOK&BjOsz$40R`!xEah6QazC+h>#Z42%1fjdPYeGm<#p6 zT|Cl}{YwTYK?K~OB!t}GC2mF>+ZNm0M#vpu;%3BAf(X>DZ!{WiMoUDXRj6Ad3^yYW zC5S*DYJ}ltBt^n=2DYX=*WTqDlZKly6Z`aXw?-Il#!N(DE}UcZom9ikn1vEV*!AF=n>(pV%!RhgbG=64 z-CC4L3*xG#dt!MAmLNjX8bRC)*KjlV_NQyO8N6l)bCP+UaLz#7jEv!C1SmlSttD^< zK->(^a5G%gfoOYQLfnkNa5F+CEAMfzT;dzJhMPhA65?j04L8FhUkMA7cL2i9OxXzH zX1Io%Vg1Gt9jwnr5I4g$+zbyTSSPz4#Le&wH^akRh(-%7<|MDqVH;qb#6rElB5p=t zxEbNToh67seTthQEIOWdg7!-D%PcxA)C-vN}5X8;kxjmF1f_l3!H6!Z>&9%Zf zrGOxI>`Vfh(LX69TZk$$d=_^Ej8yf>b4OmK?LekJAjbSNi&1mN1M4s zrOkTo8g2&FygUZz;ShSJ23{)fWQ6<5yNpmDtt-NPB^|`g5GE_{mO=?4XwC<#fL|M6 z3u3EbNs5~xj9lKsg*p&{*6LZ*a5M7IyV#o2+x6_jbE4s9v_uIa&|1aK@C-Mj5J!}t z)tqQ*uD#1^6mTha3J@X7lqHCev_|lr!EiHL;aI~lf$bmeub7)L6D5eq)dAcL zHB(2e!kJI?tH5wGW@3*+ec1Cg!f-QqJr73_B5bR8M+V%C5P`X*q_AHJXS5aCi@6Z3 zxEXQ7&2Xica9N1JKCQSJzTswA>jxrGx4uJfxEU!tbtVsoC-it~#4~O(0B%P3js+2t z)@Mt^&F~C2!+QTgxx&*SJcn00Jm6-8?^qBaX}zkMl|a2QL5ZaK1d7sOopgSxi@HUJ zlJXF`9>mQE3^yZ&XZLb4#g^a+lB!1l+>G!I4Ejn-Rk^OG3MB37zzFbeh{khxjR0;&_@)8%Nm}b5 zZia8T89w$OeA9&e%{mLW+FVW@xwew#b4JG@Zbo3Z8GHh%<|{t=moy{ndLTE0-nhEv z7ChhbcFk=ezN@Ix`h6|eoo5IB7bWE(_#P?ea~$Dja4vHfgKwTG3z=QPCCPIefs!af z?x$*mj4I3pX}%j3>a!6jISj(=UWJ>%2)R$mY4H`K<+;`&2$Vz-f_9uoiJLLia5ETj zv*BjERKLFali_9zJXq5$2)P+W#LalHzUF421QD!{Z)|0`8DG^)&iS}%n(tG)Bk6`n z3%Uh;DV3WbZpPWf&EV&9FN^Duhi~b+a_=Bl z2P3%00b2DEY;%31n6aQ;j6P}#2e&p(W&Lt8= zU^{81g}HlPMmHc_W?InQbH0TZjyq1vJ&;^qi6n}U`u#IPa)A!@7TK=3v=rw;gh{LM z5h9XU79do=lD?2@l}Mrpt0yX^#R6hlU=PQ!!f9zIr9zWT2_hQqX^qqtcm}yEKW-L zA7TzxC_%*C4eGnA=#Fq%$h5epYC)Tuiq2?_5=3xXZh~s2h2a$y(hVWi+lg1i_lTso zD=$cYW9zefAI>F`C_+3EB9fenA|w|)j~y1F)PH+0?XpG1zPpK-76poF zk(iK*e`=T(C_x13qu7HD+{CrL`@6GVp;^3&dB^0981C2ip1PrKRdrWYSF;qyEsp3QZ(6(|Z(1~vH!WC-(d?h&G?6zgn&-Fj zzx%dv%yUMtPmVL@%CfQ}{{CF%L3z_++u$v!2W1cK40+Syqf;8Yqhtqe6M54DImSJ; zylHyxJDJzzO$+8Q0ujj~K9Dypu4uB#Evgq}lB0o2FSKz`(-!oa~ICRKK*EP zW(!%j<2-fIQJFiN*f%XI@+wk0WCw16ylKJZGTL!g<)4)~Z2sWP0rIBBg)J*m_sN?U zX?fFv^?loGORAsrqTS7#7DqR!nVEh6UsAp0O$+8Qg8g%x2O3|S|FP`G{c`cN3|qx$ zworC7?tQYLqr7Qxbf>p7%wa@a$9*dwo>g1kv{?9$_fza4TgCp#9!Po9qW_&|`lX9b zFJlBtv9*rVOWw5jWJMdd$L|danZpRS(DrZorUkNrduJWVV4+@@uPEJcaN(f+<=v%5 z(@mW#hjPi>m*{=4)uC@%pe*eUXofs3K5qbqGZ}&XL=C6qK}@nD@TSHzY?+ z9W9|RYt`=OnibS~q$uwrK`;mU6w#ON;jJI~rUj%_JNrRBgWLfO9{W~d`!hewd@65R zFozN4o4UGq)8Yy9rp5h*?-$IJH!TjS2r{glr5GK5(}Hbh3t6|E*+28F)VFPirq;`w z7R+HCeGfdxeO2DHc+k9QF|6CH!d)w0D_bdVTCk4pG6EbdZ(1BCZ(6Xma>mjPnZoC{ zeNlGYSH%Hy7%^JLF1%^c+q`L!x_DJdOL@~`zPxD>vxMp(j<|cpuGue!?@h2DY&%=) zIJa)x(Q%U?dR;p$#Zqil95Gbhv>1I|E4T6VR%I;3=(tr+EGqIIZrI6R_S>>K3Iy;^7XIn$7YTienaZ5LB$?Rjo4M0nl8Qe zz0>FWtXsYxRaR2AY1-$7-$ob6M3WDaTbS9j9dyJD@D z5fd-ooZ2PN>W?kNdlTgqM;D}}r@rO$X(_gZ%Z(#y+;DRKpYqV^PJJ_pNvtX z{gU;E$QOGSy^~=N*(&zWaZcLru3&rj8~g{0I%Zgk(Q&J4-8U+@rvCBnvvWG6n8OIR z(7bO@7`|^1B%f>bNr<12Y=0HLZxApCwkra4uCzty>;!SleW^+j+C0|+WuH`;Lum8l zt!VT9M_Ks(hnIX}38hN;?%Y}xzW?Ddhjb)nKjbZl=)DP!RWb_UoqnOLX3%>RY*kWU zh>$%+JqriBm-f5M%-rFdtiN5i!25UYHRe0Bpz$5nf*V%&>$lAJE?$Rk7C(8%c>k$K z>^Ih#1N8IbEJA6NZl95eUgNXFSb-Z`a;Nb1)Q{7KjjEuzu-;Ms_igNGB zyY08)D+ND2szg5$VnY$>a^t!`##Pz)Wu>fjt>YjdoM5G=*Ip6mO6#=Wp*H~z>o#PhyA>P~ERjCBp*Xucm zh{FiB)*^1|^ndvqr9L3l2~X}~J6i&TUY9evu3a!kaInh6N;ye{`sX;?&g*Grf8;LQ zc&-SxiqZ1jzG2(T9{u$5vWq_{_Be_XEA}ahy5qFEv|(Pork|AjM|5ym@=a=!W7?Nw ztqP+BKVVf<79+SeL;0|+vlQoXJWDLb_703-skjd56Fun@{SQ}+bYYeD0Bj*gM0VEP zdq*%SxW`{#t8EFF#X91M<}Z)()>NM0K6Y&VxokUI$T5_0aM%f6yXR}Tjh^W2F@mMI z1#7JEzlp9pzT+bAs_|>lJNr!E@p-wqZY0g928z7}tx}AJoc?SLl9bD|>VtHwr)H~S z2+or1d^@y1_*%KwV7~Q(bVS)>bij`^C?FoXVNrz8a&!GC8GCr}_ToM!6G=zZO9;Z% z>nPcA_H?|^fAEEoIS7>kLM_}kLZx7p(iX9^?S-yyb-3&Y(;Qvde_jnjrC^oP&=Ic> zDmRh>LgN-8(xAX$Z&eD{*^jsmmg1gBb)#g*Y5(})-b;&2eX!?I|0p`5n$1B(99Tj+ zs22sMnmUhi323zz^6^YmdtnLd$Rf(`S?}I`|5e^m3q2R34DRl52g$7#*MEO`fj9Yx zwQ{%A>D6WK$8}xrZwJ;jcNxk_A|@|c;Jv;Zh#5zYbsy-t+g;e{VuMgl5)mJx9;)ql zW8S^YAe6&>J7_Hlo;yx;2$g~#N?XL+&H8w~haM5LipvG9{_Pu~QqZBaMZ9|bNbmJ+ z{Y-R~!{vh3sP7x0QqZBayi*-a^IN}pqqpP!?k@M?TrTUAy@O|$`I(8Gy*-unaz;+J zFdM7q&wR??a_ug6=J0+w2$g~kttaD0T3fDKg69mOqbCTxZl74J@3tK>CxIZ(m&w^a z_nkl312UOQ8XrbOF4oTd+O-yWtK=K*Xdi8+mwT`M)zW+yUOhskfZou5kwHU;d=O$i(%>*crEp!N5Yu50%HeWBv*&TE=>95_VziCb zoHh-Evlp29h&&XjC^JB-g$ChNhft|p9j)44=r4U?B28w;F^>p(LfP zRVSWyp}W`Wh_V4v8XwRak$odn3RWo%M7%{&J+r=8tl|i@7v)l{BDCY|9k#-6)9>1# z%g7EnBN@%MxGP62@UH5HG3p=V=lO?sIwx4Yq(+eJOH>Md$@bS5c-QsAoXn#yKIC81 z;K1O4=Dl+eDh0$Xl?%L;buiCxb?;X)Yg={q|8mjDfH|P`>6dle=zdb(-Cx$Q2#Dxu zn-RF4)d376l#@V^RY07VUq9Hqx}VX(2&UC1$XAb0DOjbnMKoX2FZjNb=phcQQYl>5 zNarGylR!`n0`rW-son?OG0H?`0YT_!w$18bL{*sqv|e|diAO%2n$@|x|KTkogXCDN zH3;1rH~D^0uW{~x%G-ka?|H^5Eh~vu3+3(pgD1K>#`g+FUtZh9N;ye{#?5iooHWec z+_G*kp#1z;bd!jzRn~Xg%fVi?ioI3Z&JO-JL^!sak}Tq~Sxfyv_uOQj*Ep-WT&496 zAlvU^X6~%f3%$y(mYHua?`}8G!?P!@A9V5}@2f8Oj=P);6O1_Zmi)`#sK{pyXhr?fB5b=tddq$Q3uA4czvK!@Q-Xab->XL{gCJ;b!gmyRw*i}3O_ia zjL62SQs$HnIN^c(>+YCU!ZkRm&pM5j4_f^*R(S;ze$89@a-UA%gtoi)T(HjM)l_%2 zO9-)Qt>}26;H*wd>((s=C#*qJZde~a>$W=Z7e63W3baO)bl6y#`)Ng}y-9@DCgifC zGnYk(gdf!)jFgrOv_`~nu2_4s`{IM`{ou3V9%no0i^WYoUa+^=d;4FX7qt3%TqlkR z5L*ABHHLD}AklrL*LR)1X>{+bWF4p_gqHef`G3XUo`pjS->iSYTyRwCJ9(mbXPa$B zal}c2DE)Lu;l|?E3_|lNiO?L&jjke4u1b-PDr%6uWkl9_+UvaMkIdEv!(#|Yjq=UCNW$~$(+dku zUh=QhGcwNrsS(>2dY4RFX4;+h^X#AFbnDsQYqYbDxg+CpVY`k7bX{WQOLU*D?Fc1j zvXCW2n@DG4wNenL9N_r#ADh^gq>Sw<#Zhpa1)Gb#o3>Vzm5n{Fln|yq)Tg)~WBwfN z-FeF1%(>V9)nsBAAD^Y-bw1&dv%T+cYwpc$c0~p{H13>dpgYWViRlr~%=mLl4j+$+k1Dv)GnAduaUWX z)xI{FB^qhRse8y>!F#9NFRR>E$8Yp@6s$KZW~vXR>(B1F zQx2EQB^l|o#pEC&eL!eQTE5x6gPj9zvnwjha|r0Gf38&8S6cSH4)2g^Iq`?Gw_dYr zUdq7?{UJ}v_bp`49mi1Kg7~wizx0USZtJOk517LU(5hQjEk6i4lzq}L{|}j6OCnSX ze)Jfy*;p9)A%xvQryMR<=*T~5waX7Jc%k%~FKMj%#-Hi&e+ z(_fzzdhQNeUTMl@3xUwBCI5sNl24t=x0BemI8_EETuvuu&tu zemC@W=RJ9QCoY#QjMvBZF9y2TjOtxDZs%RGR?AZH+*MDs&OaSc8SQRk`u$%js@dJ9 zHHAp46lg_fHH11?$|Z!$i0o`FvQIgn8KJtNBm0a4?UcJw#^Cz=v6W^ITMU5}cYofZ zifDHm>4?w~A`Obm0E3tVAn%k0U0jSZ zxW~c08n;wjZ@*wuxV!C;Js-NSoalPHn%UiL%1I(NY~2*@ZoB!c@$R5WJKcYL(AV6< zDJO~0G12;Q{DF@5Dcl=Wao}wooJDI1S$)>EGOakNe7wOL7n@1sz&X)(>q}NlRcm?(XF}`C&13rGYt$ zW`un^K&w83 zaH>P76kBK!oL5zO3xr;`2-!jBhI{U!jAJR#8pC}fR7w!O(m=%9Ak`Y{i=vQ=Aa5fn z=*ar<2Hii4)PV80YKl{Tu!SF6MgJkccQs{k7T(T+L z54ZZJC;Sc%)(OtNF&QB z?uSz;MhNX^bpXQ%IeUp{c2nm5QO&CC&Ao$2$~~fgqbz6GhTx#%2H=+@8(b0e`IV<29{9W zP<@=#c7prSkXwW0BV4l|PIV;5cC}E}aSnRH9oh8Up#EIDA5J+*gvQNr3Y*{P_8nd~ z=$+Tc)Sz;b2(3-)x%Rz?k6NX4I65a{MTm$~6~d0rr~A|V$(wF9GmxCs2}GnDR%J&6 z%yJgJx;fepcUu1q(SEq@y(?)y+>H}&&Oh>KyB|(DKr3SZ&g=byGh4jM%33 zA;Qpy58IgC4;PIeWR;N$^%;7nTM_PV!x!wAFaII`&oG9xGS_AizFQ0Fb%%DprdovY zmJzWUL>8v;k8C#xuEEd`sgI;pT5CY76qQtk9~@Ce#A4;Om;G?N!~JmIj;O%SOtY`6 zg}=r7SGXTeBVw%b{`_u6reZ1@E5;o5N3x^+$t*{ zLl`M77bU5Gj?;hP&2Gzw+WV<5hI^ceq%Rf)v%}OoA$|SaJ8Qo-8&X}yZSgkz`Kj6a zp>@L%$?k6ZceuNaBdV65B(101-EAs`{R~^`+YFB*lDpfqtRzC~A5qHQ`*2yHRf?|L zO!QigY&NrIpBi(R!-%-&wk~W>N-f8Xz?WAybn|hwC zO}#GPORe8DGhX(Qm4>_9l*0(@Zqs_QIy7F?)=aBaG)E+cFuU7Asp=5YYD-ho{noo~ z@ixBwYAV@_DjGU8->eQ$Hcv`t~(p4<tWQglHz#E`74L^r1azoWTt{+0oFZ5X^m$^H-4EA9_QPF! z#Gk3Hv;SRy{Wq`GsPtYQX!pZ0I*TZi-EIH*@%L2!?Q3EPE*BQQSHHsSNOPRz4!UMr zH%B|@G`gr8?PDD0tlh&s-#yg5?1Q`gq*YpOyatnd?o3OMjKzL8l0o;snhyjS;G0l<+8rq-EEqqKX4b0jwIgXtTF{*|OMOZSHI49al1tdDan zcL$x?PUV`6QQeO7PVN5QQy1`=*$=0A#R%3d_w8$oz1wQl&YW=R`V!_af}@VU zJ^PG<9UJ%kVcQ+(Yfi3+cF6}h3&xDu5AL54*Om4Be_dY5iCWt#0q&;TlS<5mOZJIOD?R^ zHVA~~aqccXwnU{!hge1X`poV&9Ve(<_DQTt?z!V8aylK7F_bEmC{%KaY^(4plLEmn~qX3w2Uu@3S{ ztZMn$g2JKOi-Y{*&Mo=d???IF^EP|E9{wDs`uRQDZpQ2oPK7pf?l&!%QxyVev?zJk z3pqlgjYOlsBa}H#52Vgu85jZ(gqhS09Yf$ov`*uhv2Xt6#?0KkTW37MAyycwX?IFcF z6mgtfM~3!z_;W$*kom-Wi)zpP{_RZ3tBsrb@10WNty{7J=g>#_N+nehUG^M0kl~8f z+>JapHJC&|3J9&6T+fxm<$~sHPX}k#SvC8~rZwg+YTDHA^phyoGTc@@!B z4wY-rnw7HlF>6$?yIW=IgKm{LDLpC+v`STWYwSNVr$*;(LsnQFo=Fk;!|emKwh7QN zKVk^YT}Wx%K&w6ztEvzl$uSBW@DM7GYmf3~0ulyh3kmGoT?D;DMFZdktLiZ+-lu8f?8^Ih)~DW^Y02SpE%e^Y3>5eJ&|6Q zZ$Uh>J-^=68L7*hVlxhE+h#<~0mt~0-mUaXPW(!&I(FWGVEC^!gL|(_o4!`dg-=>; z9MRyX;$V+_1*3(01p`v5B_)N+8%)Wpl~eec!&b3A$NA}OH}&UfH@dfff2a3z ztBOpco40s9WEM}U^rn~K4#55J{lb4%OiGm;Q|vK^5pmCdD}1SBwR{Dm zaNe{O`@!fqVnL_(3r_oXOmOI7f$14EqKu9sie~*^-t#iQd%b)GgDqj7;+{8l7k4~V zzJhVl#nUn@#c_)xE;@IVH|w}oey!&kr`UG3ic4~w4Mn58JFaWt_TAPbrh^fz&t!Xg z{|T?S?V8Yv%P`OIxcQmk-2S8rT2*WTEV{` znpyaL`uVc4o6I@%QLI|`*^=3C>lW_;`C0*6D={r7D|9nU%WABN*9Rj`lRjp_KP$Zh zuf`p~bIn?pK32Opc(>uSnCC3T7Ron9_O6;eUfN)#yerK1a&5AIj`QW{zvOKc#DUjM zGwobs#b~xrPKcdd)^iNg-=zs~9b(4&5=zD`?ZoefZIn%b3H6xDI62m(u?J z`ur?^nS6h>w*?@^L7>o$@_M_dx_td zK+Dj>i%RxLi((GSRRr`YZLJDNXLGm2cNr>0Xmck6l)c+$4wp;UOWvi0@&ONUsPI0 z=zE8hi|1d?-jugo5N(DuDP;~LdTeOu_Y_2%UO;Spc4^*9K^*_)QKi$L*j%6-LAZy6 zt9<7|9(=^P-AeeetjgK{)ai&w^Lp_{xP(pz(E2^)Jd2b4SJ;MktMl#1Lsgm{A5Ck+Sp;xwlRS{aH@qZk_QqYmC^DII+i~y~XHagPgZ>WP2 zDkb$qI$m#aXt4N%L%ntXcNA(c;&8c~p^h`{oLV!E`Qs3C2Ov)i1sWgDd_+O@IZnlt zR{77~^>atOYsszl)|MBPjxDU&`HmAG=pZGPYDv}u`76Gp11^iB%evzT<}d>J7OO!i zAHQ_K2$ssRDs2E35!uTK(N|4gaakwLP^;=zg(jGWEfqxm;I0^n3k5SgE@=#<9=i@aRf_o6ja{c!wJXaYlG7lVRVjiS9S9^7$J;R;8caM zvHE?#z5WH=E)PUoIw58C3Hqf0tKE@JHhX8Lp2;^>rQtQGb7tAGsMd2!3w~L$#*7T0 zSO2uy&~JUwEOF1k2$q8GWR_SR%&7{I^}O3vErUNk?;Jo!yK6Riu!L=gg?e3{ifZ3z zd}w_Ca-VHyDc0vWi!Q#xOFuQGyy(c&U?d6U(mbY^j<>)MzEAd-TLum zzg;pjBfBl8T^U2Llt#oN=IqxVwdb5tr@hC~RVmc7qHUdD)4E@e58RT7O1jp`$&LpfC;tW`a(f5Gi|#^1aXN3JrKs8#So;|4T) zo?TZn&~2i~3rw zNJaE(AFTEdl6^~g7w@&B0jx4Tsq`5>ybXICL!*yENw}__8>0L&uT6-P8s8c1ExiXw3!3X}qVMH?ZFP zvV-=t3z7(xVxLe8*`6BqYI_DvEjYSv5aA!ww?~{LLeW;3Mx3bJBmx#j*=}}ngd>je zFl-+&G$XR@9OY`OWgVc^KUftZ(n%>sSFb}kNqxAkEh^H15htptBqG~B$SQ+SPE`my z8r(7HkYMSol=n(;3Hp!7^9R2F%KyjRH9FTAxXN5dNwM+6v_Z8>qpP-SUS;bev ztUi*6$a9msh%*oxchH&{T#~7eY7rV~Mf`UiY?a1v-#SzZIs*#W67GarDS6SO|> z8jDchX;92bBJ`OGa`;(4R0@5R(xHx=r@IIdajHVtzP-83q7FQ0Sf@GPy%l@n6-0#Q zc_wSo>?KEZ1jQUiC~b9YmD9fue(?TI^Lm#R@N>944@UDBpmnyz>cC(8n3F^xR#wLZ znHz)jhU*5ISrsiyo*<15NX2IjB(g!zS&ih3E%{az%^@>FX+#}z_}S<(M``F_3$45& zm{S!ZidAsB#Oiy=E1stkw0R~EbwslX#-b>%Af*|XL{yzuDg_Ufh7PeXXAU6pJmOS^ zuzsl5un%RaRa~xKuO5-KM9~(pytH%h`m!zVpf`VZdEO`49#yxjB;Ddc$+$2q^Ov$y)gE$-uQ{Ol)lS96SK4ds33Oy?jYRxSL;&o0j`C2KQl70oS0 zv4V#>Q^a&O6Z`bN%6qNm&(SjnMi%L>TNJ?<7=a=UrD<9l@- zYk}6@)#mQ#mPKx>Q}4_{s1$T49U^wf8vVz!VM)}#a*rDCsq1y$oa%AeIQQBe!#w5y zp;m#8>!`f<1$R;2@En9nLATP5BWqrH;hI;e)N>)?^XO$uu;%4r&1>k>v!_X&7ldnG zrDn}*PPpcUJ~84jLTc8mN6DI(AY{$UtYFESSAk?=X}IQPT5!1Lg;Amu^xo4aO*3m= zW|d6VykZ<=i6SJg%(|MadC7TovgVZ+u6dP6f8~d3UZuFpgin$grJ6DI3toz^U`6Xu z;4nhzA+_4)B1|qFF>||_BZH1RN{*Z?I?Q$Gvvsa*ojFpjkpe<#ix~0TZzrw2zHA~; zihvGj+hznfrtyEW`eq$D*>Ua=gw>RtJ-8KPsSfQEYu@~di8QX;=q7ZSCogaqAy%2*^}x?3ijL6pG-8FC(y~}8 zUW18PnaqF=Mu0}|V|Bof(Q}V@MRlN_6`@k`yplC9FI@9N4H_NDD=wEa)U0{63)j5x zd|~b^o@rhF7PkpR0s0U(v*uM2u6fB`-E6CsUb`S%^O_|k6`*dOC|@K9u5&JnqszKw z#a%pqcKCB96Pd#Z+=7VW|{uUM=Y!F`um^O_y5d3oH+z;mqwt{ZLV_}{Gd>Ahj8`h>QvK5@@r z5yCN90*+>4h|u|ms4vMP5cebk7KV2+xd>BJ$#S)xa2;hwPul@=V4>=(UI!ys3fB=g zt3%ejW`t{AMu&13!Tr3kD*TfUlJU{LJ>H^Z&8uU$<`wXW!u?(?n{gmdQ0uKfzazwblH!nTt*;E)TbQJBLqu9N4Cyo&1*)u<`uBL z?1x0b^bEOHF^3VLvpTYNW!JV*7E8fG&6un_+6QwO5%(jDi6dBwqoDG3K0`PrUxz%` zE*fQEq3X8dpv4$Ow1NeWq8VXhC2L-8xaP&PgXS&+-eP2sbrC;Y^D2p~@<8cbpFAU% z>RlgbS>G}3U)H>$R%@On%v=VtAt?n5lUZUB%;9qNIxMtSg==0||Im4#QnnoyhO-o6 zm8^N;Im(eWuV}VL{ZJ{^XV$!eaLvnQ4wuXN%$k=Uu6cQkU@5H|>xZm)`LIgXykZEJ zihCZ;a$?QP%u{Q0RVu9WsJC+*S@ZJ3H7}1X;kco)|xR4HKATwI7 zv_)TI1sd1GnJMFQ9HAUWfY$4XlIh#iXoDy#d3xr-bi11H3U=CZ7)KTSpVl3N% z2rhS-5kB=*VU=={29gSI?8~?=!23#tLL!HAmDk#Q8W#O_PfD%1@}-K=?;43Raj7=oohYc7~IuOM9W!c%G#U6x{> z5T$HS4ST7-a;XJJ*9{{4WBT@p12iL)w!$>xL{dov{K#fIBb37k(0Uy@vh5rkZM8{+ z`WHiB%`0XVqjPkmfo1JUeL!f7vaN{`;3N^*_L1~MIaML-Xdr7|UbyCk5g_thX7Su` z&C6UzNwM+6q0+EWGbURfVwpiOrz%9`xsitFKxo`SYi4jskjsvoNrYOci2trb z>i`Ii;l6dKlp<`bWX&rG*SyM-R%t{z($ImQ%|Yn>xW9Ak5U@5MndO2-Pw$1PE`myQzUC%LAd4> zd*Wp@&odc60$TIRnSlx|G*($1vgQ?pYhJNgV0j*l<}X0&Y>U+)f776tlSCj^c8*Ne zygW$DnwObXL0Op7lP5@{19W`W0QF64UeO#fBb0_uC>=jrAIwo2I@m%huX)9ssu0!> ztPh53US@qzXXOQLp2;!a3cBjNVonlKbzZ3yJX9Jw#KN380Gn6LsS07|kj3k$_W?rf zWwc(8A<~E%bCL-7VG*+C<%MfrKF|9k+oS3>YhHf1=H+r$^Bf}2qnI_XAYAiuc@9ZD zkMfmg4b7UD7p{5vJh#NNj)+^8_W$)(!e|1Zuq_{-hDQ7?pZI)sR|+e zq`A}0p7jERzP+qyNCB+$lXHIT09){<;xcV+Sbii|5kDv9z z9Oz(#zL$>DO{;|-oFHIo4QIU&jdvm=bc6tbHx46C5}|J&<|2?8sza>;I_t-aa@I?4 zIp?LF{9{h@#*JN^_0mqxdLezLKC-@Cv#s_qIqT&YIp<}G z{9_JiMQ{s_bb!dwp_vG@M%p66)01X02ecx%&$nm2gr_Iv%bUe+czP1vKh_piMkOWY z;h2*|g!-zebFM*^0$S@vPQaA2UN)_*=`LGa)8`z8R2VChF`CoXbNrQG8dAzhBC>TZ zXP%j}UgXTPeC}n?R@f@gG7gs6!gWMIxyq>uA$^JQ+!$o?mn`8dG3{LIKhj|kC|5az zW<;n%&w7EB<}T3O6X|t1>*dAm`E94oNcEAkUVzZH&4|YrGt(t*>*bZj1A;|6 zY6h>|INJ2JS}yC0BlxTr)^TT-rmmj#!f402{qokSXO8LS|82*}VAh{!yZz;?mrv!a z7nZ8AyQ}*zIqRj&ob~db4@(L^56^mG4kK8f<238*rZ%*^(OoHLz1&^r9Jf%;dO1?g zdSMG2{?gT5AZNY2Y|eUFx%K_Rk>5;8Et0cdn8S#;=l6G+T(VTodYQ3kT8jN(bR2O^ z&-V%ze={cdtwUgX2CXSZ#}VILx~2opdU;yTdSOf0r?}@6R`2duB#7@GnU-NGj$0gY zW1msp&kI`mXI|Yn#kR9mT#|f~RnB^ua#ss?am}VN9gJXoCfn1EM=&ReP_*n3m9t)+3eS2; zj_2GHWqTiJ(X(ElLpcvo*G%g##Gc5Y3r?^YbMigjFc;5qK? za@Na3=B$@D@1I$?r|9{z$KBWIhP=B$?rIqQY(Week;cX)7bN1XMt z>soUHW>n{lW(ytXemU!9&e{2Xqnn!)vUawL(T-CtXT21i+RDA>iIdBi!-%*JWa3xS z{(8z;FQ{7{UzO%D81jzORnB@jSBRnG| zU=GSv1oSBldHn3XJ8{gNj7kwYJAV}b#~ebN(N59k%$lJRQbmtCITke#LSA9}tvh2><{9 literal 0 HcmV?d00001 diff --git a/data/kiva_shelf/model.sdf b/data/kiva_shelf/model.sdf new file mode 100644 index 000000000..b1f49e66b --- /dev/null +++ b/data/kiva_shelf/model.sdf @@ -0,0 +1,55 @@ + + + + 1 + 0 2 1.21 0 0 0 + + + 0.0 0.0 1.2045 0 0 0 + 76.26 + + 47 + -0.003456 + 0.001474 + 13.075 + -0.014439 + 47 + + + + + 0 0 0 1.5707 0 0 + + + meshes/pod_lowres.stl + + + + 0.9 0.8 0.5 1 + + + + + + 0 0 0 1.5707 0 0 + + + meshes/pod_lowres.stl + + + + + + 0.8 + 0.8 + 0.0 0.0 0.0 + 1.0 + 1.0 + + + + + + + + diff --git a/data/kuka_iiwa/model.sdf b/data/kuka_iiwa/model.sdf index 0df20cff7..3a962ee74 100644 --- a/data/kuka_iiwa/model.sdf +++ b/data/kuka_iiwa/model.sdf @@ -1,6 +1,7 @@ + 1 0 0 0 0 -0 0 @@ -34,7 +35,7 @@ 1 0 0 1 - 0 0 1 1 + 0.2 0.2 0.2 1 0.1 0.1 0.1 1 0 0 0 0 @@ -71,6 +72,12 @@ meshes/link_1.stl + + 1 0 0 1 + 0.5 0.7 1.0 1 + 0.1 0.1 0.1 1 + 0 0 0 0 + @@ -124,6 +131,12 @@ meshes/link_2.stl + + 1 0 0 1 + 0.5 0.7 1.0 1 + 0.1 0.1 0.1 1 + 0 0 0 0 + @@ -177,6 +190,12 @@ meshes/link_3.stl + + 1 0 0 1 + 1.0 0.42 0.04 1 + 0.1 0.1 0.1 1 + 0 0 0 0 + @@ -230,6 +249,12 @@ meshes/link_4.stl + + 1 0 0 1 + 0.5 0.7 1.0 1 + 0.1 0.1 0.1 1 + 0 0 0 0 + @@ -283,6 +308,12 @@ meshes/link_5.stl + + 1 0 0 1 + 0.5 0.7 1.0 1 + 0.1 0.1 0.1 1 + 0 0 0 0 + @@ -336,6 +367,12 @@ meshes/link_6.stl + + 1 0 0 1 + 1.0 0.42 0.04 1 + 0.1 0.1 0.1 1 + 0 0 0 0 + @@ -389,6 +426,12 @@ meshes/link_7.stl + + 1 0 0 1 + 0.2 0.2 0.2 1 + 0.1 0.1 0.1 1 + 0 0 0 0 + diff --git a/data/plane.urdf b/data/plane.urdf new file mode 100644 index 000000000..57b746104 --- /dev/null +++ b/data/plane.urdf @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/ExampleBrowser/ExampleEntries.cpp b/examples/ExampleBrowser/ExampleEntries.cpp index 16185efe4..5682275ce 100644 --- a/examples/ExampleBrowser/ExampleEntries.cpp +++ b/examples/ExampleBrowser/ExampleEntries.cpp @@ -248,7 +248,7 @@ static ExampleEntry gDefaultExamples[]= ExampleEntry(1, "Physics Client (Direct)", "Create a physics client that can communicate with a physics server directly in-process.", PhysicsClientCreateFunc,eCLIENTEXAMPLE_DIRECT), ExampleEntry(1,"R2D2 Grasp","Load the R2D2 robot from URDF file and control it to grasp objects", R2D2GraspExampleCreateFunc, eROBOTIC_LEARN_GRASP), - ExampleEntry(1,"URDF Compliant Contact","Experiment/improve compliant rigid contact using parameters from URDF file (contact_cfm, contact_erp, lateral_friction, rolling_friction)", R2D2GraspExampleCreateFunc,eROBOTIC_LEARN_COMPLIANT_CONTACT), + ExampleEntry(1,"URDF Compliant Contact","Work-in-progress, experiment/improve compliant rigid contact using parameters from URDF file (contact_cfm, contact_erp, lateral_friction, rolling_friction)", R2D2GraspExampleCreateFunc,eROBOTIC_LEARN_COMPLIANT_CONTACT), diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index 002a3cf93..64be1573b 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -225,6 +225,15 @@ bool UrdfParser::parseInertia(UrdfInertia& inertia, TiXmlElement* config, ErrorL { inertia.m_linkLocalFrame.setIdentity(); inertia.m_mass = 0.f; + if(m_parseSDF) + { + TiXmlElement* pose = config->FirstChildElement("pose"); + if (pose) + { + parseTransform(inertia.m_linkLocalFrame, pose,logger,m_parseSDF); + } + } + // Origin @@ -448,6 +457,15 @@ bool UrdfParser::parseCollision(UrdfCollision& collision, TiXmlElement* config, collision.m_linkLocalFrame.setIdentity(); + if(m_parseSDF) + { + TiXmlElement* pose = config->FirstChildElement("pose"); + if (pose) + { + parseTransform(collision.m_linkLocalFrame, pose,logger,m_parseSDF); + } + } + // Origin TiXmlElement *o = config->FirstChildElement("origin"); if (o) @@ -474,7 +492,15 @@ bool UrdfParser::parseCollision(UrdfCollision& collision, TiXmlElement* config, bool UrdfParser::parseVisual(UrdfModel& model, UrdfVisual& visual, TiXmlElement* config, ErrorLogger* logger) { visual.m_linkLocalFrame.setIdentity(); - + if(m_parseSDF) + { + TiXmlElement* pose = config->FirstChildElement("pose"); + if (pose) + { + parseTransform(visual.m_linkLocalFrame, pose,logger,m_parseSDF); + } + } + // Origin TiXmlElement *o = config->FirstChildElement("origin"); if (o) @@ -505,6 +531,8 @@ bool UrdfParser::parseVisual(UrdfModel& model, UrdfVisual& visual, TiXmlElement* { UrdfMaterial* matPtr = new UrdfMaterial; matPtr->m_name = "mat"; + if (name_char) + matPtr->m_name = name_char; TiXmlElement *diffuse = mat->FirstChildElement("diffuse"); if (diffuse) { std::string diffuseText = diffuse->GetText(); @@ -512,7 +540,7 @@ bool UrdfParser::parseVisual(UrdfModel& model, UrdfVisual& visual, TiXmlElement* parseVector4(rgba,diffuseText); matPtr->m_rgbaColor = rgba; model.m_materials.insert(matPtr->m_name.c_str(),matPtr); - visual.m_materialName = "mat"; + visual.m_materialName = matPtr->m_name; visual.m_hasLocalMaterial = true; } } @@ -670,6 +698,8 @@ bool UrdfParser::parseJointLimits(UrdfJoint& joint, TiXmlElement* config, ErrorL joint.m_upperLimit = 0.f; joint.m_effortLimit = 0.f; joint.m_velocityLimit = 0.f; + joint.m_jointDamping = 0.f; + joint.m_jointFriction = 0.f; if (m_parseSDF) { @@ -1281,15 +1311,22 @@ bool UrdfParser::loadSDF(const char* sdfText, ErrorLogger* logger) return false; } - TiXmlElement *world_xml = sdf_xml->FirstChildElement("world"); - if (!world_xml) - { - logger->reportError("expected a world element"); - return false; - } - + //apparently, SDF doesn't require a "world" element, optional? URDF does. + TiXmlElement *world_xml = sdf_xml->FirstChildElement("world"); + + TiXmlElement* robot_xml = 0; + + if (!world_xml) + { + logger->reportWarning("expected a world element, continuing without it."); + robot_xml = sdf_xml->FirstChildElement("model"); + } else + { + robot_xml = world_xml->FirstChildElement("model"); + } + // Get all model (robot) elements - for (TiXmlElement* robot_xml = world_xml->FirstChildElement("model"); robot_xml; robot_xml = robot_xml->NextSiblingElement("model")) + for (; robot_xml; robot_xml = robot_xml->NextSiblingElement("model")) { UrdfModel* localModel = new UrdfModel; m_tmpModels.push_back(localModel); diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.h b/examples/Importers/ImportURDFDemo/UrdfParser.h index 8e6dc6fb7..25f7e3e38 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.h +++ b/examples/Importers/ImportURDFDemo/UrdfParser.h @@ -125,6 +125,15 @@ struct UrdfJoint double m_jointDamping; double m_jointFriction; + UrdfJoint() + :m_lowerLimit(0), + m_upperLimit(0), + m_effortLimit(0), + m_velocityLimit(0), + m_jointDamping(0), + m_jointFriction(0) + { + } }; struct UrdfModel diff --git a/examples/OpenGLWindow/GLInstancingRenderer.cpp b/examples/OpenGLWindow/GLInstancingRenderer.cpp index e20aed56b..e54d073cb 100644 --- a/examples/OpenGLWindow/GLInstancingRenderer.cpp +++ b/examples/OpenGLWindow/GLInstancingRenderer.cpp @@ -19,7 +19,7 @@ subject to the following restrictions: bool useShadowMap=true;//false;//true; int shadowMapWidth=4096;//8192; int shadowMapHeight=4096; -float shadowMapWorldSize=50; +float shadowMapWorldSize=25; #define MAX_POINTS_IN_BATCH 1024 #define MAX_LINES_IN_BATCH 1024 @@ -75,7 +75,7 @@ float shadowMapWorldSize=50; static InternalDataRenderer* sData2; GLint lineWidthRange[2]={1,1}; -static b3Vector3 gLightPos=b3MakeVector3(-5,200,-40); +static b3Vector3 gLightPos=b3MakeVector3(-5,12,-4); struct b3GraphicsInstance { diff --git a/examples/OpenGLWindow/Shaders/instancingPS.glsl b/examples/OpenGLWindow/Shaders/instancingPS.glsl index fd992e5a8..310f5fed4 100644 --- a/examples/OpenGLWindow/Shaders/instancingPS.glsl +++ b/examples/OpenGLWindow/Shaders/instancingPS.glsl @@ -25,7 +25,8 @@ void main(void) vec4 texel = fragment.color*texture(Diffuse,vert.texcoord);//fragment.color; vec3 ct,cf; float intensity,at,af; - intensity = max(dot(lightDir,normalize(normal)),0); + + intensity = 0.5+0.5*clamp( dot( normalize(normal),lightDir ), -1,1 ); cf = intensity*(vec3(1.0,1.0,1.0)-ambient)+ambient; af = 1.0; diff --git a/examples/OpenGLWindow/Shaders/instancingPS.h b/examples/OpenGLWindow/Shaders/instancingPS.h index a32e7b29c..8e2ed9f28 100644 --- a/examples/OpenGLWindow/Shaders/instancingPS.h +++ b/examples/OpenGLWindow/Shaders/instancingPS.h @@ -22,7 +22,8 @@ static const char* instancingFragmentShader= \ " vec4 texel = fragment.color*texture(Diffuse,vert.texcoord);//fragment.color;\n" " vec3 ct,cf;\n" " float intensity,at,af;\n" -" intensity = max(dot(lightDir,normalize(normal)),0);\n" +" \n" +" intensity = 0.5+0.5*clamp( dot( normalize(normal),lightDir ), -1,1 );\n" " cf = intensity*(vec3(1.0,1.0,1.0)-ambient)+ambient;\n" " af = 1.0;\n" " \n" diff --git a/examples/OpenGLWindow/Shaders/instancingVS.glsl b/examples/OpenGLWindow/Shaders/instancingVS.glsl index 1663f3698..709c07a49 100644 --- a/examples/OpenGLWindow/Shaders/instancingVS.glsl +++ b/examples/OpenGLWindow/Shaders/instancingVS.glsl @@ -61,7 +61,7 @@ out vec3 lightDir,normal,ambient; void main(void) { vec4 q = instance_quaternion; - ambient = vec3(0.6,.6,0.6); + ambient = vec3(0.5,.5,0.5); vec4 worldNormal = (quatRotate3( vertexnormal,q)); normal = normalize(worldNormal).xyz; diff --git a/examples/OpenGLWindow/Shaders/instancingVS.h b/examples/OpenGLWindow/Shaders/instancingVS.h index 563d22127..8be2f548f 100644 --- a/examples/OpenGLWindow/Shaders/instancingVS.h +++ b/examples/OpenGLWindow/Shaders/instancingVS.h @@ -52,7 +52,7 @@ static const char* instancingVertexShader= \ "void main(void)\n" "{\n" " vec4 q = instance_quaternion;\n" -" ambient = vec3(0.6,.6,0.6);\n" +" ambient = vec3(0.5,.5,0.5);\n" " \n" " vec4 worldNormal = (quatRotate3( vertexnormal,q));\n" " normal = normalize(worldNormal).xyz;\n" diff --git a/examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl b/examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl index cd780fbea..0902c5149 100644 --- a/examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl +++ b/examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl @@ -27,8 +27,7 @@ void main(void) vec3 ct,cf; float intensity,at,af; - intensity = clamp( dot( normalize(normal),lightDir ), 0,1 ); - + intensity = 0.5+0.5*clamp( dot( normalize(normal),lightDir ), -1,1 ); af = 1.0; diff --git a/examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.h b/examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.h index 0550ff58a..a9d53adb5 100644 --- a/examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.h +++ b/examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.h @@ -21,8 +21,7 @@ static const char* useShadowMapInstancingFragmentShader= \ " vec3 ct,cf;\n" " float intensity,at,af;\n" " \n" -" intensity = clamp( dot( normalize(normal),lightDir ), 0,1 );\n" -" \n" +" intensity = 0.5+0.5*clamp( dot( normalize(normal),lightDir ), -1,1 );\n" " \n" " af = 1.0;\n" " \n" diff --git a/examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.glsl b/examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.glsl index 9de5c0aa5..222e73cfd 100644 --- a/examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.glsl +++ b/examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.glsl @@ -65,7 +65,7 @@ out vec3 lightDir,normal,ambient; void main(void) { vec4 q = instance_quaternion; - ambient = vec3(0.6,.6,0.6); + ambient = vec3(0.5,.5,0.5); vec4 worldNormal = (quatRotate3( vertexnormal,q)); diff --git a/examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.h b/examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.h index e52ec62ee..a98e44f82 100644 --- a/examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.h +++ b/examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.h @@ -55,7 +55,7 @@ static const char* useShadowMapInstancingVertexShader= \ "void main(void)\n" "{\n" " vec4 q = instance_quaternion;\n" -" ambient = vec3(0.6,.6,0.6);\n" +" ambient = vec3(0.5,.5,0.5);\n" " \n" " vec4 worldNormal = (quatRotate3( vertexnormal,q));\n" " \n" diff --git a/examples/RoboticsLearning/R2D2GraspExample.cpp b/examples/RoboticsLearning/R2D2GraspExample.cpp index b0f007940..54a897af5 100644 --- a/examples/RoboticsLearning/R2D2GraspExample.cpp +++ b/examples/RoboticsLearning/R2D2GraspExample.cpp @@ -59,50 +59,89 @@ public: { bool connected = m_robotSim.connect(m_guiHelper); b3Printf("robotSim connected = %d",connected); - b3RobotSimLoadURDFArgs args(""); + if ((m_options & eROBOTIC_LEARN_GRASP)!=0) { - args.m_urdfFileName = "r2d2.urdf"; - args.m_startPosition.setValue(0,0,.5); - m_r2d2Index = m_robotSim.loadURDF(args); - int numJoints = m_robotSim.getNumJoints(m_r2d2Index); - b3Printf("numJoints = %d",numJoints); + { + b3RobotSimLoadFileArgs args(""); + args.m_fileName = "r2d2.urdf"; + args.m_startPosition.setValue(0,0,.5); + b3RobotSimLoadFileResults results; + if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1) + { + int m_r2d2Index = results.m_uniqueObjectIds[0]; + int numJoints = m_robotSim.getNumJoints(m_r2d2Index); + b3Printf("numJoints = %d",numJoints); - for (int i=0;im_renderer && m_app->m_renderer->getActiveCamera()) { m_app->m_renderer->getActiveCamera()->setCameraDistance(dist); diff --git a/examples/RoboticsLearning/b3RobotSimAPI.cpp b/examples/RoboticsLearning/b3RobotSimAPI.cpp index 36df27411..235861913 100644 --- a/examples/RoboticsLearning/b3RobotSimAPI.cpp +++ b/examples/RoboticsLearning/b3RobotSimAPI.cpp @@ -598,36 +598,71 @@ void b3RobotSimAPI::setJointMotorControl(int bodyUniqueId, int jointIndex, const } } -int b3RobotSimAPI::loadURDF(const b3RobotSimLoadURDFArgs& args) +bool b3RobotSimAPI::loadFile(const struct b3RobotSimLoadFileArgs& args, b3RobotSimLoadFileResults& results) { + bool statusOk = false; + int robotUniqueId = -1; b3Assert(m_data->m_connected); - + switch (args.m_fileType) { - b3SharedMemoryStatusHandle statusHandle; - int statusType; - b3SharedMemoryCommandHandle command = b3LoadUrdfCommandInit(m_data->m_physicsClient, args.m_urdfFileName.c_str()); + case B3_URDF_FILE: + { + b3SharedMemoryStatusHandle statusHandle; + int statusType; + b3SharedMemoryCommandHandle command = b3LoadUrdfCommandInit(m_data->m_physicsClient, args.m_fileName.c_str()); - //setting the initial position, orientation and other arguments are optional + //setting the initial position, orientation and other arguments are optional - b3LoadUrdfCommandSetStartPosition(command, args.m_startPosition[0], - args.m_startPosition[1], - args.m_startPosition[2]); - b3LoadUrdfCommandSetStartOrientation(command,args.m_startOrientation[0] - ,args.m_startOrientation[1] - ,args.m_startOrientation[2] - ,args.m_startOrientation[3]); - if (args.m_forceOverrideFixedBase) - { - b3LoadUrdfCommandSetUseFixedBase(command,true); - } - statusHandle = submitClientCommandAndWaitStatusMultiThreaded(m_data->m_physicsClient, command); + b3LoadUrdfCommandSetStartPosition(command, args.m_startPosition[0], + args.m_startPosition[1], + args.m_startPosition[2]); + b3LoadUrdfCommandSetStartOrientation(command,args.m_startOrientation[0] + ,args.m_startOrientation[1] + ,args.m_startOrientation[2] + ,args.m_startOrientation[3]); + if (args.m_forceOverrideFixedBase) + { + b3LoadUrdfCommandSetUseFixedBase(command,true); + } + statusHandle = submitClientCommandAndWaitStatusMultiThreaded(m_data->m_physicsClient, command); + statusType = b3GetStatusType(statusHandle); + b3Assert(statusType==CMD_URDF_LOADING_COMPLETED); + robotUniqueId = b3GetStatusBodyIndex(statusHandle); + results.m_uniqueObjectIds.push_back(robotUniqueId); + statusOk = true; + break; + } + case B3_SDF_FILE: + { + b3SharedMemoryStatusHandle statusHandle; + int statusType; + b3SharedMemoryCommandHandle command = b3LoadSdfCommandInit(m_data->m_physicsClient, args.m_fileName.c_str()); + statusHandle = submitClientCommandAndWaitStatusMultiThreaded(m_data->m_physicsClient, command); statusType = b3GetStatusType(statusHandle); - b3Assert(statusType==CMD_URDF_LOADING_COMPLETED); - robotUniqueId = b3GetStatusBodyIndex(statusHandle); - } + b3Assert(statusType == CMD_SDF_LOADING_COMPLETED); + if (statusType == CMD_SDF_LOADING_COMPLETED) + { + int numBodies = b3GetStatusBodyIndices(statusHandle, 0,0); + if (numBodies) + { + results.m_uniqueObjectIds.resize(numBodies); + int numBodies = b3GetStatusBodyIndices(statusHandle, &results.m_uniqueObjectIds[0],results.m_uniqueObjectIds.size()); - return robotUniqueId; + } + statusOk = true; + } + + break; + } + default: + { + b3Warning("Unknown file type in b3RobotSimAPI::loadFile"); + } + + } + + return statusOk; } bool b3RobotSimAPI::connect(GUIHelperInterface* guiHelper) diff --git a/examples/RoboticsLearning/b3RobotSimAPI.h b/examples/RoboticsLearning/b3RobotSimAPI.h index 35b56c67f..61320553f 100644 --- a/examples/RoboticsLearning/b3RobotSimAPI.h +++ b/examples/RoboticsLearning/b3RobotSimAPI.h @@ -6,22 +6,40 @@ #include "../SharedMemory/SharedMemoryPublic.h" #include "Bullet3Common/b3Vector3.h" #include "Bullet3Common/b3Quaternion.h" +#include "Bullet3Common/b3AlignedObjectArray.h" + #include - -struct b3RobotSimLoadURDFArgs +enum b3RigidSimFileType { - std::string m_urdfFileName; + B3_URDF_FILE=1, + B3_SDF_FILE, + B3_AUTO_DETECT_FILE//todo based on extension +}; + +struct b3RobotSimLoadFileArgs +{ + std::string m_fileName; b3Vector3 m_startPosition; b3Quaternion m_startOrientation; bool m_forceOverrideFixedBase; + int m_fileType; - b3RobotSimLoadURDFArgs(const std::string& urdfFileName) - :m_urdfFileName(urdfFileName), + b3RobotSimLoadFileArgs(const std::string& fileName) + :m_fileName(fileName), m_startPosition(b3MakeVector3(0,0,0)), m_startOrientation(b3Quaternion(0,0,0,1)), - m_forceOverrideFixedBase(false) + m_forceOverrideFixedBase(false), + m_fileType(B3_URDF_FILE) + { + } +}; + +struct b3RobotSimLoadFileResults +{ + b3AlignedObjectArray m_uniqueObjectIds; + b3RobotSimLoadFileResults() { } }; @@ -63,7 +81,7 @@ public: bool connect(struct GUIHelperInterface* guiHelper); void disconnect(); - int loadURDF(const struct b3RobotSimLoadURDFArgs& args); + bool loadFile(const struct b3RobotSimLoadFileArgs& args, b3RobotSimLoadFileResults& results=b3RobotSimLoadFileResults()); int getNumJoints(int bodyUniqueId) const; diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 2b1401a0f..d5b50d2ba 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -33,7 +33,7 @@ #define MAX_SDF_FILENAME_LENGTH 1024 #define MAX_FILENAME_LENGTH MAX_URDF_FILENAME_LENGTH #define MAX_NUM_LINKS MAX_DEGREE_OF_FREEDOM -#define MAX_SDF_BODIES 1024 +#define MAX_SDF_BODIES 500 struct TmpFloat3 { diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index aebf0440e..650948a1a 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -138,6 +138,7 @@ void TinyRenderObjectData::registerMeshShape(const float* vertices, int numVerti */ } + m_model->reserveMemory(numVertices,numIndices); for (int i=0;iaddVertex(vertices[i*9], diff --git a/examples/TinyRenderer/model.cpp b/examples/TinyRenderer/model.cpp index f7a0bea75..8864d0a2f 100644 --- a/examples/TinyRenderer/model.cpp +++ b/examples/TinyRenderer/model.cpp @@ -76,6 +76,14 @@ void Model::loadDiffuseTexture(const char* relativeFileName) diffusemap_.read_tga_file(relativeFileName); } +void Model::reserveMemory(int numVertices, int numIndices) +{ + verts_.reserve(numVertices); + norms_.reserve(numVertices); + uv_.reserve(numVertices); + faces_.reserve(numIndices); +} + void Model::addVertex(float x,float y,float z, float normalX, float normalY, float normalZ, float u, float v) { verts_.push_back(Vec3f(x,y,z)); diff --git a/examples/TinyRenderer/model.h b/examples/TinyRenderer/model.h index aadb9291f..6cd9e383b 100644 --- a/examples/TinyRenderer/model.h +++ b/examples/TinyRenderer/model.h @@ -32,6 +32,7 @@ public: } void loadDiffuseTexture(const char* relativeFileName); void setDiffuseTextureFromData(unsigned char* textureImage,int textureWidth,int textureHeight); + void reserveMemory(int numVertices, int numIndices); void addVertex(float x,float y,float z, float normalX, float normalY, float normalZ, float u, float v); void addTriangle(int vertexposIndex0, int normalIndex0, int uvIndex0, int vertexposIndex1, int normalIndex1, int uvIndex1,