From bc60a5a04b3704cd1b7c22c37fea1a58cdc1f269 Mon Sep 17 00:00:00 2001 From: Alexis Duburcq Date: Wed, 7 Feb 2024 20:28:37 +0100 Subject: [PATCH] [core] Revert to 'crba' to ensure positive definite inertia matrix. --- .gitignore | 1 + .../robot/pinocchio_overload_algorithms.h | 22 ++++++++++++++---- core/src/robot/model.cc | 7 ++---- .../unit_py/data/atlas_standing_6.png | Bin 0 -> 58868 bytes .../unit_py/data/atlas_standing_7.png | Bin 0 -> 60289 bytes .../unit_py/data/cassie_standing_7.png | Bin 0 -> 22425 bytes .../unit_py/data/digit_standing_6.png | Bin 0 -> 29512 bytes python/jiminy_pywrap/src/helpers.cc | 2 +- 8 files changed, 22 insertions(+), 10 deletions(-) create mode 100644 python/gym_jiminy/unit_py/data/atlas_standing_6.png create mode 100644 python/gym_jiminy/unit_py/data/atlas_standing_7.png create mode 100644 python/gym_jiminy/unit_py/data/cassie_standing_7.png create mode 100644 python/gym_jiminy/unit_py/data/digit_standing_6.png diff --git a/.gitignore b/.gitignore index 517d41a42..afdb50304 100644 --- a/.gitignore +++ b/.gitignore @@ -2,6 +2,7 @@ *egg-info* **/__pycache__ venv/ +.cache .vscode .DS_Store docs/html diff --git a/core/include/jiminy/core/robot/pinocchio_overload_algorithms.h b/core/include/jiminy/core/robot/pinocchio_overload_algorithms.h index 91d09a7fa..d11312178 100644 --- a/core/include/jiminy/core/robot/pinocchio_overload_algorithms.h +++ b/core/include/jiminy/core/robot/pinocchio_overload_algorithms.h @@ -24,9 +24,10 @@ #include "pinocchio/multibody/joint/fwd.hpp" // `pinocchio::JointModelBase`, `pinocchio::JointDataBase`, ... #include "pinocchio/algorithm/aba.hpp" // `pinocchio::aba` #include "pinocchio/algorithm/rnea.hpp" // `pinocchio::rnea` -#include "pinocchio/algorithm/crba.hpp" // `pinocchio::crbaMinimal` +#include "pinocchio/algorithm/crba.hpp" // `pinocchio::crba`, `pinocchio::crbaMinimal` #include "pinocchio/algorithm/energy.hpp" // `pinocchio::computeKineticEnergy` #include "pinocchio/algorithm/cholesky.hpp" // `pinocchio::cholesky::` +#include "pinocchio/algorithm/jacobian.hpp" // `pinocchio::computeJointJacobians` #include "jiminy/core/fwd.h" #include "jiminy/core/engine/engine_multi_robot.h" @@ -106,9 +107,22 @@ namespace jiminy::pinocchio_overload inline const typename pinocchio::DataTpl::MatrixXs & crba(const pinocchio::ModelTpl & model, pinocchio::DataTpl & data, - const Eigen::MatrixBase & q) + const Eigen::MatrixBase & q, + bool fastMath = false) { - pinocchio::crbaMinimal(model, data, q); + /* `pinocchio::crbaMinimal` is faster than `crba` as it also compute the joint jacobians as + a by-product without having to call `pinocchio::computeJointJacobians` manually. + However, it is numerical instable compared to the classical and thoroughly-tested + `pinocchio::crba`, so its use must be avoided in practice. */ + if (fastMath) + { + pinocchio::crbaMinimal(model, data, q); + } + else + { + pinocchio::crba(model, data, q); + pinocchio::computeJointJacobians(model, data); + } data.M.diagonal() += model.rotorInertia; return data.M; } @@ -494,7 +508,7 @@ namespace jiminy::pinocchio_overload // Make sure the decomposition of the mass matrix is valid if ((data.Dinv.array() < 0.0).any()) { - PRINT_ERROR("The inertia matrix is not strictly positive definite."); + PRINT_ERROR("The inertia matrix is not positive definite."); return hresult_t::ERROR_BAD_INPUT; } diff --git a/core/src/robot/model.cc b/core/src/robot/model.cc index 5a652ccc4..869eba79f 100644 --- a/core/src/robot/model.cc +++ b/core/src/robot/model.cc @@ -17,7 +17,6 @@ #include "pinocchio/algorithm/center-of-mass.hpp" // `pinocchio::centerOfMass` #include "pinocchio/algorithm/joint-configuration.hpp" // `pinocchio::neutral` #include "pinocchio/algorithm/kinematics.hpp" // `pinocchio::forwardKinematics` -#include "pinocchio/algorithm/jacobian.hpp" // `pinocchio::computeJointJacobians` #include "pinocchio/algorithm/geometry.hpp" // `pinocchio::updateGeometryPlacements` #include "pinocchio/algorithm/cholesky.hpp" // `pinocchio::cholesky::` @@ -1198,10 +1197,8 @@ namespace jiminy return; } - /* Compute inertia matrix, taking into account armature. - Note that `crbaMinimal` is faster than `crba` as it also compute the joint jacobians as - a by-product without having to call `computeJointJacobians` manually. */ - pinocchio_overload::crba(pinocchioModel_, pinocchioData_, q); + // Compute inertia matrix (taking into account rotor armatures) along with joint jacobians + pinocchio_overload::crba(pinocchioModel_, pinocchioData_, q, false); /* Computing forward kinematics without acceleration to get the drift. Note that it will alter the actual joints spatial accelerations, so it is necessary to diff --git a/python/gym_jiminy/unit_py/data/atlas_standing_6.png b/python/gym_jiminy/unit_py/data/atlas_standing_6.png new file mode 100644 index 0000000000000000000000000000000000000000..c2a8ef04ee54ecfec9964e2fc093aca8c0229dc6 GIT binary patch literal 58868 zcmeFZ`9GBHA2xnjV#?BlG%=QuBuPUm`!W&A8nVm2WXZnoCbEZ+J!B7AB4kSpP1dpR zvhQRkJg58f{r&~dug~?m`{k~txz6)_9`ECQ9LFg{Sy6`S62m13f~e$VrJh3&(a!lV z7%})iQWdh}5HwdSCnc%oma=-{>ZLd6yg;?#?NNQTD)UhQ=|vjSFj;NxOb^G`Wuh;v z@ur#VvGyas?qJbyIx(Ssf&BIi%BNZL0~H#ax# z$0GLo=f4%?_Gf*1db*Ty>*siLbF=aFKOwcj!NEAbpR}%*FJF!_eS2%289aEn(wHdt zfOypZ`+)z8HCWev?H7!5$SOL2s2~VM3c)dBz78w|ax5IvHZ?VMaB%QoNIA+h;(XmT zf@Imt44Z>=Y^z)NJMNozn(!s&&q5xfZ$+=IPwxB@KZGl zcpacyKeVnQj7KY}n%fq(=NziDv$M;~9h-xws&#o%6{8{|A|fO8SH}Npjx-)`G@NO_ z4h+V{%w9g7x(q=Jt;O?X!VF8=H&+dU&Q;|72I2bxmh8$s>&&JI6HicXrLt+3z{ zs*itdsMOfJGo{qVb8X~nqWpYczA6&eUX~)y(L8O(O}~A7BGPpOoA)za&~aXSqXtLQ zh_Ci^)4fzzR~JmpL_<2AlWfZs_mrF(Dd4g?MC|(z4$CWGh%THkw6eM? z1*?`jTy|jCx3{t?tY!DyTOCe#=`&2RAj*Ti20rh*U`+dLv0kl^kPrk7Tfd0;q|38k zo__LKm#1O4>W{#>YWk6yj7)Ix3fN>#ZteIBW)GOuLXN$_DoStl$grfQqw@F>J3d;i_6+be}BL9Gsep-V#tUmOt__ujRsQFs1~F2f3vq%mY4Ywe-D?NgVleU zO@nDGdXsxKmfzVJ@x)n*g*w<<>?Jq-Xtm=)l+RAqotgw@Jn1=@OnlJfuJk_M>o3&M z5U;i!uL1S_Hd6qN{_^gTBrLz+Y4bKFW3#%;TT#6~KR^G5Oe9jkZfa+VAndYgVQYK( z=UPLBkM~B)Bv`Twfs%TI!a_m=pS1{+lfFyG^QH3Vh&Dszh7+DB^>BVff?_3=fEueK z*SJmp?rTx>h{D-IyxZybQhD94J5ir=@nCTna)JDG&ti2aI5!ik!R zqRB-rqaMS+W``FPfTQ`0Bi0G^p2xY28xQK|%TT3)@CP$9GgfQ>D=6yL)>bOUhl@2n z{|>e`e9w--enZe`B@>Pa;(z#Xq_XZE6;A@5Ur$v-Bca2rq?LC|vj&uEDSLiN$;RsH zPsF2#4<9~yluNLz>ci#~ECn7;zF-9Cq8ShNb5_8XkfTt>P2h7>p%!>6 z?fQKp99gDR0BX_rBKbws8w?R-pcQYK6u`=gbxV7sK;Z8nXLd6fEY@2YELm_*`&Bn1 zu=8Nr?%>|p-+L%5IJ1*yr~Bo@pIKqTf|aMU7mw$YkvJ8)!`0z(3PBhQ1wqZ|Xj#xq zq6E*s>`q=`;c=Uc*bjSMU*9wQy$0(fvwXEO8&5AU-9cxZJsi_x@xFiyYv<(jenx;n zK{%2G_36!Q8Mkq`<%6T`F7foP1rqB=9vvn}vkz89_8`fe}s;NdN4JYOLQ)xq3tbLw;aB^zGx3qmI z5SgXUQ&IT#7w>~j2PCd?4ea{^s{!T5G7>A#_g0<7`@CkaZ0(I2R7Aol(aelYb8e@( z;wMXKqMoM*QD<(}*4)vup9o8!6Lgrxw$C2zt^ja({olhD4VRAQ$zC5SCBb~?FiZD2 zvc$rh(Je+>iTU|FP}#7xswypnW{BX~RQ`}7cjr~{4)31kU$<*sQQ0yX%5HOU8j(!G z5Bc~4cq4H$k0#uVm6W;))C*a$B3%Gy(-tV+1hC5iNKsc;p}Q%U`E@#g6&4_oeudP3 z;m`p64IF0S^>5AUE)dlCp*Wo$CZ-^p2%j=&`~v^sP#umw-HP%Z8yu8@0jy9e)ignH zBzI`XKM)a-xA|c`nwFHrM>!Lxp>L=aZ#pc&+C4aEt~F3w3@?>C(EoRMX-1 zQQP~JB&fcg9(|2#`coNSxG9X0AyUOZ4EHog+@fniOZpi?d)@-KJB5|f#hAicKwFvI z*jQN^t*}%DSdsnQyemzw+)RNhE>nmHM%;|HJ^G>0^em=tY)rn+eZhwevw7z-UHw+X z4O|on)VsD8;SWVi5jQsG6QwO&4?4Uinp<`savmEu^t74uXE1f?%lf;H}aq7r-*sGIJ~+f zNZl*}`4z7qao2dH&nUjCQ3f}IFRGxR5GC@rZEtN9hr^AI zjy|#-(-dXB_&eJ95{^iksE2dwmqu~BKj&57TlAza+iDv z{E~5kl-Nx|`YAug!o%aJ<=Q?31vJ4?>~xnD6crM4^1%=hX{dnztoG~BOHoCQ;q(Uf zF8+&+4qOU?VbSSbFQvxD2XgHMQt)%dZT`EO%;$)&7R?SyNO$%^QjTR(B_LCvl|K%q z{#sQP+&mo=6jZxjgRfj8A*c3Q(V6@;_xI7nH_!1JXWQNBjT~)S80sfdgDcMAjhB^q z?###Xz(B-|3E%M0(9dn%?B~&@i8BJ~>cK%l1>&Me>d{K?lifi;R7<%%aZIjoOipfY zy4T-F=j|46&)xJ*lUoS%6FcN6+6iB#8Sh;9a1xGvSG)qtkYxubF7p6%bZ$9qZEb{E@JihF^QOl*8fEqwj?&?$yRh|I8efl?{0aO?uBW|Ok6MMB~_65b< zD}@w=(`XcH+|!Uui^X}Hs_~w|s)@4S=M6nyEmYrZ{%0pF1JIhRYcfdkwZ$SOb{YWB z=He%U&`-&?O+Q_%i=O{LkVrhu&djl-Y_I76|znmAY*uTnv~JP~?csm`uu%gSj6}2cP(e+gy)$lI88~ty5+DK*90s z^yF+u>5LtQK_k2dYbTtGZDZiD>jf1gBqVW9O)EZ)b$2WCBv7-6vB7$y-w&n7UMDMi zYcD}eVsPaxuK`h@ECrtLovB!V9fPsR{rirKn<#lWDV#RoVwp7~1Wj+evW5WX2%28> zC4#P%U^7ew2dY~%FGo#IgDx3^^|+{<-Vz3(KC5v#+0a7ph$rAHDhz-vZf|d&o;H+L ziD@_CXE;Y8z<@I>M<(h#egDR$gDK(#SKN55D+!e5_9tYeq(LmXL(KlWgI%UbobM5d zunu@0*^Ic2J3mf8K096OmrFx)^F0vLG@maI7jNCpw22ptUwis=)Klky!YDx2-@hrb zlvs$kv$9Cb5z$t*`Z@NvI?;<_aM?*{yt{j_2HGD z9FW(jg9%Gc`D%O$j@H(zjs7HRlcOUep!x3(zPuM|RINJ!KL4K2R+ub%Z-4(T7%viY z+%3MnfAZ^ILgcDMmhUKP+pd#xkkhu5GH^!1CmQB`LREg|H4N7?~Q#8uB-Smz&)3jmx=u)_!7f$ zGqo;jf86VJdBl$vvp^%Lv?;NQUs*P)v|+j4epd4OB+N`nU_a%*QcYei5=E6UTlitK06F{^*-qt zq*gSN?M#d%dRtX2|5qfv!z@bVj1z;vg!7W18ezs>Jkc1~yg-_ES~W@pOWFDs-a9Zb zFg7+uAjEbp03;pL_PMsqdmH~ZPPm2{PjrsJ%VOf^>Q$HyTIB-(I%P6S|m$G9cd0>r*!{OPc{_w z@OJ>khJ;){+gX6}F)Ow_=r06G1bd<>De@{F!%%*3p~y7>O#&A#iY37`aljrZ0~`r> z1tldG5w~~DRPm+{6u>AtxQ=z}V>_>vn_ylf7e8nU`R~ckzs=wZrc_^g$S*!JMaVg{ za__VD*UzQP_7RsOGZYpBK=X zW+cTZ;W%du4Bx9JtXrD-m{1WNeMN;1G+r-b97S8H*&By;ZFv z)ruo!0>28KWn-s3l4(-%ECeo_dgF11vM-oR=(fAdRqxOknR`#wjcV(~c)g! zGZmPvz*GWW)aj+fv2@|B7X)Vwt#}fD2=i8P@56Rwi&3-?iB%H)r8kY$tVb!s&mKP} zVN&O!AchYU-0g%ke#I$zxq0Fj7xTIn!k%PpxrrbsC%$dh=)CqyHr0B0*h9f7{zUXP zi|;@C+m0A&viw_ftDKw|v)XKUW~f&&S+6}3&$pC{8(MTj)7h!=z<)Ri#o`x?dxX?? zF9ijFpsug1 z+*jDnPS9sSAOQD>lwymPH90LXW~bRY^vbbJtK!#>VQ2UfI6NjA=Q@(j6`E<8l*w5+ zVE+#$Noph|5U;Af`_qEC!(_1h$HCCIOs;5IcIGH@Vt?_IO)4ev6DK{rR92W+db-&t z7)>r-e?{Ah=7vaVX+l~k^>7FsKtFP9bSRs<9S#y+x`)_CO>QKxUw|6RC{diLa=C;= z;nxi|US4BmpMmc4Jl|<`s8o}CU}B=)l8__MvHcf+59pyUPaOZKWSzg^&pb6Qu>D8` z!ot!LNNl0F8E0o_Vb}HVOF79;vwIg87Y`2HWMpJ^!K@U@;b1=~ZMUt$6!JpN3A^j7SOkDSOR5dgfb3#qGyfqSWD^NKp@d_3q<= z&tQN6%Lq7ILBWLEOav?=nAyXkE6p2F)*v`6K(>5Yq>DTt<9YR4CY?v}`fwyJ$MQM` zjanGcSVFI3GB`txSmAWiE*x=Y5HkXyS?zEW@-rQ#y`?A{LkA;WUReP`4j?~b2ThlA z2umAY3&LS8uS8y5ayvWOf4O3_x%tfrFk>AZMyfEBoWFvo7}GqK^8rk$ajBoYC@27vZW(v;mvy_foSdBb`JATnM-pFlx|Giw zBoJvjR&Ue4QD?Ovezv;QEJOYJ<>Zx1*cT;BoeO_o9!wa=r+DqZnt#kv6HL7qCdKA2 zA)&4=2?sLSX2k1%GZ~MAEjn?Mk?fb8B`xtIc4ug}wF9~MIjUyJ&rd7a4K4gAw0PeE znJz1}eUr+_X;9CV2twktN{udHEP&8ZKe4c_QZl1g>(Vl_RpPT-*q?YOstTq*yIxw6 zu_jwkKt}A}+1Y8q&lPIq=vdA!2PT3=1@Hb%H3wPnBJ8u zl^;tEu}Zbj6&7G{nuI^n??nS4l8e=IHMMSOCGRQP9#ZM04>;>jv6`Sub{;;ht1AS9 zUT8~Z@e25GfDwu3NLF884|ZX6@}Tum{b2_=5s+Ei*cvP!FKliOg+B4|lFvu%ly_#& zkJqFECf$+zNJ(D)`_Xb?zFLr}V7zIWmO_k)*8CD*S?#?!2d%-~*jq|L&C}=j0ygWi z*ufNA8f{ckBLL7jiR|YY`n-iNiegNM(Uc5)fSkLD=$}u^F~utYijp7NB&DQ;w-`C~ z1yNw$QnzLq@Dpgfh0?`%QJPi)q{QSK5QI>c?$?JoXv)zWF%Db?h zFGf?J?!`)`upWOKc2`3@f!sHvC{xcG1{Kiv!9$f9K9& zCQukGVkxrhU@8QI?kP~DdFHQgeVac&wV$U1iobr{O=$R+%?i`g(*s95QGTGmA8b4* zOhDThf||Df4Gj$ymefBDw(MqM$7;q)Cm-a0XPXs>1k#%ZH$C75=vJ90{Hp?uybzwy z%W%aiwD*%bm{Lp~9Lg*LJYBwm@wfP812d{`U;umtu_WF>XKy#Rov(w6VCC07 zv)EYL0M;u3@Bl6AAv~47hp~%@Q>(A6`FE5 z98I}hLQ_g~b|eeCr+9=bjD2q0;^)NN z_6zsQ{&8|r62PoWZ+;vc2T#DoIrb55g=LR{@t&lLp7sC$9Ky<6`{s}I!^-t;iyjglzm7&cYl+@rZ=mSGT z0-~ZeTGXh4eAVW@^=Ly)6*?K2TQ7awyHZ_)0QX<+Pc5mNmogqDCs)$SX@CA$HmE=1 z(#g)#Y)|N{jH(n>ns?68OK2J}%dgn#= zk#|%T^*JlMV<9bw{i4RjB=x){&Ccz~`lTKMVtZtj$L=!FEz=g9^@8C+&4vmDGIH{+@J@NtXOzv7J;4|MHFhxK=l*UE6M_su zXL)Zryi(%J2u?9lT^-lj3eF6vWS*K+x>B17U%ctf*xhqSNGslbF78Cw)i%LYkUq@V zix~48ZC(HFnsig{5!}IH80jZ9=o~*sDhd6Jmdad`mRq$$>JYe)xcpFGGqZx{x37jB z?yi&s!r{c+6tEw<-d%GJ09kT#7XTg5UfrIyUjtT^v6dv0x2aa=!uEQ1ExP@-c*;)3lm%73Doc1)vsd(@zpw0Pe9Hf+#Db&Hu$&dC$ zPY+a~&E4IO8#e+gZC-GhF7FGA-Zvh7_*nLPeKgVPaxq!6QD-Ejl9CcHWwTLk;a7KS zjzHeqaiPQ3LNs#Sbl+KJ9V0K+9exay6qyh@2ONIjRDh@0r!`en3TA0-{fY4QiHrbsq^veW&kJ~gMVBBprDg_7kc&%#EYr7*bFc2t+%IaS= zxv43YZZ&q}d}K zW)jeZhCt7h7F<|<^Tp9+Q*EQB{=PZc@sWqO7)vXAVt7=fA{!PFGFVW>YC5*YH0;}+Wq_YGnDf*xkoBHw*OVD!RE{DUcXRQYmJ;ma{QHU# z2RAo5Xi=N$K4qWtcqvnm=|xnKAyvwC(fhF8;czo;ByKpe*&gZlx!5YwSdtThC?AtU zVVUSN2*AS?%tZI`gmEH(Sec@7&wbmGXr-%OEumK{P=vD2TU+)7en#MJ>iF;_Qc`W_ z^M0}!onO_yDWD;)m=|VJt^0!RCf%joogLYj+5KYx$H41Nyl)OcrJB|=tr0tfXW7p= z=@^)p#v6Rk0IyC;O3Et{Vmg`LJ_Mus$ml3wlfdKp=fi@rFfw{IkUF0tLj{@aJ^7U@uuB>kSw_8xTnN0)F+fSx%(4B(bWj5VDe7R%;%`M5A4MBLex)ShSrNU z55>gfVN1)}yl2p*06$*ETtb**y~wL`ckWdZQ1Wji%0I8&(|QdBY5%TzBO@b$>{D7=>LgU>F!%J;h$$k-GAZtv(7ghA+cPgqM;c~VSa20j_m&6t{9)<~b?Lze z(($HRUo@$qu=RtVKRHnb`|FIEJ)0>cnlE1hFLLR9OpAy;^C0rScLdY+qwXA^duo5Q z;%{QX%#L`1M$nOFXmZ!wIF}VI5MXWt#dtH6%{#60&qw3E#i#{`>b*S|hQGis7#eB= zMqW|H*RNO3wZ^cPKaGtNz-@Sv)mK-Soo#Ai@pi%8BOeyr3?%P42SJ7iur9-uYukqa zXMxrkLTe7Q_bQkihhQj_0AgpfQbED*ii1Tn9rVud16%W;eM(9F&E%v@cb@k2jwY|z zPz=|Jn@Jy^r$zK=O0r z*|2$VpzeZAvUoDeuh1}gPcA0M5_q6K4e9gxps)b)|CqJ|15`mlMPI6!!J;!;a>qzz zYS+U3#NWUg$m&`Am#qQ$*^B}_g=K(!a}ol-`TyH1vc|?)oS`97nN?Mfk~;u$y*ydg zh!Q(m1ad)5ZS7q=0C2+(yDNjNr1ulg{c}Ek{-KePNM5b-oKgOc)0taWenie#kJs$> zHY7$S3)M@%s=%~)mLz&VM8pA#K=7YS@>zMue{kk5DKK=+oE-nm5RmbTsq%e2H>_>%0GJ+#u?go{N~9Pkdl;?faj0NKnn^EcXz*& z=g?Df3Eu)&MS1vU0$$=EQ?ZM*j@EFk&#`C=3c zTO8iZxY2(Rp4j#Wygfxk5Y5ZWBi9RPl6#sAtmoBHV&Zkz8B?wG)zw+|dSy;EMpn=7 z(x97Wxh$=(n<3^8wq}qx5N`m9hf8n%`H1UjWpkB)QP>hps~O5LKyTRdIVYV63LyOx z8yl-6y4#ndkeu0LA%HAaHg3unE1^kKkd`^tR> z4&w}U0H!rikAi~8(iSYA`v7|s=*^-)!flVe1#%&K>*Ii`2}VB4C4ef)%5rydQd1cm zs&qct)yco`qmZ1s#i&Oid0@douu9DyOjSEg!{veS-sdbdg0?`uVzsz-J@di) z9*c^?LMspeIj2wUYFu9dZ_UCT5lL3isHnH-)!M47f7RttQczf%@D{ymH0|zly6);! zp`@rNow@bA6vQj8lQ9c9$*QZ%#efMGQr>=c&cL!meDGy7A=rX~c+*nu!W9pp)V=p7 zMIpc}{7Mm#a|Hv)p+9_mxIDMM-lx(B+1uxiMmQmZ>thtFKCX##<0GS@#J7JtCO>)& zW*}W2f}H1)(@5nSpwz%>1S%WUcrJ+pbGTQ_12KcikRUe)_?^_M1zuok>SI9x=&lIk zhDjv_3YU$EqVr^pfX}~g=R)jBj|D$Xh!dzNSJ!hzij36XT+0RYMZi#ZP5`(7a8ybY zSrSlWg@04lmsRmfbZV+(f>BI=d2L~_2sW4v3w@MWG_WSL7;5*&;^!>>>F29i2w8b} zjNEzci$6DK)<6zrk(5ol83-~QHJ>j*A3JtJGX*05%V-1{0w3Bl6@nsX48jNZ_c%j= zk07POO&@mXmDc(le07k&U}R*pva!j&$=`>Ij>i(x=L8gE*wYq3YGsi#91O8Kd0>iX z#nu!*di2OReEU!YXAfQ=$gunO>Cn)J$&K8lq}>%y5Pn%*?c*=fOHA9c|YMhML-ShV7yC%^`i=cLP2(8*VOLEx8;mU;3-N+rBy8D2(& zh9LcS>(l>xw>(@&>o7J z@z9FTFHPXabK{?|UBQ=G{9rP+PQn`E5i<_e{386Eav0!WLQ^#>#lZ8XwR!o=gfD>A zdh8o-0{#sKrEPQ><#gx4RcU|tuQK^`5s#g`Ois|DM__~|`C;olV9_FRw?oyq;=m%h zx;{d&C*WI*ct;YmEg96^(`MvhxjC&jLs}3Z6A-=yPWb+sC&-A|44197^)!!EiX)9WdO!REL>lGE+ph)Qp5Vv5*S_qJC0!o z#dkdjNP@u2uo(rSjEhE(52sv=Kx8vwTcpc=EaS1vi=yR`s@LMK4&sMwjZosE#Pq5wfJeizAk+fkgWMpI(9mmW4g_cNfkkh)R z?>4>m+E=*sTWzgydRH(eBkqny%?24XRKAh7CQxH|={qZo7-vsOazXO=(}e;KFEsV1Ow zfiJaOqj%VYtiJ4fZ~|0ad7gbxj=5k|VvKka*z~b@MWk!e_iRHa zeix*7(uAC~2|Gae0@0_W94(#%X_cWb8TX>!iti24_78GFtgK(24^X^8sm$J#`&7l+ zWU$#5eFNkgz_2`Q?E*+Q64&DyiOEpriUZlVW0FT>Uji2d!`t&!bDitlB06Ja*3Qpo z1jg!m{w0lDWBFplkVUFIH+|OC2X^$*DtWiAp=N;tD3<=(&Fug=$PWQ&8UpxM*gDETBC3~dnOoT9RYgSg4F-U{V z%%lZ}lb<^%3~%B^YTOY88@7r;Pj>Rv3hL|A=&Qc{QA|*>869vw0k5Ve3KZh;pH9xn zy`8DAXD*z!8BQN;(cTf#c>na~@;GNG8&)EQ9r9zB0}j)}he&ZBN|k#ETq}Y}*o6|3 z7>7xztgfztOa;(|ASkI&j-4iy?Iz7d$d47~yJznEXaCspy4bEj)`jEZt4Wqg@umQ) zq*c_^otduW;i*LFV%Vj#RIuVyayE8OB@m30^=7*Z2+X`%UsD~IpKt+)@wIhR@U)ze7iC4 zO{+69B;nZQ(dgxp9qm7_YCJuO3V39l{QX_@vY+498(dQA>B>wf1@`sXUR6V#M{cXJ z+|+ql(L_Aa^Zs#3Zd7bUw)E6oq0E5GpD*+EWYkfOdUo_%VK4qw>R%|R`@^r6i zu%tn8@DAJnE5Y@^dw%t{3Z0J5NZ|C;)aG#eR;g>laVjn<-3}Q%!P(uV-QaVA6Wc4T zuNT`qlBhk>fdQ8yhW&bwq<6@PkMFM4SVFaqbb9)Y9oq+@I>52pw2%`Stg{#?Qlgxfn$=l2ZNZ`sw<)EpfjmrPvzo9BJL ze9~YjX#8AUEqMJAS5;)*;OO>F%)5?xnh*~> z8jbq!aVfDqqv?LB8(U&tl?^$H6qT5SRN`O+R(w{LITP;i=Pj|Vb|s%OkHEq={ShC> zHItWxQP>)KLWbXZSEo{a?S}G6(7~>9oa@&K1w;Sg-$2%U%={qgoG8B4Azvb!SNpRh zwbYa`-5E)psU?-Zn($#9ON#a;Agr+#*$=nOGy^_f zUj5q|Ny($c{;c=xR0;WsiMNSAiYxCA`tBw$KD5rGt{5-rSEsK`SDR6LDe{Zv~`@zQsdM7j|`^Jkzw|}c zKQm4;Brh4<*$!D3H3%mnf*E+Y*Cyq* zWetFsaMqK=Sb5i*z36Z!uDVRC3tyGVOS&eMo1Bq2=amPPf%Me9zhob|<-RN*{?7W8 z8^=p&!b$}r4_Fu`_V7mICY3IefLiM!Y&jQkG-$}rr zJlpC_Vb6@Vx+C0DTu0Lf19>zCK>`$-LnC{RR7)G%AX4*7rqc8m$ZFEpx8na>ANJ%9 z(1la=8?CJsZ;p0{n|Q~-dxwYR%vL&X_dCB+le>!t{)|tg9rCwwtfcsy;H*g4?h2^j>! zX9$U-hT)a);~PnapUMOY6{9)~*X7ZyAK*c7?3Gr;4GP+~u$iIAz^$on3wD}IK|fx4 zZyqNP6bpL&F=0b~Ki*58AG_oB{lfWr(r1W;CFK}~n`+UMHg#05tTZvHq;q1z;O9<;G2a%?(IH8AU}c-b(SN zh1p~Mt{PimHM@U9B*`1UC{6TDKqx~P8@37JgNz{}C{Q(Vz=VmMh#f8wfNG{8_M3rD zHyTcD(%W9}J2oFZsG9gfVq{_%a7FOGNN>-`&T3i~$t@*Y-NBPz{)4T#xhJ8069WOf zr$2q&&H}{`mYlt1vxC!5(jPH&N{0AoEUAqYgomT6*JRY$V(B*ywNkAZ^0m;Hjk+r(F zjl*w5bCPJ`%Ptb#y{oWJ4COtg?a*++wB?5^C9-J~kiNTpZ`+!_M(~nLU|hoOXPZGm`*o!v8#OF_piQuGsQw(X&_V zG}ZQld)6L7Gav5XxUv6zd+%1dXHPEIk}m3cSV89I(&dKZ;LB$Wtez*!wnDK#XNtnl z0Yesq3h-rc3`2Qxj#j?fr8gig8xaB8H>fdq9=$7{uwIwmv(JTv_=Rn;^pfIYkYec@ z93*h4dprg~2YJF+!`Vm9b~vQ%4?{n68t12iB=!rKRcL72JtQ^(jc`06YqL)Mo$^!) zt#kb0*Q?Z!?h!K68n_?57;lpM^w)B+MBjzomD8@*mlG=fR!+o`7%v$+*9Sf}_ItPH zeJ6eRSeuXj3-aHojg>qh0LJUrL>j5kLHCrwsYy>r z{fx5Np0ROQ@Wma^%_!Ln4_zyv=w0rza`+?iiu_zRx>B&T!|ObfSy}Z4Grd@93}QJR z1!`fnIw-{lgB$zh+{ZsC?tR}Iu>wkulgHPBf=o^_Vj`?^_Vc~tEI1!2ErcR^XAq8* zLSv|d;Ggd2+X?Uq3H5@2m`}HROP!E4IRuwV+h7?J_H(Atb;afQ`mVPHzaBmq^Up9p z&Rw4IA05#k##u%kKiRI{w|*&u_L)8~Fc$F`ZLP%ZrL#e>01S-PuPvsHZz|tBZM?Gd z^;y#mf@mJNX7! z;ewzFT}kb_5J=xk4waj47yBGMBTn3sUGPDRA|1@a0?rVQ{xdCX!H9 ztP`UyN9R_b@CI%?Hr#7)J?L7cCv?86u@bC}=-->0c2-ta&WWrz`wY9bUCEya)wl$9 zIgmS1P8V@6Q|1IDi6930iQtP5Nl8y&w?qH^+rGz&t+cK#&dMTGuFcPTq$|mr{;e_V zkk5sFB5@#pvQjeHzAX~BdUQmp7gfZQ!@gZGGM>iK?2vhB7V&eNn0f^v(vyk&wf(m7^uGD&Qu>)_-0gn};x!uer6uela1wdEZ+`jK526rLpM$yCG%grcA`p}&3M`F4y8y~K z%)NenJ5TUGdS%g>syLGMt(DIyDJGK>iL34r!n{5DXQRS$renV8ufppD4Ts|Z|rwtYpqZc1tT9N)ag%C{?IO@ z>D9puBK?Ue1g*~|6jq$c58Y*9i?RduAT;W;92w!)SSbaEU_`{&n^-8C+|OEPQsEvw zi8&bxCGuFDm{=k?9wK_Dztm}S5yC=#ybf@i5h2I<-$v=^sFCJ#{)3I=Oxpgm^6N+0 zYG0okxYZ;4ZbTvDTbJMPcPeOBcMuL$+Mux9_*buAn}Zt>T0mKipu)}qm61+5#3u}H zgy=laFpR~G%`_37knN?VG$0Yenf^uO;|Xk05eV6jSp}bD^3DNgnEmDuKa+A z!IBV>K9()N;|IOHXaFs(TC7;SzJcw2p(Y`X{9e4!e-i0&g)xZt;X{{xr6|C$%Ok;( z121Y!(y9OH(^@5ha$FAjD8fD1jiHJ;+X6T+@An?4p2D$`gQMcy-M+JK<80 zp_Izzp_=5BE(ODArF)w1pOD<8RHCm6xzlH#Pwo}CTp}r-=4XHFl8gBRmxUTh`5-hY zoXkKLO#*RHlD>mlo%7figfuU*LNo!qM6<4^4-C?_*zhVNY$*KPyt5lHKO zg%E01049NfBJ4^nli(Qb+p^Ayt;ZFVIU|liro*oF+tfk+lqBHNnan+CU4x;a>xzfQ zT+@Y2YxJ#F-;+DnPSpt&USdjBSbYNv_uq|;emRz5&ha9zn9kviTIh|f&k!{#{7DuP zcX)DYfEIXpauGFb9p8B^mCBMS;36y55QQ%-{(AK6UY%6=n#q7i_`GA@h3`6)+j~`$ zip?vhr?mVVK;`fFp%ec=X3VmtVFXdeFxW|{n^txM`}goWXQ-2*pINArUYA+9{+sas z((-*sppf>fd@1~EP`L;0VQAB}2=dnI)Ms*D`uffZxiD1feJ{(aA5iQ*#WX3X4>2H9jdKID=m}MCi4eWtI5@Ejcj#Pzy2h! z#q09qt{l1d?!2Bav`hj{z{Y;do!dS%Djfn>g=A#>pM{QHMD@A) zYX=HOf*5x0D)aU^{hj~tl2opg+o~h!LF7zZnJ!a-Y97x@jp8l01Fw4PhgOM|tldZ< z8Dmon4D}BF{N*GPhLtBEu3u+iOm>@oqp|3@KJqmcZk##t&CL%p0)S=4#sVwH z#ntsb<&1#hSBb88#kAVGk6qu+p1!_kVdx{23bOy}@TNz{arO6`(UmrgK`6Wf5FqHo z^f9f*V&}RYJrKUu`Ib_Afy=B{=iw}rTI`aR@1w;E9|C{=s$|*%e(q9H!lS#f{^2tM zl+8kskJ|(v?dggw>>ry-KZ(q;WT<0wTh2F!HNi1L$8GjsOs|8>An`3SEZ!A>9Q>-d z^Q~eg#3%b#m^se9R!7#%YI;0{a(wFWl269MxNkO#f@s82>aU%h9d$uk=4Z%z3+pO6 z2VPT=Dv%FH z&7Aeu>fLzi&!vVOOK>*zht}=&zqgHNRenrdIqagvU^3uXyH~FYva)8r3tmqud1rbZ zi0e6b-T)Qb$aT~O5!CWQIpm%RUrBfr|D&oa0UAZiV6P3Puo1uQI5XQEI8x0tjgrhb z)yxsHgLe=!K*JG_4qAwu>Au3oUqx+BF5=Hsc)ce7KYi=fTbF37#(xV7oWdXOwq=mD zfqm}!xAz7ZTf&ts_FsyN*F)2&qHczRo4tMX{t{E)*Pa0*z*=@~yy<&JZ!tL(=Z2Bx zNnQ|$gaW=iMw9s+c=@-^N5)si^=Q^{AA^uBTl8-e)f~&&ZA%Ek^B!6=qp%m>T}_-I zM+Cj#o(B?EE65$c?L4x3#$0%J+??uir|NWPnKe7GtNO>MD5U4Eg^U%7tDMIN$vJMB z3khpn#e0ao^BHMK01P9%D8JYPI|I%V=PW9nu}#ztpdp% zC@dONX%lznrsTUAsv=}pVS%^`xPsYxr6BCqO7ij#XT;1?>Bq2(0eN`^jbWjmyS*qn zGIZiEpgy@HMlk9{^ZkCqe7^*1xM9S*sSR!ebKkqv9Tk{Wyn1nzjih$_5Jj8@@%$1UC-8t z6jIJtgP|xXc*#g<t)1_zw5HDGcB^MdXZ{x?Z(|sq;`LTArOIgCfnA zX|{^_pZ>FF$@ky~(@{QR{QQ_3R$QMUXqlxQ?YH1QYOksPP~n-17b&g!Zb%F%l##BhNg1ZWhsa^?t?5@87+?f06(}&4%?7Rrd{DKmIa?DC#n5yzEn*QyB#}EoG>#P?F^{ z4gC|6#lV`;pq!fxgAD5rTF5za%?09v5pZn7{t1ii$hUzqYXYCxzYI@#f{61nKNiA} z8UIFS&amQn<^g6u;MVPt^szUb{QDW+NwT<$%)3co`07kNBCyIdv{xHB#B z)kb7N6cZ=GO|x;`l6O zUO}Q@NxA0k%;E5dWn8f&xMK&LN*07$QFV4R`WF%;H9mCY5TQPbImIc)!t>`<+CuVU-;n?_eQSqknPZ5~B0qUB<3E%LHW znvGX->WYJ#92@E5Hn^;tigu|(L?AaG3DU$$JJD1tevTCzX*?R=jt(#2g7Z-}YsV*c zE#&Fl?3fQ6&Px$1u4kw&%-?Qd`u*_pi;V-!`*Et#mu`k29|2^HvZ9(AP}emtO63D* zzU8KiX`WQBt+fyO>i7zp3P`}3zf{_g1nCR1QVeVIuM1RKegIck81%SB6ZoT^%s>#s1A>b$ z_KRgwIpbz6v-Uo(x(m7xZ`(8bPqW@*vditEK%YPpiS?=iS!)8QL|i)p3Zui`H%Vgmp5ccp05 zUsHTJdGzY`;Q?;LnZ{sTTTv+vo;Jm+V4pb$IqjWBqb zib^Lwe}%yW!hb236op73Vgy<5r_kahrc}K*UewTY9(v9AIe`f@Rs0Mq)(;9tE}wLw zmFaFCfjpm_y83A4O*xQEj*-F%J_=j_TK55uqX@ z^Mq8gcd~UT>ty8EL?MLik(u2w5|W*aV`Suz&F|^+{rv%M&ND2`bNK16jgXE zfyrqyC@n|k;`8o`f$s`(-tNz~{(PAjdZ)VD?2{mIv(DI9c6j)j@Y+t^&9ZL>Q^$Ah z%|YN`a3t6O*_Z3J>+BwWVUJn+o_<-QtC4YMNyW@-f zqM{i4oRdwWxw+rJet9N$j_xJwk*zyU>5U&8OdXZsMK?0g9QdH~+GZ%xz{m&4kf~3h z9~lBY%>)RrpjNf~>-sz^vPUpCmz}T8C5AC3*7*`E?a9E0BUf>s3WUM8vvi*oji2(C z_mgBhkJHo)hy84k5Dl7KUSXH#9!|m1o^IeWUhCUbs##Xox7OCtaS61VtTOm?YrLh4 zkOp#o+018WJwz|Bx^OE;M#RpJC5&Efz7SMBSV~=@RD3?0+=}3d6WP88A@H7&qX;G;)r1R;kc={U#;Jb&wSTQO)MJA(}(upXR)R>laR*i8yR+XU0}JE zkm$piYsRQWBhe2Hv(nR}%->qGl`p*^GK-4PW+(6@x?dz2Gr3`_B9p_DBAnRY*^Z3Y zA9AONQ6kb^-io#|=QALwLC5`f`;Fa5Id)8wFUN_+H~I!97g`iH=E4An;z`pnF_$w#`Yi@0(kb(?`um)n#rf*GvH@@s}RJ zJRno3+h1}xL8&z24&&{IbNRHv=_cTipv1++zk@mi zy}o^<{t^ubX**GTk)4ebxF|LcUDcv8qbAcAuR5r-qp4p-_xFFlD(*Tg>WVa%kDGj^ zgraUMvK{%i3tDdZy;TutK6{NFYB%b3m;2oI*XJd`Hz7*v0}>+=8I<3QApI>5Lapuk z6botJlW+`h>y@c`CeX)Xq?GULXlCV6vV@=7TZ_9RCe(;jMv9>k4}vE_da;e~ex&%I zF7mJw+!ZhVwhTA-MM$*WlizRbeP4Zl`1N@j{_Df;`8TL zEBlXH6Uu^%v_ZmXuxv}5vp-0w{@Pyby|aE6s0pW3I7S|wEtem-izjo4C4q zKlsHPF>{${Vfb%nal(CEcQ?5q`IMyASY>`Li-oWIcvlD5YX7!S#fHkp#lGU9NvB2L z=JQF=G}7zTeJXIq#&7@1t{a!O4@2WI`@u8!nnfbQ)cp9TX{g;;ur0vZ@{zKRbJ;ZBv2q`X=M7o`2>LajM~39y(H$IWu^t3HNhCSzxNp! z!^HwM#jsv^ad2U74yznTh&?_mdcX`>wW*UN4-O)KNSC)PCw={9+AeF)OYz~ z>P0;}gS-3ZU3AFy!Qgr6USIFrJlsA3S}WRV-VQFhLtzuQKla4=GPVL`boVaFFlUiAiKlXL=!rd34*nJPWg1ZO%(NqnEK1&WawBP?; ze$GXA`t;IxEr<$1cIx5oUVTrN8+Y+e>dtQ#u1}n@DT!w;RHfH-a4u3HI%jo2XIYmX za%5mS*?8h#Jr5EiKE$md?#6hYIw|WctpL~>tqkiYzq?>$SR* zh)80#YuBp_3l!8D+$ank*YL#f_uO2H#N~!~I*ISU|Gqk!-tyo$+b+csGj($AwkKo( zCkNJM8T?Wc-V&GFYVQ6^uBkiM%IqO6d*_ty<%((%S&`BoF`>KjeNFG)#ej=n6#dpj zfbMjP`c+BFaF?oNZe%rdk7e$56RoF>8+e3Y_w?=y#wHpg4IWxOnG~9rAD`h{F6%3C z>8LSm!K$g2U3J3XT#&f-oG&g3?Havd8}iD^5QJIf<*Cw68D(X$ zx9SDsbop0yr}v}z#b{~#PVgJtDt=FiplSJNHw5}7Z;R4*J{Qo>^oPV+`C}5Id8_jC zQ%Ih8m`P=E8Ra~gU)MA>#Z5g64q(5!ZZ}bvVx+CpUbB5`;P3{QDDA!4#`O-FplEXX z@`HZW*^cbggydukLpu0!$J7bW@G5lOEXCB8N=)~IRlrQX9g`+kBb`0JCR4bKy{(f; zsG2=PSH`~_cW-^^Afx}!zyZbt6Y8RVLyG0)vYX_B!_&}Sv}fsEYQzIpRgf&UIYAc% zthDz6>ISkoPZ%&TFREV+648j(JO(3H3YCqB*QYl>F2(R}ch1K^t+tKPXR-=ld2;L& z8flr_(J76GYiVp`bS&T{>U(LpHCu~?_4DWA9QgL)PSI6R|12yoA18n1BE26b{fSE= zq_1LF zhQ?Bk6&Cs$PuEOiD!1}?x}+Q&o>WHNZhEVT{0}2UJQJqk@$Xo2iVKhlX6FIv0b**H zWUY5Nnx^pV8W|09j9hbCyYcwu<04&Ls_6&$f z#0}&x>2sKNaUnFd=(CN)RKaJ71xy1`UnwOd;tanUo);3$PVB*I{w;X3j?HhcZ4Ij{ zOx-hWD$5EhL5BLB^!xs1cX_wrYb+=9J=b-^mER$srHkF)ba z3(F==pxT%%QVF3LYI976S*?*a7JZu8cTB5fVik$~uP0>K!8LdG z>q6bG4OVt?*fWQ45SD2*%j82(cl*Z{-jt3^mVvYA<{0+X!bayzvnRmLP`VzKCQJ3x zE?*a=mnC!?PokrFwbAeP^CUUx!Tv#aIzqACS&qaKn5bVYRN^sKJ=I2USYBJ_A%RAS zi*nG#5;Gk?0CaMwT<_A1VyqZ~)Auxmvgn7e5kEm-nYPv3rW9-4*;3)>>)d+!r$~RL z7Q=pA@bc{N-J}vh2HrZJNEy`LM}vw<4`_La1iWE61cwxch?1NL(BKvyeCQ zV(vlN;Rg2bZ+}0NR`Jbu+6ey)e)vcnZJc1HyjFcT3?PbQ-93+ecfYvw)HaLT3dgBG zeuPvS%lna}-y+$m$c+=5TTv)=)_a|9_?M4*^y zXFsUvK7%0im|2=s;rQ^j`ac=)dg#3!mUG5u_0W%;ZW5(Ek3#xvBpy01D=V%ETJ_j2 z&%=4ESAIUf_A)Onu7+pVcYlN3zRIc%;3U^lmgnZAeRf+q`Mjw|1lE;6Rd`@n6yC}*ZxS%OAvbd8!uDqCfYn@nFv-UOWeA}1wYwFP|+Fw|0jH+}zr#_`P zXO1e0cv{UQx@?y*YiMj1##i<{?wvk39dY+eT1$OieoAPdRNmGgwjPk11vlY^lWxt{ zBwA%sP*_+9Zdwyz-~)Xd&>bnC=e`F6m(_y`zg_wu3}Nc0x4c2GK*$Xro^cROQKJIw zM&!Ky=^BrOI#=;_I9Hi`d_xnQj>g%J%zBQm(6>&BX}|F_Lm)0P{N1b}jj`M*?g{A3 zd%>&sB4d=$Pjl%rO>Kgx7WqgN-a{@hr9e|#-iUZ*Z8@0YQLD^!K?(H?-$uR2hIy4z zZ$6l7lA9H{uOg4U@?qCNdz9pua55s#99JA~lH=XYaQQ^ttKU*m7guUGuiJa&W?BEA z!Z}K98azPIE25}H7a1=hDVaSG4J>u5%%&o-#0xkv;-{{zrGnh=Po!g0Pi{2l+^%<%0?|L95*@zL=QKasXZ3mmwN+W&6Wn1L%{)H zZ)ax;t6yf1ipaF`D-?(iTupvkb8Rw&Oex{`$XLO_k1J!E3YmmMo&xtz*r~D02IYty zp32{ferKT>BuV(y+J^`XUT{fIO0xQvQi>YI`s?K--pZ8QAfRz`)nL(@`g>%UgueUE zcS=Vk)M$5)h|j!@5OFmFXG`i#h_SOvDRqxrSZHqkV4YZWLp%xGs?kMGwVT5(V z7cwB{NMKGfediu0GrzXYu5k0m*oiFb?;+#soS=Cr5iGFpT-H_c=pvEx&1#L9RGy{eR?=!}uB6SiDl~u$L^0`p9*GdKFu!lQwK+xb-4@41eWk#?|Idg0RObnotgBQP- z+ZoAq7yqgAIRUG)=@Q#uh^7cB5ODK2}$h%oT;C+n#oXiv&g zOGcED+bL!HMV8R9*i5`F#*0y++?q62cbh(|+<;xp0&YqyqCs@HDC>f>pO_C;J)Ng+g>o8se zBiN#%j_fpF0?BhsQhfdmb|X(-Vab<=nh}Fflm7A9KF0hBV~l0!$B(8X%CErs15PcP zpf8EQ#QbPT^{6dPXLO^7Jo|XIzgE{l292Albgt6mWO_1Zx^GdvUs_Ah?doY_eJq~f zD9u6l@`8FIV-*!bAdzo1&?+I=JU(lC5v$-k_e~ptY^6r8H#64P>SWI*mNaB04jUR* z=bFfceQtQ+81maUe@E2j>L=6bnKx{btRH5boj+=6si$FgR{XZJ0Z((?>jzLm65dh# z`JXn`MU<76I*|VQdTmEXg3hI$PvPn8cuV%IgdVHtkmDmxd>7jm7n3fi$E$a3>AJPy z7o{A=?+e6o;{f53m3Bqpfk%~Ew@+PVpH~0L33-x@SYU!?;@WmxGf3P~{S8{Z+ zUAbfjW$FrE*8VL45zPx^;CDvhPIBkKcy>pDJX+|t(HwRD#9l!44}v~|+duLFEux6y z#w*Jwz~h~){*@KMo@AV;pZ_Og#U#I;%>E{q#&lNnX5W~DA))J0iKK2?%y+aNl{Tzk z(alcD><%@TVs4Wu??hO&wzcI6ULtP?<_avI*xzacw4iALh>02ZhgY`an|MqP3nt4> z7Z{b!13+h#AiQ_8pIL?OI_hlyRXW>V%Zfh1xuRtO36D<1hR+ z2K{V|Z>tFI`cNRx{tAV;1*+EMILiCbi(Y5ua_p@EDycKy-$|xzFMe3h2T7>ut^BM0 zu7kIa+={HhVqm82dZe5V;Mpu|pr9O?K?AwJS)&J()#m8G3sQ_708S~PXKzqL!9DKO zzFxYY>^gmRtDkzoRhPj1#HG#?MCDNtg=~G|<2mQbX~cWNi(=5&ZQ(se8EB6mruF#c z=n6S=5NR0Rx(iDt9`{FCuwCPuZglW5JsO9a2%Q0pmz%}dvDBV_Hg)*4O?3pq^wzPG zp>wM{eh<1@QLqBWPv798ur($Z<){}wJhCB5FZa~N@4%$KDM zXi(T|GB}z-tVO?PP?K0D=`y2nMaoE+9@Z;1xf87R4+gd5;$t4<{IGgfm##7JI`2xg zi7-fPO?jstORWK_(Wl`0Hn_}IG&@Dw8N)vsSss%G`%%$-n7V?iu3$?)&+!WR{Q7p- z2gzo4qA5s$j7N3$#WBcytY&r}n207F@1t;76z|>9K5(uw@o{bai=`N<#md# z)^Er87b>8RGxM~XIM_dN@6uBA>yfghrH?+n*ggB`JkCG$PAR(sq8kNezu#;8%6*

do=eoa`zY^*Fu5e-8Bz60>r5q;EThu~Sf&+f`JQ`L4y(gK59$e!tuG zGhx~ilTWogSgz)s|GTY`wLIm*g+M2#Y#0g0jkygk&>Y_%1h^fHg_Rr?g6d|sNt;Zk ztPsdx|HqXD1>L~3@7YLpBE9JQ1ThVLlJE*%A@{5dZcG@CW0TodaBoeTbX6})9XHDf ztd$yTE_Kv4K7Q&Ts}d)hnko3(A(U9flFaBpAP#kOL;=>oTV8~?CRq3fL~j?5MHw(F zNXK0ULDnOmiJimMC@<00#H{&hI>g-kyc7G4ycaf!#}m@-oY4D@-Phaz=8Cle(}%ST zr_&FgXb4>P1S4ye3En&&%uKf*r+V4bmz`}uIY!n_;f(=@#8+|a`{|LKVq=2U$UmaU zisy3GKEdr=TvFoFpU)2qD(6I!l-IMK?g*`uo+4mFMYo zN+?#J3*IysB|ZMG&OE^W%lByCODwlDxcIRBqen!R^}K5$eif(}9CV*ksSo!=6n@{w zlc@1i2&%IPn8dfruG9>45&O#Z5+l=1bIR@fpcd(O3%slKGT9*M*sMDt;*Cf$`S>mk z^X4%#4VDsY>G7&9?dLQH-KMX$J9dse!iBY1t1}?c)djC3@Ii}TV6F^K=ZFYx%LMOq zZjJBBw{Gg`85{Qug?1UPx^n3*?s7O4-fpi{&=6!&(tDk^D{ud_W&a`qaoK^3J&lbk zt(o<8csK?cf*^$NyoMjqDS7ur>2sYywc`zz$%+2miXaq9+i`8jf= z88?`cCP~EQ{lMmow9Y*DHW4N(cBymF({lXVe)B+7%{bwR!N3{}2E`B3vv5QS-;}sY zu(}i)t;uJtgf1J;|MB=u4q36ZvY@fIzhmr;R`y>4%bV zNb^pt)nwQ;hp1#ykhJUEYQ~Q$5t+-zd&kl;z50C0Y%Ty`oZfD%8k~FJX{`KwK7kvD z^Vht(xVa5+6A}rUmX_!9t(8`{ns5Qv~>TyFaYwAMF*&7W|c(Q3czl-=Q>HHh_| zoO#!Vx8%J%t$6ujOFi2nnW(o;DhxIw@?{P8?y%V^I_5OCgtrv>gB)NxtbWTUt!ER8 zI;WoNE7^6GuJO4eyHm5Oqpd)$0`B_Nq?Gu0I5*DgO^H8Ip7*RhF^eOU-+5tP6)Y~V z*_IXesq};N*sb6$IyzO1ZxH~ztyIZm0 zwb;3{XMs_em}ON0+V?sAePX>_@~s&W5<-}{r9Sw&l!iTRJNu7I{dZq3@I3Lk9JWPi z*xBr}#8J@W`!A+Pes=_>tmkj;a*iC7DD3tK8WcEEEy={bT6U!wJ^;{Y{a(Z1XMNXk zkBOD4EK|w4;F9r0munh%28Ls8%K+O}+KnD1S$i;`aiO1WelFIHi1=;W+St6CVcj-~ zdJu>#=hVo1^Ue*(&860T)$mN6MuRzBfVoSuYhmxT-N?kw4|**|)4%VYcQN~^m!A6Z zs*3L!*`SV%VN=Eg|6>p@aGBD8H|Cz~=?|otRQj>)-!xwH-r9%;zk@&frh?Z<&4cz| zM~a2m%Graph2z{z{pQlS-VkSZCk~bLtcFLD<^(QirGJ|ak(E7JV>V=}RQSV3t8eac z*PRXBi|%t59y*I}G&71&A*%JS8kC-L=Kvj=Q@N#0tauMiZpQM@zwq-ssy-zvCUZqh zJ^(dby>V?vUcqmRCDUTOdVQuO`@rO2Q5u6 zcLkXNxm{KvRaSnrcFE31cj6>k(l?tyfdngoOaol^Sxx;3NnNbzXay%%TKCM?!dmy> zI=!1WeF`FH4DnOc1WO7;i%yiKp<;WtscdNG*R8qtS+S?@LEZy$ro=kfN=50RA)e$} zk7Z-e6IxIz{LR4Rm!Q5)S(S`CU|tC`VS^G(xm;JssepMPP8rbv26e(*5d-yGeh!2v z3hBZ@gJ?vZ5*n<^m^zrKFEkn&`^S|Sldkd`u=8J`MLbQ#-nuBxZd~#2$6y;9+wZqe zc^N@tP6%|b}(a5Ol7(#J>8>J{rGKrY(ydaUS5w%8$UJG(@ z@*2)_{q|I2H11`@+HdkBsyw!$uZG-#{zxY#6+JzL9vT#7gW?&{iU}t&Ah4$eyf&`o znzII*-_7^io`D(8IsVwyJrA?`x{AB3K+lBanlj@_y4fLBol*XS0fXJk#EdB^*5Hmu zVT_CtG(%DMO=2$uP01)lay-nw7bB#6Lwm+EWCoT_wj%`Vc!J$fxs|bgQ9Sdp1pHeI zLmUb#G#ux~Ux;E+Px$f7cV$@okg$_$v~0regvC95Ka;y*VC|VraLACo#sChPK>qKo zw+WVLoPWcJy_c!w#jcKTJWkcK>W`nU43#+a)V(lGS)9cl%5PR37JIA^1G%YRpjGst zwLLaTFm{LD^Cg$>Gmwnt*<=dkSWdmG-x-h?NOC=CaFg(&=$RrDuNjk&>E_EX!39ar zDPV~7kk*l#i4SiX4?t2^y|*TvE`be-!Kg1T4Wh5IQb-JLWmS7u_9{O9#yaPWF#op? zbyV3sooc4CgW)q0{oVhK6j|Q0v6f#e&-we&Uq~!sVuz z^sedgp8OCgOiW1E+c&Vt>L_f0U}cn*rFS2nWS5{aBd$89^C-OL(wPztn@hrnCdqk5 zm3xokSgXPg$&@*q|J9>h0!N3nh41DaD|acMW_#oe+{ATq8j!oc+?3xt2)LL1?~hD_ z;?Le*Uofzn=D8YCSa)G!Q}p@qckqRVwO@+`5((KsuUX&e>& zDv1KI;x&;U%FrAyxBkuJY%nAB_P6x&`};3BM=V%_E$<^Jc$-im_L1`d-?BPoE^ZdD~mH z4@h)Z;hn8L?RgH(8~U{)=JCPuN*w~tbi*+E0^)6f0ix)FwwP8M7g8}e0CkNdd^-#F z%a+Q)6!C~xml>00XYl4m)yt|^GPcV4JgQLLBFjX*W|ns5-W{89bn%wSP;>3BhV*p_ z*MFTzH17HDYxw+J=bJY_^M(O$aC6rif#{Re$aKD%#7qs+S?@X&?QtYJK=D3P5U7K6 za&$d5`8K=m<>b_FCmq)L9p>4y@V7a2Jk%lhFfyJ8$0DYkOxfd-es>IVOimoXO-oPT zG8HmAt8W-hL0z3?;(70r2r{5rbTbz61vz-}tB$klDpM1IKyRs>NHf+G> z7uAZkUaUDQE*UsXH!{qkZ`6yt5~cJPjl9G}!+Kr`#j9>_Z9OCH{=`vDJJyl^i)gs{ zlgB4|wsf%?He{Fs!eyH(JXmn(`RuW~SqZ#N4I1~mKmiz&A+E*k$1 z;e&tz1O??~WvRf>XCcFEQOfqdu|TY~ zXNRZX9`l>P3&%x z?VJ8iy}S^z-y-7c1bpC=fj}1awzROYaCR0)A)6ORC>n#!xu@@EI_hr#s?@&>k3UU21L68Mk-91 zwpY8HYWQCf?5O-X+06q*(X>Ec3*_I?jYa7cys0CnaOpc#O~tdyqA6gqXEF9 zushUqFDC(${+9n%)$iutPT^73iNRS31kaV53aZGh;la8&@;0wJq_}13SOe#&V&WiR z`=yhoP2a%V=jl&|CR}>Dszl`88=W($4KO3F4bJ>FiAvt(s5-1y*qqqe#WEg?BB|gl zDX6zGx3!swqEjK2{JX4()21Q@@GRc-I%C>Ls~mG9!3z8y(s(_lR4ZyFCWsK??P$SF z;$T$?9PzMZbs0U}d3TkyFs)w99CYeT81 zzoCwLtuj^K#PIMzpsVRbk&Bm&&B$z*vE7IxM_-v$_Ef%L?5QSE2#taqoiOa)30yJ; zUC4iH@N3!Ppo1&NXI%l`*}ly_&cp2GzuP#APu({>U}5tm z#tm<06B{~nA1PBl#XX{)o$Z~QW-c8ZfKb$?_VHl{hMt>gc5p4sj(wNPECIXLCyKbg}NW!?K8cK~QEEkR=O-uR~Pt7Sf1Bx_P+%lK6v6FiJiVOt-rpUwXPT|2j z&VE^^E^VS9>IhT*s-FGW2`+BxzjAlReDdt<=EAIFYcu$Df1hruhwcCAIQ(8rt8?T*GntaU%_X zh-r<$?7aLkWY*lOf*m#vY`BP`F3=YUMu$AyTv!H{^}Cy|A*=*moXAPWJmFE>AJb6VT>J__pk+i}q^rfW7U8(x?YfM)8@lP$lI<1Jrr(efOj=y!<50F&FK z-ggO9a{Nq*2?;s60ubip2f%-z4bnEfA&{7v2lFFslcHOEJRm;=yNpO}t;{%8*| z`hI%8lkxjRojpNIg-^(#q>8}nEj%_p5r-*vc@s9aFK9kVam$HBME8s+`*RrP)%KOMg zGUQ~7pAu`VGFe`qkMZ?WL_NbOilPo+c)DVHb(iFKz!HSfCS1TzNfRs$|Lw2%P0TJ{ zJ=}ZzI-K@3>lx?d;;BeL)j%@fA>i@rw|;AHM%JzPc=)Wv9GXwmfx*V4PttU-e!I)T zssxTC)Ty8+VT>Rmz+@jk71%(Q!->XpKzxfdT@RUcN(HsK-H-9Fe^Tpg5Ni{C_Otju zs`bjg!nm~BoU&g|y^wP`dZ5px?if^BN62p!rfmFKE<`ZrZ2u%j-A~_H&ZII)eeOQk z_dmT5<7sb1{uhXBM2I3N6(t1yf0kRa5em-M)-KXEJ)2FK5T{i}`qNS&?)u1^_E|r_ zfogWHYA*iRLz-}Fq9a)C?(T}U;(l2OFo(CCY(}Tk8tcQzx_e_QICleWhLf}4mXcg=)4*B9M$y#yIGzjl`_Q@Q*5oVw!%^WoQ5URTyxzKp#LJF($l$caV9 zecT|uW~&<%QM^Sl2iHaBajbnpm^vo{T>LaPE;@=oI()~ zlb)%c5;@jNDEJJmNX)Cq^GH~#(KbmV&B4vJ`~Z%I41Q!f1T!*VG;1v$NrXgbVNSb+@`-#iY22i!Hh|ey!N=Y^YwCu!*6BLM)lzd!dcG^J~#D(D^NuJmK zo{#BpRINc1Z(?6ip&^MVF?Wox^K%M--%Eux(eJtx{4drL`Mx2@A0bkh`A15l1@S)pevfitJ*n{^N_Et=n9gXgk_Q??RxMA>hK>s+P))>o@Wp z%)=iVcCgT7@T z(981^#e2vhHv+-B-U>NWl5CkuJAXI~)R1rKLAgdfSreoDG*w^%(|9 zG?(ND0#|WZ-8{EF4mN&)*u^DNa$lPKT7-k#&!6{6rISt(1&o4+5fgc|K-*tH{Jo1bWyR)ST)n^G%ib zW)pHwuYw`@Ow9E6OIm~Pioh6LZkG@|`Lp~5tKus=WhCU2zE#0x>YPM;@>m&%T-Xq+ zDo76wx;^ zAzMQdj~oA>^rgPl%@CG2+D_Bqm&a?TfS)(9-F+BW!D}hK3>}|Sv#QHwkEH98dG6kdD5Vib=hGi= zalD_UrE>m!6CCtXqHQjOleQz`uBR~_K1CBf>J0G-2}(#nl01=w99-C;uK|ATn`D@>uRO5q1+rN4Kfh-rtLUDO+Y7_sEe7{9j8Co>p7gl zbB+K3PKda(N20dSpseC)nOP;L9S$=r=olLfB_%FAsgy4JxY78wy%;~SA`%!Gj+we!MtOsDA zJNJ5@bhy_Bcmfy)9EM~(+Z^+#J=|YON=PvL>@JAlPB{nr9NMNoV_sW9EOZ?5-Z*n1 zl>i*{91ji4g~9-vz~aPl0!GBvXhF#i>eW9j*cj$N0 z_~6HIv~2`#+5ngM{dwxmK!0i_*f3^UDC+E1W%BT@Jny3?X|5D~IxJe^;KhjVP?A(*vYjVYR_PVKsn$dDv|q z#6^-_qtzS7J+O3~*Y*~%hmhHUXF3%GoL7K;*H1wFEMT^#xPt@wN4TTZ904|Bk@JxG z)GQCzDw}Px8B#+y&85ssA?{P9K}q{ilF{6#v1UQK&k0<2olkw{3mp}0v!V<}G=yIm zOi&<7&m|w9U-!gC_K*O2CQ2LbbhN-1hn!~x@2y`@Qvy!@o%LN6 z_0EU1ZH6`JKQ%PECL)cDKbb!CD#$Y<)k$|6D%1p8l;U&*4PLjL74aR{n62Lh1k+qDQ5-2It)@p(>v`GRm_jHWINQ=^Bui%*(2%o+KtS6PgaPm( zcvo9@`}!CmD+kMRD(E!(_*FkCG&O*mSk3(DJB#ZtseWzHLwJVx~mpSjwcL|YMxN+{3NINp$3?m}l6 zsm-08qo<_9PokmBl`_5UwFyiC>%`?GO)V{;B%MR(2oN}?QJ6W+x{jQaZB9ms#>cd! zJ%9JZ$ZfY`{5i2pY66mLm251JlDV(4Mcj(Up`eRCB3t$X?Cc1`3|tS$RU4N?VIXyz z`BYHxkhc&ax&9_C$UR{hXl(~g@Vx6S$P`5(-W~^Z+b4Ism5IHsm1`K`NurqLUiHNh54=|ME3VQC|v`&A*APf;NDxAgyId;&9s z-A6)*NFfk``kt0S4=I(9se<`XAk0Ht`&s~O2F=@A3)S|liPmhmNHx>`mCf@ws)M)o zPafY+yOsIqOFF=n1nq8pVQsSz3oo)Wd}sL%1V#YyY2=Hb zV_Ri1n-<$)vQ`JRKPQ{&ZIVAfN-E=UlCUg2|5u#l;#IrhHR#;%lA0@m=;`o?*TeXH>*0!ea>|BJZ2?-;4RIU_wRmvk9G{n@4=(~H^k9;66~xQ~qxFBJ zjo4ck7-a5D<53od!KkNK8@^GD1~&9mw=qJ@xIZiQlbD+?;|rVlznv1Vv0s$_#VePM z_RKR;AnuM8My>Ag2q`;Zx3qqIOt^q3bCoD#s!}`Wg3tez6v03E(Qxw}*Y#?zO}Eph zPfM1Aa%ny7(Pys@dthr;n$ti1#iHm<$9s517TfQu20CS$6xsEa=R0R|gte%)sruv= zR^_y~cLv)>1!=$6*JM8f^f1+TN1f;loXaQa_zeEUEGh)Das7}L`_W?_)3_TU zHSTNOHe?x~d-LT>x{ZGuRT!*Go2PZyF0+t_&%H+k2Pfgj>bX0Cr_R(A1F@s+ucS(e zg$heV*oAqIS`Eq5RFg6*K=tS$(Hy4|YC}(pMi$vpS(*sN(kj33w=&d^K5Bra304Vm zJtSvCB~(W52i^|fdWV7B)Xysi+&<(Uzk|Zowwv5II8ZhC7@)X=6}mPPFwFO1EB)R~ z3_k^Xac3e&V+Sm`5!3ETylZ->>;81dVgQb?*#Izjhmf2ilc$J?70qt>>e!V~3O#dEY@$g;kA z<%)-!9m0TY;8R6VFyk|Lr?qBeYG|W7YEw>SH*~1puY2*8S1H&R3t?9)M*BjH!vCST zH3pWg!RBjn3Q6T);0{7fJIg#RMj}cz88NEbOlH5n&qKmNG;fQf7B1OeAzqD-Sw-wL zxqm(;*c^wM>`JN-r6q$fv9GVB;JL<+0=vS3rgT+HTqLNyPNGL^y-1(}MPWdt$U5~n z)pOPcySoDe7DevW)J!?Ys)%(h%~`vka&})Bs40M6QTTAEM>LQ(sBq_RErNK(37aI$XHY}uRphc<_Cvxw!DMJV z&>$((Yt{N>mHFI|Z7Ye4#_8%YQ~!rSp!?lYc8b0|;e?!QCytA(NOB+o*-3&cjK|Y~ z3DJ-MCIkLk96gCymsT;Ryu;%^#H3xz?+UFKEbeX;9`PhRx`z-Ie9;23P=!qrZp}b` zB^9J6F{<>6hMNcj9*|jO=9zq&2sI^ohmIVl$a%9uDC|dfpA?fy6y7{zW;59C zUzl&$*Edl1wRmYlZsR^Ts^-8>w!;4N0Td6L$*;#hZ^nY3=##80K>qMkmnufRiAx@% z`Z>CZNl9Q5AHTk9cKunqq^9Yh^LFQ~mNEAEcKohxF z30lx<%zsb-0U3IZtirOPC=zefJ>CE4neVpHUOZOJ$&Y5(SvXmxvewjBN1jVb5r0n= z2{0~AzIV9-ZGUqYO6)ZBe4=@Ke^%)Vh|xBK<6ndoStMlK`xRc2aYVu`mA=wz*Yx{? z7E$iOFJI~o#HsNfOI281kgr$xHq;wSBpvwq?Qbs+*vxwG93D*2d+#sO-!%|t+f{B? zi>`!e#OIYdqGZ<%9x-w8wIet|Z?85H&?(_JGV%;I-`pDReFt$v)n?*dlEh*p+H~+m zBRA(i@a@;$Mj)Ojf3z~RFOvt{E`#Cv3!e}ZF9)#h8BmWjx;}*!FI=Z9&WWMlsZfZX7C4N%rOXJF-IFv z&h08jof$EJE0O=(%m|Wel<7tUKnR`{mt|^c$KK0^pDKH8Tb)qmnR*fTv)q)Q38>fe zobXg7$dyrMr4+c%=xZ|+|G~nSvZ@?TNSd^Qr@b3P0661(1ZWmOvrFQh{U?#w+m$)OgP~hTFLOI?FGovS{`(QKOkc_yIro z73!nHKc1J)M4+di#GXp|!W&vVB^`Uq@J;j1!>PSH3a)dXGWvnR5686ntS22TX*PFt zV|RW+U-!HDWS=BtXl+9aB~EK;c!pSX`7(rIU(#M5a{s|OFs%vzgKMpKqIr$(ghWCh z$eZexYo!KZ+p)h49{Nrj@6ns1y;r;xevRH-F5x=ds%1&6TySd1F^hI9kxG4oMGn8e zRU(E&H?`lRQUS_My!rj`|IkMqK@*ssTg}(|%*v<)Nb=)brxNv}tg7w{lvQ}(@w68i zHr`n_l^0Z$dB7bR+7bvn6+35+U08kO6*>@;FMNv?H1-9VzueyH`5uMCK%q+rOxl8_ z3>`)-pC7>XhRY`6X1}D*$k3r#Ernk3AQTDvvA2ec1>|~U0V@g!aY?nutb81FREX(A zKd(bhE(15x;na#tPk!G`Ha!-@?sZig2-&oAu79Z=D~9m$+K-NAa2NPEYx@Rb{cYlmyvL z`IX(e?y8k{{N;8x-=(-(8K^tMYVfX?EDP#DYc8+X^UlJrMi`%bw> zb<)3}Uk;*S0n_e(h%>^r7HzJ4uEn9;uaM|)PZ;adl-luPlC3y>`TJ*_p^%TcW9B?} zcegv`GjM7?kCt2M=?&h`Iva6g)U1b)pTwReDNw8trPSB|kS781HFMtNX7OoqgFKEZ zQiA@#x{s}Hcg#WcUGEX857i8@KUAP^Tucl`!O$0C;NC{jv{JUlPkox;Lf}x`%7YY& zgE7T_j``pJD7bI=4LssPI^{Uh zSQ}@y69j?nH5C;VaxZ_|GWew*ktt1f#q%Ue8iJy zJ0BU_oD>l#ZhQ>y_lXH`XGILoH(Y9sCoH)(+AE>HGdllT-6K-2kZZ)G)81d;`*h#= zW4LRo>=@Cy_fxGLrud2{x65JN5~m&(%U~Hp+8_|FCuXI>T-u@L?<0^k3&a*LHSzFL z+a~ccoZOiv?QN4qKL7cCrKg@1N&V1J%ryeh82|3|i}F81v6_6p|4L)j^zH?6>+9=3 zAGN3ckRiUl`Zbo3uOEnhPfGXq$O;f~cagXTJ`o7g&DKgg6QQD_otvMZE@1|#G7$TD zUHgsbtY<2ViuT}@=Ksghc?VM2{$czWy-p<&p=`;B?7cIy6Ov6xviBazC`8$g6+$VL zy(O8)KAFefBV?ZJ-?!iU=R10z^PJ~A_kCaA>-t%KHSG!d5)0~Ie|0x&i!q}a zh3RLXfUn0j;Bj9;oBg+RAKk4i1K!H~_GlN4FfJoB?VFQ60?w-3iPCG=udA}_I$(uO zC_A@sZ1ETGk=|CpXY91PldAs3aG%0~Qwe#(0&Mw9jh` z>N>BjB$idESn`8HV7#}Cf1qbG61~2CCsK{#cINWS#OrAy8>5W@X@v&`RQCKD7$}`h zQXJ8s`{PYpP{QOjG^KA+vgIKS;36ci*$ zKV5HY=i~%Dj;4IOLezrKz}Bu&Wv6BHh9{V*QIAYa9E^;Xm+tzBi&v_|!9r=W_)nWt1h)($2v7#k=3t{H;!!I!l6r}eKOlmY=KU;nx|h`xf!G6w_1dd z``FN6qMa~2Oi*-u)xXx3yv?7NbkDo~wZe~OoMp88>C3V+7~6ON&w@8!A{w0pI&LJPio1A}d%vfndu#GuAqydsiL8Ke4@-m5G(rq+<0M`nXQr1B&v8~DPecvjl z>HXFGo(8FgfCecd68gU_3}?D}dUgJXsd4N^l@?e93YgV%$}`bhW-cqL9Q~cY3Zyrn z-SC9UW#8fi?8*a*#Rl9|kVTJLF!YUdZ&!F!1V6Cxs~h>Jq2*N{A00m#fa*h;34MJd zGd;c2ZMOB*(ND$e(Ad^#Roc{)gsY2xPr)Grx$ge2@@(QrxRba}fe#CyOvlM(_wCaRT_Qyw8pWN?wGp<%nR z(JH$!BzLxZ$3HzGcvGM$`NSiPmUsHUOI1W@jm4Lpl5BJyUP4wa6}XWmzex`&j0$Uc z2@j%we1aExskC-6Y%d2dRdR8>uBmi|TWweVoLBj`X&gs|Q0P z<*hkU61QgaF!W*$hEjkj6bg%^&QC6*3J+4-;CY6hFl67|rK1^3R8>XDF%^2$^4j-$9d)n|?)d9|h^?JN zh4_?Tc6f1Iv)s(3zL?A0H!}IIywA8_aB_Z^G>tl(EUNX+9TJ&@tj%V%2=Ubgxn#8B zV)6PBSOA^sHY)cNmi~xk z$;6XBG%?XQC!eHf8{NVM{b^Q)s=Q=6iORi$1CV0Z#T_)dUDCPGj#U!WUv#Y$6BJb9 zF1*MRbL&mIOB2`mA%~sXvbO&q^dk91rhMDS|B@OYQp;uEF@Ve(s7-|Mi8oiZFEb~{ zarL#obaR)9vn#qqx&FSNP9(4>VeJyZAsbcl6raCDI}d7g+ZTx^cOUqW8hvCr6?bzc zE1rF#i*3h{_3SL7ooW^-qxonJaCF`CYA2)>g9*J!&D>BDog*zFl z7oDrkH1dETT{HPY)_Lt$cx^2T&s7;&GwBE>dra2E;oozqbjOwZ$u>C$$<_wi#?Tl! z+qYQejCwkQWIbVKFa`Zh>M^D%vQS&8H@3Cr>r4R9%D48H>+8Y;&K7Rb$skQZ;R`cilwt~N^e69@j z*SpXVtQN<@2$MER`l}Jgcd>1>1?-pFXVrL`LPufY7kcw@=GBCvHmC-Gm1t_fd410E zOFCmi9e#iJ>plf6+AF$V|I*}->;Epm*Nc!9yy;Ol3C&`p$U(7p2$=9gW!?k!pS#Q% zye~;5w|}}RV+9O+x?UtMkKJCcb#iR9urG*}U(9?eyWOF?NgCt1-=m1E3_PtfJ0DNB zQiSrpl9Iml{f9L0dPL%91j(5|FDd5Ie~8e2SX%>5_ao4zaQC;{X`uSIsJJ)gfk#FA z#_IaIg!lXX@67~~vA4Agi;M3eKcQIF_)U_B=C?Z{{WojWh&nR3YnHdYCmg-Bw6;nD z57U~815vCp?$ih-h2xg~W8#|`ev+BMC2-ytAAv5&4cup_FQ|rnghs}^C=3v~18Tog zAdEeRJoHU{HjrMwkS2XyyZ-!@ENq(h`??P|s6V%sZp0tF&fs@!u+ncPxr&?mZ ziMVMq9CmtYcQ#^+9N%44!X)6LrTY1Y&qn=s=q=TQSVN6{SMx?p{q7_8@KGUM7Rb+VHTxVNTpd5^`Y@#xDepkFsbaj(Tk?-1T0NY`{s-r=c5RMxV z>?yUc!pbLKC6tx<+q~hnOfOQIk+kajC{rRL*W_i{8J*bu&D`1y3nII0>NC5pfuoS7 z<4GO{|3A`(UorTpy<#fZ`2XhIZCCeLQpd_{%v@TpuUaW3Et>QGjgUE6EfO)?THk`5 zMDD4PccvE0HTR^b9QN!771%|}+u9Tg_ufu8;&yiX(xm*93^!LlBlqjz?YJIF`%LQZ z__~whRQ69|+q^N7}7Mj2D6Foe0;1uN7 z_wwo#kmOlZprP#P%Ia_C_&wRr4p@k!kMv3IcJEC?RTA#_D!skm-`Vy|?>WBA<<-RR zrCf%N3>$hKW-erAaVV(o889j9@VD)5z?8448sra-NI9Dy zE47*tg0aKbk{{uAm;0RT?Lic!nZ2(mS5RGlG;SnQw_6z#bFjDNMytt6{;S~ERt~#G zG~gtC{CDE|Ox!jSSJ`yohhuteB_U-m`sVo9K&8Vt9PP`Y*p(!LAz*I+27h{bB{fTJ zpNnf9zheW}KDB51u5H8A$+hO0O$elxKjwaVJG83aynpv0I@s&eT1$rnT}X z@PcEG)@n7CRRO{rh^w2%3oa}iF~z2H;69f$^3olD;31}MH~IJ5Hr`If8#s*jqBN<%)<+*Xa(r zPfcs8&;R;SvQ37Ei-i{V($PDekL_DTeJr#U6B#8t7VLc!`PJf2i4W=Evt2-#qgdZO zf%@8j0I3aBn&v298_dR&tdGj386HrK0Qw=mldx}B=CD)Cuolo&J%v}{JZF$};T{Ar zkN?iUfuqIPcx_O7i~~aUf=0o_ui@dobg}i{Wl6mfj?k@VV@C9oKh-tjmLe`#U1`Ka zPtTTXchoW#Y}@xpV`Kuiuj?BN*!0e(@+O;jI*Mb6g2B3QDU6pA$%K42Jp6d7DPq>V zm?1dV*ZTn_*E8|(i73Ox7M&k88sGLV&|K{45n+$~^GkJ4U*H9OflP)!_E`rQrCt zHv)i-tHZsi0ztb=R}kM_fXDnvS2f9c+yb;_a{SOyA`(%xO#*hU5s3#Y1k~)fxx$@N z#c#{Pc~-m4gfAl<*q+<1|0C^Vh3~zBYF&s*gC*S|Hy0 zWR`sV_y?gSM9JhFc`c?WRDT(smun5T%(}ILtu`_Lz|DkJ*#S6ubZ5?n~$K6OMP)QzL z)$UhdCW~!%zygP-0IP1p|8gHh3UMgK@XAEklW^Ok(c5JqRbuQS7*dK?@@ zNL!=bQ6JGUaepk1VT5X+dL_lel|e#T;hde8vx;N4-~R-lBHP~XCIpB~Dtx>kBco{2 zYyXU;GIHq-Mo5=XL|eHYOa2;BumZC-l%e<^?of$Tso`t7E3xT$|JU^M?Q?owQdD5a zvp-Ee6Ze)*{o&?0~ggPP0aB5jy{^Z_K^^{rr`zkQM19< zbLo%^4a;w>V}B!P`}mA8ExJ*Ks5lm%wO?(Sne@-G?qVk}u%SUPb2O+v=uI`snzA2X zN(~Yi?M?k~su>jCM|teLR~qnL?#nmoprh4xh)@GX(P3N{8XUB>EwBePPW~U()i;%` z%ZqtLvTc4WWYUF8b^vD)=`8O<|9C8{_!}G2pO-pX;Rl@15>*HPt3loi3X*BJkgK*v z_r7KM1V{Az(Q9IGHJU5yr8GPV)U_o4O6$AUJ{?3s!v`W_7!ih z+UWbqf0?q|u>9FO>;|Rcc7l#(wtO`x40RG`oov{ha-*m$CX=kgtgaiZI6nS3Yzw^l zxQwfVp9(D+--~7l4PL&0$g#aiYa8*|_GVjkLxUN`ZN1izV9^+;@x*bVuPO4qyYJmF z6>UYU=d;+GBL111cR}sLg$%Jvs>tjsR|l>AmbR{boUmYTD&WNJuZvhWPSpG8biUJm zR5C(C60zC`muKb5K=9H=9E9vheul9pt_)=JK`SwL&OqEw__N}_DT^FX0T=IclB3Lc+UVo_5}uo*m;~D8oB?>rvIW zoSV~k64rcv^6VS&Y1LlpC-p%$S5i56DXrQV5XIK<$F%Vk6knkR;qpeC`lft*o#&16 z^a2^3f#l9?VNHHJXE|BDPn&oMg?A8Bcp)pBWG(l~Aq^UnoB)DgxM!<{`1t3()7EcE zzuwvI0BWlEXm0#?=o5J-8VKlu5n8IDAI<&vY>9s6LrL3|n z{D3~*S^2(oUR~)R?2h(rL6hdXY-wy(^79ER-5=rzOLw|h_j^U_wK>%v{T;A5GU|n& zYi54yWclsW;S=)jq*&Ca2clj-+T4?RK!vRgSooI9Bpl~MWR6;TK|n_!J(4LEfsfZ0 zdT|Jbj#qAmyZkX<-kc_+UtF_! zTeEqMHq|!1hHhL>i6T))%LH{+v2#Kn(JUs%Af`BbH2BWXposc`bWM*6+g)*QXB$S+ z8K0?A^_Y2IUte`hg7pO^UXA#hS<4sV`1nAINLr~Ch7?X)o6`6!XWnX1z+sU(|qNm%*nxB{Js_&9g212YNQdS{4tkj^96k% zJuoFkdb+#o>gx7~8DS!2o-P&_KIfv8I6vW3-ua}q^O;tb<6;0c?VPVW)ES7cJr^KW zq(D)H&Vgn+oXWN&+q#}EKBhs)Atl21h%qe_RME@$<%Yq8kv1?0HUTUz$7Mg z3b|G0+8pY%Qe=$Y-TwPqN6oedqaJ>6d?lhK+1Qm1@x=(|3MDPp*0)VkdCCGA`gcSo zZ5cB`8nT=w!Sf@Q1~pOVBwE==JKgCq|YXXSRf5fb>#g@3fTI-zYlL%wM{_f>*)4kLj9!N)0y@6IIZJ=yZ+9Aw6ShCh z3Oc=%y!~nwQGBc7`UZSRC86*T7-9<*FefY>yop!vrl}Snh~Rnfhg3V~0{Az=^p@@4`xVTwbtD z+K|&GMO*i_2 z;23NQx3l`#RKN?+Z2q;RL`x6;${koqwaFB*9i%{bZ&WOUaTy-+j3y*uuC=mW!%WL9W8y(s{GI1NloyL@;mEU5nGUzy%mWd?`W z&4Ld-B;Yp=kj^sFPH=z9@32E?GJ-j!;~=2d8}g8%xG5U6t>09OSqG`O7}lH}$tD=< z5Ha`zT0j%^E0}c0yFPRjHiwn@#f622aSKyZo7+KyUxJzl-kafObkY(x@|wSQNg0(n zrz~>RNXxW$hF_ssrIHG_5V`q_LSgUtph9y0SBqm+8WdiJs4~B+UMr+2P)|)dOas8o zGtgyPGM$RfKgis?sz=x-v;M1_gM0PGgW5>jprG^H$^NYIV$S9f7SAdjn)U|KMMVx8 z8oN-6(DIM>wY(3-59rDjIkgZ*(lqsSQQNle)e&QiBx9);a*u|gb0mY_ptDOqJ*$pX ziFM@wyA@_!$$jSrTEZA}Yx&vYq4zToy_-Yoll=Z&=D{ezukmu;rn93GVqOV^{q$KX z2X`o9=^K|ys*drqS*;%W*9!TX85v?h+woe`YnxL+BPLCvhYPnMDKxTGw}po;_b`De zZ)k8KtDXk7DacHcKG_;lIq>TU+;n3z^WRoPT+yA%qt4S|byZBVHLTY)TmBP4e)R{e z>{@N3`)XL~w{H2XlWgb-jFt=yv957Yi%=95&)M;G*7-`V7R8t%@^yP|=@&*4fSXU2 zs>im!M3@A%?C&o1K=%!|zDJlNkp>l+SQS}p?~lf2R87>v;I=49Pfy5~*XZ9F1E8KUNwgN`r^z*{{V zwLCBQbW|~7Vxq4vV%?Q6eR5P45MVL+KrBW+SW!E=^%l(2z&j*eGQHtx<};MoPA3vU zdQbc0@T6WjYQRm|6O;Dj!;F4dZjU*)721p~x;K&d5JpV0XKplIb|pmzz74A!+)&`| zzt!Lc;@pre=IJvON}csCS`JA%$D&fZSxa-inssLVo$_q2K;{**prE>=-8zitz!IM( zWJf9YXWi`d0H&1O$!gl*_q?UxxiJ;ScW@jc{H?h0s8%Ju5Q-1DBCpq+MITZf@ruqy zZu*zHN{KG%aKx-E_j1Vyr$5MyP4b@_INvY%%%zjT`z@w&ZDV!yFzfvA9xMVyMf-;* z%K1GAMB&GefGEtjJzLYqT^a4jI@>!=N}@A69+wG|%ZBW2Z?9&|e7;r|H}Xep;2tQa zo>?L@o^=Y^d%g`@UyO{%zKEZN&QtM7S5#I$pZmFHHMr+px`lfe8%6nc@V?U}^bGoY zhr|WZCs&5>1UOO`W5Zj}yYFP1?2g0iX*P|9kn*SA7D!B#ZHKTan3M{_S*Cr!zz{ zFh30!4J9Q)W_V47)fNv8Ykr3mUW(~C59flQQs0HtX`!z9lLEh8sw0 z@FguOn7xQNxiKy40ozbqFylXJ|1G zI@=|;%M2RW@Dx$EMTR}MM@K6B*lNV}HsH=0O9yG9Y_DIp%px~%mt$bk-TU%UhLux4 zCcxsqh%PCO8-|U9UAx?+dnbl5X$QS zGgVe#Efei3&bR)BY*_oc>He?6y3Izvu~N5_v%ZzT6K*mQq*cEAWrc;1;F;PzS}!4& zGv@Y^Z&`rY$1sOZJ~9MWwt~<4GF9;1=xK~qdd!AVO~Sbs9tph)8yF{#i^yc^)UKGX z_L!HtB1BC#ZB?;5)(_#y+n(rf!XC^z1qN(|s>CO!yG!=%vZXu!Ah;?yI!z_45l;%% zcrH#fbjK?F}=Cq9Q2#fcl>t_A_*o|K(t}x(WK&_VxY9oN~+M z;i;)9^Y{GJ#NAGY-fcH*boCBBCNB}L4W=EfUWpnut3|+ zq>%N3xwcqDsHf!1mlRQ#Cva}(PX(Mzy3l&4Wupq~-YiFajqfDDH zvdlkK(+6fEL5FIlB~_n4ulHxmBfffX&w-;`^6c-tlvKm@<_C;mI+>Vt_HJp5m7*_c zpO-o<7to*hyO@;p29(RUi+#Ei$!4CW$~MPAC+$JTaB6_pzX*1mWLxs8EU8>*umctl z1G1sc z=ptJ>X;iE9-Kj_qn3b>G&MFrcS+BuVai-lF{qj+QB@;TQt@3PjbpXJ z$b8|={lhg(+IXoorl=}VUN4@UP1Aqo#c`G6nYN&B{Pn zV;3Hic~MApm(;Fx!4_HBYifJ<;DAI9iI*Z}M}oJqwT_)ET^~?pkerXcZCWC-t5@lO zwL*ons|Ey|!WL;KFWD5Tq@%&o<{l$S8Y*f&y#Vsda{?# z*mpZYZc#eL-!LDV7oHWb@`{PJZ2 z_Q6R#M&~A~%XTIXJNT=OPl~F}*5Mun{(Z^Nc-EHYSj9<-^qrW37IGeA_drWaOE`^-ZjRYx zDZYwopNAn!x{%!xtdYyzV$zdeaqtg(7iML~e#WufVCokPXpN-duKyFVfvr0K6Cndh zFw5rBFS`8i?zf4NxY2s`Nj3fPmZY9vFFsbX@WRh!BwwT3IdOiCmg*6`3sdhWR&otC zKYkuz9gkNT0)x)YGEEovkH8zp-X;6JRK01sZeigzEVew<#5a{!wqhX+QEUrm5ICL@UVLe%U1n;_vkp#r=YP7C4>qQqj2>~(3u%xe@*Z{qPb)r$9YpA?^OK>l zqu<%0~+KhOd~603k|O&kr7D1Q@2Ou&2}K zr!V1)*VWVcSC_({>b=v+c3Y*eq~yFH=%}i}?<&RbU4ii1M)IXGbOy6DG?%}cc270X z9R_K4@#dDmW%0RB$|3`fRtqW}%z{omyrxf^+y`!tk3t^|$u0a$Z%L(Bu;{{91E$Cf z4%}p&Co2C_ha;AiHbRW#)=x6Ivz_FElDf@t5D|_cWqIUKb-G|QeIy)ky@eNj6AAibyXQ>q;EVM_J=uvB-+(VWj5Z= zyFYByWc0D>XUB!WCN|nla>eZje#ZbrEOTES1SMc&tgOA9_>NiV1LjOwT8JEdpI!3H zVIO2z3BX?FIT51%GuXQoN=jnkYr(5QU^y{1wh!c!5g;?*0uRxC(9Bx#eCT+q1h5nm zh`*<2V3L^c&n}h=@NfIr@nt!jAssNbx%Ogugk|LDdBuEgMb`BpQ!~jP7u9@>I`+z(b-=8Va_csMbm+ zCyqU7^XM>l0d#i`eI#%8U5T2j=B<$>!h*D$_|$_@2tY#96}HP>)3GRfLnF?gNhqAwh#;g z-rE}mT>0$|w?oQ>iqJa9Q2 za5>-;%6`yM`3g$G`bVgS1&c~bw#qTmY>__z#L3wLA}>o1Mo&+Om=3{(URx7~b1FIF z$+wjJ)k+QTZUO{TC}|X_EK)QE3l7>G#mg7*(EQ`r;|9|#l&S>@`FHAnxZl3}O5b?L z#|CvtoLNv_=2xqC5|8x4qVRgsy{ng2T?BCfgGWLq1MxLIA%aU zLM3sKzB`D#hh+Nc(?BmLi-Do~qZVE(12N~B_r>d_T$VhIdpT-rYd1;dAdDucF1lu9 zMS)89WbagWdhe_#bp*tzq~&CHd|0wF#>Oei>d8C&|Na4g0YuiT`1%Zzt_brHOQouV zJYlXlBXho6cU9)31C+tCC#_dt5TA+vrP(QAm$mFek@2@lYuHp-v8$&({vTFZ>`+1FIkTkKGU!75MUp zJp#^74*OtZ2#s9s%F57LA;6}Aq9*8?ckqAQsk#Lh$Ce$L5>bbKC&`O$EE0D%oc zV<;+AKQrthSAF9pV%_F4sm zO}W&QqoxoG(hVFEHCZlgrQiPlElSJK?kZHMqx(GwgApL?7*J+l>EV50KQ;*X3KJ8~ zOLL74MR1N+%6*rax!D>;HSImGk^KOWqzcRd=WmZs!upB=Z_YSVnGybp&pPSgjfNF= zxBh{V5qkFo0JN2WE`$CMgBP-l6omujDPSdUl^_;s4WXksY!=gGh%+t_S-g&hLu8NR zn6%_?^N)RCtz+!c~fup4BG+H2Oad+|Y zT^af|+SuoC8oq>NGKd2UOkeWgx%&(lqMxB;&J*>`$P~3jh)deZqm-d~*7^NyYGQmu z0E*+v5+7|QkqQ@94hf6SRnpADQS{B*+@^P*72|ZRGQ;aAtN%$x|y+tfH7^f(t(T-@w2k1H%7B$L>cL` zQ85CG5=!s$S*hb>odBe_#oUI$5?gP|!}PC>%F%)4>%`M;(V#2&+XCRsTx7<er4*A51i)?_M_ia-Pay0H-zSZMwKS}f#Vl{xHf3aHD^&o3*B zKO5nzKinh3=c*DD*L?h->_N1@TtH2SRF?Mfeez=+cSdBc3?a9A3(X@J!^t;puW0E$IyPPlN+{5ZTe8N z_PPXf=xCD0_ezH+s9~@p@h;h?In(C2QYog&r~jjfq~?Pw6cJtI$`IGQ>}>ElQ!Idm zSkp<>Y|}E3TBt9faPjia=qm>-f)LCUw52l>ZhZ!g{$hxK19T#Y%ne?wvmVpSHk3o& zoxRdRN+{;0Luii{yf}(L20u<}-mQmM^LvvSF_Ng9P%+Jsisj7X<1i}Iw;nY%aU4g3 zy$&guc6qnm$id{gc=Q1i2OgU0q#R6jCG`~tLNW9I-p~*o28eG(`ETj@XiS5tlb07R z^12AHWv9WGN5qBx5<~|WwwK1qFSw(w8 zO4f8+6l|H7!Ria!GBXe_Tl$;M_JgE1tLK^Db-=2?q;gG;oifUWb_9c&-#sL5>7JnY z_S)JA&Pezwahpx&FXm&?yjrg(i-=5DTeK*Fy8SpQ^?sX&NqY)gsCR>@21YJ>%|CEq zY3aIR1~y?(K`G)vmn%;a{1S<)$-R1g*4eYK0tZF#V*9}L9d*o(uVnTEcKXFM!b zzkW@egYY)!Kuz<1M2kmE@^jZB~J6k(^Z)ntgP)IdPIQ(I}C@3x;@iw@zqmLW4(t zDphLOum8E}lfT}vPnnC3qv8aMqfc-h5rURUm) z2GsO?2(*=2&Q$eGk6|csG;!^`?LH6-w&uM^hOpLeHCNnx>Ddjy!uZHfv$Je5gJ-W# z_B$&f7daDQXiC1V0c9*7ycT`BEf8-NF1ow|$n`V>k`T$1m^f7Fpp_xc=B8F#Y(ztBcy*?fV@*n2?H>|N#XlB}o{#j!Pkw-(>f*e7X--R|R{*SHT*Kj)tsEgiIu)%%QL1UWpMSO?~z&+>$bKK?J(| zaxn%ZJ2n-5CSe3P4U*@s<-N5?>9oR!EEVLv)>l{gG)yR3y`~Jjdd1Wlrex1#_NY5d z9Cdys-uv_*#Fa;@%!c0(o&2g_fDt@vOf*0#L;_|PAX{VE4_3x(&c`v>7VVnL%!rhv zY}-41yGho1j~>B5m1L9xpXE=z#kEk;P*Ih*3CAjnlvRE+OnDmzMo2G8;Z_Kvdd7H% zi!uGuy{8#p7KFQ3d$WHnm_B;Z&39vJN0Bl&_L}%5)hxz*9hIXBcWTAuZ zvJ36Ei}zsdGv}>-Z`%xq6UX{*hX4{-o{yCY1aXl?A+)H4rnE8C8JFP(IqwU_vZ&y=X3~EniKobe1RZ4 zU5!AQjcfO);Kos0dA;>mxUK7}c|NW6XDV?|zELlEtHgP2PKX7ao!AxE{D-(};(Gvh z@SlOxWlk6S2<|uE64LyM8-kEDC#awGJHp(66)~Emc=>R6_+{wZxP;?i=PfwlUjE|k z#e16>7w1FmAsOvJ`-SChtQhbW(WOx0Nyy!rR|xOa7zIf(t)HTsf^x`q3&hS+njPQL zg?rxTrxk1&?t?Seg#mkac1PS_B$$+W;g8!xgsi@Asr_XpMDR-@lEDbw-SbawKmWAs z(1--08hN-jw9|8P6&6f;t^F$V?<6NIl3nx0bE9VZX%RE}Q?O`!{OGaZO=hMlECB*j z(6_R-MjUaxYR+L|>GU;W^%dvRS4EPMC7?EzI>=FN!5L$;67qAM!)1Na7{MNcvZZC1 zqXhGHM}LUu?@EkKnmYOX5{0AHR7@ajI&MA&27sNGV^idxnW25#%&A%R_BO&<5ET}UHW$33#vzOT#P z%di)dW#Fj89%;I{D1hTTrwfi6+kw~E4<;b@N+4ft^w`KU$V zu$<~e(;YVky1~YZzg$|#cDlf8iSo2_Z`tp=yRsnq2eJGb_%jbBL%su36#3&VLH1A9 zP|{FR6Z@;X)JOzqptXer!06$Jv+$c5w`Id5J$?Q4?`{0@4?nsx-8};QNo3MolAj7{ zl1YvMo-#?i_bTGw970Lu(u?gvzUzF0c+<7_E|IWTx~DJSN^O*M9jQw)PVvowrutSx z&=vHY`pptBI1_-6c4aEy?z{U+NaZMbOzZ8(N^h$reJmUYqSNH0l*d{D`!l1f8kd{2$unTc4f5!%Bl@jG^J@ zG;^6xK0o?>hsL}!t`&A_An7h6L;k=939zl^yeX=ANjzq7=sDQHj$pAy`XgVTy}NZF zd$V0U;67}>6(jXFTkQ_!#K)9ka=Dzal!zbHw-k&n1Q*jt_T38Q!s3J3<+?%kB=d!P zqfJfM=@!2Y!VNpO9?F8hQRAi$)Nn4evTwu<5Fnu5U_kJ0;=}2{;|$=>(G;Zb9M%U7 zXS@6Yhv&;h;rS2ji;YiO^`ki7y0}JXdeB<<;8!}hq_m`z+0!7MQwU^Xn;|~&Kt1ld z-2FR=6oj)g&Cv7`PK$JSZusH(&4`+VgBZZwC~9fNTC4!lHz%}zHpq2Qg$>d}`b|5D zC5y+FBsqlX($wI1dovgB_f0a|@DV&La)$JHOtSWJ(6TFwFrr4}(L|2HhE$kwaBS=a zUw%AH@X^)>U&LU(*g{Pc&V-cH!N?gT$(;SYm8l%Z5-z8Qn>v;~lOBJN@BtG6yX9L2 ze-}3YC?}~hD)ot9_$K+y0Y8GOijwf&h{rvORpJ|n_wt_*!W$RU)mfMNvVsI_N~*V) zAf@bwnAtt_&V)=Ilzz+}(+E#6gH`h})9Z)y(!FmJV*me#x9C{8dgYI$_AB3)zN^)) zdl65LOHXKiI|VzB$2jmf;Y^NY&}rpJk;>$!%LMFafkszYDDU{ZIblu1=@ zdfxViA|N36@qCFXapTdE(qC23IGa5X7@lxq=R7 zS{tJzN9x+*0p(OH1IdkYo#nnPi2vr>zE+r5f#|3_~4vgl007+Ci<4 zVr}uYIX;b+$|6|!YHJOnw?RXl7#PU5H58?tf*S_#ot%MDu|F&}j^lM+ zCDsN=7sOZR*=^h;&Us1Zq?PBxWL;IsV;AQh)KEOD1|FmEH!e(M`xBmqdRF>aayi0# zf4u9j#20{vp_A%QnA{LZ6|C1*n|5uQ46A2C`GTyL_9S)2Yc$AoH+}r56W>IMN4gB} zz?2jtL_a^3*+@Wy^KvhTBb%ZN89ue8;=8+O-}Rzcq7%qTRhC!if!@$~(uLCHuLwHN zEL^)8i*2!-;*BmWyb~io@QjNTshQ5JO{$=$qfMca`OABtHCgJY+58JpNG1*;FwBdKkKe_l1WklEiw;gs-uR~@?;L_J zj3W{@`OdUn)yjB zp-D|^h3jW0%gV;wRV*sfPUh>wP(Bfq1H}iVitpyOU!e0me+O2{@eTD}4AdfE=FPJh z-!zeEnGG~01<#42L4M)$bs2Al;QLQTOYdqYoai;H#M1z`m6SL#WX97^#ObWOuI?D- z@#&H^+tC8Ou%!n+0946?gDZI`Ugwww=kdk=R)IvsJH<%xDwn2qcui*x@-80HIA-!%Ttl3!C{G)eEfE4Z za%~eMcsErYe-vM7mu=2BYtge)#a1s&o~~B^fUCXV-TTB{ zi50Z6i~j|bcI!XVJv_w&jvVr1p>J!V*~xxM-~bk@fm~f%EBy3HPY0MT!y`ixx3p#d zZ2GNBdyO0DZeC_n_vfIjn56HvNS=F00lgj?80o33qwl2@W9cS!b>E&8G))WDZSg84aoFD~YbJl5@wnzHra0qb24Bh=stcnjmD!R)`aZx?LHnA5H1$Uc!m~vE zVQ;BMpk_qe3eeEFOweq;el{G=@uosZ=!I-+V}RfJ8E(jJxko-21kB3}GKZsXK}Pox z`MMLIeWji=%7TD{gptRfhl!pZhIf*_FZzz1rqr@)=Zx*|`FwAaC+zP-6INbKW~rkd zIFL2UTwAnPbEy%jKqm^7-I33heg6a4B>i5$M;mfqW#}SOgx2XF{i$?_~X|x z@yBmp5Ytdu)4sXQCe-63-pjkUfvxOCNzpI~+CF?~Ygk*{h&!w8jfpv`J+j5v0MGY= zeW@L;mt6C4z28W2+b0ab3D;pHBT;8~@LTnE{60BrO87-Yr_~c2QRLuu^$<1+aU;;F zYeVSeb>X&G@`zW((=biXUk%JEVfvUQi8V4ZDkA@6w*O4@r%JQJokbjxyUFKIpW>}< zxJmX|#b+k(8|x6^5JmCkifd_4L~{Qkt##V+OW&YXI}YX+%hd;oLX^G ziSL|)_*37qsOaf*>hh=F2PmR>^l6}(C~czkz~W9v=@Wye`ua9Hn4AY6p?1VD309r_ z&)~`USt%|qVOMCUpgrfqlp2k5`s;19|1|e=+1%aUKi;|}(_fGwjF1{~ovQrKOFY@{ zO)nxS_=u2G^Ra(iA58)a9#f2`=vRl!Fp6q-p>0dI9(%1IdF}Ot-xkB=hF$6~i}aeF z0o8px$n{kgfi!O|XA_-%LFbo&-o-5CQb~dME`0QV*ivQyYb1@VS2^U^KEIQ=wz>-O zCE%C?1}w>%$E5a4Wn~O0_J1W^dmxkF8y^;u`>o03ejg^(T$1~xSV-C=Hgk!TtRmNp zP#T4qiBUb;Wz=)`Qe8#WorZrk=2!a$1+Bf0vmJRJbL#e* zYDFvAph@XyruRkGfbsln;5>UA6z5Bqff~YY?AoZG`Z8(UH2#B|O>9gi^_(<+KRi6O zvJUdn_&#yq+N-Oo`e5z}x&NSgc45vA9?J><->>;v-uWS9Q-_n_kloWF$Aw609Z9E? z>3UaGo{gtO^!d5xB(moP)!~9=sk19zNvYTq>003I#G*-1p$Xt_8DCskZw@qhy#qx0 z5XjQ5qL|DFks$fc;;FTj?fSo)E6P$oGikZqddG8h*6S~*8j#0CM3a%4&lhpvoX47; zAne4@h5fs(8ORR9u5jyy1B@-FZEXc5ZhLuZe(A!ORck@l#71iuO5%)%ROk(p@j> zUU9|!7J6a=35>q=qD%_v)HFQ*4Ol;4O$$PbK4@~p>Lmz^ZC$!wSLnwFpFBxPrMIo; z+MTvvgR^hnJ*NzTHE#cI5cgg$jMp5DX|m~XyI=Ps6P#NEzFr`=zWO5+72?es8wj7E z?e3qDH%Wq>iO*jEM+Jy3z5}9{`7kUe3T-<5u_1b^tU70)Ii&>;D^yU2_#8i; zWqKxJbe6sU1fBlUEP4DBh=K9n1M0H8IuVH&88=qbkkQhV7C@>=65`ayjW8e<(ERO+lCjo{vGfbR$rw% zr^e1)N4Ud5f{ZG7NU! z-UPTEa!ehZs^MfOm!=1(G`jKx9*_|$*bnpI!DZcJaMqu8&8%tup74~JYRzKw3?xSM);;e1+AQ}1dueG0QGBlBy$Imf6{!CHb*dm;-(C!E zK6CNwPUqi=hUvD!r~IPg9-UfbBRHSu>!wIMEo*$F!=mdRs$j>Dp#WR&M+~bfewe$&sW>Zx-7puJj6@sh3!AiWMrB` zymNjJVlMpS_~^8Fs(^Gyz@`(SUCSrvF!D9uGa(&JbFopJ%8Tj0`zfJCW_ib*R8f0( z(UmI3@PWB+hXY_WWumE7=IANu&nQWCCUA$ifZR`~^^%enG05c8$NkTuufJRt?^q(Y zByYT>pg?I0&;K0T!BjxxjTR1f)M(Dj3P_4dbtyWXnbhh>zLGpDlPdzfGL^3Z#PM5Cq%&il->BE@J& z1pgh)`WyLFl@l=>@;39^U&bFL3{K7Fcjc_Sof&FvGc(MHpA_raAmaY`bd@FS{iS5Bb~for(6TKjCZ zd5zn)_DP0>vxB7ywZf~Qh5?T+3yb;azxi%pbTic5=LR&) z4fy@!V~rJdW;9p!>CSZ_1eR?uRA3-Z)KROxceI*vAdO=gDjMM%$@RfWg)om69` z2;6*%`mWV|z!lLF18uoR{Bs88II&@HH)$HJU+1qsBgVDroncHaAecmwc{UqC@&<0!&*#r0U!7pMHBLE0(>;N0paFclc$H|B@pd6|8^#Xl= z&UH}GK?;rnkZ5CBIPZhy&n2Yb zsH*!r|AC<{G0$s(t0jeos<(5@l{86~&0fIGT<&9)P(0=;W_>QRio(qf&Qhr*++xK$ z*B5;e!Vy(f5VhTxJriP3y~~{;z{U?eWZGB?l65_g$c>~8T$2p@)kX=dwuR`d#d!P8 z0D;@R{9Na5P+sGEd1c!UTG#5A7u;s(IdY0VFr^C;hfoc|@mE7EdS^o&EHN*5ax`^3 z@wKh9N@vmW3v9O|2~?Abw*I_UUYTLGVJ#jVeiwKoi^Bg37@J&TWLnZq#X(>yRXYqM z{p!LC2a#1~E*amAUQ5olAz3qp?O_&kP#jrK#J@}%>6+f%4B?s8;`h~%1H8_1ihki{ z-Ec$`EfxoWSNf&CMGdc97sV4zY_Pq2N`}TTHN126B%T;2Hq{+D67%}3B(}*$*>IP# z$3iZFhn0A2dCrPmOdelGkd&l679>Myj7)_+@Q&W;G6^dfO4369lZEy9yR0qV+C1 z`icRzUs_un1tdpGs337K2ub8`K`vV*MP-!HYo4tJ{NnFoqn_0_;pFW02lHhL zJ@a1SMAcl`*mVfTkB!>pe5^*bU{AeG!Eb3``{PR%u7q>b`U5%S?oCw+`>l;b&)r9O z@vGlO4mG0PWBo&kCY_G)m-*|PUNbc85hZ_`b8Mk^Rx>NqqSAA_I5mte%S;;WrduZW z0;V6h%5_uyKu*!MvEqToZJfx1kiE~%g|oTK+QxC8e~h&?+zh@`N67^l$=OKfn0zhZp^IOe z+97IfQJN};2nr#Fi=2@G9ow*l52?5b7zM$J;jX8@O&=iwZM`Jzi8V%Fj`dOvq&Lom6W4;tF^k{&U#(sQ_KKGea>88 z1Q_<(yXXpPWDks=nK*)^@7NIh>v<2IuOocDm7wmyCFwfb^0=j3m_lgTAkznY9hzcn zvxwp7aB>!r6FKs$9kyMwDQR_@o9peOsGr5i1g$z+O%LZVy6Gyn$fZ8{ScyY8*woBP zs_H{9Ql(#a%^P;@#q@M-6G9wt0f5ZJ+`ffbFnq�tsnkG`JPwuHFc&gz}YOUO9n7 z-(3VKos&F9=Aa|lA;y>0=%4N#fb#r?AmQbyBt8~->x{n05u83-9Zt1AXI1eM1UK1d z6)vx4gKkk`{H)Xl&3x|~o_Z}lLxx>^3)@JQU*C^}S?cZtf)Jr7C7n1IrMx;urZ!T1 zhRx&ZS$C8UGTVGyWZJ-=AeX;`_dbtgnf1`|fAQ-D(#Dj;Q|fEGDJ z0Ux>RpqwCe5Sc9q5X}};tm1)2{Dr4qko9T7nAtWx zrR5eER~^O)0k-7^L0iW!4w-$k{lSBM5I>};7&m;#>mw6C1!ATX1;!=PP5n!s7{}@` z!h+>*kamO!wKlbEM$erML8-bHeqpx)?X`zFEVLR(W~O&<;Ub>kuo9Z(;zn^|){08G zcbMswqiILcEvTO4EFU=k-*A{oSGLUmp ze|cUt^{77zV+jE$HcX%9AAl6G)UuU0jMNQl1Ff5~(LlMVHgiyfj|)-x1db(Ss8K4S zj4;}V@jK!~-atQHB33ae9ow1Ed!_hLDq9I8Mai>{jCcm$22jZ6bLQvO2q;Iob{uZn zF$G^~HFc87=um&t>Djp?rJ@@rb|`|#*9J1wFG}G?%ut|Yp>>95)@!iDP)zq?{0hQ5 z$|+X<3$0>Vb8WJ)j-Ozu+ubz;p$&kUIm*7s7c$p=@BuvUqZk7PAnW(t$5mQs4l`>E zuZeH{GYiwx0icy!gn1RSS zC#3&7YgpTy>%N;iszJ48&MpBk6TTz!D@fkVBcn5{BRxyV;7Y3sJsh?V(y_r8vW?|v zsp1Iuyw5Wk!eZVx3a^amYnS%(^?AEj=Dtx%+RG|!?YM(iRqVhbLV-=6E0@@&qF`vx za;%2$=QnJpB>5d#YG9ayx3GT7y?;BQ>3N3_&iR$(uYlRI(+BTfP6HF8IQ@z!{hVi~ e&-P2KZHbI3glR68-uesyKX+%e(*p-w+W!FD-n^dx literal 0 HcmV?d00001 diff --git a/python/gym_jiminy/unit_py/data/atlas_standing_7.png b/python/gym_jiminy/unit_py/data/atlas_standing_7.png new file mode 100644 index 0000000000000000000000000000000000000000..592b06d9b6ec1630f209c5dcf3e96f96a08ba75e GIT binary patch literal 60289 zcmYIv2RPMl`2Hd3gg7M0CLtZN_dIs?%-(zNy+ULcAv=T|Av>E+5y$Kp*&&WCd+Y!D z{{Fw~_qoz_InFts&pV#yxu5&K-&hSbg*yaP1P}=1j*_CR76gKGaQy?t1+U1~Db7M5 z8;VM@(mMV*o0opU#uEY9WJ&DN8t=QfIVhPkgFZ7->#emMq0jy>*Stc-yuYBEEK zew z(BAg%-@iXcgI{$r#ft{>%EDe7Rn&X9gX;^~+sTEmT|E@`&3A68{r>NbC2TZ-b?$$w z<2#}sCN+x+2?>3=IXcPvGBUZWw^-)zrcgryxQR@Ww$O?G?(jy`I-$GsgIl+5#o)_j ziffB`mld4h=KPrL>gp<}*03G=*vsq2r(*_D$k9=}epmPVlXa{0%?JF#p3Cu`On%p| z>B<)uoRv$Ob=!z6{`U-y8pqAvqAKM|U z_kMyKEg*|nhR8|&8MmBexi0x{Uw`KLo5ga;r?l;HN9dQoJ8#d@($LVPQ}YLuoUA{s z8|{0!PWU@#SLgcfHXpoCu*Ikj{jK`{KayoB)x5{FrUTb^WdCqIrOQPu3U#B3Yd_Xw zzP*Z=*$Vmv8=fomo*;OJ1wTWFmO>R#C7!cSQX4pY7A^N#$l}dVZQ;Zju|J-(Dkj; z%JTfR@ z@6Z%{#OA*xjwx3=tS@zxNh+ygO9J!zxxemrCywpspEX;RZ zgR$~N3BLw`gSS>4p9s|cfOm_XC^>i;{a&#h=Cktl=F33WH`G_d<6#Ks$OQP0k`yPp_^-n7_n%H&-#w6?Td z{M{9~>z`xsPLX->FpytWTla8vq=?drs?{pt4oX9}ULUSkK9-b}B&%YyGo;&O{@~^c zA7gQ4FRqNZjLc#6m?`NksjyS@qGJ`<*;#*Rs~zIf@91^M{{+Dr}7pQQDjocLGh5#r&FIgarS+_*(d8BLlfKRq?Ixa%)O zLyU(@myE4Px|Q@X-}9{(JV^O?M_iZsY}v8uC8|m~Y*)vlegZ6!YE4E!8cYjL;kPrl z<=c`>BkZ~Nr&ojR!$vb(Tm-{sc)5cidm2-ezgS*+db&QGg5aeXoqCy0pY8PnHCNt6 zmWOS}gneKjZzz z?^lkH`N`M-bj`jle z1^>J~Mt%Q!e=d0Hvs#-5ADQ(xG_-6tmur>LhJ)13N%hel0$VW^yXI!g_6!!6(pxHm?E}k^@bc7=;lgP zuvTJ-m6EI`x!mqcPp@%rj$;;1oO|BjD`h_Qk_LdB%m__0;jVr1wJf71ojrEOksM@IZS|+;DYSa{*U8wQ_9*J-1`|`H5Ca|zl2fjTfR-UeczLzU zbWHsi#fF~5;X*Q1e?Q;N(a|wpEwN~s-0$?yQ(DyyeD{(`FLxn@`01>)A!T-Y=(w-EcOLXTTR1lt z%`36LVhAEeYj5w-rQIAM52iPY!|Tk3A$>J)6xXOZH&LV>*TBF4V-%h=8$~?W3Db>k z&&ikn^rp_A4*D4y8R2wt5n=dn-q+XbPWXK7xFSexm_=rR`0%LyidW^npSWqTJc>!W z^c?uD^HJoJ5>x9GsX14-ho<_MerEyEd`Hj9FZpx&!Hw-W5XLB*No$^7kD0+-Q4`Ml zjtDq9u29kJAyh2jWT)DK%Pmaw9sVn_+jws>9?>vGy?yowGVEi5;gg2J(Tf457(P`D zUFgYzc+ipabVDLGfc?0{;papYqCoQBzN7-QSgUL&7%O@jYzm8-7H&8_c)YaTqJr^m zF|o26dPZ$3IX_aPV*bM7UARG|)bARj$0K|^GT5z0n!y8KmT_Rn#2-Sj4afH2J6{m%z3~2oo$gM2Rh%Omjb8)hi zOmgQAV-!!O%K28~e6`zrQM%lOaHfi1RoLZa=i!WN!X=n&$`zi_AM(B`5|?#rQR@@e z#pLtRXZVv0bdP1VNsI5{@o@%v*|TZWx8VzXOcA zQTlf-l_uj*mbCR7Kd}2QE-nzZSElpdBpdazqPcBhfijDn`GJPQTVO0gYG|{VdWA$c z5h2eSE7!`VCSgjVZp&(rvMsCGlzx_Jm-^=&2eyIoWQ^TEEh%BqBoDZn5NL229KO!3 z2gk>ajg7oS`y0t!?;r@NXL$KH6(J|8L`3m0q)s_Sx8&JG7=RYR%W2P#wx+>XWMyZs z*{Q0i;6-+UyfhcMQBkJjczJeM)wReD25}9suc;KzBs%o-GqCMf0P)*W@*ER=%hiB5Js*Ag<04UJhsr1rYKebJke@IYB=!+M2P=zJ6*LpBdyalX+3d=(%?$*Iqu7rx&hMOSs1_cEf z8BuRNaHmUu+5Xpk4Q(djyT=T%ZfP;P3}uSNGe7C)8rmm9!4Ov`$^YKjOlFt{uKis= z!O?V*p<)?mTFKBHo5{&ZgQ|%qN?J}%54D6}5NXY7Nfju7*iR@Y0Jq<3< zSp87AJ@5Cs^GYVX^Xs=T5ug1Y$>ZkpE-s=3kMPH4e`1`id-`YId7fpW=VytXUE|bgtpDPwb2!B*t;erB;Pmlx46hqcR62@jNUdKrKuwIzWAddl1oQTU6gB08Es*Z zE|5CHmq>N#9ei&^!T36Z9^K79!RzseA)&wOA_+A=&M6ynoOG7Rd}dJ6%LRpy%Pk0T zwuerb{9D+0+J5%~Z?f|SL44r}&0N!o!SVq{-nYL$(QJ3nS3gMT29nq*?S;7ulI&Tr z780qZs+ubn;Aw6ymBO4qbU#tPtdE3<$a&_AhqbkJb3|a!DKy|FRl$iDURXnNN5 z7}r2@hcoh(a)i5(cTe7LT0bdm=vPvvIIGf_o6=w&I5W^Sa7ZWR4G6j>+TyR6TUJR( znmHx@;TgyktpT;nN~ghB;9K+a^3;lXL#wKEI2-v`c`_3UHlU0Udz^ErSsbCok1eRF4?64sR0;DyXa$2H5OdF~$NvsAoc};v z$|wn51_lL9^MS|~_ui;zEYWR8CHrpv(v*}YgTMA6=y@@H=M8lCG~6bZnJGDgp+p0o zl$eZZ--5hHvb#*9_r(yeK$D17E>01)FpOhN3lp}rn1z=zPZt5&PA6jdGb3FBpX-P?Mb_QfHi1(wtiJd;_oO= z@jxJjc&~6YnV_%OAU(Mf0a|ZAXqT!LW7eb?etS0g=Yd3YVsyt3H~d``B_7%BCazF1 zN+ODQIdqM;NykDoHF#Q(l{QDr%n5mkP~4wNoazk$*!?m~M|EXHG43plzw%#h#asffCf?L6=-ww;XbqPuEPl5_*vD*0h|yw&sv-v(xb}6rm`R z8@ktPrj?Pmq#xnYWGtY1myt_VM)#h{gh6_JtpE<>$9IA|^-ZL51P1BLy=}fP&oK*B zsMs0Wab``QxBKq(hId-;2N`@3=x;Vq#q_yk_kE7dz+levH&$1rpf0n`huzd}U<_l= z%`PX0LeqP#U0b#qvfbJ<1uXI2xiO+@=1N|(k~86ft;!aMESwG6xr~gQ_BJ^m^lJxc zZPlSWO}J3@)>iWPioA01PZHCdKY>S^De_CZ{!PYLBP3x&QYvUmE^ZZ>N?opQ$Oo;* z=o*zKc5TP-Y8mwUif%>HmihI%>OU_)dD@9 zG!zflEo8%JXjzpk0w$B@>+kkUr#uZ*gWD0_@Q1|rjEN$DMLx~?%Y;9C z`zxisIlLy(=7D$c>LoqpH_D-b0b1ceyt{-rU!%+|*P?MC&`XgXd zhq^;zMa2L5+LbY$2VRlY#Kaxl|E<6)3pko*W_Kds0ixbf6*H)6M=GV8#a7m`Sbwo# z%_Gdsz2Mt&H&&LJtO@K_F!2Hg>Bl?s|J?o^x#i~O)*HI)%(X%Oe!Hta7PFrWgUnK z-NpQ3_-{W~UeBp4gG28JJup&DN82QxtR5SaJ?bL=aMH}h3P8fM;zEb1gM)(tnV665 zem*|mEvt=Oo8-v9JJvS?Fswiqz)VAYe0bP)@KYHqPUc5zj^l?tanMid?WLE07mBhR zFV=QiPrW4lE#~=ftDg6SUvNjfcFl~s$ARDGr~VXTT{~%ZvFL%WfpDQ~@Tj|+KGTBi zlk0fTzE2FzLwPrf>&{$!^3}3jgQh0ADuyifTPCkvy30S2Pa!##uZf*fVA{My<%ZvX zcYNe{SW1va;ObhCSdS+yMdA7V+%uZ+ER-4|6wV+8gFyP0GcV6OrbkEr9G`<_fm2M^ z+K~+Hk2xNWD9~@Muk#RDIkl9RJ$9t*uI^n7`?o$MaWmB$HEG02IC8%Qg-7Kf|xl~!Pz>1 z3|{OqqWGtJ5L7fW&p(JSRW_QfY}N7N{Qjt;~xm^ z3VfcoB!uC^>M%-PG4*(iIqIe_gX}SNFC2LxI=4%lKg0_C+F~P|fi6Ry{T%Mch6=D> z9K1|!y;MVd{^NPM7Ib`ZSyV-eNN~5UPm6er8M@IwMg7@RUH#IeZSmOL8KV|iE*)TR!hjtv6#If}G z=oJ)cI#xcmUZS6=cM0jdxD&x`z-kLa)W9XRIiItq-TEct+L*m0gtC9elDZMqpEUj; zp&E{kw)i5~h;K-Q97-$EPapHi9nWBoV?ulKWNxmn6X4;}^nh;Moa@)jj7m$0k8fQ* z9UWHq+kS+NVIf0>@(Ib%9|)t+{f;8PnNg&})VFWn3S_E&iqS+fLJLl#_aKnE7dWWT zQpL24Q4mJ!tY`;IgGvAfelB~Chz+V{3)~}k34qhdUyEiz{q!`ON$h^b_=3B=N{+H{ zOuej*2L0w+J8<25l=ke-H#H9$I|GWX{F@LypFjNcg!#sEs( zOQIDWe8&SLWTb$=I&T;u>gGF1jt2|@C}Kenp?UVjV>qUq!;hL@c=ZuS!P1NG3=TK@ zh}XaYLlIXf#LK&MeBNgIv@Os7xMkjijXb57*@Z@(dRSEGmyih~?KqiqN#A}U5(%21 z4D?7Zr*oz}6aWhp*WRfZz%Qbev8GCI@iaT}6yAb9-o_x$V(LMxraRWA#Vs zu-CP{7{U^QdzgQ&sNeu-f#(6$6^1t_@&;hMP*avAUlWp(%aP4N$J?UYUmlh#D-doc zuuMH=8{Dk5HIr?;;%-AjRv{wc?>}5#Z zjP!I0UESM^oYIgtw2!|k7HECU3EZim)z;QFtr7&8#j;w8!5zCLIOByKXs!%fxb;;3 zyF=r2t_ll%*oDVqzrK6W;k>u|+R~&vW*jyKI&X%SrLs!OHmKV6-sNT8#=C4-j)3*q zdcCydrgGTxZ%tvoiHjrhXL@|R!DmCyARV)I@T98M(}yGyW!PD5Lo-gs&v_6$w{HIF zbs-?O+P^p{$Gmq~FAxspE5{N&7oyqa5s$Ykg1(QN*cjux)3|Ngs_&*8X0!KbJ#qL6 zgnegp;J%zDhEJ1RG+QV%MIX;1-W`tJ^;c89SJ8AKp!Y5_&m(AN!Ci-v&T|5K#{xt+pYU*=$iJc!>XNWzu$ltg}z{THL8mZ zn4^d4A#I$g;*h%$=2`glHqfr99BQ-TRF8~jHk#y@SK(|mUYYP4{@?=LB&4%u6ZEdk zN_*#*fR+J601VYm;6zK!ZLnK}Vko*<3=8-JB=#>3K_@XnY=|j{3j@ zh#*J}Jl+Ne@_mUr+QMGj4DsrXFdBAu4f(4@I)(X>=x$$iQD6h>Dv9gNXq8iUM#sOm z+akN!)S1Vv*x3~3*g{I;n9Ihn*Awkh8kFI%r$1pTrpt5Jnz(+9Qd4nsGX7xKLbC=E*&(rPU?9 z@p_@7xcH=dCDe3(0^0RB45CZepBZZUzmR#=)f)6(mx}Tim$e~ z^nAU%%9ckseOW)f7i*&gI3zJz`G&?~!wU8|&$ELy4YoRvgJS3cSDnnxr}}8gV!As4 z5Ujk($BmTcBiS%g3!Pu~EJHq%SR zQi>_Z)hJ+vm}l8m=sk@3z)pb?d8Lv{8OIg}NZDe=o#53k6pVLj zY6{RG<=09927{?;KXbHasN{1ga!*wqfGhhz8#09WkUBqk^r!!053*b0NE zeKWnZjGrlec3YrHuUyxu*Sh9YSIe=timIy1bi+W+Cjdu)uAtFltob%Jwrs*w^m16{ z82o9g!Yu?{ZN-{QE6&5qyPL||jf)e;X*R6-l`Cg@Oa9e8f4af6W*#ET{IKosQk_rH z>zxfQ%bt%ibME2Af`P)i$481vBf1{3>(owO2RPUY+il0D3NuxLK(t)Q!o4|#vamWo z+DeuCgdCe>zpFEr%BsF6MxWdxc~qSoTWD{fSFL}|A(Ru@-3!Hug1mh_vBUo1 z*rgHuy0*4iK$gz`RDx=fKcY%(XlN+GIG70D9vRBXe7{BaAR18qj_jv<=yN)M2Fm#F z0BKc=mu2ek;Sr4GJ9HIY;PgEEV7FO0;&D1=6T%Y z>Dm}%Yr8U9rVXjq))8x4Da-%1L(LPhG@;VT@@jPj0-Fi@qIJtsE~ ziAhNA$IC(NU0wCaU|53^Am+QaRat&CX->u7=ld9PJQhKoWy1PN-Qva5$aj3C_2)ipndhL@;9ul#3d$6Avx zii;9qIZ#3LnflyNCs$Zh_>EdAAPcJ}CnhDtGf?kz*q4JPsEK>ZZa#(nj0izIm0118 zKs-UB_8ce!((xpX{zK^V1}q&@6!VPjj13G?QnJG3dOHRs=uv!hw7A%dg?SpJ10Y~8 zSRET13%J$CG{k$TpipD;CQtW0L<#lvNU{Ph=eJ#LB$B+Rz! z86ET|!2t%~Hj!EOcfF?9 zn+(eZ1Ok7Y=9lClEtIBiSZ+Yjy7X^ zmKqfDpA|dSXE|i0FpoIPA)p9ICqtA2>y31aM&~(s=g(!8GcNvkHh~uP=*TzSMpu`g zNG6-UJnEE3XUh4#VMX)owmH|AfPGt~lwb)nF}nQB%m=izH^TukwCYJ}3p%cW8V{dpj>HYkh5P_p~+LW?-;nr3J&#vUG9r z5)TLB*!3_<1;dQzZBpDTY?>qot%fUy!w`l{s;}&<<;*6gJiYx#Ihvh5P^8J4zj3fc z*Kq0GlgrD@WQaOAi=c5jcUEAOnrDhfJKD2;D*PX7&S;M|Rg(-CX2;Oo_vR zK##{uL_teScJxIGbA3Yt50Oko8c@8h2~^PHqEM(^e=)My;q5Je%K^|98^UPIv5`~J z(^u)0zft^9R@Tc!R5j5Ou)pG1AGkis##l13RQnvlC<`UV3y!uJX6a0~`5EyT@{LO+ zb0J%3aC+v=&FhfRgKGMm1Aih5-kE)(`cUp=!bQoR1~dU6*#SNb?5c0X z3EvAx?8|hhsEuZxU=|Fc9|CiY%nek{C(tIoy3Kgd;E**sGR`-E-B(IsM(_3aCk$bW z=9K;Xj=^%UkpuACR zR#c&s$iDw5qx|uYKQ(fRty?Z`@v=-=B}obHBldO0#WuZdSl<@Z0vF;Hl`8SXJ>Yj4 z9_Av_E+0$jwN_AwVT-FfCQMvZ#i*2Gs`WqVus=%e1&W|7lf|)h59PH&3kDu5TUc9r z7bI6nAR{X)$Co&iIOwsb?e6XZzVQ)7{7B`E_<~Xb44<5)cgt+1imkmpTPj%9R7GYm z^Pq(X-V0eKK%#+N0{b~R30P6!(Wu;z$ge6bjklmg*^7GFw(7IpV2b+P)iuC(_g{bJ z8^`)TyI(>iCV-?R=sE+1^d!>@5|!)2<4o!8Qg(ZLoyWB+$AyyYUbJmB&Vd<9ELA5N z8XQzi0gZrb9+m@LIC%he`B7hsapl~c>9xM{bF$X%`J%lr9~sbfhrb*=dk}4*o+k#> zb%2r4HC^Vz*!__=y2!m6V3N3gjR+rnja7=y+nwf(N>HS%c}_>Q)wgDvc*$ach7M3w zg&ul&54;odZOH?}=V0=rEv`7e_=)+@XC&LRCS!@vi!YTMp&j#EzWG4)0^qE;_$4;L zv2WfRqY5D4wOwTmQwq}j(a!wN{;5zB8g%3St)-lh%}H9F3bL957RHZy;@M z&NNkMu>C5FGiuCJ9+C|5C1T84m$3}rZr&IKp$#_Wcgr$;_^@)~?yiRjIZga`|Gasi zA^-jR*~VbO{nxUmQpyLmzVfPeM{2$6S`7kW34!|C-rjzfRqZ2Egp2DndKqXVxl%V6 z$)R{~bc#(=TU+kn8<#AWp?zOh6+WtBUi*w^#Q^g&lik)NFCTL((d`U_LZU7M=(>_;Bgu5Zf2Ffz9>mI?ot-r} zPZn+jGQ9y(9$=n?LM@@MXXV!WuEbPWyB$;}sb2EL${0+8!{3R<)^ zZ_w3ZN*vBEuLw^Ou8o2j91o&nH6D}iB_$`%`%IWb!61SNmTr7nni2!?mxveLJN1T% zQwD3^Q%Y_fuE2j6(_I{!%Dv+7Itd2aTvl4Wn-D{l9p4sJ3{ea!-KGr54vk>QDPQDP zy=&F#VqQDFHMs0q$d-;?wyajPn$uzTS^O3YoH~PpYFP-GbD^Ja-Oo&umY9_m10>R( zjg)aY)>Cm5fI2Jz9QiEw5^&-9Lke42F4Oobn9Z%NG@B+6 zFYIaFBDn*$$#mj#KU4mm1~*p{Mo6Kn0Nrp&_fEA0@B{=eZ@##VA6aMrB()b^1B@0d ztgLdH3G&%+G(-cZ^Y%|#=Nuf}nC?eR$n@_TUeSjAd}57QIZH~GTs4qwvr3c*v!k?0*`qg#V2|8I5WGZyXh}1uforE>h1F!((z4z#Q&`auyyWUGRnM1j z|Gn&3@41vHNGlpz*AbS=?784>uA7`DgIf4+qY|Npp>6Fi!z*?GvqMP~*ajxw-qebZ zDmOE;i_&eb^#O#d8;}bS06G!&!NJDY`4_YRpoKg;KYtK?`z7LO#|3hFixkfz^ni@% zjW77Z1#!BG%}w}Wm7v>P&VViGmY9{+H#R_}2Ub8&0Q#R5lT}m}9%`g8d(gyiuLR^R zeR-&mjL>6|bv^?%eV7t}AnVL{2~_9;gG00%Z;KwfgW92SX>P zjsAWWAn;zD-Up1wmWO7PIiM0}XH7!G%+1Zw3n+!?Xtke8X%N6ffRw7iHrUTBQ}Etq zL5H1ROpGQ`-h}fxAjh`0Kwl2@=#Gwmz!%ci)&`#GIr+<@?9Gjh+b<)A#P)G7;R#9% zzngxmd4DnW_%>T0z4j-COH#y9QgIpBN?{=V#LE|rIi{uWfo>Ks(a{#0o1{~;@azG{ zEcxtyKs|47yM9Fb1uwjOESS}X3!34Hv0clAoGE0lsz>*D)!qwM#xpBu2nGBKIw=NuE zt1y<^|1#@3l^PH8Tpebtnh@pY_5fWE;F4sSq$8a~i)pQ9Fc?8zUK93vJ|@RsX5)-e z@7!soJ1mNj>@-6zoAU`UXKG6Sqe<*_<~;>s<}DJsna>t7%w!I3ZdE$$U@cOZX9KXg zmzS5tS`MJkcWo5SR2dww;a9D_!_*uNN6&c;%@U!~(T|!}q8K1wcG`nJ@~ii_;k>V^ z8d};VC%6efsRatZaay(9(Z|HBV~(B(UpT2{e{h<+8(ePto#to7h#+Aq@d&JUiQpX%Ts_lxVWe?lL7l;eojvC#ct2@6LVochHHrU{zUVp6$RvD*0eCM zP7l!BmUh3OmkUGMosaPuWy{k)3d=y(fFy_?>CMj6vN(E0j`*=n?N}=&y49FRU9L;n8u8wbX%8-a#V`rb2>rN>H4G{E> zpw|c!*7}!`r|hiS`1I-f?I_t>l=fq~EUB90FWcioDZ~@EW?PP*cbtuliSiLU;a+#% zvi-gHv+xm7{$;kBAyp)E0PKz_Oc}fkYWcPxhJN& z_yIneC;9~`LMnWvl{&fr*>~K2{IttFTz;ESjSN~q68!rHz~$7Gl#uXTQNM8`CA#Do z3W~L631Q*M*;$uHb^X?b!{n#_FD_#v7>36kK;wN_kim0A2tsCEGPH)7F#k^(laOlel90~olv@4Z62H9U!yP=EE{YEj0 z1qJuN!*6Hr?qWbOv@bR^?IDih0yV9K-a;8WS({3OzJZ&x9RA)quvv%Q+sF60)0k&d z&JecR!Pm#f2+Oth^+9yN$wEvc00;Y%qVYDlbH(CBknkm;sip*1lgs$E=?tRjtvmvq zNrxP@0y~}-;_|u9wT%tnG;Jp6>9ZL4oij(Pch_l8&Nz#Cx$Ne(=e?`7axyQ0HjO&H z%Y!D@HCFz(fmP=4jlgMPs-E`0T)lgfcV4WO4r?PM%wF|m`{;fLrjlZ8%92&lh`t!9 zn*b4}1|FrzE}W`ZC%`XPS~8eba#}zVvigwzRPmBvg0P%cdb(O*%nt$GGE`x`SvTME zE4VR3qeCiKLTA~fqLCx?onK}8rMd7Yj%$FT8%_`y0uGc+VMZw6RDl?_d*KO*>IX*$ z8rTgtyL)C_pJzeNmTqd-S6YuskKsLQ$dC2-ZFq>R)fe(M53P#6Fa2BapOCjw8=Ly7|Q0;}U5>3HU5x zUSNhB9BgQ8oG!VOLvQ~u+M~rp>?sp&)bGlq?eUd{tI*R-yF41a8=82nI8q zM#m9TPlQb<75N1Dpdxda!FkC+*zaw`q^mn%TeERCK0>kX-X0`#bAnH`#R#+wd>*fD z<)^wtFSCd4-_*1ePO^YS>NC9K)DYBBTI}hT2OakQ%ZQ$($tJ6wu(PnM4-!wkq@_%% z_N?FB4&9cGfI&txj7JjNH2#?W^9{7+uf-I0|%j4ZJdW*5t*JQ?P}5*+akM( zKbgPnKD!7G+&sVUv@R!hiO-jtG6Xp0f?QK`34zj-iay6eVQJ{v*4Cr_)0MYpVv5KQ z&6UsD@8u8K866!w?cZ={GA5NH9Z@$Ahv9R>8UOt0E$}aFDsBp~^<|$S2S#1s#yn-d zgrBo_5f^V+%Ys62Hp=?(uF5Jc1cDciGxBd`i1*0IT6f?NVV148UmedobB1@YXc(ap zrIqvAJBE0!5{oR#-)kKm6XSPnUW_)7 zR5oKK%gr1Zl^Z5Pe9`zZP@Ia_Q#kUj6PVsPOiXBxcns1jGCYmuUA{kka)vJLR*_O%;9MpDtsPLm~=Q)o=6!Q?tuGG^6HA(^i4(Y)R9Z}cGHqT z6bJ2H=Qks!W3|OuMn_!MKb%>}fzt1mdY)xvwHM!OK3I2M`=YI1IuRwOXQCq08O9;2tIY zsggQMNrp2->- z^q}Dt5kB2+oH_pE^)yg?+qvNFD|xZPztzWAE61UGUY`?OsL$7On29HNuZ5vKslMmr z$fxfCr(k0c1xuU+KyJ*jSS!}z-T1fwL<$O=1%V!{`?VXBR@ZtDFxzh&3II3$((cNN zt>K4fPodAQO{V}mQ9Qbj`~JbJ@M7JD=$D2J`Iq=;-qC5w5hx z|N5^c$TT}#7yV}HlrY}b21H!%-mi@smoYtzrl$N=QykVdgr%j;782lV4KXj0{QVHJ zY&h^J_MLvO%7R_8q|Z`Pm%etmZ5Su|g}Z)>(3=)iT12VYS6(y>IU&QJJ6Dq1U_U*r zRpx#1E!JH~B?vhh-;&Fy#y^4GuZEw0C4Aa?H01<%TJIyrO7{p5OwEx=iAQ!kXl6Ul#De1VFz6+QV;qrrHbp`^`hvxR(fRZ9GzI z0}9-~=a(nWAtnTu9Vw-s#QN)7LMM|7QF13NBBr}ENHpu->?oW~mp!CS zTp_8$*0B3ckwWd{!JWuyIEH3s>S>c$3ftccNIb0jOJkATb6r+vzw4u!{zb3*$RDdO zWM)*Ym!4dPMq9A3umBBY1A`}=L>L|6OD~(its4MnTctvrLqMb{7i;^K3{{Zd>7G_5au~I-PG0G5_~#CevE!PpoZ?&0XT0 zEET-VXe3+u+Co75`+|{?u#=u0JI~^OC$S{-^dh{u&&Y^ODm?P6P^yf&y7OmJuW#Z? z8Se@~Sn!|>4C%S;MH_(?dM(IXKMHm|z%nb}9BP&A({}d(r&R&QZ}~*N4!;jkEY<=% z=qJ5$2!m3}tO_{Mg@JSw6gpu$pw`;4!VuaR-rh;R%i;9&s98zKfO_%4MsSZvQ)%*j^qyaygvGky@WWPz zpb5XQfW`A6y2O|ZGIa1x+4B(7wHMTaS7=PCAIZ_h-^_;_qNoa--aVynT!DsJolHBy z=*R_)_vIBgNqNM$Psf9H7WMI8)mIj!!4P7ch|jrS)u2qEwB3lTwyc>IwPR!9vN1y0>fEhCzY z=^$K;bTyrEVV z_9q}MhpTDU{g!TdLWr&@(?No!GVk?NgT|(U`CKCo0~Q$#A(Cl?D^DDP{vMbM)0YGC zR(>(a0%jCP^X;k$x`r}ZTUTzv2gT(qGcWPrSE|gL=J72kV}ej)_>0d{T#R@(dLDlD z!n+#*0gn!aR#W1Fq6>p`M&U$|7H$*3q~1Ypd}u5!FKq!QS(P<$R?fYiQg%Fwf+2!P z%aJ1DZ3I2&0vr!^9a;)Rj8gArT=e>3U48usj;{VF=|s&ZaF}mqX7l)bgV)g+Px|xp zjdvxP&x&tDB4IaZhIr!&hp(LqQrMRFr3BFy{&{K4BNVO>E}}^6DQlkpSu}M6=68tc z!Gr0-Q=d-LiDV+ucnBfn)jP`SSLP9v3{nuxKSqcOC0-OH>%Q}uDNjdK0QTjD;pj$j z>y-ecU!By3oZux;QOiT4XvT4`I}$S)TQgHR)kZ+VH8@Tjr{h3OCIEA8|J1C7_r;|= z-@I4~{$5szP3;2)so%y^Ou3B7#6N)q2f6`;Y|c3OUHkUaAO(eu(NPu9zPE?O_-@bO z?^`;OlutdCcpAlu7cMutEla}$;1>cmEV*A*XGGeG*lK^_IQE{S-`WU__*Z}zlVu^wGrGX~%UePv_jjhX}(b7bbM_Zy&rRMejw9fO6n#=N6 z2j`+56*-@ip1WQyWn4W^zh-79q72pf#BKfk_0yNrM4k~RCSgYYHAnZiCy<2Z`? zTYfTwiV&K#Sx<}5#mWjL0kZjplzH{pT?DY09vXf8VwA4Lg@d4^sHSmh)C*fH&alr> zTQN!=VX>*Z*&0&tcSUes0Sd#FktzMSW0A$;vjEr+hV9YqDmNm7-@N|i|tG&@Cn zA)8h*)XJGMx{&QOc&_)g$H$%r8f|opX^(l%33R9xhc_HtU0Hm*;-C7n1qkQ1eOpKod^HjtmWt$$vQ#azC>XJOrg_18y$cHqU0t-tbLT8n$=Ve?l$aDY z_F)c=*z|O8t`{7I92*~J0wVixcPdTKhzYjCD%5&mMOPK zcaI*t0T(#o=h;O0%`!n1^ONt6)uwNdb(1_)*lQ&LY1osLySZUBF*fG0QPHwhqu)~X zfz})7el5m}ot=6jAB}c4QNdEG7`JsJ*mPtk9KGIb3a0=YQ za~HV$U0hvDcw7iMEBp(?%Jvpd*IGBULxwL@Ubt%xT_TdFhkhoPh$pV4Jrl`oXIJ=Y zk$C-NMIXksKAI*^Y!r)kY$|L{1Cqvqa=rJL`j``&4@ypxIqD-49M4?Sra@acKL!*i zjjjtq(bjeFv%7-At)AP!a}7s%0B17vMdbz!>uR&~Ex-^S2DZg%p(r~p_RzpzQQgw3 zZ5K^Yx%IO%xKnL?JzE6>gwhvMou;Rc>a+7Q(}R7xw4uOzq+Ry*Zi6U178Ck=DuN); zao(}2XIUn9<9qU5aDa;e!It*y@ZbQx)~nI+b=lJ*0Z@^}uPrEXqhQXIV74gl0&ief zvGI0VX7AAvC*p7PoopWydO8UkeM2@%-xlL0=X8tM5{EAHRHUKKOzkB6QkE(&yF{rJ zRxl@$mH+!T#ac_{Mwj_(0a+s+PqSbvC7YPjD4Hoq06658Y1a1HWm*6;EKJPL&(EXIy@7zaIVDgWLU#*ZaKA zd7k#fWX9Oshkt2zl@k|WFRfn=-`8xlK=86iz;#h+rDDYkjY#U+b>&ixn zeJ|p|ETPmMjpkKmzXL7w?UaF>pUUYJ5|YK;sxZ^3<#(4`|2XKlj@s4;N%g8jbS~Cw zB3Wi2T#sgHfA#lE@wutyTr+(i{r^htfsy}x-=OQ`qpHEfJ!x0T3On+842iuJ&vU(b1yvEDW3)AADmkEv@MdSim9 znfMEVHVvMXQBhYvaWN?=>gzEuj1Yg+lB6-pg0QeqVej#r1JB1>yKOS!!>pDf3eWub z5vWzA2-(bmx|$lAc;yV9XQO-W@~83(mCN$~2uZ->=Rh_L0j@A|4$63;tC80*UX&eO zw>_29LfaH-O^ApYOj+xvR&EA8lB2Lq=e!kOSGVO={I)XYTJll}b|sCwV;T>f%7+kgJNFqY^B+i0MenB&2b6}+orW%T`IqU%Q|4&&Fl z?g%JOth43*aKq=f9Zm}MT!UejDY_g*BN&iYuX}6_kADF`2@5uK^WEgD5xmtG3oUl& z=VFm~S4QW;^(NNqF$}TC8xCyG3RfhNstm7V(1cIho70ubcq+Kz+-bJIONQTaKRGz& zM+w_A42$y5=!s=JK%<}#;?D5GkDtu%c(4A~?$w040#$p@sq<4*e^ks|mrE_rNfL%( ze*ugii3?yq{QK<187WLZ%vojM1l4#5ZhO~os1e|=NzZE6KEr|9S`UzfJk}U5yE49D=Z7F?+U5mX+Qknr? z5WePQ#Bg}!Lx&GFMI7;YYLiN=>rYw)su*N0ZzlqBiAmXa zPjIw>gbRzq^YsRCA%W(2KH9fXkm7)ZSB~OvwUSgh&P|V)=WH|xcdcbwva6l^J*Y_Rp=jf5-Z3N= zYc0zv0iui*O(@!U(n(ZG)3Fd+8gA;q;a;$)Z)L+{bFcpf3V56E)S>@=4};^tcjxv8 z4!4fArfDp6;p_3#k`HYNtDKp6v$rj7**ENI>UPc+zEd)VRPH!#DTEvK6?|=Ws_{pApKQcck-4JAfp&WPv#dx!lAgIG^9@` z;aAvMda7Yj&<{wv4=RmjKkQc|6AuEx#{N?AWdQ(|uhtChLl4PpZZRixYT}0U21Mb; zsF9vxY1O;Jkk2{~`H$*hnmj+koBYxaVyX^hwGVPnQYu3Tb%KFR74EocRX8p-c91>V z%q_jpIn7KB$`wHmdwZ)RU7a-8iS6vy>E={a)D;kUrQ644ntRVT@^qD+a^41+_d3s_ayGV{Az!%8i%tlpVo&kWkknI#t2(;M$!XcMZOqzHyKHV-H7-V%BUwgdD|tUd^Ke#PBoSuwG_vU8m{KRqZ$8>yS{am zv>zw84o+@p#B5gR^;^u{nq^fT^(FKUFUa-?zrOc*YrJtC;6h*>A2RAfJ$l;Pk^Zgg zt?6O^(Xsp?^!~|J<#Ku!fP4wu&zS>*{r$kQ@K}e&80q?kBph+RvP~Nos0f{QE7$PyjBFSFY5zoz zmCD?~xG+C|YIC=LP?I^fuaX73m$x|L6J^J!L|&&UE1&U02-c0X{*zI-BU|n?3F0M& zhV9CrR+@M_T`*heeZnr7% zzhm|1W6pg?OV(tkI9$=D9vF&bS#J)&Ks*W9mF?|g3%_bF-C>e`Bm9iJXkiDb&C7IM zH9)bQPKo5+6U|iLX4z<~?DQXLw*_A(JHj$QJ)n(uOH$PlOI%5*?lY;qO-@3pC_;IK z1DLkJp+Ly@r7=rSU~Ah`PIdB+pFTOc7I^zTl$Z9<8CNgYNa1yyb4|pc7cXe`hUEUk3y512Ma|B-aJJbaBz8A%#5A zk@cJxgX1Be{ml{V48)NTa;$K;5qs8~YqpGKu6JUTvegSNE$mv!rN^r;Id3~i)gd}! zfq!0|#nD-%siE0=eSOS#;7-rOZ0=+Jyv4W~#mx7q7nHqw-;7 zu+@Z7_9We`gt=Is9h4)M%Fj>SQQbRDIM_vukFY59)tUtZj{Vp{UcJSF#dUPN2 z^rTI_1@*_07d`*HVdEuZ^q{Z)fBsGlB_({As_1upeSILMdoLP%VEnqizOSR>Q+(|* z(f|kSmpNHX{>}gOz1d;*116f zUAiCJhRB@>30!G2ep7JV*#tJ*#we2iE%bXd#47f84&wYcd)ANrixFSgnJwFChy2<5 z*0TpvkrWNGx6raItCkj7dcAhGHWylgUiCYbh^D#o!*aIiI#(+XkMP+#t_9yc3xO-m zJd`mvIDlK_&dn)A5uD9j0N>mDCg$t+gL&!TtI49_9b!8TMn9X7{#F4BQ5oX!k1xSuHnxjUH~yFnmD= zuN1bY2$m*UFz@;AHo@LSbtV6*a$f*(y18k$`bSjvKOKQwx9e=nM<6Tofy0_#$;SRR z`V4b)vH42g>AJF>zCA$##XZMi&%I*_;j{5SE!x#>BIggC;g;yxYR zDpHvHwRPQ1x2EIeOj*{Xx$Pq3B++W{Q8RM(_Hr)f$14|*c3ii2E|Y^AsI$oNEELD5 z-{o?oZ5B)EHOsEAKG|g0OFugLggD#U-=~R^RNIYFLf+tG{>?1mW#YUJ^l2bs8}+3s2{qOIN(Y7e?4-LG~fg8<4*mmM0H% zXo?%AT5tCB^Z>krDPP*is*k(7U?|dgX%*)ncRKNk3fF5tlDFvW-HxWK(KrK%JM;4$+(DvLt%Ae zjWt8wFMH!YA>TwXS7!qpTUC2T9LkY*dm*9a|WouOk)6rGgf%98`;X7K;4Hx_w0MNzqX> z&$uPpUK+QJ%M2c*sTb=Fi4LqET)lMTfJ}=&&ZnQEab@u=gaK@QOU714exhHhIih%I zkCKz$6c=-HC_t!*N7VyELPUp0t~1bICsl;f=nwmbVvyhNOu0wXvaniyKE>D#m|w?; zi1@62U6r17flt%-9@&Vwhs=JNw~Wi5{4j26!nd^DB1WH5n^DRohET;9s6Xk?I~b?n5`OAI#tI zt?Q3@{|TxjVTL~dPg;5lNvjMMcBld+W;fD~AQ4RIr&8gLCMXUTnNj4gWor)g^^04$5NK1q*GOsEyiAvO5kvz_;{J)qrx1^xE-p!!SJ29 zzyZTqDEadT(!07t5J?AGrjzF*0~( zb{kuXd=ptmABy2CBW-#*A@52>i;m5`XV_2-WOayReK?SKgT&rlodx899XI8hKx zQ&lZu|4Yu{jB(5`5ilHCeZflu3<8uIkE-)aW?c+a1sf;=+S%`(G9_yqbj#m(^CuGin6ujLpcH z7I0TpO?UcJ^eks>bCuul2e~i{mN`~VUiVJlQVLjavuCe-`CbK6<)>C^uhIl|UKwmn zy+1JR;)~=b*Wa#XMDowhk}{?`>Z~wc|H;+&?wD1i&?%dR>6UVG_c;SOF-bVNQ8c7y zhnxdxeT}32S3;(^;DWV@z}meu4Ig`yP+GNO!xODqqZXsIc`r5jlim(h!3EcH%wj~& zC;y`mF-u=m_F37y5w6Ras0;lzM|7!!Eo|lF;8CnK1k(K>wkeX`$KSu``Te(*bK9?! zRX{@JXg2tQzkd1+^o5A`u+evs0W-H7)Nd=(p4ONadhY(*NnoyDrU=A{T6?bF|4|9 z&M4$n7x@^p(-jrTKH?@GZ3KC3ZDfq{Vo9n51i!N55%|5#`+5)f2>bfCzKz1Kn3~U^ zdt-V>7e?Y61uUm|Ze|tXQ^^p1xrV4~v+r`MW2-s^2JLvyN5>B@PAuhPmRBnCXDPZR zfnon{G8k8ZR~)C73{ilROnJ-uZTv%=x+7-L)(WFE=^8AIk2*xm{QYkd{gQeEb$PM) z-{K+n{2NWb#0=KL-1Io(wbg1^v+p{fe!0~H(f2LCbVi1H!6m+89}G!sRWZSRO8<4$ z1ryebqn=c@)MVRS}N)r7SYkn=BkaaWcFX50r zFHCmN#HJ5GGe{0-1q@HqL!Je~abeMXk{nM`IQd@Ggr!aHfYUV-Th5c$O96vCBrh8C z)+gJ?%6PO`hpB9*+69y#!n`!s4NB9rEAD3wFvMDv(tJhqv5YX$MYt4_ppVW4mxeihWNJA&gjq;6#q93 zvrZGKB=ancWW6Obvzzy7zLDVp{yZIV+^5H<3_pCz32+bf&84OB3k@Jyi%S%!QO@Iy z^IKYZhz|PQxME?$Sf|}<=j|PBL}0FS3WDp3q2*r-Q&QbAMq5{x^vdN}>W|t8r}y=b zC~8E%~K72iFfYQaa=Bb{nC_yrh=Y56_fU{u?vM z3Y&nn1++5Fh#8QI%9xrUNyRoAx15u{OIWS05~H#O8(~vn82+ib{lX~_j}p(^TwP^k z1Syrfz)lPdBqb%;Qr_Kk{y5R%23&W-+{q!DGU@H2h*LIw$*8&z!`q(8RawnwXorxB z$}^CEeBeAlPrjBRoetJG@uCXd3?QZ&Aj=U)jE#qY^B5dAcUU*~Uns9@0!r(dr5Ax- z)-9>(xvpKGV`ya+m>xi6_~m#7NUC%Sky~AyU&(jq5&jnU)r)0BbTiG+LdtLB3GX z-1zyO<$$lG5ON}=3TsCPZ1(D!35dsVrk9%V<4d^o)A%tWUMo+?7WG+b$)I~$;*~H;r=OdT)KhW*@9vYkx8l20R8;{2HuN2LI7OtDVOZFfx2277EIk)SNL5wK-}hi-TCt?G zx>`4*P&;N zUA_H8C;Ir7p^Ux6`sYkQ5(J4m-nhFn*ZdZrkxK>peXXrk#?^oa_C*r*{7#1uIkZEB zeCTxU;v29@KQ`R_XXcBl@F-8lI;8ieEoSq-+wJ;V(*PDw7XH5FT*zr!D%L2oN9X6; z@^cdtchznyeR*CCbgHO@21CnGkUW_Ry-U^cxo-iGH6=a%Eu|mb>wM~#j^YC>g{di- z6?zr&2(JS6IJXG;lwzk?>sHosSo#{_9TGVPem()@NPmGr3V@=`u*U}+(PvGygg4aXp{p8}g;j}_q~wnX82aB# zG2M?2lji*qM+E#RmIzt$Au#`khkj=$<0cQ^k&DSHYWj7H{a_%yd~JO#ms^ulMSeaA zHGx@66@LJpfjtYJ&ecP`gcbRVW0W}nFW~omb^)DuDbQm0rkTfp^j0Fj zq>QEcX@Ac32M*~I+^)%U2?T4mWI6@}aJ6|k)kY$F??9ZZV1FY~E+r+-8Ham0@?nd; zo{&i4O4#}vp0HZ8SN5Zgow*s^jHXQ`X474*ou52D&bOKPexPC=NB#9szaq}?Wkp?f ztgbE^&qGL;zpw@HyzEEo2SLUC!w^3ZU~FxD1SS7RhydK&slG*EoqS=WqOXS&)q_8v z^Li5yZ=KP%s0o(RoY%ZRN|pC`0}S-WWNrTQV)kfpx9O+yE}rdf-nX!!l?^x-aQ28^ zKAqLRRpfBPBnWJRL28SgysiqDYYsAmUv&er%dyGjV=r`miEf%n2zLmvo`08Md{TYR zsAOc6$vr#TTW8cjzv00(&Rk8r@>fMb)0|dtca7?O>!#~vkay^A zSW=HS3Uj?X)*6JheSvAm&rj}n@ge$bsr<)M9&gj~9oMXZ!D9lErce|^hY-MDELU2Y0iWlTDDpj@b zL!gvbea+MDJ_1L(*40tPaE6TBRVFcS$S-iFALH8U(9gQonyoKL33+; zJ1VA1{^lKHmiuP7_xibtv4FgT{_{-tCa1sWr`ws4&gLCg=CPw;F8uoTJaNIvlXOzp zkk2W|ryqx8gE|1%o#zr9YsA3O`k@e{W&D?_j4ggS*?t6nPBeemRDuld=1l)(*_C@Lw0`Op`SCsTch&*Vx?^+80%`hJRB!7&%jA zkjF1Q5AuQ_BSjq1Zh5w3$=qa|S}Ir0#&PwfCz%qtPKmz4-%sv{1U`3Q6VCBic<%h3 zt~!7vO#qB~!?{0CuD&}QFD@woG}ko{DwE5(c{Pf%!!ZM7FzPbhn$(~q(xy)doSgd! z`YS@_5=MT=TqnYYqVhz0X_X}>4W)TZ5Iwy| zW>-I5wIC6;0FO}kb#dCi!nY*SQ`y2!n!7aL;A>w!fzCOZ<)HX(ku~c4P--506=*agx5mNa-KPKB>&B13ktW;`WY|N z&jTN6lu<7jDJ^F`e^q|=@S6tZRhUfr{BoHTnZ0pCZ?;o=sRfvtoU_(n$5*FZdE%n6 zWyo%s=NZ;7G1o%K4tCo+B_NLcEnzg*BYQPcUa_w=yxRLlZ#higLR8JK<=2{+YYBL@b@caF|T32^iLHu*e2TrX~vpqs!b}9Twux ze;B5kZCYI%>`j-e=x(cMJZqvvIhXILQ1580IOmWyH%|eJ?(}T-=Z+Et0guRc0vGj? zk2}|*}qRtf-ZjDlzVxURk=b|WZj$x?BA_tyXPx8 z@?Ut-Zh;6-rk2~0RdEI?_vo(*7=E8+7O-jZ(P_R)b4KOKXejGq*f|F^^x|(|pZ#jE z*SGjW;AuI@738}Rxq4R*fYjNZVE}^(tuj$K5XYxT^A5g= z)hg1Ru4?lT4w8P(i37U6vZA>lQ*#6*zgoflBtQ+&<`tr(PU@+inD)kQ=DS`MBEC_1 zGr$aor0gZuAFHw>LxFxj$01{Mf> zpRPvID4+l9kslcwQ`dOB%Is84B#BPT=iiF|l79hK8EM|NDowP?C*=Z0*p77+yQo|COM(9bE{otg?fOtIFtK4U|-%B2#k=bl#c&?@Wbr^Rj}?Fid~ zh|N3h{_{m#6$=_Cv`unp4r+tcM|OgPEe5q=jRMT&qXb*;7#ZgXPg&WJpX1{VQyUh|CJ^ydAKP^D-Eft;hj)?z)8%O04zk*rH5v?5ebzf7W&{>glU8)_{G zZ}-h~4K&1<9P3T27wPBaN^nG5GXx0}?d=5xx6UF?f9I1#@v0X(0T2G~Zf5_dz@QE| zA2m1PnMCxai;o2!{D>E92|4Rjd#RRQm5<`;LNhJw;YDqUasqoLlkL9n+z`Ywd8@n%dqMSK5o9;W?&#A z^Xj7S9u3nMC128-wq)hA+s0}OZJvJkBDsTPha7@F5G*Pe9v51l_2rzsI#|a~L>xwH zJ_+`tFge$S(aB%@ojWR9C;WYd=y97=UT_he3l3GZb0YAThEAPJ>gzk1rw}B|p52Ys z_N-??RDy1J6X$jq_KILz zMb4n$b;!kUUBpm5%3m?W)pWKAg{v^v2MLQ3-XD1M`HZuEaF5LF(vA>Ff%?2pG2#6w zTe*FcYP$(;G3gGPG=k_`#nZ7gQ4$bw6lH zbTR`c-;`VHzFhO^gI!B)$*0|Bub*~u#R(`vjgcIXn{olzD@SvC@jZyZ?MMD&^nR0p z(KVuammnsv?(51|edR3n$pGT(U+?QzHxshQewk-Xm@DoS{AX6>_-C|gQ0&83wBr}~ z=JEJXAJyoukK!$u3*y&Sodn+R%3?gT+Pz?q_Ydq6?IPYy9Zegce%cqNRGI0EO;o{f zRdL6#j;cKNDp=263zi42g*Wgi!h15tArjP%xxBby&#UmtV8XHVN-s-8N|q`UR-q68 zy{uC?N@EY78X#gv%XfOhAm7NZ!SKzfm78G~9S1+$(l4~NV!7X-_eUO(-2k|(uO%x| z%+3BcMI}^CO>DF!xTt^Hp~rpIC`QIt`>rep2NOYj0Y>7-#s&+AHs9#T>U3n8l@ty6 z(>!+a$le`UNb#sTr4q>gcGT4Qi-bFaWppvfOJ`gaAMh$>S7Sxm86l}jcxn1etq0A- zDN1PW_sT_3i-fCeI83t z&I}!RNeNyTkS3+Ym>|2-G2OJAKkVl3BAud6gG({<8f&GKUJkyUp`=yGDE%_DdWTFx z$gLS1wN`;{B=5-gXGmKRfgWl-$~GKVd&HQ*`K(8FHEZ(p@XomZFAvM@v91-g7UD#H zYwn_oojgKeXmhs$hN1YLIa?!2r>6*%QCAn2qf;;*`t6Yc{Rr5kZcx57f5+0dcN?q0U|Q%Dy6H0K(MaqOVVTc< z7tziim%{m!rALINoO$wR=NIhyZcsjD{ImtzHzPbi-)NfSec(tJSkFLuzsV?H-B-*< z+eNC%lvN`a&wnfPW}}@;64IT$=4Y!K|9L(+Q-YCuF{?Iy)}ek$|Fw@#TB?4w2~>le zlVT~hgSTa3u~`%K+t4U&Ev=(Z{P3w2PGmtYI(A;u%O2NF)nt*nbQd1dIbNdo z14OWQk0T+S>j%Ie8{IAh_EO-*LxMB>QMGY!qN<_-pu285G*XEKu^s6)}u2c%;zDfH4A^L1Ca1H9E|31{$)aL5}(FHB)C-7v|Eebci`-86R zZQW5m+cgp{bI;0}c(CGplWbx-cy54t;o+z=KLce(VWsanC`Fj&0I0<{S**3D;}wex z4%_BUQKTS^Ism&$%pRcXFS^}Z0v#QD7j_&o#wI82jK_-P2|0llR>mqg(F{+3k0(AK zD#r1|b=@7v`W={CTN}DP+l)S)aSu6L$O-uO`@-{R=7@^&r2``p0vHI#$F}mHvOgw7 zcd!x0w_P$~p#pT?RWLx*2f?zqyVyOX-J87A{ncSKVG6BCel1VKOAQn~IxA4B`M6}P z?w#K1V2|$i=HVFtluuD;2ZTGk0%Z+v9&!3G=H{P&Rp+d`xVeP}Nq6L;-zk`EH+-UB z4mA!$;v4GG(W{L+)%mH>&`D~%C{T%_SeM68V5iwP++NOjSN)t2y(oO(FY$eRw&rh7y9mzSoLS-~g%uZ>ezI3}AsGuo} zYk&SMO8SMooZj?&6$vbqdiruQ;%f&1GSX98Spl1cnQo`?=zr^6^;^HbrE|Uk%qY6} zM`tmDgM-}sn0DmH0ek9!JCy;MW~EjY;q2!6qUQCQ)DTS#oY+hiWuoolTy1H>39Y6} zz3{MzS4;PzVk-UF_4hQ6uMwthUToi!KfNywN7_*V z#T<^(4{c+|2!V$X=5P~OE%@Mq#=DyrXV|&Nug`|r2*bS}heJ#<~NJAL(;$ zY}nsJS04#{Utex-MJa`z2wsGM)Kc1#0{aVV3R@UPtQ=cZyoUNTb>*8v?ekig?4yTb z4^#isWdvNrWC+VR;@wg}1brauaR@7141kS#5Zlxj2k3K$Z2Go?GWWLAnQd!hU=ao_ zbKCNN`#`+y$v6aAV$A`&4h5jP2 zagwy{7hnO5Ni79rZVR3p143o!QLFckTT5N-s;f0nffqHovVx{?u*_Jwu^DLA*zd=B*b69 zcNWVWAXaEJO9VdRr;E>DGJ0r!S8f@$zHo6OYkO8lNhl~gNciuoI#*Y1$-x68<9)T4 z?0@E^lIa5!-%(=Tl`5O3a`n9u4hU(ps^}A?Y&5{ZXR0(iMEN`V?R71ZlEAA*5%QD< zET)1H2y`BAjrBHw0a^xccJ3_jEM_eGHLIv%J8iBhC-?Al`*R`?h}G-GE%=$ ztu`xs{AZETV&$v|CL?!Q@}Tvq7x{61*D!>y_pfK>!|x+@1{Z*Fg6R~{@Z zH~M9m~5A4C=>x+^%AObqm>5ENFQ)s4- z?k;*ea|(QmOxM?#IX#_)U3AtB>syAF=7|;SHM}0mf?2^vyZD_l`9pFJ&Po>Q>#9QB zfC^pXJU2wu0b5?-?CYq25m&%8Xodk2XCGPLqD-SK{ZLGr?aTU*hVjr+Wg9}UETQVk z-v8+^mlYVwtpIGz5E}@nJ@_)ym4hH!<%yQShvrYgX+$;zlt+P~O)x}Go&)e%YMR|c zO_@(@GVB2Tt+=zaB#3Li?So4n*0?Mqt=sSn^HtjwnryOe&cXabVhrcFqMV*d5!;f- zUMXwXzjAw^ETgcm_I90UdTHPHLM)pC%*8pwnkm+rp~;OwrOd=$ij{+e9P&DM6abym zU-O(u90EAm@xPsgT9dNUQVNb5qd!uK3xV0^cE)tJ{d+BsY-^n|x@?45lR#zIVk)|S zg<@52Qpl%6sP4wgb8z>8MF75R>MG>%V^#79ld=}qDI{>&SqVu>NPz05%Q7}j21;=; zkn#Y&XMjju2d_#yV?g22Cx)CzV)uNQikE1QxQwaq)lkjS73b0*0w-^N4G;EyR8wSR zUFQCG?wYb!r9}>>y1*NHVBC**NR@BK=j?o+;cX^zY3De=qJpwRhzj>vq|_yY__ZRX z5(!w`^Fu)sM!dBv)DK=25xRM- zi}?5B0xTjCCq)P#YM2YWS&&Qw0Q*pId~92fHJ3jh*5cve)}Ij>C~-;wkfD|f0@@r# z2Z~)AS~Y;zl1zR#c@A*m6kv3zcE&pI!4zA19D>s0BaKotnJ0lnL#16lUzX0@iw1Zd z%#sK^btUla&h^))HcTAtmX#)rr9Vm}Z85m8@Gbw7qaQPwDio}SZ}U~LuI_~FXuFXU z6*nrsTjbrbsA@`=yRl2RhQh33fj%P@L3Rf~5nkH7yoKpRD!*1HziI^`(sm$yZT%sm z zFlKVV>BL8_1lR^$HWuaeW&*ZvuMr`a7-LBx!EwCh_~2X^miF@&Mc`I4?Q6|)DlyCO zR{q26=+g3kn0s3XLxRz*RP;C3%1!T}X#`By%L`ha8H{Ku3yUF7l&tP@V)U~eC?ESb zw~%saR6yvg;*IEp`Qs1ow1+c(hqg1ci|EH%YvMj&{v%Zc;uV7_IR{3BRB^~R!I}YA zRbgk1sp7E*51dUuQ>5?4xF--zp<1Yq3;J>4DGs7WJ2Bh_fJ*>$-gS(rKqw_9Z9W2q# zEal&_#6@=!;tW?0Ub2)Opa7NF)~qyb+AYb6iB25E(W$Q3zO;@%WXd18Fhw6^E_ofd zM?@iG0>8y5!C`_B5mDLF3i z;EF?A^?=Wec60ywitQZMZy6#*_K&J^QMk^*mncBqEdDmulV!kT_@@Ymq#>%|k%cAu zTd0S$yY)-Prb{N8?MtEv^@7EnAezP>LT_`a>t$M;aKMuouX;-fD}N!|ZA8PRmZFpk z+zr4A9$9=8`u7(R((WdUT8s|1@!se@}V%N>uWINRDa)(thI!sTQ1B9PNa(#Pez(e6cH6z4ti_M;zBW(Etl^$`leNJJ%mvg>9RjkLCdLNWJ zp8URvI9U=zl-1VutsfAvzpX6c>sx%u4z)7A!Jz^rNyl)-5%+jTE6C;K_dQ&ysuR(* z6{Jt!Vne;*AgC3<=^0Zj^ZT*5 zxEKPZ0tGxw31NhFO9Uv#xydREf>O!HsS$1rC*$M)fIhRZGd?j~EhK-f^o}EX6<+Vf zA|Wnb>%Z;VlX&M8+$n-e?7+?-`b^cWK0ce@2-)$W0z{^u#L-z(7H_Y$H)_PGELWjh zHN<%>^Y2|4CP}={dyXKdQ`t%w^Efk!Q@Bs{T%aMgMh*&n%t6o32l6t2UKtlBm5mb< zqBPfk5zTqpCCA32CL|%@U~B-;K9>b5FYqX4#NViGr;OzzviThntT$jy=LjYyBs|Hl zEYvm{6^#TjVfnLRH28Hv^1JT^Lo8@8{HV#zaszmi)lyi4H!8swRRr_`FgOlB-5;BB zYrQxR21$ZGOSuD$SnI9v=9SRxV0Z3RDUVG5@ zjX1rxiZea`@_6X-Mcvi4QG!Z;*u#^_c>M}dvK>4JYgqg~zDtSo_I)~jB$ud6S7N$* zi{~l8H-Eu_*Nb_x7WwZ$r+|Mn-E=)WU~^03d_5+kkh>_Q_>!FO7MFo^GB(23APDF= z@XD1IVpvcw@B)Czqt@+E{~2FAaIS<+A}?!aFa9OXeag;$)0KDeTRsF3^5=iQx=81Z z17p}P(BgIo02KVDepeL4Wpv667-J{U7k?-OS)_yZ89M&BNdQPx)0S7Gk2z1Ys8|df zR|C@|-#HBhd$vdjWYves)~uKz_8V&J{8jgQqW`9Tt69Ryh1m3N{c!9HW=>8^Iwtk? zz}ed*Ady^-FLmNm>J`N*SN&`=8sZ2Kg0Uu%fu>bq%6v1FU9~qqe;E#!3Oq@(v%U&e zFGIeX34neVN6u%y2Ka;R(2E>UT$2sVLdYcmss@w718`54m2Cn!1th0-0;U&sF3&q> zllZnnP`bm#a^vEB`$Dc~2ZS2k!?3}#ph+DJHSwShy7_RU(ay(54_Q0Yyj@Yh)SC>d znvZXS!P^KFjuhd56AqBOjbKO&Ev|;)>hSDUP;$Q@sR(^Q+p0HW5b#RE>i2#@#qwEJ zsrhMRY*%YGt)Dwnu9rKPao6D;@{eRU&f=cE=Zi!6t_OirrRczzKjicAFVUw(Nv6o9 zgCHpYo~O0V8d#=?nI0>fN@RW1;x=;v%s%~Q+^KN9bFGKu?Ia!_I8U@=#^Hf`NEhgj zJAWuNcLSEDE=+k3BrGvLYn$4#rG2yr>C;^XH;hCQYiMz6t2zDv zSmvdrZ&O}FmR5|z1Io&k8@|es&ZeQm>!u9eJnRMHHG8;TNM>u8L9fJ$$bU#f6S>GG#Y^0 zdrnvPH%w=D(*gJN^e~g&om&Zd?9Lk{lvJtV#P*O zmVY=!6HV#A{2H9_`jmLhe~H=49mVCc1h!lzh&P7vg-$kai2zzx7P!lwaLF(wT#tOG z$t{)G@c~L4**@hbRW@^zggB#cfkIKjplumSSfNSl=oCJ>?X6^yrb4)HP7D1(3u+!wTf! z#@7;J=wFE+cC^`{17~8Pm!eGhjlwC5KkOe?!6+gj3d{@;$jb?lzd#IIk9&t1?>G?6 zaB7PipR+ja-o5%S0r%)=lIAFgE~|Bu!RqIE$p|(J1TNU6!H#E_{t$ zsfKMFk<#e1-jPb}>yL@d1<74H849Q%=4S&}Vwm_t%iQF(=M$ZHJOa0HMIGT9z}M)WNY98w-obYL}vIqry| zeFUmr{T?Ac>&`lwpQQKyG4E2DuZl32tamQ;<+qWst+~5%os7qCt7RuyHS7asiAH%$ zl%M4W$l8~zg2NJ>dUX4^Dv5V@c>a2f+C z6EqqPEXus#^vdQ#guGsQJux zd$R$Eq(?X2ex^x|iC$x*+$H@BRn$=9tSJL^Ii8vPpK)R}ELHKX+ZTofuY$Z15n@1( z>bnHCfVRV??!A!Qcl0D2x8FQX0ck+D@rvWzSF_6W=O3|WUH$!>N{)b0_a>mlthlD8 z2K=G`(SFMKI`3(4*M~wWF)@9CbSLCsin;aW<@0YRAEH2Z)ve)oEFe1FWlHEbRUomo zG5#P9YugBIvy!)TKQ_mFU%!FpcY8ybAZpZ#e9mE5s=XKFU^&8gL-la0 zHPyO(VdrVeiwygM=fJWDY;M*cE`|GbG;)X!+=V&x1wh_iCuIkF|9_vSr2LnCm z+{VFy9@HdJLsBpx4J?qZp)Z!bvf}Cz0ceb$wRwlQ;~`J+qR|ZXQv(!c;+Y@}ma+(X zMyfQ?f>13^kR&X0c2Id%x^{tXy+}+dm8QPfS(y$iN)jy*;M;=NIbBr}yQ;YzZU5xy z1iT786FoDqC73y*r%r7AoIQu+X?qRTFKx}p)d8!wPU2h2bzBn$>4jL=mF#V{o@~nh zk#ydHRJZRRKcrHLBeJryDmx*2hB&11l${W=vK_mK>`nHJPADSID#&yJD3_wVxk z`S*F^jL&`F*L_{@_xlyWnWvJn<*~78Uid}yep&UJUCLG>&Qv1h%!f>MMtHULUY(fr z#D_jLeoqhCw{*mo0uXSt(}yLMF-dYb9ILQ{l9v zQv_$K|88R@4%Pt@7K&MX={G%WX>RT?^<;%?b4u9#ggGN_Bgfo_n=-3t)+j#ph2aF5 z;VtgiIL?oyoOa+QEDe+rrlpWqk0AD2`M|g?HaIyMT7>%aeL0@vF=$!Iuadq#axa;0;`*sUH2npk|ubaJm(c~&l(5))>wm0nlZ zbsplAq?*mr0&;i&VRw6Q3TTyC-tvNIuAO~(CHxN`>hW|3M@O}@Q3*ipY?ux+mPbN* z1*`hqdn5vVLaU>7Lgd5`xL%gN=~%kPU2flfS#dz_X~_iyT|+QHSKf5sA(APLGzSDM zU%g_y;V(j~DoyTPAJ#ORp-m-1@K*Cm1Fz|d*mx>bJk)Gj$pvQW=is5OgSW*+v3^ek z{EytsHTXFVb+_g|8}Zt9jrKjJX!iSun$A5oeXj8k`3t1eVqIX6(}>8F^&_VCRl4O9 zcfO5qJnrw;02Al$Yhnc)#P~*C$+}Q#(gfcP5HTOH;7U7kt9>a}X*oIo9PEzId~LiP zLVBLVvm41St&7U45<7q;WY`|KCHM_Yfy


~{i~37L(DAGUSsdq5ag0>ANNPtP-7 z63N5ulHkfL_8S}TUrkyE67c}9R zmAd+;{N->(sQ2ZVnc5zsP~Xks6#}{soW&?Yo8YS7$nj*=sY=`{j8iGgY@zZ_3p0Y& z)OydkCY_@ZlH*5{6j>meYFo6=EE{X?9vu51y0$+2 zOmSUB14Q5t6)2lPuD=7lq1$vj*9q?4y_dI~H6WT8GF}DssHk^6ak9{P;@0OZ>Z>0U zRoPK%aImz^ncaIOf{hLt6QR|}UFtmSR3(Y)oFg}PmavIWu)eYI&5!ibrEA9R-=9z^ zNV}Wmx^W0Fq;o(7Sutl`aq(m9_B-LsTw<-8s)T8F@qfEgBuzSxU+AGBf)MM_!u$^4)Y4YagGkaFu-%9tp?`DvcCj zNob$ojb^wmq7?nckhd|OBJ(;qP@WQIoktse!XTOU6;NJ$!<~=5JJAu#dCy208;j8c zjDyx+KtRRZ+WdQNu9;-_TecfJ*Mp5ui{A;uP2OPX!%xZ0X750XBmq-G`@iiu<^$FH zzpmvC=DVwD(0YZnEzVrTW0KQWuifet{WWb=%|a-K;gqo$#jt8#LTETNy{_>kC6n(d z<_xj{LW#6UlZ{6m15j9hSc=lFrr)b-EqNKL!8 za|l4|W&t7uZ%}!9IUeJUMO6<<;TsqdBBE|Q4M@}=^bu&AK?FQrl~u~Q@$h(N!qv0L zv`2>GwJOrU$4Bbz9JPK~-j{cEJr4c|O*k9t>+3u0^eNDzzg6p8L{thaCk~fjtVazDzAcVyQ)3C4rr+(K z8!f^g3E(F!|F)q;B4DK&#SszNFIB2ym+hybaA+C~_F|R1x(dbI&*{T9+O@53d;*e6 zvMR64S~mDcM4T#PBhw9B(NURs&WsLcvH!?4JUtU}T++N+TDwb?j;9B>x|3be=;&yF zxnCHPz%XQ?<&D5U3+-JOuTkjO{Fyh`bNPeYx)bo0Mg$K6^pc22ik+Oq=z&{8$b?e< zl>S^#Z`D?WG_`p1XU4r3s`1ZZ8vkoL)BnxwKvxaW&Lly1E#Vt6EEScN0smEl z_rhbn-bE<_4I>m_CO34GHsN^%Tl(dS=vsllZX;(596@GIxwePd`ODiFxk09I7QV70 zF}tAJ;#Y2{P-?QfA2~JKXoLR^zKd56*c0ZR+c_HXV^-t$Tf%tGis+co2Hahk) zK6iGYR(ZZh>lJodXn&4d2_+G<0qg+U1F-b>R3*^NwFnwXeCC|394XgC` zjeSXFXj*1PXHDj=1%2lf$H$CUqkP%V!i-y192GzdTLh!}M5KQJq2IM37F|7Sz)PPne&b>Cbw@>|-3 z%*OO}s3m`yWv8GI=3kWkSh?bNw2*<2`3ks3jeZPf7c;QiC1m{B=EEXmfLW`|KS0Wu zUZ6!3LLkH!o-$FlZ*wLMUv8+3nP6;QP9J`mdhVeTaQmyZRqbM=+Q4`HGvXg<#+s$i zp+lx6`ibv9@{g+5M1ZSTP_wH=Ls>PxN+;^*S<Ix7PR6w?2BmD|tMvcJpR`TWrc5 z<*OLfC|d+eOT<%pLP9Yf!VfHMDISL#c?DoE+l5BOJ0n&$0z__ZzW&*Co4MXaf@03C z#3#DXt`j;q*q4jbhs@IEmUyO0-XJEGx%A=WLI01NH=|QLFz-W>Xngs2c>#q2sT-z) zcnC(HzJURknp&e2mr*vt`qgo9H~=zO&Z_QSSMD*fEgrndpECc{?Jh%{4Ei;ly$+-U zz?9r-boZb!I7KVQnCcRuTTHm)yLL=;gnZ}tNd9!Stb)o5)Faw1})M2FpC zV9%{;Pgee@s!E{9M#?y=PC0k3ZP|(OC`WMKqoea%t;OZTClVDK%RXz42xEcv*~$Ea z0tPYrpR>D_HOW&yf7W{g^~w@zgxnHLRwFOULNg$}wKzRD7rQ8+vNBcg81F$!U;u2! z{}J!-q#PW6a0CDv{f2)`>}7-(aq$fqcs5T?HgxDdWQ3cKS+e!-Zfm0?PVq#8Kgv*T3E%iA-ac;?cY3kT2D3GCnGb8 z86D9g+YqL!v9LBr&qw1P67yon<)cH$J4XexG=iY#mb`V;MoWB|OIzh5vbV2q8#utr z@dMUz-z|@{wfB5wn6yZM=%S{UJ*f}6hKI=)5PDM;1h^fv*${+cp?-9I<};kAM#GG| z3HXjZJw2p^1YZXhe-%-wPixwT0yX00m2ETy8* ztg>yES&$C}*uto2y5y*ofAz|KB4##e4b!Q%LPUm8gq+j4io3guzX3Uln;gJC7fNMW ziuk}Dud1Qp*8pc-F@@jz^UOW5rWCu?IG?cA*2jlx_Rqw+pe_uRIGl?!IW4xs4b;|p z1aZN&#Qb&0EV(=c>w0)r(aGGU;%2=@GM|j&s0>Fj zAf%xoe9jSY6#)W1CV0P&)&((S739Xw5~Q07dl?mjfB(FuBd?rg%a4AoYruG9G&3L? zl3_On_t3IHB%_ay4AaOqEfdWs^N4Ps?+DC9;?gy1-40-HaY)8ZH{Tcm57p@r17N$Z z_{oYjy?F7Wt+>@jQOI6BN(K8)I5EcfqW1+YW`j{o!{YYAad5B$bVR)8LXfs1Nq|Q) zk*ry6Idc^l?hfbfl3OX@2*?$I>fL<={;7nuW@`Gk9}Wx_?R)pj_F%Bu>T6d6~jD?bDGFasLDmfdES?f&fC5cnYiB?tv41RFn+ZfkAz zI4luGhlIjl;ALrTe*N;^@X+ca^##V>ST4%>z(jFdlA{R zur6HogKz}FIjW0{kbpos{o;MX`e$l2&ZXj!F`C4jVro2QgYI@)sM#vF&F8C1moA2? z%%gwxtk%XUey|)`uP>`TxG4{a4QO6N()$R~kTZb!yJT8EIOvovUO>n!jF=bHY&13) zfcx@b8;e>4^{Ueglhoqgd3)d{GMHMMOLlV;R&%yQM{7VWGI&!nZMnD-1|u4sqSlLy z6QO4kVndetbFXa_5%!kl?S=Mw;Mm5H^D7DcE70gR4&?~Av&f2Md zJ==(a$u>+3Q?PH;s9j=7Bz2t5PWC*GH~f4MTxQvMJR4$aXPJ50-5kj{^kF>G7Uqrm zo+mrdC$tr&U8}8f#AbcJOkC=pF3>$WID+B1;ZOL1D)^CUjhnG?GPQVP5 z3$1M+Dj4o7ef1T-Hh44x(gCq#y}vN4(e-U)z2~x01-pV*q+uPUp0mFJ75vV}5irYz z55oBMHEqCDJvyfZScoQZSGqAGU`D(4S=8xt-%%^~{LM+yuFxm$8b&GDGGJ$kL^bXH zH2d9=UA}e-wiB2A>C2`+RWBH6*+rDHqdsB3e2J9j2eVG?Qf^*E9JRbUBte6KBim^b zo#&Zamodw@GRaIR0}rnTcW&+_{Ag9bXA!JQQF7{zB1vsL!k)YTsNvPFG54*(6+fS> zcfxV1qikZh*w_wkl=}Jw#_<%ek%GIDm;m1n*Ll<%tBQt?bs%3?`7#Nty~f|X_FAu$ zsz_f_NEBZpdq=zHc~<7)=4!FvtR%sC(o7|{$!k2*J*Tp|*s4-w(ynqpT)Nu+y49rT zSq+KgF`^MVHO^wHb_*?I@^@R_|2K-M17%?nAh%oUC<*G9cfgOn-lLG>yp+REAf4)j zAH;XPER7qqZ<#u+hb9<^O&I8MsV zExpmmOC*wsE{!P{sMIffB`qu4&>=KQq_D|S`g=ZDX!7Jhw+smDES|};`_5vI+#jEC zEAe-2!2ku{b2EYm+GPDL)Vbbss@7LZS=cnyWkp3tFsP#siv|jCPIiht!6ev18w0B4^KAU(a)cV>nYhPaj&T^S^i=Tn7J-A z);%<&$n|f-`MHMsY_Jn-0NGF@EbK0lJTu4o)|CGK=x8E_OWgYJTY0hsM`nCdZB}J= z3cJQCLQ26ME)ciBz}^DN?=^%Jwsg6`S~dCz(C|?zM=aJvv`xBp9oJvz?tH}S|ED7N zDqrndoaoDphf-!?t`c9}j2d;7pGVCZ#7-GX_(05aEX*lhzj~EgSEnDrGKw+Fq$MOU zz2S>w4q$Ess9MjU7!MF}D{Ye*3E?aieNc>De6FFP9`(Rn4>I=aYEBQ^2$^&TbH;ig zz!|1}=3;P7f&FdzUx``Cy&97)70);;`sny93N0xVTat)7mEjOH1kUr;104{O$kl8o=hq|iS=^W`C z5MJVWxR?d^CM$FE@d`Up#1m<3M8eY22*AIS+y{EmTPApjq$3dyuE@Ji!Z++mT3e`m z)68g4ZDJe0$)GJo{%1BsbR#z}KjA*^9c%l|7m2a$ix;5j3oBWS=Y|ZD+0run8-ri? zt9%AIy`A+`PMslpq6*5=R)wrjTY?{ZDJ=v9geEg{XYO}>17<8Dk;R`%yVQnz<>y62 z-`e(0)E$TiP#`4#Gre^HgGA^lH*6jEeo;2z(krgH4UaU>RZ6-+4y7BYYQhhNhD}xt zyt5lrO?JMjt|V|hT@RuT7D)QFRgGO#aS^Ks(Bpre?b+L(zjC`fO$$iQoizaU%*jqp zm&}6b{gfUfMHIkVavF6ey51V_Wg`_MVY}O72)>UGkXX z)7AJa0G$I*98}Xc5$Qc&2bbqTNX3h}Qr|LR1UTFX=ozsniSgLdQU=G@r^aNsOVS5a zB|O99`j2VOj(y@=k?s8Ky%+f8iW6)kk$K3T?Be9ht*FHO-bj z;aB3%^AKo8nlh#w4+0R}ObgY)BBFWchX4OOh(?+=!ifmR0Kd!D4FQ3Y8US+378MGRGbo_AD_-yKJNJI{aK{{JI7TfPacbGb6y8W$LIh3_c%hp ztd}Ks@fGjT_&7vjg1X9b_RI36q~c1qgUyHRZaLgj9`4#r2iMrxpWzxFtqQ2CD(n23 zE;OKmAX2#8F=QCHzU>r0P=D6oSV@N!SoC_!NugckxT3(|KDXoYzi7fu7k7J+>sMph-@;yjJRC^3}+rug%2^%J&~S3b3Izuj1QOh#?SCrUhFsIr({c zQ*(10roVpun#%Tv3Ub?#V9S&yw4n_}`V|3xd~?1ny7J@au-T;xcxCbN9BL6nMUfe) zMK3vNf=4jA+S>cci%m%_qrFJ|+f{b!Vnfg~8 zu)n`98W|bs?BotAGFSj@ukW;N#n*ux=fyE*nNKXKC+-_3;yqs4C@Z%oe_1qIOBKZE zvQf6}i7HEPB1ba|@VsV?f|zJ7hF)g9VWSkmxxB{uSz*H9xwX0gZACfpnRSe=zLAXD z#};>sZnxKOKX|xJiC1p#xej_RmkM%VTfjp6v*e;2fXQ#V0O4*3ZlZ=V5Hy1N*!Gy1%C2E3{OQR4V-p zzx=V!>L$St)p=p!uSg)_@jOwMIM06Y|h>VWS@f4G+^(Cynju`lfpwz+&Ywo>1B&#`2r z)g@Gh_Z7#@1v)HC+}gg^_pgO?d~Wv&b#<=(oybRnl+rZrD!dihe$wa!Y0s|Dj6EF0 z1Y%U98_w;#DkDzv5iE$`He&thS*%8yW)>E3H~E4=`8J%3>hKt&c<;*XBv$-r>0q-= zJ`|E&NqpS9w*A13Z^$phZ^fJ9b+DWdRxM@iov@txST))Xo@GtVI7_e(o%kE@Rxm^t zRo3?Tz@zEvLbb~>T5d!36ZHlC`U_=cV=~88k2*>6t0GCAa?Gl?=9mdCT)05nMD`2h zP5{RRjgLSe%6rDBD~3P&-+#aJ-~Cz+n+klxux*kXo6+-ibVXv5uem!#t^ef7clND) z%*n^n_Fo@MD0uYXa=@x2G9UG90cj;hzqaV_u{*rWxiav}9acxa}uhLww%jN zdw$6WQuOMe?kFJ1E;AtsNWB&+i4{hsmnu8A+!UI;SX$y61DR)ptpLqTWvCSKy6E%h zifT(x#?`Xkn>}y(_kG<1GgF@_NMB(potEaeP&+x04i_cD?HSG08Z`XvD@zb62&bhs zcBmQ$CPuAZ`8&4ABVj77#dmF7_a3_$1-7_9S8?m5(>R8fHpfiQLHm1Tx_sCqSFn{^d%+2J6e*U?@E87OM zR)Cw4PdU6G>v>{oMtxXi-}(G*OFXU56DKDpTkhp=JCFin)TYQP5ywkyXRRyC zTmJXZ&u;a0`R7b~($69eZ?&~=q2jTmBXibY{wvQuJxS#n!it3?$>hbZdDzUfdr||^Tw!d#V;eBZ4@q1G+qkeuyp7dh_DWnN?PYXCLea+zb zz>-rMd#wX=%hy0NCRZe)=mFDQ9Hm|a>te@y?>1FYGgGprj4#h1;20WQf5kO1pX0-n ztUQOfx`Ru9(9vvvfxCW{X}F>*B{qNKJjK=@mEdUXXidQu_gVfkQAt4m&X;?8$8nSj zN`Ea=1p?kFD4{D#s>fhjxMRi~{*!7;OkX?i5i~}QkGP{xguZPEN@{c zpS{iH7CY*roODh>ypM8gC)88ze3Kq7dP3Cq2V=<)=P1zr=xGXqv+b?*8trz??yC6Q zRs|a>H_AB93IbU#T&~>x_b}`rNsCIwh`vRbLt-#CY;3FJ@9i+LG|dn62!N=Yo3rB~ z5b7G2bw7IJE{6JDK%}VsEe|m25Z=jQQ36iq?K=(0bmE{YgutfV@z^9+kyL{l3$pc8 z=JAhiI~~46Ahv6eGA)#I9MtqMCI`pBM7Q_;Vs_QxQN#7?{o8Cky|$)jr}cYYPj7pQ z?A?679Ed4X+1R1u>ZnF(#$g2-c6P2SG(HCpV?S5i^)C3$EnU)!N8l6NLuckALv!FWHJLG+t&^dwPqc`%)ytZ{IiRgnRIgvsmc` z))bkgO67N%y=)GmrFlUtQ0G(%92kB<(<(4}`bfB3{k8Mw_FjY*U#k74AbV2j{?GTi z5-DoX;^hjNg~U-vFeSgqRLB`fqmPt}cuHm0tE5aMn{wYoRaW-G%6fEnFr}XBUOQ{k z1J#_5(^~Fd9>+Pp0%KYvyAXtBfsx|(YraEj=VUbvu}qa{d@rN>idS_rGP1I)R>#7# zhN7C&Xys1rb(4e-77y`bT$P58P05WX-k9RAw6MQ;98v1Bqc5ipZ{{A)9@ayl&8vP5KxD73)=?*?d7VJvF+aYOfLS}}ajN6Kitol3_#rebsN6v}RE`<$ z#~na;Ci8y>jv6R!bju&)>>ECUf=Zq_9H#Lu0+W>-B=d{`N(;Bc*z*;f#%%QU#w{PE zdPV$wnD#DZugN~;bhr!V7?;v2cxSC_m@;8DELI){j)O+>rs}T3VQM5hZ^=1p7i{8dtUl2C%SJF#it;i=-C6NZCjEnnv8*sAI=3 z&p6`Z;KNe4jqC6KhKYSEQ!=DkQ7lx+c;mw-5%Er83n%2CuChE9xf4j3R{OsDSH*q0 zfNy5LoXSS!$#^+CfjQr6-?V?O@;u{)mSFPGO%f&R(u3^bgM%*5nH?8C3@QFw$5A$_*>}R* z4Ga?%)|0DJKV6};hHn5iX9WpS*F(vDi$GZo9! zf=k{fz{0@%NDCKD@{Ed)Q~Dkf`seirM$biMT;_5hiE?L&5NpJvF1AIQHfP%?wMD9UDfkcX>kOT05K3s34cEX3@-Ye}5!m3TEaV)#xoa!3LL6#2&R(2D693 z+GjZZ+Qu&`d~_^M@i9s)H`1PbVjGJTJNjpM^XAQ#2fNTxu_q8_cB(9ghWhuMI1#7S z^!61$X`_`p!B@l+f<||mVq7C^UM914Y^C_$VmeYd=utS+hY}#20}@9fD%2`yw3B{6@B_HYm*i_0%}w>%T0`XEVo}K4_BvB&!32v zsl9?e+ob!R286hu%f3B83RtI)6*y;?tOGS#()h7BqWa)(V7Ovtb#>wZ55A1(9>%>I z-Si^ALQZ2&nw2}pHhU+KJ@K8Eyu8EG(dtCak8E5Ri;@6Nf&(t1QSk~=LXv6#w%np!G@lEKv zYMTEh_5Hs|E=zF;NY+#sAHOUQ3)de9Od5S>_mzz;+=B10fQif7Xyx3ooOmewx$BM_ zrPq%BCh$CjRvQO&D|#G~92bCHRrHdGDbs8O7^~16c~QIRP&Nv0QCHBZZGrkgGx$nP zs*=OW(40rxNvr$&cUQR3qsvCWa|AFFmcqI3>(ej|yUy#S zzDI|VFdd>rbU$^HMxJhNj=txg%xU5wiaMAIWaai=qBJ*OzC3S)nEGC(XJ4TMt+QES ztbpXO_iNC;{Ox?N&BzaHwGAn308fM;uvN#X;7`Yb7+RE0dF(zsX3{&9Og^8*kMKHvdCF3xe{o z4k4c2)J;uQE}OLXk`G)t$lqEdCTZ2}51XWHZx&$~3<>YaMd{8FVrsm*+gIo}XeZkIK8|xe`Wvo5 z-=;TPNUK$AS}i8Qb|X3Trb|@GokP%}e$UUh`8se1+LJ3Q;yN=jc{&SEmQruT8r@QC z;Emy~;dsEc)qI;0+fg-<$ICv?E1^mm5JY zE#qZXz1RrH-M*WIUk1OZr~!u=>0wXvsd^{D_HI~|Ea@26C5@{2)O&N~T>3L1^ki{_ zT}_WAe!FmSjUF9}M6h!E8hp-*vv=WtGYQS)G+8>K$>aX4EV4_M(_mw5s77N`oM+DL zJIYUe&CTDw1<{h{QNq#Dk+*M-4XvM7EX$o6*Fmne=Uh!+Hn?c7=ibo|^J6Bt=Ni_6 zb!$Dn3vst=K!C`CbNZN}!HX-Nx0VR%ym@_?sH;hOcS|rzXi{gzu_}_48ze$nb*J8- z%rG1&rLN5XGiwvX2beJSwoT|o9+RA{cX?yhA#FlBA~oM?sopyY4%HAjW)SMh5PEDa zAA#D7ju6aX zQ(|-k<;hswe3OEN56+M^L2a9-y6~#@NM_4}QVnZs>orILAOWWbj4_*L#h(gZKz#l7 zZES5%J7#BDUy|4Kw&x*sOT?tgIY3xdu&N^{C0SQxa?z3XY_|kgIv(CwZ*yIx78}$wydf z;dqOOpQxtN1x(oyEUbfP%Gan-873e446k#3WuR=)*%r3Kp-C%9K59xRG5O+Px`0m5 zt&%ty96dexR?>OAG-&0%_~k{>b*KoY5jnYJUZDLD=W=BZFNBoj*u3KO%_mK1u(B9w z0tW{KvaE0=T@t5Y{Ma*Yi#f$gx{vY(!GC?VvqTAY!jAZZS%x#y&AArO)2(OcBA7+{ zf&RgZ_!@$ZX;0R@ch)AICfC~9#=}49{U>-D-~55>kRvVKMEZnJv%>cH+WonlvB;>@ z`9Mao6v9Q9n6tS^CkB^=X{AWEB)CmxC)#e3sU1HgC(<5b6I3<5qMbF6)ReX)?NQrnfV zHCwf(V=+A8>u%pv=A=E2c0*_)ja(sL|i_#(JK!_1IdtqJf*wK|37Bnv365tjd`W2IF+TEoK zLH9eqeqE=zw0rP2BH?f@@;W?wmLRACskp~%u+VDdG9?tmz)F|HNs)rB6h6{`-_8TU)1WXK)denCTL8@ z$K4mYnGnLz`!2H>hQFl-9rWmf3lb@l^R}0~>w^;{94f}RV~@76ojNvKFSNA;QSkyw z>a|E4ee|CLAP$~wFr2}4;f34L=$ZZc6q7U(K`8SHq*$WipRRrQtjHovJZ{%D{$47z z(&ey_;oD2>LR{AV)usDMZueeQu(xQpm8^?lgWfGzS8lX=9-g@`@6U$9r_12J-2(+m zjozAZtnORQft9k!p8jDn!sj6V_tYGgDwGUYR7uh*xVr=h*SA#asB5lbKUz@GOg_Mj z)_ynJ07r!6cDFYuqmEkCJlK?a!>8yFgiRa1X%IsjGP_!PL)7xjq4j?p-9->&I5EIF&K-wXQcV)lY*BD zcFLKXCis=bwGZ#Q#Ov0b#R_UGcOfLJW!i%SwRzVya`N@{A zU_3R8jaouI_A|;RJen5m_uV{VvCsl`-C(5@5DU*m;X*B6)vy!xXaytXJZ3TN=>b$12-Y1n@2UNU{>(PqjQNtR;aa&0q zIKj_X+eN}x7U-H)R(75^NzdfTHK9TV35ftS%M3u6uJX)YGkd z(SCJu@^GQGX}1hBLZy%n=6S>uW>U}nX~~>iK)brGg1%#^>b`Hp;y+Zfu((oAvv|t_ zSJ$sC88}0fxLmdKt7igWxkZm!9Sw$r5CaouxZZ}A$!FI)^Qj=wN&EdSoyzTh!zBrK z@3OI$6}lhANFJY-)jz3Yx$A32$`T=N*c=bK43{GyM0eaR+e}maJa1C{*m=#YJ=_Qk2rZKS_so% zGaJLK0KIKG+4VG*yHf5})wK^lH$HjYqX|YbizJ0WT?A5v%vSfVRb5Ei55QusG;Po} z-TqA~bGjL8VqHFc2yYz+)^1puXWOEa2i)$ISb-~PJK=yLQXAZ%^>A-&&LnOLx$PQR zrmDs)Akas9l--L`oro&7*1zmdO6*j3w7LuqjYH7%>Ae_q9<`io>sNSfgkLatlW12t z!v1T<~`L(*h5Nf-JMV|GpotH(UqFGy(yUl!wdK3?h9=c?DfmWH}pS z&9cP@YuhY;o?Ly%<~#9%f=lb=i^2WB2?cZ7twDUGEdJ|>nHER9fu3a{Q z83!E|M8ZzmG$ny?bFi(gji-A3*S-958S+11A@P@U{Ab#-Bk?N8&**+zUn>1oURiBh zTZZ2OHz&X5iH==-*OUG+kb=v?O0S+%pFkx}hm2T(MTtPF{{7VDWeH)|#bG#f>f>Ye z*l4GnLy+27B2cNyoV!)d39Z@B@Vx&1y~&kWpzwjH|A$Veh{j z-Zn}R2Zw%IFaZ#2Xq=k|oI%Y<$*nas=4J;Y{gb^jNzItoMLt$Ar+G(f9iNrI?1NNn zX$OI~rjWf-6y8rZ!6M5K2(KZ`%Db-s#;Mw$2^=VxdhYZBS4)+`pemm7g{o}<0FuOe)U1f z{InUXbw7d`fgEfej`l>r{^AOsdYBA80|EWQU}g}q`Wu!h_560 zYKa?O{k7DuAtOrQknX!KQWAwcALG}}MFhV1uH^tq8d%L|qd>ddyDpm@XuN!$X@OYT zbar0J)V4nH!=^g%K*3d&`uYsSzK<3K@4Dg&C5bK$PB=Hk*)l$<}M&*5PU zEi8(-v1=dfJM1#GQ$7DG?Pkf%dzAXL^BKf+d3NeL#(Z=Lk(GiIrwK@?q>R2+>tc0p zI%rVXg36`Vs@2LZa7?+tnzl$lFvbV>2y|f1YAwEeDL7(QK98KU6tP0y*0Y?Xw~p>Gc6fK z8!jNDgAG&W$_i8dFLWsDoiKxV}E@8vr{TuvEKAIAu zv|BQNClrV;*s!sm-F zzgHZwQ*^%fieBL!IW{w7lPG7E2z`l;$;mTUu^y7(|Mysx($FRTbm@ilx^s2Fw|CHM z5$v~8z=67+Q@{53e2c_M*0IwPHyU1PfNz+fF(%&}ls9f-^!8Qb?(X3^&(3N;_3jMn zvJo;f5g-@hcbg=||9=t=wQ+7P_!cnd2;EMBjwZ-{5UM+HFgCv4<=r+f;=DeU_>eth z{oz(&ZMtx?U3RE%sgd>Ld$y9ZLB_*wq7-dvJ~r734!VI&@;+hA_h0~a@MSv%67%s= z&FVi4PCDy?dS76i`vnV4BUM>h+5U+KBDEwgVjZ8vZ<+B5hEK+HZQ=w{7ucEJK_xQr zu3<;43wHmT#D22_+I78?lh&FPjV$4cef=H61C(Mq`t_TFW@&_p$wsETmm29WM}>{u zj}3ds*1nm+!iCZ#^Y`I+Ox!O$C@fDH=PP|{cX#I!Y?3M&UyMT=ru#~L3_jC`9>r+a zGJ!CM$`^Dv) zqNOF*_=xE%bb?LfnK>^i5ww`G0b|QcG$phcl4~W$PkKGv^;}m_c`pi>eGrUN1Weo% zf&L%nb`CE}50zP;p>bTU+da`BJfihuQF{CKZRP&V{DliO@mclA3T&$rJRPqMEeutR zVD@{3$ta%9Qn!0>5Gvg?HHp)I`e!RuFvf-Z+O~ev#&o0!VPSPgPmABh2X=oJt}Q9c zuMVsH2)*>?pj}+f&;oJ;vgw$lXqzg=LC(%b_yN+0RxW3$r8I8AIfeMS<;I8{DmKRU zMypz9O5A;%6)!az*t`UFl8@7DzjG8v@*nWwp_=iU36RKQ?MmI#*(b<7u?k6(Vb8e zG2L}idMf;T81tQ@*w{dw9PgD|_)#HIjj!_K?e@hC1Jm8C{dtMimam#wFS$}8&2EEJ z1L-3ifVV-^eI;yt)h z*K_urDM9bl!XeGD87E;3PS(VjB$ViW_R2EZ0SYa#=&uxnH$iq zg*{J?L0Guc|DvTh2pJ&9OxpzM7cOG-*wUv$@)jQ~Ek+5L!i*2bFg z+d6k}c_BX(-3(N?-Y|uJkDPI=a?m9qxLa}%osjT?+#NmTD5e`9OOPc!(1OzZVsS zb0>hAZW3_0EYQPn4}p1MUtb48j&Y<((MBM)w^tIlE`1DYnS#cspKu|4vV zpdpL6=P?&k-7(6WZSp=n8bpgfOrkioCC)ycUL+jyL12(FQlE@9sSMxa(8*-Z?{UtE zFji_CMaX~~T;4h$WSXCk##jmob}EfW7*J7Rr#0mWNxX<;fpG%i-lJtCh-8B9xQ%_Vl$f{0_<*@ zF^DO+@K+oz=dp<)5aF5V|&*?&z*`HZH zM3^yHyRyp428)T5A|^aN#~kFjPx_{77=&9R_*+0ZxBmWqJPVm^_4~TL8|Q5Wlg!y1Kfcz`8pN$*7K031s}u z^t~Fv?4Ld~H1yL(hhm8ltEzSW*c`|fwbW$7k#A(wM){J) zJ*Zp#iHP?$Jb4GlTOIIowk3I1gWdu?8xdj%+?n9r#=9Y}J_spiz8%rGLo!&m2$_;+ zNz)6YZ$S0PB-msVkUj#Yq(axdWH>KK-0?XW8+)3A9*UFPxmyuyA@lb$3s;@};=wga z!Ex8M@rqNqxR1zNhCxVXDZ;SY+EXBlFBf>a+rWh#qKD2n0vzgJt$(=IdD#mr6bs%Y z13d=)PdEg=jiHmXA5tgdkn0F34Yj;Q%TYEdIi-j~h@Wf}lxgO*{qJg=-Xklc#>C_< z^60U^;$52=qN}xnmWOVOy<34*R_~FoN2zRRi>^rj#sEZ8f2i~wu5(;ya_qRn`gGQ& zi4OWy4~sb=Yfzpr?Iq_xPY-m~I<~x(sYs!)B})!#xcwF3MTmzmBEv_-e0+}_#ZdC- z{k8#lRP)QV_hS(%-JW|@XT*q(4xyXN2hV89L&xHVpFMmtBCvRvUMkjzG1H`-A<#>; zfm?OBq7RNh^FPo%|9DmZVL88w7{R6MvI}QTEVr%*+BU<|yy0&vI{EfbvV;qaUdR(~ zLA*?1+JQO9n)Vw97x+FwmT9Ov zi1%LB!Bi`~q~tzDu)HB@h-fhKmyH+#`Z7Pncs`}?Py3mxfng%;o&{0{d7^H=Z-!u! zYo10wMM%AH`6c*>5HTfngeRi(;Am1rHb{&U*yp$w+^-q>KX-)TPky1rWamAv_{td? z#_>t4>9&t>@@>H)P90s{TUY!puuR!kBEZi}JwC2mKZT&<{9^v^dNeAP1)~+BtgTW%K+|?=#c+)~3LM(_G}8OBJ!H!}mq@ zGC4TaoTa6x>}Y4u(i-GGVT_Lnf3m%dF@}o-FN~;Oy#spYi038WwrDaC9-xzP&Yg{Z zgDV-zx%f!LPpVO$-|6bQgJ%A!(tayuIgZ&NH|p3FtVo}l*Aw{>I=qI^X^v6&z=$L! z#jpN(?ZYQwmUZwr(oUNptm1vK)8K=#D!av0YTSka=`ZnZr`H!mbY8Y>BwCWeWSZ=j zPgp=e?h{jMG13%Kr+mv%-ieF5wu+C`xMIp$Zhqw2OD}M5kKFzK(F83cyt=OPoY>}* zYy<~(MiButCk!Y4)Dzuwjv)+Jz)azVwBKw#NFSuGMJS~+BLV^1jCedS1N{lrT~*7JQ^x5PlGeUG8|&g)UZcM2|N@lBTDRAE?08p# zP#FwHE>EKS=31C}TS$K1*rrbRn%6VB5_fD}lk_-Qn;wsm0KaSWQ%1e$G%4N(WO3oe zQe-mRaxoisvJ>I=!p{)bHA}_l9t28c5>?HU}Z2_ zO|Gf2+-QsCf&0$U-rCyoa$Zi3cC|3iu2e*|!(m}zHHzlW^9suR;cLsUZ;7Lg(W8xs zPdK!XX&wTw^+*CAB!&+$g!z8=?h3`7fY;{cw?tY?K@CoEY}}tBuRiv}+zDnq=^P3! zesSj)Dl@Yl2l4Q37y_JFyUmWm(8Fq=Zh3vKzn6B_d)|^wQM%RrPk=S~e==+-*ab6o z9!|BN@XjD`++g$)K5Z8sqYPoA->ra_fX9SNEHmjGV8{rYEjPF!qo9Bj z-#adba|a-|F|10D7S;h@!e zjZu&yL?$2+$+-83P&6XSg5wP|m@K6-^YS1@RSU-UcVmZ3{+41^ap(yFh`xrucqibT z=SPSiVSEQzl54eo#e4m}85~d|b6SHwM{N}?VVpzQ3vYxyh8=^NTAvw6=b-UrdVJ%1 z7#>0->gp?O^3VTSLM|#q9t9*=pKOHIksyGFi}Zmw%dI8`&vKjDL3#D{qc$U@&R>Jn zF}*hDUrR?b`RB1M?7wpnOhQbyVXhB?=_U4?slbeV1wv8yMwTS<>h;gQHZ82NP=dof zDDjm0^kJs07XXq9z-`Mqe`;U)5~>I|23}HRFC+2wRTspkdL_`wMi> zvf8N~?VzX`$xg9C$`=(EZ^C@EerIsf?QfhiU@*pgD4edW+I#LByuyug7?8b=Bo8{j zP1(_7N(5X+TEgZ{+CQIw(+ipKDu}1*cm~40;F0}NTWd95=}?(3N(-&tWRF8L6c&0L zyi{V&>#sC5cZN;$h5rrEyRFxT$kO$g_JK&<_l{C;8_yYVn0$SG<(O-oH?Ei+v^V@p zlpuXv9j;m5EdJt0sLH}HQ%#KZTP+JJ8Yb>Ge#=`<_V#^!&$q;&Ul9v{!=*}kqDxM2 zQh_<=ov`g{1tm1wSsScO&Q5Dc#GFB0Q!(=-OD&4eP#3>x@5`UP3quUMyAS64Lh zaq?l%E%mL9D}5BSI$&&~!k?CeDO?8;=)`$U+q8y_@g+G2NZ9$Tt z_>zY~NJW>L%qC%T@WK7?{P$MhzRY86por)!9ZU0!9WRt^Ce!@prGm)4qednU;qByz z3rm1*^v9nV#^ga^Cj(&)Zt}*O`>D&(`>)=f4vQ^RroOg0VnTH(Ll5Fj*D~4hv|J14 zGvUb#d$D_yywAZ5fL9U62tG#rp$5Pp3OaAwu^oH`r1ZQJjX#%`;#M{^Goq_rLG;E|L5;kRBuPXWDWQfvFPLife3 zb;$yqvrd9h-)k8tScg{i$_0bj*8R+5?gbEzVVmyjRGdenU4P#8<5)DoD_xeyX78bdJuB3^H%S%h5fN=8|2Md94 z0&ImG08Y!|{h3>vf6PS@#b@K1CRcP0)?3FcZy4O4<|Lmf!Nlz#hrdixUXV$}_dShH zDVX`~&}$I^!tCQrFlgx!vImGT;>jV3pr!=k;HV=a{`#u_0+x61qV-ZKC1O;XaU+7X zx%~YY7Y_t%jTHw0uiyGn@9Xft;2nQ) zana?~@9iPP9<%gC7YDz|Xj;vat^`-N<{*&cpPM^o+$Iar@5|cT3kerJmGo6(W6i%v zWnj?T-N$4MG!%?n{jQm?yI#`jTTtZWe_8)%wnZMAkNI}DYiA@R<@4vy(44*mgnMFQ zg{R1id<7@Rv45#Lui>8>H2=sbF4+S?6WP{#qG#s(D2T7h*2te|IZk0>$(bOK(`PyhbcwcD{P8q^UnQlrf9dsZ?r@l)w+ zz+}^t7{f7u>E-dr(!Z=)(!AkOXPiOU=(_f>r7ET1%zuo1J6)}06yuTxUU*}>QbB_fC)b0y>HXcJgoLxH_o-AW=sODn-PbP%*aWBw zvNB6Hx^F!q5vxMoHT-A|xww_^KVqx);`Q~;LSG{eNMGNZLmM(RJ7evP$4{;%p&}gv z+8jVZSJdhRpf6=i<{)VRXLj26yZ&U$ltj+Z!i|8bK3TDe9q*@rWh-d;3F2>NgSX3~ zR>HS0@32_0ooWc#Ax^Rm!x}$;_Um z=H`%2eZWl8ZJ&67BvUax{dMA!)3m*->x+tR`%5y6 z_U@4t^O1fCNstmUW=K-g;xZ;_5T2Kx97A*H*A<3o3kGYhhiwGj5&Zq+h$i{XLaTEA zaW#HcBTpi}zPG*ISh=~>Q3A3Z?*lqc)jkVbz>YS!4{QXYyl=xP0iZ+fb5MYp zDyb#ii#LUtqXsN(I7{ctYM-I@UV^ohO|3;fX@%c}PVDlIMMOk?{rbhW3~{56_|zkR zDlSqyaX%w2ay9UJImjh|U<_$=bPDjb$VfC}GzLzqFx>4!#Uaj*5*0(-B^kYAr`YQz zX+`7uIoixgKX+~DR8cb<(ZBZb1Fch|qXn$FY#K#GHtlgqYrs@h;rY|iQM0A$cR664 z@B72>a4A+pBxZMUfmeKRDdIWIPZ1z;3QkChN(*D$L+v#6tgF?{dJBBDw`uu;PBBW_ zAYuU6%$}R*^XK#(O*rVHlLufuR2!A@dS?Kn9M#a-+3>_KM9QAJwxb4|+gI+VfGFbI ztJa2w`W7oXqsr``pYQN?ZBBt|ot=Z<=a5C#VR27S8{CyK660P7;Hvc#sXYmacXc%` zdAqzVU`Km(&;plvKg`4S@*e%YfS$9t^GrO;6cDi{Y#peL>E+~#DipWrTz-tWyPww? z&=3)E4_M}KE6%OVk$>%#_i`!BN!UyDCfaz0Px{-+=7iR81o#hM-;CVa*tq04Dt9yl zz4FMq$kAzx&r8o08?5v^W(~i&sYTF00Wu?riZhAb%PwI*o<%1no_d)t` zS0582^UKNV_9?TNqU(oQ_u+`c zVEx>mtE(=1hvrwb0tg$2C`z#!*w#Mi?e8M{6>WMqZ{|vBK+%XMKwlhK+lg^|-1Icp-o?H=P9-a%O10&2K9wZRtl&LH^i@{XHug|30tYAF{)nM|3VH1Nl zRO9yCJ*i4wp9e$YT&xTiFGdpx<>{WOvYw9fBJnfrFFJZF<;wfg9-icTocZC$utopU z2HWxDy1G1z9kojJpt5mjHE60WUQspnREdEoFj~{ZB@0(l2%Ae%Pm4>Is;t>OjksVh9+pa`tGrXG#SI)G$ zNg_u{t&g*!#We{K?0k%YL5E zf8zu2<*Rx%0YkC#>d*T0HMvGRp$$!uclN21Pac-grb7;JRZFRCEol{b}`t zwcOE#>6kv&I}2~#QO-#k+L~OwoXYf@P45^3%Uxy*=KIONB#_x>AlZCh<{PL^uI%!n zC)U(Ba??1=0M(f8gyB;0Ao8@#)^kXL65Od5T3DKF{DMhbOp52o#nEET7pgwTfz8vS zbN78phOb{VnMj%Vc`?!GK>}N&4t3(gO!Ax1w|BnjW-qfxt(G~Skh=RTIk6^R1;>w^fR1^56hNd_u1V4}gP6GrzQf6VM;3DnA>B zt({>oyxex_@V~BMXKXjLB%>|Ip!BGs+*Tudf-`;9AdWe)v$=!zcaTX;G7K%I8D;uu zUq&aBIeOTW7yw6@m&+wpjsG@wiHI9d8kI6q!GqugGarDL-FlXtbxp9a!IR5trlRaZnu9c^+unc&PSND>1CUwjG7BRarq7EqYV zRvvo%{dD4u?z&CM9IVsCsSsRVVY4!~L-K8EZO$Yt`odCp08TN0+ zRyJYFCOkUHulos^KQ;ZUHrh^#YAL%h9?i8)6{3UMT*Rwy;;6nAG9&(or0pg&bLA#K<*)$ZJAJTqNM)-12f!9E4Gd&ZF7& zN&pa%*%7Gct)ft{sdN5##({Ow&yCi%+~md=?#`XL_ruo#Z@`VxrWtT3yS87*JaK98 zRSJnGY`4Gh>JAih6`OU&x9#4{z@6@qVf$a9brcP!3(;m+?T?En`MSaih-t)~{zy)VjDPA^fbEf<~RkZxBMi;V0Acs+d*W{d&%0CT z3oEYfreK*`N*X+Q>(R*jVT7V>kHzaAp+oW|1fafpi}9w)kkN)i4+R@HQVg{6rDP(n zU@?;@Ft~fMMN>Lv3%xJBQs|2^oxMG9b`_e?ls-|egUPKxl4)=zb$$@3dcYs53BT_t zD1>^UFABHeL{ejH{OM{r{1hY6;1}&=k<=ZYE(vEVj02LZMPF27kQrPvh*RTf_)fA8`^-ejF7R#V^Mh17+z`^Nmm?)Nv|omFG4o zFay7=1i|Y{0-#KaYP)Y4mu8`7rY}WNz+eUd?Ah|;3i~g&ssgu0VZT}LALto61phKW zzDgmUWHRF!SpUVcye`3wq{5^ZxE++iVEqc??oCN9x0s8`BulLJzeiEOl8*azw973e zuyRsC7z8Bpi0X*7#7X{-wlp~;b+*pF9036$kmdUZJ0)`^v z;e#GWd-9DEwf4W5^V((RmKmv9XwQMa-6PL0JiuHkAzS~sC?QYxbb{`z*BS-$=d7Km zAbWmi&OftE1`3>^smD%UzFyewE4qido%XA*CRoM&c&M)}{h4-w88`DN#6Gz2RA{?; zoi9&egR;rDV`?EBA84jZQ9=dY0^o?CGpoW1rF|~T9E_|3ES@H$kz$xBQ7HLlovGTEp=FDw?(JMu>-)m3E25aA3q14LUgW6GR=3zsPTlX2+vou2!8 zdN(+W;vt@y5{1bFi7koJAmmX(%3=q0rgszfoNu6XZp{HmGvy+T*02cG3m++Y880z_ z(di2JXfOTKjW5s4<8tL`F9O1pdqXv=Q(YAv8OEwqh_<&fq~-!wg=QeUdmsh!oR{W^ z=?fq8|pH%kN1PBkE1v)F4PaPPc#AWWp!oC1kIb$!Puv}r3g6}fYxZS z^RL=PgzD8>7`hDc3Q_anW^N8j?IK!yANmn}g?eXCm5^XD)`$gvXZ`p6$IJ`#vNWM- zrf-z7J|56^9~_tpSek8M7+rL(qF5miQr&+&(Cyrvf|ku}_(fmJv7gy`R1`qZIS&{$ zrL&l!_nAMHzK|QMNbc^}F6ke|b)Ppw^iqgQ(jx^8o-nA{A^n369@F4?`w^NkWdP&Q zfkrs>8bz3OcY`w#X8*fqriViGVBi|~H$Wx0$0I%&BrqdDhB5R2G)v3)cOKV|aR^s! zSGU6Or#rgDa8(C;hWb8GLiuwH)%!qM*z)zNDbTHp3Sc?~fiFfMl~J*QfNhKeAGj&A zg6jn@s$JxN`dw@JJc&`p=2pPa9~Av8FKEfDuE$Hkj0g7GP>UfRWGnHu z=4OZaPL;b5+*NK_MK0MW4}Lb;oPk3RzYY(egci(=Dj0e4G%b_NQ&`I>q@&i-YY|$9 zgLBKa2?jn!Fw$Lu23Rwk^X*(&S`1FZ6}NygONSPam6ze(-uH}Pa2sLxEw37kT0f?z zMFaiOf#d(B-9x)j-wn>dU=Ouftw}6#R@ac_f51gV1N?jC!S0c8y3uE--fCyk+kpx^ ze6OxbH(Tf|%IKd0DCC0)x|Tx#MVrgoe&Jh59~353U&pff>LXO%FJBKw$_^3y=HWNt z*)D=tv#cX4!>xNC;<`uR@36%%bJ+thOz8IcbRUnFkM!rAGh$3KHP_tRiu$faL!KQN zqx5nnswVFo7#oFBerL4tI>j|yp4gLS18O+z@N>4FE~Q?;YUWjdr%0(ucX7$n!};QW zq;MAsaV&S75NDM)ZB>loi1UDlJG0grdKS6yt1mk{z5I8lQ7X9X2)NT5&3ALoj6M~d zY`~Ny!6C8z)xY1*_N0}l1KHJHh+bCfEQ!b?LQ2&!XyP++G7J9>nf6bICxOu<$#5WIRS@uq@wfiAgD|h6hJZ6j|fmzR9$6d9- z8rGF%&kC>EQUwbi4QS8}S;QGvV5|U*n|nf5ZWKeT07JoV1D66<|AX{%BZxcycOT)* znywb&+@!!+bAtgs4J14Cns@-SS?@7w;>!IFX;h`qXGX0XSWm5|gOdm>rejfCNv@rV z6J`d~_VE^|-Dc0L^j%`i*Gt17dwW=|VLGWSZnIL=Ib$r!U?(*qM>k5W;hifk%Mr+y z;7>w0a&kd$D=^zPJrd34QhG%Jo&?PKlsbOSQ5ee+!YG#)nPk&wXRcnDgF>e1vzZndp%iVtRRY=CMk0r87~2 zewkM$!YO|Z*Qh;btNa;mLmXmf1wL%NT1$TAp9mn=aPBvlEr%AtK9UxN#I*I74V59; UD9~?khXMRpn%bH)8F{4qAM}nFRR910 literal 0 HcmV?d00001 diff --git a/python/gym_jiminy/unit_py/data/cassie_standing_7.png b/python/gym_jiminy/unit_py/data/cassie_standing_7.png new file mode 100644 index 0000000000000000000000000000000000000000..37ea5e9b0a24ec90906b7f68062541c21d6b07a3 GIT binary patch literal 22425 zcmXtf1yoeu7w#Y^iU>%jq;yC(NO#8|DIn6_4FV!VNjC^ccXvoi=fICHX&Jif9sln= z)?%%>Gxwg{XYX%+`@3PP$}+Feh|wSr$SXNnNp%PW>FnSC^C#dN$y(VZ2n703PEt(M zBmJPwGoEbI6LAaAyhJp?Q@_9e@^Ppyu^BG@u@hs|#V7XakHEkyxv00g$k>FGK?nPb zX^V9TUGp-W?b4nA$7C*w>2EdIDs=z#e>AmuFD`DeBZvGfSkl_2=ODOI$2&9t@oy>#Z7ZLRQCm96d^M30u z>aKJDSIl-+(JPJ#3OLH$+R2QXaF6zVNU>S2t0I%PVQs&)0()X9JvY|0&$SP zS*(g-&DAzQO$QGgNrB7Z&MNt`=BRI9)MY`NK`{s@$99z2Gm%n14Tpcda1d4REp=2n zq+z*(242CYS*rE~-bvs=AnCN6N7Mu@|8F#NxHEL_lsxL9*&goN*@O%UAd>d>OW}W{6a}N;0OKnR`0J@$ z){MaiKELa+IAp6K)pI4I4?%$hIH_K6%-j|)2&xk$X9H{LZ8Cwgk-B@!3fUV5|KA`+~{gcLl`>HFEZ5yL$TX;kVU6{d5?QjJzIQ2V`qxpTIr#@BZB*^AR5T zg{T+;DIYN8V|PT+ZZjFzdj{!bz>zTw(&Bw(LIi;rDUy1!@OqGHx5>Zzfd*OqvbcJ@ z*o#xSryV#9+U5Ya4!z3!Z4j*0fL#h!&jEGNkT&{Z{($V5?wc6|qRi=dR=2nsCREy- zL6L|A;X^TFtK1ufY-2zwGs1E^GJObA5%m8I!7YYFi2WK-@w%h&39!LVFWQw5Eq9`S z!yWo~NvFU*7*_pcrKuE*p~TK>++ugQT+JB=F4^d zuuoOmtRl9B@qRVg>+t;SwsKDd)fE9jd3ro418!$E{HleC0`BkJ2KUn#KG5Gkkk}nQ zcfjr8fLtY>-BxV>`x^0Y1TR0n$AfglbfA}D=tu@OBd-#09RA-+LJ4N%0L&kM-<~3s z3S1F_M?I3yQ0>1}?)@MHhtebZZZn#LycJ0a)$AMnzs>|dMYY9TuPQZMKJkD6;};6> zxXv9$wTDUEgU*l8!OE|u4p;GV^e?-3vjtqfhsr`cBwH7=_@9+v3Rx-EXIrsA^5HWmO4=C-xztpQ4#f-Iv_*xLpGp9atIv`{RCHOZlmtZqHsp-RHOGE z@N4|{vj{5K8H|_^EmVvz-~fBS4psgv>Z3vYH6K|f5ZuXHO^z6TBXjp;k@Cp~MnK)S z?)xT8_pV}O_kX`~RQJ1YeS{;CgGPVo_N+ZD9vf8d1u%h)dKbnw&Gss5IOD&~iztXH z%5)R5Dtpt0VBT6BxWgRyx{tWnE;_EOFTlrl!c90WVC)V5W+_kgDl1+ZT+#j8wAa6j zho~#}I!ivjrGNB6A$d|eH}2`0QNp7@`FMDv&02&qyRH8aTH?9t4|1O(5wU% znmnZ##lU69(-I6H^mM`J_>)HiK972!txGW6!1u)b4AJR>m)*rdKY;zMI`=#@$j&V- zzlM-L&HLV&_5DZqeapYgMWib9BNE)Aq1?(nigD1%RWOtGJx!?qBqAFZ`wDXW$4CYKJmnW7qY_r&#*|y|ueVm<6+5ZdipLpo-xy(}W*GZ>NwQV+*R;`l1g!7IzBpg9!~GvXyhTA)OsU~%F;eq|h&=>9p# z50+C1-D@ZyT5a?oBp-Pd6AU#UG(6fCboCS>8mL1%PQQJ@xV`M?%?5$Y1R=pGoO+8@ zI*V(bzO>V=T%|prc3-&vC*De+nO4oSvm2 z#s4heO6X847F+v6O07#ziKMmoutRU}+gkCl(=_!7!xC6Kcl-?s(psQWhpRVv08#Mi zZSk~AsDcvdjPJ&Y!7DqtjwNJt`txI?F61%sMd98aA~)l#kIa78ODk>CrDRMvrMS+` zhY>!|AmtmT5x0EqRXe1O!xt2Y<+VGJwJvV$Hj5MrD5L7zwl?3DtG<<@j{17m>*dRb z-roDF#DfKQi;7QVWK2G%OO}!T=Gz!F59Jg>N9a8n8X{iXc}${8>3Fnb$%N&93Ir-~ zo2%nsCa)e=$c#rj^z@cZdGXq0;&1qZ93D9jo7*sv@*Xp?to+INPnUlaZEulU)OBmG zIpkT5doH;ani+OCvwY)*g19O&>kh2_r4Y!Sv{6J||Ld9Zc#sql>fX{+xo#wgw*X<3RTGRS{8AJ1=nVjKxV2y*sy zj-hkotYtg8a6c@woSl_5?nhj7C0=!KR$1+&I*7JX~=%b8yn?m*0ANz!T{;e|GWa1m=^Lf0X%EkG~|Aqj@YlM=R|0u6wD^ zklhvgL)Q&mbmK|aCK3PX!|%Ch1tsaxc2O_4R1UEv*_cQ{a}vBc^7BteH`n%m3~p5p zb>>_~E0VZ)md?{WFaEGZ-;}?sTW(h;H_jkg7jcqio1wdW9F8JTmkNyI>_IpQ*h!7& ze@uP+)OV6T&jes(XYBS*Bj1g!cDt7fzQL}KR&9+0#I|X*3#9d4h9V`|8BN=p=ADuJ z-f3gq$&Ai&mrE=!oG;a(c~NOUa)|wnmpa~*pFREG7%z|ysP(~$L@>3_4)tm({^ujY zW`L(QGV%%vt$-C8q6llwD(L8$thPp_Nm$>7xUR5KA&gq{#BTR@=9pgaZQBnsPICs5 zW|jYnJM_Fe_P@B4%*@%r7BU(|Fu;^AiA>?YM(!z&KBU0My&90s!e2B zD)6;lJt(1i>OQXTPAvx~oQ{a85RTab_fh40`&r7k1X^)-ZSOqt41^(4IRvF$Qy%ZXnMOS_`oNG+bg z@IS`qU3>8T*;3EwNeI*DdtSh!NJrPLBPRq1;OH6A-YkKF4f%&yH`G1BF&Blg-` z-cH=1%e%UiRzeqFva?<`b0!}D)X!%xxH2sAOG{)dE8onLP*H)}+s`Jls4&2&o`0cu zzUGk3PCHc1JaqPvix_^dC6a|1+O3eZJiqK`t+!BJUvJiDG!bi^>0aQXv+pT<$j3L(gx5~i1nrIGveA9c+0 z7j0;k!uLOXTgzg6)q~F{-#yiDq)Kn%rZX zPRETC%g$C*Dq^p)YWlwl5!XD! zMhp2}6WVPY>#cSCk|A}VvgD@xwxERHFZNDwELqv(YW7&Z$nf$y<$BH8k?pRyG1YRD z%0(nDXexo_I@ac*RltfEBNWaheSR2X*EUTZqHVDBd{bzi?sqk5_(=V}!CVCE+VR=X zvpt65TcI)dWl$rOKc>Im$sVDczP$k_&EaE(;hZ_s7Fx~RzcI_@xS3@MFdPT>tdsm(B%kF&w2Id1aJTR{GRBa& zZpqA+IhP*}UCvoy@-qD}^Q?Pwbz3nks+ey)9t;9p#ZtcMezJM$yDqx1G-blGA{|H2 z%#4=Jb7-a>OB*gehJF*?BYsh0wt=Jj^1BTimo!w)A!9rgD9nGqEbDdfxa;glDyO-$ z&>JXjUY^-S=?CXeA3n5P3|8Tyh17B?<4Fx{I>omV*s0R(>%v*johOVuvD|0rkQ_zY zH?_|*%E*V#^1jdH<1b!_7vZM;$=qg27yGO2vt&ECJ9Xb5-NDP{62sg?@w`}FLstA$ zStUcD&U`HM*DtYyd`;x?x&!I1OOAEJs|xRnGY(XivV8%=*X1-q)!{wj@dgDeb_4zZ9_EgPqVAnc?QhOzE9kon3#~HI_@TaIQlzR zv$vv-Omx%aGi_+NIP_Qy^JXY+!uL|>XL`Hp>oNFI^-^h66`oQ44+~VN((W7_-1hN4 zMEPOZY^SSRRD^8pRfK+JMJ(T2i(wVo8Jzz$H8uT0F%5@ro?Zjj4l|*R+dVw=KZir> z{4<9(HKQw@u}Rssl&u@apJ*KUQmb##Q`^2t9kj!l$1F&1OiTNX(}{rMeLz=P#GVg~ zAvuE4*ldqN>1d@vdrC^LOe0cJe@^ZG`t_@?PuglhVM_J%`fkkcq9!m9sqR;Rn`FG! z+M+^T#)OFR{>-R~fAf=U2It(3phRT+9EAwv|3V9dy4>4Of8K$Mz7C5EENjS)ql97dIX*G*pz7gg?MOC5e-q z&vvmsnV*=>SvUO56NiYg_d8AdLczs5)_T3AGM3fx{C+`%d1A@ouJ&L}am~1hBh|}Z)`e&L6N8Q{EL6kiq||(Fb_?qK73wog(sMY< z;O+;HbvuI#3I_!_^eZaQS~ z=r?3UMA;oVb3bYN_mZt9K7XITxs>lUSP(r~Sb3;t9?GHLI=xn;J>4s@H)`dxnK1wO zY`GK}`m_#Zj8~#>h+v7}QoI!A$XB(-V;s78%CK&xQ?oVZ+>}la3j>E74L&^$_AWJ* zm@!$dV5*v#4*P`_nj2!VDLXq`A&K>E+(3SQKG?_)iT!dWNPi&#+ zb{L6dso`$^8wouO_uiZ%<@osc@xH@d??Fv7%oMraFbfNDbg#eVgmW-w$Q+8V5cMj#+N+wGub&efRZhu}Wy< z=4{+-Y$7Ba*`&C2`?{w^`zsmOsvIziPZE@MyCCsBYHp6 z`(bA?Phn(aBtCFBg)@|jfLIBhz$2YIak@Pgp2KH7Q~HTRE=91cUGiE{BrAz#H-x~D zkeGO~9ae6Nlsz*+u*9Cx7-vi8NKQuPyP43I=!dSX!Bw~V&R{L@zM zmburxbcGiq?D_qrP+p)*^lTfySvS}1w`umNr_SSuc$i*Tb>(`QbT4^bnb2gX{PC72Y5>Nk7A+TNQt=wXz1k#KigMA>uXWW6A|nDT>l9 zf2Ea_M#jfgxrob(iYVQIO~wuUZ2s?!E5i??+uK_sziYDt1=W6bTYMv(&$&2WUI4$4 z@Y?-kLX9knijICfNxJ=eC&Zk8Gm+7m>gAjesGZ>bA3fr(R?e{mPnWwRCZewRR`iWz2P+mhrBcf_+>+^?1Yin!Ej~aLubtdXcpHHsuX3F$jE5x~ztXx~` zb-&UxB4TN5|Emlne!A_{ur%o+z^uk}qEJzNln@66SUF|d2uEL`fgoO&3{{LKBR4yHHX4^D*DKda z%s&-1bAMI*Z!`=}MhP_p|HFlOPbf;O#RIdeYir9ex%Uyt8rqC{BkZ@{6X2UAC*{Dm z+aocDA(~}4fjLsxc&dN(K^Q~F`_VT5W5_o}x6Sv~ja+zMgC5bOAN7WE6D)1^+e#3n zKGy(Dk>Gm%D9M_%zqcpgb5&_aE)Jat^JXvup$#O2zy-$df&->V%V|DJw`+-EL@T`H z9uj)PI>xOXw&QmRi>bw55-g*QKg#-+lv7q#H$Cp3P+-K(Jqylx+`v0f= z(o23(7FV>TwxmxmA##I9m*7O9@hXoouW&0~e)I;(I^x>rp?SZ&1AxeIMEzzFmpx}f z@z0}=)HZe3hKFfXttW%5(THYKTzKi~HxF(_rpv_SFivyjwu|{O`gdW{xf>fB&RfGV zG+~T}ITIEcnw&XRB{`o>?6J{=FF($XTQ*uNH6GAGPV!^ob)yxgaeymC*Fn zt5?S!ck8|3$jHdR&mVgTVTbjYRDI%LkW=R)9o;^)szVRq)Ep5Xy&un(0N$SEeDBk8 zxEtwI4*g&^roSm-@j9Za5-=)fY~r;Pc0wzAp-{PNXPW{v#YDmA}im3PVWKD^x;%X%d6KPD*BECwJe z!~LN>#@*KVX>mcQN=d=Z8aer&@+s)hc-q+rm6nkqGTn8#$xpK*CL_y8PcJPh0{-Bq@#OKbqm-JJ zwe`j^UqbT~R*7ygz1(D)eS49fl~!o|yn(N3!AUjqiu0H-?}`uSz1Mg9_*Kb$BoyG8uVGrpY4^QIAXR{A>mX@A} zZI>X>0}BEjT3cB;H7!n0$LG*bdjt?a#{T`k@m~L9@W*;5~q3urh=d*Nia*X4O1)DCqpBH^Hbz2Ls^p&)X zTj%eJY1#QnS3Q(_A~zE2E_-C=|I@imsJIhj#!nOWc4JKn@819*GXunAGP03R9M0RL zN;KF2BAlO}7in7g{QFCPc$cF1Rh%+4lQ>d(VdY^p2veS=sQ`_an-+)bU8Hl8ndkM%X2Xh~pegg4=+N#pSsD&@_9`=l`?f~XWE`8Ahd_X;tE61m73{!Q`brB{K9o%+ zrX}1mFRz#}{*!)?%zd%S<9PiO#{eOiI+rbs{UR=_)oTxz4M$^SE&1uO_T@_)KIenl zs)mRd2;C}`T{>*?-Qk{x+QWtYBd6Rauqy!Kie#zKU<00$#&PU(4b4iGPAPEid3l>% zAus>TB$TwxTMEK*T-+bsoYa55G>6Ux_J$MK&Yfs-5$9nUVWHf75Hu{#u+#MuwePsU zSh;Om8QOFLjx0>_%gl@H<*taTS;Gb2KfgoW{FGTghH-Az)P$VsWFGKMeJjsmNk&G7LH9*yH%&z>4RBa7?Nf`I^HDT%=3|Ce zyDCO(J}+);oSWGDbX3NEm6zWa4<;EOulE9|0M3qa1VD&4H(q@@&d#S3xiT6>ni3Mo zQ#71kD1T^8k^FeN=!_YrBR1MWpM6yF&V zJ(E}sCRrDL(sJJ4n?G!b`q}o%biGc*e2_SHO)eLC)LFb{9=+5E=+^Q~2}LCS?-1bq ztSO;VHb9w%zcZ;KJoi=1Q;&;_JA=mia`sL4b%0#mq$(;3mC5V;0kn7}W-j!`-p1x9 zlDd~ZR&X4h3P<1cf1$Fpabc1s9v(Wrk}TiOWH>ek6_egGv}=;}Wyzg#4X1`-_8PMNj@RH8!4?h|26DV~p6V#7CLm6Z%>Zc&wj(i3Lml+wzr?SRm za@9D_!Koeg<{~B|CeE38VwIcxq2_a${`Gq>m=*uK%_M*Eyhvcc`QFc^)HqVmUoGqb z&@l7ge}qfCSjCM1I?uvKw(2{>9-F2%kL6!ia!!c~Gb02@pF8*zZ9H>y3f87$N5w=4 zJAA}6WsZ?mZGVjx^63NZn6g6JSMh8IK4zE+Gd?vhS)??ZVXN%A_wl-vT&#Gus;}?; z%H7BwFhFRt!sAu+qpF4mPNX!jSebphIRApH&CWpNvmB6YWQqEVnA)s$g@90ySMnO< z*h*k|7+@#n{ud1)3+~pCbaPWXJR$marX|9AYJ@;By2F>!4e83GddvCf=8nfJko-E) z#;JAhgFs^STbVXB$E{dd?tf%UhK3h7!F_#wxiZnQQy_nC*)L~f{orJsCpZVMbH7CJ z0@y|sV_|8j*6Rz7BJhayH(VbQ7Zw(h*o>6%z7w$Oe}rmW0g&PEbbH`Fmdfou53Q9z zwAl@_^dR*XATRWmF2ao(guGj_@L9BIUiw^#19`*~Yy;L!f2NpjTVv>5?uKsEuGClT4$4&;hp3;9s z)c;LS<6e77sTKCK-5dXN!ZjciYZ^H3O*4pL@z~w@EB@^U1jZxSAZ{L>ndxc$gY)F_ zq9T6Ry=hFpBV+@aRMGn>(YEWYw77vkAmgQq!IFx}|M21qh1?{x{RD0$@(OS1Th1ZW z#36*EyS}xk3FH3B+{4Ft@ACF`iHr=W-_{+;30mH0;OHoUpkT=>l>B^J>X>iMJa6P^ zdUt4!t8|#tMv7fwC`6uabqUlV{I0I9p%`RbF~j3$^dAzZc3lh%$dtZm;hH_%U568} zi8%fFb}_KDv;@F~E${=c4Rkvz^7FqkdOkx%jiBM&+&wsGx#>>8On+FJssD6)LB^L^ zChnc5iFzUA*mCH(ZD;HD?9lZ49?qKlY09DhW0u8h&A}GS5g|2PhBrlJW&c=kpOQB6aFWz9opO0`anXWk zW=c_S0c?Z}7_(qzNK4u*tgg;6%Ec!N1E zdmp}g`|e+W!VQz0{-vesD~E-GeFGxNz$XhuR}YV5t3Uo{x#X5IA|01)<_q(QL@QYt zf<_A+{wg3Tri%H2q~&xBP!7O>-WPv8w=>*p$BgQ2=Bmwx02biq;*ykjVih^E-g^*E zux~WK9N!?_xnrPX4seNdsWKZ46Gf?Pqi zbPhgAcJo0ko-WfvT#r*?o%Q*XP4Q{6%yQngwnK6epW!bmJs(<`E=h}>t z6fzNup5v<}kALVMMcz56CvE~xvo1VkenJtq7pURn=@3InYy?s<@dk-zd*0N~yDI$e zNAnbf`mz(c$`+j`(|Rx>Fc)+w5be{iUpi8B9;-I1zin8$*adJT>g1J`=yyQYT?^F( z)7U1MeZcMg`t{jOpuqvM#N*9+I9pUiL?OxD@+A+8ffbkMW553$>K-;ucyFOys1v1J zEI6Ex8=?=ns*6**TnUJX$jAx##cJk`vq|NbqB!La*0nSJR(8QTFr$=4iT;uT`Lau~ z|JQw*y`k(=&b^bFFBGb>;y53ioAhb0!9mT#&1BE7Ki)$imRsB_n(J&A4F8d(BtE-Q zQIF0bN^pHA!3edS$6X>N74mR+e7LtlQ7P4}lgC2Q)uc%pQga@>ToJwgg<8OJ^G+y0 z$%)*7o3|^$4-sOE^V^Ae-H zXT88^anT|pBIsc!^VZTq6dfkI2w~!kmJo+A;eFSdGE!FbCycBaQ2{{lxXz z*J_pU3uzucYCx`XIfsrzgWjITu9>)$>KqsR%U^omkdqfw%fePAvauo!V;f6mGTGfO z{>~*C`F&`~FlcFxXeG^fqE{~@zwlZr#>#caNgRsdnu_f>rNnFCzVr$iIf>Bp{(ig6 zd;cLjhm!ucuT*kTV&HgEf67f|K!LeJqL0(=q{>9?m?RaufPg%e!kXYYZZ0Wp)>uu6 zQV)%sfXC5CKy15dJnPNa+2y}F2mb!$3;3u;E(zMDD>%$Ws`O^P3+I?K_|amBAyr$3 zPn{u|aXe&VFC8B4#vTjXe2;gh3gp^x!g{W*_y%~jGD;o`+6{`s3oeYCY2Se|u~FN+ zDtT3AW)LV+=4LS%7F3f~AGk<0U9gp-+=%t9H7yp3sa82*#~p@bHk8}v9r*^FqWU{5 zlzteQmPyLz0K5&LN>bD0(G;%HUzx^M(_x2s2tE9*8Jql80&{fiI33m2YTv~V+?ydX z%~l0@Zicf_^{3skhUJ3|wjA7YmGvp?|MrZTZkrnF>WWwLFoQD}=G>>$T|SPJ=Nr10 z)Y`8gFh%%c2R;##kXV`&)5z_~7lX2=6Tj=4&4)yg1Z0n_Fqxcg70??O7+DHV>jn@f zR+YG;1FjI1TDw370ZSyf-Dnx_N=V%w-@|^5)#RSjfc_{xCfB?U$$aUMuN9f~aJC{N z6Iv9AF0~fHzQ@1=0>kOoLJHv&#rCsF1!`()0sp0$`oFg;EBY=Qy6qQr@KDT4EAnhd zOIU z!osuYZR#O;%?!5N5{aJo}LaC&jx-UaLqc*+8P?ppgwZB;{OP;O0M28$q&#O4qJ}X zaf!?Gb61T!apVFQ)b|?=Tptw{BKkKP7Ek8PGw19MNNE1nUxe7ozV}Rzzm?B@XV_y9 zE|x9RyiP;=srTC2*8lMsWMXG$E+A|C6hS8Hm;NTYe?#-2d{jfr`+}p7MozcoB9LR$ zxBDw#pADM3Jm;Tt#|>5sf%S9rFdCYk6)8o_3BNpK{(@? zEVMCa=V@}>;m&E6QL%UMaGl$^RdMD|rz8iyyFYPy0N4{O>AGM3iX=Il;=##3=lu`P zW4tF%5y7r7NjODFgcqDDsFIgkr~OL%lpc{M@^X>WDdfU>oi2T;{$NfiEi*!rDx^2c z>O(kVe|&kVUW4)d&8s{fk68oTz5Jaq%O#P$_i|MtYd_6-e_tF3?g;AESv{RjCr5ib z8WmoCyKaYIeI|Y=^em3Zy=|@DHZ9Zl;&vVp5uz2#bs`rFsHZYB+@_Y>&e@K3!+QyA z_vUwn%UKTz2v3`WNAg-##+Q}K2F_es8p&OV-`Qj{ROpORJ{x| zg9isgNh~d87Sqd9&XqOJ*7o)UT0J!-)#ZI0<&p>G!}j8~RhFb_9O}{tC72-Q$}-}LixybNX~q@xfYE8rsRmkh`q>4#H<(6WZ*6pr){CH1?w9;`GvlCi`T z?={X_cD5HTIotXZN?SC&KFitZ&FFUN74e}yGn@{ACC|JQIUDx{R{3{6Mg?Z^U)}Xp zt>JBU=*-2LOOb;AILceW95*9B>-L5VA(wuRZ$}x2LIZcM9x2^=;)kxLhHsl8+rLm} zRqY|J)#^n)>FjQ+oh@edr5FR%U-l)>)mqr#twIlk+2`MXSpQE+v2fc-*7~BYL7FdJ zQthN#s2IPDfU$*#+t@w)em1;0GAFXt#i zeg8Nmb+1L|=?iujTENsrtjuRW3&zh*IhAt7B8 zk5h>kDulZMYg@*`mv#r>LRxl~vv*tCl(24CY(e`IuD?b41`_~~>^({OtkO!V(bN9zPpUQxm3-c*1`M@*{vD zehIh|kHbZ1<2bw5f)Qg{@b8=HtX8v(xA{sLs?L7zgvCj)#Acs3HYE3xKW^98&wvWz z`{y=qv&c;pHT~aqm+Ko`>yrEq?mqtHlo+FAnM8S~oL%oD8yVh{sp2 zFP7+>!&jPC{gXAbpv1SdtgU@G|KyrdYJh;}dyLt2AZq*ddbnuyu`PteVOM1|3|?kLOEADf*?XE#k0x~x5AQKymy!z>FUnZ}vd)Pq=cCnM8D>w2 zygow?ciN;<`tZb}rYR7cl|{@1;zqBo@7|e0XNFB@KQqM0(hx_&a*}~QrAQM{=hA7@ z`ck~l40Yg!nsYCIQJ`TaBP4OtD=^pnUX7|028~05>6L$<{8Wx%ka`iivF5;s3kw0n zOyO50z%JT8qyIi3b@@slfu}^K7k>nS}Xia4Gb7m!G5N%}r*CwW<@<9ocfPSwzb0xNRk%?@4hM@~LLK z=yh_=?zHS<$KyjNRm^YTI20mDh=6vW{oc)J;vgC06XRRH7Xft+b=X1fWo=o#8N8-; z#LtCW>Mzvx=gdABHrRDXk&UU5%jmkx{ezCx&fC9o(k8i4>*eNLDLNUD?U&LASF;Z% zMAs47nUeW0wha7>s`2I33M)E;Fw6O!enw~hP}f|nQxmLV{azIR(Jw()h-PPV?c!m$ zdmRyNmy>^7B|yk#t%e(-du6wLhnwPl;098$4zF{s1M23ec3rcq`m*FQ2PUkUbrLZ) zWYL*r&h^66@D#Sx(t;^;cXZD+ zzGpXWD7^TL56i{*KlfbxiH97t668&ycUu_aGc(10t)nk}iz<@;a1%#Pq7ecc#6`n1 zxD{_$C!3P>F%~JOuXd_)OqN$snFXM&-ge>V0+Q`Cg3`=*JTfy zaJKJdK~b4|m>B_>ekWg*#O?1iAG-+VT^U=gp-BjSOyS!4hK4jh)>2<)+)Kc|gOl{$ z_^;p5YWwmss}+W#ZQympd`W-GJ}*>iN38Sgtq-x|Y+Jyujb}kwZ*qvG-jU_w!ES-_ z5ekHm_jNmaL{hnKEbhy5pm0>N)O`V(+;b~@5=$dOicw*3TUTdIUT85U92|m#fs#QU z5j{?f=gtx`Ar#RhntUNWQk)%Q*=ry;_RT<$sBU<5`=3d9ouzgQCk;)Q6vIAe00Cg$ zJwS97TLvD_aS)ha5P0&DKG+G!VfWO*xbGY5TVdM z=|T*)B>H%r2k^MThk=h25<39MpL*62L@Ljr~*v+_9gX1^)2REiTH?%UgEYY9-dIrcy_ zsR|)exT+qvxDjEC|Dku91y;hKZgT#wX2*)Mj6qOzfV&;cOKFq)9IZt~#V!T-hFSK1 z#hGj2oA86U`;>3I7jwxIH=+lsg$e32e;`GyX!E(=&h+z2iy2Y>t33ORiWFn&EDy-D z_>BZhA&UJx6@RyW{bG z1b~Og)-#}f?KtXk{xhXzQk6_2=Tb*e=D!}M1hk}9TW!aYaT;)})gy@s0bY0FP|DN> zWRZpTBy2C+U+6>!U5SRYR8FabKUq9KMW}6+FB84%1KQaYUOYrPSIYZ<4WUizBm)H6 zi-d}2b_)^l;!J1r>{@ELbqdUubh*lUl)0w+GX;Wz4fwDY;&nimU;oiofetxP?U=m} zFeQJM7T`F2LXbUD>!CcNFfrdOnMmjDwXD{g!9ipY648{}D|l!F=cXLT7?!323fl|B z`7-M7jvq-+kd)7puP*qp-SG-rVeVt*)Zf;nu-!i-N~vkyN=|kRR^N3ZlZ5l&GL4bB zGXowumZk{1!tkB!+*7gt+FJU%cumOLg&$u3$R#W7M? zzSbnZ1BLJy*?3*lI&`DQ8?U-7Mar`)J$qMZ)9J-p+AU`gaI8JCh<*L=7Fcxd^?Sh2 zmNnu4*(ZDA*tX@C8VxoGTMa-AoY$Zh4C2F`n6KV%rikfpxff=m(G^|D2d7#OfJWSd=<-ckgGs3iSZpt58f|~yVj}`o;tAj<& zj8hoP#c!3e(~-i1AzHN8ptlRATiCSu`{WZXr+B2%G`oteDh^r*p~Ba0Zd#tqp-41w z?b~m^3zAT{bmZv%emp7HCLQ{QTa!ui&}$)Leq=JlE)?@S<%wDT#lM} z?gzLuVir6Njvq2(f4&%TEB|u^vTx~1w*y`Qfqc z0Ihcp&Z*CIhIRJQgr?I`SdmwDwa1{1fk`N?sqM)vp&Dt@Pq~BVj4At|(eU2?;MKoX zExzt1egA1AB08#*X_BJD3`(g$Vn!oZP5Lralr^WoG`G(61;(?^ayYDAMW^rEJw9azON*7N*tI*gXXn(%CJ;lk1P!~M(F z=98F&@{T`PgwMsLl-{)sy7uUC6xKNP)NTH-n^e_PZ(zHh zNWq%?wG=zBOM=hE%S}_StNkBI0E+=CZ>g!NK+PZ`((bf54=-WL9PD`vd&L-{n9VOE z>wXteBhgi|Zda0;^kkw{$-)}Hd##clR;3eRBX}NaT*^us1#O<|GM)r6k%V`d0I1R@ zEHpHxc6NY-$@lKq{1xlC?sF%h3Js6%nwWG*QRY2Mc-(AHHJ5c!#0EdH7OSC0`T$Xe zx{q8e?%Ql@a&4I97#uW)DcULms+%)2V1z&*Ip$Y?4)_=K`<8%l@8{IN!nGP*v-&F< z_3$zl&_>Nm0BC29W`v2ekVs^!0+N1#RSw%UOttWj5L|v__UkKaP%r`f<)>xmrp4T7 z5!-{ zcir+eFP`bo{XB`LL)IG*NH$KfA%j2&ImZ1@c42 z1W-x`g7=8G&4_6ywtOj1z=X$J|!OQIF=!T_Ty1Nd#i%qc6 zgJ%=1{4@+qux@~qu*0}`d7~pE0o|rZTjPFcTw<70V*Loxde;9HfMYx#|C;LozNkiP zf%i%9vXjSi!_u4^NWYsSW<1z9Mtf2L(aQtx`=hmG2R>4aP!bXn8EI*t5G*&)X7y=y z-Jb$zjvG5{IGNql#Rb%ZMKAv2tmyC~F#W5yGN^pJJ@X{H;+d$W7lR@S-%NOmK&aqv zV55?!A-KYy5sjvfApA;FfdU`kmot1kIc2kOA_P)Mt^e|Ajzeu^fxw%d&+$}bplacLT z;kvURy}qG9WrJ&|FS29pQ5ix#Umj*O*!ecsI4f`wyLPtna&xy`F0aVOdi?oq^|Ha9 zR|Llkg-!dos!?L(x`%0^)we%-v=vm~G6Y+g7u#oA{m&-an)DGdGLtigqNLp|;?b+U zPQgh=%TKv4QAmqhIgJgnJv%O!Zxw5un7cFFS+ipn6t^DV5E0p0c-)mWc!5@!Jj8ci zxBeIEaPhZr;TFQ!y)@pJFhPJi>}|dcyc37O4e$m^N-IWHCL{B8Mm0xo7ekn`WscU- zvD`5?k_THv(hro=Ut_QQH2<+7-V!8x2h z!MOV?cZ=J-9Utk3+MN|vqjnq5t8RXLj6DjEHKcDX_Us0xs=Gbj6@bnkqrzpaKaQ6L^<2u8f!zp%fh1Lq}WjJc{F^A_6S z1vHGAb2V9(c6M)wiP2I$*?PW>d;ca!LHp)Sq1vMIE;=h12&DLcyBle#3#S*pvADb5 z<{e4D*0i-Pqj-*kgY%2)P-^0ZaF@$ySYsPI-}QTz12lCZP0Gi}^lyRWmgbxX)vw7Xh#BB(Zlm-H5wh~BX{Alkbmb@%um zUHi$x!7DFRF_qn|qBj<;fW8`tyPTx*S#$8Pu^BGLt8G)b&LKYZdg_ntcqya}7xQ|{ ze}E7 z>dUt~{YSbbFw2B}8ll$9Wx7ZSJ@?^8KH=Kq`BGOvDPwCOmd3=KPJ{}a)wdRN2fx5K zc3Otqhd^6-?XwKt&{%&cvo`~DjPsR)Ju|+>NDC*EMN7z1O$x=?D6-==G0sc6c@+Bz zp_EGxAwwf0`)p5WZ(E6V$7m}kD$h(*jhf#eMSdOT)c9Sj(MBJVn%bj&qe>{Bs#!_x81AmQ# zoV=l@)%sr_kJQnN@d=*{csd4_oQ=T?TCA0@x_+=)fB0b8a0{Uq z5ywm$kXdOvhogujNvQl9h2aU(Qv$J0_uXSgsVz-SUhVNOVnNmq!hb`pE$>X+J5K?# zGKx8vUPy3~Zt$)c*CgR8EEcmOgG601 zwy)!@;F!b7W7k6fWj)_dHkI@Z+i=Z#t}9JwhylO|@X6j*O{rHsi&97HSKv`A zFw%C9DULzdy#KY|!KUZ>cylnYsY(^H0Uly#Sgro1=%{%8`JYKguh8^Og-0$!*KMR% zh3rp?XU6Y?|62OCY+@}GG+N(tG#nYdIlb|~F~r}WG=C)OT105L=f&?&s#NV?ctrr@ zF>(8I;`W_VPWLOFv!}4hh{(mex&rmX`Qcl2B{z6FBrS(8lf?A@yeJ9)ZuRjCp5r;l z6aNle1PctkTfm?sZsjK$8IYfc&DeB0xu5t7(@wIy zQe7Gc$wFgvQk*94hUVo5oxfc%J?*!2@Y=k+dF2v4T3Iyi7+5;9vx^jdYZtxnrQldQ ze^(nC8nzc7=D0O_83Dk;MYB@mvdxk zMpi84&g($n#fu=2(8yY6s;@AKiEpez+wXdzIk>K^abZMm| z?o&bBIgvhO;^yha0iXpfWTMlDPdIEv=KL`P3frMoKuUhO)cis4WG%(F9lbed(t1#> z@6|L8AZ2~v&RqkUoIc>ZTU=Cckohn?j3%(4$vfNM$2>Eie%t{o4rd1Tpam=HdRBEE z4iu*Z$X$?+LYbAPn)c?RuJ=n2&-L!WYF~C6;m_4XZJ7+~{lIi5lL0K%>Ouk9ieiU* zt(_E=l>xc1+CDxyJUsmIqjT7~D}9q+6{fa5Cb)nCOkCBe+1|)wiQtgRfxl!72}&H< z7=c*$@Sx8F!81VrlFtHEWI$kGAn+vJojVctM`z{3ZS<4A-~q=-U54V%V3Au1@_svfL3-dL5=;n>i6dsw9yok zAV#NISzc+QNJYqj*J2-7MJ#{nmxO73k#;t|7pqlJK6+?- zyYFlXx>NSyL4I(UlA>pS+dAXOfjjp0w{O1&uKC0;ZjSB_`o9k3ms7)xlZzlS-q^%< zW!WUKl_CY!3}a(Ak7yLkf**w3>BdhB`;N86wUn!Kzjti6fcT8{+1GP#6I5&~%V3{`$r9<&FMvo|bIIhI&QiOBh;rvJ7FX|$wrbwFlP0Br_z zi1PQ&o9CPuHq0(;}SzCP|f^SB_#=BVWroaytoOpN1(swkAw zrbmmb_u0;KR9CfkMk7Ix=5;FIr0xwo8u>OqKX0e{&(g;l@7CDBN(!LH+_^ej#AEl?rsZt5dyLZSTB`1yESq^_)gQiZ#RVzf#*vM0{8;7{~xG8 zCQJ0n?yWd=yD6aW6ySl?|EuBdOeIdN2Y$cj8#s=^HcQ}$<(5}4vPydi$s61}pE7e= z=;iI%avNdEv>Us&@>B;m*?=0C^xbG-G;%2L(EsBg;-jNCEAtb8Bem?B@Yh1Z)0V09 z)d_F*7PscOBDZjh4m6UW+itoq>d1Q(FTh7@RJOA!=XD6|-u?@6krojlakraY- zNuT@faWxk$FG;}gwyArRioo-V%ANIAJnPAMW8G15JmkYUg~=V4~W4V&s5JyAK-Q=CL* zD|!{HHj|P^l-IDMQM{IPSM012Xt8dCvUQ&u!3arhyc$jhf0IkfUm^-mE30M54@g+! z-8(gA_oF?L3ABB06dI+E7NLfj7+SxHeQt7o7!CTWv8%)NGY_6COHsXNzUIGgZNJ!z zw+R&gIk`8`jmYS6D_d`7CO80RKR-IlZAX*cRD&%3Of-hW}F;IPYGzH4XX1SG{?t zNPP2$2)<>HxZD=)kG!L_ay42k6v~W1p%r3y^~%sbibbbjyZ3e^Omu`td<=np^{fEG927o?5s{Unskzmlv)96sC_isXpu`a{D(M@KhvF>Q zRW3*uvn|%3=&a672~?#F6u(e3IH*)yY~qu+?GExXK|VP;%sG7wF@h72-&W`r3rTG(w4n8R!tV&qY)-al-5j^`f&jaAHzv# z)!{!{yN5vcgwh*jCSPYEglbuNkgxCBhB>{s%Wlm-J3BkiP!v+?@-4t_4qqAuO>O;N zAnbE`7^IDP7;s>ahXw!9!{!RhqM2Q)`~XZ&qS-|l-@s6 zRvwcYCqZ3yJPkvM3r+h~d^|`h1BJ9UUzfPRGSRro>i0Gr`LDd*^kg`-0Ag!eusK$% z&>5_$?1&e~uKANx=r5tSMjk+n=i3ry`R(Wu)PmmNY(BUl>QT?gPA`|44NN`g>t!&V zCrf$Ep5&<(W_H(SQ|#;sq578xqUSc*d6b#4C`rB8LYm|n+4&yBYi?VGHGGvY&4G&_ zvd{{=dc!5X?7GJQ&tSlxO`=k$0PzFjfPSm}_8Xg^8~GuC>(f z;F)`5L8~JLr2Tb^T5LcQB!vk)BBzK#N1VxTJT+MQO0)|k>@5BhB=WSvR}U3dNP*a; zp2xOGHzf~CjlAP}EW;zjuFbCgfC}lc8;wRmLCkDVJBIP((RKAO-a&KQ$=qEj6q$Qb z;&ozP5AN@tak?7FeV27{h&IYhDlhV;GD_T?H=2>YdvAx<(;KL7o1}Fkj&+_tgD3u0 zm(need@4mCLuP{Y+Z2LDG|R_i{tGQ3QefPG7vz&pD28&Xi2&SHJ_cms+NZ)&!4>GQ zgTz}Pp^gQv@YAkn(Fjn&7;G18vS|DuO&M!7Ixud?;~4ex?{F z?QmP7-z-myIi2_zNBQztC=<;PO*L5)MAvuoqQo~XqPOO}4Hb!m=}1vm*%*eg``s_e zGmw&G{yHDzeK(p-<9QW@Yp}JPjJk>$wOF^_(Dzt--5Co{C_{y!Ja@#)h z6hEwvZBOyEuH+aW*Cs2Q2PIx#4#lgf{Ge$A02AFr1C0Wz|gQ1Q_cJ4*~b zoo>RD#=lphn(Q17M96c_qa3a{LW6+Jf1rNmIpCkkjdqmwh`I-6gAxBMij-X_gh+M{ z2B$$!oPm7txfV_jwP^jxmh}k2t$z1lbuaFCn9s5itlDI zF$}|>2V^zolqq#(4_b-M-rx~bvm{sce#5^c^J!eZ6?2e*LW|YE{M;$H=!$|D zyCS!O|EITeYjHo=kpp(S^%3{J2|gGn`WsRwb~^do2S4qaaE248d)5tzh25*ael5W7 zg?tD2I_x3Qba~>LvaTm*JeIqncRR>e0t{B3VZSlU6~o}ReJl};EFOJlAuk@=cKKSx zqdLjK-Ni}W2ol+u2Gd{9^C#ez40gK-4pQ4$VP~s)3V-OIO*fJ7NCSz@I53oNdin(c zm*kY5;yrqmopu^)Uy1;mzh~%$`RC*_|0R`8pF*v^td}yC1~6pH>b)sW^LU&e=y-S_ zHN0PFTFqetjD`DEM?mJakZH~h9dWZ~m`yKw+LibjE^|PdRts|!8j_3o3q-S0=`O}c zQgD*JJPg6j}H`9y#_zEDQp-F%kK@ z@ko)`ShZ*~`PkPC!ef1+Z~MBB72WLO*C-f=FvDk#-3MEkF}|1@SC--h5m0$)Dc><@ zF49DCKc{_D1qm5)N-%yobWoMgiQZ5&&se32LCpL(_3SLN_+85Q5eqpBG=%Q|^Nj zI&cRrG{kDayI~A8M)yN^qU5p^ejyldqr*wuhHS!GK26SSVJ60zgA30VjX^Q2^8Hju z3TCj5IamcAHIz?)P=&7;(?$zf26zI#qA7N_&|d26mtx3F>hbR4Qu2qT>1j`XTC2yi f^0vdEpSXz~=?{&oqOCxZQ3%A|24mf5i6#9HZ_0I% literal 0 HcmV?d00001 diff --git a/python/gym_jiminy/unit_py/data/digit_standing_6.png b/python/gym_jiminy/unit_py/data/digit_standing_6.png new file mode 100644 index 0000000000000000000000000000000000000000..f9f6341b9e3ae409267d46c4d896f863c59e38ac GIT binary patch literal 29512 zcmXV11y~f{*IonxY3UB7TLkGA0qIye1*D|AyGvSH8kYKjbc%FIcXuqiG{{ol@P9se zl$mkn&bjxVd+vMQ_e_+kvMe?RIR*#>!j_l&s15=lT|WOse*s+iSTDB<0=eMIf0Wep z%!YM%WK+z$-S~awK3EnWA$A`wT9B`eVI}5h8HzSvthHioJZ>(MbN?bqC*qLZ z8^s~3=9FLs(HToBGh(?mN_)dFXULh}rr<2>j-=RiLPH{){qjGZlx`DL0b{5%vd*Xp z_mA7LjCH{qgFW$t*AjRrlILNa$TeZYDlW`0^k7;q(7Kb*idV_ghV3N_8p~a9;)y80SL z@))%K+z!-N`(9NPquv5|SEce(_dFU-905c&s1YleHd5x5M=qH_%C|D=m!IH3vvY5r z-y@W416+{(j}RYtJ2@7mf6j?Wk4Mg!FPOCDEqd?{X>RyY#5%WQ4)gOff+2cG;h{%r z8|Yxbj9;5=f61wV_B)uz69 zYws>Mm&1tvzhk$^M3?!vnC~#~*l2OAjXXWKu7V+e&G)jFcg z0wYYp13cVA)0qsd`j7Lu>tC2c+4jT5ef8U?lAzeNLeFFK1vgyG*XN%=_|Z`CTg}%f zwY-0J(>AwBA*EQ?X@CzDV9^AiNnh1V>Z3~H*}n6=r#c%J#F~AN^4xo!7r;qv+e>M; z!sj{tPWk@%|3Akp#O1dpZcqYu?4TZXps2KGL9vHaCZ5~-7Ov9%*2p@MTXUT8c|yP7 z&-iq!u2OP40|NlX%Jby^_u8hl{O3N<`$oK)dK7VQ5?Fe6;Pb@x6WpUqUr~nS0>|NW z?$fFreDf5+|8u@r+JBR6-3eedu0)~~wS zY9d7>`JE8m|DHPhs1c+<_Zo$ahV_6HvW%`+_69vE5-_ps(=>yA&##KKd!A2r?0~Oq0ec|^4llom|Hnojtn<3%MkD}L+Kt}tzb33;9rTu) z_7xAK->OtYq(GGE#h(x`>{g|E_dJeroKc}img0j~;k37??qMIlul&v{&iB>_#u9J^ zz}+?S*J2#q|99^4>>9~<+?ukAD9;_?bT-a%yhbjj;iGy-1dKbqKDuSotNjUoNoVAU zAmL!rn3Vt{kv43=kS3Fzc)%I5ml?m5#p@tn0yk^yJYHV$zq*E)7gka^K}c1j!qDG_R1x=;&UHA3lp zRRPLt?+(FLcNBS)=OD}?S9Bp-ATDQ`f7v9z@6p?OB<$g@s?FcM>Bx=M!;Lip{0r&<#rB?tmWAR;5y~W5^zAxx z==?W$50m{)FF8)df}Rre!EGbh)qg<8;o$HP4m(6;JWq+bq2@UcKrwmr)pYNj0-Q8y ze{kPJ)#7;|Bg>!9^He3%$4?YZGnzMrf)@ztEx!8#d%_WI_>r7s$SW|tN@VDfU3usc zdQul~`xl>`#+;1MBUy0-I;cb?&kep(zLU<%RU>z@jo14e1CBA`rl%(^3z?JyKWD1s zy$YAB#cxyMMD%Q$=;~n&fk0%EV6cpuXD*4%J4|DA$yk&=s#+T7 z<-eE5=?bf>4u1b(lcJKE1e)rg9>_6-FS;F^DphDPwor$gwpJT-@vt@&Zc%gd)G=@j8Lnw`E zx}hv1|Mw^Y5^OZ$u<-Y{?&x3GM;}yj#;-om4hk^a3GZUI@feSnSmq(q{^r&kd0YHt zlIS}Y_l9dLgpC!j05wp?W&Z_;ZfEd}K+Sst8dFV^7KId5XDJU9S)llEo;Uu@Cewd+>XbYDR1OYIeeIj`u$*Dfe1vJ! zjibC^v%zm}i9tRi{<58IlT%JQ-qj()BY5Y;7hst{)w0TZf*(>DBzo44y1j(b8UFE5oRuRHUF8dH99(IJJ1aT z!g~?@0)p}Jr4*c4YJPV1MIiggrsKlN4K6P3$wFIGbCLPs{jE`rcCs7jXT!TtJW0Hd zYQ8%jUABVjpV0G7g?o66@@gvE@283tK28cr_G{u1=(w!b#RWX><3xn$T|7KIkZ>CO zW~Lq@TF^%w5;Z>!7FwvTXM#eyv^1A?uaKdjv^bPW2nIW5D998v_?~mUJ~wx1NiTf_ ztfx18A;J}Xv*Op}&k&2FM(CA`8_}aeBd}o1kMy@G4&@Mw$d75jOC;Bk`6D{gi=U9p z&UuyWnYBrzP=i+A#Y5K@AUh6SBP00D-FS}h{QSJ->7&$ldI`V~hT$+^G+yG%b%Vu^ zT|K<~eygiwTaXcxeqvxndJ+0D*ds7MdRQ;eQNTb`lMpAua_mQUujc{#h!7=?6#9S@ zbpjJ1MguMuDA4lUToCU&a!6ua%1+~)RzcE`n;TmiM^zrLd{@$SeEe<<32ZT7qfy^J z(PDA?Y_P798RNlYt2b)XQGgQ1vbhkC9t=eNB;>N6Of(Rv;BgeQu;0;{Cu#Vrmm#hn z@yjr<%T*$7%W;h5<%gmOm>89_%OI>&=|yqM1qp|r%MQ|0Qy;c1#V`K-T_p+JP~bfrG;RymeB?!u+nv zJ(xxq)?*3=`-$bTkGMKB9Q`Lui33svgMDa6>exphkhOOXaA}`wBq*(GHG{W5-V2ay zTk9t~>;ag_F^*;>N2(@JG>|hfU zs?3B_U+hY!TbfG{fy|za${gDXc4xoeAA6Ranw8~29lU-!9%hC=kAh%e;x zzWpB;tRW--RxHX`uNNDQYEH8l{tg@6!LkO=%PXkk&n ze0_7{(_y4WcoiN?{6{$F@7kJC?!I-U(!kG8^*?^67Hst{6Qn11_)ULSFfmu3t6=+x z=K{dKA&euFHg6}7rE3L)R?7NQHCt*4LS0~oNVIrm&Y+GVKMe`x71D{{_RPJxdkCgg z<(sF^wa^vnapNW}%8l(DkZ71EaBb;dimg*swHIU>ZT;jdwEd7{h151z`}=oJAgz4x zD{!w#N=#cEkS+*RN|~!3L~;~DqM6Y@s!0~hz+YP!!_2{8B9#2r*4DPRwxXg?Jy_=c zU+!24MDGl1%-5zsB;RxN$0`@bboPpe|G$ukJfBB75vO_H9I1zlZ^zgu@>l@o>X&%Y zA8|CUyw-y%h1(JeIoD(EayyzKxAZOa&mImM{E+?dNzM5`RS&C31!&g zW6uY2luHG+ehsLfxFbmvu6xk04P6W`rm66KI1nY1PpbPRj7R?(Kv5Y5Mk`hB<_wzi zE?3g?P^L`bjXFre zIW{AH>+@%%pN53pWTjYNzj|drq}5XL^XYnSP=jMJz2S1169PF{hP;OtBGirt*dF0a zJfRa9a=Mty+QL-S3HyJ-FhP!-q~usATD*J^2&;S&y}W%>Rwg(5$hnA0k5>mJQ?QSE;G?$)J^(4uHD zu#rVVlMnw_0<$n^=JVF=#Xizc1+X!4^;eS#pWE~HBb!XV;xSZ895g>x^x$RK99tU% zBJAx=@J;?d`!_R6l+YSW1X|>0##v6=$rd{uN&4|*m5=hMe5)n=hAb=Rx<@fzBn z4AN6zfhJ;^m5g2(T$z(oDtggQRa7W2Y=A%l&WF!00-fGHaHcB|%E+i$L6XBymzJ)=)v9@0-ShVe!%bu|RV4WKE&~fO;TSL-OAat^bVsLroi$zk@(n z6X)(reN>->Zq~r-|H8U%jhCb%7|3{?m?qZ5xy$P{D_o0ktzL%YC=u(RVp@PAu>wBO4MrhO%$U-A>MS#E#Lz@d*>Prt3eNRYk4 z5mq@^Id_>SH;RK8^y5KJX5@?2Q%~btMGKTRG*n{n z+zbjj`%0F>^Daq=;bTP#62hTK4;5t65ONE12zctDd3Pb+N=|y5a;=J z-^Yh3{xU8~F>#nXx&S3aGTanJa$!~6YJwyTjrDT{>xlnl!wLPxUQp1%!^D!e{1f3U zjXY8O&sGxrA{Q=K3pUM@6PnMJs)zX2r6R=($b zeV>a|Ghfc^ujcxCcWUA^wBQZMgfzSaEEu0`AxMbfhWY1lQ#Bh`C8j_6d~0hs<$;6xuuiPq~s6Mb0HZkfe1R^PIhW_XD}@zi!=-j}4HnR#RorKoph%dHM04dIxa zHCF7XE>#AC^UWy;R3V_16k4|X?+Z;CD@YD!AaEWNbb`{;z4rJTnrnUPMc!_dFtB~* zN&R&C@q5hjAATwbioc1;?|1Gu?|R4-9{BCsBg8nkxLDaJW?}e#Pxq*zH@@Mjk}7XB z9RNEP1o)1KAgkMTCf)ZhG4~R#<_BojD+9=F`4eI+)rq)c|3;ez<{v35(1Afej&_u( z#0h>e6I@^%!)ZW)-ZiD7qbF0P%5fU*pys=!7Gz}PZj+Lb{3OX_hvAMJdpYNBXbp{9 zLw}`1Zny8wj6OYFRNz4EWC_Bn8}LnX>j@<-P3R?W;%NY+sOIG#)i9N*~csI zj_jU%W(a%qzRWvbk^7Et`TXxM@G>6aF$}hEx-bQgpyv~kp_k4pda*yQ z|DQ?jwQF~<*Q@H1MdaCaBkuLbt04miKEv0kNbz+NEbNlJC} zH;eyQW8+7)l!Agcx@oKS{B)ro51Ut%i9$pL#Q&O3^?zbTN;)r^IqT zQYXU8dwEoGf`gN}M9KrZw;|L8pDIdRso=ARDdzRFYHJkhKYa#9oZXGQD0+=DaB^)h z1ou%h1}}ly&VM6_=0_vgziR|~^_=K0{Zp@s0m1t1m-^{@V(Zj1u{`h3240;t8!&wJ z_trfBaAciw39TK;7lv=V(hR`xhMPG*RH~tUG%Kzs9~PaxBzCJ5Mj$4XuVUI*^qsxs#k^i&GGUzv6J3S_sPtebL*FXE>0X{RqxSh90Tx;GO-I>2$x2%6CKGcZ2N}?}^AYzQ~zf2Yo zDWp|SJ!Wn;tZWgfX5i|?yn)fHHr9qAmZ#DLyKXEVrUMX<^VqnpE>gjAPiF&pKMQ_R z!RG`grfH9|j=B_Pi0pw?%fTU=m6-{tsIW$zg+wZEPDeDe9 z$)Y>>_LYBmGl^gfo9ByyPV1Rz6e11p*G+xejWWj$g8E-KzPN@B-THAQTzwrjULo=d zf#JLsmH#BF_xHWcP7JJ*%VGtuv*q>&yGM^4YO2Me#Ymc0hmmd?gFK|Brlzuz*DWTQ z@vNQZ6+Y3D@&rly^5xB}%Si{tmpCen2gIdGiSZ(QUAyK{HsM2sjkezd<;24rqq$#3 zm+xh0t*zqdZHNA)3L0lF<-wr$6EX+k@aAi?uaIH&g1lRj^ddF{76c$oNIzwX9d_Qq zF;QOh^(EKe*dm!Jf6GweKCObzPk1%acpv1;#AvY_wd2P=_HjV9Rbz)64&Fg}-&Y(Y zTw`^4rXZw`?8Gu0#J>D!#&yl6q@;4iH4w1~b}x;njdmzEnAS0uzx?I5npDKbJ>^dY z5{Q2*1aCX(G~xcY;^GwElAynzOEuo%Hp~{rzu04c0wOB;R zqCu(4oTrx<(`MmjUJ3tbdwN0ky;mXSltIoc#Jd4m@z|s|JRCJ}uxP<)Vyu>gWDz!G zwY~N3S0yi`IJQ`hTiFi416}|60wx9!l>XFs7ge$ke2sFOk9SXExShh&iy4#cUj)1O z<*CgaRw`+I%fFJEKN}qj~w%9Mx*EGn-&cO59PliluR$xoH!h)E~sNJMH`0?=(jrw0ia}2*2 zUTKcEme;?2D3Q!$uOWDLfOp9;Yu^w6f=3rA7dkIlYTFBE8R=NzCIsYdo zC*rGZD+W=y-Xo|DnHpf7D%2M9wxRbDAth_Ed<*+YwcZ$`h1E_m7E;Cm>&R!81Y=JP z=D6R?CYT^by6zQp)AmPo|8qTrG{?8LcqLZ+UH9 zrA^+*QsIA%5$?HPo|3U|(oeHcTIo8AJDC>$+Sd7-STgVx5!!X@qlH6+0g;D(Y%OIB z`;fukU197xLuwOedCGB*Nq^*5y?!Tag{3M3*046GZPBNhcHxRF66~IPc;i)&L|~ef z*!^iwC|-KS+>Bjh#H~}cg>9G%>3Noc{NQM2gUE7TB0&;=jh$X^CVsiz?Hr5E-YsYR zwh4U}WRV8~`M}G&;tj1zqNft^+$v1iYFe??<(^%Eg&9|M0XfjL4H-1j=LJs!YUOk& zt#mB*ZF0R>m0C?D60u>Xl_oBshraNK*}G1LKpB2mPa&5;KXnK)zTKCA6`^z z$#eB%2>EPd?)H4c0j^v&@OtyrM`agE*FKt1J-1^q*i#YKEB z4~Ci>-b7Vclr__k;*gQHPrrr))0RP69o9QT&~U2_+uT=M-BiRMTon}fM_OYMKQ)JL z@i1caF9ge5|Jn?S`?D1JYs&29rK^~6{d&EjuiCBAr&FrH1t(NmdD?S${Dc>3!rg2> z6x|o2-D}u>h8BRCBrrD|L)emHAx!$#?nb{<`Bw9R-p(p@`tb7B7bn7OJXaJMc{2?2 zEvJ>%?3fK-UDP{qpS%mGL6SM?dFlH|mfEu2WZ%-yNl5$iVB2xVT&oGsasa2dApz(3=w^t;+>Y*XxS-w9f~*lP4JF{u>5&_KWUFT6ykrQ~dF zp&BZp4KDkM3o=+_6XuvyDn!zwem;grN%R@t#i^VU3~Q9o62GRF2~+!7V-)0r4^?xb zmt-PvU|mm-4u=#Yz0qy-@-BPqI*s4lR<6YVb^COA-rgPuBvdGJaXehF*dCyRBYGrz z+`(XghrL;G8Sf*ysU@wDeMv3H9p2)Q{#|5wB8Q->NfDwvF_O!7zU^AVc1?|mOy;t6PU2L@k4p=pr+YuyLey!)|wB$6`~r(@bGc@vL>u0;Gij9bHrR&#VRoz z>CiNo=?DMoh*}xvf`t)o47%Q3=XY4!u0j^NB@8=padAzn?pY8>9s9atPgPvpS;ZG> z--}sUBfoNkox|y$(=S1`mVX7N#RWPlFUJ}&Grq0q+z&)s@H)@yjaNXH*47^TDI5;o zdi0Dqj(yv(=LsjYC5ohiz$#W|TJ-;;`r+1ZZlfdkd)&Q`f)1Y!Y3Z8;UMPTP8k(Be zqIm=a&q&57nh2>E%HT-2E+xjW&lz#8rAsctpK+b)KNhSnMGLV#AN(knLbb z+Q@(>u(+Ilo2J6Xaf^tx4yK*(Rs#Lp;*8#M85eCb9~#@!)?ZY(bm6(|?X(-jHhQU-7ply|JMZK2udS=Y2Ze`+KmHqN zx{QG$*H=AgyI;Ge8Ngoz zO-G&NuORe@o-F>ZOp`E-%Kev6 z_LWSam6a?1E&|R5U4K&71n1*m(1j9<2~ozY0z$|ulotRuIVX9vCceh2SO~Q+;3RSD zIqZ|xr=T-;bi@Nax=#k5blylVEsJ+lY7+KEM@M&dirFwv&L4Wn`!r}t1neBpIINP_ z_FcL#5%JVtD)>OwwbdBMCkqGaNWSihIrE>w`#BL7gk)=C`uU|&>^(g&U=Lk)4kXLq zzY3?Y|JTbT)_nmmRja*#m*n~*#ulz-X2I2Z4W3K&pS0$0)RKzo>gptDB|O%|P~LX86^q>P%85bEVwOL? zCz}`JYnSV$cN&*}oy6D2hOMaJtGj70LGcZ zTx*_xrpDn%CG&8(M(J9>(*v^w8Yrzw(WUE$a@w#9=EqBH_DALA;1B96RmPuezU5Jx z)gG_C7sM?g@c>O^dw{`~qd#iD^kK*+nd_EpaiU9ETHe4{2TWXdnS12+$MddleL2%d z4qd%FjHDuI(L+K)G)fc?p-?CcmTHj^?PG0S4lw6Um?Gmb1~+g(1e zY?eM52n6*-P-(9BXX7K~tJS)#+>2Iy{TTo1a687ihm^k6I`S0iJz+tw30(RLq)u9c zsc70mwxt>GfNRSDRFErP^0W4{y`$I8E-*}wL`>+XfBYMurznkAE)=_y2PBvV)OTwcO*8{(C|Wc$ z!4H?E;z|kz_53xuF58)W{C(Ac=I9e?N}4yme{m}ikBJIsQ9TwG7L)^mIe(XymQ1)8 z=I8l&c{PoU{yJqBFasZ-1e z_ZOnuS@Y>~I_X%C)ni@O`cZ`z!StJVvMDTOAZ%oQT}+gi{Rhp}T^w{r$CN&jNRHch zym>!Y?1$%ZZNR({Q>dn?rOHZqU$#K4)L|NW>G3QxW-riVApsFci8LryL`=}57>0XBE`N1_#J`vdwnO-SpzST~BxG5D3J8Q=6F(h%cq*9O%IV+nWM^p;xTY_!wbUUF7mf z*~(0D>n|mLaz?X{1k>LCTZp0;ck;F#YT7f9CP}dnB*hZD7=2&A&NY4k2yj+bR@?n| zU*6uNL@qPoC-j(;DqLO&wC>tBn~FYodpQ;lXVY`t@&1^)fxKJ^DkSqzv9aSRbpL5) z&TP$yg^jKBgS&hC3=0<*5DPO^i*2+iu@w}K_~KpK;o@mD-#L(k5a1ddIRTx zUu9bgbI0!+q3h*=d#WdP)^z3tDBmy_d?|l;B zTT9DCem*tNUw*o9#AH=0~xaqyWxSPKL=RClu z%=34i<@8qYu(}1=)0t~=CZdJmZflP$=s`Jn?9A3y5E-h(WEgI$K#kPwJ(<+te5boO zy$7?pQ|anUAn=AqL`d?(Ss;?_1)41of?MYHSn*ekK>we4G98J31)q@QhVcbA9L z08Na5qIHZiM{hYZ@R23U{HF);nT8Tp*Z*q|6(!a+&IdxFPOW%s)3E$-BLDr;zV$J8J zZ#Qz`qj};dYd$BFddvG`vucFMp`isrctx!6yr+A;u61KDc=yU1DKPB=1R^9LK#Gon zii%o4Ym-+nHdX|&adL99wmyWX%_aM|&#PqeHq<&TrLf$^Q>qc|hR;^Kl(e$774|we zx3nznmkK|L2$KDzTUen8Gi z_R~K~7*W zQUCkw>qnoH4m1!@GQwqG)p1y&udhGeSf6c5+7G=VCL)?dHP}Dg)7{JT{bHe}Ypi zH!T@St!$TOns;uib;hYcAQASglwVH!IsB8aA==djEL>cGNMFCEM%b5|OD%LVz$AVf zR_lJ!=_h;*UzODF6`+itnwkQXBw)>VcT1*OJotCf%ZrTvV!s=Fn_$&&5&9ik)Afje z)|4g$+;7t)baF5|2_&`hEM{JQMy^boZDMD+nx@fManWBi(*S>db)hhEtnQ45<1rN} z%<8O7$N=YcgRoZXx#d7Ggx$XtyTx5z9Zr`5u@cAv>#M7k31vV(Ykj#%+xIfPM$)RN zZIK)8{T`-@m6tvQ{&g`_Q{#h@z!mRlH!(FE}f+KGOX{c59~{uW1* zux{14RA0m>MDqubbeqDWEGi6O)mLc{)@d^(rif4Q+QwKQjzQ;38GwwzKwF#7REiIz zdRA<)C!0VW_L{$>z5PB--#*{InSDfL+_=-%YbYsoB)ul;?vTdc^Po4XaMSSzkPd5U zp@M+QysN7#7!1~JqMAg%T)St_g&~@~mWk zABJ>I6?dMZ*1P{YSJL8o*ekAxDF?r^YArOW83sr)!9xWMs)xfcExC+D0)|t($%UsG ze`^i{1uWBtBL4UP(m3>an@~VUP-xeAY7G_+&eT#WSHNv&t=L0(seex$yWP7z_cj?d zN^HGi1@W5Od`>7c080y)d9bF}*HzjuL7)LA z28P7wl+`v5ht*ba9&F`5)1J|c_rR3)a*yVC*vH;YrgOS=K0Vs9kA(M_K1=wisj1Ng zmseNM@rCnU=Fr~@kvMq31JpP@J^kk9W_tdr`!0s7b75)88`gkH?X}}kOJm8h-_5C> zOP{8+migiOeR;eGF_V3Msv60u2zvi}x<*@ftsF`S7aA^H$l1K6A!TC%j^@f?Eam8+VwIhp9RQCVY;1ti z&lX^L0IQpX%ZU8u?&}naxb(T=uo+p!X4@^vjDgahblffKm#ZO{>nRwVc1z|x=Jle5 zqH-sHS%QMtMtUM}PommpCMG~`GMeCGY-HYxQ1>7bl+n1)Sca7# zXDa83iMi~plwH}1u8UG9jO?D@Jpd-TMvH-dGVm{b1@`fyQf+N*+a{cudTU$T;!Hd;?JB7T^X3Z=8qg_{0&D|I#Vpv0q>fi8towSU-7gf`8}M{zJZU3`i2gumb+*+vZ|Fe<6Onc)osr)6GFtyTzw2zhHwv&F9sp{qa{k&E zO~j^MU4$QS2Q!XB9GDH@`2Dxt@srkDx1_#)=Hvz~M6zaHUrUP^BMhBxNt3!>vmfTJ zK~Y**xLurX1SI*0Sm;uN?R>SN!o2UaQl5hU6Fs9B4VJWLVI(w`!$6>;y`2<9PEl$z zef!~qvYkz|ctg$5g35|g?iJ-YM%;0+dLi$@ME*m-mG+GjC0grRJLo6m2q0wBxQwd> zxm^eG<7%!tsF46_ZW0aHr&L7FLg@kV2M9}zK=#NAS4gk6w)#=9p48Zw2F&Le^y*xM z3;o4_)BkkDEHVI9PcPZxW!Pu%7Fj3KUa{V(?kH1g{wyqf zRKavuUwnCXF)ki(G{d6g*mWAlH8VT=TB^F`>*M{cLV*~fs>ui_Y#ntnFg7-pk$DN4 zpa=s}eZajRAN|KN&b&MPyYg6tK?d!fPQdQFgdL$p+yaD4kYkI1?VPX83RiBjsYM!< zxh12uwkFfujSg=gS|GGWg;!r9Tt{k!Lq9Pyuzk|o76%kXUIa;4N$1e-kNuSFCJNfP z^1kYBV;{-vTz6l#a|6mSwG70~`k4Turi$bF*L{b8wQd0<_v8BnC_oW+XpgDT*J!*g z_qLdrm~)=dLqWH>ejIRyn$phXV_lHI<~8#~aqKWj>&OAyZfZ3SLRs;7$y=e`|`y`VheGlr7?=POt)` zsaXKu1rW16bHl(b+CojE1(dBts>u7#=DOiteXv~p8aBm3wAY((`ik3>z_O|!z?bh za9Zt;)rPBYEbBKqe*LuEZ4XkW~*^^b7P6dr)bX;4>*frGWy_dyo(pZ^i7GnEf?D_K_N-2 z6KN~Arn@;vwQ76~X7~7jvgug*K?&b4%#>6{jhJ0WLiDCKGI|}T^doNX`nMHB<9C_J z*bHRDd3P)ObCoSlh)XNW@TtYc$G^fgsv%+5E~O8&XlQ7MGQp;#YJ?%(v{f0VpT3$~ zknU|p(3HHbI)Geu-_bmtmSU2$)-^$$m2n0-_441VLx|hedRhH#w(OxM6K~9o9CgvV zUgR(eYpv}6&GA`vo43xf#Aj~1Uf4df>b?UgZwB;W!1w$g5Mh`kYu?ZtGrRs`g`AW2 zUt!hJ(ZX~^_4T}j7=l1jbSUy5P&!Qp6f}1Og{=T0skivi2=Rfpl-Aasb=<5ix4K2l zXGOpQ2)=iK)-i0T6{;^qqvgbJ$|k1b$&|B_bfB=QpjF3y{F}vJmR!1Zp=p9gZj_(C zvc-YD{7xUwN4RLj{S7eJ99nkMfIJuRK;*G{wOiX*)N;EKK|@`z1aodVIMr@iUR_;P zDm|ONVMGSmQ6~V}1hDC-K*19e6OQAeH}&=P_i&G{3r~pP-{giIOWY~U)2i~lS{=#t z?MoN_#xvq1dPJRfwzXDT1R(<{U%dQtzOd#rV8_6~pvR|BNkpJ8QYd(0XlSS+dPO*X zq3Jj>JPZV%54LlaOnEC)>*6S_=24xIyHMjUWI%`pXpLvB1gKbHM1MiGuBoeA?jRtI z{wkuUUhJHt>mR@qEkTWMhqVDf1;pxg57*0<)#8?gnlwiHKXaTm)G^k?_d2m=BOAva zx^IU5AdjRCTTsZ8tIw)!;Uo?nwg0jl&lL~Q0^o&a8O~W~?v`^){e~Y9H)#C-(Z$xk z(*g7>zIlV`b#YDbEZ&{|#KSoEn~~22%mDI#hb29rI6E`r>h2z0AYl3j1xRxtM+5n% z1E#rUM~Y3ht;xuN&&X=MGp9Nlug+!`0{i*5lh+l(R&o8CM-6++;HXT)p2r>XSLXQ%-J zplwBE>`D03CT_yy?X}fBxe)Stk$kd{5Ku=xFc}Rg73K;l0I5l;NrI`%%CmPb;AwY(@z~+6o5rX^qGx^v;LK;&XVM>Ryvf#`OZ-s^G!N8wUb)>ts+V~h| zRP}>MMs?*&aa$ial0@6)be$t z41(x5@xui@?ixQ9oAilNP-R!rZ0z?2tNda!|EAH}p7Nu2$5&ByMfdahc7$WgXHPMK zIpgshXeETzrNw~v7bI^hK64cTk0q2(0_fJ4lAu5ag|uuzmvGdR%i&tHf%w@9ZRFpb zel#oY%Z9aiI{L!z@JJ_oKDu^lrH@>}9V6Ayw;l1oFQo$UKvs$7Qjv31lFL#;pFg-? zoRbnD&id@ut;)~5W#hB?jMuTPZYlUWB#idV?B0?{CKZjTp#EoFHeFVub=%hX1VFs8!#&Gm%&u@>g=Xw-FFXHhYpeH$q@ z$4On!Pmh;6$TQ-E^683Ij0j`=w7Jl^O3$A!p;pdgRx@kElH%fO^`Ac+5%v8W>*eh` zWL;{jj=5w7v$b~HbWTG*pcnm_YB0-uvJ8s{pvZ}h{vVY`Ne5tRzHy0i5UzE4TRv~^UdSC2odJO-49c9qJ3m# z(df*98nfdoefr;TY{WQqGk00N;wc4fOJ3%!4hdCqT?#g7DZa(6rv?EjfcB-N+4c;; zUm6;c7;=&*IUiYQb^$!}xcHN=kB=~j8_NY43<`kZTdKFF9GJZ3x_thuBXG)@7Nx9h zD^`q;9w>>9a(9?lJaH?wRqp|KF+=YFn8X&kxECpfrz0 z%$Lyzp}agfAqm+V>m_8nWTY8x{133Gx_Rexib7wb{!3r`!l2IlKcncq9K?8!i%H-sftotE)RY3~SmYKnGnQpXFtfTbqZ0DjlbXYD4{oQmmed zJJh3J1Yo2zq?|uplj6;tMUk-}5FZ~P3=G$`yB@MWWGdx`iC~}0j}0&^BXw>flqqm~ zuQP`HM%LMP%`lnh`6&tN#WKz(PJH)m$HpSALVyi=wZ&ydWM*9KE@C7dAS0QoTxZzH zLCubve}0XNDbUCo(p3Z5yc={521I-SFlIKhMNie9iK)&G21Kv8Kj9XBI0Q0EX@g(`oPDZ7e@F_7moRP zZ2Ij*^r#}cC+k6!zRaFK&g>|r1N&O$U-wwP3Qxwmq)%C+0IK}JPosRF3$50FShD2; z0pIpe4ych~NA&17e#;lbVmQJHWRwC5P98r$c&|pk0v%h6Hhmf9eHeI$^)~tqPz${R zd~ahn6Gw-l`BESPUIhZtWD7#)W#I3>jtY35ZZvgX&CA1)MAhIyn{z=#h#yNa3nNAl zq70T|ordeKp_|9Cj%FyC_Q9myyFA|dwS`#M7cM2WPBwP1-p)>Y#0N>dzqz7!bNUVp z+%8rfE$kzDR0^>gDj*Q)*OS{cW+ya2-G>0UQD~Zaq%Md3<1kHOT{B9csiw(6Dd_jn zYz2@A@0|VXdVqB)Ifx%bHQ=aspcZCQC~rlNHm7g)BC7c(rWdGfquO$T(!S}%6+S*R zLRU<@iYr`^Q)JLW^BHwdK#n;C6_8fX0QkWi&BF`q`C(SZBnYOCUT6&-1Tys%s#eSn zGS_@p=%eXS)0VeX-vq^QH9|rthj+9rJi#61?m)n|V0JGNvr=I2EI`oBSGG*zStKaT zoV<9aj05pfmc!f7Xh~qrCmWGaL9U4ONovYK^bm%LF~wRu+Am%90x~x#gjRkwg#Uwb z&U?$vM!S=V$JU0120(LOrf_ISdPmpwp;I0VmQT9ejzXscvKU``*Y>WaEA~nQX_^yj z+tp>S*9R1&sDVgQdMIl8ZbhT0qz_tXmZO(>|4y^k@8N&K6w=sRIAK(YuMpSOdeXcz zHxv=k1^lI#2r0Mtit>N_O;-u>vpX0=|a3~%7ZpisqE9)PI4DP z-+#+6;9DE-^C2cW##9VY=yyP)2C|dm!Nj-E+{dNg?r`e(crIq0NRld;PGIHw38?Zu zf{WX)EqlFN@<9THM=^^H1dY7JLayUU(g4#@+TR&Jr5ur{WNF4saNB0GC7n(1s4#pr zTp2q)50T2FTjXq321B*0vw>~52Pg`sC-wmSgE>5n09C(~H#^BHM$L{$UoL^7DTjc& z<mN>Ol5a~6O+DqE{IS-5F@~qSEV)D`V}YmHtQR^Y4)*tRcq4+t5A_20LTD_{$AY@Wz3%eZl|D@xR~!ERP$U;Ye^p>(Msw(J|6h+j$M zm+IUz#mpjjd#ONcUX}_fGBslH! zz!nft-HCi($o!M}hRfhQrZD17MI>~{3YQespjxiH&E4yJZ{yR|HkNzTE-HRu@_SA} zn&_H`Px4W19pubRC61wMTk5%_i1!bO`KNM+wXC9M4>vb}La6WoM34@jrbjpO#(>)q zV>k@93RHqA{ni3pe||nsx4G!0j-xXz+t0yzCgC#HQ0a|}fpS-rNR;Em0W5ATM`cHW zPlnX=wJ_PI>?x9_%*+H#A;C1e7z!ZqtkbGf5_{EARqV?i9Bmn{H zsOyPr7N$%bG$im)`*yefWE>0|ZF&Dy;N{kij@HE0$34|CCK)*jie0m+3G99p#GQV@ z8xJ92L!Q0gf5P6I_Qp-72U zz-xzMW`SlLOjT_p;5FF*_?bdh@JQRPE@ixJ+mzG+GH?J zkbMGSJ#|(AL0VEuQPI{%UXrY+HQUB1(wfX6Vh)s)W$nz4dN=fYKyTxorKuElwmHjD zQPDIRUX&5_0cP~d9%VcG3@0U^s)zNB)$~PkuhVorD_tBN2c0U> z15HV<&$-lTb4H^hh^UoxMpjg1TGG>{*0HyF(H2W+GWz=EO#@riWWFD7$O*2GUtsiy zmPqim&_nU=g%`5{b2jBRpQj&r$5%pyqw!K<#$lUlOa>Q98sU1=T@9c*1e*F#B0nOg zRHoF8qq^QB)$3?firhy#7M3DRbHez*%hH^b@v$#2vtx;U0WFh++>-Y_1n z#2<+sM!)F(N0UC}tqgcH{cosDueemgk*@f*_avYDGe`Dcmx$mpc%#-YOIHI84ReOp{7rOBF`tSljf#cZ%Vs};cQInnMlW;@Q$FDrsC-w4 zbE0_pA}q!|*8-w7-=t2Vp@CM`sJ)b=!0&QE`?)2fs#vrjB#>c0i!Fj9n+I zf~}!MEp;G@WMk%M-8;!1(lCdI1FwdtyvjOQLrX$yLRrIyFqoJOSJaY7DGn@KZ0u6) zfBFCN?@R}yw*5I*(~O11@;aLl@!U{ZJe}@!?Cn01a4_U3lIiuH4?tk3j&%U{NTx;@7|9fL2 z+ht!g$MY@&9`tfgMyr>Q=7u*NRiC^D*hpTn&q7_`1SX7+sFJ_6K0460ac4H$;p-0+I)O3!(-U^xO2 zDzMTbkPjg4-WqzfNJZK>-S-B1L|9}L*v9dk`ldLpzUv5!*|5-(a0QGr-q^HY)T0R> zn-8vF1DILAHW!Q!j9hw9BlA{MhHi>}OacNW)%+H}B%U+bWkM{k6f^x)L2t#u)57un zltP8Y3Y#5c-IhNYo*7qkWhGk5`ET)4q{i5fNea;U`j{%k#9XQ;2GqJR_}N%l%vr7w1>*VDd7 zqd5>eSK@7gr=n_u8D@c@8f)T)+wq2C3Zv2j(ca_L52OaJ= zs*@5=kxeOZ8Pi9;>?Z-nIOa$_ZJF%QEo(oKBbIu??&azc9q-bNE+PHp;pg~ir|nRy z+ql=iTWg1OG?K>$dU)TzHalXbE%;#j)3f(fby5ngrY=#kN|%8osOo@`*|}UQk@3?X zcSfr%kw2HAo@Om;E%75?8{yG}8TT%#PCEprJQW|jq1t4T_Wv;&qisz?lxM~BR`ce( z=W0iKugA}NeSX;N`{jR^1IM8AjFf}@Zjq85Og%ni?QVgfBNKP?I&2-m8umd+ zrxNn(IBbmiaHbNg{=35O%T`m_*)4;h?=26Jd>1gSI%dmqHAiY z*Z-{*B#F6djn>Ma)vZJuO6@s_UcKKc>dj}+|NhY4(EIx?qu9gesy5BVaL@1+LT=Jn zoAo!%kk1p1GzocU+?QN0(%~8W$?Z<1jtf?sGu(EpC-Zf-T~{du=dEpuZBcJ0M84ZA z#(l|Dc=LE)6Pk0syI1*`eBlt}7Srm1x`tJVaZ1AKU5g&3dwHajoL8JatA)OokXC-S zJzn#?_v+B{V84TSX91UiYr$cK`*(#F;sv?ZJ!PBb8d4IBp|GlFndSwt@=Z2Jdb4Zk z(X;PXY)Fwe?Q99+iM_6zM!bae>;5X=>ha5BoCCR=gLd-9fg}|cU&&tc*SZn~eDY{C zbUM|CeOM3(FdIZ$AL$ZYxz9TqOFQ;UVind^Bs95Z$ey!SNp_NuCgioJ4pORaO`Z@} z@8T~V%E9f3>jFOOX?eN!;#Yf`RC2R{IhIO%E;~M;md2LM?nQarUTPlf@6HDzsBz=I zxO3q#7+ejvmpUgaH!=vcyjZa=Q8q)y21eWG0#tTHP7v_m2)gdcg?x7;#dPm@5-i3O zS_0`0jle=DdSJd!%Ud!>C~*M-?d`acp-(U%vBbEahRK+)^t>;c$tVAQKW}W?@S%t0 zaVGPOVEoI+UJn1k7caBqObDxNb^bf*>vp-ni~{>9?(5Qx`};*25TnPTp^Oo%147t- zr{A~wt`0|H8)x#e6rQHb>O<+)Q&xhCKLq8T@NHF``V1tVVZ2&cr}B(n$45BPE+I}y z1AWmF@nv=H4HN$XVqat7RglRcm$lRFchc1rtXI}U_C$(w47!fPc(pz}UqU5S_5W0y zK90FTy*SU7o%u}Vv0TF~`Ic7DB92*F@u33!v|%W-1{#FUpaw+qRyf$%gJ*uu5#v8A z`$(CGUtgU0^RM+t1rQ!Oo8Wwz)X!Te{FozAk1An3s`qf^mYgbC8NooG#!hN=Vyiw> z<%YTU)yU zC%y3tOIA#0(o!kqdqaUr$Fv>0oNuB%Juw5&JLbsY#@8oDS#4e1=2Q>DIYR;`1TDK^ z*WW6e)ULuet#aU#t*Gy=_USv+se!P$h%$9_=c>)PuSbZG^Iv@uN~VD$e5^;`(Ub%r zIAk28o!+~YJw1j1hy}2GC9Dt`T#%XD-Pu_cah)g>jZ6g&?&O!hI>t{3A3(lcswuaq zhqeruW2jROCuE4KfXIuit?in$&$&`GwYG7NJyGO9?Gb>9mXAq%lfwC2@RY{i{WqO6o0Fa0 z>(LR&!t>0=$Aq3CE{^)R9DYfldKHVti@)a4VRpyhk1zQn!86u4xrGrbj%rBqF&dW< ze)KJXK%Sz()O_i5-E#Hy$Epq*<4q8+ZT34v-jBar|K-l;J91wc|wFUFrlHaDC3oy`j)xursGx(5@=VN~U!{6H80fJQ-@ z`$5dRDt3=?_pYD(FDLSz+9s>4I65CK$_SHpIrSi91I*g@Y8R-4Tmo!nm?2KNLfQFO zOGvdsqjzlLkm1HJKuHLwWdL*vNJz;N>FL*2S5r6VNqpp3|%<4lRgS@ye6?EwZ=H=qPj~LKtxV#RI zwgwy}eG92g?@uyXQ?;S*o0lW$B)R=rQ33eEE?VPBPYjj-goO^bg!M>5T13Q1Pfy|f z1!CwX*Gdv3hJB_>DY$;u*VSd)cL40o!FiV%clpeYyU45St0duIA=MSE>&FSUy|bpP z6h&Lex-=h=6h}CLLA}M_I88Ng5vofNhs-Hqz00&K{9JX<%*p98t6RB7Y2GtvabMjV zOxSwWss><`V~r1D$yPRw!(atj(R~`w}Lz zdezT{)w7QuwLR}m5qrxLU0z+Gg<9tVx^U6tx%BPv>yTTm@D@N9_T^;&c%8;ZKF4p{ z)r@S5t@|szLDE5mzsX&rjPRcpe!0)h6=(%5Y~OubMgS?!FPL1p{yEpb+E7)X0N{Bb z|DL?YsDc;M5Bb2G2nN^vSO3qh6h@=(rZfT zq1NU}_8w{5^G~pgTW?v`0n-Lgd&xFLI-}_aE~Lh|$?I(IS#p<2z2Z<#BPRzg`sDE) z_*FwC{qiaX{@Oz|TpvU}Y)8^N^7;E4_da}(@%C<++yVi2#KCRf?fELEQ{bPEMchWb zw}4GYgGC)TjTdOXcVBKPqmN>7cc@8lEQiOa%V%e5inZ^3b93fh_U#@$Ad}8cHgH}6 z(k``_*OQM6H%J~=UlFQrNobIiq5k9UnVp)Nnr|yq5WqR!-lbgVzEHeQur(I&lb|aW zm)P5w-z;yZN{+Q>zu(|l0U zFaqi!NJGzK+~M&RaNTjRvB{#pe(^1zG1k!`zS^ucJx48gvmWBrcf5G6I|In*>3}A# z4HfJUI$9q&Auh@J@93zCN!5VzNKtEhUqh%fcin8)g#ndK;eqWZMftH*rNzZ%==QSy zR_ymF$edRY`$2Fq(c|8bj}i#iI67AObeLWKS=lgiGbQTO^4 zW=*Pwl70mY%W$c-Y}3{nwla>4wOOfcTb2ksa}HX_SQANJ`x_kctzdCMOvo*m&4=lP z^NqB$M}=9(bO+d^0E2SZtHUg~Z)NRJIUQ3BMoUH2eLNA^bTkNoSj{jy{VZp&$}@;y ze$^8-@RQpS4iRvfwn7f%y9FPE8Du%zw|yG0BSER{ywV$Tb%w#~(flf$X7E0b#Hx=c zKtD^p*B1csW6-5$Xv}Y*X0kgslo#f9?m9G@_5AaSGZc_0gAC>@FE7l*|6Ux*z7@tvz}%^{(KFAkM7lZ&(y9!;$A*7aIU09c zCfR86q*5ANez$CFX4Yyqk`FWV+ju@V@#X*mX|Z7iFbj~mjwGr&hy)U41)CG*&=%*` zL32VH`p-7kbdvhhvzL4EUEbd$BprmZ)eEMY$uoZcJ`z7Lqdf%yb(5@4gY73{M__7Y zRN6Q@Ir(2~NZ)}Jg|IWTz0J5J6CR1v#l<NdrU2#LBLo;TDMPwIEC+D*@ABEd0NQp->U>LEbwg|Ew0Mdo8heLQIG?)I^!KM! znO%O8^OJ89ZgygxctVBcN*dqtECW0E82GC?F33 zGL=0R_5G``P8Y}b~T>0xm_#0m-GRUPje z-Z^Ak+`G8k$_SX_kuCA=q*3U}j1GXvl2e&QOR$bzUNoJN_)4}u3c#Nx zh}qdDqq;SZwQm?!agy^pJzL~CKQS}V&sq}^Q_*#BaFCam2Oj0*G5Gg*i>FASl79cR z?__$Wkux(p`|`C^`3&2b2P@R1!D_HfoxmytHYcA#-eBP#DjQ%R3u}AITp+Yr6c4ao zA^~1~D+lFB)M)^~6#z_txVSh*Sm@B2WtUK=fD}{k#n^34bu|YY+t)956!cls>fPOf zBbB9h!x!ds*gKn{NI0P#4~|pRvHK+4MJaiYgPVJ{%IuYgVCyK8{=(v9-xZ1j%*s22 zxq=dOu)GK^>axIcWVCde%X~ssS^z?Z7S^#2wpg+$_MimXAg|`m&U}LoUVQm#v&UQ} zg4Unb)eIIF0;)<%KKgyK;2b2xzo*dj-SpWLG819VQBbf3Y9c@t3O=YACmjEP4(pUCiO2#YET%3<&u4=Bi2#kkM@96Ze@{WlCl(R1ARum~*3kutvZ2?~NiG&+{ZpgE zVPRo_j{8!Fe13NJsGs&MJ0~aPFo726xMkZbYIl2VJb#;afSsJubc4vO2gO7e;y-Eg z&{kI(iaK8jsqO4s_%S*ROg{)YkS2a0p}|Ax)k3v3;odSk6zNmSdh!B9j2$?qRibTV zXEyJ;s$W@ClW6cvC#So++vjV^NqOs#P zzK*?=$Q@HmRV;!~xgu(CK+*RxBoiZNXU7LU=Z*ku+soJ3)^>j1Qu%m6e(-ui zTsrt_KgY?*$w5|9a0S?-PiJh75((J%;U92-{%LyGPJrmW$o>LqnXCwlqYyoP>M_A#(DyagVRw$ zgj~CEe085g^#(HOjRjpS{8sPD*_n{5#MDOjuP!WHc6gF9^`-w1)m!mf(@Y-#i!tOb zfezeLi;(M6u+InYJ6U#}&WZ!@D8-H9XDq@FM6p~7jD3K_cl7VY@xSt?jDF2$iO#nh zzurUK<_b9Iz+i}>HI;fkK7*x@;{qHIL0NKbo7}3dDV&;_xd1-@t-+m;?aJR5GvQcc z_)9kfR;h4eEDOK>q|=zqP1}{LWkSe41+||ec|t1-L3i!V-pjuKmILd>-T<_ZBn{yZ zOsdFjuFjW#hZX?eN?5^0xqI5$@&@q7cD&f*KkHeRD56{CSF1a4lXE5vo*W!Iv8aUV58^gC0 zwK+MeyHTCqYuuC^s2m>OJ0v`Qe*@=OqqDEC@DMDW5hT%TO!5YB=`F#wW46&G-wFODeLIh=?&L7|X8-*o%#Hp6x} z9PskYOiVgGHbw!Qb#-->Np;pvgpw9}XO_MwQYr{m{zLd6J~&}tdB^qg*Tg(M$Mhl2jvKRIj5JNqlDNb87=M%J9U+ZXv8t-~^0$q?{#^aa7_XZ7&k7V)d5NVzpVMxVmzecx^IJXcL10PJA$37!N6r3muQT+A$uLnZt-%0rn=DRQQoa*AJ3R5J{ER|AFMNe&?+1fHdx-T}pBU4Xz z&wVXi5*P%f=<&3lKjk!6hfoqMP5N?u+`e}(=wA49uzs!)Q zH~2g%SHuOI<7EMp;C{(V0KcMoFu$W`oDJd`u5E#Se!14Uq!xZ}!TJPnqd=?~5iFN7 zL~~UyA9F@4*4)?ID+Rp-Dl^fb1;8QU*l<8dyom;XoxYVx-o%?VKwF>(G{HzBZK$Qm zpXoRyZmU!aEhF{qCT=}f?T zoI`RS{jj}l3A$PU*=ACb>n#AHq5PL-Hp+fK4&<`SZp0z4E;VQ?7*Zc9XfO3#{mJ96 z4GNMk3$h=0vff~P`1Rd*fso|arPp5=VROR+b+Q=LDsh7e(g?pps%-nk#l?H{U_S#G z<42fbTNiKNPEq^5W%^OUAy9XQ;h1nEU=9fZ3dK(V z24}|M9DAlB5%fHX0=`w`hm1nG;xDJ+M&G|S5^U*s=$q6YCIKqt`vL+h%iVdAslY#n z5Gg){fU|&uYZDMm9pyg#*uUxyj#DZsaf~X>+wc4OZujQv78c^Pm8>$`XNaGfpmfeR z*e1+1;0G_s$`A-dWu*ha5&)f(wL=gp>M2uA_xk;<5^O4a3oT>&+^2q{<15m!ry~m6 zf>-u6!s|v$Yyvx-4l^&HUW_U)zEt>jWU>Kzc!7|*zP?G)0|<9cH3*MrLmgZCm9Ie< z11x#?{aP;zXD1`&-fqDIo8GPQZ6op7QGeEGS-5@gMP1s7*02I22i6GdFas3>_b7u= zg(woBi66;{Ost(|dlt^^^+fzgWh@|Jk%o)DMA8U1NuXMAWx*a`sjjY~t2+Z`j)Ncf z7$49U;MEhOeN<}+SW(kuIwkWOJp)DJbFIE^o-emZIyZrbc%go~a(nzy+U0nk=OSo~ z<@3*Ut%?-u&@G(p?~2;cwysQ~KNswcoj9oy%yklFVx{wXFwNc+sb`17?aDev*$JA3(z%9ibu z$fq>$p|#g z#t8c`E*xUObI4nABv2UA?!gDK5=pU(Sl=CdGzTYRKyBiWf0Ch5p$Yord2zJS9Gs@H zA}ik1A3HUZYi^nveGEhm>bh=hYO<8_gvcfs@-kMHCym}tRuqY^SEy5Lnx`?&1C*Nz z-WcC42>cE-?g1TVAk8*gW4v~L<=}*NDO4L03h4Z-VC%dBFhl?A)BUwNT6IcB`Npr# zX?Q^ZPv6p;lk2N!L%!=Q>TY%LG2#j^?`~g^y#ONCGvLqxg2#ZuVrMKB{MXOPsk(#} zFqX9Ry$_N038Xw%XKlAa?o z=dbG`S>zjbTap^~#_j3j#j!B_Ika+R1CD-aI~v#6_9ZH=#&==U-R3Gj?R}(JVsa@=l@rcu@FA*y~P{5DDnUk#aC830Y`iDzUNpXA1y=AO&0&v8Q zh^a>WFq{$8S{g!&c(?wM?kC=_hXwSlO_rb02PKVp55yk(d-AQ58;KMVleg-&(Xpb~ zBK!@96AEU-LEjO>YYgOrlInQJo1_t5UAnnLE@nqJR?lFQncXRIM92dC+arBsSa>38;QaMiXte9`-q#ey53|;I z(DZ+ovdj-QVr7z*GN{<_%wQ8b6F_}48kDIbWyR8k9#4KmBB-(AyDHZQW(HnBVpokA zjnJAcKVuI{3g^1JTJb{$Fg>y&6tC>fw3a**5&nkw(`jbb`3@0hs_Dh;rs4R_A7BqLn&QvZEzCMSjZt|2t~CA#wzzYP6#aQq{Z zazDQ7sgZv$A1Gbz1Kv{tn%@ChOZ=bkaJ-JJLLL7GGYMZ#YfbX z4e2yQ9kZfFZ0hqEGtiFflqr7fy6S7b%@blp#SKT$Ns{xXDt#Vo)a@x(qR#~nVGa7J z8i^(kC1hs8d4EaYgZ_2{K+_%(uhjmvID#+npDh^WaeO`nac7PK}y3 zBom~a?Uc|`Q|)*Bm>3tI*0;ZI0@Sf-fAGk>KE1SBfgJSwF#JS9@3&g6bjb4OB+9+u zVumyLHq$^n1)51I4}p>!!^pUADS4d zjd*7Pc*K^`<{|Haqxw|vQ*w%JBl;yob-OK@4KNEwEZ*%AQPIB2mW=kbLq`UWU^`OI z0wI^ro&%2S1I>uAcH2}}C(dofO(wtmAL#t*lnL>m0)K4mBV+VQXo1{hY|UrMSz_Nr zsUw;%T@+XgJpS_8C|6G&6vH?~Yv%s_FI{Cg*fRc!2;p|oN50P3p^ybZ6)p4heNsjO;#?u@Snx!-b;Py{d!KZG$YwI_WRN<-YvA<}^FjRCeUS2VNN;Sn zEe>0!GQ~N1)kn9Pn%Qof8D{i|a>M*7yPO(xTKn2+><_H5O>@K>v2>1-f1mdnv7`BUA zu-TF*Ap)5UrOI13{~9d2haNAk)6VEN2RioS0o1p2N~Q4M$86xXCSqCI;dkIUHPjcg zBc2(x{ejL02VAQJL0%k?bu+YL4^p$eO0O)GU8F`ZfXe98KmXF_%$4240)-mcNhROI z@E>@5SF@~;7}2k0%GfMfn9>pXqktIeWfBB4_$1io=7jpy99=fJu4#nBLn=aO)BIt= z2XLP8>8@1ROU5ey@>zyvgbTzCfG+dR^7)O_9AyL@o9+C(t|0G0{CcFeX9ZF__D59V zB2Q(wzu|yg3Cl2crr*FPqp4sOl4d6&&sYXjs5Z8ZWQ|*2DJC#P=SP-HY^;aM6Noq0 z>Fi{~48~8=+I6*%506JMu9)s{K^KVBkd2!RoC-$p`Jq4NnQxd5YaobscxY8cV3 z+fc~71!m8yVsl$qdg2F8dK5H~;tLKi0<>J;77DhXMyASl(~ ztTBg1%mp6h1*>RImQv~%W4$G`6h?X3E3BtP-917vKtEsdzh5C`J?-A0dBjEZz(S1C z_w)Cxl>-T@6U4C?qV(=wCIA*58)jax2P)3|4+b8MkdO_(j9nf7Z;$crQ9Edz5oWWF zE|aRH!9EKrR4L^FFoUshm=T{H4`1^cSnT&UR-9>z*zHX&KmqHRGwA-5gD$M7hkR;tMt`vhWbq>RHq2cZccIX8 z?a~0d;`hmPj|Yr~zWX$4$ihfL04Uu zhO>1&{`(6Bo-LB#M!V$Ypm7%Ca^PFpT%GwkR7lNI0()hgEPkebb5X~Nf-sz^>Q%r) z2`GE#fp&UzK_s{uEv~9yxQV@8j`ZBT@3K52i>hOdv z?K9P*;sJ)(_q^R%x#oNMf1$p=dvYsx0`9)$NZrr7;Dq~*bHFCk-@|D@73myb3f;dq zhP{Tzc3s?gN8sDMb@z0A5Nz4!LUpuQrsE{}VU7sR=7}#p@i#P$?|Q$Nvo0H_1pbE9 z#&a2-U7uedU5&4p{6W_TSZmmJwb$7X90_4<37`|N1{jn#ONF1X8RpUso0=@SIQB8# z1D!36$s6R2wl!J)UV?<hW&r;jl(E|y}&9RqB5=i;FvSgfEp zxUZo8($`>>dzpTv5Lx4tC;Q#iDo9s3@zdA9+*8rf>?P40eh7kfs@XCT-LqCX*tY(m ziYVhnx0AsD^?nX#7;(xvEtU?xE$0a45m*2hc$h;s1eAkA8{wk&j_N+g-aU!vFc_FE zuA$U$UKV74DP1wOfx&FWu$Qdf-p>~pq~0gp1s}z7eXt?pzjKfrk;!KX_8-kSY>c&L zJ>_)nel?egQ{u!L4R}DV1R9K>2IFS{v6tK$AO%g^d+=N$UEWot#zp{{St?GT8tC literal 0 HcmV?d00001 diff --git a/python/jiminy_pywrap/src/helpers.cc b/python/jiminy_pywrap/src/helpers.cc index 11f990c3c..ee4345947 100644 --- a/python/jiminy_pywrap/src/helpers.cc +++ b/python/jiminy_pywrap/src/helpers.cc @@ -351,7 +351,7 @@ namespace jiminy::python bp::def("crba", &pinocchio_overload::crba< double, 0, pinocchio::JointCollectionDefaultTpl, Eigen::VectorXd>, - (bp::arg("pinocchio_model"), "pinocchio_data", "q"), + (bp::arg("pinocchio_model"), "pinocchio_data", "q", bp::arg("fast_math") = false), "Computes CRBA, store the result in Data and return it.", bp::return_value_policy>()); bp::def("computeKineticEnergy",