From 554dd790d9a59cdf48968c4ffa858d46ffb809a6 Mon Sep 17 00:00:00 2001 From: Navid Mahabadi Date: Tue, 23 Mar 2021 10:11:19 +0100 Subject: [PATCH 01/14] fix: UnaryFactor Jacobian --- doc/Code/LocalizationFactor.cpp | 6 +++++- doc/gtsam.lyx | 34 ++++++++++++++++--------------- doc/gtsam.pdf | Bin 824145 -> 826123 bytes examples/LocalizationExample.cpp | 20 ++++++++++-------- 4 files changed, 34 insertions(+), 26 deletions(-) diff --git a/doc/Code/LocalizationFactor.cpp b/doc/Code/LocalizationFactor.cpp index 79a54903e..623aef8cb 100644 --- a/doc/Code/LocalizationFactor.cpp +++ b/doc/Code/LocalizationFactor.cpp @@ -8,7 +8,11 @@ public: Vector evaluateError(const Pose2& q, boost::optional H = boost::none) const { - if (H) (*H) = (Matrix(2,3)<< 1.0,0.0,0.0, 0.0,1.0,0.0).finished(); + const double cosTheta = cos(q.theta()); + const double sinTheta = sin(q.theta()); + if (H) (*H) = (gtsam::Matrix(2, 3) << + cosTheta, -sinTheta, 0.0, + sinTheta, cosTheta, 0.0).finished(); return (Vector(2) << q.x() - mx_, q.y() - my_).finished(); } }; diff --git a/doc/gtsam.lyx b/doc/gtsam.lyx index 29be8dbe4..a5adc2b60 100644 --- a/doc/gtsam.lyx +++ b/doc/gtsam.lyx @@ -1,7 +1,9 @@ -#LyX 2.1 created this file. For more info see http://www.lyx.org/ -\lyxformat 474 +#LyX 2.2 created this file. For more info see http://www.lyx.org/ +\lyxformat 508 \begin_document \begin_header +\save_transient_properties true +\origin unavailable \textclass article \begin_preamble \usepackage{times} @@ -50,16 +52,16 @@ \language_package default \inputencoding auto \fontencoding T1 -\font_roman ae -\font_sans default -\font_typewriter default -\font_math auto +\font_roman "ae" "default" +\font_sans "default" "default" +\font_typewriter "default" "default" +\font_math "auto" "auto" \font_default_family rmdefault \use_non_tex_fonts false \font_sc false \font_osf false -\font_sf_scale 100 -\font_tt_scale 100 +\font_sf_scale 100 100 +\font_tt_scale 100 100 \graphics default \default_output_format default \output_sync 0 @@ -1061,7 +1063,7 @@ noindent \begin_layout Subsection \begin_inset CommandInset label LatexCommand label -name "sub:Full-Posterior-Inference" +name "subsec:Full-Posterior-Inference" \end_inset @@ -1272,7 +1274,7 @@ ing to odometry measurements. (see Section \begin_inset CommandInset ref LatexCommand ref -reference "sub:Full-Posterior-Inference" +reference "subsec:Full-Posterior-Inference" \end_inset @@ -1469,7 +1471,7 @@ GPS-like \begin_inset CommandInset include LatexCommand lstinputlisting filename "Code/LocalizationFactor.cpp" -lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},caption={Excerpt from examples/LocalizationExample.cpp},captionpos=b,frame=single,identifierstyle={\\bfseries},label={listing:LocalizationFactor},language={C++},numbers=left" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},captionpos=b,frame=single,identifierstyle={\\bfseries},language={C++},numbers=left,caption={Excerpt from examples/LocalizationExample.cpp},label={listing:LocalizationFactor}" \end_inset @@ -1590,15 +1592,15 @@ q_{y} \begin_inset Formula $2\times3$ \end_inset - matrix: + matrix in tangent space which is the same the as the rotation matrix: \end_layout \begin_layout Standard \begin_inset Formula \[ H=\left[\begin{array}{ccc} -1 & 0 & 0\\ -0 & 1 & 0 +\cos(q_{\theta}) & -\sin(q_{\theta}) & 0\\ +\sin(q_{\theta}) & \cos(q_{\theta}) & 0 \end{array}\right] \] @@ -1750,7 +1752,7 @@ global The marginals can be recovered exactly as in Section \begin_inset CommandInset ref LatexCommand ref -reference "sub:Full-Posterior-Inference" +reference "subsec:Full-Posterior-Inference" \end_inset @@ -1770,7 +1772,7 @@ filename "Code/LocalizationOutput5.txt" Comparing this with the covariance matrices in Section \begin_inset CommandInset ref LatexCommand ref -reference "sub:Full-Posterior-Inference" +reference "subsec:Full-Posterior-Inference" \end_inset diff --git a/doc/gtsam.pdf b/doc/gtsam.pdf index 240528179e0dc879c32e2bd2e7bfca6612f972c0..cd125a71352875ae3cdd164fd6acd0a3583034c7 100644 GIT binary patch delta 95407 zcmZs?b9g1ey1qRzC$=WZ#9py&+qP}3*iI(4ZQGgHwrz8Mv-jC&e`kN^{MA*f`>pj> zUwyrGcRf$f7BfaRGsa6^t*OUp2n0r=;+J zdx{%DVXv^cBMGb^q;ESwJ&3S3?|ftAllR^px|h3dctLoOVqR9%MZQIPkSEgLU(OUI z#8USj_XE#&vgJq46e?6sJ_I0muY+`uH8jJOX-M>qBc^M*U1aSXx3S8bY-Va88{Mjs zpSnnjUB!VsaU`=)(MfPE&m2KXb&x$H3bo-l^`$y!0o0*5+aPJcaClz#!7s+BmHrpy zgtYtXqil+?F$RUVY#?-(rJHIN^5H(iMyrB-V8aNCoLMUfAfEm65*ie8-r zv2Q}3rXdK>d37nlveJ zK@7hauE5Sj9Kas{gUn(rl6%8mZ<&IjxOQLT?)UmEQ+G^M!h%)jWyn~XViJDFh<7sO z)hT64-9mgz;+kwLl_bT~+A(D2NOQgdtyxS%G-0z{42?89X7SaStv zYRtTqHal2%1`8Z)O8>J2Fvx0^xV%< zWxQWbpz=~ZUWSdo=;c6~R?sU$)6~PWFv2pwoKv6*2$i~sdD(4MWL9-auW9G4H5Yqf zd|Jxqz4=xv!Bk>_X5WE|O?lpiumk-J0= z)T-cF`3PL3y`gaV%p!bfu^>LsDe<)DS)AeEpW}1E7X-=_*)+pkHp|q_hsA=-$J14? zma-`U+mOZ@Lk$IWPbQL#7C=aSLC1y(0pNPv6JNRQ!(wj@UpRp8OuXBZTxu4koIg!7 zLA*&cXM&a1U3#R)C5SZ38}zIrlD16@=kGt6@Rqh65V|{CP_{YsuUMm;WkJq@gB~c1 zFUhwS&9l0q9Zd{u{Mc7~R)4Lb1MFd(pryA8yN zycnJTZ1JP$ncLZz=(!r0IU3kH>p7a(+cn5yivKMu|GEw?aget5Z!d4>|Gf4$-8$NT z6dy(wM%I58pTu<`6ksDn0xPQX`l)F~-xConY;+YiTpei*iCMze8&Btn={RPzk#hq@ zKsZIjhj{jV)_@ZU4iq8?g07xE(8t5e!DUjIpWRSw)hAzR*GtjE|*<1~UzBhC2q<#`>*P7%^AX@nrN9NS{I+!xxz<%pJ1Zwy^=j?cL(X~ttlS;B~hhFKu= zVj!97k)3jCJ&(po35QpvZwbG?1NsUkejfzp3~@`&N%5(3Izgyc*?=limV2y>3uPw5 z@kt*71?)S8Krphh--O0mj2q5Pa6KSe>HBn3j| ze}aMVv5LWxNm~dfU9FYZgyxvTB+Hvxt{A@RoXrT8RoW*=^tCxabwD)HhzqfjRA?dFyaHA;Pmsr{Em1MU}C^ zw068V0wkLw=0}-FOL{rT*`vgNw>w%jK(;IJNcJgV@NAg|Au8ijQj2pEHl~wLLvgH8!(Q_G$&?pE>kYNyI3Za;6Vf z$Db7?+1=w}v`(vji$cu*eu_`CfmJb`O+rjuIXq_R?*)Q`e=KqugqX>wc+JG_&yahS z131sP9o81?TXUj2RyZX?DNz!FpC*y*1NM8QNUpBE@RjRJNiynr=WsqZhnXP`%Yn!{ zr&NveY6Xi21MbkuuI+I<9dQ}-4qc_0O73QDD%U#?z=IoIwcWz^i%$35S6ghPV(c3R zxIEGbJUYY1R(?f3I^$plM+SAeU@55oFet$kd^bcNfZS}<@IH%2IRR}ZttWab0ABci zKs?O|tTKlkBl(WiBF6faye*r9vbh-=;<>D249vL(`O7U?Mz$HSUHq_aj zcXMQ{8ubD;7k|j(Uare7`u6&Em3?{^yumo0&1;Ft@^pa+G+Iwv zBWfKe71p}dy8Z^0nlxQyq`O3b2fB^3QxO)c_wR!~n#9MkD4fCsq#k{9)=ALSV>v<%*&%hjXVuvPpCd|p)JWeMmytsiqKj(nuaR&lH19+4{< zOZ+H^Zk*3OWcZ}YqB_6T%KIZ)tq@%wpPvd2R$oRYkN~?P1U9Vyu1xmm0et2{Fuj3x zloLl&xiQD3+l>{7WKajUBMLwJCf@&zpKv#!LZ%YvRRH2K-od41JIIg=d5S6UA zsIhNbLa2p04wl?``JhSmv1Gi`bs>y`ADm3H24dFXrD5(#j8Kr zuJ8<||GK}`7gD1g(Br$kHZK&cG-v?LJ~YK%KEic%H6$VaGL<`9{F3YU+v#9}qGQ3B zl#09gw%&Of9TE$?!(*IW3C}72FZs6BC%9~z#9RqnketL$34Y+VTRFXHLxabH6G%_Y zQd~{;v_Xd&xEbj56q}9s%5?DOEu!NJ=j6CkSeR`6R3FwrrBcY`2$e%;iZ57x(S8UX zn?ur5t7))-p^Kq8ieB7a(fKlEnzmi+KE_J75U)gBARq)r(O$SoF5uucK)RtY>=Lt! z;1&k*wzN8(*9&-*?mWw2={R+rctRvqz)LZOWEz?$yjhqk=E41Lq;f>d^2geAy#+!@ ze@eLO#Lm?!LE^WyoYH}On1Sa3zeY=heGUetP?EPQEo(lXPBhEUEi%OM(i4yX=a`Uo zn=~Hz{zC8W(H%)LR$Xm*1A~FDo z(N+knjr)d3J+MeE?=6^m)$QaxYT)^rnnk-*rMs2=xGC(A8qZ6~6(0XL9-s(QXzx<* zf8o-IKh-2S4{UB_<5q+|66TDj^pP}{^#1TpAcQi4M>Q5l?&BRKe{dJ@1>{*29c9f@ z?jr$0LJO4k0$&mvIk1dUSs|>)SB|lRF25^4zykho32!3j&#eug#v%P$0pBGFffvRa zMw}8j|1u`u9npF>iTJKc zuip7RL3HS7UaxAjf2T)GpCh_9!CXJOA_{l|KO~7j7{(G+6h$Ii3}wA#lYokAbX2{7 zBc~J!xIyJD#|?_BCHGb4D}MHmJtLRS1vL08o_yWqIzej57gEx|Gj5+{uF6Tw;++$I z!9P{R0_WNFUI$2?J(@Q-RTZ>9=dIpfDh9c5}$ zh#e^rB!L5Zg7gDeLs_J=IOYwiuL5gnU1hBYx|-ab3e#(6Ym9=$2&ywjx*O__$}QoH z-jfhmLKjS4{J_9il)B8 zBjsiaH8*Y;m1f5*_%UWUz$~ph!2z~DBTl*ayo<`c2LuU&nhi??!9ay({}=N8i{W4s z|Hw3hz^3%Ef&O0*mohN}g5N+UHvkR-+i<4j4g2?CraSbP6&q;H@&9p8-yT0I!~e#|{~GPcTLj`ixsaXXzqk;%iE9ek&p*Wdz<7{INu|gFXJv&O6h^ z8lQG%R*xY~m^?`tJY6*?sluQKA&i&;8YE`L&cMY;W98h1XLoMIbgS)PrS`ECm1zsG z2tS&MD{~?|b#rJvL&i|=AkAjenX6*#a);_Q3^0kp*6wPR+)+Q)(hOuFcgLWw=&Vgl z&S<4M=F{us0Fs(R*_AU8XMR(GJnS)baQI_M0MoKWbAn6-j*?e;yj?wixOSCli|OfE zs}K5YCRyxtq)YP!fPm1EDnbsT(P8n1pcw!wV}uC( z?9lLs`*9&*XrlB2+Mk;hSdhpdMhZw71Or09=@JVj{h~J{$yc2wV*e%#4m+ss_#ONy z+Fd>J*0GzAG1JERXOsI`Nxf}*u7Hm{6#M{%a()eu&SW^J6Nnv(=%Y6EK#9JjJc)bP z1!SC|b#udHkqz?}Jo5}MZ7ea6207(>KX7cG@s(1K6gQFun;&=Z7o19s`<1mgX7M+P z^6j4S@gM~LJVI0jp%1tF;6eAN>j6(1G(+}uGT;`&$AO&UpoB3@e)pXi2XWHUhkDre%jJzA*4bU4J3u~~M8m|ya6lj>{NUkf3)%`?jVb#6)+tdUAI&frh(x>k@{$-v{Jq z^l=4rUt~0lJ_(O^(&b~8|gK5Qi(Zx<>H|a6fQaP<=@GeL$0DYrP1DY&zo=(Cw&n!f^)vq z%12303Hv=8RG^J_cB+%Ba2qou0g_6}Dfu~(kpA8_Vw`&fb7LPDzx3{=nJ{yedF%W>k+*534rBXx8gY!mDQz1K`!N)_OIq*^O3)}J6UBFeJs9cG$Ti~r zLS#M0D00^PHMI>lAPku|lMaxQFKgKKH`gU#7)ODpgf#A#8$5dD=r$dRiGq`>^o#1K&=QW({?1>-U!KQRd*}@HfbI#wz zq9l*8WI+)^FzMMoi=Cd;lXbTDxftBt792q@;E~_xdDU) z-35a?yjbGdMr+f3=g=YLS#ee+^)u6M+igt^?C97^8=DVZtcM@iZL+xOXhUk4;_*po zU>0tC1aEg#8<1;IX}5Nr7hg%xDCW~D^_{eK0V-jF>0PS4`7UjQMKX79v}&mewh#Tr z;t|j5Xmu#m4E>&&kDRetok$$6qXDd67r#K?JEPKLD*#8Vmg`3YqeR(GD-{#EJ~sow0<6g!t$^h?me-|| zVO2p(d)|EZPf;KxB^N6Z>9J}TY+YT+F3&DuUnUuxK0@5IK8yM*L3NKH#527* z*G!~r0^z^A%au7=wJz0FhyZ(}tt+Mn2n}Vmds=H`w2eGq*%qj)L(R-0;8TfU$lD1r zm>08!^oYGkpA4SCb2NKhig=vIUAouVX(9{P&{zHNXp&_1G4;b5%@}HR*TT!m;gRu6 z<<7>@6p6N(D9++|%J|MQdtkxJsOgh7L;8`SN!rRw4DOKTK<{wiw}5#}w?p3qkt8CT zgG@h>VqD|Mkw`_u_7KAZX1cO|BCBTcqa$7#c}6SXuwOwy=ux1#iJ?FJ(GaL@Y6IWU zx3xx$!lD+i3@s50V-;KT>#TMGsf(sHsITrvOd&<+n~ivvkp z#dbByPOdQ#(!6AWC5K1a;g!u$qLnZp~-I6H+X)&Q>a^RkFC=M%7My;oRz0cXVM zd~B16g@~vVQMbTj^1LKeQ5Z2VV*w`)k7aM5p{8}oeSVrZ?_J&0!F}`KbDE0>O3@Cq zTXiBui*GiibxC!lO&*{oV1UurBt;2$z+ULUy0|Jjr_nG%i2xqJX0ouW`?OP)CK3Pv?YG56poD)w?H&i{IV zqme^Y2{(ot_zH&A7Cm%71|M$ETG0ef){HgBG_|@_FL5Yh`=jrDqFUpvXje4FFM*U- zO7OA>GR4ID?E{(K#C4D$XR-wB-&56OEeuNkq%fX+DMHd`&iWy<6T!VTd8x2y(d^HO zW2(eJFgz7wKrtkwy*V&AF@cmsnQW(@XE(|3qB=d|A1ve$UHRfARP}Y@p|>P?1l-aSUC6|SA$c+ z$(;o70;BRpAFkKi&H0&-meLBwSHI>QH=Cz<5RPZ$gyxp*k44l)j8rnJwLE z%(*py|?oY{~-mo;r+%ZqJ;E2Q+xF+#}OjS0uNYW!j3Y)S!-=e|-KxQ%T zgTp3B@=cb4ehzlP2v0^u^Wogmrrg;ZF~haNh#Kb+*2mu@4cuqkaR9}CHaB!|QzuV~ zTe`Zcpo_4i5QVj9E2t&bu!*>`w;+WKsk)VBbLE9{4m`-(+HvHl`|n7f5eUoN*rtB> z3UHZQdZh& z=7y=?zdT67X{yrSqrg4pW3j_MvO!~*1^ghXnB*aR!_b*l$mM1a4t+Ysq;F1uLmfOj z_|0+m*yM|h5krbGEaz>NtFc?E`UAhA2FnFa`)`u83WC#ag@E`FI#7ZzroX!)zP4~3 z!(a*iZly3XV2=~;*dymF3~n8z-DP|U3CTjipO4$jt6Ev=0+HJ4|=JokdA)>705 zxt_xRItP=3)Y0>O!e*JXTvb>cwUqG%&A!X`^EfY@#5rpv1NSti{y;Q4)#jf7BleUY zBkht)?v8hz*aw0;^>H0RQSf*D$<9`Dsc&;dIJ~GBZ_t~XA$BJWfEEmh^N(qAYCnCu zn3UsI@9(Gqn^Lw8#1(4``EgOoB7oe<`@W1t1R7dsG#;dYNHpW_>!*K^C^|xjzy;72 zgVo~>1i=@X;0!yy2v`@RPHmhWfZl1$XYbC5EC2}eV*#%Ns~?|v=ljw9-5DOkG@w<> zZJ^b+zB1)58<_0x7?9cRUux9)Zf@UGzCjh6^zjqR#D|^AyXfu?MgEM-7DeyW5Z3Q1 z{UQ(8N|x|(qq=cPW?tuX(%lhO(!T6mPJ|LncO|xs`0#P1x=7jX`ubH_PbF7;BH}=G z^3*;hO9sT{_KkM2XY3aa3EpAPImC_~W}jlh31isgP>xZ3*dso8e(SCu%ec@A`wX7` z8Dfi~hyr%uKIfD(A3IApdNtqCb2K`JZ-bb}Y|M7%P+CiFQJu)C_0?%X1atDa$rrZ{ z<4i=O^egU69WI$8jTNi>E|GqQ#X?E!j`!i?}go~Im~dpF6Z!;p{?sjXxI z+dq83A#S_LUjYMgL?vh+^)kG?_#sD{~0&H%6`cw@7L`oyaecJ03M| zx`ER%D_7lzFiU@`%hR6}bP3#S&JTQ^m_$-2#jpniD#hLhesX{M37iJRlt1e~HUj%u zt};=6G$WYR;gM{{`Y^mi`@F9#%bZbNq{a;0Cq0@+?Ki6Q-L>@)!2{=)<%(AoN3u**RlLN;aVxWQ#4E;jS@p4$7 zD?SG!Ofy;=bshG=G!^slLhxcCvLv>8ySw5`yWxTRS3wxw_cPYXvuJvIoyAQP4_3_G z3)a2_o%_8EDw&86zH0qPbeDSP2JBVqS_b5)u$GhNjznPaBdrA#lN1wNoqg%T1(2-Z zxUmB~MF#{K=gL_0dil!x$dfu&?VzY65$I$suj4L) zAf1&mMWTyj%_Ibj@4&W5hL3#7-o5swJLW7PW>(y7+1Cj$kkMnBpJ~WEUtc3$MLynG zOkHxKK!OrL@cErGBECAW@PBhCK1p6Q6b5 zX6%Vb(g`D2IWe@Lqdudf-W$1}==_FS7^$@F)YgwVi#RImpj%eqyxl}|dkAS&m#qb< zF-X}UgEyAUb|QGEngy3LfF@t(`luKvH^_SEr-=UCDTbV&BCAB*12ReR#YCVDA z!WMi#JUr(EO4YQu7ac)+quF<5P|>ef+72VRxc*w)uQqV`jgH4t(8#@B7rAaYT$E2i zoNWJnE-Xtn`f1$oAx2E$`U5XuN!z~!3#xk8brp%&M^D_@#W9sH&q9fTX0l6voSRz5 z0{?YAxr{z~AhE&;#3Qk$1qfm7rfP$WQY#QvT-9=wfedxALQ z%j`K4n1x!w8ZbocTV9VdPaU$4-2-oq&9MrcrfpYV*66ZI?A&^AhQqlLx!+QeIc1rBB`dW?)$pghW~ zq@m6lAENaRFyN`m%5310G2e1-vkaR^pNMY+*t?BccC9O@@#kFnjV&!3(_&^l{`ZbszmbetSZ?=RqiGMLc7W34Q(=(Q<}NxK^nZ{qC$Q? zA(9OZPfgn_6=8=I1{5!~JWk8Cn;`3~u$*y!11}UH-SvDri_rb0a_-+1Xg@nSRB2O3 zl70?;DBLUrj#lgR;D)Ai+fg3wLUJ<1;pwIH5cND4xR8?Sm*lcsmk@mruX&5 zw~}v+U)P%OVQ;jv0sSZUJ?0?6(Z;sf_m`G?%J|PzG%aI{(Gw>QYs$Cx9o;Ryn9@Ox zPor)`f4&I}LEyWw9s`729f^a58l@o9L{jZ-9NT=u^3qXwYU2}4L<<3 ze;IzVR3~c+Sdn^;YjzaF#c^wF7GZY)7b_PMtlhTD+Vb*OfOLIrLAto*_94^snf!SqE4$K9nEcL-I@b)|Q+>R9l(8>BJN z22e4>97cYqvBJL#9qm~g>b99mqf?Sm#o^&Q- znn2KxB#w4XXdt2eJ>gc(BV@dZ3}2+dZ7bqk4#lZ`ev9^-JQ5eeV+9ty$F?X!h*un# z%VMOL;!0T7{`1UCE2il@j3Ui5bnEN|CrJ|Z01|g1mYiveNcUU851GyA7JC`{77NZA z-iRrG`|RQ9^O)w5u87z!A+{Q@ItDB^>{EODlxiIDDRBR#^xe7jC07CS@C%q?8v4s3 zKmk5hl1ThuPP;*4aX_mg?<;)3v?3Ys2k;YKic@d1e;oovUutN7=`q>0x}>R2Xy+FK zzh@xFPytlm-R#CGIh7C2a$Q1jV z84Rk0`MOzkt3RIr@`qyEQp_jq!T5ug!r(|d)8x*+2T~{+hm!VJEPH*;NFBo)1;S7e zq;Yl~=n_ZVfEFQN+Z^-bb_fm_CEp+F)KkZ+ceT>NbtwAO-vfm1<*}H0JTo+BU@@8A ztBZ3jDmyjzM-pB5bd&6n-4E5kE~S1;SEA4ELJ527-0rbiOzVhC(<$<`H^pF=Qw_n$ z({i?RJ0%%v^aKd?Nn#-o#QMhm!22Mm^)ePy?qF2+U!xY$#ivA0!}C%6d;$Yfl>3P` zQ(!jVX`|sP&qs;Fq(5#1$E+?pt|Uul5oIBAAjD7+n zsnmnmvbMpBTL>`Sc)qS?@v3G^K(Bsu z(Fkj|R8?7GO;1K+9l`4WcaAygg)A^piQ}?4Qg(?WI3(rNw1cvB#%i*`4_=%>!9oEF zUxS=YOPGp%$7;|x@HK5Sc@TcVgmZ!1VbNPC4p8CXf3gkpJAQVG_z+H&4WM#kZtiST zat79CxSAl=Aa*_fG1>!;=V)F2H#y1NklJ55rxB;DldjiHbX`58QLB#<`WcK%;R|a}VW@cHwPjFl!j;t)jS} zgRm#+w^Hai+_lUEhlm!T>y~#Sf=;Rw-+#(A;MCN*EO}bG>K+H<>k^oSs%%u>_LE^ki{I?TzW2Z!Oe4}lfK~E=(O*2 z^5;Y@6l4d4lmj(p%kwztf`?8xtT7Zd2s-^;yRN_TjbP_pV9aiYX})nGoG(8b`55+X zYLx0Jpv3MD%7Uq>x}COLbRW7Z#W`*Vj%Ub(GH) zT=)*Hi?3Bx%Z0;3w)YD#`(vO}q1o7qScVvfO_novOHo!dD5qI~_Y3wpV}3aE_sHav zx3cRc)pJ7;zEQ^)Oa?D#dw17a4kHaVLo$ z5dgbt-MouS>+@N7hh==(qWZ-xjORI$^WoBNpSfJg?91`My0 zyO)lqjh&s-gqRQyKxbiJ2ThD4{vw?~(V7ZnC&ZhE66N5|n#WFae(|w5zntiX$+zwc zPAZt{%bq$1Eu!6S8`c_AGv>&XrU>*OF!RvRQ$a-uO{1oWY%fz(VQvaE76?F*Fo_h8 zO9~h1Yz@+l`dzD9;gY=={i*mZ9wRzEj=@G*V`a|KV19v2)I3p3?J$&E>l6{Wygg&o zR6PRQ&;foR!vN~2i(kR7Cqv)=UDj8V)E0HsU z|FOiS+O&Mu$R8A3AZn;jIU~r4Yk~?Qn2}&z)THU5O4jyDduL`*+uO+ZE zVS6BC&M1t{PZYYvAXs^f6G9-hbv%{n;aE9kzCjkci^giYN-}5)<7P)QDbUbAM^6Pk z&fsn2P&kN9#?-1(J&r>{#n#!|$sCSi808JQsx&N=T%+npgNNky(InYob4WpbYFuSW znGKb)afqYHK*PA&)MZN7}QA7AI6v$gPX zaNs8l1Vce0RG$FD5D9Zao=}AX{>WWXZXZNzn$+o=J*9%pPJ!y_*MnPQP2>E1iczdH z-m*-Vpf9YB#t=^^n0Y3H-dMZ2@*Ugk?wOP!A^;$F7b=8P3> zR_2z0+nHY0n-Se_JpGjwBC~ls44E1nvn`(L)ahAY7dKWmi4l>m4~N>~#T!aZlgwhZrn3jQpMDw(7i>%b^cfd z5LIG0BVptRzTlvDWTRP%FGfhmdq4=AtCT4>e+xh=ly{;>4FZr8ojt5?k(8}k78$cL zT4*atq&kA8O7{Dtu4aJ5hT~)iVAK_uoXZ}e>34l~KoHFyfx;UUU4mcmmb?M zmc4dGlSff0E@PmCdT827|MHKk=0Xx^a_daeF2Dy3B}9Pz##GRznZy_psor7&?qe*Q z$w-7#lXlVLH>83vQT#Xr6R2GM(Tj^WuVS8z?*e^a)SmMCaYEynmw2=OHD5g=tGmtv zD1aE^zp0}6^NZ_mWve{9K6PLS!YbOW_`9kTWlc{vG6Am&Ls-E$@c08!=`wTH8_0sV zolE403#+i#m2n-R^+J7d4L3U+AMlN!m{OZl@kZe7;Q37beh#kKWbfUtd^|-#gHJI$ zlwx}ry-bEV3fFd|#DB8m3Fr-iWvPzqzu&W6!f?0EqsGK=$30o0cd`_EbLQ}&IlJ9? z6Mh84WCG7NEBjDpNw7z7{tmpcljpQ zKh; zF)#USF4qXLF*}OuY5`G&E!=_FJLZsv)Q&PD>thyB2eStSrMuyq43w8*!nzEU9}e#e z_qTR;PorIy9?<5Wce{DDEd!5(o7Fq^?Amp+FuU3vW7Ngjo$gE}%Iv~b^g z*n$=k1y<1#=_;WA2l0?MaD%WU!et62`pBXrwlxq!bNqh0mxui)voZbmOXt5WK)L<=ARLLi{SJv=?NI-sH}?NcZ;90dLZHkHf0JQP@w)=S z0c8dx#uuT3GBY;l4pu`Z5;LJD{ut*2^1rN2uv;Wp;2vLDKI_g&Llx_%sl_XcQ-!}T zZwGv%P%QRkC^uUh=OGD#*xA3@Ti5Yh`D>&!xH+P6p2lP|JFcOGV-QUMplobF1c2j- ziAy4HOawkBLdT!NhZ?ZIiv2o@JdLWgSKPK*Z*9+%WNq{CdhP%EOzB)Y%#wTnJ`7Ci zfuuvCNXWJdAOvFfg*jRH(;I|9lS`?{I&f=X@%xi6zBSJ^T~b|L%y)n1+}_aE(_P)Z zTJlgV5vfkL_|*48{k7h$Ws^fC;jD7nc3FKrZrIh@qLU-lq`8`HpFo2SUvW{}QU7}* zwXs{ysUQq_bA=?L@+6mKc%}Rj_;?@=i-XJaGa_Fc9L-_k(w$rXdxY^sfQA`bJz3{% za~E~;xS=E#^xkDQn$vPwNvcdYNxSyqQ)r`SCv#Pt>)42ktBI6t zpO(*d=9cLe3ze3+8@Phy)ryRUSTihZG)VRxKm-5=D^?!*NW8w``A5G#5Wz=ZMA!t+ z+g8-{CYBf{QXgA8=W{`9Clxe+A6&W#s&5MM2NAU6f;EhB6jZTTW_k=Nco@5w1DHbu zIt~{jmh7P~IQ*Stn^wdu7JDt$9|Z4nJ38f=ZySUmhaiwl;aE4BbyMl2-zgT=DzBQPE(+bN z{t-g{sZpPm*KSNHj)OnF(}%>2q8i-6A@x;}9XtEfOf-|OBO2$xoQ zIByATkw7Ko%n>Ak78fMZ!$wha6bUE}N5s_U7HGt&k$yurG?)U<(>=J$ z5eKr%Zv)V|@dL3CHs;^%Ap(>MrdLm%rVi!SR-|*eH!C7 zudlZtoa^z{Vzwy=8)uXfFTmj@Ud-Lu993wn>AUMVNMxNFOkn9Sx{j1WY zo6kiGDay9w$`pT8KBfp%@D4!PSx^N+x-Q|(IRM~xJ9Gqzux^I!=)9cuLMXibjUOXR zyk#EcFlYoYoXFbVvx{)g{`n9dW@gRNh%w35GL>P-K4lYQ!LKYxcDf|_pdygjLiCw= zvFGe&^sZ+FY~=CI7Cxy%+JC_lxxuK2`6xb-#=pg znxE}_rUMlda~^wW_dw;@c54xhpIYfraWk9#Ow!~}z1s_w7OjiRR@~Fu<>4arJKUIO zA*?Ad-ddOECz?Uu=b>5E=V4cQOZ6>R%X2j=KW#()-6N<|*0M!@^0c>}&-K|)8u3%I ziss#!ogNLRRw{ICViO6b^(W+iDZu8q3B@AxVM$4#gU?;x2*4Q=)kYCKCVtByVyVN%se z%CDCCTZd@xs?b}PErXvdxEuDSq47ju-eIG+%cRw)f2E$Gj}@wYw&b`b7l5{<<6;Ol9>#P(ofKAm4msR`Y;&OkT?unL?5 zRj1P&k?yZGJhzaUpN3P00*qu4@p~+?veSHkpA9 z>02n>u?`h)Nq6X%&l=9;r3&YveR|m{@tZvhDh-omRY@)Xby?!_Nk`O!*U;Yq+iG5^ zTvhF{aS`I-5%dGD6AoglD5jx|!zm+J5e`|ZQ4jF7@>5}Uz}T~E9y`ErSIap&Y?FPg zFh$r{d|9oqrTfSbhj4JTZK>X+7hF+>bZiKdf2-zCKM%;EZuz!p{}fMN zO@ahgj!|a&{kkOy93DfbV08@zniV}_Xzns97$MUb22uKlY`(6GG-|-CUiNPZXCFC< zFAUQ|Du>R9J4i*RWISF`BYx!Vxr5rA{rpj9!4-bJ@+3$T%uF!EL%y0vD1@sXdemYz?36hP$M~ zwwgUC2#CSnM&yV~2svoLeHXgJ2TkO?DRe1MuF-#nLEbp}^r_{mIMh@V5+8yk>|H2o zc(jdbc}twKb7^Z;JRD&Ons^I!y_y1Jb=QeP^zrJ8`q{lY{NBZuSrS}p5X!F}Plm!8 zy63Aydx0n%W}{<+ma)^Ik9}AXlF_B5V(scM$-Cs?7tMmN#y~LR+V+{7wR>j-+Sd5n zH0`d#`WT<NX_cJ9xN!!eELI zBM3PVoHPLTdr%-Ysd(7nUgzecF*^(Qr6T>6}3 zZ{)-$WbYYeqXpX5iGd9+wS0;dRJ}O$@|fkjR^9??@1a&Z)+! zhq;e%eAYDJms%=Off5rBPL=fl45(SunfJKPe>r_tjX5~@DXX1o+6~C5U9us8hRly+8 zjWy`))&$#`n9{yjBW`M1ij6YsrxF1L%N8e8n%8i~?kS|Zb0*knQuCNM?Cun;vKneT zo8-_$=ES820@xgpv`I_cZ5EL12}2(1q8lhF?$L*hPLhV058w)ra+V?Vwb7bPQ{=$VYS;{MV~yXLZ9 zHJTiFvyw!`kw+%NCigVh2KM%$_=2(gtyVi*;?=u3L}dGfh}Hf-@xcYubECl`UyuSW zV{-@xot3Y_Gg~fB31EtW?1t3e;*rF0!i*aAAE3cW?ijxL?~;w)2i^n|PDTAeZLCV+ zItLdcHE?Lel|xFAWC6kXi6UO>a?`t}p|lT`DfF2E6<6}2K9lwh@hg$Vf+1h2%Rr?l zC6wjwlT9oUdyoJ3y?^Q_aTxg^4$tMp$w$P#*(X>~<7rilyR~uiwK#D&aed^(mjP+J zJd#(K>JBS)atbSB>$jN-U-FGUA9Ob>vA_@KcVKte{iXfDzt2y;0d-Q1>xz`jCf>k-#yz+W? zpK~!^ljU5-fx%vaaIf}|!rW9P`k%$M7>g2t$jVlfIKG7pfL}Nh)f_h=$4-^aabCdoG(Q3f8!q;!i{%QQa z#X}HBZ}vy+% zqR3}6>VG!~7A+o@*rc0Hs`-ff10O+9!?CWF*>9aG;P5l(;HR2AY}Iw}n5ZTzp8kC6 z(N?*p@bxf?I#7#Zz??}Wj@oRo2|z@d_Jmviqs=iT?c_oGJd>K?oHS~Y5S%`w+ptFn+CzgQc%aq6%VxN27~ zSZS`8e7WbV3?N;sdpZDXX@VUKh50~Q?#tQp(s}F`Kv$lxHk4`spH+>%8oDwI;SxK0 zU=kZ*&%;!^=W>8Pw~9v!OI>`cVKbj&oOAOAb@BjsZPJu1DI)uspUL_rHW$N2M0j_< zH@_usmcsOh9e$#WK<&K=59S8zL4qLQ@nFxp?WxTWet-Ts;m0{6NI%9W4Qn>A6JZ`M zcL*}Fa7)Cz2*?!rRx~YV;ICWqWnMsNv{5NTpp(~#)2$6;#0wyU9~o|4{Q$EpcjEik z_Q>`3?)mo?2%6^whyb`j7<>RHIIe%9N`Dg7K~sEy{}~qo?eYN>0X+ZBLvZo_i-+K5 zY0lsWbOioMj)L<*BnEkO0+7JDx&KQhX`t(}#)Ia+RNa%W&X0-&PI08Dm~1*8K^?~4 zl-RnfCQ3o^FOekggTR@?mc80{8(G7(x(=5RSz2&_>#cY`GOQv?5KCXgCE66+Qjnum z$Twv2*rWjy2{};$r6jch)PY4N4wOp2U7DPoiUZHzj1gDYYcS5g9|BNt5P-cAkV8l_ zV8l!YP>66I1})Iul{>5b4%;wys~|?0Bfqa9w!{Il#-oD7C@7=?aWo*<<38>M`7QD) zlD>N|yarpOC0P9Dc1PPK7d<&~Y-A~th+>0m8ASo&As7@+E2Ka=MjYxa@dk)TC@noX z7(Vp#AdT&mRfyUE#|HNeETG6wp>;%x9T%{CPTxH!@-7JOd#G#7V4zAxy0}$*7?=ni zG#y7B1f0w<00AXNqtEV1XOESbM?{p}7%sCguEXRDhPWPdW>NsZGqm=Yst!z_8qowY zj44g;n~72mr1+n|$Hnw!Ft8-wRFSD2q^e*>0_r}e8pt_!N_uJ(dEkLyO}6QQ`ECd) zVVL)lI3H=v{%&{;(*9}?D_W{YDpqXSHY))S*)3!fkH{r2kEz5?YY9@0;W~CWSdvr? zT78dA$})^Aj2sPv3M;8GlO915d)k=L@(84JlUY z=N%ahb`{Yb8Vv=gS0Dj)QBZz5Z`NU>NSz9ug=QI^xCV(WsRgZF45h}L8URxcQB$2R z)D1it-3n|`)jPaL5bZ zYnk9{eTAo0|44@d^QZ$No$g%;;5?1`!v`{x|^{{9aYkc3JQFDzyF z;$poGN23i!NkEX!sNP-Ss2wevx9jWia6b13U(65}(EmrQ;#}Sag-kyUE}Az^A5Y%y z$=Nzl(l3aYTxkRD(ZKp16h%02>3B)>A5hX-=uhZ~ z!M!l+ichN1$;1s(zlHce6OM6$B2RtTn@(rVP6KhJS#uciWmdqhkWASpA}ZQC7%(FQ zu(t)X<)cH0`dN;gP|i(Ec4>|%`j`7;tYHpwNU}_C;b;R;svjoy8)LrZ=M_N01uO`m zPL|D`)&VuZBTW%{S2Cy3J+rVpl{E1W${8}10+1Fc*=2=9?U1Uru~h0EnDcswy1jX^ zC#I#}w(L}Jw{~y@@9n5O9GKR_NusYz;RV%(NhBfam(o9ClErr|DU#?69O4!snz{|Toc$iQ! zrH&gv9eav>zzc2`?wrRUe4rajB);BGJsny}G@49yfRw80)Vv_gA_+2B;1v|wv{QZ* z1Os>JjiGMlOTZY{d07A~UZF(ApQ2NKC_dJCx~YLd){G%v!WtdIAmuSIKS)7;MQOOH zOf#S%j%J0AQpGj9mX4LWUccA&eEvGxd5vkNZOBQFV6>-&<#>LS)HP|hxP8K>Zx~!| z+^F}m{%OQwJfMS8gsB@JCGsl(wy6CZ>;TXic}MWI`fh2#rctd}zzLa_XIyP&TrIv_ zEtNY6IT{)w>H-e&l3QBEQ7f?Ufh~M8)jzE$^wSHgV$ojLkz;%vm^jE5Tg zH#Ph3H77r$kF0HuuTA-B%G7LdF$xe_sf3FYJ=5n&2;)8x8YoI}iQ22;%?WTlg}(z$ z>XV8h3I~^xu<|GL_`sG#U}i%LygqE{ezK28Lg#Z3&yih4VRtak-?|Dfk9@o(glCA4Sp{>8@5tXIfO*36Mn}~R z*=gJBSO=cZDiy|4Uk=R>@@T^AjQM~?^N^-CLL^mItS@N5Nt< zqCdnmj3&%KDV1bc<%$mmvLLA-c0LuW>N^9OR0-V< zn_nBhWEm_vB@vFRLHQx=wGlCu72)DC#fbbV58TridN%JO9fE zWwc1XQ;3@d(tLFeSxH^VH`bYX;=qP)@5o}8Mx4Il~PqUdg8()YmMDHM}gj_)pC-YrVw{cyIuA1*^ zDw%RF{Ft#yitK!g6|Puw$J=cQ?rp9PNTr`qJ?MAsV_MpC_$rUmFW9yVjSCYTFUUE)L^x5PwE{=ocE3AHA^Fi6z{C_ zq|pV_k7gy}sJuC5^Z)(Ta5j;k{Y8S=mycPW{rk*|Rd+ADxQ-?lCcnJj6%{zDro4%t z7K3OGQ{J4xDv0Z)FDeTX4S?+t&$f4usKagg@1J;$im|x}fwlTXwbV_o)_u=U)iHHh zNVbQHrzdnUkYZIx?`u-tU(}~ggOuDvD zZ^avjDi6a3glR2Xe$G(u*&frWA|arwUPbbulS?; z9Ni`9MjDeq=CWVdnzvD9D{;2}m!JP~{Tg}fm&|VIhXYr!|Mrg5u9^R?32&eidj>=R zabw|m`2nNd*2-Ay`?IT(pj)kfdskQfM^8REX9QzNTdB@nq|Q2H)Irmklp?V`u7P4W z@)VT4b6;}lB6-ymkn4shvmzY&!I}4w)M3)ECyYJ&)U7m5Z;kBsy2|Cb>Gp=-nXhg? zlU7Q&aK-DLkXIpy>nWtXn}gIagWv9_Rux6IM{FS6CD8vTl{AVkm?#^?qF19qokLx< zsu+*MI9G;IXRWU39#nmq6R0ED+3GuL5X_SYVeL5PQw>lKh;q^`n^H7*VZr7%Ww7Od z&|LY^f9&*V*X%NP{#LO;WZcToy}A^E!#A3T5S;Z@Aa_vW?&asF)(g0u(k$1Q&k%yO9%isr!ZmYIm&oi60_(sd%LGP0S1EyQq({bF)7AP0>IMiyh&Jm7LkD3FI zmv>!p8pKF?Kyb`(|Dex%3(t4Hhp4Ne)lz^}f=qgw~jiyTE|6lLH?{h1>)Ura8 zhL+D5qtu_$DTz%fPO~9fUPu!fi-ooAV6FvD7U;7(H5=^tZ$TCI=KOK)DBQ&1E!R4u zOP9y#z56L52evx7xT(Nqwj9+(j3}t z1?8KQ-6fl}aif^^{khItdMvoOuWaf{$R#(plqD#<$(~T%{Se)@`$cnk-7w!rr6owV z`CHXNX#1i}+VvpYf+DA1Z{3t4s>z{O<_f5xst?&2-&#b?i{OLzerIlMVRS@-7}J)W z@QN+VNdj`>17N^$|HB?erf`e+X^lIdav^TK&^IJml7$wOEN$@47jpOgFJ1MC=?4*E3Ajgffh`WE(VE zM#0P@8H}_0`i*R8@j$t2N?0@6*FzC1e_h2l5tx@;0V3=642#JR^ON1}4sR3G_V#`q zkxv*KZ;kB*K)0R3XxEgWWcAig%9O!6BJCYGT#H@PCy_CSZ(6~me!^T$b?PouD_kml z!Ye~Nzx-wAngr@fGm#oHkfP`AGzPS7Nib&@QvBjEK8AAvb zb9()Dufa6TDR5}FIXYFhkb1?M!bFKHI%!XTn18ai1|C*H6)uU0CPRO=$7k=ask+71 za0h54B1FLG%dFc^THCfMKZ|#tQ?v0tz3 ztx1|m(8*r7#uRzCZQKx1*N|84tL99@|`q|sJ+jAtHee3GP7W4T+HEy$?E;O_0K4aCiHox@Kz0ieOmkZ%1 zvDdb(G_{4n=dV8Bwh7Rf6v-UtUnuA*^Y_`pw}7(bw{s;Uy9AiuX&3`4jpq;^v^R0B zXOufbr*a7#E`(#KOGsMTmebO_A6AuSiwS-dscL!Ffwd*ky3|aChj_h3hb|s6D3t7g zKaeBzkCU^LYzwrKZew`sn3jufeMMq8j!U#V@2*<6IYYJ#>6=qsxvPpKp(+wH8SEUK zm;q`=o23sCmHLTh7oiQX+<)ca=Kk?cinfEtJE+Q41QA$3exed@7WNG^}_!FqNNT53(smL;Wrl7pqhyuFlr61C-%dx0$ z{l|DLLF!aHu}Q))B~zsaVQTEjCQ1H?j+F=)Ndaj(0MB=Ty@cr+coq(5mD zBcP?4GD#!IdNXp9eG3FNAzZ6Uh>-N*aT4GGeb@m6vMFI~9~exzrGEM~1(s4B?ohz? zU8GUB1-=||_J@kb7{*y{&k!d%68bWl*KFB&9x0DkUP!%`C9z2daATG4PKR|6w*9$a zKhS1mDBPyeDl#E_UxGkA? z0sgIG`KvS{Jjm_mA7+UQ)btbJ4*QP{e~2aY|6AgM3(8#r&;z*tn_lAK0g)~PumHTx zJj(zaC>-9uNBK`hGAGZ!iKgcG4ZtUOM3YCLopIX-#K_%{$-ms^{aeP|Ja7nDhlIlb z9ls)*yDj`XT*UkTYjQx>XMe2b{fiG10Xd%o*kJz-DE+JO4?64ro}rWrfFuMP%Rl-Y z+&`Va1UeXhKG~YnQh^Ph|aho+E0y}k(OpfgtR|IjLd(7C|{ z06ZWSZg87_Cho7N|Ie5d2$Kg~;*X_zJm5;;tSq219&mhQ)_-Y|;F+aeSV`De*_s!4 zz_kys{&w;|=Z%%CS(FIk8$2A_-;`kU3=M=I9GqFk$U8&}%(MHyY=iqp2L8|T$zp>L z24`dY6EzbDk+DNC{o~xfXNdiO&k(4B9YO@a4mxLtu%!KKKGoobgqU@dO}|)}xsv>4 zm8{(#d)fZ7Q|+$~+n){>$d?0R1n>W{{ogVyP&^+159G-SK@ZN(5?06w(Ok$0DO85{ zcR21pz5TaV>z_OD(Aaq4nZ+HxIykF4nwVLTu(7j%{*1ua?6(c+0FK4}_gnEl#%LBH zf(U~Ltv^8ie>vgoEZm^nb4X*DogGrIs;x8->;5-oKYv@G9MAQI_A( zk8Mx4#Go?abm>j_LfG$72vM6GZhRsxir_*Pn{~q3ZDm<`*V@uEhD=`BjWgSnPsmIF zpBEITX18_ZW#j(?FZs+_fj7;MLpXPjl2U$eUI=kJLZZTTetXhAtcKx@jKKu_L>{dx z2@m=nc(!?lEF13yd;vXipV1*q-?y;|LyJn#(eC^dTOwCJgNUotvd42RZ=bb0E(w1v zn6SirrDEu1x*Zo_il@A0pIIS=>`H1S;^s(ufzt6GlvoW$h~MB+ibW8Xc_&^Q$YF1o zT*}KEVcx0gdzR(-jw$_%dXVhYL>$ukwa=IfNTI*+tD!W2%>c)KLOndcr=YGs$H1X| z)s?!*2a+p%4!`~Jrz^RXjMueOcxnMnr%zHS!Z7?)k8Yh_|$U^ z%$_RZyX|!abnNNYW0@`oW>hy^9h?gxieJ9pu6g8i;gDS&%I?DZYvij+%TRlSCEOz> zUUqMUZ8i&3;~lL36rW$74mtyR9$oGic5iuqQTsjXh84l?Sw?g>l;(6)jNJ{?4RpE) zCd7(!1s&El-Sj9YUg>>K{&F7>K{8?j+)Ulexx$s98NhWsmSr#G`+OS0rAI_f9VHBH z(=!HHhEIC6pt85tH*tDqqSC1Psru(oVB{5ruClH~HFV324BYE4so&qWpKmJhU~cIN z@bfYbYadetDDGpQdy)2=R7kdoD)ESrr4L*u8``HGx>=|voP6Bn|*o;5Khvm8dfS&gKYuR4$lrD zy*E0iQ?Y&WxtE5wFf?ZZmw3}kxA=T@8D4yaRmskQ>`4kKruU_tLr46BB_GFPK$4|;jfk60}Rp)?T<#DeS;33 z`^;kyJ&{f7)=azsC$v)}u67m}?bu7BF=0-#O6cER%z0HKIoG4NOMY>q1;mrXcOpM} z9I=fUejb})Ic-SeWIU!Qe4Z+zz?jJ-V2&C>zg$srnCWz$j#hAjp6O+u2EGKEM3**x z#Q+A_iX97IkdKTQY#cEXtKBOn;@8?kI0P|ado>X&`gqBI$J`u_1xYc%YvY6p2&0F^ zq?D6lTf2R^pVU(2i`SAnq*Pi;c%(68HeYDM^%`xdv^uJ)YowA$u0lz+?4u?EYvhqx zLaS6Im>`MHj|t4eQFEU{0kU)&*UTFid#&*(?0Kae*eiuz?e+m&>h8R+>7$1Om@*fe zuZMWUH+0p&{Q@1X_9NS_&{Tp)|71x;HYQM#B4Wk6oXV%kur};bMAazuXoAUx2Iidm z0%3!}#^^nN<8QvzmVXnZ5a|m@st@#B(vv5e%tjLme3ZQJ1WU{a0z$$_(r#k}dbl83 z^lID3qNHmh5_Ixm{QKlRHY{pBI@`HG%F-@#H#xXl7IgFwGZ~S7$V^kxQ?*P$m?mcwK);a-ZS+V!23^u_{v}rNK^1 zl?Q6tr%|iWQjjg7x`yWUEvh*jb|=hGsWki2>ui~!R_L1USb|f73LoRO(s-N8o!Yw3 zeAI?eQC;Oen0O)GK940Df8NE0Vp|S^6B%#x0|}8V+ppzcsz!26J9pCU{9v6g9QTIM zpRxg4wNav-a6oc`TgoL~DkEooDr2;8#NYsuYA`edc$!FI+Tt%+AExUCB-k9UqcuoY z<0!Ac`wpNgT1)c-PWLMo`>~)T9LMa1! zsp`?0%UBx1*#A=!%9zJX$biVXy$)!hsn1&JFaemhD||Jgh%}vBjhm+Wi40*(ZMZ(H zx5;^%0qQHeYM0^L;1Gj6i~==}FO1ETatN>C84(S=3HHP%2Ps`=$G!EplPs$+T>}6= zOWo?vXbr;naK&GN#gS?vj;&lXzn~}KQB)~KuM|1=)X}Q$KNolu@Nc(3a+e}{1oWF@6+;M zzy1xE{tF`_fKs8Mg#TdwWoRh(@WlS5DUF9FcBYT|?J zAi-sDJQAU2x9*E?!YfLzqc7TBFP*xb&({Vhik>4uDv_fnHfT{165NV=qhHvc7C#?R z8z_419-CI49s{*JHkQtrQ(&oRZ>$a)x#MPv-#hfn1neAIJQhnIrVr^V!=UzZ8IRQ_ih~tXt#Zt_-?Y_nL*VxtbeGb$qO*^_Mk}F6wp?> z^BR*}Rs2Y59a63w_+k{2+q?=)UKDK}XG25lTlav)zXA;p+Z7_UujKxT5iXlU%bsHe zZa?n1M_S<9Rq=d-=-M=Ivp$L{o-5%;?9kVx-}v%A`iR61`yHgl3CsJ^0i1jf$+WOBOPK3q#?u_o$|XC)Mx!< zkgzENI{2`ZTFfcfA9rlhn}lMbKFX=82dwMo7g$D4^IY~w?lrm?>3PnxsBrX|aYQtQ z@T7Qu{>)RiX@MG_AkqZdoznm?lj71siO6y3eb4^l_;7ut1-=A^w#`y}F4q($eBSZbcav<6G|eVzEO>x`eLp%KT03Q`grw&+n1u zm{QL4G#wIp(xBb40gx+9ZwHB5Mn%GplN)=kiCKH4{-TDKL|fT_V7b@OOJU zC58`)?w`f=jb;a-Rh+5RA}XxkYVpn7nQ*X2aqFW-+9FxtJ9Y(jQr1F=^~IEBM$v?Y zT&~PCOY_p+>VkpYLfk1pvtvINt60BcB@X+fYZ!tnFFNw+Nj+R~H}>f(#881@gv4*X z&CP(zodc}T{vBP-9{JZW^{r)i=`7ul#gwr5L^=dI9O}Go{O%>vfVWci*?s~B}0Ja2!oZ$`K06*4?bNIMH5d)B2EasyKmXG{Txge+ls<|%k7;t!ejXEEWD5XSA1zP%ki|bT=e8}hRVxvY;MooLx?C~tqIqA!OZIzPUzQ3ORAmP2(u0e{C+U z>t4qL1s_Opj_qhJ9q_r-UfSlE!&^}7F-b%o@v5p`L|~BE&Zn_{$l^?0qu~iy%8rD+ z&-bA|({8hT;yE#BRhLv%@A@Jo)IiR|v~44-(_jjeGmAM&8p3;$Ho!_+U$#igkYEZg z$O&ss@L6JWl$Rq^@Fs zW27UHdnO2Wf3PCNmFrtqI8QD!*$$(IN#dLsC%=5Q!U^8C3k=ZSMl!K7~d zlsS`N?-2?O?6ZjEYeO(Zq@US}%qTg51t*k|HWw1spZln!ocTukc=)FA#9ZKHWyMLz zGdOyfnCZ0js)^J#I7D`{54Uxa2rYLc$dG`z_VTL%S)P|=3Jwni*3m%cJ@GF5@j{hQ zij7+08W=7gjgjGcJnllx%|tw;_OEu0g#F{=F;l1X5D07sbo4)0NSh!0`844P^H65Z zb0i-QRpV@wLWFMLtVIM^#(6Bn2E<*p?7EzUja2t?gUoU`q5PjJTjdER-VdJ)UV?A8VkAOelqy=f!#DsL|e2a0bLEAjEiS)oLU$J1Jn z$2s$A{BWHxO!4lW;@aBR36?&=DHyu3{$2~QO|mqlDiolPW77G(4$ZU_*d`Cz9nBjD?I zM&|Zce6V0Aw+-h5I#0f6Ni6{(dz$%U^n0ATYZ~znxx&fX3t_SfKIM_2j=-N=xv2+1 zi{4yCaz>!gm5NTgS`#E7X~&Gg>s1QTXz!a;%(W^ipBlK6z!NE#NYRU6Q6K9r=w@qP z7&xtzi=|Az^gm+$F6J|DZ3(HpGE0H}xJt#B%U}t0;u)9=p-oxFUQa@yl%4awGM-yo zEdKzc_+Fj;3$x&I{ckYFO2W#?#tIs^f};emf>cG|X@MRv96xNAnl>X0(JW9pV-52j zB`)n)hK!SNhf4Avl_X^E@baR*qfmOI1d&j{s^*2!L|A7hxlH+Nei)s;{H*^eFx^>g z`{zU|Kcg2zTOOVJ7|0|7lm`_zNCHYQ42%>&$x%rfL@1!IFE6OCk4%DqV2C9N|Bjg- zHH;SH7z!xfWAPrG8x#_xy2Pc)a*|#W8~}0Q-3|!I1Ir0PR8f=C!66}IV0gnu4NL-* z1o;^wff0)K7(f!7NDkx%U0q4{{rI7}^zwQSxBcx3EMRW#`)l_)K<+|?0ulThgli9t zRmsbJEJ_W24=f;1RQ3G>zSnOUH}obR747E!9uo-J?gK{_uXH2u3TA{ehHDIaA4KMt zgA|ZW3E|p%F(X_EhvozpooQm&4ImF8AH$9g0k8UG&jO2a;dZ|J$s>Rau+$C_-OvE= zCQ|wBQ1{>fF1)Sm0wyB5y|wf1`GE)-{NW5OP6F$J%(6}l?E%iyx1Iwg=w>IHL>x&B z_6^AYN)fctfwJ^&Ow2Oz=_^q2cQPMNPL(+rn34AHVj*T&v|oWYXm>%aZxyOXR;j04 z<-LR&C>IwhJY!KuR{muy6d2AM9>84Tuv2*H-+i;dN&*u{nBi;-9#0?Gv>ubJO%=vP z;UBi>v%*}|H1H%$42)#7q<{c#@Em^>t6X3Up$Iz7FW?t2B(>RY;j z01p8Q0fB*4n7;x7+MhneKimey%H-Pgik^Lea_{&WT2j9OGvH*VU;tDbI1?}x1)x46 z2`w!+?6U`nAIq6C*~d-=l!pXZ0r1dgqomvU;fWmlLKwXd;~7 zk?{rkO|YF$1tzum1(>f#b9K){1MJOQf48TYkSF{F<2DnPOET4sdAnwRg~9RLd!8v23IPQ(&^djDzHjd9!v<<8sxy|WOHAjt7IuQk~&8W;;2+yix+(67^E z9oA&@(;3ylcdZ5<>5GA@LvvoGpoqqk?aRb@OX-=Ah9qbbJu(b$FqoxjIV9H zEh$C?J?Hw9ew1PE#z+_eS{0Bj^Uh;X8+k;gtUC8odY-R?fT+ue2lMl8LrkJ zx^@Ou5%N}?Rs*>U*W_Z}6hflGhayh{v9kh;OsbYEQw=Hk8Ks!ztMHA?9}#j$&-#Q+*(1>--+Jj`b^`pp&uGz`L7&q8 z_!J)G{#{~xCPkiXw0ItXusB3!$c$^xt~1AOLag4EwJkyKV7^)C6IMm@nIX+o(fzJv zPNjyA6-m6+`_MUJ{v_cDBEU$x64Ev~EQ#Gc3AOJyzo1$X74ikI&V76N^;+iv}>U4H>X{y)Zzz#t|fpm2edrrFRdKw2-HYd^nsPbM!v_qvh0w zyA-1hmmg;GoAPd<6&^H|-5i`DQ(r>wb8FmJ?e#vxdmza$Qe6c=2Z8e;4827i@mGYhBw>Fv-qW@`~m{3xiZ?X9=8N_mF+YZ%_d@+)MoSGQj!F zk$Y6nkHup1h{N^e7KvogacGLWif9zI*;{cW@`L~7es?B|S0a>K!B1!Vv1q&T*1)1P z4AMdTJQlfRh=WZ0a{!dvo3>_WlRWi+8#F@j2gU*M7mS5GTDn+`i zvvO?S0uyk)piWVLLYhd+x`@AxJEPY#pHlwJ<-G)4P|ne_0d;Zb;Up-5o3TAZ$i zn6*Gj(UAsbQ?Tx=)@Rwp#~DWV^@;^i9%Qtb7`Rt<>M<$U9(!%&)^F0h>3xk$>X%>V zYOh4nnM6W*EE@@DVuG*?Fw?zWYLh5@*m=={e-u{=s}8CY+mt);-#*3`A-qjm)hM-b zTAKhCAM0%VhD|;5?6N!4FW_HbFPwQI4k2PD3p{uj2{vRXb)T9AG@Hwyf&q zbJK6n;lIZXT*A5J#ii$;T;XYwJW&OuYobdhctmb~c6?rkz1`eO^#e=pc5^OU!%Kc< z+T*vlH%oEI!tBu{?@dTE?Miar(RL#BNa+S92kRNW>@Q8V?0xoMqo*ez8!a{CO*~~` zcWY|twegIoGQos#qp%Gel_1N<;I4K=QR|K1dEagdmiKfb2V zjA@1&0KqYyH)&nxm+6C0n%hKe)#T!bw+*$&METWcV&}K2$vC{l-4`3w(*6lOn5+@t zM&iV(<`a8B!OrKPmRg_1?-AoX$XkU4XbKZ^Zup7gU1eL#r91U#@|r^XgT@m_WLFpn zDaj09HK4-Hq|<1PasQ++J}GhJo0?wt$obekHk_DmeM89fteQ4^Zli6HNfU;l`3h&s zCM2J(g_`?qY>c)mSwG~XB#{K(oQ5Y0Xqk1WoexX@^&NGJ`!y*4VkSi)&9y@Ddqx<~ zGs9TiudIRmJD2G!!{8`Cx@IWcHod-Kardlt^>-s5cHk>XE!WK(~YuG`hy}mM#lDNZJ5gZ%#;$p%i-P2 z@rx-oe=*B9=2iE|Zv-7}y>H8m8;dBvFbfQ*4IA@VC6bn9Lg`H!J@}8dn@GZEUq=T0 zVh)DXSb}8l7Mcjn;jv@ae0Dgj2JYJgYFH5?X=plQ7E5drzc}ZWp_+v(SvmT!EkN9A z9k`lfcMW8gPj8(DUq7yBaJT;`x(!^AZwRL)AQdX@U#+ot@`~z+b*#wv)#}^mFw}fv zt3;L0x5w9RL2z6)LF?Lf=rI!6*GfActm@h8AK`~D9S`3n$FDf@rb+yz38>%Y^!2A( zakBYWDsE?QU8JR$S}nDQtAVfCgj{`BhXll~S$Eqsg|ZV8r+MOehE5F@0pE`_r?XZ^ ztHy2Znz^e$h!wnzHNUV*aeBEdeTc~jhG8;~b~lbXEl~18-_sPRUJwQ^A1ZsHS{gR$ zTKM&mQ+5f;F+eUvPZR!SvB2(zjuIErpPK&gku>?6*mpoAelGO$Kgs6O!&F^ulix%s zeQa+t2YE~AR;uDLp#?;;h3#shE5f#51qMoDIXHJ8OA}KsKPY%$-Ma}}`a}h(g;}3$ zK*Kx|g{LmRlITB=`l(`_U=FBD8j2@+ypFP?)s}nM*GAokqb^fEmjaQ_9!<#17c5nX zQ)l@S(9YOcb!Qt_NVcY^H$#u zloe9HB`r@Let1PtxY*|1{OS4JpbB@)F#g+n#_>4nVL7~qkN?*WH~c~a98EUFeT?bW z3TpxEbPo@@Ji%@BOc}5Tz9~yNn8#gMvN;bpk{IG>16C5__X>ZzF;G4)uF$=0%`t?n z)tB%+AeTP{XE@wkH0dp;&TMVcFF2)e`*kO4*E@FfOaHQnEtjPs=zR5{&Zx^xh7W&{G=7EPSM0og$?ss5zGZE?V#zd32&Dz>T z2(BZux%lby4L&AEqU&*1E(qFVsW#IA6VcjYvcA1Hz3c05ZlRnE@)p0)f@jZSxWRaI zWcFdmN34sk+#z(@7MI!7G-$%tctRpRJWyUE9;fKD`7xoQ=`J2@+_9jaAGdJR^A2~K z_hjBm11>j$+C5M~F+W}q4`;9Zg?rD4ZN%JK<#PprfkczvqV)jc@?f}lhOQ|Npi=8a z4|Z~ej)p8|3wfU7Bi`xAd$R}LZgCVD*!-DW|1dwsOyM;(kS%{a-IS9fxz`BR%;nv2 ze8C0U1j`ui34?)XpzV4jwW+dEwK*+bgt3y%D}8xkPZfCbkovNd&_lO#BV!_^FjuL` z*O*#VI)Hb)V6zGhv6F0WIY#22Yua=NUH|07{o?+84qQ%J9J;i_gcf>U0t(NJ&{h|H z?Sk{XBL1Dw6dT2qX)L0&1v#Sm(eisU$CZzEJAz4*I-hLnS3q>!+Llwqm+2KX%wR~f zEz%0kdPSgTww=ctRD_3Y7Q}}i^V=h4tbmeFBif>k`dCbUIgW!u-KR7Ir#p3buA!DAt|*o=p3x%>_XxG z+?c^%f5@C27y8Axc8kxC`@Si+y*Sjloa!@@IjQVuMutFeG)oI)O*-yGcZ|dXv33@Z z2@@~yNQS-J7omIfMeKt%r!3wrp{@6Q;QC%3I!OI+?p9##_+U0hwIsFnt?S-2*1D0KZ4K}D$kjtn%lznqq$4`M= z=Nyl%>eVu4DYqDaDo|PA6Td(Q%!*n5tIQ$MsnG>^WH9JBabFb$~a~r9AU1c zP#Y$(;sps3BN)M6-^Em1$+qOW9^xejH@LapBYWm|KCxl-a5b~9?jKLyIvuG)Kb9E) z{oP2z7Q+;-)fK*`f9J;Z)|YWs4DM5AlMMg45q_7xe%89kSRlno3K<=`<4dJ?Q<}hQ7Nt>`PNP%6Lik6Nsm1T zZG4KvBS`b<hcOhuql668u<=B*m;8 z@d?w;^>WL+=b_Ye9PS1yxcs32Eaqo7x**q>&wHFt++GD zf>v7%R&B_g<6#(K=a|pk*vRMpwJ{MVPPMWqI@#NGL7=`jn>z-1^E)jdb1{a(_j!8p zF?D`P2=m2+?E^XIA2&G~q@U*q0t=lM!I=iswWK;VA*w=lpwDa32g4|oEunN3Ux&J( zw*v6mM$$%Nl1sg-xYvDNS!39@K6~FHS}m|!Dcr|SNQ<}_fDhI+`Gw_Jzw~O#P?+DN zf%ZCyOHK@aFeuq6dJuB~M}-WA@jROka&v*MfMb~PN49y{PW#71e&w%yN;{X}BcnRf zA@PS)5plIe#Fr7*cl@V<^7Fk*PDl8Z4hG5ytv^Utpd$&n;nK1P1#iKZ<`L@8cW5;2 zw7HRq#1rCDKF_UxuT6Gy7{De&D7c}*I$;!oA%81G|AGFD*+eo0ba_gv5GKzyu%|mc81kz#z$l>;^F#W3U_5Ov7n6fEjRH3Oj!xofEktCHhs<^IAIWSVs#i04eGB4RRT_RHP)&?2 zSSVURzv2Es6<(+ocrG3jQn;2+qpYyAYW(rFytzx28P@0bHn1>2v@~7!rKN0jJ^;?C z+SgswOhA*QHP>-p%-1b=V&y!Pqzjhf(lSQZTgHD1&i=@>GQv;0ic_YtZx}(iMq6|Z z^SXgUx4Oyo1dXdC3j_NS#5%@^i4CSNROl3b^hSCRrA(9R;j$%^#Q5i!Dx$zo3Ib)? zZJ#Nx@WYQU4uP5se6?iAN%BD7OTXm1uxit}el)3w=P&k3HZ>yLyFWvg!6tZ2&WuXo zgz4&nY+QBn&b!MvVTl)94~-RfGiVlcAyUp6<+j|v4*SkW(zp>%@nIDZG~Al~9^;nB zd>0v*SA!n5DBQWG8dC`C%6~U3JPXj+=rJqQN2?}Ong+VqhFD2{t}8{T0t7&4(VyU@ zd~?G0_w`hmmfWBRl?+X-$(vh#k(*O3X)JIcX;dWkZg37{6mG--Cr`u5Z}y-*%cXG( z%M7isK=x3AJy{dvL?_DJM&pgfGR#gJ#<}Iabwh^~MPDb12@5-8%Vc7?um7oMZUMDF zQ4^ytQ33?IauWD0un9H|870~swoN2lsf@1?`64xUarhGNDPH!}gv;~M1*dC!YIU1k zFVj2?>n6mfwc=N9TEgoxmf#!ge3!ec>t&@U|H(B)&f;e$Kc&WO75{=@bP&4HL`ABa z!DHj-egWwcT@cLPOJ7lyMi+k!V?2MSv9DAm!wMX1p?geC)2v3}lnWj~jGx+2XhT=g zalGVL+EAF2;+8D@b0h(H;;U+%yH}rdy@xT|z4OYdBep?Es(g<1PZ&Ob+>!_H8r(DR;fS-K6(=(O~S2m7s$)lM^0vgFF{e`KiZgjT{i z3y}iNz>QkDG#5uR&kojc3^R{etI(g3U`C48Tbo~&*S}c{q@JN$MTY(=ogpE2!92Bi zJqT!i&d3}~CYtESR~E0(k$Uk8Z~VSVQw(cN>$FOppWJB(Z@)XmoIZH>ki&V4^(GlK zx>o!+X1nP+jWG4YyTH9k-z2L8)q7^?RwV=oXGssH!K-q-d90}|e}#*PXG;VYwywPH zL&a(?$J^v4Ce!|>f~5JkGQD;N{! z6P-Fcv$1dcgc~!FG0g~-5Pm}S7xTbc+-ias7B6vDHfs6`+1gRGOI=FBKD%8Ekc->_ zn@3%Dpy=2y0`*t*vm3nx&|6r3*6<546N%E?96Checck_Y=HxrLi)ufY!`ao-D?u`2 zsF2X)PhZTMiYD6wK=8=NpNR)KC@}`|Tzj_GrNUV!NVUOz;5Sg9wdLw8{34{!N!8pL zv>gU=pm7MEs*G3H_{8z%zm>Dup#qSkN1!Z$r9SmII-U9blJTq5KB-tnKPAqnk$9vWy+kW1-zI}(aG!QO7L*HfI zQ{I*)#dyBlgh*SSyc+f!b51G%VzpC55`Ys4OwVr$irAd3M4e_IKHVVvax19e@9Zg$ zlgK^aZROK@_pS zKIi=Zk#$b7fd}mxuWh$mduwcM+qP}H|6;e+*6!Bb+O}=mw%xP&zMPzkGsz?~nPjf! z;>9z+$Dwp9??q~pzxR0BXadMq2|0svtQ=65wt@z-4cJzn^e9-k*efFN8!AQ+2l5Ux zV{Hh!5$N88atpst@vbh-l%8UjDYj|o;WHxcl9$#}+_^1MuWO+j0(R8tT7uUd`=A<> zLq(}rp0(>^AJzgQn<4^yJAX9IAc9QgdIZYZCWaM28qr9f zzYPC7fl2=&1v8hXUp2Wh?HbAeuPaf};rwosZ7X9-3xvxgB4c(QgG~P7C}7-+ zL1b7rD;K2yN+aU|2N+S&+7KK6gu|M>vce+MazrP)xZ8TG^KZ+g+;_~Mphb^M>6dL3W=%*jK0Rl|yn7fUhLNmgL zi~Tm#jE@l!!uV1~LBZC0&hiJg{&A`erK~PO9!)fr!fAf02_PKxrA>zRBa!-5j}UXW zevl&%TdboHD`ZI&oxa9~g?1^@F z_Z`OYcmCWDuc`c&|Hotm3{63bl)+9TQR&s15wp z0rll=qGcR(IjTr_c4d$OlTz*Ch)iO-wdy{irpSg8(>k#*R1#5}CIoMxxJFUtF%PT; z@!*j>88i8)G;c_+6BOE4M&zJ%J1#0rP2DwB2YH(V8C%IZL_{+WeZ)E=l!6{!<&?6k z`xQEbl1Da3j*_E|-75+NWu+FJi}r4|xypRmxg$0S4(Hc7hybyY1w9Jd=O3)jXn0@H z?9qGe|LHuZ5E{Y3pu+v1RPJBfnS+%hMI9NA5{!d2<%SuQDy0w^P6(`StLYdS4jk;? zS58il^DYBG0GE$>9PHHa=%1A*5g8Os>4{{AlKE%ZL03|IydrV{2Q4;LKvF^|L3hvO z1oF0z_w~mW=PB{9f!q6-Mo$kK+%v(sM~4FRLr(g}Cn;#3!M9$R=PSd~X{ys8P=qh0 zjkv7PjrWu2y|1(@p!xl4=G`Oli*^q9Y9iIr;As=MM*#5NfqP<~u&g5kEQNWuUwjpT zaQ9ZY_@7Iv$nQs&r2+KBm5*O#Y5{@Si$c9Ur{S~Z`0KXk>%b@pLoEt&^)GG+bNde} zyU)b4cYRKtFmO$RQ?M7m0bZ|~y06$vtFdvroJ!ObD*MmBU@g2A_~)@gpMzA}#f7g| z+@|>BxmaCIu?eBrAkOYkUU>qDU$8eI?OfT5^I+#U&}}K$=y2q~?+c=Sa1ff0U{6rN zgDzA79*~kxZ~J#*`Ur?j7I!~Zep%)`qQiV(`zrH%!aIWo$bWSgcPq^Q`Y5xVEbip} zgv`nF`h@2fyTf_~|6FPw*UQSvIeZz)=9{<`c#h3LZ<0T0uB+Fjn^est;TtRp&Pr`M*m_laYvUj89W+Y>-Sab)&HMPZN_M&Y~&LZfpb* zQ;^J-z|88APK3U0zHL5ze%bhKr8oGyWLpfayk%MtiEGOd$bYwK#uOz)5^)S_4j=`= zWn-fd0znxbgM_#>WM(-PMvaNhywGC&TcB&3(ie%18tt;UoMaZvXlnBsPu|=!ms*_;`Q6 zU+e0;7u2>IQ3p7K@aDqs1hDrb?w*3yK)qYz{INfQc$ve+#v&73LOOj6T?$+y=B3vo z3GnGfg$wCkza(2XT13(4{x}37pim14VTE`c(t3ymhu*HL0}W^v{E~mtxUUjbT)r}t zVZyoGw}rh6>9qxASCoJe6wyzD-}$u-qS;#xaA|Y5_5fFV^n7%=G0EyrNL{o|5W_N7 zpmbN?-plwns%htOcLooj+};;RpQ?U571Kf2B?t0w2^qq0lp8#Z2JEurDPag_>0;pIp5Y-_; zs35dq^cW!z9*;hF#&^(L2A#C?@P-KOON1~W?+$}AwHnKTtXo7g#N@J5NHsf5LeirU%+^t73@bD-1b(kG}AXu5Quk`ix1|H zGUM1Ti0<1Z$7-;D1$+YkDs7m61Bc%kATNR2Z^*}AbPro3Ujo0rMsK^q-@D-BJv?0B z?aW{7{@s@>uPAZVg?}k_7Sl`w!uI@u)BU-&0CH<#xj?+A=u!ODNJBz*1uX<;?!#y< z51TVe|icn7fuju|f*sX?|IzmTb6w%wn<1zlEzb>&X;)dmyO zeVKa(fY?`k1rUS$vom{+&Fi_WtbEe@SX}j!`0DL4K!WLq2OCV!2@Dn!IX@HTp0p{T z=Hpr#?4L%SokaBF9D*BXLj7<~I2;S-)=Gn?F}uC%a=IrU#sI-z6@GW>V8f;1b$qh$hXk)Gf-6CKp?XaxS81tFRVx< zs2tROo0jGa&~26>zJ3X?nu=TGUTHq}y60IdU}Q_c{-yM{k!Q-@tzv{6?|o&MtgwoJ zKM8>)0@^Po^ymYVBs2vMc#+e)R{=mC?Y2 za$%;vz=2%Oi$v|wKf!!0;J(ao0ibEPG`SAet)hfO-)hM*kpA z$uD;@n9#)Ct5dl>)-$e1bgkAZ30IDfCJEOfS zdmWJ+2XYp{l5me5Ez?;`Z_f|1|IWK!wcQ@dDKKxxy>J)9qX`#uC-IYcNvTS!0>Srq zy)q{YMgtjcko998=(QxxH56{qBYOJ7-F3*Wuq$-ak+-V{L$~qmWfmV-ynEn%k`$Ez zgFoWUxaw{4r`ow?8q;W1)RQKb+)oFwuhPRTs=hp#Wb>GB%`F}_w6yJ&eo6 z4qKr^5AY3(R=u9@Z zdNaIOO1<1ttekvyoM@zu!izzTgVWvwosiU{5mV$=AV?wc80+{Yi=YqZnp@qc_XM$W z>vzc2dgkP##=%J)s*-8C6TeD5Yjjt0xT22*-=ylE6*y3{`dq%bPTL_xR&_Ji0;Vfq zm4?bqyKnMaj*cB=5mmh4F4}f`I%U8=Q$}o!`cUGD4YtE)`Lk?s^J+xwFVjWMN!orG zznWwMuq6L zLXy*JLFYA8OB@tCN2?_=5F44Np~al!^g}OT?9-xz6r;M>G+n@*j1f)qwg!RIV@I!TNod?u*>weFI)z4Z|3gGI4Ma#-xsS7 zP`>ssX^C0bsH#7jCmJ{Z&A0gv>f+fazuGsfm57nN>R*(@b`pWDmu}N-9t}k+W-712 zP^A(#wi+7Lsg!T-dfB`g&zQ{nYiCitsE@K4MtWhDJC4~vjkTZVtRQ8uZ0&&FKx417 zDVxYMI^LVzlDZFdWI_-_Ld4}*a5J10V4#~4SR9i4-thRSbG>wZ3DUFMnCqZ2(J<+0 z6W=m+uoK2(`}lWxcX{~sXoJdgYvS2)jca&z@L2eG&agf@O8`#7RWGsC6ldA`*ENKL z?v$0d_V;ut$YGHOcygWhh03e|W1jgnJP^!bJQwErS%KF8;k0xO6*4h0opfw@ApXIB zt$Xw!CW~n53_hZX@T5JX8RI4%3OhngMW*0KMFZYQn>=Qc*1Ya2)I}P6Lc2t!MK4bQ zZr*%u;V`(i=5uyM4{B-DWu`0?gc_a7fxI=J$k1Qu9tWxN#4fOL=8~tBv-Gzg#fn)F+lPY!K>NiA)+GzU zhZ2#lB;(@(X_oxiv-Ul}aw_`M^rqrvHBhcscIea!UYgWuQ+kII)XeCu0vx(bk&tAf zIB-WQGa5?4CC&VP=+ucc;Y@sr47UPQa(vd}*&?9!KX-@>PJlVU`m^VFZ0`wywg<1@A4<~8UT(Ce96cJDnRzdIfa5&9dT{A*eH4o%XrovxK`ezs%ZjK4(r9$;NiYBZZHBkUJ@r47&y zB5fyQL&U-|0&u-nQ>PgUAnC$G$-D-6e_Va6aIw``Rr=drlrq4LRS9^-wi@SuQ9N1* zVQ;e03uvPIQk= zzeW}ID-wo>aNADvNB;`ghVc@t*C(k&>Wh`SbRmsglZDkCJ#@w+~w zJ&<+JzEfUq;}WDF0@8k=68A*apxUinuu7b2YQ$ss`!`SAm`6L8XLlAJyOpUXMERO| zNBmZCFTs7RG)2Hxn#o*~)p-x(EJUpMzOY`-(vvZwz!HmLZ@oUU)>zaaX+qUuw#!|L zuzo1jwbxmu1sFw?!z<4glE)Dts&1YIMP+U~beis#2QwXa;d&U7m-#F|rMWT=^!@&f z(%Pm5=V{eH=KYSR;q+IA##5e&Y^xrM`p&u z1nCXuacw1bxZwwvi(j%p=>Y5%z4p}N4aV3jO^L7hZ{X1DDtRigu_N)Q#V4r{g-_V8 zd641>~XABF1J(p26uZr@IZQq^68qfw>O8(r}&=yCsTOu(?9-KPi7 zjIs(1}RshC+BHidISy0 zxYk`{GGLQ0%UDn9=Q!CjFZRlXsImjU8&;ZeZkk{&rw5J>9J2ejKdr@r{QD=u#joXr zQUjj6$Vl!m^LHKp7LI*K0td0Tp5({{tzVynNJV2GFX0=J8lDGPmyXmpzl{=>#j7~> zcLLx0I9=#>Z}!vsn*^gT5dW1wY*bnuiAZgK>47AWIJ~mHw>~ae^$Av4ad~?QFoAv~ zZ<$s4=DP?wVk<4|q4mp)cs=^t8JW<%`RmJ=DcE_r9TAr3hM0gkhh)Vcl+fmeM?%^r zrwsDzLeZg05bHvzR-Q3W<=M>zDa{Y25wKRX9md%~i>-(G3 zzfwzWUiD^M7Ol_`v(=o+t1KRUA<~Pghz3F;ZhQ^|k!I9(QDpsk>`nBNCj)aR>5>CI zNu;TRaT(IElL`}0u8_~z^G*6)_ud#G=mQ*{$p*Z5W)~@REkcJjQ2a=NRPOrcKdff4eaTgYl>5oUbQP=2jVe++Z15dWLb3AW*t`+cl0Y{?|G z*=%;-nYAL<=5U+F^G zpU(YHAGagkX?)H}pna#6IBQ!<^XoM*o64s)N4O+DM=!ZxKyWvm9%en``hs zN2OYF3DuB#?+B+34J}3FxK}S9>5bh!+I8{|<-Xm}C`&tu zw<%q^a{Qw9-HmsIVPA&G<=V_ZlhsGrXSmQofMokj&Ic7vN*P{e&PuLq3^IVC@F$Ej zq@}fHZ8|h@zokG0ANBK0!p(S#A$mvyxBV})GnVv9zLpl+Oowg&jevS^i64c88JV4^ zZmO-HMelq*r_pCL4SU?#jvp{o#}Xkk-r=E9a;4g+@c6|X*^{^y@@{x>cd{~n(dT6} zz>m$By$3%@Pp(MQOkLggs@MqIwp}y6s&nDukDTPzB2)6Iu{xF<9l02yt(2ni9IkN9 zyo7qQgclVA#Vckc=3^a*VxUwL>Vs`2~j+Jz!oUt_=874^w?ih%}|qW1RRp0WrM;gVx32 zSXt{2uV=f=(>Y%6U=8gl$ZKO{l{zRhro0-h(M_PX7@RnFgVvs9cr?-R)!E zD+>bZNdsROjZ|o*oXfxbGd6?(A&QNeuh209;H=bna`_GJx5sq2H#f5xf4lUPMXSKv zi}tZu<7{hR!}csj+c!Fd5&s(rE8%*!%;bkrrvTEBJKf;g#~SPGv*$OfeV^0Kn_Agi zrvQa`>ZIerQ3~hV9Bo2re>R^>>!jA$cwI9i$`TYf^sXaIO=?%XaHZfSU8%*mbFca;{NLd;Ts85$UZu zx+CwG8f#niSJf}^KCXQNw0y^zPy`#3PE>2WzqGzOi#kp7hO!7{Ed0PKoS7&`#wB2^ zj_R_{Mi7v5x%~OEOArpp{Zz2nFzwRxsDovi11QO|ep4HXBkA5HJ zoEG#u`gd0*XHKw<9T{<}si**|y$crHAsYR0+Ok7`kTPs7R~SgdPrg9pPOi*-YBA|5(7kQJ>X{Kzhs;9yLu810P5r_>sG<1xxRgV1YD9;E@0vR{ zIXSZ~yLPIOT_y)<8pk4A);(;2fu;ugU-+1;2KTvPARKKK{lB`r{l=tI9%@R|RTE7w zqNqn=pBiOZe~$528+}j>dwgks|0d{&btVfaB>hCj3bkgi{)79s2ql$kNvIT#hR{~h zM~+?6+vPf%WTvjh%@Xg1mriFyx(W{gpXW}$CTk9pQGm~alcQ3WI0SpC4)!Kls9&+DZ$74s4fA^tpPgD=ylU@dAOVXSP2+8|(7Tc^g07Ts#}a zl;@MK@-deT%f?0B$hQtUw9o7%8rR{3_uAGbD$VKnA0BWTt4tDJNN*xFrywHE^xqiM zt_Z3S#Htloa0R%aI`OPMaIMn1KAPcyF~7v0Vl5jBvvyu|<{KLp?44)50XH~Z6$6(w zPJpd;`Zle=xD5GhvZi=``@~E4K`((rCVKQ)pr9XVV$Ggm*@*M>CU5EAYT#3i^HmAN z9cK#nMAfUk5<|(%-)Lz08geoL|3_-9YRv~u&IQ<|1JoSmMK z8$-MRf)-Dxf{8h!ZRiAbS}B;naq3ky5&1kEDGw)A{ORox<}|_6E~yBTV$^V<{d0dO zBYFZ2ntnjajr1c%uVU;HM`pu_mSmr;Az9iCu&_P~2$Z2jI`%(T~;~9V{joUtpIXkbWJ{HEWi=ksa5YA1rWH zD1>`E{c=6tsoCcJW*r3p>1I|vLrd(cU2p_j0=IQ_ditl#^bAK@TRUv>rWEw`3c3K7hFoRudY(Ac&Q5`b z^(XpE-Gc+x&IF!k$+q81^R~j=KTgQP*wz5Zu-FHsd^S);Q%?k;c+7_0 z^o?kR_6aMpOQ5zuv~=yboZlHc46`4DhxFZ1wq2FahQtKmu;%}oVQs?gxvB8&$s zfdRfJ$x>0BmQmiOFyG^u&VYx?1~0}X@gJaa0Aovh`U~yk1y>%iEa#ds$~T34ByjdB z=)1R@^Nlv}Hp*}=iQFUsFZU8|y0=z*#wAy@`-0;b(rgh$5%{nXf5kU&97YH(GOt#A zez=7(0++Z>;JVlO!0JiZh~J-CEcs{qZ2W7m2YDv*^Jh^>KW86l5e0k<$401TA4xb72FR4C*4_SMubDhZ5gOy})wn>Z-XH_M{kj2&fuU zv>)Zq*3%H5Y--Dyy3Rpe2^os_p91a-DU>utBiTwaWKXtmY8!qTgqul4>Y2m_XHJ2A zg(FPiKUtwtka$Ck8r;SJ=c)NJ9J#p&m8LJ%O-cinDW4_ZXS{2E^nGlUscvRms^k`+ zyfFZlb6E&i?+godigQJp=rylKjB-4C)=<2p$jJNkQ1nQsbttUBBa<1&<>7nyPW!!C z_pNJ}EBt`@8MZ7~8V5I|IUA;oy1eAKHbZCXqs3RVB~#18sn_xD9GM)ba+RE-jI4~c zrLg99cOR~_k*OnXoqybw&-Vp7u@*<*v*+7Wr^I@p)Ja=#?6O&;jCcgZU;Cou)Edjd znqXC?A$&+V%aa84!WVj+WmvwK*SZy?8bv+Co0N7>B6@y@4`M#NI6Cx$m!F5cbsihX zsgyn?tywTO5fBU6sJK(ZyeX5vnnDAR`*Hh(yyMea$-{pWHnz;%;qTb-Q&|-N?ZM}J z#rC?>GM*>Y@-!+4L_aH168f-=#{_WsmsDa?{HRsjgHEuP zM4AhaqG=s0%6t~5rc6VER~;GO zn`q5Jop)Mw#E@6P^C{5;UruKNm^;Co8VFki9bKciT^B1n*_#z)L`A2nY1kebZ0to^ z<}|*Ia3!ft{{ARAx#pK;cpaT|XhF9OT$CUhz0FX*PK#e;d5>ZkJP5S`qSVMi2ujoD z!*{_*P>Y0C<@k@s@HBcR6NA%z_*`f9E4Wyqn&6f%f?#QqXSm?@22B{uzhML?gp1su z8Z5xn{1PGUA|Dvcyg}xORLoRI-8B4S;x5O&(=uuHaSxp7ZjLAfTh2AM$1KI~a-T#dbEJ*`(LD%p{C`%| zKLHFo(?2YzteL%qtK~npXC@X7mjB)UL(l&2l9-v9^#|L31TsK$6Qp9s85TnnwvAJh zU~Y5UzwwU_O0MbX5g`+}tGKQMH}KtlU}HnOz1g5Kvu=v(OTgvIl=5Y<&bMRA`v@Mf zFrBilxiFtgau5~F%-q5V9Ym7Grn(Mvd6`q|-&C}+tnXIznciZeiAEY8z&wXReMSbC z!bU;)7Zrm7xs2|kF(?5+8GHd*=-rcK-IKK4gHYRsCVO8gx%rVGf^f%3jS$pzAQ<>0 z#2Tu2QW8{**wqb)_Y@OdgrKfi_aN^6{`y4%8=$*L#Msr4C}4_E!gl{^8@TiVk05dq z@JukL4+bR1KW+agQh}1n7PBvJq7LAr!<$*@mo!)(If4Wc+6fEE5O6O~ECoq7VD$6e8%|to%L& z6n*<@1!P%k`HSGv;Yt83kObfcr>Daw$P7SXWa`H=glvQcRW(c0{FALn34&t$5=t_? zxo|T85FH~ytbtD$AbghN!^EL#K!X_Iy|?jcz++dV&nFFF+I~qymIFV%(rSP7E6>jK zfIF7ka$El|K_F{SPC-8g6e!+^u4SP8`Q>BeLCR7n1^o?ar^k>> zV`--eAOc#O1K)i=Rc^M>Xn1(K(QH8>Q-jNUQ09TWu5RM8uKkog4^SU4gcbefAtb}M zy}K)_J#23+ZsGHePv);XUoA7$0nEaB+^^H;EpAv?355V;R_t#9X~7wY-Jj4So(6=# z`zKEn9?H81?$-`2a*Z>@^_SYkSn8)*&D$2lpEn<_W6&=GnSq;M4a6WD0^}UVd**eX zFUDU$(Q6LF7l80ZHu@F4|D_WbmC^B$W8Et7@I}Nn4QhM!(9{EOweg1${?GYyEmYhW z+XCcAL;WbROm#-zm-RtzcZwKFsOB2*2GoOa4NjmR343O)<%+RiC4tD@ zr-;rk@Xu97+RZKPSkx)`jW+{T973XYrsDc)2M@n6N3 z?ydr}tZ#J9^(`A6UP;0R37GAN&J@`!%fDLMDdar9H%i_dyG*M-(d2PybsTIy_54sW zF)oI5^T+RUD8Ckbw_(JE`(Bs4TzQpWS0x`u;ER6l0h!Kg!O_WKodY=9^Lm@|bv-6C zB8E;~mRv1fQ|Iv|DzFS$58*&2${RfkkJTIm}8GlK{qJNt3VTZ+3+V3=% z)-fM6T{#*q2elCu!2?>mnvogn>l}^>L4>WOUL6|~x)Ry8(_0n)?k?1)ith<_Ij#l{ zKdx1ft7})ea#z^SNn*cHb@7828Jw-*L$JHQt}k&_As{_48-y0KZ6UBD*txx)B!@jl z#B2Lhvr4Yvh|@E|n#LEBB#TIFbGr)NHmAx)UVisQ4(nzj$pN-m!+DG!CxqGA!TI~` zmyKpkE_t`=IJ-(;RgxYbtjf83kZt$kj!+1bEbgwXii>}VvS-ekYwftcq|Ihs-D&Ju zEkN1`J0?MsWvt&>e9VjK-qvpLxGV%KiTCI?HoZgA4RNcj(!;Jp zo+hq^&Ww}2Jpe-BXe35_?;6Q(85)?FXq27;1a9^UWxS*mParoojd})c)6oG$|>0x%AqKmum0dF?QMvc^TE_ z1|m9H_7qg2N*<)$?VPr`j*n99i(|?73|!AD4&)XTcx#6*b;rb|48N~cm)9x z0-0pH-@@QX2rY{@H8eF{{)Dy~jd8zUw%laR#{DE#TYi`WMx{Gjsop>b23#2m`{{IO zp?(5dG%)}9i>33eJ0YIu8>Fov1~r9bl;=F#1Y|lg%v6a zda0wp>hTZtnvfZl!KSe1n}oRcHueahS?iox$$^ohnQ}7`2h+oHz7o@BfqtJ%D{B7GIdN28a^%Tr;I?#WO~-Cke_%yv>HNGq zlARGEWu0-^oCo*)F}K4j+L!p~!mq$a!tjV&>tb}g9F0FtI%p%5eP1Ll@Xs;&F(>m0 z7g&vF3fo3_=jO6hyXa5+r$-=pIZx<<U^5pBKKeI85VDOS?{UbXuo|G}QKXU5@IX%GP=U)!nksjcl&yga&KS2MjN!&uf@! zsgu96Np6jZ67v)sgGVL)h>M%B5}}~F1GMve&^6ca^oj zxzY?bs)Mf$@qV!2_{}Lq$rf<(KE(tNz6N_md-ON-GAVKY12S|uQ%E4^K9%Yyd+YcA zKo${)7r8mxtX#rGpL*YtkXaJ-f&0h((wRp8#A(}P;%=DyrQU%~zZUWBtfe`W7_cJn ztf#nYR6f!w#gSq+$BJPn)t`t7$2@WNR6f7sQlZh3S9kc$N%-tgcUC=!APE!c*V4?B zXDV|#Kjm@XS;*f?&~=GiaPs$+pE>NPrlz&W=v;HN1FD4G40h`ZUu2~&{r4ru+6s0iCz@v^q3hkMsEf0T}|b(Nv~Y4Ecbyk2U} zwJ)~f7MY#K!>x{gt#mnngJ@+ZX`S92{~D#|VSwNYsw5E^;JOcEJD&Whfr_QhMVB#G zP46pe+RQq}>A8@Q)1EwT?Y5F-wU(Z~E3Ik_FdnVK0Hl%WSG#A~ zF=}4i<%36G+TFDil8Qoo4~OHzJ0z2(&WRmtH$hXkh{XckX#9KmJ+tLmB_OXVpC$eK zYJ0qptlAt9LWNj+Vn-ISZd(=4YK&V5e{=UOp6CG1x z($S!q4ZJ+BcfZQ1|%mc79?`GcL}XSm?hx1YwsDt$_PS(0=?pLg&N?deO} z)>A2$BwkG=e@KeRi;Kl}QBpuM_S*(cIo|7jPUEnO`w$uL+r+&-*aAU+Q!zo2scP2K z@uvNHGbDW=rtV!XVeE5+AbGe%UfcmXce!>JldcvO!{$Fz(l1QXib>p5pPex=+rIv1 zlKb-+OUnzTbfsKphDGZ9oe^5MaebH9OlP`AWIJxmG-(e!VrkzheDB_3!!NjnoE}{t z7ZlBz;aS5~rErgMkmgcJ&h6n*d)4w|deeCk{7IqBWs(gNv}3ooDr2;PIh+3=jyegp zg6CfChGZCuyJo6q0Q~p7bNrHMjMBmINOYu@P%7wh`BlKX3D5xYyI3_O+L++-+c-PX zZ!7oEb>c|3!(kYMF{8lrQ(Z-vr${d2MGwxdZm?2l(?;PYf}D(HY~3UHARF8Z8$>Mb%F z%bBX+c0D{&$$l5qb$LUoj-Dxs^-P_2SZllw|G1FgYD&&k>B!cmroslcwPn^@^Q1 z+=DEB`dyEl1>s=Kkp8`H*$*AFJE_nruvSab2xz8^Ueri37u$TsGZl}%Ul9>W$r}#^ z{TS2FB=fU~GdN4}QoheSKJ)s3X=sC=SHjh_J5dNdQeZAti69|h#c^h?Z+IZBhB`IQ z$GL?+Q%n!KIGQg<>QnaK%=WlI_F~VEv%O~&6?m{JP6^Q4s&AdLe9#3eTAI}&DT>4J z1Rx82eSes?sxr^7cC-`i;g+a9(3tW^usqnv6jQpV9hT|E8GJrVm`k%k4i3w73t#vy z7wPAOO4>e6pcghA9BwG+j$oe?{RMZ_#qZCF)l+e7dz}PC5Ei#_XLWv#Rfg&^DiE+b zO$_*=b(qh@eW#%Kp63Tc7pLV4j?hVv4a8m5q6$tgPGt3#>n-qWE3+!#=q*IaTXd?R zIlsmPY=jxb24Al2=V%Qz0Yfay39r#J*7aL!W%GPLjr;1=d)vIJN&gXbMCSckF>zrp zm%PpnbVZv8>8bo}!PSjE?LU3c9^j}d3*qv!$^YDEFEldQc6gBF%sMQb z_uT}}^XScX2i{(2xph!lleaX)^Fr5~1hs zDqPa?C~HvF_WL?NJlu-=9d{!XKvnJucD8CA&LaKm2H`qq$@9cGtXeUaLrAH8YcSt_ zooU^$iKfTMxl20M<2p!f0Jsd545t+?91xx6GHi1sDCrV`$Q}>$>XT1AI2H3niOZ17Jsq z{=R+>?J~6gUTk#myZFIFy4X1!!|IVfqQC|ZdE|=q7X?-I)~~f@tb0NG?=Uq5gD__35U)(nGe*Yifl{dZY{1>Ngwq#RlC2hv`T}7^ zQterPnH3zL-i1V0XxVFs_(%4uCVGAM2^ZelZ-42Q#{^5Y7K{C!-<)uBYYsC(Z>SCV zUEpXOn0Om^Tk}x3j9p@d`krbrHKMduWO)5q3>c+S&ytJI_j@i!X`0TMM(om1)wK+9 zxEy-C-J~?{#Xv_sgKZYe#+4^Ic4|m`lZ?5`9*Q5)8U?Gofe)ugt#zHbw%1$xP{0FY zB99yLONxrMo=7M^(LV{+k}oeRp&Qs`#vjOuHT;s*o(wY%d<%Q7jrClOn-(v6m9}?z zJuU?&k%rqk$4m45%lq46UtQ+xkxsIf6Hed!30257Bw!+c3le_#W70+g@k}ePj2-eX z)CYOOj1}NaDA9}k*LBU{$|xB#Y@PG$25AI#ERmHdFMNsLIp->X1mL^uFcWV66d_%V zq*N5Msk`}B%w*KC+0$xS23{#Vi^zY6VR6ic>uDn|Z_7n8Y)!X6Q>heuKzw&Qlf_=W z6$qK(4v4yx$&{LT_H3R72E}pUexbL19+dAdmFkD)JWy^~n{G7AnXwvd%rjPFZc znH0@rFPemMC@3wpYyw7AL89rKGU3l$B+QrENji6HiU}J@kG*)2S=3wU6B)AXBQ*N3 z&Kks+-uFcH#I|E?oH=1B&f4M7RVOBa8#Lf;fO=ya&?J|MFK>L-X81{-(Atg`7OPiJ z4iqXubb(1?g&OA)F{My3?aVr`gO9;OXV|e1JtG#&tY`mbdxCkvOb8RM@vg@h3-F#_ zBU}s~*-{lj;Mn2Km&$w-fon(EKT*!nv14vYk{&(ap*#KXwHxLsLGLJJcd8$1MdQ^5 z?oDvl2x$=^#1$UB2jP6`mb<kd8T)-ymA?rI{T^(Al@qr{EUansx{?BNA(s6cMRJ~? z1}@?A+~2*yd70f6T)Rj*rMCh_n+N>>(_p6d8!r_TMr*}GKf)}Qp9J)?%|jldJN@N9 zZtVYT6Ml-$$U+#ZYe>(TCBL3{9=!drX|b$(i%sT7&kubcV>FuFU8-0+p=jee@;RwD6XiVwm zdE*c2!Ri(|x32YP=G9>%nYsR zZ>Q)U<)Ok%O=or6d7?Q_RV73TY)J6d=y}UM+B*yR8h~ci7<1hEsKB#4k~UtOl}dji zvBmmSP}U^#FTOR&{9KT>n$pdu81l(WV>0>YAh5L21j+)D%v~#8CmZGSTtc~xel{kZq`5^zY>d))upX3i%69=7kv=vp!bLmh;D|StY#AavTb2Lxv!kWIzvGVblh-^2w z_~u(Z#Gk&A37ZWt)mt!o?axF}&x$-HSBVlrK)K0Y?Ldi{N4((fue@IupGKGX9^S+$ za5i9fyiG!FG@8`{<=dgyaD5C5i_)RTh3KR&OhH8Tk+qk+$7Ko?PI>;@Tng~zI;)-Z z)}>m5k@a2&>#^#I3#X^g=`B)puxhCK$sGQXrK1{tykPcC@AlA!*K2DF9CXW7e&Uy!xUDeUiY83_eO-n-; zaT%)MtUOL(<47SG8N#)h^k>QeAueSrt>o$bL*y>llXtjpI@ux%d}|303*H827H6Z4 z;a+L>j4ZRj{{VbIgTE48Edw+j-6G8$wdj#*@p4((kRJS= z=Ew|)*Eehw(;f4kW4V_EFvF%e1z1HJ?QqHsj!cS#=6_JMf+@Z-@mJ{MLq z-8#Y#dS9;vXjRv8QZG``Ff56>R&^|V)K%pvXR++ts3I1l+?z|=7dIiUCfHL%t6r9D z5Tt=F56_0Ruzw=%YBDzJ_L&3=~ou=3#1sdz+vx+M)^M*c^# z|J1UG$T`j;`g%4S!Y0%fIFNsH>Q#A1Lgiy3(H+6~AF%`t9lWwWfQ%7rQz9VS8OUiI0QrEnlLX z50ur*U>2@g&HPd%V zg4A$3be&B`jL7|jzsirYh{XZo(Zy|l_%V@d@)#6so)AQojk4rnFnME|=Ob7YLC2=> zUi&oJ_ee%81oqqcnUvqkJqP@iHn#=~<9az$8%sZ9*Gg~YPlJf?kCUhbX{gq2gA*4} z-+!>o%!MGO4d*Ql5rYemL^zAIHH;{p83UI+zV)X(JQ`ZL56oKhSm6c&g;ZVDPK+<)K9;eV2X2??4A8g4X9{4Cg#P%l%8!?^x% z{cOS!8T%XeG>86KdrZCyfkPP)?Q&kG8yYhwX#^-x^%RhBrB=?{uE6T>teps0txbKV^OdqNdrupy;ok#XC_@#w8`A%D6# znK)*X5Zp}o`X+o*LlcS}oh9t`Ph#oB7Bvl;#RWaAhVar)t63}`9F0V9 zV>*qkms5G=@Rjq-&5{BQQ$t}3MuO6^VPM0uflVAEq!#V`DuV)s77QI^uh%|=;ues3 zxHc$>9*`^+9OS08SI07*$giV2#eY*jNQC7m6V{qMR(@o|JPSSYDDC(ZL2C#T{V zg=L`1=YD?mbOB)!Xhs}1DSS`S-cDlSJj^C`@Y$J~ms|2vXDI&?6)m+7TOp}SWAK-( zrtawERJi%;f@?JXGZ(=)t4PY8LGVtzuK<$?iC{SznU=9dE>`xpq`kXcPqZmdqJga*{9cr=Q`6VpQgzt1{ zlQJKmzL@XTVyC!UY!kNW{4H+NNY&PVK-)%oEDec9{(D#k*Wqf^#p8zh($5akAVzeK zi_?r9#VqTQ)~(CfsBVnxE`PE#DVWkOOG?@4ZyKd%CA$#jFE}cku$ZPnP5MRN z_?wV9+4{v#!N6t|$iQn4eNr=P#sh{lmmKGetj5k%*n%*}@b`xbV+mIwyDPyL^!5Iv z;k-osZ+;Innjdp}YF8d)OM#dD4HCtxm~^^RCcbDfu3V9cFh^VMWPk36EPh?Y@zWoM z++pbE#+KN-rp8dCly|RKioAIu)D85xLrZ%iE>ep0nUzpb6aoainS3PtOu1BlO%Ycq zkWADIWEJKyCUt-1t!WPF>f|Q0-uS+9EC*REK)NwN0XxX4-wzo-=VZX3>;~z!55<_v zpSq?~)g6SmX$A}R`G51ckZ&ARTf@RN*lw6To-TCh!dZTYW_7qASntL$b$pJTUTp4Z zeSeXVKLh4~#1IShz~~g`XR+O@To` z(%$#-u2T}Nb{CN``6SCAdZ4?doqjjo_$en=@6J;SZB+?eSbstwyqEF1s@VA z3ppVQhV542K+*^uU7`i!83#)i+MW!81|FjUs5~}JG2df~!vm3xw|QBIF2gW=W{Nta zN7XbEMwUaCQCKKjw~D)CTC^0N2zh4B#-f$A?#gNtD_d_H6bA)_8~}Cbs}tqR#i;&N z8!Fw_k_}a-3x6r7M5dOH94LL$J~9nX@nMDoqMsQbg)rZEgWQPd$G!YW-yXxm&E~V8 zW%vwY|MIJh<5ng8mE}Hxp$;@Bw&Rq3Ct9C*I_IZOk1Dm>3J)wkyeBkIZY6$_RoNTIcbJRjiB2Dh zV%k0Zv411cu%T~)Bs}j4?;Hi7I`*+HCLJ+tL_Y;Z{JN|}#x>1%;lb80@mIXvDOL`) z0IefeNJWBC1Nm8E8RdO^*nPd2Z-fgG&1tLIcl<-neA7YRqd|=R%Y_cb`fu7x)tqu{ z(rNKTs)%q6yO_&JX^A^byL3OaOyH7d?k?+E4u7@q)v(>=NxbkxW3RclcFSe3`lU+S z4!HbW%#rAqY>~=R+I9Q4)Nhkan=IsS7Car|98X2EWUPyU9Yq=T><%Ok&M6%sm9Ccl z+BeU90ys`c64Zl-UbPloge;*k52hL-ei>O<_4SzVUTnf1-Ut+=VNd5Xuh^d#aCSmse(8(EBRNdFM@D^0g zaIXUf+aUuO;pH^?Tn`7{XV7j^NJo^gKx^`Ss$EPBj)O7oI&{KC-hT^TqH&Qny+K8$VprQ_## zPPofZ{-}n*7tDxl@tbGIvgF;EE7N+MTx$%VN)(WkE!23cPbAH#W4V)wf^4TOKw93y zFpJjQ8dTsZZMs^ikVdxQvU+Bp>LL@zSqg2gwR|K?6!sY*z$x>b!4Z6}D$Fd4Hx{r4ofh z)hT5f;a^jq;%}<*FGbMR$uqhEvu+gur>4|T^C0f`M2*jJB)kD|eY`sDm4=GgUUlM; z@7==q45rVx2-)T3y9715Lrv+61U2Nze@t?23U_;x|u4^|} zj3{bai$eh*lYyRyfRPA`oPQ8v+9tc37&|!w(WOz`o{L&#EdG?3{%dQQr8fKA;~{Ub z&y95f{#%~TX;*&)?@DiSS>Wpslcym#1DjWRXpZg*1M~S^AH`5o!q0~`#?+&>gI;mE z$Yj&vj&D}FF^KEBXXXWN#s<(S9^GLnhxq#2eO+%L^U5?z55SmV6QcLX#8IKRfIy}?ydCYW;hwPhHyJxvV%zKf;SS(L9fynFPsX;N^Q zBa#VA9|v@TCVd#I*RwsKDjc!s-6L=uMKwa-XGj}i#zf`tet-Km{w63kV!eXkUgdn^ zMe0WB9(dn8rf%n)u(I*yN7GLkV*=ys;56{6SJ1Snka0X0dLLhZ#bW8EHKBJzh13b zdT*K2cyGB;64ya`;5H=TU?=2EUbMSo*76ptT)-~4KD~z|^;9#9DNw#zt547ruj0+D zYLl8{)qkt;Ix)->f+$92-BS^C z89T1k>}aVY*^S~yyMu!}H4xO`AGSFVjjLy|a@mDnFLFZ3p50dzPQ|Pgyav4#18!sc zXh}gKd?^CJ7>;z>F{T0dYG)o4S!oj%-2BkTbd>^%i=Z^GZ3Iyi&bVD08;ca?%ecs) z+J7OIXkc-aGf=_uL2)S5#s56DD3j8vY14iBBloi6drBj`b3Z%8!ljKqOiV(Rp9II| zatfPG!iMjh8&kQ2R?Gx_>(AE1;B*=Cej$7nY!u(e7e0uIc(eT z*jUjR7LaBQpBEtQ;B6e=)>0fNmp4G;dw-as+qm8uSSc#Z$og*k)J9!MXX`3BWV3{9 z0*8Zk+Wz&80{rkoG)+RbJ(JbZa!3o#_%adPSF$!=hr9w%`@2Wkn98dbp%0fb5A9D( z`Ge1Eav#sqW@RHrf>k$6R$(=pJ3R!c*LOU;^4@wF#CcgXCY~B!k%#*?EzJGmRDX^M zU=x%@%vF2X`8Z`Pj62AEKN^;aSHe)V7$_V zUSSG6U7aS1EcX@R2Hhx2*u9$mqbU)kEx2aVV@0!iGYFY_~+ZS%0TUJgB6fNeaoybEcELF#u^5=Ok8&;v}8x{lWZ` zhqIGZ#cKL2n*yn!%1i1S6-+{*!MW}&D=%9h6i)|Hg`8& zSb>YLl3J$K9ia*Pcdq7s%71e2v9r~aSSSI~H=mqA;DX=9dPHYkGoF}`ofTVJE_vLB z0n4ah4udzKium_J&{!fs89Ugk3SDHVxAiWY*ug!SqPY!av6AzKFqk?Wh1=bpA3Njq zmhv5`B22G1mR5StF*Sh(=W#I1PZ~@K2|2z}MdOGpQ@vN~SgP6#nkUr8O2eTPoQZx^ z={7m{nqLbxX)wFjx)dv#kI8f&j(jGa{|}rT4U<9H6B;r%H6Sn`Z(?c+JUj|7Ol59o zbZ9XkF*G?dm)402B>^{=Q9ueQe|7~_6k69dB{4K89V6Y$(4cg8r_?YEFvJWobc3WQ zARUs@h#=C^A|Ndx4T6NU2uSmx-uK?`zW=}0|F2nV=A7r*d!N0}e)d_zdS6GMSJoD3 z15-jGP`qG1kOWX(Q%@8K0txbgKmq_(Rs%T78TJPSuo}VKJ>W=$#Q);uf8Aja)Gej} zLEV~ZA`w6}PiG)l5C|5L0Ele$3)JKTsv!|D4*;t?($&`; zZtsA)J>@@3AP1Ba2o@I?<@xOnly!l*!=VraP!oc3fVteB2!%KU^^s6G4CVW;5F8I3 zP$*XketvInZ$5~N2OrYie_o1{2j~q)IRN!w9x!(=m@V*Exj-$53+#7cd;nIUfdky* z53G;0LwQ5oVZd9!84iUZJZ>F45wJE2BdGL9_oqtux|0~SxB`YFq<&iEfFa*j2@GCzBxH}Ab zd+WaZzuW4BKzbwm|E%rc2wS^fCD?kp@*5)HZk{kzg}*FrA;3SFJq!gD27y4L;vgW* z4G8mrI`IDrZs6+*fBQ{>f5Er;2l~4rU4eGDCBOpVcCgzYfWHUC3kF2Fd%^FoTQ<@iPaA1uTL?(F*)f2&td)UEb4k+&0o_-|8V*q?FLgxSJ9UH+R@ML}+7 zKo()|{P!ioe?64oJ}_GyI11|UM=F1C!(RjD3`f9pkRI?~4+@YM3mQMWF@ z+wuZ|c1U-?uYQ7o{0cB<6yz8B8xR5V>%;9`{sDvqe}VjV@LN&;4G7!c9 z|LxQE&;HiK)!EbIACKEpP!8^}{}lsti+CgdaS;RZ`@!7*0RJiw>gn!&JKnzqcw7B{ z_P^f}7|aI-16m3?Y^%I5|nr`B}WUyG>YUzUI3eQFqI9$GTN zns4)Bl8Ol%#Y>ONMRwprJaK$7PL?}z!>E?Xe+>xSc`8`sZ?-J(>}=9+q0&IWql21- z+Kh@G^O$UKjLlzeGgXc9vwvyPV&R0jXK{?+dD+Am*<%AdZ?xVIt_ ze-om{e4j>A@|ZoD@xcAbtQVuyETi%fb!yf9NPa>_T|y-y&9^~4cKj|3v|Rb{CmcCU z_u*xoxd8PLVR9*gp2AB!+aw+}%Zj=PT52qwgAt1`%L0Jk1|=oUCoWpN!#eJ0Cx^0e z3`cG6&DMFh9Spn!CpMm>bt~zRjKS;ve`qKJQxZb@qOW~c27FzIvT@u`VHcyv73uOL9AHzzmdEm?Dtf#y&E|# z_)Hh~Bu$RmOyADeQ;1+Qr_`rwxw!eu(wNrS!|U8Q@HFkGm3)&gPAQ_4 zn}OrOfNA!*HG_;B&a$9;EUK)-e>ZN+&vjIpYk4)vl14U-e4K`fx_o+eWES5|%w?0C zEvbn(gzUdsnU!>qovmIP9>kU)X=hGA+Dv&hFWv>g+RU#QkBIYk(Yx|{=s`*Sn|F?( zIF|urpCELMyK~o07PZI7}H>&;c~=} ze)3h9{F%n{k91*#e(KYj^e#1wLq#=3*$0=?c-)rX8mGKuYu^EoiUZfmK8)pFbUV8y z4XQq}82vwt-{!u=={uj4fAX1??<#NK79PV2Pd?he@0~wx`7Mdy?C$jYqG_*W4$Px5 zAs*hsFj&|3cjGOExYGQ3F{?Xi($5rX-C%B=sa>Qmo>tJ|*7D}(mE!s+?(P9uj_1># zQX~{`2_oNpsY(wso!|!fb8GRPU)6>5NR32CvrFcMHuS2hUC?y{f9xy-ZzJb%G+NyW=q$Es}%q2mcNt&ai#wAaV#L0sOU&C=KCM-(qN_n1@P=0#$Om(x5r z0=&hNy~CNQ<4c4u8XY)qS?A(OtF)Ir-79b&o1a`+?Gxl8(uMud$Wq-IlX2M3DBkyH z)k`MDA~9lRlGFV4f1a=J8{W6cMLV_&QDM z&nn}{!ngtArYzJp7v=SzheuP=_lbyeKX22itlNLKyCm-BmMkar-M-yXe?pgvl!nw#he+^>#*bbZ}x9!0rwX(<= zgQfTv7^GN5&)E&r(O3;1Bo>RXb(rwd?7OeV)C{MbN`0*$W)xz>Rql~?FES4h$toqv z=+oeYd3P04CC+!J%W=C;$R$8G=5q1`BRahRS!v7n-&RV1{5`2P01Vv)qp}P*bB=-j zZi2>^a%g4je=im|uE?oOi_rQU5TGgJ_j;T0`d_5cJju?`X5SNBVeF)t^)Ob~r$ooY z6A^D$CqGKgv^LJ>^`>)fC;8WTyq4T_F%Jt3OKJBcb+%M?(CTBH#+JF*Ugn@nOYk7{ z!D=}dxtBCUSA%79t{D}|PR6x`ThESJUfd(HCjE77e;d&*o7d!@ol~8`$kUPmj`q(| zJc-`no6_@f(GsF=c3N8JxQpgZp4H?m2+}+wDaUNjom>B6u80;(UF#0G*~ECegqv~f zdbK-*+Vx$)qgg`k5=)%{(EUrUAy#Rx8}v^)I?Dl%6f!FKQuk0}s-)>uisP+&=mYpM z7NJk=e|pY0jJB#KlPVS+MU5a>g$Z^y zxR~7cPE#A&;~toc?F)Mb?X5kMVB}Vo50N-}qr}amMFJQdrwQJUGD~-%PLoB+=#K>K zoQ&kU%yCOrmm9q&SHU*U(-~bBJPf$N$a8hc05P=`wHexqZq$EnqwafTWRkO=!dHxH ze|@d=u`SSjvfj7JG$^m|EtTDDUF+y1>%G44Q$NPz2xZM>-Jl7{XF3D>3M0;FUyn3M z4P1LoKe(!`o)Az+TR|6fUr6jNp*bdfTP)rQV=?ry zmh71=_A!jz>azFE8cP#bTS78B2N2`qe|hqlFE;mmnQ~%qx8FE2bN8B2xCj8g4!BgcFte@P$OhHbA=}n%jnr6Vssi?( zFtkQe#^G~qmD03j`FbBvT#=9xsOJ)o+&?UsBmz}!ZVR4bx_M!x@hMeV(VNJof95L% zo;(pYmh-j5API~!mYNtB@Y7ClTgNIX33jUvFN~vQ$^k}PyQ}sG_0Kc1lt_83<1FqT z7h>N5Rh!C`o;CNC3ZIv4k~H|MwmzH2kRl)Sy|WSa201GKc3~%+QC2{*L+(s^ukc+b zlU_7wHK5bps-GvQ{^F+_pJD(Ie}NnvNiz_60GBq2wHXu&UpNXx{ew5*v8C>I^1g_hW)4VvM(`kbc;%5E7;|m5;7N-0 z5ui>+23bFhICY>qc*i%Gp(#693GNWPGp_LWo5gqWGWvG}Y&yvV~(=(|Y_(;H@+ z6=H8p4gVY{TBK5l)+;o$e=m->>{%b;@^oV-5>ZVjbY}vzpABXaL3@0=72&|g?E|za z0p(Ub4CDt?O9_qFP9q$zlx|!Ah*dGJoJ%@WG{G|_K6|vFZ-V-A)0Ov!(hi3_7RBD- zaSyL9L=vW^z|$LNzA1<{^;0NZwwzV{U|xHDJlBC#ywKDEje}gve-Pz^PZZ5V-_KNC za8J{Vrhc@-Z_)jU>ld!~K8A3F3a)^Zd!8*Bke7#G!4$B$XVjh5X3TiBUw2pU!1Ex} za;M4St*8KV{WS%;dL2ZMKM(NrvMSs5ncQJ+EPfn+wZ0n_LeINL;Xc z0%@^t7y@ISJPbB_+W;o2JUUIW5Uo#JMQlb~rL4CTNs@@foNPmb7?`bJVIeiG8&#LT zK3A5HrH1w_t3K81;;I0Yg}N``Ku9THY1C)5SPGsg95;A+coq1PSeTc~GjF&w(K4@Tc7^LN; zMvFr7hJ*oYW7K`uF*cGb$kVZB6pf|Or`a)(Yrwj@j;ULH13h_{9qql`X+c9+agMHt z<8vHOf0DhJ`*nng#i-ylQw<(w#jR_v@PVnTMltCSVwus0-$-ve{I7_0RtC-3~CpTzpae(B41Et`DqWE z8l=iwtivaI`OiOWT>#aoE$fP-bg?0Q@(l2N|2XUi=wDuzk>NbHE{WQG0FbFQmR}h7 z=@cVisay7bUaZApAT;> zT)2lM#KZG6o6~H=@{)gJRdCI35Q!Y6;58QXe|(errL11Er*q2tgl{y?qo+&ne+zFa zeY7vQW3+m4!S3Mzr;t~PZ7E~IVtc0&cHB(b&cUPIgEs3Kz_Q?^SI24GgK+=U9a^d& zri^X)#LpS%;`R`gij)19^zU<$`~zPU2$44aXe?|VmRwfP&NgfLpE%5!FHr2WP`a?0 zIcSCAJiw`~XMQWIEFvde&)Cz;e@}J;v%G(otr+w2h&#rrY-c2mXhyaby;G&QbI%}{ z_z+0)Ua8jlFswPH$`v^4N>0S^RJ;Mj11W>fmH6UJKTn;kESPolUIkn-@R4533<l3udcikuof9l99Vc9V> zx_Cb-?rQEY5XE~0eM#Ux%;l4PX?fWLo4R{=J|^s7*r3QtQOLNsuEs|G9cPG+lC{D! zi)fs{oO>%~KNH_@R>q6Dh7~`GBJ%#$IK;(K!PN4It-`ZFqMr-%g?pyw9`6udtYms= z9h1Af9KyqXlJ?~BLH3aSfB5ML;!Rn(qTlR8n>WK15d0s$elt-kwA^HGZvW%l_>H`n znB!LxN=n$=ilaXA9doI`%RpM3`jk}JHj^noS{BK)~a{nKqmex!i9OEaq=f06O3#a63?T-Mqp zxDvwe@MAQ0axzx~69Z1y%(Pkzdw)LLzR$cwsQamvSiU+nN3|W$6ts?{{fQ3@$ia$T zVNnN@BYFdT#Iu{De|IOvUw*+k^oQsq)Y;sjRHx*(BXt?Wrs4s`OJCZFyOz3$CGd*) zkr)p5QQ2c`k)-o&DBBin5)wIxW_7l_i%1BsML9Uirh+IU^m&g&au43R#UsX zo$)JL?3(_Z3#^Q`i>bSH34cVgzy-ZrJSi6X!>->ZARTtfT&`CR1bbgL|y%d{26*DfozEI74Er7UEiI4s!ul(Q%VGJjbW zO~^sJ=Pej*{w>4YBxhB&uRSYRD9d`#;`MH7K$2JFYWS=GxScZ|Kj$hU*S1vzi%(Rk z*-3t#e;ExtttM=nwN3@gR_?BeIj0GC3#&?P3Ss<$f94ftK)ckjl%v%XAj zPNh^Af77|Lji3N61=m+;26P4@W~|>YMpf{jB$quX$MQoz!QAXw^Ls$9WRhBbP%~YT zxE}qZtPcf(-IM&w&~HLBQ{}sfXzGiXuPtkX@xKV#?6b&J9Hz(8k!eMKTcrD2b3C_e|pt+eNd^#Zlcr&hEXfK<8w>LSConL zf0bJC@IPQ{s49~oH1Q)P_k$Acy0;8equ7svEJp`4NP^;nN=g;?V=Vb`&C;EMN74H5S2xkIf@k&`7G~ z+mvkfe>iLEqWeANV{9H+$v;q?dyQ5t)@bKNP{BJhyo|v*n^UA6Ixc5m^c;&)rEJcW zlDorIEl?k@)c?lCwM~s$FtW7YG~xD$9@B=Ofv4@0#c6fUD*EHkk}& zPw&x(LaR0;Ja=5U0?S=rbwy|;`nT8}~UQSBIR}G`Iv|R!f|&hJ$+UI4}7>Oa3w>D8d^>?p!e;O&NMH6K?SogJ2T9 z=j{)+*l6&NrXf{6ea#GW?L=73e?FxPJ~FwM=Iibz^WmpCy}ab$^D00YnUB_ zn2DwNO*temEv6=ygjvq#W0(i_Iw33~r%J?3AFNoM%0_tlQYmgAO}X?x#X zBd)x2;J6+dYjEdBDXB8Kf3TO!(3&`@qtpOqr+G4uc0(bv1a%5BTei9Q=bP)|Dm(I( zXrz|l9kg8RfTOE@eSz^r32|+g{nnS-%;}jxx%07L-gHaBAJ*c2!}8!+f6r+3ch*!9 zGCs)0^Q6v;fsAm{ayFGJO>IAM63v5!h)7}z#+MhZC-Dh{L&|R`e_)T^NKONc?9A`B zWlh!>kJJR2^Pi4!H<~NvdbcdNi%%l`pfk#-cMpM#n9>=roBnw0h{AV>`bQ{Ficceg6?k+ zqTkWoyr-F~yZwA$e?^J!k-gJP4m!t)rvB-SaDsJqgW&S3RM~=ZUi{hfprt}V9eZkN zN-s8QMekHM>MfUY*yhiN^n(bjrc%@-CJzVpNHTz~-Xpn+6oTIq6}S(XS+%^EVg$Le zBc{vHPJ$9cEM~Yow%u#le2wez2MQk8!CXwPNH|KWRMD&`f8!=`x8gI+g1(ozLQI)3 z0-JbFpLnu%AebMagB#$oioTWVbTjuXR=U$+@|Ts*9_gWzNJv>cdQD&Ip}~xhB_e!k z0G5PcrU^Wd_vT&DT}V_!eNLloE=1R-O>(6_FB3C!6?KbB&0iWw9l7szwR${1y0UFw zjbHG1W1IL|f1ZX|5L|?^xPCQ4dH+tJKk>Kp2BNR&>|+UZUzLwelQ@IlemR4r$QYR= zTRy*og;oE-_M}_)d|u>r%7I)Y>C(F=ach*+a$OU5CaII+NcJmU$q@R{8$~>U_=MAqT?;r&e_f+aM2o}J4ZRfWh)iaS0NYXN zF1Uu{}+tY?0KU6eBqsTIE7>@TQRIyKv|YEMwsCYIr^d=ZeX`V}HcgKb=g5 z$kWoHV=bo=@!nx?dE>TEkicBh!=;xQ^gXdbA}z`rV6-(xe#T8#p~fn|tn>91*HmqP zsg_Wwf1r8lYZDtt^fvblsR9~9IQVnUR+Lux%NdH-nV}khIGtx`F=(w36dlRw8d|}+ zm9B{zW8W9{V+HABRJJ>Z#cY^N*Tsp2v%ibHIBa?L@gpy+C6nT3d@qYOUFTMdqm}{t zy&|uide}-Yq;h>DZdMraaX?w5`!tLn7wfP$f8+Q)ZnWX4Ez23{1XjrP&m;D3tmJnO z$jlt4bq2DD#47Z7us@J@c;r)96Op9>8kpX_f88;%*%u_78STASN`a7zpubE>gA#~e zhAN%80p4CSx4b<+k?1WpH;o_nwPwD9r~yYT4BOY}({Ge36nnLu*eq%F>weiFiF>8+ ze<6sek8Q6~&SGOz`3Hj~fytrmpxJ<1;2o>;c-0RjH^wH7~U@->dm1 zyNlTgj(7Tu^Kq{i2e+7oA2Y;mIf>O${J{8(BOG&)trOidZk7pzI_D0p6XgTL^pQs4 zaZj`_T!nkM#`#EWQ)Nw`3QDwrm>#xcq_R#P)2rVpSNm2yd(We+Mg(uxd@%mt27ds; zzoVg-!F&r788U}@YeLw&IIq!RR&i1=LSAVb1_1(@`7IJ z?GBK02D?E()-ZsUHNpYxjLZnKh5`)WAP5-Y^RE!>j~oyP7YRN-FE1}%YiD;}xSPE+ z2RFbAf^Y!ngWbVyo?u(Rua*JY*3RI+TI0oK0T?EZ#i1-k)|*#QP>ngAUaFzk=9<{txYz+Z<0;OFK4Pq@Fle+7cTemh%(KyYUlYnTrN zW)HA~K*0bVWldg$H-Z~r4YU1aXbp9TBmJ#Ctszir8>GSS(yal?a(V!3WQTwC=MHj% zxFFnl-67ClJ@WkugFI#>n5_bT+}RlnL%8Gqs!tK(1_mL|-G}e5;X1+KUNFDEB|8Yr z*6vpuwjM5gMlgu02UtzF;`(Ml+i~tA&#YIGf`2k>80N5Mk!1pVGp^pprxAHfP z>>UmRfnYe6^w z|Bj^%M=}=-VE-@Cp8$n_fgt1?|Nk@Hf4ltuvHVw*|0~h|w<2W^DD=0U{g1)_M{n&6 zf%^Pqfn=@+0=WfRaO5t){@2t5{AYEwz_t(%=l|8JA*_+xAP2KYGMa~9h!-gI2Zy*T zL%hMZx)21&;SX#6;6}gp4GMvQb>Z%iUpEZW3kdul9dgM)PRLt-#2rb^-zqS2hyI;c z2?m1O{#rHxVG)3}o13){E^^jLNf_YAkK9UIu=j5=1NeAha0Jo?fb1~%0}%ZU*xEqj&H)+FKgv!y?DNiVy>=rMkku}M+qZXXJ7g`Xkulnd~}t6 zYFkY;lA$|S9x*xNPs{oJa?JZlcW&@Xx@tZGMX7&7{*b4CVCct5w>_A_7EWV7E}9X& zL41&;M^E_F9NnBP#bo9>T(n1U>-E>7n@;zw$KtyHXF$n05o0T^i^g?xJ~^$(v7^Z2ac<>mLe1N|9-$AucbH6qm!q|{`- z>Wq0K$%E8?eDjaA_8Wi+swAWS$zONJb zp~<5jE<7WZ*Ryg=XSJDQ_=69hsyR8@fx9+?S)QfF7Ug_6^Pol$n%|2~!2rOl?_9jo znu3>>U6^U2E;Pkr1%?V*ex0DYd>WUX#4lixCIuCL8~prAUPKql;4)%ovT*$<4M0l6 zLaM8Vrp@TM<}vb+oA>NhKcv$1K?>}2yZL?la8KkRocTLF`N!Zy(~j)jzMZ7EYQpEA zh>bawL=bfvv+yn}j)c5~sUZFQJapZ*P8G?=vf^_SObNz9~hR2Hg1P}0@#)s z`JIm)o|bB}sUw6EAx*o9*W2=DAA=7?XIAp%Z;gViNXr7B~m8*|> z42@3h`WUof_38tC$K!!`y3BVId%YcOX!zvPkOku^)%BBS2R)ysO z@@OOT0c*|n(`Ib9o)30Sr$6xc%`YT{HiKO(w;Qz&Tz*!#$}0j$2-)Vs#RWI2wVttx z`=R4S83!ripNWy+TTe8G2+Y8EQ5@`=a5tec8VeMKyXMT#n`4OUuT)$P&wJ^XNn7iG z==jtJeL)v!#UaXKKRtB?mp=2E>WIAek%M>DeGlB-vM_O_RSeN;!HhB!S}i?^XeKT+ zOPKypXsWApsCgr>VI|OVzq+LyuA1hD%TMY3k(z91hpnsKgWA6hj(>T6WupCnUO!tY z^|)j|t0iFy_4Fre>P9B?f$|;2lORohVpM$x{?`o3c{WES)#CwNkx+bvOAA0r@nR1< zb{L(f-84Lu%Wj-1S8I3wL4CjlRE7@3xe~?nz1lKJzv`<+g>%Fv(I-f0m_~)p(8qX2 zwfnJerr!MAqB_$jzO_P3nMh`JeK^V-^pItLSb^aDP)a&=-{@topZ~_$nO=Z@wcr=! zGALSF=ZTm%dKE2J(MLqGs)<}#PxZQFJ>!D$%ET?cLhCSDs4=`gW6`rUZ!cM0Y|;{2wINksCw9<o~cMsT5Axx1i(oPn(JQPfSi#GgHFJ{*o z0if~GD~Swk(cuVdz^?*|PJR8zLJ*D=m8|dkiuB~f?weoage9?}!_w)a%|gGd ztabUck)4@DG@`C-q10dRX+&KMIq67I z?%!6*&KLob%a)+r%eruXrROV@U!71tWpNUSV!NW5FEC>6U0l5#o7s z*B+KA2GO{3!pB)6@>0Z$g`Tj*EW-`#>a2vi@ph*0$%}GQ3qH($QJ$axzo^N9A=&(? zbgt)g*${$zH{~GfF&Eg-;zq;N=V`wReC_fOlmiDA_a7DC4)XvgEwgLdMHC^MU#g53 zHpd1-yR6HzEl#&(rn&J@_m6E51<;gC2O^QAJDn)c9;;GJ{cj)Y#S;wxmT0>BjCw8? zINgb~7cFig7wz4DlEw9p)3>_@Ha+JU#GUYbh~p_5Rg-;OBxw|fW;XySj@0}7xf2qH z`e7DT%Q-f_Dhe`8EFu2jj8 z{nACt)6#_ZUI2xUwjaQ96dw>d-$ffcw?v8OJQ7~>_?o7FuTYafZ2aBnd>m-xq;VWh zHji2rlcT9x{HaxA>GY&2k0bL8%QcT{b`fOelh!}lR-B)650}(R>qG3#Qy$rREFg(7 z<_#^|Y3_L4#CbWwplqm!&{k%-&XgRTls(ieG`#P^N!z5+?A^Zd+@o#zfco@rPW6ku zSgZQ`>6D7UeVar7AUo;y=BaM@!Zk*q!C8KBuSHMa+exU8{n#Bj$A#8oqgIf8SzK z5edL6*~9;im7izP$X_5wnfNX?mCJvtmVL9uc=~96HAbbZ3Mv|+VMl91=DXsSZ?!M= zQ-#TotwLxd!c+@T!rn#In^qTbK<&%7RNpl3`%$y^ahQKgwBkL60U;j3A8SCReV3*f zn#TrL%_nk$YmrshQT6ZFsOOsHHd9-=I}p&$x-r$80&^6@U~l&^twQ>6-Du8+mtb&t zLWx~}NhgYz(?TQ_!=)-ehbVSg0)#1UqW2(#8Av~O8{AOYYb*olA|Z+PJ=qc)==bj` zmbSff^fAni3+`<+b{_niu}1A$`oUgdm^$es>0s_%YxX^HUyQadhEWPDL419Pz}BSx z%m|E9I6dcnhIs6N+xWEF^8&bIjnTfwIjOgQV?iq~4malLC6^6oI%_7P38FrjnTg=+Op9m=e|rQGYCgce&R4wXQxBv2%~Kv0(T6HN zRQeQ>?BY_R%vo7>R=1MrdEllqWjh8Fh21YA{)lEL9?DrmyJsqK*107;*q$xHIl7`r zZ-+V>N8T%*%xazND9J_dN8SdE#Nn7&kW04jt<~V%2{zT}L0vR%V)LDUeDXn#et`oA zfA;-+{C@qkVS6fZZ&u=>=GZEM`tHH;H%moG*^PP0p@jRR7fa0oJ&Z?WD@Ku5{y8Y= z4>5lT8;9-MO&Z1QxatN6TwH(jm%5A1M*g1Z5!Uh7?Zw=7&lW!_Wrz>h{F1_nOV4HR zBKM5Dmb+WZ-?36am{?&bL^S7Y8ZY@Ef4!zLV~&m}i1!fB8RJ9qTX3 zxaeeSij!MJ9 z8b+ox0cwBQ=sQP?1`^nbpsBQafv?QG;{G!!?aT0c9X2q0`ZzyVN*gnFX{LEG&h6)& zL!(Y*K7yC<^_WYPCBU9{dDFul1Hoi=t`FAL~RP_Ch4-rBPTxvUz}&SJb>!e zyiC#iniY+1vsOmV=W=qd@#H0)VTx;~@}wBL)$Oz#adH=ImsIZ)f7V^0vqrohtFPpv z>8?D?VCUlvbBO4Naf*iB+*e0zoD?^%rq2xT!HyA+Xs2VHj`^@<$_1RMIr2uv?M_>2 z_S4qZ3om^hvTxKpWm)j6pd~70Y}aGRr3}S7ygnRuIHNWFc5VlTNTRO*f6g!l@OYO4m!1^{qHhQo;7s zS|-Mjn@b0EEkBv#O};WQ4N+GVDBPVMk+!eGcCoJTB)!#z1HGE#9P>8U>OnSfAxGUb zd&^Z$apQe0tybK|`Y?Rg0Z-PZn&AtD)h~kDC{3D=-Rr#!e|0_lk|^BUTgPiJb@QHc z@w})mFEDzZQKx)nbg9eKrZE-~!ByG*(X10JN-6`aWKTQChS<{5W@|P`+B;#1cayN2 zsqrMnLZ7}q`!4x(ntbc4+yu6&M8oTsYi6qSHvB1#>usuoe$8H?gZh?cliAb++_*29 zmCHV*t18YPe;d=txEy2oOlGu@>8`LSOSOgc3=YUgVxG^R7pQ2=={nR0YB!iSqpJ;D z?L<9Oz&e22tw3z4;5cY4SS)5lgT&+$+sRHOyBAyua*qb(tA8RMh>sf6awpI zy3|A4_>z^GM2vWAfzn%;sHa>@8hTSf4im^jj1 ze|_!z)ueL-?<4~r5FUm<(F%G2nqili11HqUoQFqjkUq{5V$g`Pk3=u;-!AGY-y$TH zjm5PE}2pk0zoXv|rSL%pL z2RoTuITaU{cc6}#*06=X`A%O#kxNM4^T??5&8+sKm?qrTanXI2K#(X>8ZYZ1EzME- zB!bN}&6Zr8OG&iuPwb?vm6W&C zOVBA#5&Y4`DSuzEKGXx&hQ|DMRc(M^=Put$2NQhz^b_ubOy+m1PeTHD#L4ye`ij43 z)q|hq$;@>R4()ubZM?@owCAvie`XO=VsqGqbMvijr_yRi;L+seX!-ybI?*12uBW2b zd_1=THh(#+&Eo9{zKBA;?&J!~BEQ21_)%Sr8v zfQh)YU3x(ITL96-Wna^&AR@A<@~*YOu_B_R*Pp4h;p^%5#2MWD!69?ZOTKIAS~77Cn(%i-edl!?ltb-`^BnxkCZitH#Q^ZFh=(sO7FKk z7MY+5M{(v}nRGDVF?mdqK!7%;PQ~`N_F`D7Y;(y=`^$@ZYiNZ;H1nm7@T%@+m{+gW zM6?nxhEZchFnVHy$@0tOe-C@tTXA5WozeiiqzjYO?XVqamN&;q#eIKTVPrRWBL+w3 z$I*RQT ztf6ZXxaWz7>wERZf3SJwY6LjHOlI@&Jm;Qyj<3&n@-#C#n7?Y#X<9hLR$p%KDSLmo ztY4xOhL4GK*J0GA^i@*LmXGY${<{{VwJYr3e<}2;N)Cej(hnc`$lHjPLm64U6Iu^3 zWXmHz9i(CN*cPBKc6e;=JVEIhMg7W@8Fazs@qO5zoKbpFfAA-;A&#=Q{gvhP>r^U^ z=`0?k+ewK_9b0z~>{Jq?83@3(icA4KW(W1o7-+fO8|x8E4twB_Y6%~n8jY!1(T zC0pt;)qJL(D9vJYkL*OdxRp6+;k}i`l`0jz$< zyj+=oSHVOjf6(ZGo2dj&7QW=_o3C{*eSFMDgH2Y~QhJv8dCMkB?+wlAVXXm_B;T?B z9FRy&LmsG>|i8fh5OxV`-#s!7a4i@(Y*jV5rv6L1ioRou%Cs-Xc zX#BZI;v#JKS=@uwk`T<(M?ST$$?+F%9~D&LS2sy^MJC`?-_ON3~PvKlZ+s6ZfQW z>BASAfAl1;9z4vy(PQ(S4Wdvw824ilipIKcrE)!%EA77Y^~GaNPwAclH&#)qsdsOd zGR_FlGzeZ<^Ue|V@KKYa#4PxbgrM^qWm>ZwA zZ05xae;Li1x9lKzx-LV84VqrleDa()`tiH1f86_wbZUEB2@P*vD{JhXMLb#N4|)5M z8qOLlHOu4c6(l$jx4dl8fi_gbOIQi}iGSqMje$Fb<{1sOi{yCH6jLf;{N{t6X<;`! zHTxn6AT<5p71=y-jPXerBKyueil&L9CML@dJrIQQdiwq%5&YDLw=II_d^wFvFgV|% ze=GbA*L}q}$_7l*N1>xwDMD=8dZ@weL+$2J7RR3 zp9@X3l`r1*?SWX?cY1$6M5nG;4OfKz-jQ zgWV@_-CD@?ik`-Cnf)l?6_J||Dv8^}RSND73%#R>p69wRNN#WUI@OoX{7xv(f8b}! z5;NCAl<(10IUrr#Ol`&_X}sU}p}TW9>4pw_*pm$7#WMJDSTa*|%k}>Gum2 zUaR|bKcQS7Eb+fy|Et=S-3f7?f)@c39MVA&_LLgdYM#*mIvI62vn_zqhE`dQ<^ zrH88CDv&dq<{VF$xhL8RI@_I*`jnC6C8QpYRHzi%v*GaCd_v<%==r`fRZm*|Y=B!K zx-$y{qTk!XfiOyh!R`xo$-X!~P`$kUD(A5vbnjii=G% zB<_*Ji?fp~SF)WDKq7p=IpW<{9Te9tsiMvd-NUkMs@U!vki_a%l5|7$#=yV*Lf?-V z5YpVL4c{IlqYX4RRHm30cr@Fjfu< zey{jZs74%{?$md_z5P}2e{9|iT24k||N8}NJKj`vwh*PUq0r!T1P-oA49~rW%%Z-8 zBEHN>M>@zK|j;+6;kYpVFDBY2Kt0J$g!W8atoPx5N>AtY7Gx z4o`el{S?iY0%i43l`{Pv%2m(9)L~9a`72hs`!*nVAp?lfF$>Mn{^Eiv3s36ELTP*W_=vBwoWi8as4Zrr8}&G5Yv1)!-RM{}@5JFb zDSN0*t`$*PTxmW=o}R$vs50kT33jMQU@oIG8Ea3tA9v`N35kTBAgHrKFvAax{#S7d z)KutY{Vrw1n%=d^e=d|5)n45-NiV%fa82LMW7X7axLpqZKtUAmlKYTzG9fz3~0$#zh-|zf91YzOAlIA@ z+@v~UkR_w+(A1r%>S4^&Gx?jQpQ+Ky9^uCL*JmH{cm|Tve;ACoFJ60n;G)~=oFK{t z`(Jj|QKDaYooD;W;9K0N*SCIdAlDeii9dL+jb=C-MjNC8U?Wl34GS`2Yp2b&a zRcG$e7+v~dN9oTV*C>A$i&=ix{zi!F@)A#Dx-_{8_f1P4we|+Mq=_;D*mh~ zEB9E`!MEp>e@5ko6R-PPyWKq2z>$e*RzaN+FcOn`gtBSkD|eMU#?zW8$HYBn&m_*- z)OG6URATfw+67RGezf`l!@HN!k~xp(pv!c%%OGv0aD#Y?)4>$)kRi;%=q$fm`}B(o zmg~;C+&e-1zNHX;q9Nb*QFxUYq5PA03jxG#vI)zff37ke-sUtmt({r%yGAe8RiVyX zc42Fb#9J!pw>dPf@=X#+agdv3yX%oH8E&Nl3*N^5(z-#a(~kjYsHrpd*VVkooLH83(T3NK7$ZfA68GaxVuFHB`_XLM*FF*P_hHJ9-* z0VjX0w`EkE-PR=v1Sb&OrO@E+5*&iNyHi*ZDBKAa+}+(JxVyW%OK^9+dC%$YugAH4 z|MdNS)ELiRGS^&duD!=7N>W7?24Pc>v6%$O4$Q#9$jl3n2ih7tIVyu}N;|PYA%+?SFdyW;y~b>;P1MKb*~MK=!s~cHqAd|JR8sW@Z4er5V5+Xk!Kt zRZ!HDl9vQfOUkPOB+cy19E@xLicZEhKofv0(8SEn(ToOQ4srn4{QCef0oj=X|7m~C zk?}8DWU*BIaMUW%d(Zm604+i|LswgJ$Z=PUFBk(`99f5z{0Fe3L zNK=rB(?2c!%l8-NuNQ0tv~vW2&0K%M|I{)z1DFCG?QM+Q{?`5rX72#}7Y!#zpq<5k zF`x%Hm{}M(nA(^*I{tcy}gawzp_F9iuzw1fM7>68*@fP7S_Kt zO~8L^TLA44nf}=oDLZozfQ9+rc2g(&|LJo!bNJVQsQ=j+n!hBBOhI-wZUBE%Gjl{H zc@X$-NdWc#oyv^=eIoxiNc`U-@PCWE|Nq4OPmTV!OZ@-$KL01Qgp-YpypiqS1^D+H z1Ni&M7}){-zB2$>z&{U-lkNX2#mE+DtA*?J5w_U8=#%pUtRw-QUC)BGxLA=R4suf z)^`60!0~UFnVso>(*G;fzsNI5sVgfbD*jypu&SH=UvB@S6*-XU|2q5w zBO(HF1$Z#9aB>3}*w|VA-o3wscsQB8{tqSp1;p}SXE`IV1JD(q^S6I*W|n_-|37~J zb<+C}7;!rjkm)~bqXIUvGyS`1|I6@?+r-Ji;jh5|y8M5;{-5W6?YxCb-GtulkhtPkEoTfV$ZJnx>i*DbaNxuj=-S$%(dOi5Y4 z@D-M5qLs}7{^Ehgm)tqm7n9=N9>v=v>30-X8)_W{dUf9M302(T!~NI3;lY9a&MTPi zJp#JSCnD>GY3;Oj5J$$brbb3i!O{`M-U7o(8V&Y?9s#S0<0Vfllgu%#@-zAuiuPQ z_ruKEZ@Z5mc}0JMc+Q};Qr(v>{f536!>$x)mh!`2kwl2swJtj0j(_zDPR`_&&E{Eg zr@q`6G9FC+l#LE6bjueLOEat)S+Qlzi!)SkPnP$(k;ThUId!;Vh2VyWGXY##z)acS zNYuQwC}&vz5Fq$i{E5dn`UFWhS1>J0cSiCq@kP|EjMabN;Ewr4T!5$)gsfygO3P!h z$^p>fhDVRn{~^-|JH=Dqjnli1oe8-Oq{P5ooqApF|GIAt+B8ACttMH?7f7k7(QPF zW0|^?fuZiq54D6l*ysE1pR0`Axp3g<49DYE^Unx9cAaD2mgnpaUpDU{^xm~2Z)55` z)1#|4&AB9zd`Gv+n8fn?1%IacF1{%DZcMg9s*(a5c*rpcV*4`=AU#*|BGN|A` zjI>aJUf4}4JPBq4NLLJDjcZX|=v;U-vU_l*uv%Qd#AGh@1{y`v7!oC(6|=d-S`i2c z(pEb>tl(1!HFb)ptS}upX4)6|bdcVO^0*nW-9xCr`)(m5L4xeo)BUx+mj>#vz3Dvv z{dgWIW(y_s+76~kb7Gr_N?p2Ym=BgqmhJyEm|LMr*z1-ImT=?c>kc7%Qx zTx`5dsJK^C-&*A=IRVieF2_r5VbMT`Mc-{%+Z+uI@dpNQj*{uTRLPpp$u zgn0oO(T2BzjddS1>b4`G<7Sn@&XbX@N2T;5TY#nx(|1-Ac-3`JkP~;6hXAIwIr+}7 zg!VxeRN6h+Y$q!S60mRAe0MeOi4mcj9uLX2v$L<|=G^d2iQaV>2;>e)E5N z^%*Ad7%_HRXU(pX02MSK_6@JqIh@GxJ_2T zsKh*(g(s!a{i?2DO7FK)4d;li@3DWC^OnbRin>%XAqx4hWe(CuGVtw=KOyax}LxMBj-}$P^0vm(_HUDe!(OUo)Up6e-GyU zN+Z6;mKTmFzAv||P`zh`pEEGCi&c$@;1R{r_uhSnVEQf8kIr3_1osb|4_>sH&_0OOP4#Y1=JKx}_Ql-bvh zK(m1Y)AQnLISC3Iqk;Vd39rc6@Byh$6pdpcrPbpY2&C%pWJ`}3BRaTHjnq+ZMQEr* z6M{N83*u*ONL+kRo-6K3@b2bT+ir}oBk5jM^&|AS6@_UC#rs!9xs;t$JC)ft%FV-y zb?%#HD0p&PVwqNzZi=5p>Mnow;%t#2zSQzy`Kc%x{T@q^6TYzO@=*6GLZ%%53P+=O zAD2(ciOJxS116?U7^T0zmpp%~P(pUVQ-1)UR7S;}B~*%Jcn*z~38D#(jUoxt;CKo7W98dWke0AWj~nH za?k6>#rMtY$`?ngP`V3Sgh!;q|7Q+SoYZbd;zvU}Sg-<9bC-b_u01ovEk(W2xR;Je zqZOrVOpSFqE6t6J8=`;I@;*%>JN8XrWD1vp`FGw5xFt99)IQe(43w!}2?Z;P-=Nw_ zLUFBe!V?VHdY5tEhhTrJSU7w%Q^vA@eshVR+ieBl*{oJZVaMBSnt$!f8^FlWJX**& zbC~@~|7qQtIi>T&J0YO+H@I(xj5k&-K;4d0Rj-Vox@Qbpnv$n(lEf}q^N)}OElv1j z&~lIBH~M1Q@{Z$P?Jrpu5mgRNg|C3XFyBpZJql$fIW=eET&8x zbh2d%c6kdu@Mfyfk5FN0=cd-9gY5IsZszvUN-hVUC$i=pzlO{3vIg_S#PB6do?%-Y z_A|x_LZ0wVPxRK{Ojk!Y!z02{&hPO}tr&_zyM?5U=87!(-3BEQN{sqXb}e7Er79P! zB9)Hr#^`%k5qf{ykDjhGP3IAf_x3C~JV=gb})6RdI7nt4u;(Ctq%7Yfy5_ldb zcm0d#bArre&h;^9npWoe6I$;=`yA0a@z9TF#UyqOc)DoD{F&2W%I#h~G0BRf5(Xh5 z8Z#qxy{h%@L)w0n#c4Zc7wpw+Yvu}wsqaFvpG>}Mqjao^)%(2Aad2q2<^D#nC3-OJ zmq5Ev1@(W9m5K(adj=1E+UQiUY^G#9Eg0dFF&$u(d1$os!S<*6O#fX-u`Mahm0Lfg3ro{bC?Tvx6VnsM7|ty4eF{G z_0fN6(H1H)x6Tivedr!r69=>3OF1s4ah)JcY&hYTFSk<9M36tnt{A_E3X<{P%|s1~ z%9Kxl1DYQ#l8SIDDoW4>)uX_3-X(NuX_;A;LhBNv3oSNM`C`Zs9H7lCojW_c1s7N# zO}wDN_+D4lV4Ce#eY~<0?8xWT5Yz6cA5edCaWB;4B4r-S1@Z@mo;m90Ltks_K@gM} z2@e(?!7zFT{_M7lR# z8o?G#Mm?>3X(WVe-88tlP=-kX>EeXGi+u8nypxN*`%NytULYsjE>pX|?1h zzt%aBA=CQ`YJjMey@ihAV>y45{P3ZUH@T8sxA+sUpp!vsAeM-A9qXtuYO|o>_@GSg zE!wBG8{1!US*!vIg3&6vQgWb=T#S&Hf^#6Q@AWy;AriR1ZL{7A{&&D2)HWVD+Yg8f02@t@l9;h z-|JPATD=q6qCanZ2kk3toJCs5in44o9~U<`>H9dD8whJesN)}UU>IS=AG8ub^~TR2 z5#n3{V=g1lG|qY#KRf5>wIbgHI?E^!&&CqTL?>;OW#lu_R5B;rZ;pZa5Q>6T2F46Z zbe_Hq7;)R3%yS@dC4_%qq?83vS!Fs-A=M5ph31~5^F42Uzb>YAlgUP&>}!p>+5nPw ze3R@YLel=SoNoJ|)mJlPV^h)69NkhZ>)eFe~`;;PNFYQ&}a3vGa8ZdxN}XkUq_!o}F2! zbCj;)kE?9rOk{t`rv)d{#Ik)kV+R)+4#WXzqBAbY-rMl@OHSizIbb#=!z0gulO?KY zO@w|S)Xp`I?}@-0?W$_&l%f)LdU#!fnZes&E;ATJ!XR?bPV>A@F7}WXlrhSWyatFf zIrf6R+}nO?cG*majf?5aSkWtu0($PCsE(C7%nd|6X+D2fC*t;MS4A2T@qyjZy8P&2 z04iIz?iav-{aUj_Bun!Ty!&vwZ7~g9VLNQI7GblV+rwt>gSNt4*AELEK!ofYCw^pGsGpYya>FQw1 zpH8e6Qh#I&=b5F`qDQOB1E(oPl1NP{&k>zJ8@0oVc!UfI!;BTDB-~+~`$^wSNMmcF z2ahNZ6DIg@mCw5c%1#p<*fB1Z)3%Wc`Z@WGk3@eCTpk^>g#mO#M4>zO-bUW#0Rn@k zHoFXD?g`A3pE9EES(I9hTffED1-u6z=rC+NcGlpJ#5k&sduXC5`l<}q$0+n#7FLBy zF0ie2>lw^`-xVt~#C&{eq5^MF!|XsaQiKM}`^gBn-df#WLgs}X-eEMI7rR%Vq}2tu zvO0fge`P0LKU{(9L&>z%sy@(2Dqbxo4kpIRiWRH2)QijJJ`Ct+Tr|1Q+-*!S4w2z zDDe|%RBfiYi5(O68J`ej`QPK@jpeUAERY{JtlXEh=b&4}*B_s_y)(M@<6&m&O*m-w zuQE8>wr#D~mmuh2ym?a>;YANGFQZ-~0ITzXLFN`A=)}+sp!(W~`%kN4plibSN27lw z6X$mx8i;3*_!Wls^r_$a4Fu%|N_~e8P7!pUc@)U6xTu{^dK5<`y~?(kz%w^mggbD; zy9NWssX*-@-|7S*qqF0^!S*h60@ph_ic1VJk-((tdwf=eM?53m&uxDIX)Lz4?3}Pc zJF0q@NR{^&$OdFLtWuPqhJvWvC<( zl5u?iIWG|m3o*DoeRq?}c7`eKEd07D`}9?$Ul7Gt0Pq_|JU z2Qx%Zn(lTAL-M=c7D06yY^a-LRHQNb7kyNO`u7=0<@rg;4wqb&Xl*eWGNs%e<|!kf zLRXHkQxc}E1zfyy%fuHK-C%!?ckQ|KLlkXPByt{n5oNE7EO1R`FgQ^W^5}_)4RXg@ z!dOxa`+le_?Htx+MAhk`Sth> z?D^3j6O^*ysbxAG8oy@kSF1U6Fpc3=dAi#X7W??ksZa1N+FAn;}4V^n}kw_kNx9Yq>k{ z8^5$p&aWPi*16SSt_pr-L*Z#EN51q>sWKdciL{NI5x6D>OeEP)NWV7U6l+!dq?~Q5 zRdJ(2hM%)5F_2kcr`~^JE&O${0UP2UZCN&I+A$Ydj%qmx{9!*TeqD~)i*vXffW7FD zEEUp68m*K|D#Q1N7r3TpUGOQ?MsCR0>(02Wu_u5!xtY3xM#*TX*(4$_2<1TUj@aOk z)8@{-<5I7)_OA5nGzuH+Czt3TEtk=V-EAo`=ma_ya(H4PO;LZ3Zi_D_Mvr8s+;+3f zod3a>rOaG6bwUmccdyF75Ic9q7-zf&nFyR_+F z5kMA%@T8%Z2Ec#A#TEor!7ozS|G!N=vtt!0AB_p5|; zSVEk4tS{VxYNN-B|^gOMZ|fidut4Vc7;&>eLW6Lo$Z#+tN~xqO9Op zajI1da;{IrZB=lAWXmFg&btw1Pn*Eulo-!Nn>1%1a%yd4Hl|SRgadn;tnqui19O&* zNj8<&i#dW6n33PUg;)vSR2Jj4^}>W(@Mm-6$uZl=x%=8cZJ=3E#$*FeFJ}PsM%Q z3uq@ezxbK@$tf5qLGuVE97{r&-&mG&E<^ji6BU2>j@2`5ghP)=Wr7+bIX?%$OIe}o z^q4ntAz|&05-ho!BQV@pu2$3>Bs`Xw@_k7TL(S%nmnX(rLBse)c8bGc1gO6=CEOs; z;v>NgAVV7@ti_LYBj83WX>^NEeUN#sia{G1HwDPL?v?)IYjn9av^B8+2;L)t`t=%i%F(IM#nT zII4$ja-{l~HE039xeG#?ezmqma9u2}kA85U51PX$PvrQcdvbkm<~-F;O&3wk;xhJ- zG5(rctCxM&&0JpPq0LS5xZQ2|(Y;>8uoksZg%xJp8V$AHAK(SuoG8P`01I_);l;+X z;$l>jJ?~j0I%-Qi?Yka#p!;oPp;~_%@!imn1gIc!Kf$Kpb}%XMr_d*H%k=}{;FoNd z>q*!x`UrEs{uvMlfybKsXCZBgxpCHyh1@zx+tk8K$!fii{oLT#bZI*8rE>)yNEW(t zoFCWqG5K6Km;9woxeiql^L=XA*Rj;r+IgiKD+_yNh`})9Kg-Vq{3v&UrXPQSt|BvA zVDASJ*BX9V7RG``yubhEvWdJ9WfTe8NcjRDbBp2n^$G$N-~*d)o0Gk3yy>xnTx;H0 zuRg?CS&gZV*bwd@aMFdxXXWipn!|IAl9lIExL+GpU~S;9oC3fV?dW)yR*JtK8n9Z+ zP}qeci9SJF{9<#qUFdo7vn+p~eg^;XxxZemO~50zkXfN`H!SyJvs1JU1JJlb^~s z`K|fxTS74WGWBIjtNp~eF4kIyIA0@(q%QshBb%o=)h!pQf_b_Uf1MmI{f;#)%dJfB@N$g?7ebbjsu8)sIRPIsr#y4+VLppwYA=x(Hf0IA8+mehkr+iz_H2$_cF$<8L5nwZDj zF{#TZo`}$k5NJ*gIE+u8r_}wKXXGOXWkA(G*VJSN&{salZ%qH0U}l28Na=`Vjk@8lEWQu_8yA8=dX$)G9Vj@_m4zOxxomPh!d4L<)akA%^O zhGkOr+r8nB#6)NMA$G0Qgg5=KM;ScK7)%VA7u4x->GENC)z4WrJX}ncKlN8v7}@DW z0yV?_z>%TPS8x#YkV(YdK`PN0<~E-oInG!ra`MQ_Q6EbV){52P``kTI%hS+=Cn4F0Y!7p5 zrHkUNuq!+g8jzF+quqfYXkm({OOUK<^a9*jrT~B2IsLo^)m)8TmW#4*##0m~pgJ^p z9e1VB&6%x?}mvq&w6OLo{bDH zVsDZ-mXEe9@|14@LsX!h?5*G}#?3HI<68t5NEk8Fx^O0fxbJ6d?0z#vZ&iDZf5>sE zKrAHMQib)j{ocA}clE(+wayF`qX2X>Hv8jgt!p4Tkw9!p;*r{q0|)nFsl{TS(q!{* z{w&6|jxm2y>>7IJa#SDH_3$B+E>lPS=!u4q6@>Osr@3uvhqw0d zdq_?mlx;Gu+D--Z-nHgejbO4zqiu?11jiJ4{(MP%w9|2 zqI8xvA6%$BO!~?eSY(mY+}+e(km?j)JL58(dnSeJhbG+P&wG*cARmiabAM^4lZ@!T zn}vVI{YS&GA@aIO`{VvME4S2su`?cYwVB%XAc~sc_V@-R^q8A2!ROzb=53#EtM=PV z;*87Jkcb0dA?n{@!;8dJ)kZAP-pbDeW++K^O|@eKa&#> z_k1n6p6{H3<2T24V<nqeM2Ln7v z9U&BXO9%oOR1o_7UK+yWQ172C#CU(2YqjNTP}LG>rSe zIwAbz;fMYR4ZU7-3>G-9drmM1pEe zeX)G)RaOA~y6E7V(7arF7mj~#7(%-2{FH{7Q`66|tkWp!8Bn?*an|MI)$=LdLLj4r zLUc#IiMPU6F$)=b8`%I)?tXtHjkI#u4o9tDctPI(bW+xPc9;ub&6n;5bb4SkmKee%F&ze`bvv#)vYoU+Drd{2J8f*O2gJ8rjdEPU#Rc$ z;4__HBncQ?N~YY9O%(#{loy5_pT{}-6s#WU{gSzR=M(0J$)@&y@dsAY;LX2}z;R0p zVM*884|X2ntn$3mvw~<4;Gn0h3izC~#%64I(H$mkn%u1~)GUAI1r1Jj+VRJ;Y4N@Y zk>eN5x<^!DWb$;CCXG;tXC5z9%pdv{ryj;eEso(Y6)x)aCLv`yQI~@-5Y$QF|8sq4u!pS%|p%E7pP^fm@M9w7xaQ^+I*JDZcEXs zf0j2$7y?gbZ_WnnRu>4eFd-B$5Vw)u*K$=?RDpjyUrz+q| z&UvOL;$Duua!KEJUhNaeuAOIaUWS^_Gv~bMH6YXNi}s(C3Q_gu70+Kmxg>pKJ2YZS zUOsoZAPRg7Q-h&w)NLNSwEXgR6h&;n!3$TP3I|6)*L1$`}~R?2#g}J#G$wCLMO1lAPN6OmkmRd7+wkd-Wn>$vjp^?Usrxj0`xzcKR-aKB~ zFn@o*N2VP=5*9J-vJy*I(&50_p#qTNOm?(uED_#fPpe#cZCr__e&Ev7SuErw;gzvg zV;SdhIYhU+9g&c5aiWi3bqYiWt1m6=1#3innHND1p*rN(Zq!=Z;(N39?-6)1usN0x z31%7UXcTPfMN2oUe8u(q_}0f;AAC)6k}!Yy#MEfYHBIrI=y87p9>p@S3g&dd51%6X z&KVf^jt*Z95qQXajuvh+`P6j=)TLE#+3c0ds-Nc7Pr>z;MXA8!RhxD(Kk&Vt6L}1D2CJqR8q*m<};2SQ9yr& zrpq@1EBR)r5*~R$yWEp4Mie`Le)mrd{ir{I9Ko#A6L1%(Z zSYm8T&KGRTyS*$zK;u#+3%`^eJ%VB&F3p?0So6&d5y|GBPcN7)DWF;j|53xXmK)ct zgOi?OCdEzCMS+1f&ca@^ZSu<@6C-~po8QA}55N9eS1lDaZ~mGA?mNkL`1#y$fl-1+ zQ*GSGY*|arx8LmjReu`sC`y5sIYORMXJt=to*g?~@XhLl?r!y1iwx51T@ob;3R@8eeAv4=t=!YWh(HTXLfK{(<)44d;J#v6XOC29a`D>P|P~C zaI=KK;a>c3$<+pso(~3^-LckvUMsb|F&Mj!E%3X+*V#RYJ|pMx%YF%tvqoXo?8aP- z(&vS8jQ0Cndv7IouxS%Lk~x1&nhFK(Ioe{md7=94V6onaM;Kh++es6?7JI;>)j@?0iB9il?pGpx$ z!CRXlMqcAEwGfcqnFb~T-uGCuz>^0J@vNT}q-^YK8xEsTvjSrGp@wdAFdK`w7N)4u28hw$;2NxH2hCVza*nf<^ zgu?d}socH6B89yA?dZP5M=Pn7I96|o-h{PjxFuwye`&(w3`?mzd#WKQ^83h~ z@b~zU^cIXANiB~F4XiLnHJBZB8RdMUI8S0WP!V5j7>Mz%2Sc(QyL#F7?)|2e5T*4% zH%mvkMNd9K3AKN~AO!E?oc8dn-KgR9DktcV_nTb=CZB}#6||J4H2do`>iK)Ol0$yk z0FaFRT06z-?J} z*yQV!>_T8<4_x~$K^Y&hAtSTXhnitcS!V=LLpaFBfVV}lSS3nS}oD}bhg z?+4f}0vdn7UAZiekE2%iIu7ecY7z!Imc*fjIK0EQ)HmcY)`gu#R9(Tgu5ovFci*_X z6Wnd%4#8bE4gnHeg1fsr1b26L4+M9(obledjn{e2s!@&Am}`wS=B)qwPR&MeJ*{8+ z8pR?~C(Myi2)+GfkLjNBcahZMV6zZ~c%=uok~<3=Vk3*LkS&rG-#s61pi&82&XKBB zD#M2f>V$+j>a&6z2|+m*J6OWu)>Z=GLi{N1B>|lP!F6t~Lr}|f8+yvdScLP7q~na+ z?dvx`x$Hw=x^VgT$1;bC;IrH4Xn|%sO93d!oPm|k)+|pjhd%3{rOscXmn~Et-a!MW zr~B62uH;B2guN#4#qbXTgtg~QTcfW_;{yM-i8PI$=va&jFBqfy#FEO$uWkx}}W&@b!6wxvK+ z-APpy1$5CnfnVvFny=>sLxY}0a=7_dS3Y$kQ$YXzyK?D*Z?kL;NXLEPn{`3)kJJLX z0H8^T#c#JGjfCd5NMDzs{E;qhH)@D4#)xLAylKwG?Q~FbO z2P1T17eYi`6#|%-#(%pzH?uBR3i0o>Bh^hS_Z-tSBdX|1ylJ zESUd`)o(z%4<|Y8E)aaU#}QCBX|6o1yWTMUIT&+xx%}+j27&vO+j{C^{@_Xl)p%dpqO9A^qdv|@)@kOVYK0(=(}foua3iAk>o>7Dv7G4l z-_W4kxS7F!D?bYd@*dyOoIEqayk~c6xiHh>DvU~gCs~IaauHl2=cDd{Hh=eL9DW=x-I%Q^|+n0~8JoLU1je`qqO_+7#{4s`e+R4G2--rP!6g$(Q5etg=E;$czUwEZAEw^Zv+nR15LN!WH0{g0k#L`_l>Th)!3-g zEHy%5zn-o5CQ{B^a^hv|rAm{Aa+N`L#!JJVJe!k$anq;Mm6H<1cnpJWm%~u{$sNUg z*9-29(6UnC7pe+SZ)tZbW2#bMlQp2RH-{9h@fY}62Pe9Te>%=yN6X|A&^#ecwX3gOFQ*$-?O)>~( zbJeVeT!zK{tiMRPkdSUf1o>S;beZS5p2X`S@D2@y4Hlx1+cdGe2CDB5d zb%3o*>6*E&SPlwK(bs!KrLQQJ#L4R5H2elT++a0heK^^37nR<4ac|=d^O5#RMa<#{ z-eq$Qz)Dw|W9-Cty$4+Y^1rF#)=eS$jz#!;F{At-b*gKL2{utZ|5ur$=@ZCO@hl5h zRYwuPQ)j`0NzSYfR7;Pf0#>Pg2rA>G=7lO{<*)oQliM2-B4KM~byto&wNb_%*y|2!O^)nieQo0WG)o~` z4r9CV{k3Y6zp$B%*RKyGQ9?|2Q{@>osGP z+19gfOvv!EooiM72=q=J`3`aF>~_sqe%ac8QnC?iuhv$fb&F@&SyyaPmSxf^edp#u zOsNEB1fc(tgJcJgCzvyKHaqg?t-%FJr;+bqs67#%-VL2RX{uKS7L1cq78JCn-x8X! zO}lhRfAk41IW{Avwx-zK9kC9dVN$Q?{@K>Xf}l{4RcK`xEW*xafs)Rd4gsthJYl%f z1x*gGAeTwH`vfLK4qiK+{Sm*9ebp__9jfJ2v5o?{UnRoIk>0aPy_CP4mhaN$(Ymb- zX9Re8HVO1^6uP(v(FgnPx&))D7cIANyxmh3=D8_K4(i^L^1y+s-JR8V8i?$qta|+n z5J<30wP~c0mo8|kSQ*L2R)1-{?%oIZU)oD!{y5kE)O`!sJzde~(C5DUeXwzDoog6- zM)(~h4rG6XHp!y&bi5&hBQ9U*)pW1aSBo$L%FjXB)YbFD;{-$FiAT`My~7_Q{rwzw zXwlxZlqc$mJ7lBZUVv0Gcq%KcQQI#EY0|aS-Gl&9epuAt?zigd`Ss^W+b4jSTqCQ` z5a<>(`zCUT#%Kk|I#p6l|Jz)?vYi`8Iu@?q&&W9luDcgFD;0 zI!iy#9UoDEqTA%Er5OIbNBL(Yj2Zf)#ZmsF9ihgksz0}QHMpE%%{MtkQq$4th|_6j z9LBt@2{EUGv{Hn~{Yp(Bw+!x;!X z$_C!LqF*mX_vV2|uwKtLaQ-0;@#7~fP`OJKV+o&#UBGKZcLFd0_)MI$hbKKrk;mBy z*ym1qHk5Jn%p4wo^VYiSjIp0W0>&w@s3nu;)TXp*hK#U^X(WX16x+i0W7kRk`Fnan zNBLf{#{rX8otg8BXUh2WC&py`^ad1fpbfzTMa-K<;;e`W`3#{(#I%<4=yF@fzQa*c zK#xJ+d~jaFnPizFzkwuEh+SIR{~(efYukCJB- z4FTb;Tw~4QDHTv*ofIY=V$s|8C;DmGdLj`{6Q@rzl;Y#I(>vdn82OYx9jKtq`y2^m z0vqCupt`nZH7-7h>=s(?WHyqChYqC?n?c^_S;E@*p`1R}2gf%6uF$d5s zs$8b-{#8i7No{^1`WAxn9zXna!&28w-vIHMMUW^3WvXQf^lNwfX3^qv%2-`CIw2uP z1~D1tK0P(N+rKor&K?QC@SZ^wv=JssSj`S8t*Insj|h|T;(T_cW7TnnH(u&O(Uy&x zYOw3c!u6KscUbBiz)6NZ1DNjWtEjqvlicd#J6q>b#9woz%MPg2WTZF0&_&I{kR5XfCYwo|<=(i?wh4%j>5INXPB5U{kq#JuzrNS)gi9>(qd2DmG4{qmMMcOEqMzfsSy!gk$QZSLeWd& zd+AHl+Jbi(M%n>k-yDACZi1bYe_pAT=Vb%ooe9^U8kb~I>W*Zdy z=bxqI&teB^EHA9su96kr2qq>j(W3$%r|-j0_A`n{l|nMGhz|CGLG^SowuDx_{r1U+ zOLB5b$t=svhW}nN-VDGzhaU*P0eiSDEcZOQoQm+18;RFAA}&Lren9!DUl6XXnVm~r z&lS!gh7~q}ymw0_%EpjZ6YL2q*pd7kJ##KK)~eZY@(HAmu?FKsc>;}|)}DM#DIQ!p9ETtJk+8@=lgl9FuKKqI8#ioaeGBIXc9(5-)q zv@`aoXV|dD0gu5ceHLu`U8O`trW?Kr2&6D)qK>E_PM<7(TuQwtEm&%et8sZ48h+8a zWw;f640OHHI&FdtpAA4Y0lgnnR-jd%H1nu`LHnSa9MO24_MbE*gg=4z?3-&Fy@}O= z;o=l^Pv!V;p5lVoLbyEssLwPGJ2MKlyfRx;&#~KtGWr=1KWmtN&XC| zKc7{gZ4sG879`m8Q!>T|&jHMeM4Wy1Aty1J@(3cvGy4y&X(e>=mg&M@+ z4W`(EeA`5C!L=F462@wDWg;q7N`nU&Tn+e9Mk9o^OC9U%o|IpWhlV+Yeh@OnzFQI8 z);2kM{iK?CBPFRXsEnPgWl+rnhcsxG@eBZvH6As4D{j*m*+wE-N{9FFn(EpqQj+c0 zR0hUy1cGk=CH~8AYt(+M%MYc-^xT6uJ1Ap@r}KBoWyOS^eW-Zdnu}`{bV#vk1ozZ} zs}E$OFtm!Ji4A^F4eh(p%Ysp%3P7J>$OBU&!0>9#nZ3if$)7CFgwXq^(c%w~ z*}vIZFc8bNTUJD_%!X7^2GS_-t7hLnC>HxNTZY!Z?NT%o~pFQ&YZdmGyTCTy!f@6lzur1 zKSw)p^uY+Q5EsyIbZ!MEJrZz>qA63-v&`^Y!5qESM-=55Xd}-wzQ3 z?!Qp}mZo;ZDNeZmX5Lf3GVO#d#aD>J%J6*u8+`vOjD*RXD!K#?2ab>m?}861CkI=q2@eEaYE2h7G^jNtV7aDuoyxri+7y=Eux0Ezf%k`5OR8JKWm0s4 zbq0^#21fGAJ6n(c6u2xxAr)&~$EAki7!JHCAMdy)if9}e2fQ2{M<$+F8h5C3>jFmo z&YCp^Z=r)Y)v}YNB!?hk{#O7Ju+*oEQIdetkm*EC-p@<%yT*iUmxzif9)w_{M>hvg zMTE8pb8bz6JbZ~o#Ww6rVHgZAt&y;T;u=mzgVC25O2?9$0~O_#PxgnL9P7{bB$)CE zoBS9o6)5=VZ`3LWfeKR?`It6j;Q3T*ZoK<(PHB+hfJ-uRRry?`d|UG%S{zIQj3{fC zJQQm=MEE4Wa&ZWYnM5u48PF~a1_Yg}br^*!Svj`TuoxI}mpFvaG7;vCL4iT08H7OC z7(wIUF2s}$ES*4(*$)%Bx!pdr5Es{zmE17iNb?yQ8_zN;<;HGS-G5ukf#3vAH(q{UB={rOU;H=`1jl9P3a?p)z3VOx}Wpaq_ zeBv?yPUJWhh&vcTF$gFbwJ!(|_z+pp8C#l#7#@nOxv|y^$sJgIzAR4OCDIW+6n|+@ z2rvx*af?=kv@`hU4g{tYmMiT=4d%?o;)w^D1*?nLsBlMQ88)Vthcs`56l1z~cwfk)jSIdq( z1Gy@pm&d5htjeRA1CZzlB5(dh?vr4Mi`X1|5^*ZEl&9Zo%FSYFy^>p9V9)(qSrr-2 z&TlDzdt^Q}5oC8GFjg6Q2JzH5Z&%-!chXqR@Uu_#5xjyK80-rmdANwHGlXyMuxuf{RR zgtGoJ(ZNC?^hV`YD~vPcI(S!}E^e^lVc=W@K2QX-N~l-8sE2QdNX#D1usGAD@)_*g z2hXo+g4U+3JvK>;DPNBL)XYP+;(i?$0J*acan1PCkRnc#fEHjA&SLZEg_fsYXbjVV zCu{}Uk^Lqfz|f>&FlcD=dB2BbAo4NCT272KeOG5&`^1nea}LspecBYusnM#NIPHE6 z&NgjhYo;Z>5Ufb<@pDVe)Quhgc(+)_1Sat@NTp5$Uuh^#XiUO3ZPJqS)ioRC6xx&{ z1Hy9^iCk$u`1@R{TlDvN;&uh2*=4ub?mWj+fp+EXc}O2wP?5}CTK0_kOVEe3$ei*W z$6v+ykLAjL?Du5&I?S$&&oACv($-oe-CncNMhtt4drn_L^T;@jx zD4aUm{lZkCg{0_?|h#3~m-QETQzmvijvDOS=K*fAoz z{`kze1LM#gq1v5e+{OY@$-#dR`=Vy7`J?h(P`zNtTlfb z_O&+MC+7(GBAp4+$)AJQG@lg;tcaQHhhufgPvkCe+56(enpM1Hp^(5|)@7r26)MuS z^MClrCLvK*@hl7EdIz0cg039|=@|@^8={Fi#$eo%9^&i7Jc0tHasTxb1p9G6f}V0< zYQL;=AfUM$rwpk)D;rBnKrn_^x<4LrFX622nO5%>+&=&*_YI;WQD4XRvYw$lk#rLyHua!1!Sr=9j-5>J# zeciLN_7b{LH;F^fVDnzYG~RP7K`Jc-lMzw@T%CEaf0UIa=I3YbIBk9OTAr~Glv!xi zd$qZV!7qLL@f8(dQ3h=mxRE!Dxqd8EkcS0ol#wI;Y?$GVCa`j^5L_6Q$Pz41Ty|$y z>F0IhfnTJ}d!Z^9re|EJf_ZKs;t0k#%G(v>%#=Ysc8|_b(ea|*&{#DJ0R18nk%`SI z7@nTpKR&s3y?eTzEpR{ng-G-^CGa>nd4AM5GTm_gfLz)67bXS1XeIr1xxBL5e{);V zyXE;N=iq>y^3}%qdENZQ{Xw~&=hAZ&mZ+D;%(VTRTVnNG!rS!)oORt6>2${d*c&Ww z;A_=Bq0{OtVttlU&#_sb4oKT0@$Afjo7k#9U5Cz3?18+?n~Qn?{Rjy65lrvW>K{A~ zc`uBU= z;)NEkIye%uZaGfXK)y>2kO7vQmu~yEUYL)Uh7?|*y_j*d<}0U%*xPo_rA*CVPhL^Fj3q%?F-TT=;&aOX*EV->!ch zRqimQh#fUP3N(J8RJM0IbOtZiU#QGWxvR!JN;^n-;JZ)-zrO)!ds!-EdHr;cz#^5&?D8#S96}OB)vjPdiVp_a0rrexw z-Q1jeL+f|>VKVr6i}d-cCT6Ds$Lk2q7`xlwHI}p)9#msZ6-|1eALQ7U_F~2BScrT_ zUU}>8FDz+~xZI6&-siq3O~2VX z&SibOu1B)*%4YDvvA^w*rVseIe0g73*e=x#VfB|1Ns)z5T)QzRI#0hTtvrdkDK!an zV*JG&1p3#oH_{3))X!o0@e40uc{K@iXYf7{nMP<3OCmmwETxjNwAA#1IZ+xn<0# z3~~13>p^`I%)ZU@9|#@{+aP;t7~>!QD}_G8EQ}w3KV`N=k0#QDtJ^p(_}GORr%VVb zq^kiBCGdkB(UzkM7BA2VC)_44A3B3dPY(qLIG8U-IG>=+2L=tuDwDcbAZzuR$`u}o zf+&Q!xo9EdjYC2u5TV)spdsRf5&a+wkt-01nmfYKIUo@+u7kP_vy|mCp^F5+enYGT zDz5z4gBZktPk5wB4kovc=_3j`Y63&YbD?U_V9$kjbHDQY11&)iQQ&bVER!N>w)vj1 z8B!`zIaT$de;}ERyIhx8Q#nSC5t?o%4vNl^@m@w5R_Tu(n;jiD8!$ha+~k*&%`&v~PY4G-pP z;Eltk$4l6bLERqunA)*tTgiU9|8e6CXt+l2BlU(R21~`H>*NB{8TVs?K$9nZ1*I`4 ztd+5^$&pUJ&HjecAp8YkjKV=pE%ZjrU_S}CE9mt!NLGKus_tU-W|fK^dP`^*3Fj9J z=Itt_Evk;SKt&|LQ6x}rA4cB6R^(Fx2_={}e(MSCGs1!erV20j1Ch&{6$}$hP!1&&*j}bZT={P1 zLOJWT^hPsuih1cx63Dw&mJq=RFkWR@k9Z;)c!mYCAzgXeuy8ndLT{TWAdW+oAa50Q znw4mEF*!W!H$kxw3}cUiCRSvL=zICFfTo-_FI0yxJ&?}a04jv(qH$P%4r5hNw=EvQ zrb`UC^ph%HJ_M9SMc499WYjI`9gRpx94{t(@vs-%5a%l`?k`Of0$`^vjTn2v;wjBmiM8P|*voTS$uZy66F}ZlrAB>F_UIA5mgm zefCgGTAfvEPpG%x+`nAyAO8RwGK{sP2d{k6r*K2-?5(hpvd8GTPK-Zurb}5~y=(4C zTVX4#xYt6H!(Ec|^r+#_G1jhRd)a&1RjPqhb{~FiMlC2dqqyDBAav@=!lb*3MdXX! zI!1okf|uvIaN7GQg|2*cpmqg!c8_h?fFm2m&-TSOy`Zvcf1!!t#Z)!cP6P7bj&gl% zH`CQ}>@0@uB!}hdlO)bK89`PpHwGmJ1=}8uG6%WC#|6!*D+{@U+D4>-&m)5sY0JvN zFqUi|=cylsz;6|}pp7wTE_Ier&1l!OA@&HunX#~rc9L>j++zxUlK>KQhsr74rACXk ze66hY3fDT+Rd&PVWe0iE@-fp4iDw4=z4<%~eOm*L!TQ%V3?79g;O`ZIE;XCy{^H7I zhNeo;NXfpvjYHE-;R>TvTk{&ws;aBDX)3B`?ZBdAB|)tNw3blE!&22S)H!@!S&>WN zeTbmY=Y{JLwx|0ngPBZSPVjSG!7;y35)qiYQHN|7s~wMODrJ>Opfw~S^KHzPNsAe{ zkTXk{Up;Af2pyT^t;6F2Q6`Cum@|!|{&_}Ason_sd-%^wSMa0C?rO1edA^3ILQVS> z7gqVoX>!v56iuwXYcu%j21UJ|arG!n^kHTPI;K>}HBJLgL?UqkUn0l|4HA$q8@K5Z zHlCRcGdTR9aWz)+^iLPg>s( zAt6#vv2wx%^*b*&$5~nOm%Gl#Z{BZHXPatvII7=31rw%m)79ap$XSyzlwY8?PO%;8 zwaFmNYQy`3@NPcd&6hWnf$eR`>#KrV%jjeTOd>2Ct$_Exlj25B=!_FaOAPzvMfJ!u zj79h)=Qa`DEJiCLg`}s)F0|m?I;6mg;nXvk+ncJFJ$A;qf5QF}h~ZUR_bqxCA^TNE zB97jmx=GtIU3yN)KIFWn#JZWaC|T?9FuTxZduFx1qaagq1NBB93Cc~O6~7LD1V7Tv z`R<=EjL^w)7Fz>CL!C`B*0|9gnMQ$t*TYNXo-4{neJUr3kueAA2J3y973SbqX(voM zbw(HP*Y}pIt!`=Z$#+rGMI&O$Zx;SjIg+%X;=IJa_HdRc>DL*?oqC<(PPCH_;uR6O zZ+~b1RG_koP3oP(;TAE3*fyf4A9o{IE*bqcwP;cV|%9R@{O{k-rLSgd80b9zRbu0V4KVyEsGh; zK2?8>#^YilZV0OtwPT)T@6mK)9eX+bC^l|yIHZ7e-`5-S7UYnSEjA-$=t&4H zB*`loQE)QN5V1<=ewsj&5|}4csvZ`wmhVUC`QELa8@!!4H3M69g2ddp>&8**w8DUt3{PK7=n%g@h zS zmVBu~1dfqECrd+{^7b4}aa8_{Ti-A)wNr^#!bF?@-L>u@irY$pR0|xAz|L)TA3`5u ztbLt}({vE&aln`*%DX&mWNCZkv1^q%h=ZH`xCBGD+>C&cNBOMrw*t!_*uL`y-_s~` z-<#MMrUwfNiZX?ZnK{A%O;dlPwjlbWJd%8UI9?u0(346 zOK;KUq550LtMw>g_{|`!pX)0 z;3cEeu+Sm63Zd~122WRi*Y;q=RQDD; zT$j3!PuJy9u%OrmMZv8IDA4pIWW{U|kf7;`0#DHzRk5)8q$yG23#BKuqJkUss9Hgr zg=hxY=jl+M>)sCI#iO!L=-M{7u)(KZGpDGasqeRoe)@`0iw@|>(=s**+Y8r-b?dD2 zwyH-N?R4N04o@`2IjNePxVNuhW-FrB5~Hx1id_4TD!nswIA<1N!}AY< zmS*To&)B()CS7YgV7=A;U~)sV2@u8Up>s3LRL^<5-_jqg!NBJcnr`J_|CLtTl{rs* zS7ew9@l__zl0Qop(7d_B*W-&FnZ9|GH6-=79*Lbo+Xg~-isd=|&OMg#=JZAKq`90E z2f5sxo@H?e?JWG5RA*w}W7;m8NauNgtffi+Kb7_0fj}yAED|Az#}I*4-Nxsu7WjA& zShdOY0c0FxfUiw8M@P4>&Hq4e)euhGxVSkad3Yqm#dw6t{{Ke|k^Z+*c-h$!ulwjh#PbUFNt$>=*N?w{&pER2 z7Y`vb-6an|<6;)T zIahgLvK8U{cQe6aX)<(Ny(@79d z1p4SIa5azR(q#w`)j>7v1hm3lhLu+yKkB%Ua*n(lNoB%U&Cn61|6;upyf|zbOo+&X zx8$e`o0VXTcw#Dm&HMd?RM0jfzJa8_Ya^Ti>rfy6Wp6u1u})P~D(v_EE4sHx2>_7t zTfDCCM4I%g7+O*s}^WK7R%8GYjE|NNu1ipwfV6!s(%ZbBH-%WI#SC6boi zRXnhm;$=#E5%+$lI?z?C;Bh)0$q6XP!grr2wdSU;dio;0V~A`7%O}x%7j4IGT10Q7 z!j~E=jw~KK_Xm)lF1z90jkiT2tHgD85SNI7y0V%Dj`z^%o0cWeOFQRHk8OF0J^3#+ zb03A(+x^J9_ARaUt~9Un>CTx>hsGjREm-n-#1ma0--``Cv(p?REDvp2r3;%${EJtW z*0TtA43Hf)yYKgPmW$sKt`wiwa?ow^J?XZ)gelzbl+tS6>RpTb7X1OU&>E{{_4B5n zE3Ms^ptPc1rFH*01fGVcN?ad}Cr{5zy{@yUV@3DXxoRo(Fk#2sjO;VXFGRK#ISBrI+;KzT|Oj& z;=7v7*(6r%FB)Ng9$`YQ(>_MPTCof7y;h9021z$&fok%0TGVXXm=)`=b;p>e@}RXr xvb!Q+EpJQ!^rdZ5(K!4YUFLN4ZvP31`aWWsN|%U4g2=_j$%8;mEu}1t@IUsye767q delta 93458 zcmZ^~b9iP=l&_s9wr!)6bZp!1*tX3l?2c_a9ox3iv2EKp{k~^rzL|5)_t)N4*V?OU z|ZLCnO+$ee)kof>$dDdV2OjlF)P zUK0#awJGQ>KfAxF-9B2n;r7QZZ@Er{L7bm=wYa-0M-X|>dh|>-3nAE+^Nb$=f2zKcdBM-?U?4vF%oT+k&{?Z*r6Ed3SQ1ZeE31( z$XyM5*4sMC=O;KNU8Ko`3WfY$ACyNM#AIwXadT07*`yv7X7Bb+_Wkm#o)*cTi1x^C z`i?8|!~lsdd>cfvaqhzBkqIk*=&BaOHea013M(yMEFyg!kOoY{@wyKEFvTtnxuJ&fP(%A0sdQdaay-OBzHN{FF2Qrg9?M3+~`#1;?Ucz2Q&^IkxIA zia^r{*scw^H8;Gc@&3c(^dTT!L2Lq#=27*dgaeYa(RN`~asmng@`1qb!tYv_N!c zm020{)t7mlq3oaPL_rQ^(*#gl8r{m$n^qjJ)~p)S46AjMfA9o$+(Sl?vRtsfAG=4M*ErhoS7ubAs zmo7%U;kPQfm`YHYQLm2|gz%5=oGwRWlr?5eyj&+Qr@Z9tPLawQZoY4IPRfZGLbi~psz9vCF6$yQgqxJu#=d5Zj~+M7nAiR# zImC>4-*n-C2A;S-!e_gm)4a@yThJ;d|8CC0QfO(;$cx=ZYdD$;4$}qbAF`Xk z@0sakZ>E_F%nOoPA4Um-x8IdA(ynrLYF?wAugAU1uPeb8H-`WYu#Us#6~na_{5Mtn zZ)QG^c%A`tZz)PaaA?p>#EiuDMpnf22Jl@l0OEu=Z@L5-%({QiNE3*$$PqjZ?e(1v z?M#g9JxrbJ6|p4$E+YS$4bs>Cml**%v%ZDBt*QS1uuf3K!l>W;K7{^1793_aW{!Ur zoP>1|RA3=QJUg08^IY+y!4nBRY!rP=$Z|aGXqpM|gHX@qZUigJ+NPd5FpN6g!x8>e%B zvcI+Hq~>LXW1Wp3gH0o*X%z9pn6Bsj$)6f&76y1Zp4s7-8lOlab@zPgAIDP<9~O<| z7b|~Y?h3{g79U@xgEecR(MhmO#vG-a+R$yi4nhw**|%QubZd@Ozog7)KP%HDT|dy% z0X_zxU@=E9k2B^UuG8_dLP{9aK*RPma zr5RdRphimDZ*_LmmRCzXzdi;E0-(r=f$=1RU;z-jx$7sVyD@Nu=OVybRaIwwN7qiH zUiX#3>Fa9H%5+)Y{lbtFjjdz|7!0FuaGj7)f5A%0s)RSWORRzHD5^;8pYezyR|q1y zj(Q6RQMPpTmJPC>Xbaz}kJNPy12tA_qbeCGXutLJ$j1L!ryfKaG2zSg-9M$P1x^me z&9Yf5t?{u=)J0*Y)yDjqS1+mZZB$bkp79{%VsrjomS3j${dO5kK+AYC0ea->MNCqr zSXP;wu@d@mlnn+f%*8^K7YRJRX8}e?2W~0!{s#Sq(W0^S90!h^8VW)54GPrHCI($L zbvBfGqfyluDdtGXpI?iB0}W}w3uuN)3L9*}=A}WdBEljj;n^{@2Wm69!JSgLY>|br zNSrtIntO;-i32m);oA>f^i5M69cvRnn21ujcD^heJr;kUhEUK1Ilwk6xKdG9=T;b56(tPnXTLM?0p4%7f6r$c z^kb_UY8kbnvMLuNqp86F4E@fJeIDO!4-bJcfv+eOoT4S2b9D{1EoekRuu%@3Pf)3eF(d938(O*)#ny zRHb86Jl8_4L%v_xAKLc{&C`jzigkv~eq20x>l~9Ph*d)$NB@V&6o|ABG(aLqv<>n= z+$n*7yN34oCe7`CUlYK0MU=q4xIjz!h)(mMjg-(Bv06(a6>H+r6BQzY^;u#W^(a%* z{t9MQ;Ja43inLtK(Wr0#LqJI0*XwL#ba)AgefczwMkqX12<@ySJozH+!Z5-o9Q_e- z5mD2ibcIfPuxKM-2WW>O0WpA1>!Fj|MTc5P87@p=fJH1RsI#9i`i<#>od}IBoMfm9 zb<9G6y_G8MN9D{K#Qk{Dnw-_XefR5FiFgf%u3GDqOKaL-{b^Ow(eud<&v;-%k{fOV zezAU$iYcET?fupmTbWXmGJ1l6Ao~Kjq%y$Uq6gb1XRMI_3JC1)g(nocgbB-sCA8_s zcxSRefgIl^AXg#)k-`RnCfB)bfa`r2jzJdo`eBcNtH`&(RcL>`9Sq|@V|(o$k6eKc z11<9B0~)-z{NYjxeu$WV`UCk#5pWTP?tBEc!C0qU9MlJ?z~EbY!@FRD1L<)@&qWVg zH_~czcL#v8iXRMu5+Ic92#)Tk^vhjc9V|B58lxje(z^ZU^O11OtTV}Qx$Db|&bDRp z_XO7HTW5qBa=s(M?&@`$H;8HDgghxc08v7xlpyeoXCbA2Wrg>&)qhJAZ$y3isAhvU zkR`zUD1)8+{HX8qo`=gO>+pa}RFq2d$RN^ik*5F9IEiyprW@kVtfNSD2B);QPJJI^ zEjJTu7=z@^?88~2Y*q8HBb?0^Ne=l)FLpmT4QKu;mC&t+P_d@+z+;47%rkh9#}9S6 z96q44T$=?p8`qJ$luJ&L5)ryNbbY^KzMV2%K5zC%*Y~^RbRcW}#abW+_;~( z46n86kao1kx*8jYcq}wdD_{${pIx27v;$#wdhY}VpL)Orwox*VlZ3Pc4=!wDY=%7A zLH?~-C}Xr;v?vudR{XsYj1XuznClv5ozCPzszSuewegfp?nI=OmEEh;kXy~I6!c#> zCuqRI1nhqtkR=Jis+Z7@=pAkC=+NreMRi~o-&4UjF%B^b{X|DO zpF_{`>t-aiNnN#sAS{8X++6i%PEx+#PrirrDrkH_flkevqm!)`L4VFkid|o z(l!$jCL>HvOWtTiFxc>Y8^7UFAp_N~1K9YLWOS(R_<}rqGWA>2sxV`b0a0ulEYNHm zY!&O;&9c+n{Di%O*FySNM~d#b|8v@N;R$&-;t;mDvN$s3!mz*%hZIz7gOl1h92Jd7 z;58cmJzj8Z4VB-qK=D%m(g&4nE>nGg^6@8bzVmk-#X=f7c;>Cs^ED)?Klp4UpFo}G zGle-${Wq}hcf8ts+^0%9AN!3TtE#ytUK_Q44DxFTY=vn=)jkO}$J-a0jKEq&+k0@%6E7i7Un9JO$U`LmuoZBlAGW2v9Bu1fieY{?1^l0I!uTyftn7wJ8BDfJ?MQWoY|4vMF1s?O^BDL7<(9usN?>Y2gXa7X-S=0?(Z|a-{x>1V z^1lhW+$Ms03Wa`f0CD|^iVy7HgPGpoU%gmQXF>4KLE2ILZ|7fUyZ_~h5S{V=&(pq- z7{vdSgj~$5|L#F2@hoH3S{~lsVe=qBy_pWLG1H6%(B<3`&N0`_v>N^jtEfsG+Oyh@ z_^dGP`|hWk86hNJYWZ+KMrx(`y>_Hi94dDh`L6aJzxV!!!3EkO)To9+=GHE`MA7s+ zQPk)L`Ghmg+q>gm`FdF6?Ki>S_;<~a3%vBAOR@Rp?bw0ZZ6`jm1IH?E-CFyXLai%dUb;zFj(a zWf0p3Kc9e!byt2~9Gd9exHir$N0+0%*$WwCUAvU&6cI*x$@L{>1raGrSlznV6OO{D zrLm-}DAKv;C8PJByGQyC%t7Y%sFA5^qd~f!NCH1or4z(%FL$R&z@@MSK_s>C1GhJa zV~7jy3!B-5l*ROp;?tnaiF=Af#{xNj!6nDgh+zZE`;noy%OCvcAp42Kf^Mv5bvkY3 z5E7*VJR%{j$UR`UDM&@RK1kKbaPJ~}0mP(AxkK@I#5L82mIXs|H^Cz=4U9porkfO6K^$OkF79(d z&@#XQ(}?SwvHU3@o%u_jp&Y42P@7X;I!CrQ(d;i8!G!c9fh1RXGDYg+V7ss{H{Lkx zn9t6w=n!G}v%7nH#z@0gDwgoWg zUx2iSX{ZVTjIxFPZXkWniqm7G;Mblt;Bs(t=0WTt(K$4IpO=RK-Z(YODTJ6=JIQz$ z1~jJ1kT)W?m+>dc0C?ZL%76gb_2~C&UvW+td{8oI_nRw0J#l5xUf0aQ#lJ?iNkG&A zYUjjIk{bErFkaZY5yLcfF z`%%hS>ta9y&ZAENmisW5=W{8&rf(DuE7|@L46>i~ORO!kjAQk(#+;Et#l3769bA=6 zqD2xagqLt9_0+iV#@J%8WYQnC>D+wmU-a%&2I9pp!#1^}i!bA4;o?@HKt!=)7xf%@ z7+VFdiZlGU==5& z8+wNg4#@}1F##m8Xy8&Kz$N*v{4!gazPqx;9Y*;d7wCp0Xy2)oyRb=~6=B3DHSO^r zpNL8w_1Uw+EqWPDHgoi*34@t=L=RSHq;IKXs zhPo?8f9rgbs-3Om>W*~XjsyRZcU6c1%_%^SxxWAI2$2*0C1v>wxE|ShTW>}Z-U=ob zcX^t*W~4cP=i@f7nf`$=VgAOpqJC;_dHZ)@R-B6X`XN8497GmLF-ck*Ndw~Mz<8{m z=<6AsYb`uqHlEk9;-q1NAoNd`b5iNEmb-TvsbJD3SWGddWXJDTpzhFeyO4h(jLq?r zh{kKU+4JtkMDtW4hv`WrPY4aB`f*Q>So_k zQtVLW)XN2LN5Pu{38>J^I4&CZ*vMC8V~d{#?CdUWpTfKqF^bg>3RV!;e`dMZQaMQ3 zN<^e-q04+h2AF{U#^rl{Q&mlO7r?CN^_P=4!$%HT-Hm3!KPiH>ZurW!z^Qx7~rLAaaJnq$Q#qDP2zUs)2YiFVw zw?XGaBP!W#3{BREC-U0jSlE_}keQzzMR@3$WZvaIVo&bYW-3b?t*<14&JkaeCH{cu zHCU%-K5hxVVv&PPop%Es18UwQKjXOxiTrir3>EtU3`Gl5qtg)yh9_mL(YI9TgIc%8 z&4Z7MJzFcL!OjX-%8I7ORmfGw)7389`O^SiR~}^_8Hn-WZskrxIjcJl@q1%Yw^}f6 zBk(fI6^sqJG0X8nT0E;6WrYPYGv4N@r)e4t?ZP7`X(w97IdbE;NErNGvIoaKkvA{0 zrHbhgSQ*C5UB*$~QI~8v9}a^=n5+>}8gyVH(P_}9)V|!3)L`Gtvdz&yafg?^k+BE< zhIw6AA-MN`abd>ACOme(%ZX~^R3gvH@U(W-u!iTbW!5i{W8s;qsEeG@DJd@zc%}@ zP=bjw&~-mJfbdYylM2Mr_$1*1l(4f;c2S}l5Amw_Yr}et@-(D&p&{@vgCa_7x0K5- zKpjxSnuabYvx*dAxgHjlfflkoK|PKpkWDezaz5lgcDI&IrOr=_LBONlvf4)6U0WQ= zcV>9CRU7&7DL#;kqc^4jFT~cZmhi-50V?-s zmfuC)v+yeTmxF|iS)<%(-hVq}yun0;*jY19_ z394om~+EfNb58z=f&;ApNl-n!bngvs?)<` z(kFSWQrNR|3q++s{6S}m(?W`4Mj=NaS(S7(Ut}tGOS2s)TR0$3u4ZjW97Q#`Lj1=A->+Zs zMUhU9V8(5NM4&4BJHyT%Rpk9au026Z=IdXdAE)Q1KUA$@=^AA_oAY zG{{X1`a%ce;AbyZ)^a>+0&A*z1P&VMXd zcXz*MNopohvE1i#Vz{)I)+d~psk5ytLsHE}piGD!n#SE&MDCFmFfppC2qpl@!loGD zfsBtys+%TT!n+JUC`|AP;h?G3>j6>V}5Wpt(AK-8$su3S){rnx^yO?s3XlQNtRamG?-n!T9{%>ZWA4 zdtkSuj7<#I$}8|1M#%AJR;&fOkPDcmGVh}+kDMC{1@FrGNc{w(KXw2D^EY^lmHh+B z_#GVDq=l~coJ8CBFsS6(U%$o$noGuO1pS^|e#WMUQTu4>aN+K?w2+cfw$By$`TcZ| zsD{Z&=y@P1tfBH*Qtx}(YcdrkLIG^5tIqL{j?eAbX84Tw<-xOH&=~_cBOWY(et{)K zOia2nnh$`A?8j>AJrc$n!?QV6QpC2)BmQ)d;TvE4E6NLuCJ~97@$-kj&+lB-!VF|w z%H*?VY1*uMR=e~)^0CYq4o%ObNY zwJWXDj;i*ITbu6_=j;=&Zb>@>F|7#=CrjX5H;z4G+&Ma7O6Bd= z-L0uRlQ{x)FieVKztfWQ-CY%W!Nzxy*D(nqLXZ)$0#BCh*DnU{z%!RvMHj$O__2K2 z@G~8_Jm!_gH{^hHC7RG7WB#E5z1U1|h^_`nb3!8Cxmd}scJIX=Ny^Z1U^Cc@(E|g% zg9EQUj8`Hf5)H!@b{%>KQK#vPh3(&$RJk8E(A`;ubt)*A{SB8Xnqd+*70->C9o zvLgc$Y;%ZjQ7fq?accyNNWHq0;;U-%NM@v)=0oh+miK^lSm%WSk7woM-M%vY-W|%$ z;QVkco4QFUwrU*4q1^3Lr;bb4me5hIJ2(VsHkasF(OY2^6v>K^IN?EZQIE8J>jW`% zn@%uN)>XvHk!VW}?WACyoA+xAGp{i88G*)@ml)cII5vex_WH%g!21KjR{xIC<~PtL zp7KWo8cv{SXmRC}W;zExCchDkbXBC^xVJaaz{NV=M1gGF#r6a9a2@JPv;)0hkcwJ8{ValS4CKF`MED!)4f%K-I~BG_lXXgKii_L&fMuf91t$X6W1H8 zk>1n6l$%HGL(eE^+^AG2b_$voOLzkHxAQ%V1Z+}E4bGgCH*itDFTKCK1%#L8ME6+{ zmTfodgAuuONb_>smCIa}Iu&3oPWX4>FlmI0xSH?OU{}uCACh3l#!}zsXj7ckd?t_D;d_f-^v%k-k^78Gi0>hjKo+oz#l}XM8Feko#8za z_3qqQC?o<6GpDZueDulLARcUI7hmY3kQLJ}VmS;ZVTHH{du?~=46{xQ+K?V7UT5J(J)p!hCDsukfbnb^*7!OgtI!FqDOw!ll#+#+j9kf@8N5C&c0|h* z(V{*CQTt2m2}u(SV8>NdmlJOkGeMfBQf^K2`f?1Jg2uB~j1s3Y%dq$s`z+V=w|D}4 z3#55w{)8(BeQwaG5*P^=SVLrNzpF9=HFr0N)28u(OvUwg&7?oamf0MRN8YX+Zo?2w zQ6uVfvy>qp;^SJy;@rH3c2oFM3N;w>2TaNboj6}MkRlepem%ij3W|czI;NqAfr2n| z)i`DpNiyyp27bzd8MoGlHismOGZaf7wmaMf_jpi6zWpYM_i>+3WhYdhi6lFvDu_@; zfJC>1_rc!-mifBjvSlud5Sl78fVa4fB#3MQfz^FllxGG-mjS(!{r=$(4m@lqvVZQf zF|4!`=>8MK5D)_Q)@S0MtRxI0+kd1bQ$8mE9KbBKN&7Q)`0l6bYg2zPR=@an6z}FP zTl&rGa9fM-{cS-;*z6PSnIA_O6e?5l3N(c&KoVmX!7p~e^)>&_^HrzW~+Wae-gjZ zMu06JdzG$zcD(w&8P^Q01!3)-c32=#+sD_iU+B3?mh5z~cuXcxpl}=i%;tA9v!Ipn znx$oxUd>a9vg({&uQML0!%xpk?yUP`l?6O-d@gG2jK_FRs=1lUef}o;et!o?7uL?A zz3FBKV-t}W5_N*ER9w)gwm2>gCe9tkG^k(>9#&90R!;45PoOW}_~4mTw8ICpUkFmy z9es^o7Je;_ChfPp=}4^612zTnO&DCNk2KpvXl4Dw6U)>y8$;e$ocmA9Gz&i;yCv|t zv-J(aufT#YyEU7D8`K#M18)c=RTy0f@~5HHUS#0?m@?%~OahdEYO#{9`{PagM)=W= zUUOa3R1ThBC~x#_;1`lWUCc)+f!BBp>n?=G=0MyCgWvggKOeTDiifTETTrg)uUk`} zjPiTkJ65;hYKWMY=`D#)B78Su)mflDz|V$d+Hxm;Y&=EDxk7#=?~-bvd5Tp%19^N1 zY73B#u8u#W`iNKsLz%%#80sPz;_6qQin*eeGB-T1trSY@1X2bIRMGzu#V5jHAxIqCa;hcz(8nd=%=$y`XTbHAlU9IK|uV09Y$3Q} zo}S3CwS6&B4EJ%u1kaRT-K;NyQ{^&8> z4JKi`H*^gNLa^&r<@3{ZoG0*M`12;BV8W9`le*^CwL8~qTlC%cSb0kE@*!9LhscRu zPBA~vBSB842CGpr8hmNka>A*ke$Z3$h&z2X_tG8Mdg`yWYNQ-_fvT`;ld`)WT!|VE zt(+zXq-nocP}an*t;~*9DV_>|YUxjd^>S00bhE}}$eK;4^r2nT7+8VxOnn9GFOWwOGRJ>bxP;tH=zl9DbP4B$JPF8IzW-4#smY@Fe@L61tWC)OGHv~D zWfivnrL0o_Qp63Jpx5~SpnY77|Ch8ms6++Y3C^(&HZ_eT8+adw3pZl?N~QCRpJjb} z;OUTTLgivAKg<(B1~2q@8F8L+9}!9C)Bxx7==`PY<ipG#R?%NgK&7cNfk0f{8Q`0#X0a z)K^tb65p&Um+rJ!TJ_I7Vmt(lGO1Q5< z$<$D094@1nohgC6RaMn*tiI?IIj@XIYO!B=0y)AMdlR0A`00?`6CBrK?Q)H&iecfr zj)2Gu$c}8Kx27a;GEJK_ty&9os9dk8hxq~2Jg_Rp<-?>FL>|zu9tRP5PZq5_}zd$m~3(pqp_oy&rqw)*sa zXz}2HZgQd9u4bMcJR~`amgcajA|o$54HNu{qJ>St0x!-XkMf6qogfrY(=g%(6K#r` z916l&#qaU4MY?+Qmc*0IM*0^xI3FKXRl%PpIVor;o2+S-wR3?JN@Y$3dl|mkf=tOX zF&1KCyu4#pY}2QCIQsf#X^Xn}AqO2gW^%49al+b}D!9pFho|3dtmr}0Of5rUTUA@z z#^%QSG?c8~9F^LX3&z@j7r&`qS73>P24S_cxf^(Ghkv+M|0G;vRXD4d{gHt<3TCBc z!7#u?jW}n7XxmFpj6|U{ZlDW?XiSxlVJvMBT~##~{E}|#QE!{dwv@(R^!dBmtiGa( z!{+?Dx7muLf+_L)gyCfB)Pxh$NY1BXO}xJ+Yz9mE63(zp!ens{P_=S(s8mkPzmlo| zzu#5!EWk8rQn$RpiF&oE6XntaZ=yk4OF!!hWn|kQ92^?+&R+~=R|mZQU{k=Gnmy?| zlbEfux`RVqWZ<6D700u+&>E!*6xT*igZ0bdswiqCbOb0Rs%WUnMwpgG5iVdqPtV=K zBfm)AJnAs-yZ(<8;OVRx!)l#MGvs5DjY=v?*rb6MR_p}ABj_tLp`NTkEM`s^B2igI zpGs$bds7q26=Z`h>!_=xuclRjF4m(;YeNETy7aZ#;&*RM=4o4oJ-N2ygL-pz7TTjU zGopwGqXhlQs15pCkQ=?6oHQIu%to7U?4`!!E6o)3-()f>fOeV%I#nf6T}?^-v-RAp z;gGnMX(YzzXt<2BC}C)}_fJF)jK8>3sg0!YbuyA=o|iH-(D!?BW=eh$!+?PY_;Wvz zEPp;D3X8g*X7x-FAh{gHpM;~JZ7b(53r7A4TqKJ!9zb&v01bGd99`6WHby?$1wz?g zE={=ySTdzT0e!G^)UK&>VZ^@YlkyGoaH4RA_AXFxRLP@YRYZwwCW%#r(^bmDPwHt0 zO07Fh{$v_8119HkhHLo~H95tI5RwzV&YD=(~QUw8Nj3I+Bi zCN!PwN}`oU13OBd_R} zb=f(KS)-?c>4U*Dm-_2kMmm5Pzd63>P9wOVLV z0u%{<5>mu*{LB$eBn#Y-i#yMON4^)^hKyAMMi|`PxnE@PuAF8-K@m!}H^Oe>8Fkfs zzGBa8XgD;kR3N9s{v+>6<4|5XF2_W+GF610x}P zQ98~gP{T-#LPB%$>#C#2EU+S!a(+j)+)YyZc^E%4kwc;(OT_KJMUF+EUmPs9$o5SE z+w4Bx^RTDM=vaQ_irlE=tUMVEbJ)x z@QfvP#s5K1V2lQ`IAOX{S|7Ep!&>Q`wc~3gj4pL&KJ#B6_fDpXPQH&n6CZhNeVQe5 z49_`ISpeY$#^3@>-p)Ws6cV3ueY}AgeL2+K#T`5c(fJ)5KZy>wgkUVM7EaI(_^77| zcm~l9mJ;2UhzqE%qIM)aar-qVHs+BZx7k1)&F_^+J&m8kz`JN9&qa61>~g&LKXo_x zTiw}X0F_%tyqJ$eXfYB2SJ`2_BktZsOg}HWp#5})u?H`y0%IMcyDb3UcJ|A zP=8{Zk`cy&_~+i!ZpEC>yaXJP=?nNARc7NJcc)%-*3Aky4AF(6ivF&_^e8wT>S9~< zFnu^3rz=;xWLgnZ{eIPfSB3-+_E27;-UL3W_A!X%#uwm0{xHW7+@1mJMxq% z*eL}Cvq^d;09f5sg!y-y#qyuj@4p-`+@K(UJ;i_xOe7&@@H;f)|1&*w&i_SkBw!DT z09aDwR{<)ZESw3oLl^*-gxGBK`n919Na%ki{0~%|;5R7^lzd*D;Ixdl#5=mQdeWPf zg(@aaQ;+*0`7P{iX)6$fS~=g3vBG?HoR2&hVtem$cTLw{V@uns>*=tsc^b5p2IQxEc8+=c68>$uyJ~Nd<}Vd zW6&%L4~bj=-uG|l1Jb=fVdPuHA3Je+L!Ax%s}04E71ZidcP;AX{YkPDGv1U{i)r;! zOFZ#hx?0;iyO_G^*)?@2JSo+s9xS|!)6%-UO|zM!RW-|6PpSyRed>J}b#vfa^)d*7 zsMX}~w39VraV2iD%6#N$YN8QUwy5CZE;G2sHuG*kFDG(gTuVN%@Ic~w>fO|go0ef* z^srFR`bBCJS&t)|_7U}RA8Bmp-E+bt=e5$}RJpE!G7a^^Uxn-X>Ee63oHoEU^|8jzr>VU*w{{cje0znzK%q{yW(E~0wqsX9KX-l*2$WB#w&f@r+pCu zG56k1B1P1!o3Ejc2P9gApveKu(RhF1Hpiggk)<@9a_M1jGC=9ziVX459skxIG?eXK zj^K+D+Cs}+jAyANlF2|Ek+`kwdj%B6BOW}*EDIoBA*n z>o!c;3n$z80`nG#94*9z$g}TWIa%wu`tO7G#0X0BH=rCkBKbWA;8q z{1QNWf>ZTX`^J;q1_3SZuHxPqUC1yzi!6N0MblAK2}#i|<-^^N!i#ipi;TWvhk@w1 zw&^Wjc+*1|EskRU7Z=>Eg=R9Fw*SK+#ygDiDmpOtw@4ZBnxTCrhk}39G|Wo;jU>Uu zoT9Cacq${-PYThot+V!{nhCgy&o6=E^%t|`hXQmA{wC|9;Z_;%*mmd6Q84$`BOE;H z#WqLP>UUa}H4NrzB3gbgNMt7}1@a^!(!DKTCGzLYKI-s?&;Gq@CEQ=s+mCaAA*yND zdBTa|->mq?snY!T*)5&KeI^6LLD5J+Fe0SI))%8k^kv8FBvq1x3Ly6+lQ$#LU~MmU z5T`hV#qdTE=|?d$zwY);wsMYK6 zwG2v|$WRcLN0S|)JhIFhb%N-?SZ$P{NgyLboN{i6@XjRf7X!%m2vyITXo2;w{N1wkIG*o`6^Tg~pMO57)q&;Wk|*%R34`Lp6zUI( zYSL5frl^d6F_49-klKh0a~|63+qM9W)&qkl zUX{a=D4MlDlb(8Mn{?HMRoMZJB`7)Mk|bCOlHNi+T)xpy-30o&tufu|>W60+GTI{b z`p1D>LTkCM)j%^>F@zB`LHYiTzI09n0&xjsPJ=N2i}8R=?B90?t!H)oyK7fl!zo~A z_J&FZSmc~7!~{FsaJSC7E(KPI7jPmVn^bcAlZU?IzkXxk2;Y~{|A>tdp55QD zg;6QjC@I~u)Y(aia{f}_ew;T-PAT=1=-_Er6>wR%cm;lMLX_2)*|nC_%aQ#C5is3S z_F4ZY>=pgDwcmsltVlojbYTO~s`R0r;(>()t)uow@tu%-n99bx6A}-~lKO<}KxT#} zV)dix24kZ+-=Kk%?k)RZ+otS_LD@{*QeLWH7j*m6dYk{$c}Q`joR)SAD2E{q0_g0e-0ZGe%jy9Y2?`Xcv$9c=-#*D#ooVuq0iSRYDB zOH!}PnLd(WgBYguCKhvwj7wwp`^Kq#Q}-Z1fR#5#aP4)3kNtx325e0)v?z8c=y!k6 z(e$L>8hu=6#yPfl39GK7w86UVEs@2qwwK-7*;`!$roCYjZ)N2iA2Va1beD=jA4GPc^!_QvIX_8YMh6i7(Y$r_ zcO4RqJ{WjvTTK&xYCi0e{&hE&Ia<~5Jzr=NE& z*y%MQ#1+s4FlQo;%~hC>Pjzp4c5Tdyxr-<&C&{g$tGtaFLR!` z!y?NHKWP>mjg%r*04oB`5o_ueBohL7m}2@+${{O&3W#152#XLLghL@2I=|bo@nFJ< zfQ8z|94JC@M)ze!v`PJBBkb{9q%^2Zf00n!fO<{p+zqJlg0;mB;qcN}8-krbSPh^v zIndIy1=1#ZfwpYWneOewbMlstiL+~J&Pz^9Pm7$9g`e~4O;k_bt9Y!q)zg#@_3T|2 z+gxVi0-v*Sm7^`B0fYCS4IxXaUVb5dA~CC+BDKq-<3^UI@q8$#WR&r0!I}Wn3#oz7 zy9SJB0^?P%K$LB+V+*lLkVr0=ETi-DrMl9(kkbqiy4arfCu`j^#H7_9Wolx^ z4@C>MgaW_4F>lB-w`dBUa4=w`QD;?wl}?Qgz@Tk6+Xq+rl(8m$^I7(Eo+lHfDh|y{ zJ3$=TDw{RBgW;_z27yoRfQK(z)Sc^L7!vYK{VwmjIR^VG1TeQnCoTc9nH~TPbU*bW zoq^yDbXCN|N(l>k5lo4=QMIL?)mtmnk-BwYP{i%I`m^m!jvU{bnYY}R>xR>RJuD?svgVQsOJ$yh_~n)X%w@M)dxibA zyqDQ$w-fo{)4+EF!bhiA;hLP9Jt_8x zj`VYFn1o(9eq02auxU2^WJ$WEsB32Y~e_%?iQ?!v4poNl6;5MBRA=#ah&LRn{S|2ix! zK6V-zM5?FW?@~ES{<3LTWt5&YDedX=hHwPfD|wX-d#uGG+2>rpI4epKWmRn7Am`FP z=gXw*<9~(8C7@P^w9Mjr0)6Jyhq&t~RoRe|=W$w|jQ3{N4GcRONKGG<$+s4JFe2P(b#k44d) zkJ*ak@z0#zPea#r?x1Qo&0B;6*OA-llqZfXw?o$%O7O{`8fM}*&1zs?CBXerSO_PI z`dtNOB$}}|6`?Kj$&Jw;sW}s8bYuB;-!$@yKLvhkwpK&*BaUMF#N0}BA^TlISA9p4 z9Qvg)J@}G+^3H*u8WZL}1a(+->y94v_gnHncSJW<&y}I!^p%tzP{Cdv{Xp zEOeCTa2xoNLYJ%aHWc23mDa~_TSTGoLn9=Q2&QWzNC|j`B1c;QG-i-qs zY*7;7kUj}&LWG9zYA%0yQf3$HcSbrunvN7|7g~F!Q1Sq{fHYJrsDnFLz9@!fSEnK-x%fB1%^yjdrBMC9ju0rKPbK@7l zEZvdo-=N9%-~L{qOX1}O2m)ABe0c$mFl_%V=kg!n@_#Frq)77tJ2T30OmS%~jV_}FaEK{MJwUTwRQO)Hy^3_jEIOPq)}J(oDr0o9_9YeyV;DwOfs zcpxF(BT|wkbT~{o+#}GUAkQBg4OszzU`{YSTux5fV-2$JumFggsquFMlCz$B5(c=n z%%kFx>sYryc^Uuxi=&)`a3-VY%tMe!66rGt2uKu3SbqWlQ2NwGElCT1((aE7qR@xV z@RP+-!2j|NMtESOQhw_wfd2vDl}6pN$dMFz_wNTrVoz}fkb)7QY>^EG`S}V(g3ol3 zh_j6RA3okWy0UNU7R`>GRBYR}ZQH5Xs8~Bm#kTE=Z5tKab}BYs{m%K$ec!$Jd+(3g z+T5$Hz1A3`&9+*fz4tku!f&uQgt}+zP0*NufE_3Wa6Mwi9oT(nEEqlzbZ8VRNX}6W zLLABNuyS;xuz+tuW(?$yP?hmAqYD1q0(bckQdp4kqGs4egiP!a!lhZlLT{xt6nUaC+w|4s%O06DP=4l?QqZ;D0tIQxH$9@;WVx& zA?RIV(4W*vf^lfXWHFH7ve3a{e01!P!vGNyF@KMIc`3kM8x-g+Gn%9&s>-NEICVe) z3@f$JJE$pBQQRM*kT?}4)Lw0=moOoqa8J&S7}T*E2wa>ytSUi?(n)8;2&k&#v@(;i zCFBbXbuhFNbn&oXfT2iTM6N)I5&~Nk7$h0*w%>YwDWkM_$Yb zzSl*BZAxf0$Yv$WRx4HWbiTgiM8H$%j zT@fUums;?|JkCfmwpyvcBu#0e;;UOaJ}2@Q^xi-C$X;htvbR>VXA%oU`W3aSqC58f z`tZiGL4h^I@XZpfnY_B@+^aBlSr$R=+~=^jP8ND8^A<@OZG{^OBTiZ_4LKW!3O7*z@_64Z_-+-zm<4Gsn%2=o2TiH=%?v1|R2aIjwuAP8@Ysp_iq`7(=IF zGXv1W-%>FZ4c$(1Xhl*bIOyZ+K_t8u;rl%l8=kD-*3nIi4NQ2B3$d|K6 z=TV7^17t3VScaWWkl%&YFPoQf)3L8b1(*$ z3PeQfp1SX#i*-%+`3Ia1zBtf%q^sR zYa)iN$S39!=;{pUY<%st2Qq!H*?hFl^%p+||4!@g^ipGpoyo*nAf48dKlw-?vgVH0 zrlcrtsz5u;Er`17EHdcQlT%Ve6_1P-qr*8BBm2it$MV4t7wx#tLf9$I*Vu;Npmw{3 ztfbpx4$QFe?vT;V=}Z4RDEpS_>_f2Z9cuQ_{NDc5ajat4SwD?CXQshH@&)uT8h5iY z-dfOwA(wLk!UUr~5Pei}A0^1~xHn{G6poEc-_mku=^{6kQ9;HZMCRoZVK?)4uW%OT z;pIvoY@kwi^Bpd_Kf|yxcQqfK01LM1v^+4_L7+;Dv%BPcyvD-J%G#w0B-KqJ{k&2G ztlFyo5TO+|H;n}Cs*bSP#d}2ItJfy?QUUXFjDZyGQ4YbA{vK|4tZ8b^$`Z zXOuEh8iRlehe|^#_;Sap=g6Ye>N^RO^5Ov8&)}wK`C;r3f8$Q> z69vVbnNOS}G()IQ>HM$H7448g`_ zu<5ewJ+;3dQ$dCgf8z+|9`E)K%Ns4gq7YIX&^CB6^8)O#jW$d(h?`^XoG9s}Oa{U2 zD>U%ov`g#3;P?9vDQirKCq&Qem1?)eop$N~O@vXuWv?Iyh}#GCN9`fm`6K%KV>ZY< z-s#Mwx^rYD$0(SW2{!9wOu2$fDm7sTx`WG$iEFC>I$=gf=-L7u5c$Q6N0kYQxSPjn zFP(F=>6(hZtJS1z7(^E?$3+?N({_=&d$rmYb@{e;_%|A&UM&y4A?$sSFB~t!yxiIbCn>C~SXK*8eC|{;)JKmS#^UH{+9MI8m-Dy|S5mVn2O@JbfddoOazk z<(d%g)Vf$;fClM4?-MCfwK=5CeK3%SyTw^y#H+r53Jb#pS)ah@nkUCssP54s@ zDAGzKX+@ieHWQ6^nD^j;WWHU*zuEMe;`7<2eWHBWt<+H`0E4GfcZ2PKl60Dq7m-kY z%*J=`oD!>1@od9Ori=6k-^cpwxW838_4mM0!gqXhAhvuT(jVS1x=R`0v|%j6>i)QH ziALJx6%E+Q+!u}Rhl)iC2demwKDR(4L;M~5VveKWoIiKv^uiItA+zL_@tUbae$L`o z5s)OHUe}N%%nK+tDXIbgpsK%#E&iRqIsN}6D?E!Q?ej1q@goC@pc-5NgOWf43`?_+ z8|2wQcP&6?a}Kc+YISxSZ^|l!fx}^$)BXO+!=Wz%_@-F?ab6_OQ$?`bk| z6RZ8%_8fv&Vw~#J+oYd@(lgP;a85%%Hj-^(8H6MtaGF5sNbgUCAOFg<##(Q2$LJ)( zbv4eQyV2$Bd6r;i;=0Rv3pv+ir2tJZ2RsV5(2IBXE(Op3%mf~2YY6ZvS}3+523F7L z-x(^zJ{ev;DLlRjVsApx9WNGpW1HvC^9eLqmQtwdC=40xxD3h@B7Hm+H#ZY%37)WG z!;5lbd4wQz%B7Q#>H`*w4+ccKusPO4-|iB~}MvNx;86SdAZ zZ>jolNsYPgu>u+2a0V@~e)ai>4s@%;pUR$gbYnyM3C@8LSIv+h?>P-h@@G6-25wih z{&cV>$mls^yZQOe*2x@s9sP;-tH;ec?#G?vNbt=%R*ssFiQco!uHpMe-od%?ZYcD# zGx3!d*-Xc$)Q+eGux$pI*${A1rvSM(qOw*P@Fzr}BOf?#f6|D{^LLJmXgL7*|5ySe z+f->$xgkqWF%;Wal=|D-!!cJ+(z*_RMsc4mU5=u?&jJbpg)k3S4ggGA_iG($*X9JF5&5%@7~ z#-HcbrMwfg|8M|vdSDNytufiS6Cz7B_pN+29$xdvHQzU$imvgl?EF^$@)0ke3)oHp zSbxl~u{_VilY{ZS;)u5WeLXxms&XD3>qkB^;@{~<0HZu`Ckn1IitpElBy*CCU`GC+ z!}G)+_(S?F2}Yf>!FKV%m@8MmoO9R6vX|UqGNJ(qy+X2y`Wj*B)+H6EZ;zxUc81Ov z4+!t46EkB0OvY&14^%SsVINz%(w|V$VrYY@#D4H-82{lC|9kg07M4V2Xlh|!jWOqa z4&<(LS`V@cIUJBaJ9}qx1&TxNq5|CnFmVwS6b4x7)j}WN_F4J#gu^665Zqo-#u`Gh z&MwN%T#dkyRM$y>0`O*ZD439w76x@!TG5`yIM1XeEJCgLq(&}L%Ifq~OtQeJCil-L8y2iu1fwvP?5-db z%gu!K8I;Zn(&3HJ{HCqVC#5PT)bT7_Q zYiXZ`kGN1yPeEYjh*Pw%FRq&qS9kRnccL9G)o!lszT=M`G8I#G6t&zyChMPdQkP9;^eQ{3|=LX!(nO(8^+NkUhS*51QxZV(fj!$ zM%z3bch3q22nWHJ1LgbdS!;*N63)Mz67Oa;%ziKuNCCYp%E$KFG^#s~FIpU1E0Iaant6-j?JB(kr)#9Ocwwjk{TT^BeKK@G%`Dj2Z6R+Wur%TCO7a zdNT$+F36?KkFxvbwf*t8XkMRRUUDn`!Kj@8aURQa-Bg%dUrj%kL(CN#B%2MrcE1%a zb57O9wg+@yi}$orGj)o=O`xI|s>+*(d(_;rvRujaisTPjr&g>S;J^XZ zd_OYQ{Aj3o$@U1vDq?K)%hpR%oGDQyzwWzz9ShI}eLt|zwxCWf8c{Eqj`$odf`*5%BXF>COvh89tzT*n*NvZ6XN&_PJAmZD|t&Y5j zt1?hkuV27rxGl$0TwX*s*vmhp%6Py?h7!k;FS;6kR$x-oR~Je}26$KRMXj- z0W_eT9EpmG+LX+k|8mFt9~PRwt{KjM9{69b87}4)tOYX&Tw+P( zUIn=QpU#-SQq2EkjY)-F1Bm@wi%|vqTZ-XgPmIq&ZJAsHKtNz}{U?e4_7!Gf=SuAp zfu(Li*#RKH!VzyjJ?(x0#=M8E{#6jctA7g8B6$Yb0Ea$EJ$*+qHC^~Gb%~qh|E&pK zs>{{ia5?_r!h}*Et^h3mJ(+*;VX5}l0O6!@S(hzBBSSO(FiPgCGpkf8?!y)hn4Blb#(uhv@&6D(ru+9CJ(H zA$TY(4D)|D!4_p&Fkcv$!pzZ6u$ISH*MCRJ{NHu9R6=$z!GALTYkG3}U+Mjg|KF4$ z>;I&%rP6VL2?3Z=?Kr^9ssBm&Uydv-#qZW;CjXeSU>T+D{>IAkPmF&9m$qa1`-3(0 zodaz2@A@&?g+YV($M~g^NQ{A#`pgMN3(CS7O3nq=Le2#)Q2uwl{Ogu~rTw2iQM? zrnudOG_WY$&vLg<68d9K7(P-DpW`u+D+9uyaC}Zxf3hPj<_T+B;_!-VVn1*S3!;FCE}D)9H) zde843V|8th>gD7YW@r)?X_!)sb^_1ugdVm{&hvS?o6+_Y65Sb zWJz5v#Ojyh?Dm*Eu*Y?==(_Nn2F1cro&O}7e}6`i(dnxmu)hH%NcZiOVcEpyFd&y= zx2cI{@eBYb95>JjWF8UTWsg&mVj?=1W-aE?JrCm0A)uuEP56_|$OLpTI?lto?8e^s z$n}w_Y^^M$t;xxVWJCIyy5eLJ1PbSu|8^Gi6|x>-xB9-3U$C7h{2kxpmP%03ma^bV zKtBc!cvhkM!2WJoR&~1D)5{;sltI?*y7RQ;0v;OtV98G+U>&70#aNujWgGumNP29V zXp;SOOk0+B^5w|+VfGM~&ssa2E;9ldp0P@H9~SyLs6fwY&o{t?Nfj?|1YL2r_avcF z?OmreUxmWbJ~i&_jZv_m?no)?SU@%6W8I%V)d(8ds2Du<<`k0Q&j2*5w&`~Wf?ot< z7|+>1Y{Vq&fCSgKYThLhjR8GoA**4xRbGQMl8qfth93Qs4ju=Lp4_oms0?(=XPC|#)9L9C z$%;Rxs>#r1vhf;*_QIcROF6L&+AJhWxWG-aXPMIja? z&!!I@^4t=Tp9M!Paga7dt+$6<(&*ZVsGY(pTT%Gz0hA(tI@7P>4E4eHbFE{Ygp-;b z!UN{vfRMZhZW*c318g}K`j_UKQjGR^Oq7Z>>4wI9kS?dT-O;>L(ic-IC?{~=e^P2L zh^P4D$d!DSs8wduK^WKiXXzTQiADVSdx$Q`7c>S`iUuCs?)Xg<3w*|axPSZlELNZW zA|C_=vM2*#uwzLl!t(QPi`!1d@+*k64K}hBDxeIY6uL9>2Nhg5?2n+C-^{fS*1AC~ zNJ=3cGOUK|l)PBi?;iH)B(C_SKHd_|*Q+Y1L?V-$gbQIOR!aOrk)Ej-B-Nf>r_?OY zDjru0toRru`+3Z&jx^8Ur4p?hNVSjqnA~v7S_H%vS&D})AB5KcHekt^FY zF5vhFm*EzzEnc%+Kf=pej*wo*H-Xh?CIBY^xL!ydlKLy8UVp^$a}fyqFXorKjW=Pd zV~>dZ@Iq^!oSiLYWVD(WR@iu`8kE#mEr5tt(H!uZ zqd*m0ZpydifjJR#M?DgKljb?vI8rv$Y2Lk+tl$OddSiPqfJFGaJ9P>Z?tvl2y8{+4 zaZ?yt>roh?gu(yxCu#vf!H1=a5d2kQo%8j5qbLu9?R~5k(V`+EN@I+~+H2HGj*>Sh zG)!8tpsK$X%N+4?vfvlph_=>F#8W8f`+qE!K`R2_>Vk< zak(`to89apQ{r72{l%FH@Y4l}c!}0{Rqg_;_0haSAs-oIEXC$uNO$KD(%8TQ8`jBI zNO(N-eoPiE=Q(^Wn21{A|X#&Xg@sI|L>q)T(uLn%r zNIFKNwZ2{c(QzQj@0-2zfO3@Xz?Z&E4pK@YJV^+aXTA{GeoID$)kYM z2pJ(qZjPBFs0`Hj>Q9Ha$BFZ-Nl+gt;*$t8B#$5n)a6eNXyx=Miw7W+FqJ^!Gb2PB zR8-TSAW0=ii507?5Yp7ori?{W5JAk1Xco9j27bTosQPGVT7p^!xcn||L-V=5dDkl6%{#Ci(w%!0PLZiun>O-8Hr6~1K_g7Q>M2I1?KHG!$qsYv9QYE*BVN@j>Nq`;EUHw!t$u8 z0Wr|;(s83jm`Ck<9jD`oa}&PDQY3_iS8!OnCT*ORdVzbrIg#jf3SVsTEo-3eqW8Src|+Vci~!NJUPA(cT$`?KgA1F6>T!7mDV!D<@E*dP z+`a^U@^k2NNT_U=)z8rK8MilxDGrZod8N)c3_rXfpM-JQFzHbBH zJx3yW7iK%t;ozFCy{?_AgHtI*reE&#zzx1!BhTuradTE|tY3h0jpoaE>@FQ?k^xWi zw^3#wK0di8-B);z#t}BA7Wqi(jzI!yp!j+Puk#39r-RE-OQZox4jU(ocXE$#tGoSZ zam%4|FsT9)CjulB^;4xzH@UcvGEvRC0|+8pNnN<1>7|j!K+d=d=+IIWy1M!IpN7z@&)&d9?$= z+&f{{{O;lEa5cP-s3416M4*MI#kLIL?(Jqt0f6s~TN$_Vh?)_6J|1_L z&_$@)GtiZs2ObuugEB;YaD8NG5^udo=MCGtrrH1}qLlV)@PrxDjEP&9hSs7f3>eKc z(7z9^#<>$ni!x-vLaE@5Y2lIFGAH8r{_f;DH(-bo(UxmJ zEIB`)yvp0bSGwhvl7rI30)kf{d;+D_Zq)}-4k;=5R({~wCUaMl+Ovg_rH28eAGvKY zuSkI3_8?uV7{&10L+~pR6szd#=Al2+UxSMkU7LQ4+$c_4HV)2~@ffp-uiEP#1Kath zpeCa2n+7VZ%3UwNZ*K>vq!R|8Hp11BKq{zd@KQjGw!4^*162sOZ`j$y_DbW^LP%j* zdW8|V&h(oW%~l<|Wk?CzzxgoioMO=NFqZ=B$aqTX$i6Jg6B2Pds;(&N;7F*kcI0oj zAQBsY2%lansGS``JKf&mfwUa9a~zPTj2of)QWe-AxWK){3(s=1`6g0-W373Jtb&lz zz-5IffEP8yqprB)s5~LX=BST{-vo>+7|&K zu*(~?Va{!_7QHN@APN~xPU&5&66aJ}bY*kdycVN*Q1NFeUA+yX-?GU6IAavCw#h0o z@j$``5-Zhl)961yiwm!#@SGv`~!VS)Z{gKF(H!WKRpk3R{2^a0 zhVX(*vq5EO_KX2USNA6FN?i;k16Pjc^&p!Ba}+~rR~3Tnx@%qBRz0Y*YUJmVbn?W~ z8bamoj9cq#3z1M4^f8Kb?_%jdp)S>uBz^=jg>)9#&WeQ4+j_GUEH85Q)=P|zH>9mTO3~m*c@wuFV%e^n9x^it>6tn7gBfAnE<{a zqLll&AUqZa#3I5B6}$3mD;sbBOcwphQd7XL)@oxPQD2cm9TI}Z1&SO)UmvW~5gNuV zMya$#?k7B)hvtVbuqx*HLKK~{#;KVuV&>4!; zZ}QQMmDDDz#KU>=O<@?g4BpGB`%|yisi(0i6PY87q~j1OrxC7zC3zI~Pkl+1&`%;y zkD&~4=;VzZ3m!H^snBzcWAdw|izeDzCXLMglF~_zZB__HO0`7vyxgKy=>_dvwM$AWqI(QU8xUUft`y$(ZH1b(2Sy)v+8OBx=V*aI8N|*E~iZ1=G zSH>Xg8?1jJ7Hp3H8;mg%F|)I=rV8J|kpIIh(E!~c)ROF$88(UVW#EajMMGU=-4U7K z!Qh#}2I55Be@anh2eP5SqRfE?`upek6A{x(QK<;NzIJba`5jlfPGvNi=Xe_~Z$0_` zX>k`4aM&J)2B)<7E{)Pzv zFC(NALaRVAJP=gOv?oJ<=6;w%CYcHE z$`IVIH}?RG2fmAg zcX*T9zxQ<;rSY!phFrg$82Ps+5QF#>UdIYJK%*Rm-(uW{w0+G{-P8V-&sf}vp@Bw1 zqQX0rzd!dWXCgy$PJ9B%7aVf^N&3EX(xa)s)LJ;th#e!4BU0j+mWre%`+#&jEOt+r z$%+PnjG2NFpA-io)CHmh42ztp0V2qO^5ypk?=ap)hZr?d_M`5&kb>dB{|MZAN6zo+ z>sA7RJq1IM_;T3UrX?Xl-huv^2ZE?%ft7V4IP36RskCQ_^Fgxz9kA5T`3DLd`s?-m z4!r%8NfLa6e@F0sn;b($eQutGb?1%rg-}TwdlyLvE-VZHE>=Vy1Q23&0y6s-6+sg{ zZwGuz_if(-brE`N1xMZtiJNv5p#AR+Y3%2oT2QtHtNK1H>^(rfwuF(K=4X^Zo`A30 z5?Xp#&UX;+Upax>3|}orU+9Nlt6yKfB(8++PupBihCyFoP~N>8V4qC(IBQU@ta$BV znco7wI2Z9=m&MLS@QnosfM3zp`MsQ?1>o*(UzG7o4z6i}3$q|0fvxY0lECF%icVg5 zM0O#M0l!Ud5I|n-HPD#T1j?zSO|#RX`~f#`OK!2JMeV03a!k*#qL>~ihy+O=K#X&! zM>`yBrZSiWG-@Jxop75tZ9$Zob8UC=3(u+qDY8^LB;+x38r3^JB*0 z=U-Z7XVY}nxpA>xYJ630=X-Q`*b{9?2fW6;+zMrq0|oc&c&7H#=~f}_M5;`wwrUn% z4Le$;qI|!yy@03QUgIknB*;z+vrQk*q4D8weX}6PVXRYJR`9-n5L=H^&Yu2kUP^YF z_L#Njs1;^l7Doz&rQ0@+O02OER8B^#X@|sU>35WFXyx;O+Y`Jove^J19c%@{uJ3WT zIJ>@75KgPl$yc6?oQKC;bYpK=I;Ll@BCYlsd^B2$8~uck8iGg3bS>964-==9^5to< zFT20FGqp^->J%qSb!@8D1Zv-{+QU6#t?Vp^iM9=a%}HQEze|)n#xj~pM{wh^-%I?lIzIQ!TLAjyvy%!25;RlmA7 zGBHWW{~o2YTC6ub&t=uu*JWneJlnU zpgv*vZ1|J2_XBezNAkKAf;cXNMT0jP_^EL1hXp_Gc+pKvODi7OqK_I*DH<#{T{NM7 z-7`8qC*OJ@KE=wf$h4{E2uXTGHUaX164;80D@fdUyahF569E#5`nYpGixMN8)HJ+$4b>?+lDQJoP=QnZ40uo;b9J{ zKK|=Q>9?3b*z>f`$_6;aW%zK&)<3lQY#Z0q6MGfj-y&Rap_pGb)aafBjE2dNw_x@n zcVTjvvGAgcF?M~{PDZm14*_k@gWcso@uS;H*9Hgu543Vu24stkpaC@|MU){>!?#-s zXnjQE@E@?(@))SqyjPomm$MNXJO&CK|fX3LB?+@O?mvUYsC{RHW#MRGtr@y2Zc&XG^GV}V zx*(NJPOZ;VIrtPdT+CF;b+H=|x+eyytL3%}bm4WlCC`2dZ2RoZ&vTYZ+Ma)+O|P^q zJ@SxVp^(;vzC!9`BsfOC8lS%ieBRNdT+}&UH(j6XBeXQJ0$dkCvoYAECTEL4cXijR z7;6LsuSolwop2)li8W(M@M?C>`s9<1Kc;+paxFfSB+7756;1N2joA>eD5l{&+k@mu zvEgj#U>cAhaRt3M(qu!HsNqP^r6^CDmQ{GpOq}YwS=**NVL_i#;xic8m$oXuLykd0 ztG(cI=jD%YSM6{1{y~21J^OontXR}0`=P7hY#vOP!DTKO5WAXr6!+ciQ!lR;J#6fN z&r?D?2#1EY^jX0f=Cc845J(l4e{CA#8DJPq(ph$B0lqyd8}mxa%VIWn<0frSu$Ojc z3B<7rAHl{n=<*Fog;KkWWN~o~QVjXi^;iPd-47dkaWC89NY+v&cy8U`7Rl-8?J&=~ ziK~oC;qmLV#k7g^YC~^Uuq0el!3NrNRyN68KQ);|GsEg)U>J4G&r3=zsiVFt5G6xc_x?+quzt>WRICVZ0R@7SBvn^o#7bY6Rtni2heigP~qrX5*yiY+_u48!mxH?ca<60}0 z7If@&c$sFMl+#nWcw@MYMUb{q(~2m05PwR4WRAqibklePb;H;$AsjEF z*;2SWdub!KOx|#)JcbqFZR>ONhhgFoy5>IaQ5DPn9zMwzEj0YmXc3rjsy>~&I$=L* z^T&nFE(x)kx266Fy#i~1l9_<)YlZbKpdbgR{|ADeuZS)8{FE+U*FoH zhm^XXU5>5^bS8Y8@~xI`t#7Y%Ctp(agN&dn6+njf0Pr$n{^6xWlN=%M>YfM@Cik{D z?>dAi;~DA>LxrjIj3KhUMum3uj?Hda6p*!g{9T0)K49Z5$WoXB6aq@QfWH zQ!9RxU24SDJq1(7I8z^F6*nNAe|o2GKyk8px~z=^K16(5p?s-8B)B&rF*2N!=%KQy;z{Fe%LAfuf5jldIv2x zeW>=~3>E5AoC4{Z&p{W|_cblZrCD7B%(CdhOj6HOsf+(^R2RZ}O)Tju|J6KvdxJ|Q z$iguY7*3w!sbMK^gs!{YqKxP5Um(d$bZ_-Nhz(?6O28@l#qaiE^;-#03La;lmUh?D zYUi4tHVRcNf@s`WYW3I0V}S9wvs9mygEZKPTC}oW96~sYT&8C1K9Ol?cqNV<=g=vW z;Z9KJNNdPoM5{N{g=x~GW7*en1Ckhw#}LFOa1MmzyIV>UrrpRWjQd?S(^`z%4`av; z+11*RyFdzvNmKszWwMR9X0C}X-BbZAA(q96bHWJJS6uopz zeZJz}4!>^1V6XH!%!)-r1&+jmqK8VYtHc!(1oZtB6O$Sd`%PYjwr2)ntNiZuON1Ld zfDFD%n+aa4br`bMi>$lAk!)Qp#xA^_?W7?K8t47KXwKJylQn@x?qAX2TI0CO z5Kn{B5f%sygKDrB;K;Xgu$i+VCR38F0m`HkbKLo4HM3qixzN>0w6f?VVQ2bSL@UrY zd-D9!;IRv7o>lT-4^C%EGb{_DFP!x;?%&M+SyUM}Hx?#L0~CwsqmvF87F(8BTBx?r zr{r}pN?kz@N{e+fr#Y3}`_q%XM-TTpySXcqwx1=8!k`PizmMpsQ?lk>r!qv;2jp^u zcbKro6fjy}_mJLG&A1x<>RsOvEk=#K>;7&Fo)XgSwj)iUys|c2!6CAbvi>tF@t2Dq zMj>`-e)5HB%vUvQ@t> zR-c{L`ba+y4Oyn4TI-mC7mQ!$(&(z-Z^%>f>hIapA-ORN^RQ$OogFnrRZB>F_N8v# z?w5OukvB{TbdS6iSEbwRkN3?g_RB}30d(Zlo_8wd@$n&=AR0dgg58xz1AvL;susV^ zB=xP1G_Q7AJPmR9z}VcGON#Q7GgSSu8utLyA@0!^SZ`?AZON4S9aZmGX*+){~lNK9o|vy8mVD8 zXnhQ$HqHo_SG{c(siBq5(RLiPN`amY;f?oe=m2YJFJ4H49GX^)_Wq6#2v($I!U7s) zkvHxgJw5jeA8pnlWFkq62_kx5Dm42b5xGXeRp##(w>}u7$Hn3vLFv?HNjO~ z%*g7PncmZKcm{d+gdtG6apQZVo;SO(&A~*F?UqWfUCI0#vkgZvJ2xS;t>>OYrbAvM zyTFeR>LT-f$pAM2xN0Pt&F9yEF7<=@ka+$E>5_(%YV+6?nNRO(>9Xc;zkC-(T6G1s z@6O0WlF6N6m-CW2#vlf7W##$7_!!5Z*&^PiP(8k@=6mZ-6rTWDn~NB=yud@BBcFQw z(oi>e`1*$g404QSg|u=Zm0mamkQc@|FLz{d6DUfZ@Hy?4oDL#wJWmc1XPI@j2=|P& zHckdNj;ox?crTgy8thD|>*p8^F^TrD7(?$!oU?X|Ppf{5W_>@|n%Wp@;eh{zCBEg| z2}^H-TS@uLDzF0x2qpqcMdRsO4L_46TEwlX?XJO z`9l|SJiKh+_J_!~HA%qpRp{5Vgu}Y--h}rM$nPF)OBX3Fzv#CuGw~dSHD4)Rc}Vg} z-O`9Iim*{G?)P+yxyM3NkE;rOTbG&&yMo?fvQ+j?cmg3{p@TY2VUHVol~G25GP+Lu z5;+c4MGSb2TKv8mcqzT#O8?uHQK@8;M-wJz0p z78g))0Rt;}cf~%9rH*8!AiAXSTs_;`ca%W*I0YA=G@jB*Nb7G*)4I>7?*Yilx_ds- z5lf0BSMSfLDiWUc$QP~^vUn{_yb~o478vf{z3{YlXNRck(|5cp8$9S$gF;TTo|@Y$ zy(Xza)WhlYr&Y(;t}wW(?qn9fDize|6mOW86EpkQwoabtG{>$R1QdJNieog|Cf@pn zbVxgasbH#fo~nXJt&!O^bUVf=;Ojx1@$n$R@Nc!jh>|U40D0-PTI)^|SNfg@lr3?2 zef>(W@G&=KZI7(GG6=Ho1$7;&B~bukezZ)hpIfoz{H>RcyVuDAyCSoDj2SGns;Qi* zxQM3C5}#^4k9cVeUtE)nW;w0hiJM;Sg)mloP!PZ zXdmtMr?e|^Ud}#&z$2^{H6J3!!>D2A`m53;LV*d--9h z$?!4f*87R{No@?i7C+sRFY?qrc2J9fd?;7?3N>)JL7HaX5$Uwm#QtC!lxG+@F;19% z&MqR;;+vGIMZ;6;lBV|N5_8%`O}0i=+aaIIbF$ppcP`D$$ZKdh=VmacDjqZK}T^8(fq+o`EXr5ZzTyv4xWqyw0#r189wBu^2m3@Gf z`f+$RgciswM6kz8e{zYJlH4S|cr&GY1>5Qe8HQia;S_aPB}!9Q5StKxcefP|1x5K( zL7?kc6LLo4wy=#9eZ)GZp6#bg+wP`DpzY4xQ;u>;pR~7eKwp%&{9{!KENB+v-kxy^ zaM05&KRcL0biRbInSQ|Lg#M5KHB-H^y5g^^CC`8+e*2wn{mYYrZE#d?(kt1K{iN{I zt;MY!!(7pRs@79zE!*_CFXZY!MZQJrs><>Y%YNIddwO!`N} zS_?m1V1q@Dm44N7TB$=Ykl^u20L3_P6$V5dQQgb!ZDA3`H#BfW7qTxODd90!7Cuus z#vvDF&YnXSGPAIJxrQczoIghK_@|sYY6?N9U^;9-u!kn$Rm;J!Y=CgZBk{D^#wEeQ zNH@IH`Htw&n%GR>L+`Z}qR1*}GSO)|f;=uh`Zl9ZCbd2DTYTUrP`~4^tKmbRh2JB8 zyiyW56>%98pP)vJAsr{KUWgNbH^JMa|pzNj*($LRR4~Ibn|zjn^sb_@tnigDy#+M zpM^UQkqvw7Z*AeJKv6Jr*udeCj!>v7x;iziWL#{7v$!npDdzPj3xVZ~SyEt;f!fW!$6A5UFS^5-HJ+`%KaCcNKZ_cR%%(((>CAwF}gLzUleEjw} z`zH52D}f$nTn~@HV#qftimdA>sJhyl)qA-j8KF8daNG1&pqpi7>S1z+-W}{)Snl_- z99dg3+J$F_For@wXTIDrP2O_bfOP#HnszsQA5HCTjd)`voUzJdhwL9R@2-2)?_5d! zJ0DO)s2$v&z#s?D>VyTA7O^^$odL`j9`8`9XkRF&pOHR-etqv#YHr7=9*eWmny6kBb|#7bpzJ7=26YE z&9qY@7RRdkR{CKqPvH)I!#hY<=h2_EP*omvG*d$lfGnn|q^HrML@)cVGB%MIxz^L{ z_lEc}{IDDYzbsP=dmZnRbET4M2=ap?$7buH)Z6t!vgpksd|CS&5-W0bfTE*ZVj~JZ z9yga4j@&7&DmI)=xcg0%wVvZps_{J4U-+*VE~$9tsM0g`m=uO!My}*xW*!8cclrPDOG~q)* z>PEK1^pRKIb+wOuw6jMW8I&U7EU`s5Q$GeA@s4xQ3x_DN23Q!sB!PqRy%m&sP(^hQ zZ#_cOac>+`GJ=${D3Q3zU(b@sXxnl)deMAHz-M*PQXV7}OL#l@YS;pgm8((7PK&6G zZW0O$*$n7-dI=P%(6vYF?B8oc1B|y@1V5Mrtwjj2|Gc&HUQzx$?(Op^H3?W^f2j6sfkcRHt2rU}{nn58{L4hsq@nb{*O?cq2V>h8;ZpG4V2@f5aM0w}1^R z41E7|T~&*ZQIy+x4x~fw)SuL@2>9Z z`&{ShY(uz2AJ^s_Re*^Xwt{%{k-Jkb^0D`#!i>%$L@AlO9!>6-8!vQwjEbNIEazi> zW--2HN9jk)9;!S%u>zDcBa zHX2@{XvRy8J(>+zZLb}p4V1hZNI>M=X)ks58lr0v+27E{P;a7;pY6H>asZT6AP^y{ z=hftfVtD8z6{nefwttaSzV6nld%Db6D1j8%S;s|qL0^8_9)^XP#&NzgO;LI4r|VOpb-W7U?6y+T75 zcYz}R7a~AtSRFokps_?=*&@ep+6r0)*&4>`OMy%$^7oQLbEG&eEo1p!FvjF0!Egc< zhlS&Rc)I@&0{)vlbFy=%On!%@0OMjxm`R~b!AF4=2J_i$GC+X^2Lt9_?Ln4-u1_Bp zk5wkPl7Oru!NY&jlai7m(g%sOm#XA1H7O|(evr)yolFolIRY0DC|*uM->Z|Jr>?zs zZ?LbEPoz>F=v#H?ukey>0~pA6xtq3#;=MO{%HP1>Z+-ghh7j+ru&T#%A_1WAU*}!K zyhv>?bGSoatZ<)pFTj`f=a%AU)!SDW`bg{Q%1560^W65=AE*`4bH1-yH!TbGWmImJ zTzNG6XMJV<>zqh6P;DWdi!b$Z5ODrDvEH6j%Nb4X=9T4^uS8KD6Ji1bIA`eb_17uW z*D1Dahh<^B?o$QK;j4(Fk%+7hz)60cwaL3xM&07@P9*8|3ML$ zm{KxDV9EXgnmvouKvexd7(pACLk2c}_Q&uvzG#Y*Ylss(Q$IX2+m9asPQ^~HO^HsS zY&8B(DL?M=vhT8=+P}IMpZ;o|rFm~OJT+XMZPq9LO0U>WR&b1kM*}m4thI**BTGs; zcmct~)3L_G%e1Jk*D^@uKW1db`HMKb0tp`k{i*I-z&Z^72v{Vr1n>`1ixPuCs(XUO z!h!6gL)^kR*nx0yb3uF}2J*mx6^yTUCxe)B_=2Hv2fB+$WL_PF4Uud8tqzo%@6y813~4%0%U76b3P>_QZuINHgIrnJ*w|PZ z$J1HPom?b|1n59qna026f;xb5xB1b5c0q%yjN=IbsWo{sVD;AB48VE10&Qwr8Y}d* zMKzSRFA+lwb|tcOEbF$tqi<0=iqOJ$h!@m~drDu(>!l44U+eC##5dYEbz-J{*V?oo z$oZZb_+6M_4e*NYM6ElOGfAU!Zk7XadsuD}v;$iY2Cr4xuJ7kcZ2chzYY^|0n^BH-L_yY9rx8-u!|{ z!8P-nYmnH!Xd5@fiqH~2%{ zonBrNn6{<7PI-y*t7;;h|8DT`18g6z5sd#c&%G_R#SetZTs^kx3E=&Vn)Vg?N7RCS zV}jBQAh!5Y0oVd6KDUPsc?0-CzTw5Jf`f7Se0(NGb8!K*Vf(y&3I1kkF7NyDI50E= zV)lp;YkU&9Xk#;?0^VZq&q=@^K{U(!3^6!>zk zg{LhYJ7n7dzPv)D@UPctJFbqg8}<~4d@P?3LL>m;eNMSx9ELM!`d}P}GH7~(0we6G z28g~$Ye9R)KWpq9K$iJG;lM!8v%7Y>5N&q;bwduHHZ2lhe?$RYlti&m!(cY{h`)%@ zOtdlQ?KMf|PA6NLi6gxdJxYg0coYpHVR2)#IW(h|#z%FO=n^!~p+>RRT*`qTT)JjJ zmf)RURk6kOey2fU>`G%1Q%sg;vv1DN>(8GO>>(RqDdib-HzL)`?jUkee77ra#resL z;OX_t0{70|a4?rn&*Us#us!%Rx>r_GEJ@HK5KfOvYzBW1MYVAGj{5Jptq_@QJ0-D$ zi%SZWsbO7p^9I_~1>ZQhSndJr;+%F$7NH(`yS-Ejh+tBBHZh8UD5bx5+(>5}#mhE~ z_)BX#81f>~GY09*d1Nl6#zL-0BaHPP{f2iJMOK{(Rb3Z)D>g;XDY@Sq^sI+ulpku4 za6=v%%t3R|C#eY}LcfD&JN2vB<42fwEi-Z@ooy49H(oIgfmu|=b<6|p!61-Rb2*dB zZkCP`%4*{=Dt~Mu8{(0AF)#P7eFXA(r~lN;uu*y9ub5|D7n;46F_8>-TrG4YlgC*E zFrwNw_y64}jwjao{uLAd2cyTh!f@ApbQI18@?BnLbGNA$4!VTc+>%W>cP&TbV5v4+ z8wb*e|8KK)Y2qRQQO6m;`SRm_^%PEgkzlUjLjHZUoNL^5r%HAW>wH(IzY$wu&iLUV zy-^ysueIG(N_?|zoGuYsf3md%HwA^gz@v-mWVh#@FtU+@(L_H1?+48WGg4WJ(A)afu-y3`&>qBl;-z zY4--(N!q-AP8r$IU^%4JC`VuCF2SY=*u3Sm!vMht?~M~h5QYCu@=-$bG8H%8@GOu@ z3-T>jtf2K9etkaq@KkO7IMapfUU-vAL<`=b*lFT*Te;Ra-ObtzGCLBttyp{dmlT3XA4^1} z9>YIZtWhDiA<@R2+{ZplCTIeh15wx1dpt=ZDEoSIEu|-p#hNaoN@Mml7MB|C)oL@~{-uoPDu7aC^nZ-fh5EvHAOI9vT&|TTd zd-7*=sT+A|Oa!7A6D|Q8H&+7OT17J(TfeKqU2QSAtm)JpiJ zw^uB!St8d;gVGsc2-Us{C&_ zGqTU&1d{=}ddhXGBNUu{@u@lY1XF-o?L!Gu0M1npDe}xJIYu zmEl2h?K{a0b5pn{oBa?CVPwVvsiNvkNK}EkFhh_FUsTG(qj@zRR_XaAmwNx^YwV@Z zOh?f%6`k84WuT-|N+L5O4S6-w_A8sUS2pLw#1mduXofP03VYqZX=1K>^uG&hY@LLGaFMJlW>G$m6pHY1ni~h6k5Wpf7#Rq zC~O}Zaqa>Rb`5w$Mh9ZE$)ve>5%k~z$blMsd&O(7RyV4h&fCbFq+6t5j{zragt=P`#QgXvXQbC z6deWs3Z%ByLph{zJ`DnWWWEL%OkJ`58+DZxB$!tobo8U|j?}nphn4Vm z*)@95=ikksB}k(8ZGr zUF5raGg{6!$s*=PoOM~UjJTZgerP${(=No~28iw%X&nQ7J~++Q;ePPNt{r}!@>Vpg zxsn&M^cKOh!~O8+E7DDXZ|ih{qokHvHDK!BGbd8t!I7C^3n!H5jltUrhD|1Nb?N#d z%F^M%>y*rX5$al0EZ2be#r>!jlhFu5-gVbZh5FQOMWyZ<+aKR-vi;lRbj`M~XK!Pg z|Hathc31`EPrQ(rf@ExChhHVEvWOVA;Z8oArGOv|8dzV7pN$6anw8VT!kerf*zk<) zI+!rFQ_iR(wkb`L zio%9Zh*{2+3c`nQ16LnMmPExKT{~%ue0j+`crI#zXO_CMJmvNGg8&LZR zsUzw8DSw7bq`qQc9fZH@av5jvwG`D1%}T9cMtpZ>K&!|uL{&f7&8A|RQa9oC!+v#e zu8+iG{0a_TZ&-r@S$@`KK{7ER#s;PnZ?!R5Em|j}+}T?p#&sTs$f;nD71>T}P%&hb zaC3v>l#FzM$`L2+VMqtm18bX###a5~%Inu(jFlx5qs%d&QUSGw-D&;zUgXqNY;<{c zuYTmqeM&6_4};qq_vkqhxBmr%Sg9i{uxF|mS1=ujBbd;wqS_umBNl-V7nl89{8=_+e^YiqKcHc&&>aovbm6$FCg z*Pnu!do?7OySLQ+E*zvHy#m+ZJWXMilb&_MBfj-qa!Z2@*?$+7m-y4Zf+wi-`{gdQ z{1;0t(2OkEz<4?t72mNPUY`faOG+8Ggys}vd)-%dS&NF0u~6@X;C-^@RxNNY01nUa z^U%$7z&9`kOREdHU6R7FW{h?@I6IdOTH%{6L+Gw2gtv@l!fzRCFEz_)gsmow9PgQY zB9W&k8Xc1Bed?Mb@mH_@mpe?-P9HucP+UYMV08qagOxYjN61v74QU9jB=Q$#Nqxon zBbPum|9!>HKpx^oU%w8ufR|oXAq(^$KopZWLKJB-0}G_ zH&2WbuJR+ZQS`6%`@UQkFeg$t9n6PkRlZC(kAU~drad2CiFR!v3QLkelm2%F{x+gW zp!q;}jIyYLp>+#)SH?9KzL@kxaQ!Nhz)7icgl*hMrmpND#Uiav3;yy;XS^F)T|Y~r z@beM(?~5e!E-2-pn{k7g-c6~qdU&nRmhBJWU;ef5KZYA^llN26ye3Ly*ptm<9B>RZ z`oL{!?T$>+#7jIkM`_>Dlw_Q7=u*z=fr^7CRW2My{iAmoio5ytZ}UUv9BQ$d+2d5K zr`^w>x`Wz*ZGy~a@E7RD4x1z@-+G@*q86WS|NUL7#P>TF%v&4goks1lGjnN0ytA4O z8J?h)q?)4i&pQ6?!KJ`Z9mbiNV&U3Qu@hV#^O~40%C*&ex?jPI3m)t0*4`)S0LZHr zQv5nuFW4QNgd@7)X~5|LxQ1ms*UR>Vcjvv4z?Zuh&Z%+H&{Pj3Hxc0)6OmAtT5E}OJyerGT zVWwJgCnKUno%mI)yBn8p=3@!suWKUIjqd zNgfk&|23MLlt2(vML1FYO7 z5Of}srB0%EC$+XD#{JD$#=A=}9dBg&DyJ$Z@l(N@BesIzp zuNgS#Zq=B|nXzTESaBw&)&3w^d5$aW`1|~lHX59GQ!twHQHFBOdyQ48r3HuD#N+g} z8OtnIgKiS#$3ZE@sJP>;emZ`HH=yI7CK90nWUQl<i3knhXWrA0F_gPL6GF&h^It!^q`OzyR8m;JK$*D)zxvQ%}oDSYMh64Wk zcd?mZF`&+X0~gqzj{~xRS_hZG{e5Id<**%|W(KJ< zna61xZdMgVi$W{g;oS?PF^axxI9@T!tz<#G8Ztvccxv8I8iFTn1>N%>gM2ZaoZ~&x z7IIK5Q>oHFYRsYDUP^b?Bwn!d+zze}w;*o)7no$X3kPB?9`I;v@Zr%I4cWIR-2Sv0 zD8dt=tqpcF-&-dqQzEn5&tBr$!$Z{a$FK%1dX__wFzfL_;kRk+vD=^ylKq&j`mURy z{EZow5-Lb39Dx}Iq!JE8Q)#+d)4eiCv8*GYJ#&lFCJh;ic^YA*`>iboJT6H6?|>j7 zBA|xIc-NG1d`+%`9POLxQaUB?Q-;s0mR>hXo+<|EmKn|Aw6S*w6^vi^F94N2suo2L z;yx|HDbQ75Hn3U-dv3h1lXxMyY1zXT2vWGY|AmLiq4`JxQ)l6#837|J)n#5V`l_Kq zOD0xr@0YUO=d53Z(QkIPRsDi`?CnOI10Zy_gt`<^NOw0PgO<~mlbq0!?_u#S`jx@b zWLy7qli>_?ueFo!R%B&%E;(@&pw}LgD#y9aX};E})0;-27VIi$VJndtT#&v_2D|Kr zjuuBRU%v!t__O)serGe+sLwig=?X1U8r)*pLH^YKeX;^-bUswO$5EtNt7TM$0_cUd z{&%WaO5tGgC=(1nJ`8{6aI4HFrmkFQ+jo`6T&nXppX^NiS->}K&H?Z^7dITQy7(EC zQ&>nQk3H!JztV~0PCpm!vs^Gh<>gyR(BIi&5*I(Pak$7AlKRtF`t^bb9yOX*ug+jvErgz@|Rq_zVD4i!kYRz<5@bw%0A%04{Fs1A;;v zLZ&HZ^rdX50gskD!DS{aJG$c$KRvxp$2a)UKzkuz0Mj+O4&NuAHl4X7X?9UePvny$ z8=oRAPX_XDQL=7((%i}>CC)Spv~|=(YwR4Q7m7MdMlw!vst>s^bw}JsjTq^r$@An0 z>I&e0z{|4t__v-1eLJ~KfS!(R(jst?cL{mK@s8hHee)dwluw095_Blq z_D65o*rY6%j>(p9pE#YD>$^&(Sw^Ma_1RK2sn9(0#Phx)2v}_y17;MoWMEeom9AE+ zdJ!<=h1fndgMxe7a*EJx0w`&uQkcZz(C$I*tiLGGGd$`Q*0@mV4;y?Fci8&48|+kZ zlh*kYNVfmp%~giXB|aDxP{$`iiK@rnj`gg+!%|Yn$BD7|wGG<5@GBy1$g)eb(@!y6 z2rM*ek8R%{x5Ck+Wm4Ene2f21yz1E1dsK7^C#qQ znBQd7ImydckFJ9lyW~a5S%NOiWCU>s;YGIBU3$1a5B}EduwiU2Eq*Me{xj5luP$lh zuqXRLnQr(#o7)&u)Y=E9R%q!zSCBaAK64f+Wc^5qpsL3^z7-%6wET-PoqHDJO+Mh^ zpARWn`$own45%K9Jo0lN@I5M(VAq<# zj@fkNhu6HPj%RdSH=Df`%wYOHk7yPMs$=0kAkw1Yw;%2vk#o=*zs-Jy_7m zaqmRA!pG&GQJopO0_^C)K*{9JDOiiyaz<~`M-w0qAwKrBTb?@7;*}NdGwyj zLb>KR*<12l9Q;ZCMQm|+w@e$-tk4dThXUrU2CqBrhkwBL*2~MYiC1#riD}^n%PMabqTM@(imA4 zj1TyQCGq18@dO#h@nb^&s6w(rlC6((OhI9qDdH=%rAC7z@y9j3&iQgbklek8!y2i1 zW6kHB_C(WWw3aC^<#OsAbU`8OHKb=6p0ksmc2X7)@0Ok#Qurm|6#De^h#A1%$!;1} zsGbnZ`^WTWYahJ)s=sMs3^YYS7`$-2V-H{p0e_$rAdP9#I;`ikN?D+Co+JiH=lZ75k0CV3$G~%%PF_ zR$asD(ixdPLm46RcX?t9n+=v69o7cgLFENw6>GtyrjbNC2YxofVsHTyFzyHEMDz%TnN{BQE+~By+WpF7PwA ziOT+>iHDbHMx=J*6%t+YHp|S*%){b{+u}UeiOAbhs0JVEWQ)2Y>dP5 z;|!2__>!Ck^5+nfJNLFi#84x!R`Naxam+E}b;L}f|5rp;evm<>?C8NI@K zUh4_ae1q(0UV0=6G}0xZq>RcK5hJngphX(EcSx8AJznMJmJwd$o6Cdaf6!PNiZ?Yc zVPNKO=3UKBW#L%V!bAYC-`JC+R&z;9?Riif1Rlo78LLv zaU}A3HK1rK=$Pa4N2VfNNSgksJbzE-4cfPLXHiSuN{p0EsgB$E0|4yQtV+hYRItYi zqhv9dI|#6>u+tW|B6_MFFivFnO1#H;;bgxj;tD!a#BGlvl-VN2W9A|n`((LTwEc~1S!3pA&D4!dKXu8pjsGR~a@+a(yMH6fzw63zl@WaL75OiuHD zXX>2wdjCivs*h_Cc2(|lE+L2TB3|@psEbC~$tjo<1W%|PEkr{7bek>&0eC?7P{+<(rBH~ zT>W1#3_Cj~ETfF+Z*wOL79#F{?omMrcnk<8mVZ{Me{2j8)o+hZ<6F`o9gyH4!&6gZ?~+_X;{^KA224<(92}gSoNBC|=4vGg54hjVd~tz)p&kV&?tn}k;bh;fK+sXM$6Ud* zn*13MHkD~f3Xze93VjW+>_;zzd{hjL8A?73bM3?>Br5kkcNfI}{iNc#7@T#x zY8Aw{q8pg~K>y(Vj&&b&kOT0~tU| zy5Gh4cn;oYa|^bRmJEWyqu4d0$0UZF0aPk$IqUKzr+DL*Wp)`IWKE*)>RJF1lX?Bt zQvw99A6@q7WzVCz`IboTZ{(^j4mE?&!UbEDWClcQE#&Gya6ja38B-{sFZ9Q8Ai(YF z>gw)p9l?a6L1Np25Z12l(+LoB1tWp(t!q?pLPn?(@b1$vh+!yeNRL<1I|mL&NKgYg z1|q_$FPrBnd>mxxY6$IakV7IXCWwozb9tuW)2R>TyR7a@5b#IJ3sBJWF5s&oGJD?? zCTQ9H{p?c`Sm{ScQ>|Y}{WN)xk=4OFMZ7lJF@mbLv#SI5?Ghh+tG|AkVgtU=wry{L z+_HZx1jADo%cyWgF36`KHy`?yEkPwP;{RC{X9)6s1T#8KNgn`m|0T5*o0YM#djkIc zMc^wa@@d=pm38n%{_)irTOX0NL1^|Wc>Wc#GEQK9bd%DTkf>`QZ=46=je|H0w4M5X z;+c}ik}nT@cKvl=sw=)h1_CtJK9nV@>)4j@O-f;dHJ9H@^Sauu6E_jzK}$uldb$X4 zLB^E(KF1!}>@aL|2+)p-^*#*2_$TH70&2(_U#(99KE&SyzG(>wX;7=mXE`qGAdK5{ zfm;6SU$Gp%QRrYn{6Qeu$1flixpEd=yrbX-b0FGl86Of~5WXNBK{zrycm0N*6x=mt`XM;x7Y zJWF2*o<{#F4}M6iuk;!m-xsZ_p~rx|>aK7}*Q+HOc8B}~(!K7^sY#?vu;8d+Nhia2 z5BFaNAmlEGNn5=5P}8S`+05foK4~P!9}$+^aj=UgzAF&|@J=y;SAAl-NC*<>5o6 zltOW9lZ>7@qtnN`wDpcI9qG~ZH1Te`r4++ zAgYX8^?LfcwC3d`5b6}x-sl3(BDI1gM#lhc5?>@h8-PGuf9kt`U7dQQoA7d(ofZV` z4*7}JMGRVrUR!r|$A9Ka=;hs?b@ahHSe*YT_Of;gkUd6b;YKS?8zaZu{&{(tPe>3k z!j+?*t5A4-mnm&@eHp89`sKfnyE>A~(wMLS3#K-rgyb*~$bPw!!#^*s)W}m_FcvCKf~H?7@0^>ijQ=aVO=)>)!06NhcB=xZ0b{F$Ic4PM z>@@lWwKMfOY>@jD_JkCMGcs_CN$%#VcQmEAk?$am^h5$@MIB6GWd#~HT2NRe_jUvx z_DqW~QU0WoU2ccZx+i*u25x*dujhguOxVl=oPqkUE1rb9+|;A7o_%7Q)Arsgen(RK z{xGKX+lc+HO3+-+B|r_)11he+G`q>JcCQ0lAQloWdDfJk7K3?*Uykx{xzgP%Vl#GV z5l)>4SB-Hm3oa-T4!7~NN4e@pc%aoqUi9yc8?vM5wz2(kVUJOLQ!!*)-*Sth1P3ZJ zU~n3ZdmCC1ci+U|ON;T=I5)Hwb_PMLX1OO?%ugFLJ-_elZ?x=7X>|E0b&~w|aguB7 z3`EZdLzVMFJ~Q;Qx|YdbFfWE&?i$#5HX)dd4tP`MY-J!9Gto1PAElNnrRrhkan^+& zjD_YE8&riY2}T<}zXFv#)%m{(Ed&NP0U^pWGea`oU9hGJpexcHinIUF6qkz_tJ6yJ zy5u)&x#T;4bsCos#a~u}-lJ$Iq#Wqnd$KE(LY&y+o@TM{7m-uCs-bXP;vN+6xGnKP z8AJWZ`#)_B7ZG~V4_m;iGz+#og!L3W&haE#PXp}d#1&O2=gE+%hl^LaNq63 zv*i@wk)L#4VX29KxhspiTT6uMmxiVXWvJ$=woNe@@)#Ks=KLijPHTj|SVa67>H|cB zyhV5$;w9yh(pN8Co(_%qrAc;8E)Q9@7 z0}S%-j}wpaA4gT%(6xu1+S0pftj^hmwRvLRW;@sIqXYM$7IBCnyf273q(D&qf!o0= z?LU#?H-!xPGIbq|`@58K5#LSzh*Uq?RTkep=hoi7RN*iL-i0*<;;{FQy=+Y!W}2;z$Cu_vWJ-6HS3# zW!31&BUP9$f;c-y-QI5>+kki7dREk}>_q)iFf8J>DGsvY%!1JyMQi(sB*_sUm7=Z^(3osY$VhZAq z;IK&;|CZ%|9Dhy~m<JgR$UH>rR?4rPKLZNO)-t(@6lHDw|Ys)@Qhc%f)o*Ao1eXmPYtT-Rf=) z&u*1>V*~bXEC#y=CeYnK{xSqQMi{+d4}A&~u9aT!#}j!>OQlZJRSPX{@O`5yHatuQ zKG?aTuLj0*(x>!5)zG3$AiM3`f$kr_*ECc-g2SKwneWypwx_7N&_08Zl4&d}?s2&~ z{__mQdop5wq20NDny9Nx=nV0NH3VPF3LGHrIG?3}k6?{)cmVnKWkyM<9^?4$qL3ZQ zqu&(4Y38|LTA)f-KxGGf%l7!~KQ5@icz5U@U*yEyigz)^f~?jaNJs!t=l{Iz(jQa`pR`6|mzCoLU!E1w2G-Zt<{Nv9wR1dM4w^|}~(-GS^ zDVFy4d57?As8z8V%`F-5aN%d>7e2c{fu4N6 z2$mHH?6*NOi8WExHfQO-;L%!H};wY#0&SHE171lQ^ zuCS0i*}!~GBzRiej4{eAH+d+n`icDs{$XMM$>hc}_W;Wh30~};Wd(XrkRPCT6n2+g z0Pr{{nv~~aY7Q3gNE6rN>HOv@bjd!}o=?Ez8ERhmEls=uMe}|b1DTOXGtkofAZ9Py#V5;~lN3riM9)2NyP5&orGQB@LjE}?>7A-gfoh)pkOaQDXy9HYp6(`O0 zpjsYNX|X&Z78knd=EG^0>kh#wx4&1qATZVGqlo6tU5;7gaR+CkfukpV`q8r@IzJL9 zqHu;*WR0fle1Yrc%|2r&)6$}fCEGJ-ETvX13; zo!4jfgy%)JvY<{_hG-=8Hv9$RnChN7-(q3S9sCcr1$x71fgbE^11%iope^e}3b01( z*$EL+6s`&>K?P?Pr1f%*psVM)!&PZD6iyovrG3?c0)WnyeAs234-mv;CfuyHP010z z(uPK!$o3Ydd`uouPRsB)DptA0SURD>!ob}AU=)EvQ^ObhsDc_Y(LN7EzE^b&LAEkq zV3Yop%-k1IwlgB5B~Bc2^@Hmn6>w>0Y{&ItwR(2>t?|aA+{vPe@Z{!^*!(T-i>Vaj zsp1@I4B=ydc$a4-(m%4=b2Lpp(*eL}60KAEi=s)_`lFa)4IVl>u0Z z<@37gIO1_-_lILKnRCUN7CJ^^(DEd-8jjkGeM|m8~b%?U1QXFh47ZCE*$x7b}g^J;LAKd&C52_=L zx3k)0wdRwjj8eK>%J5sJ3}EAISE-(4%H%S@hI~ zs&}d1E7owLYHf$N)LzN53DJ+_md<)_Psuhiue_kKtY9>!Q zKB;-&dKg`$dRShZK{VklBzvBV9GVbOmH$m%{~2Y&WYFEsYGn+pQGi;5s1${>4AE(P zS}Yr>N6Y(aF=0OImq4ibmj;`-cA8Ft3)$J|4OjM%XNCCNCm&S!zj^v~RaOylEBTN) zR>*T5OuxA>mwkyxfJXFvI4 z6PG@65VK+`P?`A)2*3_0t{|U#aLS1%8WS?qS}fWFjGQf1OCPfYjMr;K$Qv35PxLtR z;FenI?xSbK zAW`+s9_yC^QdSoxVV#i@@an$#E(Mb zKo2{JIO6>EPZ()h<9jj-bw={jEj(^oQ6o4(C|T^M`3J5a5RMY%RLja_MkS(Rm@ zgzgzy+_p>9KY$D+aq@cpoSPFgv>^lbM&gS!ORXhk%3B}ZNiaDT(PR$s;~P!K-tQ>G z=wL%3xUuy3&#QL2Z;sgJOKF-xSV19@cdgx1Fcj^0aN%H23Fg#(hon+Sb5}mqnlE;h z1tynBXipW&qlrZZ>eh3b)Z8)rIb=%a1C=Q9IoXor${L{SH4;Q>r zlDE)VPBhWq4j=4Fc9az!&-08vvYngkU#8B!GbHFZ59@a<ll}AC%MUd{W$VTDgBB08;39FYAhprn5 zSB(SH3TRhNw&u9|TuB{m8Bc|aau(EVGOVz1nIG9p%Jpabxc&^rCwKpd9QRx@3E=a?_x zB-g!`$RCngDykdYLtuf$^j|+14*JdiCi?@|K`wg8h&)rx$dA@z*&rq6^FkUIznI>5 z2x^bZLr$ZuApQswtY+pe*<@-V0yzaF3@~Ck$9$tRwI6qbw~8_|4f2lSup)i`mO!XO zpvcx3_Kc1a8c@T_jxIIfRLZ$t@rKe>27z5c+$`DYa1KLrEfoJp-rc%!U{~#3fnw>G z;@O^!=%N(<6?IE+Ir}WZ(P9DS#Jt0oqQ1eiTbpA+H7(rpNB!cYE#mxZ8Pw+d0U(9u z*N=O$2g?0!M?Vt}`zCXEj99rjDe0e>0f2ANB=cb6l?|q&ypQPN%J5}zccx85?x#Bg+>(p#et zt~Qw|w&l0VAHJv*IhtS%wJbgx@iM^+#iFv`a)VaSxn0aU%=t|kzoQ;0k!EowGtB#y zd+yb!=s(({?F83g=PkYN#z~8%^p)^Omy2;2AA28;TL#;&mHZ)r*2+pM0-W6r-*#)M zhz%2;CO}19cQjk+$QYpVY6?UmQyiA0SyXgGqrhFN<`?eHR^98CzaHtkGB2wj%Kc|6 znEM-s;@-3=)?18pO9POoH99Ih1*x_cyUwebCn$>t1#KmtQQn3cMa(&K;5;BuS&Y%J$*fA_ z3b7S^hF?TWSR}qIX1fl0G|Vh00;X)oZKAz3Wj2K~c#Z5SWiTNuw16!1*#D&D@22M| z$j`n>A$ZM{pV^WPm2Wd_t=8<5dXB=bWv^HcldKL=!hS5;j^}-l=^m+G?~aX}A1^d9 zl9~l_t7D)S{g)Cs08VVi7E=ZOQR4#6%bKY^se@>jA-45Vj1-&^GwodR^p3wYDZC(U zdBaH7s2t)44!JG*3>p_&R+0e4x|)v|P?@*Z*#D_{Oe&f%Q8vluAOx498c=VNC3_Bb zc8)0v@y$5O+?dXU7@0H2)9l{P`@n z3_(Kj5Nwt;hAH%xW!YHE4?u2kXeT{!LjC30>u)N?+)z~Gwm*$9G8fQ<$+)==b8nfk zPIBLoMssMMX#7N+TEbp%pFSYTeK?=~bpE+=R7;#?8pOq=j^$9JfIG=oo0W|1KIk&1_O^yAP_*1QCko+XdZuvzev{j7#ajo~ z!pV1PDLee5_R&E{2SaOBw@Aw_s%N)0RxP8l+p3`Z1@b#w5nTGhR7uFFY{V|k`g@+b zu#NuqpD_n2-Xh+*PK_&zOAbaGtc;XXr#vFYX?0d5@ci{yLA?v6ZAmfm$`GtQYGp1} zr(<^v00up17KNt}He7S`XFH229MZM0aSdemof{6~a+VR|rlbkAT^ti4Bvm!?6x|7$ zrFEGEqH1{3$TXxgiW9>ovJW;sVIt3ADt?mcfemQ|3Ge*c^oen4@^5L*cj7#|gqGRm)QE;>HY)k8^=q(OvyL|ic|Ype|;*$?3kaa?Wdn2ku&qzbqm~3 z&Nc*+R*0O#VFh!25ELTgDH~AUM5ok6w00l z03t(~K7334s7>(q0O!mk{yAQjg{J^Y0i^a*Fb|fBz>n8uu3&;pdskp|%N<#S=uu9I ziY3f42jcLbgdb3S1R@_MEcKlizTIjne_ZUl#`QOO%E|QNSND;ydos-}9GAWAxn;n~0D|(@ zs$xw83KE$h0omxCj;dqA==n_OFeCoTy^K#^C66_3K5NLvn`k7Z@?)_6;k1hbnPBML zmjT7npQZ2P9=e=EHwuAs_LWLK@5%L@5nmW~C?%|6FNk&K8_PL6%H-F=o3E$6zz@p4 z?_UdZQqmXkD2!RC1FnRheGGr)>lt}lOyN7>rx$xu*D!hiVE8#lT0R3A+iZ42|QzU)M zWN{KRZWx@GUB+9lY5IB9kX&T+p!W`{*PG6jD-PpD%R+ED?KcjFk?&3}f8Y;RS_DN6 ztBdK?#IaP|V$i`t7ujX{i10WR;m1Ng)n-*Coxr@+s-y!s33HONU$~B8sHH4NCEt;&Ev4Q9 zULGB1jHwc@#URJKeSI#{J8lNoH7&ZOaKLQdk7#QX!bj&<@iHz-HoyKpZDWsT)HCdQ zY~d>o!l_fR(lv8?bZmuxg&MiE{1}1Tv;yc<>a4dRto(aYdC3Cj*0}l7M^!s$x~UQb`C-epjK< zK<@^kQ^%rDgl(#jnV*h`wYqe!5a*p#L`a`Ew>RQ+PO@;xY;v~O-WAes+-XfdI7+L0 zWekm^8q63gg`ajXM30#`0rG#O{H!Abd6E~Oa&@(Bm4}F_Z@IL|*p8Ww8ETn`6x+q} zoZd*OUXh7SZ~FO%zY^^4jBL*$G--kVP8I1Q{Kli1>xd6n!B}F4MZM(g`cB=zbDMW5 zU^3ANELL`UNE&y4&DeLU>N4!(%JbHMzRFa{ZiKiq2QgNA0XeOrNT@FsgEE z;lz0vq{;&RXIDMk;d&y|WcnC=zVA26SnQrRGdPrA;IaBFktDid%ED6W)ONFNqO~m$ zKNfYNBF}c#5i-gWVJ7`smNuj!`@q4c%he zx+427bw7!X_sKw}=&QC(#{JxjsAE&@1JJNMmx+s!HlGedc7)AXbDe|d_niG zjnWFLB0rchpU72{eQS?;ZzZ1}sUp^@tsLu#g|Kt0<8VFq#8{IiP>cXkgq8mw>oJK?dY_WJ6b&Hh{z&zZ1mU*asz zincBUuIx$J@5>~8oTciIz_u~&8Y=WL#7|Z5U9tCDpq@I5yI9m*J^B>>6;rslp`a{v zk7n3tKlXpjeJNIRAD@KM)7J59(!UX(MN)RMLVVF0xvSn>NY_1th{08P$opvbv8c6} z*r;wFkV9srj{4nC0>X0~yMXPahEjSes!z}QO0BE6_&^R*6CrF?I}Ve@%RbrVmzH@) z>9W1@cRg7aPxt9M-*P5Yx6y3Pov_V&Q+!mDZg3caV|Wbjf|+z2%-3c-BAx zf%xT#T#Zn!qn|Hm`s&sNGq_oI!CAjXn3Y%?#G8cU)k4=Ok2ShDs{|P(9*XAn*v!xt zGPYg3sGjFHWm~6?evcQERao3M*q@uOv2AKJi)=)%Cp?bvImsjn%v@6!d3P2x?$8FL z$8LWq%Ftdc!y+wvyZ!7@M^$#vHM0IE2eU;Bf)R}?^_L_4P!$LWRb{3JUI?$OpXEi1 z_`VkwdOD{toS4?T2<5rKRHPTB;r{KPBdens-F{5%wRt`dqm`p7jpNWUppSp>!qqIB z*n5bfxZwjh$P_hxtamps99BBq{&I>}xa)t&_018#4unCCgl<`EtwQdsWUu>K0ME%@ zGd&a=j(oGXkEep~u*th?JXAHq1fat5KAZ-;n};`9iI z#)i1_=jQvks81#*o37@|VoL&8DT?(wD=!C3;Ylil;DF83w7CPys0b{p#8D}WtMR&= z*6g3ZQMDG^iKZRGuX>&G8K(K5;e3C{ox{2eFj$YPGy*nstKh>gWk{XSh&6J17=`p{ zp1A5wH0*p_e(!lZZ%$V~+f7chEU21im@2g>z*~4LWEe zBewZzZE}LHD5;k}Ry`Qj*qnu z>6FX+8^j|Xew zF1@C{L`|Q0L^6%mAbn^{KFo*E7_x^_B;{teDm<>@xOX%K+^WSOh4MN~7?}HpRDfCE z1D?%ar@dt^{~=N?07cM1r&uJg&2~v6snkhqO_;j%`Dz(Mx~v*WzB%;@F6TYQtK1Q1 zpk~ZM0(~lj$csk>Q7?Z=fqnPEHB{}N;<3{>&N0h(505zsjw&D>OYrL%WG}T-3al-3 zWML=V=2+x;3V}-!`}#7WRSVZRTXImwOqmrrla$yf_*OzsaxQ)cnTZ&+FO zN9>%cYpMqcA36L`_bsg0T$c&CINR_!~3~EwBfZ zBH5Q5yOh_-!Q?*7O&Te-)t>GY!fp?vxf7-kEro_m`t~?R>kr@uSmoPB+PXT_0kyn* z=XaW#Br63@&$)lr+f2QJFNBg^RCZqqzp+4JYJi1T1j99^xIJ%)tenzC%MOtx7eH^f z2|a4lM_rhhL$~aN@$-e$R$b%oKPO64lhkWN&owTNTUb(?b9FIieAl=1ZDE%wVogVA z=3T(Z%8M>R|G2$<1CjgCBaO_rQ|*xZ)_Rz37dz+MkcoeblE$KulkFO? zVAR4f3d;7Z(4KL#*(ZNdqqW;|)#g!ekzEHMioWPDgPQ9I)%PG$gh6$(fK66fa(VVw z9B_WFH+eP*^^7 z?g2-vTFfGT;7 z)QZZsaX+ee-yG1*M{oJ|%b|t?NemqpN_-!4-s7Iob>5#>tOcww?V8C8(+epc#={z2 zP4zJ}3`~P-Bw;^gKKR9L!iwz3T1^yc6HOi>y!L<7jH?Ud-D#~j2ugU}j~}*`i0{6_ z8f~`Me0|2qJ6LjuXv!Sr0(>7u-=a6X^Ycc?A>Eyzb+8bK=5#^RId)B&V?6v;rmY{- zV8)i{nba!y#r|C96LIwk1HpEY$Ff!)OFaSNr}!%v{83xO0Pg<)J}V2Q3T19&b98cL zVQrUNg9`~6H!>hFAa7!7AUr$@FHB`_XLM*WATc#DHJ5IX3MBzKlMyZ`e~oqpR1@sm zJ|!_4l#WR^8x2Z#cS?;hV8lj@Zcs`TkQ9)VMg)bk=ae>iLX;lKy{^J;)#0r21H{*3;W2#)w241q$CZtf6-KOEr*bb!0UfVwJL0w_Ne z9}t4D|K$jA^+KZKe<3~)xGTgC?eP2H5TJ^@J`jTD_a{3qs3+VV$zuW49K>8vA|5!V~5%vzhDA;?u3mPNf9^No@ zr9VB;5a1uo5rzVafh=92OzZY zz(CNi&)+L6w6^S#2v`4q+$AugC?+Q9dw2omw zu76~22@(ZC(O=;Iv-p39{QornE6e{P`~NxVPJXTh&nz^km2*99{pue?+*K3fvE7uLnm#o&FHeUp+vl zcZDNhdPpz$uV)6x4+eq$%Z8pcs0;cj@j`d%w+V(GrGJ-HMnIAFzh+KIR1665^n~~W z(2Ym$M1g@|^l;k4{C?{iC@6qHqR=5gG`(P;1JV=ltDj(?pc2d#1^I>k2E>4ZhHyu> ze*jTof1scP94+;~0UBG6S(PM)y;$N@qlzQ}(< zB!GeeFwZ}Le-VUwdwQaW{8b<76ior3CK!wdT4eHN>3Cu|%*@TtaB&8EFvzv8P1t#Zc_UEjC_9q0Ci zlI;afF_u%*zhP;=d?~JY`u6#q6|vYbe+|~VbkfqtoGHu)o{wjJm}O>}RgY-Xs_sS! z5;N-)tB`2F4e4` zv5K%R00eAMQ`3Fop(i-31vYhW7QkGPPl{<%5S5+@#9Hm zm>!YI-dZWubYh1)+$E{e)_H&Of8eWaM^;^@a)mKB5`S;2&h&uLSwY9)apzn|W29cc zQT#M+bMYsL4cq=VvRB0Y-b(hjqo#$Q>f@iJE6`dPI{15w5N+m^`gJWAH-A|g(>c3; zof{9HrvJ2(Z}!C{Rh)WUJ*!EEo&It&csvv^%{jMb^!$dqEaVQGI{WaAf5-AOJ$2Sv zer<~6kxdgnmtm4Fzn&er#di~P*_0Mb8e&di`>$4JrJdwwtCxlcaiz%GSrd_VQ$Ed$ zw?VKr%PZz1()?Y_uKXTGP;&p~tz)R(YlVQo9=ZYt4C$rQdV6r()`Ds#XJ9w@bBCP$ zuu_P>nP*$7QkAYnVySY!f51rMy!3W57rS+7tDulcMc>Q1`sQ>9uDm`7(? z7x{}P6%6>b{P}sM_^0^Q)yvI2*0i^IQ8<$2boY(`Z*k;racAoJlMsr>1kYR7xp~v8>}5~)3Z2L0 zr&Lz^g}8}z;odi~)^x>Y9u6=`@c&u$l0~^lf>f34G=IJ4f9v~(_iYL>&aEUH@8Y@* zGi(zrtx4%_GB0?Gta8{OJ!YJGiq0vss(A7+UVx-I8?D_%dHv_%(bSB664Kny+YD;! zj-MSaNxONa%gO!sZ^BV)1B2OC$->{R37;DWk0LMf<>Co`JRnhBu<|SH6P0|ESsx5{ zFM%B4UF4mHf3SRP2hLL3_YjcVSmlhtQUeQ&Qf*@99EKU_Y=#e#ip4lO%=qc{Jy&CE zhEq>vzE+Sji*Vqp_Q-k`Sq6z^m6AN~)8dBtb`{ek&39)g@On-tBtkdla`J>9b@~9Z z(wFbPt&{=Vze=KlaQPP+fVe~m6KvSmg4K@=D zzsO>EQ=DPUz9+iE+DW(QVXm%EjY)tfA>OV|ew3bRZJf>P&EVcn4y^NfExqYx84(_l z+U`y6YOU&|)5koGD|fNI%*BwN=tb;@({e6$CwYdU2FLDPJ35?`f@cfAo)f#gxJPVF z_Uqa3M}f+8%05ojij^dAxNGbAT|`D*TBb&vxCz7t(%`Q?!k9%@;$Xz@9-w%&9G*bw_8%)-<13`cFeu+Qs+^E zp+(zWt5C5%^^wQ9a=e+`iDXJWo|A~}R-4?cl$(G+l%PjCd%3$SP$5i^p4igi+nToq zf0QY`l|(al?I6=B<%y4j{5?yFeNpd_y|o8Y%)F|KVNyqL zRCrl*$N;0`bfMeP78!1|>GCK!!;zq!laXAvIbP}Na+CLzYPhC(dZWw2hd~!udG2n{ zK`bprZN~QE8}*;tX!{_F( z7n}S3EIG0G+i#p%d3#rS`z)VN1tt%rg!-p$l&4yawvy_e7Sql7D#M<+dRq(gQA`6Z;m6;e93eZjUSjQ7Qq2E0OV9$6MSzF2ubBsy3G^J!|eO6+JK8Bx?v%Z+$wAB||yr ze`_P+4RTcR?ZQqZv%HXWhr*fcUg5h=7K0e_YCxx>O+Q~q{l!lY0p%bde*!r;l5Qk+ z4=!sKXE!Jkxo{MW`U%VFxW=ZznwY(5&>8`UY;z=Q*;@<+9|=X7{>UO1*cK^y8Y!^X zV$D9pQ#8t0OEsW06SQw3Tf6&E{NYnm@B!v4A|7I;`+BS30cWeT*k!^1jW){D)Vu}U zt!FZf-)}3?<;v>W-0Y)9f06k^KQ!Y~6Sd+vq2+PM4U8Daiv;rwOVN3c-Dqwb;>z6a zZek=Y&om?!MgVP zc&-Dfe4(ue8V9+Te<8{TA1hmizn`hP;GJd^Py1*?*rNXvKOoZJeJt?^4O|JS@GM(8 zC@&AehAm`w$D})}&6N3QzwWldf%ieC^-h!3TX7-Qs8{XL2bBOn@!M++hRReeqSb|| zx;fLM`^F!oWRb5th-%49ElICG-ub@9oa+&XRZLB-w}kN#e|7)(juYl;U03hW7Xv<@ z*W!;!mF+Mhde)mQL~l#e9m{lQou%VFKj@jtzI|HAdZ)$7kitN|c1K3&{UUB8zV4)~ zD=CY|A{XhH(w1&i^s%?gF}8?JF!Nk*4r>_^Mv<*fd(1gVrvfj6ti?ugt#U@;{)%*k zrs7&Rm|S(A+FjH(B|LjVsdp3wdQ6OG(uFFbeG0?Pv>Z_+U|9>++0}3+vK@lK<0+q6HJeL!xS9*_>i8Ps5?8!DXgo)Mm6%JC{wo!fg>oZlwI9h1WvicK)E-nXh%(p~fQrVT%Z!)}i z=9+l)e~K2jAF-FGc-`i9|1|P*(eL2oMopJm$>6ioL#+#}*!bu<@|ChOS%3=P)`{F) zLt0(n-jFC@ZH%_>I@V5l1$jF5l&Y~5`XoCR zat&Db)HC;}Z(yYCa-hGHJ1uMsE6&jubAE>Be@(U*d$*1_sTdWyX0FA@s=RgW6FD$- z)hHnwMk+UY{~P&@n{3&B_ruJUuEwkJcJsY->JITqYhzG!?{{t6wiz?Nnf?e&h?9tN`6%bE7mxt9AH9ui*KItqY(gt#w^-v_3ARPmu|p z9~h5&5A(~*G77whwk6TK_W*LWriu##KV4#l%+;33QW90!wl!wnA5SEw>(Fwgg4WpOfoVu651(|)% z&B&9iwB5M)dn%($s#7K3Ij`CnrQYn{Fl%k!5Af9CLbu5B|&84RTOu6Va_GBYD>Wd%u zG!wb|?Rv=MUCZ4L=253M%%-EEbVJYE*b8@%!~_K17IWHdI6jJRYznRgjiQjFRQ#sG zfe&xezLeEV_jFGAo(PP_d-Ze~e|+IjV~p_!cZ^mqE;!sD;1=;Iu`gv#Tx{=D!Hu6u z-#K`&d(dV(16UTG^yxT_zZV&pwnI-7!t#6@KJjw~y0|?=qvqoHCFA>?wBW!OC1Rvq zAO;(Umo<;g)3eQ5!N*Q>mJ3w-Y}9TX7EU_hc=zyX>sjB*tBNVe)-(6?e+p9Ez^w1y z<|xL#JmQVDDcc!ICz+9N#q3lo?%Xp9B|QX^y;rHVJ&b5ht#Sv>x>J%cJ&|lc@j=R< zb0z+G)6dc-D+^|weOCdOOakN=Gee^5goCIr1#UyLJFWv8-o~X+)a|%#e!-pr1yL_T z24TLm;Tl!w^!fxn@?AHIe~LEhN>qLfgCQY+hPRsc3q<)2QC~8+4}1A!Ush56z^?8N zfu9*C7&a)jQWQ2Wsjsz>f6Eo3r(&!0)G7uqIOooa#m}TS+?5Fu?h(ZgqDg$eH4gD` zRj{-?;HdB}km~2be&Lzvy~jU95GS2cTF2t4sDSWtoTNW_c#u8he>i?Rf_PI_t{gCX z-|o$D1%&X2f51%i3Oz5y8}xsin}CrQ6LW$pBFTxHdr{I&VwK36(n{*XvzL=3Rg4Z3 zLpI5Y=G&bhGqo~yk!oJ;IW=sQ?=B5+G`{okBtBR0nQPdO_p|RHAqs_8)_%|=VMHKr zX<&xk$d6P|cWGu7eu*ii`r=sfoaN%$cA_4RhdqSwf1sR)qf4<&%6T z?#)o0;o;Ibs?~B$8A4DUs@P_gn8#MP1Yb(@9bv5YPEO`(a8l6enuSh_aqrKk+jm)) zi1k0Uk}6iG<*2sN0E)kAM7r0@TOD4xb ze>n8p1wD$Ee_bM4ORWc(GwS2YbwpxWWgWkz)e~|m68vns9l>q(-Dj>n*&NV+iG4W3 z+mU<^p_#oT*{BuXNf}?obGyQ}ng0oxD2%rTyYnzTYoDgdxo326PVMlADatbb=iZ0W zL)8wANC#Kiowc@Y`R9iYM-DO&Q6)t(wlcA%6<5c^f3~aCdLEH|!F(Rd42D%U?PdCk z;%m1Rdp5k<YP&^K7eaclF0-3+8iXrBr-}4oYvHbSj(ky3HzOOwiR3yuG(CYPW zT2Qi2)N16c5V)N?fiUOlQLcTf7>{tS-aM;M{5J*&%i^$by zdSjvU!IQwCHUW`a9Bj~<2wucf2q0en_MF;gG&}xt=0?{BKj}EWa^bOy^ZLm4yc@!W z0cele;> z042NZK{=Nn1_^*lwR)fliLCT-&~WhfRWO+bj98-bYhtvH8t`lu+uJ4#%MfInL0$NXBs@TRx!F zf5hCUw(EmhJ#G`VAuxhg)sv7{Hld_X%DAd$= zmDuBbEJ93mpU9fv3-<_P>kz6u8V}Ew9L2=T13X|MVri-KbgP7A$E0s(3a;N<^Xa!&Z_~2-LJZlxSjuq*gtam13)rn z!1A5m(%FtuRFn0qUa;08c<`a+BQ^}OYQ;7cyZs-o+WMFQPXw5o2UhYA)aPDfR7*5E z_z+d_&kQePvCrld>4uLh7@0i7p;jxKGpFY5aMuVn1T6KxadU6epcRfP?KgjPe+4P< zB3j7p!l~mi)Hl~^R?xF~5TRy@qd@Uq-_cBwSe|pQiKjY!(rvjW^`)Hoo0YMs4GliM4!V zJE+1+vb5Ho7&wfPaNl^b)VRnC7RtjsimcJ>9-AxXa1>IoLnBxcXs9~^Np;2%vx>H>z^&nYipo*eoKX1sxKwU$0N8bCDX#5VKO4FvbuJK40v3w4@Ox_QY&p}?}Xf2grJGwt`&<7)_Rodfbl#>CY>_I~_`W0u-u1%-`lu=7No zLo{Hkg{lTi&&sG_wk+Ur64|RE74CjSHzV+v=q0vHg6U@4qwv9!lKgKzt>+0Iy-hV@ z6|P${ptbC=z*=ky7*%q2YAT$fbaQLMxuw+8QEbmW>zSL#S z$OI~!kA?DQSPTEKl?)hG1kVO~$7sH@rFkUhhip7g?z|Xy9!Xx#p;o1>8z4!heX#H- zij<1^CH(*P3(%iC>Pll8?TH6fOQr(?X0mdd%lEeoEKlgL0Q zSbe(I?;w8XQ~WR$Z>XyAX5Tt1tKG4TVL0Jz{E8D^N(!0WGs43)js}m^(i06mWE)b3*A%n9>pqlCK$@V~Gr3RgX@SxkKN6IfJCinOLM)Kf8s4Q~$yKq+9=dUhH-1fkG7d(!0m; zYt*y~T@$w^X=U=AMDKF!Z7k<_C+Ho=ik;TG*PeXu#!gOSQ%#Xd2`FB9F7l%{nsfs3 z39lQse-?0_DTx^ae>E+g~fe@g$A9MOuqmg6wQ)l?TJg zmrAbh!l^g7jET#q;n^6RCpP<*rBbP5F`Pe+e|y_`nOcZaj(jmJJwB5O$xk3nY0 z_oN1?^k`pz$<`R<881VH2D{?2-q%+=Q?>o2e>x(i!j@^T&FmmC+q^U6N*GL$;LkZ* z(K_WXXQ*ChhHC-h^`2tHVzfS@>PX4Z(h1eCbWhS6`@XOrC(IbDw%s`_VaH;=E=eky z{ax(EVawBxANgS|nN&X$df9XtI=5P!b&NRg6#3-T!&Z7BmFpYvv!aNP1FB-(rxAkq ze>jJ|&yU~Z#~7d5vz?Jo;DlZOJmT!eNqKjV!oqo4Zy=jQqQZa=_XA~zS3Z?32}L@f zf#u!%*Bv99eIcTmF}{1HR0xGfjF+kDP$J38aFsI;z}suqmbd38QoY5N<_Y8ewyd`h zHQ+}J!;UqEj2q=j#XfB(c1t?_`d>E4f8t*$eF$OcVz`S{n1gIlbk51Hb&TqJ6# zeqepZ6OFyd){E&Gx5xxSU2})lN%DaahDejh_{X{z?xH@IR9Csj`<*g9{TGH!~nGAa7!7AUr$@FHB`_ zXLM*WATc#IGncQh3MBzKlMyZ`m;JB`GJkq|-_QL#|NlAfdv?zDyFOQaKUaLWGZsc& z10FeBxD8kt4ny$p^8zIR3R(tc{6GK@D98&03gEJ^7(x(G@ZUHti!s>E9Ri0*{L4bY z4Q!1-Vv5!Xq@flZ22l5a0{8_1{2~(kq7pzLKmZ67|JxAmCIL{i_Jr61w0HsPaDN!s z9hXG`?&9MHv3Ecq^Zfk?U?!2=+$~2!x9SAD@?(7q7LmJ1^YLUYdg&-~~ZA0QAA`U^h>&E#MbrfVQ zf1OVe;sypG>+Zw%r@2lrxEIXtZ^;e&Rk1%SOl4t&2782Y$?e=C2(NDcvhE^rrs9g+q(0AdG5e&G7KTYG{52saOK zfZx9r|1IJ2^8;)lAOye$Y<~}d;r=H&5(eA-B_sRq2Jr@%1Cis$4*>pp{qtmjoG@EB z4C?bA^WQDz)6myZF_!20L-`-2ygb|+;Kw5%4&V_N0Rs5>`9%PtqQZcH|Bmxd1^#CL z8`ZUj{5jpfBC5gc-~jQzNFb~CHxbW2lfnLHZ8!k`ok1IpoM$kA{eM5>{{$!u1R>w} z|DTuOx6A+E?Ei}Le;xn-J(02p6#84w{+Gf3M{n&6f%^QhK+dxV0=XMnaO8%-{@2t5 z{MSNjfo&lk&i|`bLs%nsL=I+;oO2$2Azq-+UpT~F8R8AL)rBBH4u8$k-_1bgfI?tk zUAQ~s*S&-E0s{X>hksl>kQ4H5aYwf7w+f8htpCod1Ovfsf32W^un54~&CS{e7dZh) zNf_YAkK9#Tu=no~2k`O2;0UA(0Ld``U%3lRMc z*xEq;m{d5D>uU41a-nxc>tn13G&^5fB$7 ztG_WJWM&sPxC`9vS9Pra%Ku;7K^|^y$m`+vkRl87xBUAq0)xH5Al&&GI7l+g@l9C! zWvv{o7tfbb%+`OlfO{{E{kFN4hZL6t9GIZz4BPM73X*s`Nj(I=n z&JA8kSItMDD1Y^D$RF|)4E;Fiwg)rV!fEWsMKhu|h!2wV=n0>iqnop(n9N*9-lS5y!<|Qpg%+KxKN|FMx;7|l$y*}oqsWJBzcgUJSkWGtvd>k8Ua(UqT5g#&F#gMuE7_Sy=;_jLk4G6@OJVqXJ^Pauxhg6zA zNP(ShH@|Nm?uk5vGk>Qi{}`NT+L686x0Cc%P5As1u`#ET2%=777T#sWk&u@#6{Me^ zhpyY!sUrDUR(x)PDZyBfu)vUb)=+Z`B~u&6On)L=?%5O(0jbmXa{AW`RU#i=N`*8_ zrHMTQ1};t<-c!`uOCYM-xUbjq1H&@W#_f<#0NYX{zw@!f(^73Vb%anNq-i(tdRyM? zWALHq%u2retx=E_X<6Wte7m@x@n>77jR*Ora`jPfmUVWhNcsvkKm-%jD zuYb3LEp5wNwejj4{gBjVSVdxxDXbV;*_0sMs<1pj9&KbkV6EAH+Klbi^TDp^^amcl z`Gus=X0VIpcBA%z%g+i|c|`yTA=_NIxZp;$)-zUdKXkk(;~+)+Gcgi;>xsq?ff*Pt zii2Gf?j}@5V}YV@*PQuza}06)m5R&Zd4Dh6GHGia9iRH3FX#fTI7C_Or>Cyq(q}$X z9g+7wa`3LY?}58p7ACH=iXmDpm{DdztEDFq&BTRf3DX}6O?8zHHE#qqtOQ!_SGSbI zRnz=%`6<0WQj-nsuywV2Q2V#R@h{J>Otc@+>t`#a9+&KAwIocTp8jM_-N=MKP=CIo zcoL*ZjH>Uz|C&KL&*rG4dOUzD5{j>IX#prHUhHAV4x{t5n}&yS*^N`>YVGbns1LY+ z%Fuy0SE87{S6c?@SADgpaE{m{`UEKr)2PrH`WVlsc0cyb)SI7MRA>6cw^oQL6UnTu z4@a4U9OwFy68d;L&4jb4gt?YclRQaPR zEt_&ue;>nBUmrj`w}ktfswSpKs5zJ7L_s zpylTrL$fA}PJ!%hmTG833dy4tUAB1jS0jr-o=MZ(1I!If4o0O~GN<*sGHWR=oHJpf zo&>X$Qj5C$?g1MrgekH`+JDKymWP6A(S~2@#q3%m05m>&C6S>mIvimQ_*FpBsjnYd z2*Po~RPc(flJ$LGk)E8`ee;W)uq0M=SUP>QS?HIQwJx7FvNIEK^=@E3&t1TdP2t36 zWxdvF@b%PdSql(@SV|p?M%0xpl=|yEji_rOCmkuu{o6{}86!Y)*?$t0ds!E*^n8W# zs}t&{EKUMZY*#e%1xC!hi>tR|bK6r-;B6t6v&?T~~K zuCH5iWHTCm>3e34e}cMJ^?iP#evKly!+@zkGGROI+QSmXAR1Rr_&7^MUW$0J&=a

_B z0Gg8NKqQiMrxWGbV^xZ&|LsG)c%lKo5>0oXQP1T9r#q4MqJPCrvbg?n`gYgA zrso`kxD%caaXdw%YO;@uB#q+G>;@pkk$Rs$cS7P&Kg^1WQjlVmcj{}XIG>*f`=25F+ax_(oKecKsot`x1ab%uh zx#n@rE`rQ_()vf+it}^s;gVWueTcnz$|GBk1tc-XyrE?~%^k0sI4?&SlnoUT+R7}~ znUbTEvWJ?5hWA}KX`3{fz1vrwd$cVdP@n$IseZ8+YkyULpM7C^+)`kUg$Rf$cYU+x z9M*;sJ4W~o>hBy1pL)MnE<~;OrIoxotib05seeksg69L01FpctqI`zFRHa5x{HHhb zXvtawyR&@N=kyf2h`DgIYgKS|#JsLT!#7Xu?^{eNA^~_Md-&h6^7AYj`3vMI6W_(A za`|u7vVU*37*8Lq#;BB4K}AC}>}XBMd{^A^t@fpUsxbMnRS1nlm}&t^*t@8D)9NA) zsD1gC>YL_$KWg?q4)bq`R=meBAjCuXV-2XZ@6r@Q^Vs03`9yATEwTzbs{Z{N^<1;u zW@<}!2LjqzH>P@1V2)xK?Cn0LRY)JM8_n795`PRXPbje~=|u5zT8N}#xK!om5XCM_ zfH1{P^d5vT1L@~(gBvP)jb$KRBqY(kCtG3z{r+9W(zbVwK8D$G!M%;f&Vyew)~H=e zKiDe_QzxAy9n8IJ&Aun@i_!MQFiK%1h_4S3*qYRz8G%s>r{~=jalV4LqD)~p#(d(@ z{u#VKT0B|}KNd^q*YMJ_UygIh<>a>{C4UIvor#HhG1jwNho@;A9eDcw?)uUhpA2d} zhHt?_w#Um<@-(rn-0HR7TL@hc&8Ew{^Zs~-VJs~7WK>}vUenM7G`f$YuQ`ss(iIvO z?4y*N+wyDV7dll|eu!~g4yr7~riB50DJxW7)2}^njeeW3Yh7-l_l?CjY>G<#O@GUr zX%S6fk03(L2iVv7iWhzAVRXNF%EKc1P{oHzpF)ydTxyg#E6dL6Rx&*g+;paF$6%tc z`$fbb(d@)SIcsS5OeM}bx1<_}@xuwA=JqnI66-Qa+W>yQ3Ycd^;X z-!nbJI{v!7nA`5z;zy+n@d2A(QaEwxx$Ir!o^jW5cT4#@Rtg9cD-4B*=6{?`<0T)Y z*ED9#(Gdmle&bUvqoo~c837iiBlL6ET4PXondrR0cn&nwT?D$%UV=AgoL!E;t4G2c zWNYiz(}VA<4tL}}1__p~>ydx!l4meJ4P-tPS1N3!NOY9KeQqHGsN8&YMJOzI zQLOykeyXcp=!JaN_GZqWTz^?5$y$f&oAJXD!UwDGRwjiSv0@k^ixMZk^S{=$qxytX zb;3Pk(4Q}Iy3vk7_tLGX)I4dq+wsUU*tXHAa^0)5z= z_uL<48GQ>DcVV>ZL@m{8UpU)jE78tTX*gKJ$do2P?JpaB=V;MD0y_~jl~ynCm6=!E zeWGb#;>OkV znc+RyG2#*Jbga`cAGS=nfHO5m-pIJ!X-mz1+S+>IrO!k5jhd${3w{-}M5T=FdJMUI zKvwrv@0L@$E%{2Ws%f|92TH34=7`A!dmRnBIK5ZQSAWcJq{wJKhs@^6?AXc*f;fmQ z1S@FL33jIGrcqcpwE|S>dTFx073WDR*uGlJ#29jO>7cIVCv&{XS0<(*>WTt|yVE1m z_Ep#}))k(lx4LkkS96?W-sW08$R;l2sGDYQxymVSysxFzirZKphVMGy$=Xyie4()V zMNk{1Nq_UPd%c&Tu7_U|g?oGJcQwC zOqJe-Kc#WKO?A+(*(-EV-_mR{o0@cgwPCBBsAme;hlUisDy5vf0HcS@Gj<=+cPbMw2xFx1m{Mu zjRIO{pe23>qMugIt*!vd)^yoll6HM^@5$-KT>gI$on|oVZfJpS3acmrL5O07*wLSVg2mwIR$U$Qcjh!JlsP_ zR~3J8@!P8Ech~fyG4)37A=$5I$_IS5z6|%JU>WAeDhOYzxY@58VfGOTe_&3C%!p<6 zuT5y|iop&{TUM#qoD<8-*ugKT!PN5nvdZpAi6{--SOwr8jTgd>_H!)8Ec*3OKbTO3 z>&zw5L^%`i#=eTLKE%;C@1&f_glj)?eE5GA`<5+atFN8Enskofon*iR!o%<s1Pk?7_9+eJO)TZE*tvAKp-seoxV>vJZS0S*7BdKv+r z3*T=XdniWarbH72oUlH-=@S#@y_qR(+p?kYlm~GIDRptl;0+0vM6p7}Pfc5Nr6+%2 z_NO>%%3BgLJ&4q~L`(xCoiWe=fun$evw897N*z(@U?-C+r{co$4%89T8n)0k-|0&z zatXU6W0q2%?h8?6 z893E=pQA3J`1)}*Q%<*iihRtA*s=b3-S6?IlJb^%2|DE|f^;^pRwf??3g3-!IjMaSFcFuwOAjc23m}@f>}xs|L_{`K z-nAAuRz#Ha`ZJX_d_Dc1ID>ziKR9GgKBXDskdGQ~MnYcCF$WhGbs}HAO?k)?gr%DN z1ckfGd(8jTy~f>pzgRWzk+KHy#%AOk#^}C7>HU_+A`?{MD9+p~lMV(vCXY!H2++pV zso37uUJOf>Z7z9fe|b@F4Xu!fX1>%BUe(wCnT@%0%`o@Pb|^H(i8O$%q(>dWmtW$zD{^-Gk(@G+6@I*i(szDlau@{#@8 zf7fEPc7^@>FNI!J$w81``r#uVc^lDkC?l(PLhB)hY9Cn!Cm zs9%{fgD%)Sz7K! z{q`>QgDAaz>{Bm!`-!CW_8Wtnw!9ps*$QZm&EdJPWJ_J9n$PqTrCE&bk)3E4w=yR! zytlHLvOQqdcP|CgGNHZ0(FlW!uYD}^!TTKBd@lNfmn(ns?<$z61R6bXGnK%}!k1iq z^R@1!kB`}Cu*vFLO3yMsZ`nlYy`echtTlj=%XC_E5?vMuM%ho z#BRr7y>~+2S;XR{ml1D%KX=mksCEkd$KKa+;+}sLE`9hylb+<&gNOMydThS4K@>^{ z<9;kc(OCDbRIbNzrQMglzId$ZDcw`x#wtoR_3q75#u)*c2Ei+9-Z`QkK5BB5m<1n_ z5H!9H;TocG*!-RAvvsdQ*S7cSK&;e~?;{okbK}#N&AfQwFQZxWmK_97*Ja4CLDOrR zPo94hM?ZeIm3yC&PHk^1q2bMIWsSYFh$qYZA#XoY!&!r+W_f(Qf&?exmX|F$(1vPw z2`gbg@sC`(F>t5QJfop@ksME&VoD{9-+a(BE$oJ;W?uvWgr*<7BAX|UF+K@HWZ!v5 z(KKvp?5UV^IZ1@$?ff4r}}@=ncoTJ8T@QnV&+I>`T3J|sfN#A;4SX>3lxPJ_BtpQ>z3STk$4e!fQU5p`Qdy0SNzcm|V zYx^h^9v>?OEc;|uh`ia(7}9YHCnp;c-(f32KWiMg^ib7X1#)K7oZ|^I_e5JkXS*{} zpE8oXgw*4a3Y9{8HXL4?PiQ;|J>OTR>Pf4g4R9+&cV=Ng^m|)45JrhG*nPn+*%!wL zs+YH4zp#?-f4^)re!$o%(;yx3|9vp3R#< z%gJc$f4^XD$D69o7NRsZ6dIh4z`-?%;knn4S=5(M#FzUuKK1O|4~~wERQi`fDJlrg z7gB^pn<0?wQ#vy>&6{+hM^9-^W9QTPmN?Ymy88y$=0oj5!vWe>HYW9U*@Y6L+N--J z>7^G5uIamZteScax68pFD2U=+avyR|hD5g&nJKb9?VJVrPZpnuYx8(sc*XIG#Vwq} zKkaY57rq~ToOaprgs@C;NK-o-k&Rb`qoF$j(vSgGUnz|EJJ&bvJCV$iP zGc|hIBitDO`s{y09?w8h8iNt{#cQt*Ty$HV6GXXS|I4mAO7ttQ^K3sEe2W|P`qs}4 zdZYFqf0;RDE-;v8s*PoG0X4T z-w1JCKEq}ty8il8Wpwd=gV|ok!4kvUNKF1p#h*20%dnbtBw-mxpH00Yp3a=6) zlz$R$A%K6_O*UaU)K#X#+nmOxwKFSz*XYH%D%5$)E^LjFcuNKSHiyPlzDXh}4sx?> zcRjKt!>v?c!Q0qhS~o~_`Y`|vHFd`Rx|;Xc^9Mz(RLk>$u_>VwX+KdZc~6S;vog^;UJCstIU6Ed|kHWRnAb)sXUXXFOR18t0*9hL2DEz5zfq=hqHaK!}5eG9PC!n3JsF9NyH$cP86d-D50$^qae=u=zalw%TMC|O{9e@^= zP5??ZWeqAC8ruJq{9^(zcK;8}Ur$G%g)M;M?~99>wVl0N6XaV+S4mLnX$G`6Ypd-M-!N}I>Zx5X8 z06<$4YiHAc0Q{Ak+x-iWy@TCf3!A^Xzrhsk9Gx6Z9Dw#tfWKK4MaBP()5+4v>7U$= zz`tsMo%vr&Q#%vqe@gn7?r)gCS|=l*ts}t6%+2Yae_Y0908^l&y|t11-`szL**gIL z1;g19XlwDG2xtKgW)?;crq*VTj(@}ajr~t|{0G%Ao ztj+1+n3(_OG;#Wy+X83{$MDarNZFd(0hk#7EjM+x{|}vunZv&tMETFmQ2hmAWNK$? z?G7+Ce=~<;khgRCn-W0zf5$TYe;>*J4HW;k5d7al@BbUQ|COWv?GpdL-sk@sTHM*% zTHeU!?*ROJ#{m8=86#W3-#r761^lyUoNfL;E=D#$Yxn;@r~hiLVfJsd!gkiC|5YdD zWc0TsLbeuvXk)(WzPjO@7$^Ljc>qRc5xP{}ujUs{RF@K}uFyR78sA|FB&DWvKXf2%J>i?f+u? zpQXsznf|ZCKVgK0?c4yKbWH4=06G>{roVUZFCZ>hRk&^?^4WRS4 ze{M#me^viKpZ`4R{g*IewkCF_|BQ`_laa0I-%0ylf`8N|&JGTL3I5mR|6BEcoc}fR zW@c_?CU9%Zb|ySQR%w~(PPJG$!;_*q{k=@!!@>3?4XTCte${q8zG-2*Tos0YYJ%w- zr@24d+?USmKMtj-k4Aejt-trAm|f-Je|wWs_2r{%QFL(790f4wmms8{YeacoFUsyf zXtOh_AMH&lDeD*ifg+ghU~z!Cex~vxb;972w^UR8bZ;YuhfV$uzj4MQP-zg}!e{cxbC4^Rn$Lfv$D3USMdXZ*1FU&1bv{+-uiZk}q zci+&oY;M_Hu5}N}o9$8Kku>mJR4Bm*p7;c+G0m8&U1M&n(V{1kfPs!1ZPH^rP(*%?FE0x~(rhyswo&9Quh@Q2fQBIa!)ZqEB%o5wi;Be*l9=#&)Ee4JxTYL!P-Ec zIID#xaZ^!To@n|CbtwZw-T9wt$&XNPPkn(K^ql$7PI12+&pOQEVf$@+Ci&MEZBO2J zo{c*{77hv2XP(|hT2coae46)+e=^voR*u_b6hAaP zDmC41T`|+C;69JHQ`o(;npAn=Ed&v-8$ua3AiL7Ia%trDW6ff;yCKDAuMPwo#Zeg& zq+FJ=xF%TP@d;4ZIy|rAk_oo<2&=3!oH}OPm-u!QKZ#%(2yw!s*eZzwPf`6r2I!RBL9NB#<hpUh|u~iTJ|yMfu??-O2L z;%xz}6Q%XJB(D<67fDEY-%OjWtbiS#eV68^n{j`_g#_n6pxi#W;Ma^)7W1Dpa7}16e9_Ud=OI>>_lXGQ`JygEO z!&TTiLKv>@GgXi(@vml4shKq4wN(sRLsqI$Y;jHf_J8Dj)>n$RYe+Pd_J~v z;^7jEe`$!g@aHSoY`DnusfC$fwlT#v`ZSkWd! ze}1css{ys_NAlXAxcxbJ_`Prau(XP$dohK%gu4R*^9T~94!Tpmn!B6?s?aqL=m?>^ zvcufd)mw}QXc#m)5PK)pnCEgb-AOn>h9)eZGR1QfKKRCGvB?gu|J3%c--IiTduL7^Oe-c8PoU3t$ z$Tm&$x1cyRRn$z#TE8McZ7FqS_t}6pQqFZW2B2qL0DEhB4g}d?H=L!cacF{Qf7=c* zzNG2x@PrV9AsY*oWQ~kf-a^l5C&TDxgpjmLYscwv?$tyeW7kAAhXdCuN!z}E^G#Gm zvw2EN)G9jHm<<-|CH*u$SJaLdYDZ|co1?qoDSkP-WKwGfnxf!AF>#BzB9nffL0PmC zz5c6h`*&@r>Se1KrPIer+J0u(e}S&k*Sl;v$OSlgwzA#y8rWRpsNn2$UJo1R&f70D z>>X(GD#>9u&6Yk5y|;z4pp_N$-S#zd&hvWb!mI5dv@BYipdrS2gO)5o8O;>X>JU+5 zq7&SK@mY%)>H4c`gM{fvz#o$mtaPX$58AL%J=F6kBy0cWWvO{{c{$%Mf98VV+@W{3 zE5tusD2eUCSBY|W;RNu>GBf>7S-HuVw>X`K^ioEkzLdi}d+9v95t^kR*yX{oQw)o)je=Q}d9|dww-ll3Y zK2(Q1+I4@1Z}gCpGQN_qXwc*yO3AkH5=|gF8CsJ4?MfaAD~dRel{5Po2liaM95;HF z%Xl@)z6Xm}cp*G=6IDOHQdO-YE5m^!8O2XpLt>zmn<5q^a~&)Vc{^CVZ2%9>1dMch z`b`Q?9;pUpO}zTVf1F4=1&Mplm(dYKzm185S^a9Bt7&479XckoP&?9t)Efb4;N&g6 zWP|_-@8f*zh=@$(v{O*qi$!V)R#jCQ%7}Wb)1prqjap`Qj-}w1_{4I%wN#-fLNuG* zPL9r_EzYtl6p$)Oz+mdIw`L^MX16Ix*%@jaJ|oPuFZL&xe_Y}_<&D)IP+VS<2KWr=q-88K!S)xyfJOL&Pp;8zD#)Pj$Pk`1_`Nn0j64f+#KO zo!toD@jO@(_lToe;z%gxly8g#v46CV>?~KHlYzQAqaL81J1WwwRjmu&lbWdlhJH_) zktPIpe=^(f)`ax9Bio0B;jfLcXp-ZdYSeMItnH?EC+HW$_2uqO6Z9#W&5oLUUZSru ztV<}=M!}>sSr|Wm%jUzb>e=WTth{7t{arRro$ZACXc^1#xuH;=QwYy9% z!pvYt?Cmy?w3}aIfZ&@p(pr|yv({kUytQq0Oy?gCdI-A6ZLC}Ba#OVrn_|M#)G~Z+ zJVfuunKljrfyeL7Y{=QjKWjrq-yKNZ8y|*zN3m>!6(2 z5i9DzlzH%dsFNqix0=TewQk5yJQX*M-x`lk~ zd}O|XFCt%FTBx&?Z{SX;>|jl2f6HfvrcfoYAYHOL6&nsG0;%GDU6Xuv;vAJ-BsQ=? z?np$%TmfgwR5M%g{lh3->Ks2)fcM%pwbJP&WvsL?x(4$j51|}pkZ|}Rq+UJd1w9My7B!aC*`_e{Rl%UA1nC zRKjAz2NR8jabo~vmOfo1z_9&hn?np!+fSUQDBC?z4P7ByTw2J|AXR$7$QYuKHIZ$9 z@)o<@rM#}M+{j0v$*2ufm1GF-KZE%+w@K`@A+*Q?GyF^?_%MEM!&I_l)y{+in$+p) zPLb#0CN{?@_3aUfDQ}Zve>F2;g)LyvXnwqJVcaL3~vRi`{PQ55}D z#+u?41}uwfA|#esHv9Ap79LgoEs_}m_>9&SJjB2OOC zTCYkyYR@wpgWQ-Mf3&}|5^kNWLk}WmTWZxFYowNLR1$^~V&o)<*4pxLU`N<2n5$8B zZcMw?Y`_wb;%WzHxz>Mwg*G?|P$#x-q_ZoomOV|SoZjSL^%Yt!)j^7as69&{Cp>*F zZLM~Z*=bq|Uz}XdN%-!ewFtw*qPIP@;A!jbY0>jphiF7Ne`*=@`>ClbD50CB&$|mc zU?RhhNwQiz2TO^UK%-_S(_Qoof6(|GFDKv$t6;Kl{dt-6ta<&ZtSb-IBB|-@-2Ic@ zZ3qWFS8v)ub7+Ik#inz2tEmiD5ADN;vIHk?Y;6ts4i;Ej2n;c|2ty@=Xtrx=h<*a! z5VgC*|9ml8e>HLW2u7%`3Q6Bo-N3YUUsQX`p^6YZHqj}y2T z03c4l^pRZ@GU!59?-j1`L6RsBY-~QlwZSc&CtUDsfBTGHtpAH z5%lbjPYChASw&k@CExy)AKqbzrfUz=GtTS=&fC%c_~*OnBi*q3vmNXF+RWG;icq*S zZ03iVOXc0vJ=E3dZxh6dvDq~mEGqvt?LStFs7_Rdw=HK#8>o~+MFgB(bj`{A9JMpo ze~hFTsN*}mm*0{${5l288F`Lv+@nMpVfJhA&d&1kxx3&gxo~4b?}m>MZg#?e9;nIi zMo<1dw43?+Fx%l;=U2Bcr(2wAkhewQxnMY&$}#W#6smM*P6XPQ`fIsag#O^B5 z2e3}of-qMc(xk!$iQ|;=iDh^`aDq4WeiVU6Sj&z2c|RIgwDbp2rnOO4Q7IXXwwXj1 zgdiU4JrWw6uvRpG(47npF?DU0(XrI(Q=)LKG>5Ig-E7RA%!6n)D-dTf3rX` zF?t~}<+NR3^a6@SS9slrQHOb$GL&BH45tV!8V8bGd}8bw1*nq+SPxi9R^RijQnZV* zPmFqS#CmTVlSnR?-y(dHQj~FSj!I1Ei5T<=aiBCs zDoLTB?Aob+iw9a1#+8X&9t6XWiDUh})a%q}cWdjE)P4z8$aDtchlJt!kK~T+UpyTC zoLVNxJmF=`W8z}mlY>zf6x$`n`M!O=J4VQC#j|+(U-tg{*$0fKzUA49f9aDPwh{D{ zRk-;&7#S6tNzYtmks6Lj>9Zjb!x`XKq+Me+$1es!FOhTha=ih()c)k0Tr(*ln4&@-X?}Xyyk=s*TC- zoDkia#4WxqR3y{=EZmqajlbGqIA6R{%892{Fh&!?n>Q$^bSIw%Q{s^gYBqgt!T*?2 zLX#kZx)AgAD59QbNAfrIms2oOg5VNJK9c}3zqhPpUxV=bBq;Kme{5pdj)EAM%C>8X zVTTWbk+MS7={IlT_=a&bfw$^m4oi1$xlvVjocvN|%7c^^iJZ%sBu|L3j)KNda)HHW z1Za9R#oxx$;vvEg!_WW0#hs>}t;ON$bGkc%KP|@kaDejyu@$E zoQ zUEXKTF|#LkM;aO?QO_W<2+R+Z3y2@U(I1=iPnzzpvolrrW&G9^?Zz;B-=>f0)z+l<|=!H6{Ohy&Xi3i5_%OOfHB zg95v<@Md9JcQvZZUGgdsnXn<8^V>>1*5w~xuGNP7e>5~C0xF0&+vt&UfgiN2@>=kLF{Tmo-68AZHKVxFLv{8H#4y`o?RnBcaDwltqQ zA6m>1x4KW}+b=O@W@Cy|7T8A+tSq6a1$lduwy1ogH07mq&Oa?GP}VTF&OuI9U8p!W zR*K=z%@`dOh^&G!1mF-B;VdpT%l+^EmX&jFe@?%BpYApql5q&F#kIvv6~bcboAzI( zVu>4zkN;E@s6R$k&H9T$Y_EB7pv})a6Y{ESsYF>kP34hLr;rtg+a z*!7qp%Os-NQC%l6iRcmL$@xDd6akeS;Tv29%$TkfNX26{0PKyE>706G<$)rc9=S|! ze{BX)q!%*I{+oVBmLPQDrhW{W4dCosq8*KJOLYR@)Wu#QWeYTC`{W{2&@a}L?$V;9 zKQU+|GeQPC*x=H0+$;1>ZZ@f~L1f7(S`dm{l5s)v%IR+ts|aJ!<^9D?)QVLhvOO=r zj((6Rbc!zGtq_G$-`d<*mHuHG3y8X_fAo_HswOZlc^t38`_^h{L+nYV?Z3GV1kFV8 zVr7xdNGV|Kp3&tIOMxAL4K^nQoFt_!k?RH)82QS98Bh!@wzir9^p%ebTe1R^%}h{N zy o(be7`Cza-qpA+gSVF-S`ROKmiqOv?*SS4gid=Ar9XnUR)h_8B>NMRnze^zlA zIK5Z}d_x;V!7!<)_h|ktKHZabg4rN7?L!;>B7=h-kB%nujyyLdT{#A$3ZG-m#lc`1 zsK2pJ&q^a4tQq+mngn&JiVd%yL_F~kREf&4;7zcBeOo*xk3kf_RXV${Wsn@9Npopk z60;+EN^d$u#K^TX`Zp$^i@ivpe*~K191|Vu?AL0Evu8n``ea(DR)P)>eBX2fS92?l zxI_zrJ>-LxE~1aZfzWtFP-+3Bb~kRYg(;3MUYf4aJ8*xE%!z;h0)7{)troK)A94AT zt0a<7b#&$~@m8UaJy#ja4RMd)TGv1q&B7Me2Nb@`W7wird!?kLn{8A4e@$KVb{vi8 z$LK*53kh`e;S6B{4|PS%18`k5M0cU;`wO8!N7!sqc*aE zny$Klu(NW$1W=UKsvmRqhg+I`wZ{v!I`b6td=PDztS=W0Zo#Akd4Pdvx|dL(s-_f0pH&_Mkz z(|t!fs-vIRQ)1@0VuyaiW;STxv7@kN9G#U?UAx%r)tGIjjIh_5e=!n9s{IRmE;fXM zy8t_|Iz~#b>YN%Ibo#b&ey%WDtdM%$G#Qynx6;0@w8B+Te#TbIq5bjcaK9VUuBcZ% z$OT#;cQcuT+(p`aWV!kz^*c*&iA7#pUu#!UhI3NGyz5y0r4+V5ico(5_jTU0d;)si z(~Yf88l1;L4hrXQe+|dxn7dZ(ucvxuPN}0(7aWLMGqt@DL^XlEscmwINq1d5`1&35 zPWXqKqpq?Py|`tL|o@NbA z8bmIW>#fT!KL+pbU>j_7FixU00H@&W#zeGE;+<8p0OF=4FBC?DM{ZI6G8S>IcRarq z-&ZFl3lQpYeBqDe5P(4yzHj~NC_0<^&`dGfJ7=nme>aF>j<(Q{c`Jh?CL+1#mEj7J zCdTU+_A~Re(5t6E>I($KR^6Es-&x~Zvbh~1Cg@5GvEKP-9!{}=(XO2A8?DU|yg#V0 z*H3Gref}r-82^V+O|pQWdBr11^F0R4m&17lFxc9~XQn5IJ45KdtZ#g7VS0%)1GB2o zZyCJFe`p9OQdkr#F4w(|Um8HTKlC(lahQH>fFF~znkzf+9VQ zo@BxItBg!!U%r*Q%1TVq=nUP;KyW+X zN!R9gTo42~v&lVix?>X}7_F`H3YNBC{S(|SFV%-Af)o{Pj`CC5@XnBHNwynfxs%Qae<2WP>-#WnX2K$ko6RZucPg-U>Dp+WUS*s!*XRXP3Yi?AB>HAiXAJ=LYO9BQLfBRjy zQ@PYQNP?ueB?}(WHE7vfz2&LnlpcB8;V)d#17<~5oT3>m70aCTkA`Rv{yPV&lNGgY z0GlzC%IvdK1={Sh<*KC<|I&<;gxHly+|}YWT?6fxS`P#TWTzV-WYpwJEG=W4HS60T zwEGiih9l<#r`z+2tqydf`T=ome`wz}4{>~l@VrCuKx5lzTkbV-g&R7PkL5M3fSNXs zWt#hHoa*njZ6dnh^M(7%VcU&myc~3p^zL1>C#U;iNQq7GL?rgcPE^xBAV!N-74D$4=^f8Mv*4UTdJ zTU3f7jj482-NCqk8L2Q;A8xV2b;KLu z50(=nhP1US*K2~{k4QC0@)q5;$s0?gkJDH}12%5xrVMC^8Y@&K6`db{a0@4h#*<6| zmgS~m7G~{YT8^fx0MWPoe-uI8GU~dMv^3xFxZ&VfB1dsf*v34cfPRy&@U{C4>$+B5Kq0rnB~e1a_BadH05 z1i|h+V0Xk)HgoD*y*|3^44+-QLD7hbBj`}cg!sjUOnjep1(@jKnNl5ZT3nYeH$(`a{#K5Z2vF*LGGr|JEHUCnOBAue^ZV*GD(7$qj4BS%itQw zi)DXYvbaYVVDKj@Of5+83F8$?l=aMO?i@vT)y5fTO7>nffq zs>iaee<n9$)P?pr7S|!{U z4Vwl|Z1-+m<7yp|cNv}?U^_vr;0bwHF+Wfp^CyU5uLe4z3RbC9 zT$O{|A>Y`g#fMV~V+^oYsKhoxma%wS%1P^-+zr;NrJjUs$ZkWyK7Jcn91A#hnm+aG zXdy^9e|^24eOzvW8Jm@y6EDu>#Yz#$Abdmx-Jr-fHXj@#<8WK01hy#TvXz1^dtC_! zb`i?JNknh_Lf;xD8st%Ig#k?MDwVc%aRp8DHf6pp^WtUxoOXi>xzc$x!}*r{Fc^5v z>hZ?p{{b5oC*lO7+~~=unpQH6*Se4JT_nj*r9YC>+(~{tX`-g7vPKo$8io$OV zfA*j8p`ls?A|$($VmgePS|(uf?!4Dckt_6szVo+TkobM>VOb4ng27|9Zsh(FaqVQp+w9lIgwy_o&)23R zwkssu;@(=Oi1GuXUt3;>e5mhK@gWaue}HM~$0 zrc4!KCH&c%KAo6{{cK|vbc663MkqJ7SZ979!oh3x`BTKW$Kx@RCP)~%aYJ)%4rMZ< zN44cp;HFw_c{TD%R(R<_J>f9cjO z9>?uNK*5NNMg}LaXqH^&yf$;s^Z8Rq_-HWFtLd;XpHYmgT&xgZC-#T6Cxm}QY#k@J zM&I=oY12mp>&2y0{l;9n-FNXmh(4p+Va!|r1>I@lP_S|sKXTu#qqt0 z0$352IH>sf1023z?1(L~Dxsq5f5{fbeGe+lf-bJ=n4AHDG#!tF)zn<5`CbV!zHk`z ztIMP>EjSZ)4#iRCtFEZ8Q9~l#q-wvE9+tKH@a%DhU(t@u`+Z@0dX=EFFWca9YuSe! zXjY2qF}zsi+68a1Wa=4JFF|Ro6gvh^qPwfoR!tZBLaZz?G&T@SJ=-Erf1o;$B-(%O zYux!22lgg03I?2Z5aWkcMOcs71hKzEL)Tf)r3m*ik&_C8Wb3ZbDM^c0T#~?{uPbSl zu)u2emsuxmDCx*3X-uQt)@tRO%xU^@Z)ERa_DC@R8j2I;LPRloWD@ z(Jn+?k@=3;hwW`*<5)@7e+c-tG-eL)@Znsu}b`5r0`H`L+eu-CxK*3Y+ z#;lg0-fF{zF&%u6uB<|x`>Tx-^!@e2lc!|?)~fz#4}n3Aeg2%38^R(bGmBh1;_OQ_ zM-A2DUT_LU&2s5Ee}7OZQk9ShbK369S(z2=PBp5;9X6Tk2(%k^D$tGS@H@K?@mM%; z!-~0Xo&&CCPb6b$y13zz*=WW^xsC=iR#)|B7N1@`4+wml4i|zi4a(zBZWo7Nn_v|X zToVt43ZdDfV560|<;zd(m@m0I$?cH!MY!{GIbD@@(ZQa}e+Eh@02bUCWzQuqmGx&G zQ*~?+tM`6(i#dP}{N6CHG4-)8iCIa!70O|iu1kCi^`dZ>LITQL^~I8x6;E4d;6d2= zyreXbNLHLfd+PiW$Ln1n2=Y*45!_go&X1^`Ct+8dmT*g?#jp4CrFlu`Ss2GpT80D% z0<7oSa0cd+9W)`|Deghh0KEV?hO4#PE5#U;`1>Ie_4MEA{El{_MwTmYaP3yZK1b0)fgNM- z@HRPCyg)bRj8?4?+Z5nT>549zm60L*+ZM1O9=|HmP>)xqgNiXeq~%t8)&r*c{NMeP_{e?Md|{4{Y~CCL>uqF^B|suJqY&$n>v9bC&} zWlM%OF47tr*k$Zyn|UbX3Mi7@x!W}#?;U zzXMa-a1er&gswH0i6vb(b>uAD=XHycU;aeLrW=~EoDaWyy&Ld1!JfwUe)=;yeN@*3S-fPm;QnmPz+Phx-fkngo(UgYiW^Dk zx1=Wn=9=TP(Jt+0aQa(^=910T{T{|jnoBb%WEH!{@Ps_Cv zybSk&4El2lpg_Xhc~%O+;d;IBe_F8sKQXSgJ);(XbRbdl;Yf`l+V0zob_1`~2ER=5 zi+sPvEc_VqCL#a(Zi*8@^4Y`o6z<{26SXd`^(&eiMyuG3V}#v>iE@`Vq%RI?-TqR} z+BMWg=Yj#UD&kk1yXeQw4Fa)?!Np1oiFvR7-fK`0gfzS{$*V>RPATdfe;9+Er9mSy z&Xiyb_-~?#7F&dp?7*|NeSRQ5XdK9(5q}EWuL{(%XBLHhRZty3*CZ|%cMa}(aVNM3 zcbAI=cjw{|+&#Fvy9DtOOsn|HVQzN# z%}|-8NVXn{csk^G4k;tSu7~mtmLwW15mA*(*)5{wP~YlpD3im81HTMzxj{r36t$Q; z%dBc!f0$g2bilhYpSdCsNnk{#mQw!d28RVpL10TbG`MTZKy!|7<_na;Y|q6ne#8x2 z>qfXQ)uOGx`_`7(hUClBJ2vHDRA*1|(M7X}b{2j*{? z=ih04je>6%3-gNDcA)9^b`HS?hF)u;kb+#NCWQA7{W-Tx{WjaJB(tj4>^YgAhH&s!^ z-z@-~)2Klw4*-Q{Ivela;%*GbewEWTKI*D{{>n+g*Znzii=E6n^g&3Lz@Yd_Jy$;*) z%Nd;m^=a4hKV@E477jCfAJtbn{B++@kF{K^-ne$4ksze%`X>h&;D8b`7$HgTNh{V* z)1X{^9|0!3^l9(rh(q^OFw){3R!h&!1W>@MJ?G%8>6(bQWpaB3=jn{=)hGOyF=mPC zUjc5>zw#Sqe0U|WIO~&i_fd+oug4N)@(Kp(uA-_o=?oW%D8dac*52kr!0Ke+I+ zuH_W~YAW7zDU1x0EJ{xM+<>r{fUcM0)Z3Au0&lq{?c)bEiqU*_F!xg9hw3?}*zf{k zHw;!9%=b}`n7$+zyx$|a7sR@~5c9HT@Q074jLFWoII_yI3(q5a8mllh}4OR7(HJy*IxKq~04W6#uA>hkBIs-=Ftu-+3^ z6XGL^nqqm4boPW7IKA;ZMm&3`(~RxrnmwNaD(4aMni4FEy!J}bo675zXhPM^x<2N; zLO9K5L8S z!udmCRSCUY1?c!&q7_S7u@TQt3^mH_u-BwXEW}wB8lVF5BM`x#;^308cI~2;d zk_~%E(dA6boXRQ>LAmtQn-L|HXp0F>R{jZf?2(cAVCpOK`U?Wnnt%fNSwXDB%Wd-L z7Y7U&w;+LsMQIOqvOXrOkkcz=pX2DOB`)^h;TAD!8!d#S$uD4P(4ldG2V447DpGBqW=a^I;A~?q~XLl<^2+vC0!+cGcw1MA&08g>gJp-MB8F z+NAMGI!&LzIZrwL#XDJZb1iijJj;SC6%ReBkxu3O*VSX11ofH%;f>H}4IS6KDfLj> z%_LSNje}{E%o#mV+Y1S#{QDxrik@R|oc423V1DGiq!ve6KG~S<>Lt?C|MWHpn|GyFjTy%u%CYi`z;c2E#aO$ikGoV1))M<4%Ts z1E-8mkh><&`8&X*%RpLoc@ov*G}RKTS#LjoA)roQvfUh4vzXtR^lw7M>DW(Uha{aY z-ue;F+FsCkC|}s}>3rJpm2%1Trw*iwPQ*Bmp+jQg-K<1Yg+wjDcOu zgmz>5s(RD7q2xe~YvgbiD_T3PiA2r$AWF9Jb@ zm>OI?{%t5$M6oTKGD|{>At2_VkF&VURaYUs!{*l@glA_&!9zvw)%i;Glb+hUtxL21 z=U-gkVoT^GDSOoBCG>Q*UU^sx8!-Cd;9ssgcTh}h;n77NuD#)jt`NCUNdk2nv%{Lx zQmZc-HZEJEjn383?hvEO26EBwyb~Ixxe!u0v~RZ9Ho>-yPiQPAPZKcO>aQ<#kl`yP zFsthlsYy3XC`{)PFKM%(=4kavg}B`25{2cQQrfdaoQKBJK7!DbJt6;38A<;V206c*0Qbo@@RQTD+=9>Q=g_|6$x%~*<)wV5(I<7^os8!^8}dqnCHe7RJPZb$E@I&Alzk=HW~Q`yKqw@L&XKUWo2SXsOF%zR@_qKC@uh9u z7V9M66O4R4`i%?dgscxT_RT9v+=`t)m`_3?v~8$-8O7eY4TYX(u`_vt%ez$6WAq}) zvlvd^G-9P%pU3I@8`JZQ(+!Zrx9u6)ePgx+@5)a2eTmk>^z27hDGp z%wPHDj1g#b5a#}P8S~I9Qx$In6bB-~`{G5ap>4+>$-AI+mJyYW{MWQ6i zbhA4PChaf1d*5J)=3(x2OKzB4yamtH70|5tt@Xw+%}J=~DL z(orRJ%0BWlmRb;sQiz*>#?)f>sspDn$CiZGH9NUfyKmqEwWZGr7dRkI0VnM~W8Xtx z$8)*J;nez2F%o_~+FGx?LlP{@ZXBt{8Zzcn^{0F>?9r_H5+1Sf2}vu4#PA<+du)XN zYTLIS_aXh}MED=>c<%#}juIm8|8U32rI4|B5xM`%9Z&n!3rUK`2jl{}KO zad4;gi2>-r=lXhTYojgxf3=RzshWB0-70JO)H)*}WM#;JknHV~*wkxKO=f!0Ote6> zzpc5=9n|gA^2RJ`uj)UswZGrH8T2&26xgeb1q1UE;V1xQkx;nKZ4+bw>UE7@D4XBN z@YlIeisl{BpudQ+6+;gbNYG(i#gCy>P$G!9S9tvb^DUN>|FA(G4L}NPt_zqz&l(7b znT6CMgr3O@qy6qlCI{OVPRvjU7lDBdjR^&~l?aSSwhj+SM23nl3gp5S za~i;g$!pue57>pnH&gCJ7H{mMbHs6mWW#{L4i$v@H-{-cnLtK05QO~QLYcu-nIl*g zV`c)pE$SQzNf*k*fu6Dt_#PHU4c~)5Dgz*k44f|tNG0IH|0PA<2$A1_u&RoAD>Ah@ zED{O_nxY^nLmwRW#HX8?f!jk5W-t|LO-v7$4ph~40g;gfB5&h{079Gy=qLk`Aia_D z>Go)5unP#{D-&>NJo6-BIFT@{zKGH*M~i~}*z=(%>%<@<5mn+80>VV6lof;CtPylg z1IXnlq1A)n=;%;a168rhM$msn9>?1O5i6pAXwa*4r6Rnhk+%p?7;wB-vEB!N0$~2Z zKFYtK54q`N5fCIWTA1nfO=fU$vddB6bPL6xr0@fhpe98q2r*a!Ea5`SILm}%fN@|k zWb$9sk!fv9fDu#53P(cj&yqSP|cIAEZU}p$2@<$xq#GXYH4DSoyHu_v8llJ1~ zSB%`Y5s7s-gazA*P~m!~OzHp7g1`ftG>W57)*(~Gj*}rIXz+;;iXG$%!Wr&gfckY`v%`6f?RW7Vm^kMYJB zSuFJ}0Y#o8AoIis`5QoJYgs-@k|fa4HX6rXYWuILt)-IGXF^xAxIUkRUiae#Mku;l|6G zjdIVH{fCQl3Ixy+_D3mt=161xgkZQFEn>SEv0~zFe<%|i0s`6C+%u0em(JuEU6!Jm zvzLoo#$;U!CsEQfRgO_&Z=xXO3KRKITr_r?S7N+N9kg?fztX5+H_h$7K(efDaU(W+ zY=bO!@R9Y2SQ1E>b_|>wFOAVCFiv_avHylMB#*K=y84Nz_?T`=I*MLra+oYt zC6!i06xnqIBqIe<2*7g|Ws#Np_|}tvn2|^@Hj49{v=34QG=Ryr#?YL<*^e5vJQUfo zc_W!0TbN``K}Ar9uVj5Fv_WodL6^x(5+2^GnYV1#lJA&ld-D z(QlivSk{(E!QF6d*J)6G9^?XY0J{kA`EMp7H6aT>9Yx!IDfz7~ca+u(LQ0~=M1 z<1T>KaHohRr9-fMBFWq955E$WX?pu1dzz5T3J0r?=D!VM<}T@_c*&Xc`$8Gpt^h12 zm^>`?bz*Jh1)onVK5u72{tqNyed2PvN2WLTcEH`zHiwEP1-2L2?X0x5dR_@Rv`goR zOucqcNE{}jK8Lj$xb>dg?*|%Twlualj9+^n=)G>Py)l~qn{qUKnxncd=d6OhIbsTaQmVUcc!mEU}kZ7-443=4OCK1m}7we?^~ZugP zve{K^ZHTVt2p*+UfQK)HBecyY9JcKs|Al^-&;-^_0vI#U z#Z4mE5@wkd=C#w#5bWdqW;v;q(wAFIbXs{tcU)n$pS|?RZz!WzvWs&mgEh?a6x?z( zGR|2w@JD^2RFuca+^Y5E?QP@ZmA<@Jr2)XS^f?>vf+JKx!-mqit#cf zQ#nf{z@zh=z6lmtM(!W!K=-w#Efl$dpFZFWR#0p&I#8i#-ZK>YN;hmkgDx6xzD<3d z)rz{$ahh^i5}9vd8+;56yN7-yv2BgL4{sppnX)R9*(aLIJVB28R+Lv}{2gb}D~ilW z-7pka$@%_t9**AQ+F!dr8o)`3Y-k>G17q)LOkvMef)Rx*iO{n?T=-@ZWR5Wwpti3C zDTZ?a(V!z1n-@QtYC6sxQ83FMQovB8oT2V(yzvyUQa30R0$yK?Ye)fbn6RU@fs{kR zc5<*Vn9CuGH+)g{Mfb0qcx|m-?=oS^ zs=SBo!Y2Fh1h~uhA*PFi5n5^6`JoM0Ahx08yoM#*JS9INO)E}jDU+RWmTHD~Rsw^w z45`mnG4e{1OhjN24Z$a+h6HHCsTG>FAU4^L&I1^B`W0QDldLNyTHJ=ToH&9}m53-0 z<&9Kmpr-PpW^{GJz<&Xcpw%CI-$A^hjb>6?6@(fv0hSo;(rjx@(=~!2+h2TCQ7LH> zFK*pi%vz~bA&*!zpbX%PPKIf{;-Ra{skD&}I8SFNu^$uC(`(R-#ErQ&KYuv6;YEGB zVkiCE(38r{bUIU}+FQa^V-+hLt=VtxaN0L>DVx1d86FgS&GoP^-~HUY*NB+GMZk!) z#W)XO250Gnz3B_Xgji~FPf$)ksLnU&?Z8EmUkcb4cGA5FP=PFZa#<&D#Zs-v2b9*GW=Nf>pLJ<1MI__qY4B3H z_T%~ZP|7NthEwRv3=IZIB0qN@ypUkeXzJ9Y!4b>$31*KBTn~0u5;N9e7>j$JK^M{l zYnO;waZ;L@2w3Ik#shMT+S_>&A{8wx3MnYvou{e{>-@Bk<|4F{_p&Wgr^9U$dCoD( z&YW_UBcmwUbj-K1>zPr^14W2%rP|>w8y5IFBcN~Scj2WRb$f&MiK`}wbS?})A2W=9 zB6u`SKb!Dpa7_GdHO zA-yH*k)=<_xB_8eb^mCym6@%I@-B z&zq}ks^2fNR!cizS8;P-<$LBX`e&(Um_~0`CU@(GdTh`!s6|rQ(NuZ~v@ zGKl+?YM3ISX_$9I(0aX#^P?0pB88<;KWh@CAcdU|4Xgt6qQajlH4Ia4xyFjixsLVr z#&`3TI(t2rVKt^11UM1j4Xn2IcMXv_uf_-`B2+Ed|G?| z(%W;RIoZ(rFLO@JF)mTJTo^F~Y2zu(pHNZw2$Rf~yZW5^ z<47dFfh!}rAcZE07FjQ9Fz1jj-+3a>0m~ibzc)R7>&TwHQ>zxSN2C(of#&rtJH2VE zY!`iKPND6FEh&k^=ZpDTLv=@c3H4l?N=;uA=enit$*5VTsVUlA<^#phc?4_fB$p0H zbC6Nb+Sj)y#+i4MZ|~dySN8D%x$b59AyV%cr?!x@WIjTuB;l#tlz$q^V{k5#pc(|(zzW||M;l~9wUn+r#Lo=JSF1D z@4i39geol)Sn$eD6lbG9n#`FI8(J~r zOnKlpF!kb|dO3r{2o)fA4IUAJB-02cKY<;<4KQhi>%UQ0D;JtNM7Ay$uvBbz?|FV{m*;xm)F`L0 z^i7%XM5z@&I}|qES_5}B8t^rst=#!pJn%S8%f&(V$6Imi9#j%JK7Qbr93Olu{EGA~ zm&bpB~cXTb7a-+#L?AJi**u&*@6k5x-GXnyVr)N6j7b5gty6q@$lRNk^-x_P+ooBcb7 zntrE86`C<$@_vTy?@@t>BVeN=220xQ99C}18H@L}OZh6}bl?`@K#PeaH)$T{i6n?<7eWYTf)k z7k$!DRzaiO1TmK$TmiJ6r>~j{b?_qf4!D~o3a#`}p26%p{6IXLGIthMu;QtenrkRW^OT^61!u8*U$mss9N~U1#Zcg?u znj@_<8JU=XjfIUKAS_H~ZV&qBZ327tCY2~iz^uy&;LNY9PFG)=q&W$ zV%0Il0U&z!E8}5o{9gUupy~p&IfimY1uS_8Z;@THRKYhKTKJEgA0uR_OsafB)62KG zYq*$>dA3kqQ0d>5`C;wK4lscsR_K2q%UjYh8R~xjn3WlQZ52nnX;|?PV|mrU8_zEf z5oGk`I}7M)@5uTpls$Q}QSlgM!DF)yzH?R4e0S68iUj%_zPRa;c9g(Qx->N9`ER_~ zH!zn`?>9x*gsKZIX4#)YRv#APy}C7)KjOgtnjwhmeagbqI1bI`6l$*zI%z3dK&MmK zS|mc7HbGAY1ehSvJwOm>=_vc~g$W{MkXd3_;okECE{|k&^b+8AX32ynhadu8aV`YLZ|zMqR~ZVDy?~V&B1L z$pH^aiTH0(8#@Q^|92fA^8FWnPuodFCIWLB09e)j{ShEz=i>yhYLV%&k#Uf*{Tozu zaB%%M_#dfORRF83y@kWS-hXQ7KRpRDJwYB(J_&Aa32|;V2?-u<4nA=SDK;Rdq@*YZ z7Z(SwD337N|3Ab4`F}Fa%l3aVO+7DftD%8Ce0{&+vzGH3pc+5ksH__j1nYowK>kM+ z8~Y4e7ahAYR0M&XN+DY&nh-8N;&%W{Mp=@%co09ZoPTyu^ovYTJ{w#GuQ3^n>-K2T z#i!}bgyG*a>FJKGnv50K-%MEPlPAnEZwS$c3R5aQ$!x4>d^#;;;A*Qk_(Q72 zY=tIp`cZG{QI@eCHy)s2+|kwz-7r}EioXj0pRN_iJ}<&NKZg4|qMDs<92Z4GCy3S< zbuu7BnYHqRK+QrlxQe5PG7CjMU!~<;?oHI8AA$IA2-6eu@cPVL>Kib(A$QhPTjUwD zP_i!Gndh!AN>C4Osv-X?c=t-vDj_Di=rB89%ON)oPpQv&<$BS|DYgN?2rBh48|SFQ zTs3B{3gW6GT-~ug3PD|YWv+J@s!B3Qmy`B?Q`{Xt7_`L0$~BCmU(1tszuutB4MnNL z;O?_H3S_<_whgsk(MqzeWc`e7o~<)n(e_DhqFO_p9$@i=EN~M5lX*9*Jq#GH9=u}J z+akPx_C6)$DI9&s{R1HJLxk$k!py&>{DJE=l2h=*=a4M=Nql@C zpG2c5sRJWCj3kl+{+Z|VCElI(mtwgVsGej!Cte7p-J{gg8&>GRpCgRm2V+`mK4~+f=%(6^C&T z;<&`BXZ8cF4}5C!J6tObf4|ytAWr+^fyl5QY`m$1+RnuuctEy3$<#q>r*F?9$=#^3 zzqdEz`^gJtbK!LmosR|=H?B~`Vs$Vo*`uOuxBQTRhbipJeGJ29Cl2)w$AUA^`i}-I zbK3Du6wrD*`X&-+X{-iIZ!3SdaN4Z$C&PjRTZ%Vf!FutZqh0l!Pwt($Yg>`xADwK3 z>g}GqQa { // The first is the 'evaluateError' function. This function implements the desired measurement // function, returning a vector of errors when evaluated at the provided variable value. It // must also calculate the Jacobians for this measurement function, if requested. - Vector evaluateError(const Pose2& q, - boost::optional H = boost::none) const override { - // The measurement function for a GPS-like measurement is simple: - // error_x = pose.x - measurement.x - // error_y = pose.y - measurement.y - // Consequently, the Jacobians are: - // [ derror_x/dx derror_x/dy derror_x/dtheta ] = [1 0 0] - // [ derror_y/dx derror_y/dy derror_y/dtheta ] = [0 1 0] - if (H) (*H) = (Matrix(2, 3) << 1.0, 0.0, 0.0, 0.0, 1.0, 0.0).finished(); + Vector evaluateError(const Pose2& q, boost::optional H = boost::none) const override { + // The measurement function for a GPS-like measurement h(q) which predicts the measurement (m) is h(q) = q, q = [qx qy qtheta] + // The error is then simply calculated as E(q) = h(q) - m: + // error_x = q.x - mx + // error_y = q.y - my + // Node's orientation reflects in the Jacobian, in tangent space this is equal to the right-hand rule rotation matrix + // H = [ cos(q.theta) -sin(q.theta) 0 ] + // [ sin(q.theta) cos(q.theta) 0 ] + const double cosTheta = cos(q.theta()); + const double sinTheta = sin(q.theta()); + if (H) (*H) = (gtsam::Matrix(2, 3) << cosTheta, -sinTheta, 0.0, sinTheta, cosTheta, 0.0).finished(); return (Vector(2) << q.x() - mx_, q.y() - my_).finished(); } From 587ad0fad35706ab234a7a197bd0dcb68edc1719 Mon Sep 17 00:00:00 2001 From: Navid Mahabadi Date: Tue, 23 Mar 2021 16:13:13 +0100 Subject: [PATCH 02/14] update: use avialble rot2 class --- doc/Code/LocalizationFactor.cpp | 7 +++---- doc/gtsam.pdf | Bin 826123 -> 826064 bytes examples/LocalizationExample.cpp | 5 ++--- 3 files changed, 5 insertions(+), 7 deletions(-) diff --git a/doc/Code/LocalizationFactor.cpp b/doc/Code/LocalizationFactor.cpp index 623aef8cb..d298091dc 100644 --- a/doc/Code/LocalizationFactor.cpp +++ b/doc/Code/LocalizationFactor.cpp @@ -8,11 +8,10 @@ public: Vector evaluateError(const Pose2& q, boost::optional H = boost::none) const { - const double cosTheta = cos(q.theta()); - const double sinTheta = sin(q.theta()); + const Rot2& R = q.rotation(); if (H) (*H) = (gtsam::Matrix(2, 3) << - cosTheta, -sinTheta, 0.0, - sinTheta, cosTheta, 0.0).finished(); + R.c(), -R.s(), 0.0, + R.s(), R.c(), 0.0).finished(); return (Vector(2) << q.x() - mx_, q.y() - my_).finished(); } }; diff --git a/doc/gtsam.pdf b/doc/gtsam.pdf index cd125a71352875ae3cdd164fd6acd0a3583034c7..c6a39a79c4f06bb23d4b8b26d53ee5dda5912389 100644 GIT binary patch delta 8376 zcmajjWltQ;*9LH8ad#+M+`Tx9yB8?Mt++#RS=^&KOjIN1bOUGgmq1u9c1|z{A_HiGcrA8q@ZPs8&@#Xux%_&ae{b27-kQ!S zfl{eaDvFQ38QVQMg1S;})TZI63o;&pTS6MK>r8qlM!}!K?{bm6gB5E}N#g4o@OH0~ zOfa>@j&GGulQgsMnom8OA(P;k?~1L@nwPzIc~d&c%Uj2qK37lWe?)s zXx_1vmVD*V->Tq*93e~GfwB(QM@2~+VY6S%6i%0+4F zXx16BZUI45mIw}|?35W$n)v%&cC*e9^TH5A8-hDTJeUYc?%PX;+kuKT4#TO5JIhIc z^jB$@K4hbaOoX2mbxL-{`2NXl?V!9w-}^q5Tg~_M9-bhJi_P-7`qkfV5yX~-@>0{o6K#n z`GiqT7tZ^v@DA|!M_KrESieExWB5B=xSmPAhRk(IeQAJcc-MXLFH8nr5J=SGFiV83p>{JkFn!2v|Ob#z#~@PAQ4YvNY~FSdzM81jLlF{i_fFe~?! z=6zphwny%J$ZEAeUOnUT=lsWClc^4}Q5H^iM1XkPKkHsKaz36)pxjLyw(jB16J5g7 zexzl_hH^|Qw}@k=R*cpd2X^P#G%HhDaz{G>I0D%3aj#_nz!nUjI7B+(ux`ZOmq&L> zHY%jtZ2{UE*MCK}1t0*&C<)DOVp9R?l@V2-A2I2caR36$QPavK+>l|Png+z@F%>B| z@fjSP7WX+)u>VzLyBTFKMJO^pt=4{WxLPXV#A7du(Y-{)M25n_E^k|<$tslv67d~M zx0vOcY-1|a6oSR4e-5ogO*f9mMID}EUYTbc&83w=As3P-4a)kkNxvl%m-i7|XAl?@f@rS!&oGjIpqXl_3eDa3+cC8>Rfnmxkq}a-_ zV26<|bw~qkFW^8Iwq$R zuvFxsKtV&nvQ!zFTZ%yP5JeE=)Yx2hYXS}x;;}%y+*q3aGXk;FKlrRNLZ5qHKGjKb z2R1~wZ_Pum3ccG0*a%p=C-SpoDAkOJ8zKG$bWs0Q2hkadEi}^X)R(#nMRREiihUmr zM~O^ilSTw;2CBI%u7&pO$yl!^$AH7h&`e2YP)lhJm~=Ux6_Zn=Re?3+?={88Ig}W! zJLGi42fwIfB($xy=S!}&f;LAbfu^a3Bw93vj4EFXX4nTyuv6eHVxVJyS!T#LF^k3H za^b(PLH7(?)a_$uT(vV*Q>T{bc^FyVt_j6?@Z3@KAcI{E`YL zopNX=P~?~^jC5`9 zbXRiL*=AwT_x#6}=zCyE9Gg2usb1Z2U!S7UWl8jqNxLPL z=DQ`y30gdn141ODFD0&BJ4edaY@Yzeu}`Hg3AFzXRvC;NOnQJ~N=X*afiyb`KsGDh z*&Elx9*#eoTNHkBPY093QYU`BDAfRb2*9jigoLdHNZ(@r_yQ*q|}C7J%aCiE{(!oeq}N!mM4BE*C_nFr6zIAMM!1z@O3gcVeKGugDSpWL{Gc_Dxny>NRODb+gqVK+9hWRJ;m zap9E^cM!oXILRPId7U)Mt6In(@s33y}YfhMp;#pc&UHxcVD(mYn>o zL!=6?&e|56KdZr^>H)1C?FibUL#-$Wh!&f?@k0|c$JOgx&V3aXK?Q7fK!`j zM=ka2E^B9X3e}isg*;MB@Cr|q=nzieU}IMo7ANxc+w@_&h|IILuI%k5%g-6N&C~)1 zpN3A)&1W(^p;LYH7&8uAm3*~sG!H7J$?&n5oNi5)9-9|$6a9*p%+aPc@wC}LqtO*| zCD&_e9Hnbitq2^;Ux89#*YEWD>|AwiwaCUe%bNCSa}ZqiBUkwOC>QSvyWDUzRfxFJ zewN<3B9{b{^WnOVXLAp|Ol?ueb8l@Yt%U|60{VdqihX}S=kx!SBkYy1*e!z+|0N&k z%QbK=!Po8J2d`%0Pyhales}}oLfu;mF4>(1K2*BOLpw<@{{YF-ZxU!yIRs`-(O|-( zoO&Dedm+sNgt)|`1v%0GrVrwGx5*keAW*JqHp(_>9(>z)`2zVCQ?Y>QFvh-JWL!OK zzL(Y6cizzU`M^6)?DPHJ!QAqy1=Qy~u7qMvoY(4DuAf1QiG@P%E{!?`+S+Xdi)Jb5 z4s+wu9?b=W3NE0c^-Xij)CH@~(pRehXxPuTa}D2kr=+}^twh#a^vNWjJKa?2Yw(1H z8qY(pBZoV^86YWc!oP=@(3$~`6{=2%vlgnCdi8C|$IYe{3iNe0h>Ms;F+Y>+VH}2T zSBe%@x`p|QUk79NXwR#QU`Uf>s8wjzNFFn^hx5hF*P{)&g0)KTJ{ zmGQ_TE5#lWMuk{>LL_Q9%+w+zaQk}rhSp{6eqTNy+|s%&TL912|AK7`yF8xKu&@ZF z88NXqH8E|wO@;YbF8nn+82aZW<}2_aiC2g4b$~v}d?*jvrND zyDF7r0UZtMu$%9hY>;EHbCx2^xiv#y)Mzjq%HuBzH(5MX=_CuHeW%DnSt;Fg42fbZ#3 z{FbWVUHls6Sgcr&1ugx3cC!=U4#SPG#~VSmt8)j6?R(Y^;rHO4CRAK9%{eFgniC&b zEYpKwGBqa>+D8>|GEWUh=(KCGdD!rVkOrfs<-U^ZhOw#VI_@=UxfO6HF@U{;ByZ^~ zPOD0FneJ&AFyQE`*e>axOG36OydCYFu`~39YDCd>toYpf#=-zlTahe8;m{y(Or(Fa z48JsIFZgVR#~0x>7f9BeY`x;8KF}tl%Tks#ujpu4v2IBICPJUYlvo?)jic&Qp`)G~ zaKI{- zZh@;}=wP@w{=N7aK{~oFdyRO0kgDx^wpr>xCxjyd^VOdn8{AfN%W~w4si?`hW|Lp@ z#lPCLb#)@}QAmy6tw!dp{G`SBwBvlW19b?${Y$zmT)Ild^6}$zf8@9YQ%%ui!u6*o zDG`|!tsF`Ekuy<8W`kVI=%`!gcI0H5QiA#S_KuM`V&((1cTf}WpDMY<6$ABJ6?HAU z*#pgp2G`ler;U}@urW53DI(&lzUI#v5tg3;e-b{cgJi@7^G*91QKD`DAY@qy7%xU|3Cfx?8L9?6YlL+y5$hN~7;8_p?snH%b2OfH3Yc%JqitJq32R%9^TDA8SSk?Psjb*fSB+3EH%+Gk%N-D zL`CJAOax zrwWtYZh1U7!_Ad!NQv)b5PAwC3E%5dndSGlhcBS+5x!a@3LO(_%C8ZVOc_~Z{&zy9 zN9W=}_X77K*msSJCoiS}Rdx9*i>VM8nY3N6!;UOr$A_nyW`-NcN=>yP$mNbE*6SS+ zkKQ&!NSknuqO~a>DpBVWf5s+KXnGWWZwc+gTBrG`qS%v^ zZjkJYS76{*N0VdO&MCd&ZFO1r$?0p%ND%e|KO=hLy4=RwyMLSKu$)+5iPuoiwK8%v z89vqQeGQ-0>i&n}Ym1;kFx<^c5mj(P|LUWe-@Z|F-z%~n_a2`f(*7+~aF?&rG6_PZ zJ8OuLaoY}c`(@LYm5vsnKG^oM(n8;a>=?Cz^9sJBlWX$26+DR7el+r1`Y^E3YtfVWF z+IW+b_o{Bq#49=YYPRb2Z}Y2+gfrajoTpoN_u%6)L>)$vl1};FVy~X4dXY(YP5A^q2GYh~Nv zjqT+88LPHKWI6v^sXUnSqe?})qgOh?o`)(u24A|3h=7FER6vNY(}{@H9)Zh+OFhR- zFMP!=^uFF39zlHkmsro%L^bH#!LqXf*+a?zUZ4|`EEdAgFVgJo7`8J3qE)zMl5YXU zy1T5mF5MtADWxZlCG z=onnUSqzR)R>adZ!P_q@7fHXE>EFf5s9m0+1}^IP7ZD;jg^?NX!UO&Sz3c>6fA2*Ltf?!FRW;?T7!OR;F5?qAs|2d z!jeGyV~1k_K4kM6)I1oWNi1!GFQTO#bBxz_d)A3&i6pS{F<#+P(plrRMC;iC5$l$v zRUML;%u)ePX-&>O)}k6gTY}5Q!)U;A>X6MMeS5?1n#598D@KXgJ0D$KzV~$gBfMeW zvfJ2H-U4+#a|;7$@QAvomOKWyi1va7C-OpSi(oKS(NY%l8oB)8(NwnKnabw+1j0@o1HtZK{PdQk(bOiuiKfP70*rhuZ$_;N8o(k{^+GJt$t z%pThJx#&N#As-q8OudY3;M|@?lcX`78<(eO4HiY-$hsFU@VbN0fzl8u@kZKI1gn4`?< zX3^gBTK&ZlNC+%@|IGW+=3M+SyppU+}CiRG~CCeEqpbsNDjS_+HTikQ%;6chc$$!r6j_Fbe&3?2C0W@+p)hVr%0Uz^2#wv#CX3 zvtJWTRD3^az@w##xAn+%mZT|>KYk_ca$mghBAJ(Br$nt#KU;IIlVI9IEP10qUoZ2z zLXKhP)ocv;ehuAaDkqg6k+-d>*Ad74`$_00H;&dy(ef|da947{h$R^v1b)rD?-+E* z^crA}MjUW+GCmA9FBprJ9+Zi%RF%hbm1WpdfE{n}ea)yEvK-g6TB@mQXYcFn*v%#e zmjUCsa<}9@Xo@&u?p;hdu=kX8?bDs>+nu1z^=E-^*L(XLKekn_XZ?5ynKN2`3C%qWr|*f~A38EHgE zAk`O<<_E-hS8vtC{p;p~>px^i&Xq$FqU6jl*f-S&oPN3}L}5Od5;lXKtmmS7t}@Fi zjU+ZpSYN4ckUAEw`9X+Dv{z_6#pD>~?R6e7#BY`-_U)?gSDv-DKwsQU*aONa;-z!D zxaw#~hXn5wY&<)m`={etm!ir~;ZuOn#k8IIwMDl8E2|YMMeVFrbyI0UYE^v37!kKV zOC>lbGus;?Lc?HLk=J*mSX;l=kR}ubBVAeirphKjOV;EdIw;_q0Q)TQID&oeOrllVpeAHYrEJ1?9C~-wEn_Kh&bh-V5Qm_}R{#^#9z(|j64-T2YZit-ub{zPn zOS7`U6ofRw33^K_^DuNTB=TX$2*ebpO-=ZqihNyDV@?DjOVH{CnR!@i{#X)qTN3qi zDzG{Mp}NAE_`NZv9GhLFCy&jaZXph<6RJ$zzyD=I_$1XiWTnn5sPp(6`EIS=Q^O%l zoolkZs>9|oxH>_9xRcGoM9-zT!uf6>&A2ReFF@3=5ah@ztZ>Y(@4DcZX{j^%i>Z2n z85{RZEW!S)$F~+?dmg_|IHC_i8$U;+1ePeK#!HL#3pOVZ??+f8L4ZLcjX}x3?a9T8 zf9?rMX1z24&I!;u=FvDUjQ{ax{=At6Fn^GaJcTwi( zO{2j60d4wtONXZI88bS*JEl-=@F@A_@APV?jP!5CaEC!AsF>wyq%GGUrKQr(+P*}42 zm={Q(Kq18-I{X#0t(SSsl#_hakBqo@s1AGf&rlEJ{f@V>?T))4wydPO(s%Gj|HE+A z_qx}{OdzHS%r-XZ(>!mVjVj_(y!!=D*&&o8Cq_kJ$ErbFG0Obm5bnqOKvXhimV=}DEBkk8h2wVwg(B4_`bCSr5HM_}_K+hbjQSx24 z%1qvh zpNprtROEPOn3%l195%+TAEDEGD?qwlUAL-hbf$S~cR^M3__(d(;Sbz~MNIfyGFf(> z;0yMR!S40cZCrUhiJ8DAW=qkGX#@QwO%w!2V+sv-orddI4u`#|2daK3)pE1Av4M|W zE}s2#o9*7nmE+nR+A_iRmlo#_P-A9K3!TdS({lLwgm*vokXUGQx0>vST~!cO?(=OF zr+BlrOlQdfwOj7o#PxJf!gF7i!X6CP9((aI?;H+3-UMHqX9`Iyj z9${;}n;g5tCJtqOYI!TV8o9al30k5(#3PYwpD8}%_B`}=jNy;!XBhbFoI4(Zo9ib# z8i32y0`}?68t+EC5q?vjP&6{Ud-CK$)2FnJF5lBih8Ew--T1^ zG^*H%L5(_&1zW{0#OnVdc+qn9lhU1Kt_+TF+R=<;9IY4kOkM=pe@jDKGz_t9Ef3_G zcwJmuZLRmQRo~6yR_ENlxv!DBGkLFKC<8edNP6~H|EgD<>&k+FPkvj-APR3ixgxrx z(>qk&x2z+KU~Jz(@oZta8>so5p4_B%+&-$R|C*1y+A$c;-YH-plO9LLH&d3i7?q?^S)ZVD;xLLcPJ){ zj23KATHX)#&lez;Sm(_L7Cw1eaYLd)Z`jYw|Du<#%89|2^(irt!0dfizZ&Dm2no$Q zIbhQ~_J&MFkj2(yfoeB~{Qdy;qS8xJ>s?zKMxcCvMY`7V1wR__A%iy{HI0&L=P6-Jv2|fuRh0y<7qL0j`Xl8Hm(~^RZgCC5^$^fF7*SB0WBOJOug$PZpet2rf zaizCdT`ZU>*j=a{wkcPnvbiW{TCv(-hEPOWXk$umt05L<@!g1CZ_A(LCs0xsgEv(% zB;)C6RHA5Ggc|oplA6vInzs?EL5P+S!7Za|sDKCRi5bhn zGGkD#?XzP&O$v;PD69~=ruHQ{hZ#2a=<{k`CThhrwXTc6d(M(ETNg{=cyP%TE^K;9 zR;X3IZn3#2*ExLY@w9jwQs_2KR)a*k?O(`p3kXNxhpG4MPJ11j)1xKocp&RaI;m4X z+^WIRZ&E!{^{g-pBcAaf3uD&1ZW0glXQR$DS>1Ads4pvFu*XR_5)pF_G?N|id@lxy z+Gr?dMYOs4$Wb}u_8ymjU9atyIV-LR zcz~dJdZRFh_z|7_PR+JJzZ#z}_Li*$QAawDW88@QA%vk7>@a!N5)ZeL^$!nm5xVXs z17p?dZs)4?-p0vi2Oow3)aLnIRIx-@6NC9?hH3S8&bucA{Yhn5Y0c2b-{$3KoaHzJ z6JzGm7%zd*&~m)!1!hZoq??Fv$3<1U+@SC#u-l=YkdFBIy()n6GJm<{lk#9@v^U;x zhstk1!K6*6OBMS5D9Up6{I(}cs!=^jhrp6i7QY`6m4xU1=KI#ZGuXOuLSS3E^GP(v z%FrgpEia0L28OQfUdq%uxupqyk9?iaA5qQE`c*Aok9NXksS4Aj1P09_XT9 z%N6Dle)eePn<-MkOuR z$fkB}uTW3jJ5mR>pqo<8%FGdL>P7JPc+sI~RJP6Rf6j@7d_-0(md!slmT?iwJF;1FCtEVu+-oCSgf_u%d>i%ZZT!QI{6Pfndb z;9NXazl*u(o|@{K>WK!f$VRSe-atey0YSd_oFztp?7x_$=8LCS^c*DkCy>j-`$Xka z>B()jA;UPnrCeEOhWbYLiVW5hMQ8UW**Bjs99Vm;gC)yHBwn}(9^*%2uG=NKM;tNVXRZMDNqjQ}si^F4c6 zdv$zLdNa$OxKX3Z`b>ApLYonr;O)1j4MS2X7PJ1gK+IyM*%(VrmP40P=M{7y zXgy)a$g!q&jdf!M_B^YYJQHH9F<=$|HyNu37@p>OU^Jp5i{vGdAnQxS(5&)2wNoG} ze5Y8t);Tf~j4hEvg|9CC>~R&+=Xrb9>&-%7Dv(AGta3bWt7-Hpnxo}*T*?cA6K0=v zx`#}-M%<*wHhQKDd>7}7%(uVjr?$ z1WH;*9{qZ{CyIi^+}_6CJYHQCm*9RXXFwrywbBoRng<1ct z+kha0G~|r>XO^+lm#KH(;0B*e$a~pM&1H1?EzRet6!UZ~vz3;<$k)(-n)tq+zX-AY z)Fgvq8Dq52IZXO;ownh09Vp=_fCY0aQ>Z2Tc-(G6H;O6+WPYM6M*$+kj;J@%xBJwN zK45v%RlZHpUym^8{_k$Lz`Y_fW3edf0-5D#Q*lc$(0V6MH&CPw= z;wYLyWvF_BioDMzo+ZdJ5}P;nQS?mYSYFM_`4IJOtlk)K2yVfto=WCv`diXG8HaD- z(4J>qWZAZbI;OWRJb)}Kv(X`vxk*e*^`PKKeXX3I{bM1}NbPbW$aLd!Nzrrzt5=Q1 zm`u_ToswdUH6YfX$DnQWs+N><{!doaH(iID3?R*CHa#~f5a(wn?sX`bFT^^LL zF6%qLEd(G=IEof%Cyr01DL;U&Nbd4D)ru&Gc7dR1-jcuP0PGHA*`@s8=~^v-7!u(Q zt&W8wB4AAZ0s78@l=oQK^erf?>Tk0$83gy_Uo+Oo3wSQ6tQQ^A7DC{JS1=c%(0%o% zA0NkM{O?T42u9l5bs(A|<{Sx}2}Pxh5<(!*ziR`NUSV6C`?~q3bu>&stu^O59dSmA zMmixwMf?D!_yeNhR{5;bV|x4_t}#kQF}Nv5RWZXJK}E5DFJuTJFcjOORvGLyQWQwl zc0v32$o{jg%&a5q+=23YPr$2_GrAUni|#5sJjwwW=7>$dovB!KcAeX~;U_g2j#gF1 zwJIj%v}Ph zkI603(xydKE6?daGhlv#J6TgzNYRnl4?z-f&uA+7Q}B=~V`W z=f2cx23S2WeD6lhg0<_@_eYftv@?B7WxN)0E8BU9dEi>je~Y-O*jE;YCh_yb;&I;R z{1s+nkV#b)_$qxlf><)5H@5n?K+w2IBwIRSEPk}oWu79bKZ$N=8)0!XK|i*P4#009 zVC)>vimnl~e0>r$q!XQY)uQvaGHBUoP6=vjTTLCF4x6dP?A>UvId5wL)s2h#CfD)E z)ZZYsI&1f;)oHfcxlb$1|I{rM*Dv-PvvUJJ6CoI#Xg>PQE<+=EI+mODwWM16e-n!; z`yP1sj5L|bCrsLnHM_$U*^g%E2{|16lyd`D`h&* zOqR3}*oW@cycB|oOHr(L zI6|O7y~fRO7%N&LewfjTj!?qPp0Ed-Oz%#Z0ul% z^MjaK(l)F}9?B=b=-*!H23HH%2!!dsNN}YLEmFZoc5#kv`CEb_LIU4f75U6nm4&UyMQn|^V1~}X+T*75)QM+(j$ZmL@F}i* zO2sAfwarAEMD7ulqvz-CEnV~0FF}S*>}yb!BhzVUF1l|}c@Ae^2u}4=7@~|qz;vE5 z@=3zlnGx=FCM_aU8a5hv>4;d~i&D%RyzUSjM?6O~1fGXKnbQxG3D8@KUuwh!Iy(cW zI~3wk2Z+$lr`!uwTq>vYRkoBLjjgzN`lr8rj6+v^IDMS+Ai~hd?|X`^A}!+fnm|P) z5@)H-?)r&R=8wYur}^z|WM?4~qaZM)Kki51NLkl!D!jD*8Z@@#?(_wf)vteurWSQG zdDB_!4{~7R)wqBDngXd+b+tofT#WlGg|@X1YRN{O%^*{MmU>prf?8 z7PG-LeQjtmV?UzANiSHFFP+SIFj~;$%yXz}9x7Xp@1uc6=4Tth+!HD70V8qc}@ACrqgKTGhc(Fk2^J{o^5}jLNw~3YJfx+tlm> zD`!%&0tL$#)Sf9^JECHUv0x7$qqc6i63L}*o#NDwH2yg+ZaR?1a|HCzBYw%+GzII` zi#D94BJJr1qStf`Nw`-Qd^C@wKQa^dCnP^8A@@8)ZE}0Zw_X0@`99F!Cb~}17<)wm znc<4)*NEmlYAIicS=BP`{f*LBDrMPoo}ix>l6oOc0U#NoNTFH&hDE%tk~u@sDZ_GP zxHw2g!0S%9x$1qZyQ!DyuhP=0D40hh_S0Jb*&6*4SDI=pO-H-yg43#Is10^Mz)Uy9 zxsPrk0xsRcyC@72u(zx%ZMWJMckG?xvXMHY@d>aeRUoQVU~E8igG=kdNwOBo__wu+wpRPRM^6t2J+}eB0+Ez zvZF%Kz2m?odFGV*$zIg;`dopI?8rP$842PuAgJ=@PHeh|Fu;@J2C9pyRceo_v-+B$ zc2dXfbjg7$;B;T5-F<%Xl>82*(4t!ctP%%3_~iC=qd$@+HcO7MU022!R{RPHTuoB+ z^WhM&|IlmKKsar z+9>w?WFZ&KrW?xRjE*-)O*OMa3G4I$=+FiwZjO?-kG?mkrlHZ&QESg<0kx7@PHjPfMClI8MGy)+^({*niQ(WQ6BH}yad?`a0!hem9x z8gkl|7+;S2DBq{~Ih8}Eb0kiQ_=;)q@n8*wZ23*kKgAli|#Yg%=;u#xY;_Ps6Lt zbS9OEXYoqo8$!2Q*E*5~yJ`;HacI+iV_Q5Ba>Hta!mZ4WQR7tn_n02Y+pBLwOg4nW zB|SBlJDWTGzU$2#qrF{F6pyj9Zf+Fk64Z9&P8=<}LmnA=%0;=?+}(B=L7B$Kn5+n+ zU9<>A5Z`tvP!WgBI(b%~cSIisMo%hu%=x)+_NI4Q=4P1kOxIQ^R6s`R3z>`d)fv62 z{7GzZF`?C_9J&cx#_E8)iU&XEO67RDaB}OXoRk-Q3lJkDDD+l>9emh!k-jOb#3qCN zp9@D5A^sg9{*{^MzTt0_zk}rt?FPothY`E^ZESOzLKiCp9@nAGI;z!hRVK;H^qA&K zSuT`MOp}OeCa91lF^O$DTeURaUja(GrRxle+Vc~jV!Hnhdz=BR+va^FVG^mQot-0b zK)I^PvtSqXJAo4{or!&^++hIZ=AJmSRcYe(n~+>IuU=%SCUVJipdgn4oaBTx1W>>rziVTy#lFGP>~cFkN03uCVm-T zU_aQew3c+5IdqGp6VsYRZ~^$k+WKWq7xrI#`|=aHF)hAlA+6OPh|xClHBV)QXbQ?A zE%RGX?a)ug)mvGe1#S2%Y$MK@4pZ+MR&>(W74pC6eL(t**WgGQ-i^w9D*mMT4nbEh z2f3E2$}$-}&xOz$?|{X}eTC&fCy!y)-6|%5i^3I9*q%&C4o#VcH z8Z_eE5%+PsWc7U32!aEAoY>^+H$dphG6v_TN!qWE+ptppq>aFKU9Eoi zJ8BijC22WWgHPc(jlYnG-%`whoozDTFQi>ILaH+v!?V-d3io^au7`WSa`9n_uXa?| zn?vn&gft>oM17RI%WGCx_f1!faW5$Z`sVM4_FV++7$2Y3zpjc$7xxLin04R;h>yOP zdIHRiIFQtGfS&SqlzFF5>97?_iD5W%k8RD5>+9Gft>L3^v($j?yIIag=zxy%2jxH@ zMr5{vs(lJ9G3R;i%Nb)>3gF%iv_yD6#y-YT5ldhP8rFHNb+K79aq;jwZGAMd0Q)N1V)T|Ul z(C9b5fRu(Wr79(-5`(N2iXx@K?es>>DstM+E}w#t7Zkx`uJqia*v66IDEFUrw5-2J zJt{?|%~x&+2vvzij0ZSn4MZJ9Hx9xg zVqntzRR}d4#2zFEPEN^{qzdDR0kdfvQ%ke%lGfqJXoW27Ck32&6vPR#aedjXCiR7Z z%^G44n1O#Z=z$Nw3#PJ=(Mrz}5}vVg|JLkHl6z%QLyh!$BDREgkYIlvO83|T79Ugx z^P13czJG)ggwmzq;&1ueuTQWE@%5ViI213R>S~Z=@%VIlzz+Oj- zAoUh6vcgKmJK+4aM04`a;fm~;e%7J3MW48!QRTfoGf-ej^3Dnk-^O~$s`%6T3@|yu$6mkeaj0JMj-gv;59~|wra43_>Vm1k)Tk&);G%OOH^#`lGpsV2?!s;gZ^7zNvy zKxD^tB>?-}W9v@+(vh#|#Qdvcc#_C2;>205vU*~9j_Eq5>Jfx?^1I48{ zopca_r^mg%oFEjF4f?y5pF&Ss+}cD*LM4(Ztc;8UM5#O>*bK7XzWqql}OM3A|h*s9u7=?mr)7>p_s&HU;Zx$;= z?8{oE@t)!jwa24jI7^Si=SN{oUq5eL1D3=H3-|f>nOXdiHj^S^%TP&0l%4|a4*F|n zR7_f#p}!bDUjPXk_MLEdX$+ZrmQMug;Efe*JxxtB4xEuA?@}^M@~`gRQTUa+KYKXL zi!t-7@X?sW;tW*q&cnZG&zR#3BZ<}bbOR3E=-&*V=g+<4r~AT*%DeWjKGq-O+|yK{m69acfM8BMksaH=%_CKfImL(@hl+&mf} zr}Dvp#83r_Gmhlo+>=-`LsL1s zT?#u3)oy1p%83^&c)d~xehlP$2rld7q5hgKY(J}2Nt^8v9e{QQ_|4MGgTB9$kBjW~ zzw)A~kL&4V_tLo@C*J}dNuJViwcxb*#Eqd%pcv=E?{u|J9V-*H7m=7+MqN~t39GwO zVq%>Y!N%AfdZvbcPjXvE&(C>6+hqqQ_Oz83zSKA(i~Gxd_21HU?YOPC(hYoF94i;)p-9r%i5SnI#^zWq&z8FK0wKM$<9P=3FgX?_f%&d*VHT;)=Pq}|| z_Uj;uVq;$|9|?vaSZQ=0Olgm@5u2Z=;~I*@we3+ZL=OKlXTvn>9fYrv%N@*xW86Xf zAD}?{d7jzNi}@!eUzrA%Yk_q_5ZJ#ui5V zRG3k%*>TTAio8_i$tDYM1Yzx?aR0#ngYXaHKS=)||AX=m>OW}zpf|OTV(<g*kdxu%mgAI?=I7<(mf`1@mXhQbqZ0Xl zj~Jq}f3$G0a-Un#2Pacd4mUj%-5jYeL>P6tHTJ^f&ev5Q6l! za}8MR8L3!}iGG4qc#e74IB5I&g8P;V2e4SK6Z?>e@bi#!$!IuJJcE$nO~K)DRI$xd zR{(!!hSm7PIKRuTprz&8&L~&FP`Rz(XOzhz;vM3X_>M;w`pa?*=USj#P;}B0g%m&X zs}hSy+PpKk=0V?V1>sYy=0Nx>`NuBWB8hSh;{3J z%_yfKrR95f|9)pYzaMvHGtep~7|7D1*{?;8cbfWthUK7Ha@T}RN^^wWv*e-Vq~2rZ zwM?=oF9ZNo|d+t7=4ucKVj|kNg~)W zU3t~SltHo+SQsX7*OFDopY%oA5N&Il#tXImoCG*uOg8UbH|Gy@YLSzMSH2+|vWsp&g zJLVmy|C!b@dL!14>egByVwWKgxfc&LA^XuKV3(XJo{|MC?3+pQG=&_;zFe#K!K#(r z4@RIooOzifZllH4e2f+MBY50+;>&?b3G@yUt%MCTxGl6KvcrYY!r>!dPU?d>SEB2Y z7AV%I*p4=eB1r(2*(kiXiObk9CyiU&K5e>ZD?s5PbgKF5PV95*cWT&{rPbz{=0z^U z5zE2AFjU=wEtg*^-WlPg(BLgA#Xih($Ch0#zmd|na6xq`lWg4p%TcrAW=m(T@cHMN z%EMwdu1&57!x~Hs>~^i1QuSQxQrI)&%Q=bkWuc^Y+7vj`+IS2|DdxF~5&#rq~_f(%8jWGVsmQ+mZto_;)H>{bFOC(iIQwjkl|V)urC^YYs?xhM^j5`&k6haa7ePF770{eJ+>)-P)S diff --git a/examples/LocalizationExample.cpp b/examples/LocalizationExample.cpp index aa8e0db19..d9b205359 100644 --- a/examples/LocalizationExample.cpp +++ b/examples/LocalizationExample.cpp @@ -92,9 +92,8 @@ class UnaryFactor: public NoiseModelFactor1 { // Node's orientation reflects in the Jacobian, in tangent space this is equal to the right-hand rule rotation matrix // H = [ cos(q.theta) -sin(q.theta) 0 ] // [ sin(q.theta) cos(q.theta) 0 ] - const double cosTheta = cos(q.theta()); - const double sinTheta = sin(q.theta()); - if (H) (*H) = (gtsam::Matrix(2, 3) << cosTheta, -sinTheta, 0.0, sinTheta, cosTheta, 0.0).finished(); + const Rot2& R = q.rotation(); + if (H) (*H) = (gtsam::Matrix(2, 3) << R.c(), -R.s(), 0.0, R.s(), R.c(), 0.0).finished(); return (Vector(2) << q.x() - mx_, q.y() - my_).finished(); } From 039250983c55b19501575d536bc74586a0fc7410 Mon Sep 17 00:00:00 2001 From: Aleksei Evlampev Date: Tue, 6 Apr 2021 14:33:55 +0300 Subject: [PATCH 03/14] fix boost serialization version includes --- gtsam/base/FastList.h | 2 ++ gtsam/linear/LossFunctions.h | 2 +- gtsam/linear/SubgraphBuilder.h | 3 ++- 3 files changed, 5 insertions(+), 2 deletions(-) diff --git a/gtsam/base/FastList.h b/gtsam/base/FastList.h index 380836d1d..752b0b571 100644 --- a/gtsam/base/FastList.h +++ b/gtsam/base/FastList.h @@ -22,6 +22,8 @@ #include #include #include +#include +#include #include namespace gtsam { diff --git a/gtsam/linear/LossFunctions.h b/gtsam/linear/LossFunctions.h index 4e6a2b609..c3d7d64db 100644 --- a/gtsam/linear/LossFunctions.h +++ b/gtsam/linear/LossFunctions.h @@ -25,10 +25,10 @@ #include #include +#include #include #include #include -#include namespace gtsam { namespace noiseModel { diff --git a/gtsam/linear/SubgraphBuilder.h b/gtsam/linear/SubgraphBuilder.h index 88c771ba5..21b8d8690 100644 --- a/gtsam/linear/SubgraphBuilder.h +++ b/gtsam/linear/SubgraphBuilder.h @@ -22,8 +22,9 @@ #include #include -#include #include +#include +#include #include From 16852849bd0c09963a7bf84fd787080798cc4717 Mon Sep 17 00:00:00 2001 From: Aleksei Evlampev Date: Wed, 7 Apr 2021 13:15:12 +0300 Subject: [PATCH 04/14] remove unnecessary includes in SubgraphBuilder.h --- gtsam/linear/SubgraphBuilder.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/gtsam/linear/SubgraphBuilder.h b/gtsam/linear/SubgraphBuilder.h index 21b8d8690..5247ea2a2 100644 --- a/gtsam/linear/SubgraphBuilder.h +++ b/gtsam/linear/SubgraphBuilder.h @@ -22,8 +22,6 @@ #include #include -#include -#include #include #include From 5ea99c4f42a8a2304b9f30445dd550a959da8bfa Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 7 Apr 2021 16:45:05 -0400 Subject: [PATCH 05/14] bunch of minor fixes --- gtsam/navigation/ImuFactor.cpp | 1 + gtsam/navigation/ImuFactor.h | 2 ++ gtsam/nonlinear/GncOptimizer.h | 2 +- 3 files changed, 4 insertions(+), 1 deletion(-) diff --git a/gtsam/navigation/ImuFactor.cpp b/gtsam/navigation/ImuFactor.cpp index 98b1e6f9d..28c0461b1 100644 --- a/gtsam/navigation/ImuFactor.cpp +++ b/gtsam/navigation/ImuFactor.cpp @@ -106,6 +106,7 @@ void PreintegratedImuMeasurements::mergeWith(const PreintegratedImuMeasurements& preintMeasCov_ = P + *H2 * pim12.preintMeasCov_ * H2->transpose(); } #endif + //------------------------------------------------------------------------------ // ImuFactor methods //------------------------------------------------------------------------------ diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 29bdb2a99..35207e452 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -192,6 +192,8 @@ public: * @param pose_j Current pose key * @param vel_j Current velocity key * @param bias Previous bias key + * @param preintegratedMeasurements The preintegreated measurements since the + * last pose. */ ImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias, const PreintegratedImuMeasurements& preintegratedMeasurements); diff --git a/gtsam/nonlinear/GncOptimizer.h b/gtsam/nonlinear/GncOptimizer.h index d319fd5fd..e1efe7132 100644 --- a/gtsam/nonlinear/GncOptimizer.h +++ b/gtsam/nonlinear/GncOptimizer.h @@ -298,7 +298,7 @@ class GncOptimizer { break; case GncLossType::TLS: weightsConverged = true; - for (size_t i = 0; i < weights.size(); i++) { + for (int i = 0; i < weights.size(); i++) { if (std::fabs(weights[i] - std::round(weights[i])) > params_.weightsTol) { weightsConverged = false; From 6cef675e6eaeaf89f2462e8cfec4a4a9a497fac8 Mon Sep 17 00:00:00 2001 From: Aleksei Evlampev Date: Thu, 8 Apr 2021 14:54:52 +0300 Subject: [PATCH 06/14] return back including boost version.hpp header --- gtsam/linear/SubgraphBuilder.h | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam/linear/SubgraphBuilder.h b/gtsam/linear/SubgraphBuilder.h index 5247ea2a2..84a477a5e 100644 --- a/gtsam/linear/SubgraphBuilder.h +++ b/gtsam/linear/SubgraphBuilder.h @@ -21,6 +21,7 @@ #include #include +#include #include #include From 00a04a1f5d91757b9876e5e4428cd52743fa7a47 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Mon, 12 Apr 2021 19:08:29 -0400 Subject: [PATCH 07/14] Squashed 'wrap/' changes from 5ddaff8ba..bae34fac8 bae34fac8 Merge pull request #82 from borglab/feature/templated-base-class 6fd4053dd Merge pull request #84 from borglab/feature/print_redirectstdout 349784a38 comment about redirecting stdout dc4fd9371 updated docs b43f7c6d7 Merge pull request #80 from borglab/feature/multiple_interface_files 7d8c3faa7 redirect std::out for print_() a812a6110 print redirect stdout unit test 97f3b6994 support for templated base class 3e16564e3 test cases for templated base class 7b9d080f5 Revert "unit test for printing with keyformatter" 45e203195 Revert "funcitonal print passes unit test" 8b5d66f03 Revert "include functional and iostream" 34bfbec21 Revert "delete debug statement" dbe661c93 Revert "add includes to the example tpl file." f47e23f1a Revert "Revert "function to concatenate multiple header files together"" e667e2095 Revert "function to concatenate multiple header files together" 600c77bf4 add includes to the example tpl file. d5caca20e delete debug statement 4a554edb8 include functional and iostream e8ad2c26f funcitonal print passes unit test 077d5c4e7 unit test for printing with keyformatter d5a1e6dff function to concatenate multiple header files together git-subtree-dir: wrap git-subtree-split: bae34fac828acb6b17bfe37ebe78f7c9a156ed5a --- DOCS.md | 1 + cmake/GtwrapUtils.cmake | 34 ++++++++++++ gtwrap/interface_parser/classes.py | 13 +++-- gtwrap/pybind_wrapper.py | 5 ++ tests/expected/matlab/inheritance_wrapper.cpp | 52 +++++++++++++++++++ tests/expected/matlab/namespaces_wrapper.cpp | 9 ++++ .../expected/matlab/special_cases_wrapper.cpp | 9 ++++ tests/expected/python/class_pybind.cpp | 2 +- tests/expected/python/inheritance_pybind.cpp | 2 + tests/fixtures/inheritance.i | 3 ++ tests/test_interface_parser.py | 9 ++++ 11 files changed, 134 insertions(+), 5 deletions(-) diff --git a/DOCS.md b/DOCS.md index 00104c123..c0c4310fa 100644 --- a/DOCS.md +++ b/DOCS.md @@ -98,6 +98,7 @@ The python wrapper supports keyword arguments for functions/methods. Hence, the - Virtual inheritance - Specify fully-qualified base classes, i.e. `virtual class Derived : ns::Base {` where `ns` is the namespace. - Mark with `virtual` keyword, e.g. `virtual class Base {`, and also `virtual class Derived : ns::Base {`. + - Base classes can be templated, e.g. `virtual class Dog: ns::Animal {};`. This is useful when you want to inherit from specialized classes. - Forward declarations must also be marked virtual, e.g. `virtual class ns::Base;` and also `virtual class ns::Derived;`. - Pure virtual (abstract) classes should list no constructors in the interface file. diff --git a/cmake/GtwrapUtils.cmake b/cmake/GtwrapUtils.cmake index 8479015dc..3c26e70ae 100644 --- a/cmake/GtwrapUtils.cmake +++ b/cmake/GtwrapUtils.cmake @@ -103,3 +103,37 @@ macro(gtwrap_get_python_version) configure_python_variables() endmacro() + +# Concatenate multiple wrapper interface headers into one. +# The concatenation will be (re)performed if and only if any interface files +# change. +# +# Arguments: +# ~~~ +# destination: The concatenated master interface header file will be placed here. +# inputs (optional): All the input interface header files +function(combine_interface_headers + destination + #inputs + ) + # check if any interface headers changed + foreach(INTERFACE_FILE ${ARGN}) + if(NOT EXISTS ${destination} OR + ${INTERFACE_FILE} IS_NEWER_THAN ${destination}) + set(UPDATE_INTERFACE TRUE) + endif() + # trigger cmake on file change + set_property(DIRECTORY + APPEND + PROPERTY CMAKE_CONFIGURE_DEPENDS ${INTERFACE_FILE}) + endforeach() + # if so, then update the overall interface file + if (UPDATE_INTERFACE) + file(WRITE ${destination} "") + # append additional interface headers to end of gtdynamics.i + foreach(INTERFACE_FILE ${ARGN}) + file(READ ${INTERFACE_FILE} interface_contents) + file(APPEND ${destination} "${interface_contents}") + endforeach() + endif() +endfunction() diff --git a/gtwrap/interface_parser/classes.py b/gtwrap/interface_parser/classes.py index e2c28d8ed..255c26137 100644 --- a/gtwrap/interface_parser/classes.py +++ b/gtwrap/interface_parser/classes.py @@ -279,7 +279,7 @@ class Class: elif isinstance(m, Operator): self.operators.append(m) - _parent = COLON + Typename.rule("parent_class") + _parent = COLON + (TemplatedType.rule ^ Typename.rule)("parent_class") rule = ( Optional(Template.rule("template")) # + Optional(VIRTUAL("is_virtual")) # @@ -319,11 +319,16 @@ class Class: self.is_virtual = is_virtual self.name = name if parent_class: + # If it is in an iterable, extract the parent class. if isinstance(parent_class, Iterable): - self.parent_class = parent_class[0] - else: - self.parent_class = parent_class + parent_class = parent_class[0] + # If the base class is a TemplatedType, + # we want the instantiated Typename + if isinstance(parent_class, TemplatedType): + parent_class = parent_class.typename + + self.parent_class = parent_class else: self.parent_class = '' diff --git a/gtwrap/pybind_wrapper.py b/gtwrap/pybind_wrapper.py index 4b532f6e1..1e0d412a0 100755 --- a/gtwrap/pybind_wrapper.py +++ b/gtwrap/pybind_wrapper.py @@ -125,6 +125,11 @@ class PybindWrapper: )) if method.name == 'print': + # Redirect stdout - see pybind docs for why this is a good idea: + # https://pybind11.readthedocs.io/en/stable/advanced/pycpp/utilities.html#capturing-standard-output-from-ostream + ret = ret.replace('self->', 'py::scoped_ostream_redirect output; self->') + + # __repr__() uses print's implementation: type_list = method.args.to_cpp(self.use_boost) if len(type_list) > 0 and type_list[0].strip() == 'string': ret += '''{prefix}.def("__repr__", diff --git a/tests/expected/matlab/inheritance_wrapper.cpp b/tests/expected/matlab/inheritance_wrapper.cpp index f12f6ce57..e68b3a6e4 100644 --- a/tests/expected/matlab/inheritance_wrapper.cpp +++ b/tests/expected/matlab/inheritance_wrapper.cpp @@ -50,6 +50,8 @@ typedef std::set*> Collector_MyTemplatePoint static Collector_MyTemplatePoint2 collector_MyTemplatePoint2; typedef std::set*> Collector_MyTemplateMatrix; static Collector_MyTemplateMatrix collector_MyTemplateMatrix; +typedef std::set*> Collector_ForwardKinematicsFactor; +static Collector_ForwardKinematicsFactor collector_ForwardKinematicsFactor; void _deleteAllObjects() { @@ -141,6 +143,12 @@ void _deleteAllObjects() collector_MyTemplateMatrix.erase(iter++); anyDeleted = true; } } + { for(Collector_ForwardKinematicsFactor::iterator iter = collector_ForwardKinematicsFactor.begin(); + iter != collector_ForwardKinematicsFactor.end(); ) { + delete *iter; + collector_ForwardKinematicsFactor.erase(iter++); + anyDeleted = true; + } } if(anyDeleted) cout << "WARNING: Wrap modules with variables in the workspace have been reloaded due to\n" @@ -156,6 +164,7 @@ void _inheritance_RTTIRegister() { types.insert(std::make_pair(typeid(MyBase).name(), "MyBase")); types.insert(std::make_pair(typeid(MyTemplatePoint2).name(), "MyTemplatePoint2")); types.insert(std::make_pair(typeid(MyTemplateMatrix).name(), "MyTemplateMatrix")); + types.insert(std::make_pair(typeid(ForwardKinematicsFactor).name(), "ForwardKinematicsFactor")); mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); if(!registry) @@ -555,6 +564,40 @@ void MyTemplateMatrix_Level_34(int nargout, mxArray *out[], int nargin, const mx out[0] = wrap_shared_ptr(boost::make_shared>(MyTemplate::Level(K)),"MyTemplateMatrix", false); } +void Test_set_container_35(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("set_container",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + boost::shared_ptr> container = unwrap_shared_ptr< std::vector >(in[1], "ptr_stdvectorTest"); + obj->set_container(*container); +} + +void ForwardKinematicsFactor_collectorInsertAndMakeBase_35(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_ForwardKinematicsFactor.insert(self); + + typedef boost::shared_ptr> SharedBase; + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast(mxGetData(out[0])) = new SharedBase(*self); +} + +void ForwardKinematicsFactor_deconstructor_37(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_ForwardKinematicsFactor",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_ForwardKinematicsFactor::iterator item; + item = collector_ForwardKinematicsFactor.find(self); + if(item != collector_ForwardKinematicsFactor.end()) { + delete self; + collector_ForwardKinematicsFactor.erase(item); + } +} + void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { @@ -672,6 +715,15 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) case 34: MyTemplateMatrix_Level_34(nargout, out, nargin-1, in+1); break; + case 35: + Test_set_container_35(nargout, out, nargin-1, in+1); + break; + case 36: + ForwardKinematicsFactor_collectorInsertAndMakeBase_35(nargout, out, nargin-1, in+1); + break; + case 37: + ForwardKinematicsFactor_deconstructor_37(nargout, out, nargin-1, in+1); + break; } } catch(const std::exception& e) { mexErrMsgTxt(("Exception from gtsam:\n" + std::string(e.what()) + "\n").c_str()); diff --git a/tests/expected/matlab/namespaces_wrapper.cpp b/tests/expected/matlab/namespaces_wrapper.cpp index 67bbb00c9..aba5c49ea 100644 --- a/tests/expected/matlab/namespaces_wrapper.cpp +++ b/tests/expected/matlab/namespaces_wrapper.cpp @@ -55,6 +55,8 @@ typedef std::set*> Collector_MyTemplatePoint static Collector_MyTemplatePoint2 collector_MyTemplatePoint2; typedef std::set*> Collector_MyTemplateMatrix; static Collector_MyTemplateMatrix collector_MyTemplateMatrix; +typedef std::set*> Collector_ForwardKinematicsFactor; +static Collector_ForwardKinematicsFactor collector_ForwardKinematicsFactor; typedef std::set*> Collector_ns1ClassA; static Collector_ns1ClassA collector_ns1ClassA; typedef std::set*> Collector_ns1ClassB; @@ -158,6 +160,12 @@ void _deleteAllObjects() collector_MyTemplateMatrix.erase(iter++); anyDeleted = true; } } + { for(Collector_ForwardKinematicsFactor::iterator iter = collector_ForwardKinematicsFactor.begin(); + iter != collector_ForwardKinematicsFactor.end(); ) { + delete *iter; + collector_ForwardKinematicsFactor.erase(iter++); + anyDeleted = true; + } } { for(Collector_ns1ClassA::iterator iter = collector_ns1ClassA.begin(); iter != collector_ns1ClassA.end(); ) { delete *iter; @@ -209,6 +217,7 @@ void _namespaces_RTTIRegister() { types.insert(std::make_pair(typeid(MyBase).name(), "MyBase")); types.insert(std::make_pair(typeid(MyTemplatePoint2).name(), "MyTemplatePoint2")); types.insert(std::make_pair(typeid(MyTemplateMatrix).name(), "MyTemplateMatrix")); + types.insert(std::make_pair(typeid(ForwardKinematicsFactor).name(), "ForwardKinematicsFactor")); mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); if(!registry) diff --git a/tests/expected/matlab/special_cases_wrapper.cpp b/tests/expected/matlab/special_cases_wrapper.cpp index b0ee1bcf8..d79a41ace 100644 --- a/tests/expected/matlab/special_cases_wrapper.cpp +++ b/tests/expected/matlab/special_cases_wrapper.cpp @@ -58,6 +58,8 @@ typedef std::set*> Collector_MyTemplatePoint static Collector_MyTemplatePoint2 collector_MyTemplatePoint2; typedef std::set*> Collector_MyTemplateMatrix; static Collector_MyTemplateMatrix collector_MyTemplateMatrix; +typedef std::set*> Collector_ForwardKinematicsFactor; +static Collector_ForwardKinematicsFactor collector_ForwardKinematicsFactor; typedef std::set*> Collector_ns1ClassA; static Collector_ns1ClassA collector_ns1ClassA; typedef std::set*> Collector_ns1ClassB; @@ -169,6 +171,12 @@ void _deleteAllObjects() collector_MyTemplateMatrix.erase(iter++); anyDeleted = true; } } + { for(Collector_ForwardKinematicsFactor::iterator iter = collector_ForwardKinematicsFactor.begin(); + iter != collector_ForwardKinematicsFactor.end(); ) { + delete *iter; + collector_ForwardKinematicsFactor.erase(iter++); + anyDeleted = true; + } } { for(Collector_ns1ClassA::iterator iter = collector_ns1ClassA.begin(); iter != collector_ns1ClassA.end(); ) { delete *iter; @@ -244,6 +252,7 @@ void _special_cases_RTTIRegister() { types.insert(std::make_pair(typeid(MyBase).name(), "MyBase")); types.insert(std::make_pair(typeid(MyTemplatePoint2).name(), "MyTemplatePoint2")); types.insert(std::make_pair(typeid(MyTemplateMatrix).name(), "MyTemplateMatrix")); + types.insert(std::make_pair(typeid(ForwardKinematicsFactor).name(), "ForwardKinematicsFactor")); mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); if(!registry) diff --git a/tests/expected/python/class_pybind.cpp b/tests/expected/python/class_pybind.cpp index 68f7a42e4..43705778b 100644 --- a/tests/expected/python/class_pybind.cpp +++ b/tests/expected/python/class_pybind.cpp @@ -55,7 +55,7 @@ PYBIND11_MODULE(class_py, m_) { .def("create_ptrs",[](Test* self){return self->create_ptrs();}) .def("create_MixedPtrs",[](Test* self){return self->create_MixedPtrs();}) .def("return_ptrs",[](Test* self, std::shared_ptr p1, std::shared_ptr p2){return self->return_ptrs(p1, p2);}, py::arg("p1"), py::arg("p2")) - .def("print_",[](Test* self){ self->print();}) + .def("print_",[](Test* self){ py::scoped_ostream_redirect output; self->print();}) .def("__repr__", [](const Test &a) { gtsam::RedirectCout redirect; diff --git a/tests/expected/python/inheritance_pybind.cpp b/tests/expected/python/inheritance_pybind.cpp index 6f34d39b6..d6cd77ca0 100644 --- a/tests/expected/python/inheritance_pybind.cpp +++ b/tests/expected/python/inheritance_pybind.cpp @@ -54,6 +54,8 @@ PYBIND11_MODULE(inheritance_py, m_) { .def("return_ptrs",[](MyTemplate* self, const std::shared_ptr p1, const std::shared_ptr p2){return self->return_ptrs(p1, p2);}, py::arg("p1"), py::arg("p2")) .def_static("Level",[](const gtsam::Matrix& K){return MyTemplate::Level(K);}, py::arg("K")); + py::class_, std::shared_ptr>(m_, "ForwardKinematicsFactor"); + #include "python/specializations.h" diff --git a/tests/fixtures/inheritance.i b/tests/fixtures/inheritance.i index e104c5b99..ddf9745df 100644 --- a/tests/fixtures/inheritance.i +++ b/tests/fixtures/inheritance.i @@ -22,3 +22,6 @@ virtual class MyTemplate : MyBase { static This Level(const T& K); }; + + +virtual class ForwardKinematicsFactor : gtsam::BetweenFactor {}; diff --git a/tests/test_interface_parser.py b/tests/test_interface_parser.py index 23f931fdd..d3c2ad52a 100644 --- a/tests/test_interface_parser.py +++ b/tests/test_interface_parser.py @@ -388,6 +388,15 @@ class TestInterfaceParser(unittest.TestCase): ret.parent_class.namespaces) self.assertTrue(ret.is_virtual) + ret = Class.rule.parseString( + "class ForwardKinematicsFactor : gtsam::BetweenFactor {};" + )[0] + self.assertEqual("ForwardKinematicsFactor", ret.name) + self.assertEqual("BetweenFactor", ret.parent_class.name) + self.assertEqual(["gtsam"], ret.parent_class.namespaces) + self.assertEqual("Pose3", ret.parent_class.instantiations[0].name) + self.assertEqual(["gtsam"], ret.parent_class.instantiations[0].namespaces) + def test_include(self): """Test for include statements.""" include = Include.rule.parseString( From 2257a37184473662c7f7ef9cb3add3f2fa637845 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Mon, 12 Apr 2021 21:50:23 -0400 Subject: [PATCH 08/14] include pybind::iostream to the python wrapper cpp template --- python/gtsam/gtsam.tpl | 1 + python/gtsam_unstable/gtsam_unstable.tpl | 1 + 2 files changed, 2 insertions(+) diff --git a/python/gtsam/gtsam.tpl b/python/gtsam/gtsam.tpl index 60b3d1fd0..26c220a8f 100644 --- a/python/gtsam/gtsam.tpl +++ b/python/gtsam/gtsam.tpl @@ -13,6 +13,7 @@ #include #include #include +#include #include "gtsam/config.h" #include "gtsam/base/serialization.h" #include "gtsam/nonlinear/utilities.h" // for RedirectCout. diff --git a/python/gtsam_unstable/gtsam_unstable.tpl b/python/gtsam_unstable/gtsam_unstable.tpl index 111e46d5e..356f37c42 100644 --- a/python/gtsam_unstable/gtsam_unstable.tpl +++ b/python/gtsam_unstable/gtsam_unstable.tpl @@ -13,6 +13,7 @@ #include #include #include +#include #include "gtsam/base/serialization.h" #include "gtsam/nonlinear/utilities.h" // for RedirectCout. From 24755c1845575ac5df79e3ac336356b02911a2fb Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Mon, 12 Apr 2021 22:17:37 -0400 Subject: [PATCH 09/14] documentation about wrap update instructions --- matlab/README.md | 2 ++ python/README.md | 2 ++ 2 files changed, 4 insertions(+) diff --git a/matlab/README.md b/matlab/README.md index 39053364d..25628b633 100644 --- a/matlab/README.md +++ b/matlab/README.md @@ -8,6 +8,8 @@ The interface to the toolbox is generated automatically by the wrap tool which d The tool generates matlab proxy objects together with all the native functions for wrapping and unwrapping scalar and non scalar types and objects. The interface generated by the wrap tool also redirects the standard output stream (cout) to matlab's console. +For instructions on updating the version of the [wrap library](https://github.com/borglab/wrap) included in GTSAM to the latest version, please refer to the [wrap README](https://github.com/borglab/wrap/blob/master/README.md#git-subtree-and-contributing) + ## Ubuntu If you have a newer Ubuntu system (later than 10.04), you must make a small modification to your MATLAB installation, due to MATLAB being distributed with an old version of the C++ standard library. Delete or rename all files starting with `libstdc++` in your MATLAB installation directory, in paths: diff --git a/python/README.md b/python/README.md index 6e2a30d2e..c485d12bd 100644 --- a/python/README.md +++ b/python/README.md @@ -4,6 +4,8 @@ This is the Python wrapper around the GTSAM C++ library. We use our custom [wrap library](https://github.com/borglab/wrap) to generate the bindings to the underlying C++ code. +For instructions on updating the version of the [wrap library](https://github.com/borglab/wrap) included in GTSAM to the latest version, please refer to the [wrap README](https://github.com/borglab/wrap/blob/master/README.md#git-subtree-and-contributing) + ## Requirements - If you want to build the GTSAM python library for a specific python version (eg 3.6), From db373dfa5234a4ff0d85995ed48d3ba14554357b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 16 Apr 2021 21:07:09 -0400 Subject: [PATCH 10/14] Squashed 'wrap/' changes from bae34fac8..b80bc63cf b80bc63cf Merge pull request #90 from borglab/fix/tpl_dependency 015b12da5 Merge pull request #86 from borglab/feature/optionalargs 362851980 address review comments e461ca50e Merge pull request #89 from borglab/fix/template_iostream 2d413db57 add pybind cpp generation dependency on tpl file 79881c25e include pybind11 iostream for ostream_redirect in example tpl 5e8323c25 fix test fixture 95495726a Merge branch 'master' into feature/optionalargs 5af826840 clean up the _py_args_names method to reduce copy-pasta 844ff9229 add identifier parsing to _type c3adca7a4 remove extra spaces from Type repr 350b531d7 slight test improvement fd4f37578 cleaner default argument parsing 6013deacb overpowered default argument parsing rule dbcda0ea2 fix unit tests for __repr__ ref vs ptr 1c23c42e4 fix pointer vs const ref in __repr__ 9b40350f1 update matlab tests df7e9023c handle __repr__ with default arguments 092ef489b update pybind_wrapper for default arguments 3a2d7aa8a unit test default argument pybind 61a2b114e implement default argument parser c2b92ffec unit test for parsing default arguments git-subtree-dir: wrap git-subtree-split: b80bc63cf466f9751e8059c0abb4a4d73b23efbe --- cmake/PybindWrap.cmake | 1 + gtwrap/interface_parser/function.py | 24 +++++++-- gtwrap/interface_parser/tokens.py | 16 +++++- gtwrap/interface_parser/type.py | 9 ++-- gtwrap/pybind_wrapper.py | 49 ++++++++++--------- gtwrap/template_instantiator.py | 4 +- templates/pybind_wrapper.tpl.example | 1 + tests/expected/matlab/MyFactorPosePoint2.m | 13 +++++ tests/expected/matlab/TemplatedFunctionRot3.m | 2 +- tests/expected/matlab/class_wrapper.cpp | 12 +++++ tests/expected/matlab/functions_wrapper.cpp | 31 +++++++++++- tests/expected/python/class_pybind.cpp | 13 +++-- tests/expected/python/functions_pybind.cpp | 3 ++ tests/fixtures/class.i | 2 + tests/fixtures/functions.i | 5 ++ tests/test_interface_parser.py | 28 ++++++++++- 16 files changed, 172 insertions(+), 41 deletions(-) diff --git a/cmake/PybindWrap.cmake b/cmake/PybindWrap.cmake index dc581be49..331dfff8c 100644 --- a/cmake/PybindWrap.cmake +++ b/cmake/PybindWrap.cmake @@ -72,6 +72,7 @@ function(pybind_wrap --template ${module_template} ${_WRAP_BOOST_ARG} + DEPENDS ${interface_header} ${module_template} VERBATIM) add_custom_target(pybind_wrap_${module_name} ALL DEPENDS ${generated_cpp}) diff --git a/gtwrap/interface_parser/function.py b/gtwrap/interface_parser/function.py index 526d5e055..64c7b176b 100644 --- a/gtwrap/interface_parser/function.py +++ b/gtwrap/interface_parser/function.py @@ -15,8 +15,8 @@ from typing import Iterable, List, Union from pyparsing import Optional, ParseResults, delimitedList from .template import Template -from .tokens import (COMMA, IDENT, LOPBRACK, LPAREN, PAIR, ROPBRACK, RPAREN, - SEMI_COLON) +from .tokens import (COMMA, DEFAULT_ARG, EQUAL, IDENT, LOPBRACK, LPAREN, PAIR, + ROPBRACK, RPAREN, SEMI_COLON) from .type import TemplatedType, Type @@ -29,15 +29,29 @@ class Argument: void sayHello(/*`s` is the method argument with type `const string&`*/ const string& s); ``` """ - rule = ((Type.rule ^ TemplatedType.rule)("ctype") + - IDENT("name")).setParseAction(lambda t: Argument(t.ctype, t.name)) + rule = ((Type.rule ^ TemplatedType.rule)("ctype") + IDENT("name") + \ + Optional(EQUAL + (DEFAULT_ARG ^ Type.rule ^ TemplatedType.rule) + \ + Optional(LPAREN + RPAREN) # Needed to parse the parens for default constructors + )("default") + ).setParseAction(lambda t: Argument(t.ctype, t.name, t.default)) - def __init__(self, ctype: Union[Type, TemplatedType], name: str): + def __init__(self, + ctype: Union[Type, TemplatedType], + name: str, + default: ParseResults = None): if isinstance(ctype, Iterable): self.ctype = ctype[0] else: self.ctype = ctype self.name = name + # If the length is 1, it's a regular type, + if len(default) == 1: + default = default[0] + # This means a tuple has been passed so we convert accordingly + elif len(default) > 1: + default = tuple(default.asList()) + self.default = default + self.parent: Union[ArgumentList, None] = None def __repr__(self) -> str: diff --git a/gtwrap/interface_parser/tokens.py b/gtwrap/interface_parser/tokens.py index 432c5407a..5d2bdeaf3 100644 --- a/gtwrap/interface_parser/tokens.py +++ b/gtwrap/interface_parser/tokens.py @@ -10,7 +10,9 @@ All the token definitions. Author: Duy Nguyen Ta, Fan Jiang, Matthew Sklar, Varun Agrawal, and Frank Dellaert """ -from pyparsing import Keyword, Literal, Suppress, Word, alphanums, alphas, nums, Or +from pyparsing import (Keyword, Literal, Or, QuotedString, Suppress, Word, + alphanums, alphas, delimitedList, nums, + pyparsing_common) # rule for identifiers (e.g. variable names) IDENT = Word(alphas + '_', alphanums + '_') ^ Word(nums) @@ -19,6 +21,18 @@ RAW_POINTER, SHARED_POINTER, REF = map(Literal, "@*&") LPAREN, RPAREN, LBRACE, RBRACE, COLON, SEMI_COLON = map(Suppress, "(){}:;") LOPBRACK, ROPBRACK, COMMA, EQUAL = map(Suppress, "<>,=") + +# Encapsulating type for numbers, and single and double quoted strings. +# The pyparsing_common utilities ensure correct coversion to the corresponding type. +# E.g. pyparsing_common.number will convert 3.1415 to a float type. +NUMBER_OR_STRING = (pyparsing_common.number ^ QuotedString('"') ^ QuotedString("'")) + +# A python tuple, e.g. (1, 9, "random", 3.1415) +TUPLE = (LPAREN + delimitedList(NUMBER_OR_STRING) + RPAREN) + +# Default argument passed to functions/methods. +DEFAULT_ARG = (NUMBER_OR_STRING ^ pyparsing_common.identifier ^ TUPLE) + CONST, VIRTUAL, CLASS, STATIC, PAIR, TEMPLATE, TYPEDEF, INCLUDE = map( Keyword, [ diff --git a/gtwrap/interface_parser/type.py b/gtwrap/interface_parser/type.py index e4b80a224..b9f2bd8f7 100644 --- a/gtwrap/interface_parser/type.py +++ b/gtwrap/interface_parser/type.py @@ -203,9 +203,12 @@ class Type: raise ValueError("Parse result is not a Type") def __repr__(self) -> str: - return "{self.is_const} {self.typename} " \ - "{self.is_shared_ptr}{self.is_ptr}{self.is_ref}".format( - self=self) + is_ptr_or_ref = "{0}{1}{2}".format(self.is_shared_ptr, self.is_ptr, + self.is_ref) + return "{is_const}{self.typename}{is_ptr_or_ref}".format( + self=self, + is_const="const " if self.is_const else "", + is_ptr_or_ref=" " + is_ptr_or_ref if is_ptr_or_ref else "") def to_cpp(self, use_boost: bool) -> str: """ diff --git a/gtwrap/pybind_wrapper.py b/gtwrap/pybind_wrapper.py index 1e0d412a0..801e691c6 100755 --- a/gtwrap/pybind_wrapper.py +++ b/gtwrap/pybind_wrapper.py @@ -45,7 +45,14 @@ class PybindWrapper: """Set the argument names in Pybind11 format.""" names = args_list.args_names() if names: - py_args = ['py::arg("{}")'.format(name) for name in names] + py_args = [] + for arg in args_list.args_list: + if arg.default and isinstance(arg.default, str): + arg.default = "\"{arg.default}\"".format(arg=arg) + argument = 'py::arg("{name}"){default}'.format( + name=arg.name, + default=' = {0}'.format(arg.default) if arg.default else '') + py_args.append(argument) return ", " + ", ".join(py_args) else: return '' @@ -124,35 +131,29 @@ class PybindWrapper: suffix=suffix, )) + # Create __repr__ override + # We allow all arguments to .print() and let the compiler handle type mismatches. if method.name == 'print': # Redirect stdout - see pybind docs for why this is a good idea: # https://pybind11.readthedocs.io/en/stable/advanced/pycpp/utilities.html#capturing-standard-output-from-ostream - ret = ret.replace('self->', 'py::scoped_ostream_redirect output; self->') + ret = ret.replace('self->print', 'py::scoped_ostream_redirect output; self->print') - # __repr__() uses print's implementation: - type_list = method.args.to_cpp(self.use_boost) - if len(type_list) > 0 and type_list[0].strip() == 'string': - ret += '''{prefix}.def("__repr__", - [](const {cpp_class} &a) {{ + # Make __repr__() call print() internally + ret += '''{prefix}.def("__repr__", + [](const {cpp_class}& self{opt_comma}{args_signature_with_names}){{ gtsam::RedirectCout redirect; - a.print(""); + self.{method_name}({method_args}); return redirect.str(); - }}){suffix}'''.format( - prefix=prefix, - cpp_class=cpp_class, - suffix=suffix, - ) - else: - ret += '''{prefix}.def("__repr__", - [](const {cpp_class} &a) {{ - gtsam::RedirectCout redirect; - a.print(); - return redirect.str(); - }}){suffix}'''.format( - prefix=prefix, - cpp_class=cpp_class, - suffix=suffix, - ) + }}{py_args_names}){suffix}'''.format( + prefix=prefix, + cpp_class=cpp_class, + opt_comma=', ' if args_names else '', + args_signature_with_names=args_signature_with_names, + method_name=method.name, + method_args=", ".join(args_names) if args_names else '', + py_args_names=py_args_names, + suffix=suffix) + return ret def wrap_methods(self, methods, cpp_class, prefix='\n' + ' ' * 8, suffix=''): diff --git a/gtwrap/template_instantiator.py b/gtwrap/template_instantiator.py index f6c396a99..bddaa07a8 100644 --- a/gtwrap/template_instantiator.py +++ b/gtwrap/template_instantiator.py @@ -95,8 +95,10 @@ def instantiate_args_list(args_list, template_typenames, instantiations, for arg in args_list: new_type = instantiate_type(arg.ctype, template_typenames, instantiations, cpp_typename) + default = [arg.default] if isinstance(arg, parser.Argument) else '' instantiated_args.append(parser.Argument(name=arg.name, - ctype=new_type)) + ctype=new_type, + default=default)) return instantiated_args diff --git a/templates/pybind_wrapper.tpl.example b/templates/pybind_wrapper.tpl.example index 399c690ac..8c38ad21c 100644 --- a/templates/pybind_wrapper.tpl.example +++ b/templates/pybind_wrapper.tpl.example @@ -4,6 +4,7 @@ #include #include #include +#include #include "gtsam/base/serialization.h" #include "gtsam/nonlinear/utilities.h" // for RedirectCout. diff --git a/tests/expected/matlab/MyFactorPosePoint2.m b/tests/expected/matlab/MyFactorPosePoint2.m index 290e41d4e..ea2e335c7 100644 --- a/tests/expected/matlab/MyFactorPosePoint2.m +++ b/tests/expected/matlab/MyFactorPosePoint2.m @@ -4,6 +4,9 @@ %-------Constructors------- %MyFactorPosePoint2(size_t key1, size_t key2, double measured, Base noiseModel) % +%-------Methods------- +%print(string s, KeyFormatter keyFormatter) : returns void +% classdef MyFactorPosePoint2 < handle properties ptr_MyFactorPosePoint2 = 0 @@ -29,6 +32,16 @@ classdef MyFactorPosePoint2 < handle %DISPLAY Calls print on the object function disp(obj), obj.display; end %DISP Calls print on the object + function varargout = print(this, varargin) + % PRINT usage: print(string s, KeyFormatter keyFormatter) : returns void + % Doxygen can be found at https://gtsam.org/doxygen/ + if length(varargin) == 2 && isa(varargin{1},'char') && isa(varargin{2},'gtsam.KeyFormatter') + class_wrapper(55, this, varargin{:}); + return + end + error('Arguments do not match any overload of function MyFactorPosePoint2.print'); + end + end methods(Static = true) diff --git a/tests/expected/matlab/TemplatedFunctionRot3.m b/tests/expected/matlab/TemplatedFunctionRot3.m index 132db92da..5b90c2473 100644 --- a/tests/expected/matlab/TemplatedFunctionRot3.m +++ b/tests/expected/matlab/TemplatedFunctionRot3.m @@ -1,6 +1,6 @@ function varargout = TemplatedFunctionRot3(varargin) if length(varargin) == 1 && isa(varargin{1},'gtsam.Rot3') - functions_wrapper(8, varargin{:}); + functions_wrapper(11, varargin{:}); else error('Arguments do not match any overload of function TemplatedFunctionRot3'); end diff --git a/tests/expected/matlab/class_wrapper.cpp b/tests/expected/matlab/class_wrapper.cpp index 11eda2d96..3fc2e5daf 100644 --- a/tests/expected/matlab/class_wrapper.cpp +++ b/tests/expected/matlab/class_wrapper.cpp @@ -661,6 +661,15 @@ void MyFactorPosePoint2_deconstructor_54(int nargout, mxArray *out[], int nargin } } +void MyFactorPosePoint2_print_55(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("print",nargout,nargin-1,2); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyFactorPosePoint2"); + string& s = *unwrap_shared_ptr< string >(in[1], "ptr_string"); + gtsam::KeyFormatter& keyFormatter = *unwrap_shared_ptr< gtsam::KeyFormatter >(in[2], "ptr_gtsamKeyFormatter"); + obj->print(s,keyFormatter); +} + void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { @@ -838,6 +847,9 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) case 54: MyFactorPosePoint2_deconstructor_54(nargout, out, nargin-1, in+1); break; + case 55: + MyFactorPosePoint2_print_55(nargout, out, nargin-1, in+1); + break; } } catch(const std::exception& e) { mexErrMsgTxt(("Exception from gtsam:\n" + std::string(e.what()) + "\n").c_str()); diff --git a/tests/expected/matlab/functions_wrapper.cpp b/tests/expected/matlab/functions_wrapper.cpp index c17c98ead..b8341b4ba 100644 --- a/tests/expected/matlab/functions_wrapper.cpp +++ b/tests/expected/matlab/functions_wrapper.cpp @@ -196,7 +196,25 @@ void MultiTemplatedFunctionDoubleSize_tDouble_7(int nargout, mxArray *out[], int size_t y = unwrap< size_t >(in[1]); out[0] = wrap< double >(MultiTemplatedFunctionDoubleSize_tDouble(x,y)); } -void TemplatedFunctionRot3_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void DefaultFuncInt_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("DefaultFuncInt",nargout,nargin,1); + int a = unwrap< int >(in[0]); + DefaultFuncInt(a); +} +void DefaultFuncString_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("DefaultFuncString",nargout,nargin,1); + string& s = *unwrap_shared_ptr< string >(in[0], "ptr_string"); + DefaultFuncString(s); +} +void DefaultFuncObj_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("DefaultFuncObj",nargout,nargin,1); + gtsam::KeyFormatter& keyFormatter = *unwrap_shared_ptr< gtsam::KeyFormatter >(in[0], "ptr_gtsamKeyFormatter"); + DefaultFuncObj(keyFormatter); +} +void TemplatedFunctionRot3_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("TemplatedFunctionRot3",nargout,nargin,1); gtsam::Rot3& t = *unwrap_shared_ptr< gtsam::Rot3 >(in[0], "ptr_gtsamRot3"); @@ -239,7 +257,16 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) MultiTemplatedFunctionDoubleSize_tDouble_7(nargout, out, nargin-1, in+1); break; case 8: - TemplatedFunctionRot3_8(nargout, out, nargin-1, in+1); + DefaultFuncInt_8(nargout, out, nargin-1, in+1); + break; + case 9: + DefaultFuncString_9(nargout, out, nargin-1, in+1); + break; + case 10: + DefaultFuncObj_10(nargout, out, nargin-1, in+1); + break; + case 11: + TemplatedFunctionRot3_11(nargout, out, nargin-1, in+1); break; } } catch(const std::exception& e) { diff --git a/tests/expected/python/class_pybind.cpp b/tests/expected/python/class_pybind.cpp index 43705778b..961daeffe 100644 --- a/tests/expected/python/class_pybind.cpp +++ b/tests/expected/python/class_pybind.cpp @@ -57,9 +57,9 @@ PYBIND11_MODULE(class_py, m_) { .def("return_ptrs",[](Test* self, std::shared_ptr p1, std::shared_ptr p2){return self->return_ptrs(p1, p2);}, py::arg("p1"), py::arg("p2")) .def("print_",[](Test* self){ py::scoped_ostream_redirect output; self->print();}) .def("__repr__", - [](const Test &a) { + [](const Test& self){ gtsam::RedirectCout redirect; - a.print(); + self.print(); return redirect.str(); }) .def("set_container",[](Test* self, std::vector container){ self->set_container(container);}, py::arg("container")) @@ -83,7 +83,14 @@ PYBIND11_MODULE(class_py, m_) { py::class_, std::shared_ptr>>(m_, "MultipleTemplatesIntFloat"); py::class_, std::shared_ptr>>(m_, "MyFactorPosePoint2") - .def(py::init>(), py::arg("key1"), py::arg("key2"), py::arg("measured"), py::arg("noiseModel")); + .def(py::init>(), py::arg("key1"), py::arg("key2"), py::arg("measured"), py::arg("noiseModel")) + .def("print_",[](MyFactor* self, const string& s, const gtsam::KeyFormatter& keyFormatter){ py::scoped_ostream_redirect output; self->print(s, keyFormatter);}, py::arg("s") = "factor: ", py::arg("keyFormatter") = gtsam::DefaultKeyFormatter) + .def("__repr__", + [](const MyFactor& self, const string& s, const gtsam::KeyFormatter& keyFormatter){ + gtsam::RedirectCout redirect; + self.print(s, keyFormatter); + return redirect.str(); + }, py::arg("s") = "factor: ", py::arg("keyFormatter") = gtsam::DefaultKeyFormatter); #include "python/specializations.h" diff --git a/tests/expected/python/functions_pybind.cpp b/tests/expected/python/functions_pybind.cpp index a657bee67..2513bcf56 100644 --- a/tests/expected/python/functions_pybind.cpp +++ b/tests/expected/python/functions_pybind.cpp @@ -30,6 +30,9 @@ PYBIND11_MODULE(functions_py, m_) { m_.def("overloadedGlobalFunction",[](int a, double b){return ::overloadedGlobalFunction(a, b);}, py::arg("a"), py::arg("b")); m_.def("MultiTemplatedFunctionStringSize_tDouble",[](const T& x, size_t y){return ::MultiTemplatedFunction(x, y);}, py::arg("x"), py::arg("y")); m_.def("MultiTemplatedFunctionDoubleSize_tDouble",[](const T& x, size_t y){return ::MultiTemplatedFunction(x, y);}, py::arg("x"), py::arg("y")); + m_.def("DefaultFuncInt",[](int a){ ::DefaultFuncInt(a);}, py::arg("a") = 123); + m_.def("DefaultFuncString",[](const string& s){ ::DefaultFuncString(s);}, py::arg("s") = "hello"); + m_.def("DefaultFuncObj",[](const gtsam::KeyFormatter& keyFormatter){ ::DefaultFuncObj(keyFormatter);}, py::arg("keyFormatter") = gtsam::DefaultKeyFormatter); m_.def("TemplatedFunctionRot3",[](const gtsam::Rot3& t){ ::TemplatedFunction(t);}, py::arg("t")); #include "python/specializations.h" diff --git a/tests/fixtures/class.i b/tests/fixtures/class.i index f4683a032..f49725ffa 100644 --- a/tests/fixtures/class.i +++ b/tests/fixtures/class.i @@ -79,6 +79,8 @@ virtual class ns::OtherClass; template class MyFactor { MyFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel); + void print(const string &s = "factor: ", + const gtsam::KeyFormatter &keyFormatter = gtsam::DefaultKeyFormatter); }; // and a typedef specializing it diff --git a/tests/fixtures/functions.i b/tests/fixtures/functions.i index d983ac97a..5e774a05a 100644 --- a/tests/fixtures/functions.i +++ b/tests/fixtures/functions.i @@ -26,3 +26,8 @@ template void TemplatedFunction(const T& t); typedef TemplatedFunction TemplatedFunctionRot3; + +// Check default arguments +void DefaultFuncInt(int a = 123); +void DefaultFuncString(const string& s = "hello"); +void DefaultFuncObj(const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter); diff --git a/tests/test_interface_parser.py b/tests/test_interface_parser.py index d3c2ad52a..1b9d5e711 100644 --- a/tests/test_interface_parser.py +++ b/tests/test_interface_parser.py @@ -179,6 +179,33 @@ class TestInterfaceParser(unittest.TestCase): self.assertEqual("vector>", args_list[1].ctype.to_cpp(True)) + def test_default_arguments(self): + """Tests any expression that is a valid default argument""" + args = ArgumentList.rule.parseString( + "string s=\"hello\", int a=3, " + "int b, double pi = 3.1415, " + "gtsam::KeyFormatter kf = gtsam::DefaultKeyFormatter, " + "std::vector p = std::vector(), " + "std::vector l = (1, 2, 'name', \"random\", 3.1415)" + )[0].args_list + + # Test for basic types + self.assertEqual(args[0].default, "hello") + self.assertEqual(args[1].default, 3) + # '' is falsy so we can check against it + self.assertEqual(args[2].default, '') + self.assertFalse(args[2].default) + + self.assertEqual(args[3].default, 3.1415) + + # Test non-basic type + self.assertEqual(repr(args[4].default.typename), 'gtsam::DefaultKeyFormatter') + # Test templated type + self.assertEqual(repr(args[5].default.typename), 'std::vector') + # Test for allowing list as default argument + print(args) + self.assertEqual(args[6].default, (1, 2, 'name', "random", 3.1415)) + def test_return_type(self): """Test ReturnType""" # Test void @@ -490,6 +517,5 @@ class TestInterfaceParser(unittest.TestCase): self.assertEqual(["two", "two_dummy", "two"], [x.name for x in module.content[0].content]) - if __name__ == '__main__': unittest.main() From a866df16da718a783898b8b061ecb54cb952ee61 Mon Sep 17 00:00:00 2001 From: Asa Hammond Date: Sat, 17 Apr 2021 07:42:41 -0700 Subject: [PATCH 11/14] Remove unused body_P_sensor param --- gtsam/navigation/CombinedImuFactor.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 0aeeabc22..0c7ba7547 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -212,8 +212,6 @@ public: * sensor) * @param measuredOmega Measured angular velocity (as given by the sensor) * @param deltaT Time interval between two consecutive IMU measurements - * @param body_P_sensor Optional sensor frame (pose of the IMU in the body - * frame) */ void integrateMeasurement(const Vector3& measuredAcc, const Vector3& measuredOmega, const double dt) override; From d8105ca73e8a9170cb58d6cd9a83bf695c9b4ba4 Mon Sep 17 00:00:00 2001 From: Asa Hammond Date: Sun, 18 Apr 2021 08:32:16 -0700 Subject: [PATCH 12/14] update docstring for dt param --- gtsam/navigation/CombinedImuFactor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 0c7ba7547..ed94750b7 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -211,7 +211,7 @@ public: * @param measuredAcc Measured acceleration (in body frame, as given by the * sensor) * @param measuredOmega Measured angular velocity (as given by the sensor) - * @param deltaT Time interval between two consecutive IMU measurements + * @param dt Time interval between two consecutive IMU measurements */ void integrateMeasurement(const Vector3& measuredAcc, const Vector3& measuredOmega, const double dt) override; From 3c184a60b07c792e25435c627d2bba31898182ac Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 18 Apr 2021 21:31:26 -0400 Subject: [PATCH 13/14] remove redundant stuff --- gtsam/geometry/tests/testRot3.cpp | 2 +- gtsam/gtsam.i | 3 --- 2 files changed, 1 insertion(+), 4 deletions(-) diff --git a/gtsam/geometry/tests/testRot3.cpp b/gtsam/geometry/tests/testRot3.cpp index 290945837..889f68580 100644 --- a/gtsam/geometry/tests/testRot3.cpp +++ b/gtsam/geometry/tests/testRot3.cpp @@ -825,7 +825,7 @@ TEST(Rot3, RQ_derivative) { const auto R = Rot3::RzRyRx(xyz).matrix(); const auto num = numericalDerivative11(RQ_proxy, R); Matrix39 calc; - auto dummy = RQ(R, calc).second; + RQ(R, calc).second; const auto err = vec_err.second; CHECK(assert_equal(num, calc, err)); diff --git a/gtsam/gtsam.i b/gtsam/gtsam.i index 27f2aa924..65918b669 100644 --- a/gtsam/gtsam.i +++ b/gtsam/gtsam.i @@ -2563,9 +2563,6 @@ class NonlinearISAM { //************************************************************************* // Nonlinear factor types //************************************************************************* -#include -#include - #include template Date: Mon, 19 Apr 2021 16:09:06 -0400 Subject: [PATCH 14/14] Squashed 'wrap/' changes from b80bc63cf..903694b77 903694b77 Merge pull request #92 from borglab/fix/global-variables abb74dd26 added support for default args, more tests, and docs cfa104257 Merge pull request #83 from borglab/feature/globalVariables fdd7b8cad fixes d4ceb63c6 add correct namespaces to global variable values 925c02c82 global variables works af62fdef7 unit test for global variable 3d3f3f3c9 add "Variable" to the global parsing rule ecfeb2025 rename "Property" to "Variable" and move into separate file git-subtree-dir: wrap git-subtree-split: 903694b777c4c25bd9cc82f8d3950b3bbc33d8f2 --- DOCS.md | 7 +++ gtwrap/interface_parser/classes.py | 35 ++------------ gtwrap/interface_parser/module.py | 2 + gtwrap/interface_parser/namespace.py | 2 + gtwrap/interface_parser/variable.py | 53 +++++++++++++++++++++ gtwrap/pybind_wrapper.py | 17 +++++++ tests/expected/python/namespaces_pybind.cpp | 2 + tests/fixtures/namespaces.i | 10 ++-- tests/test_interface_parser.py | 41 ++++++++++++---- 9 files changed, 125 insertions(+), 44 deletions(-) create mode 100644 gtwrap/interface_parser/variable.py diff --git a/DOCS.md b/DOCS.md index c0c4310fa..a5ca3fb0c 100644 --- a/DOCS.md +++ b/DOCS.md @@ -91,6 +91,13 @@ The python wrapper supports keyword arguments for functions/methods. Hence, the ```cpp template ``` +- Global variables + - Similar to global functions, the wrapper supports global variables as well. + - Currently we only support primitive types, such as `double`, `int`, `string`, etc. + - E.g. + ```cpp + const double kGravity = -9.81; + ``` - Using classes defined in other modules - If you are using a class `OtherClass` not wrapped in an interface file, add `class OtherClass;` as a forward declaration to avoid a dependency error. `OtherClass` should be in the same project. diff --git a/gtwrap/interface_parser/classes.py b/gtwrap/interface_parser/classes.py index 255c26137..9c83821b8 100644 --- a/gtwrap/interface_parser/classes.py +++ b/gtwrap/interface_parser/classes.py @@ -19,6 +19,7 @@ from .template import Template from .tokens import (CLASS, COLON, CONST, IDENT, LBRACE, LPAREN, RBRACE, RPAREN, SEMI_COLON, STATIC, VIRTUAL, OPERATOR) from .type import TemplatedType, Type, Typename +from .variable import Variable class Method: @@ -136,32 +137,6 @@ class Constructor: return "Constructor: {}".format(self.name) -class Property: - """ - Rule to parse the variable members of a class. - - E.g. - ``` - class Hello { - string name; // This is a property. - }; - ```` - """ - rule = ( - (Type.rule ^ TemplatedType.rule)("ctype") # - + IDENT("name") # - + SEMI_COLON # - ).setParseAction(lambda t: Property(t.ctype, t.name)) - - def __init__(self, ctype: Type, name: str, parent=''): - self.ctype = ctype[0] # ParseResult is a list - self.name = name - self.parent = parent - - def __repr__(self) -> str: - return '{} {}'.format(self.ctype.__repr__(), self.name) - - class Operator: """ Rule for parsing operator overloads. @@ -256,12 +231,12 @@ class Class: Rule for all the members within a class. """ rule = ZeroOrMore(Constructor.rule ^ StaticMethod.rule ^ Method.rule - ^ Property.rule ^ Operator.rule).setParseAction( + ^ Variable.rule ^ Operator.rule).setParseAction( lambda t: Class.Members(t.asList())) def __init__(self, members: List[Union[Constructor, Method, StaticMethod, - Property, Operator]]): + Variable, Operator]]): self.ctors = [] self.methods = [] self.static_methods = [] @@ -274,7 +249,7 @@ class Class: self.methods.append(m) elif isinstance(m, StaticMethod): self.static_methods.append(m) - elif isinstance(m, Property): + elif isinstance(m, Variable): self.properties.append(m) elif isinstance(m, Operator): self.operators.append(m) @@ -311,7 +286,7 @@ class Class: ctors: List[Constructor], methods: List[Method], static_methods: List[StaticMethod], - properties: List[Property], + properties: List[Variable], operators: List[Operator], parent: str = '', ): diff --git a/gtwrap/interface_parser/module.py b/gtwrap/interface_parser/module.py index 5619c1f56..2a564ec9b 100644 --- a/gtwrap/interface_parser/module.py +++ b/gtwrap/interface_parser/module.py @@ -23,6 +23,7 @@ from .declaration import ForwardDeclaration, Include from .function import GlobalFunction from .namespace import Namespace from .template import TypedefTemplateInstantiation +from .variable import Variable class Module: @@ -43,6 +44,7 @@ class Module: ^ Class.rule # ^ TypedefTemplateInstantiation.rule # ^ GlobalFunction.rule # + ^ Variable.rule # ^ Namespace.rule # ).setParseAction(lambda t: Namespace('', t.asList())) + stringEnd) diff --git a/gtwrap/interface_parser/namespace.py b/gtwrap/interface_parser/namespace.py index da505d5f9..502064a2f 100644 --- a/gtwrap/interface_parser/namespace.py +++ b/gtwrap/interface_parser/namespace.py @@ -22,6 +22,7 @@ from .function import GlobalFunction from .template import TypedefTemplateInstantiation from .tokens import IDENT, LBRACE, NAMESPACE, RBRACE from .type import Typename +from .variable import Variable def find_sub_namespace(namespace: "Namespace", @@ -67,6 +68,7 @@ class Namespace: ^ Class.rule # ^ TypedefTemplateInstantiation.rule # ^ GlobalFunction.rule # + ^ Variable.rule # ^ rule # )("content") # BR + RBRACE # diff --git a/gtwrap/interface_parser/variable.py b/gtwrap/interface_parser/variable.py new file mode 100644 index 000000000..80dd5030b --- /dev/null +++ b/gtwrap/interface_parser/variable.py @@ -0,0 +1,53 @@ +""" +GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Parser classes and rules for parsing C++ variables. + +Author: Varun Agrawal, Gerry Chen +""" + +from pyparsing import Optional, ParseResults + +from .tokens import DEFAULT_ARG, EQUAL, IDENT, SEMI_COLON, STATIC +from .type import TemplatedType, Type + + +class Variable: + """ + Rule to parse variables. + Variables are a combination of Type/TemplatedType and the variable identifier. + + E.g. + ``` + class Hello { + string name; // This is a property variable. + }; + + Vector3 kGravity; // This is a global variable. + ```` + """ + rule = ((Type.rule ^ TemplatedType.rule)("ctype") # + + IDENT("name") # + #TODO(Varun) Add support for non-basic types + + Optional(EQUAL + (DEFAULT_ARG))("default") # + + SEMI_COLON # + ).setParseAction(lambda t: Variable(t.ctype, t.name, t.default)) + + def __init__(self, + ctype: Type, + name: str, + default: ParseResults = None, + parent=''): + self.ctype = ctype[0] # ParseResult is a list + self.name = name + if default: + self.default = default[0] + + self.parent = parent + + def __repr__(self) -> str: + return '{} {}'.format(self.ctype.__repr__(), self.name) diff --git a/gtwrap/pybind_wrapper.py b/gtwrap/pybind_wrapper.py index 801e691c6..88bd05a49 100755 --- a/gtwrap/pybind_wrapper.py +++ b/gtwrap/pybind_wrapper.py @@ -186,6 +186,16 @@ class PybindWrapper: return res + def wrap_variable(self, module, module_var, variable, prefix='\n' + ' ' * 8): + """Wrap a variable that's not part of a class (i.e. global) + """ + return '{prefix}{module_var}.attr("{variable_name}") = {module}{variable_name};'.format( + prefix=prefix, + module=module, + module_var=module_var, + variable_name=variable.name + ) + def wrap_properties(self, properties, cpp_class, prefix='\n' + ' ' * 8): """Wrap all the properties in the `cpp_class`.""" res = "" @@ -341,6 +351,13 @@ class PybindWrapper: includes += includes_namespace elif isinstance(element, instantiator.InstantiatedClass): wrapped += self.wrap_instantiated_class(element) + elif isinstance(element, parser.Variable): + wrapped += self.wrap_variable( + module=self._add_namespaces('', namespaces), + module_var=module_var, + variable=element, + prefix='\n' + ' ' * 4 + ) # Global functions. all_funcs = [ diff --git a/tests/expected/python/namespaces_pybind.cpp b/tests/expected/python/namespaces_pybind.cpp index e0e21d93b..b09fe36eb 100644 --- a/tests/expected/python/namespaces_pybind.cpp +++ b/tests/expected/python/namespaces_pybind.cpp @@ -50,12 +50,14 @@ PYBIND11_MODULE(namespaces_py, m_) { py::class_>(m_ns2, "ClassC") .def(py::init<>()); + m_ns2.attr("aNs2Var") = ns2::aNs2Var; m_ns2.def("aGlobalFunction",[](){return ns2::aGlobalFunction();}); m_ns2.def("overloadedGlobalFunction",[](const ns1::ClassA& a){return ns2::overloadedGlobalFunction(a);}, py::arg("a")); m_ns2.def("overloadedGlobalFunction",[](const ns1::ClassA& a, double b){return ns2::overloadedGlobalFunction(a, b);}, py::arg("a"), py::arg("b")); py::class_>(m_, "ClassD") .def(py::init<>()); + m_.attr("aGlobalVar") = aGlobalVar; #include "python/specializations.h" diff --git a/tests/fixtures/namespaces.i b/tests/fixtures/namespaces.i index a9b23cad1..5c277801d 100644 --- a/tests/fixtures/namespaces.i +++ b/tests/fixtures/namespaces.i @@ -17,7 +17,7 @@ class ClassB { // check namespace handling Vector aGlobalFunction(); -} +} // namespace ns1 #include namespace ns2 { @@ -38,7 +38,7 @@ class ClassB { ClassB(); }; -} +} // namespace ns3 class ClassC { ClassC(); @@ -51,10 +51,12 @@ Vector aGlobalFunction(); ns1::ClassA overloadedGlobalFunction(const ns1::ClassA& a); ns1::ClassA overloadedGlobalFunction(const ns1::ClassA& a, double b); -} //\namespace ns2 +int aNs2Var; + +} // namespace ns2 class ClassD { ClassD(); }; - +int aGlobalVar; diff --git a/tests/test_interface_parser.py b/tests/test_interface_parser.py index 1b9d5e711..28b645201 100644 --- a/tests/test_interface_parser.py +++ b/tests/test_interface_parser.py @@ -18,12 +18,10 @@ import unittest sys.path.append(os.path.dirname(os.path.dirname(os.path.abspath(__file__)))) -from gtwrap.interface_parser import (ArgumentList, Class, Constructor, - ForwardDeclaration, GlobalFunction, - Include, Method, Module, Namespace, - Operator, ReturnType, StaticMethod, - TemplatedType, Type, - TypedefTemplateInstantiation, Typename) +from gtwrap.interface_parser import ( + ArgumentList, Class, Constructor, ForwardDeclaration, GlobalFunction, + Include, Method, Module, Namespace, Operator, ReturnType, StaticMethod, + TemplatedType, Type, TypedefTemplateInstantiation, Typename, Variable) class TestInterfaceParser(unittest.TestCase): @@ -199,7 +197,8 @@ class TestInterfaceParser(unittest.TestCase): self.assertEqual(args[3].default, 3.1415) # Test non-basic type - self.assertEqual(repr(args[4].default.typename), 'gtsam::DefaultKeyFormatter') + self.assertEqual(repr(args[4].default.typename), + 'gtsam::DefaultKeyFormatter') # Test templated type self.assertEqual(repr(args[5].default.typename), 'std::vector') # Test for allowing list as default argument @@ -422,7 +421,8 @@ class TestInterfaceParser(unittest.TestCase): self.assertEqual("BetweenFactor", ret.parent_class.name) self.assertEqual(["gtsam"], ret.parent_class.namespaces) self.assertEqual("Pose3", ret.parent_class.instantiations[0].name) - self.assertEqual(["gtsam"], ret.parent_class.instantiations[0].namespaces) + self.assertEqual(["gtsam"], + ret.parent_class.instantiations[0].namespaces) def test_include(self): """Test for include statements.""" @@ -449,6 +449,23 @@ class TestInterfaceParser(unittest.TestCase): self.assertEqual("Values", func.return_type.type1.typename.name) self.assertEqual(3, len(func.args)) + def test_global_variable(self): + """Test for global variable.""" + variable = Variable.rule.parseString("string kGravity;")[0] + self.assertEqual(variable.name, "kGravity") + self.assertEqual(variable.ctype.typename.name, "string") + + variable = Variable.rule.parseString("string kGravity = 9.81;")[0] + self.assertEqual(variable.name, "kGravity") + self.assertEqual(variable.ctype.typename.name, "string") + self.assertEqual(variable.default, 9.81) + + variable = Variable.rule.parseString("const string kGravity = 9.81;")[0] + self.assertEqual(variable.name, "kGravity") + self.assertEqual(variable.ctype.typename.name, "string") + self.assertTrue(variable.ctype.is_const) + self.assertEqual(variable.default, 9.81) + def test_namespace(self): """Test for namespace parsing.""" namespace = Namespace.rule.parseString(""" @@ -505,17 +522,21 @@ class TestInterfaceParser(unittest.TestCase): }; } + int oneVar; } class Global{ }; + int globalVar; """) # print("module: ", module) # print(dir(module.content[0].name)) - self.assertEqual(["one", "Global"], [x.name for x in module.content]) - self.assertEqual(["two", "two_dummy", "two"], + self.assertEqual(["one", "Global", "globalVar"], + [x.name for x in module.content]) + self.assertEqual(["two", "two_dummy", "two", "oneVar"], [x.name for x in module.content[0].content]) + if __name__ == '__main__': unittest.main()