From 9c8a45059e706830cc5811f9c98cfcf6b5d6bac2 Mon Sep 17 00:00:00 2001 From: "Felix Exner (fexner)" Date: Mon, 17 Jun 2024 10:50:40 +0200 Subject: [PATCH] Fix calibration (#1017) * Make calibration tests parametrizable * Add two more real-world configurations to tests Note: the second one fails with our current implementation * Fix calibration correction There was an error from using std::atan instead of std::atan2. In most cases that seemed to work fine, but with certain calibrations the calculated angle could end up in another quadrant, so atan was returning the wrong angle. We renamed a lot of variables and changed some of the docstrings in order to hopefully make things more understandable in the future. * Add robot model to calibration tests * Add documentation to calibration algorithm * Add a comment on test suite parametrization (cherry picked from commit 557b57e53471fc0a9829e721f172184ca5d00039) # Conflicts: # ur_calibration/doc/index.rst --- .pre-commit-config.yaml | 2 +- ur_calibration/doc/algorithm.rst | 97 +++++++++++ ur_calibration/doc/calibration_example.png | Bin 0 -> 40759 bytes .../doc/calibration_example_corrected.png | Bin 0 -> 100338 bytes .../doc/calibration_uncorrected.png | Bin 0 -> 213664 bytes ur_calibration/doc/conf.py | 85 ++++++++++ ur_calibration/doc/index.rst | 17 ++ ur_calibration/doc/usage.rst | 28 ++++ ur_calibration/src/calibration.cpp | 83 ++++++---- ur_calibration/test/calibration_test.cpp | 156 ++++++++++-------- 10 files changed, 367 insertions(+), 101 deletions(-) create mode 100644 ur_calibration/doc/algorithm.rst create mode 100644 ur_calibration/doc/calibration_example.png create mode 100644 ur_calibration/doc/calibration_example_corrected.png create mode 100644 ur_calibration/doc/calibration_uncorrected.png create mode 100644 ur_calibration/doc/conf.py create mode 100644 ur_calibration/doc/index.rst create mode 100644 ur_calibration/doc/usage.rst diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 40a28ca4f..7393b848f 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -116,7 +116,7 @@ repos: stages: [commit] entry: ament_copyright language: system - args: ['--exclude', 'ur_robot_driver/doc/conf.py'] + args: ['--exclude', 'ur_robot_driver/doc/conf.py', 'ur_calibration/doc/conf.py'] # Docs - RestructuredText hooks - repo: https://github.com/PyCQA/doc8 diff --git a/ur_calibration/doc/algorithm.rst b/ur_calibration/doc/algorithm.rst new file mode 100644 index 000000000..036439030 --- /dev/null +++ b/ur_calibration/doc/algorithm.rst @@ -0,0 +1,97 @@ +Calibration correction algorithm +================================ + +When extracting the robot's calibration there will be a set of Denavit–Hartenberg (DH) parameters +describing the robot. Due to the calibration process they can seem a bit unintuitive since the +``d``-parameter of the second and third joint can be quite large on those. + +For example, let's consider the following dh parameters taken from a real robot: + +.. code-block:: yaml + + # joint1 joint2 joint3 joint4 joint5 joint6 + dh_theta: [-2.4147806894359e-07 1.60233952386695 -1.68607190752171 0.0837331147700119 -1.01260355871158e-07 3.91986209186124e-08 ] + dh_a: [ 2.12234865571206e-05 0.0193171326277006 -0.569251663611088 -4.61409023720934e-05 -6.39280053471802e-05 0 ] + dh_d: [ 0.180539811714259 439.140974079901 -446.027059806332 7.0603368964236 0.119811341150314 0.115670917257426 ] + dh_alpha: [ 1.57014608044242 0.0013941666682559 0.00693818880325995 1.56998468543761 -1.57038520649543 0 ] + +One can see that the upper arm is placed 439 m out of the base link with the lower arm being 7 m to +the other side. + +We can build a robot description that splits each DH segment into two links: One for ``d`` and +``theta`` representing the rotational part of the joint and one for ``a`` and ``alpha`` +representing the "passive" part of the joint displacing the next link. +:numref:`calibration_example` shows (a part of) the description matching the parameters above. The +arm links are left out of the image as they are really far away. + +.. _calibration_example: +.. figure:: calibration_example.png + :alt: Example of a calibrated model + + This shows an example calibrated model when using the DH parameters directly as explained above. + The two arm links are virtually displaced very far from the physical robot while the TCP ends up + at the correct location again + + +For explaining the correction algorithm, we will use an artificial set of DH parameters for a +UR10e: + +.. code-block:: yaml + + # join1 joint2 joint3 joint4 joint5 joint6 + dh_theta: [0 0 0 0 0 0 ] + dh_a: [0 -0.6127 -0.57155 0 0 0 ] + dh_d: [0.1807 1 0.5 -1.32585 0.11985 0.11655] + dh_alpha: [1.570796327 0.2 0 1.570796327 -1.570796327 0 ] + +The resulting uncorrected model can be seen in :numref:`calibration_uncorrected`. The upper arm is +placed 1 m to the left of the shoulder, the upper arm is placed 0.5 m further out and there's an +added ``alpha`` rotation in joint2. + +Note: This is not a valid calibration, so when placing this "calibration" on a robot and using the +correction, we won't get correct tcp pose results. This only serves as a exaggerated example. + +.. _calibration_uncorrected: +.. figure:: calibration_uncorrected.png + :alt: Exaggerated calibrated model + + This shows an artificial calibration only to show the algorithm. This is no valid calibration! + +In :numref:`calibration_uncorrected` the separation between the two DH components can be seen quite +clearly. joint2's ``d`` and ``theta`` parameters are represented by ``upper_arm_d`` and its ``a`` +and ``alpha`` parameters result in ``upper_arm_a``. + +The "correction" step tries to bring the two arm segments back to their physical representation. +In principle, the d parameter to zero, first. With this change, +the kinematic structure gets destroyed, which has to be corrected: + +- With setting ``d`` to 0, both the start (``upper_arm_d``) and end (``upper_arm_a``) points of the + passive segment move along the joint's rotational axis. Instead, the end point of the passive + segment has to move along the rotational axis of the next segment. This requires adapting + ``a`` and ``theta``, if the two rotational axes are not parallel. + +- The length of moving along the next segment's rotational axis is calculated by intersecting + the next rotational axis with the XY-plane of the moved ``_d`` frame. This gets subtracted from + the next joint's ``d`` parameter. + +Note that the parameters from this model are not strict DH parameters anymore, as the two frames at +the tip of the upper and lower arm have to get an additional rotation to compensate the change of +the arm segment orientation, when the tip is moving along its rotation axis. + +The resulting "DH parameters" are then reassembled into six individual transforms that can become +the six frames of the robot's kinematic chain. This is exported in a yaml representation and gets +read by the description package. + +Also, no correction of the visual meshes is performed. Strictly speaking, the visual +model is not 100 % correct, but with a calibrated model and ideal meshes this cannot be achieved and +the inaccuracies introduced by this are considered negligible. + +The example as visualized in :numref:`calibration_example` looks as follows if a description with +the correct parameters is loaded: + +.. figure:: calibration_example_corrected.png + :alt: Example with corrected kinematics structure + + This shows the model from :numref:`calibration_example` with the calibration correction applied. + The robot is correctly assembled and the ``base->tool0`` transformation is exactly the same as + on the robot controller. diff --git a/ur_calibration/doc/calibration_example.png b/ur_calibration/doc/calibration_example.png new file mode 100644 index 0000000000000000000000000000000000000000..6185a198c25c2e95667e5fc8d8217678e655ccb4 GIT binary patch literal 40759 zcmY&=2Rzo_7yrjDvtgB4QQ2gZQ9?x7dscSHmid%W2_>V9kiBK^kr0xVogE(8+53M! z`u_g^*Z+Av(Q}{sx%b?2&pqRP&+$^_t~?p>d13@X$P{khQbP~|O9a8gJwXU9>)&~9 z!mpE$Z|gcC2>Dm^A5H`ZIURy9BMP@}Xt*0KjCj5=aP!{U=@3m@9&z%JOX_<4n^C{S zY(oE$A72xp_Q1*`##ezX{ku7lzk~+a6 zt$Omg3x?}~%%k5Va)kQVwlB8ygvmt;M2q%}^lTOS#)?WvSa>Y;Y;9#(D~_buN6XQ> z`Tp4Q@@Zml`!zv~h_Sr;5NSIs<}kT4u8i=m*wyS%n-%gq(qC~ui;xy6nd^mxxBtMm z!@<;>50}8VS`6Zw?kkrQ>PhVojO(TM2ygZy@pj2mbt;ar1cN0Ezeo|h4hQJo8w9ey%C5|&?Pa*mU#m(!iN=*OWD|1U@#oe}Oc z^jZ9aLL`8p=L~$&5L~GEnGshHv7HS(q?)F%lloVn5Hg&t%JqH_ysfirNyvS z2<7oe0gOZoUBozC2qH~1;2O<;5+Rikv&12-eB>IysF!_1nj~TI+6Sx4may~ydZG-Z zuA!bCAIPxesBl3^K~_XUWUdJJF$0IR);n+!qAa9N{wfZ_XieVv8djmdibIcF=RAS( zu4O)vAo}>>;{g#wXF?S4`kC2Mja3q}rUYA^W z1J6sJI{N?_@1^gQAz?xrCmMvIHJXo)5aAF>LL||($sBP)8-mz~hFogaHOW62h7PT8 znZNxxKEj#wjt;r*+=*Lf{gYn$BG4>{(hRT8^A@pRXgtpDF%z#@CwV&YK{F!-+S}E3{Y!>mi7mx}C+`A|i?FY6 zhWGMQ+q7ws4kBT^I+gqJClHQ`gB=>g3QS1TECDVZli@s(UseLLAaL1`R3z}){ zha}LbI`RHOr_WF__qfwbh%mcI(f|26KU|VyDbQNuz%W8O=XoJv$@O;c;uZ!Iy@eq8 z-7-NFveIx;V1GF6vSXH&k2yuSuC|3|ol$wgyVU2%QhqTcH>B}>ubjt{WmdxVwON6@+~TMa6s`P2Wc@AD#z3M`eI$Bxm<*km;J|ThZ7(2ED-H))j7}` z`W}#Z>`c?(ZCS<}Z68d4mdLkwB(B_i5gr$6d^P>1f(hNCu8}u2G`QBoC3MR-1kS5p z=Fd^fpe@thTmRzO*$!WA;v6pD`?uN>Tc;J!(Fy)`gbzo&7B|8bWkIz`?6}zk+QI5U zP7Wz0K=dX4C+6b9N+jQ1_qG-`=Y{$G=n#`DRq8)0+^lht^-Lp?YZORzlS36%8xF!z zF!&+&Uc@JHbSqw(inS6U!;Ochfzp_X@!l15-bz5fL01(SYkJOQR}KnjkJNoBeytt5UC;u?IY3;iAuNdzIC(NiKn z=}9lZp{#6rPKy-DZNpcXxN)c7k5Nw9D8Vt@h3BPhlwROS+YBy{?loVKfswUAb zL%W+SJDjp{KLzXf42EHFLFq9+wC1zj9V5VOh=w%yIKF@{5v1s(#W}RQ@cT~;r@Gf4!5O z2xvwyLWzWgh!8pe9SjiOqC_P8pbjPG^nVJ_Qp%c~5Y=V24_a{$AyCY_RIu=Tj*zLx zCH1F3tLEDR|2?Q-+{z|g5hP!5frE$+RoEaUHt&h?Fu@=o&_<6Ak_0RP7CmjG#4&M- zwdLIg(jEob4tu>J#BiDTo&=JrZ&ECpT!L}AI6c6&V5+}p&?1kNg~XGT%*D#i;XQ-X zQ}XyLIZ_f(hi-xA%Z@0&AhZ$e1MKd=#UCOdBc>-n#Aigv1&Q!L%hyGkUF%tALq*}< z>dqOYB!q3K{uXS5{(Hh>1D3E>FnI2=B@t?1xgN+mA_M0)qmX zFe^wEd_X!44^JT$jHJ}C5Bg04sO)T>4;lr%$N)ns1G%l{7SCdEka?3&=+le9mT?eE z1hK@kHbqS4b*_@aGWaP7DbW61Qa~3NpylzpJ`+@WFZc%D155KL&Ngk(9%f9ig(JWT z;vw`9_7D}`POaEn5`@+q+Kyk+OsgGzpJq&W(fwBedxX!0Ji=oN!!g;zs)4EF2TJEB zWv(F$q$C{Zh$GlU26}k9Pxe2PR{ipDsUAIghUn4R9CWSdI!Oqeya_+fvEL`e14>=^ zP!6J${x_9nONp%*B}xyU(o-C8GN4nWh%61-2{St5Yd?!<`vNaJ&xpIhFh8WxFY*~+ zUcFDpe2@Ej(-g_)U+>(M0t#)wDN*u;;S#1qf=G~(P&|W!P%!g%z>e1a=$s%!#2YYh zI_OEbHigmtonZUmC4H1IlTZu0tm8Mw1D~Do(y+Klz-gdH6OKDI5gvwNk`x~q5GBM% zOlJ4JuL=?!yu_dzkG?9vd8%Xo@LizC7(QW%smpONaY=zCzQ-f>v>_%I*cEVPrAxsb ziE@iaO}q4eY&!_zKfMcrgpQMNh4+8}sg!BI;fr>ugFS%3U$*do2L}zz3SOrOF%l-j zLL^-17TD}>oZ1cG3&)_Cja?fqG$^MyF1KU>1}7s1est#-T${U(#nl z6`(ItTyob9RChV|z^84^!uoaWE1$(}a-)vdcA~M}e{JH<-}j>Ahbb4?udE@Wd_%9q-roo4_q; zp2=_nWPt8a_vC`QC+H~Nui)DOhZjz7X21hjSyJ;2@X<_e!|CHBM*|O}4s+}TFFO1? zC76$2P+@Z$NZb5h$JiOrLC^2nL+ABt71jU7#VX>X^Ig0R`fD0hLK2{aXm9@K%kf?p z8O|yN$pASFvrQA_IOb;Ca^m#D^HI=Bq!*60Z)clMCn2)Qs9sbJ`i=G)J=d|SGTDAu zh)Vlal*gd+=1_~aew`XrZFS?|NwhDhxu{3OGvR#4-;n!kTt@qL{?ie4j~(d)qx~4s ziB4axLJ}lIG)ZBav`O5$(MxBs$|!$7FBZ`^pR^-H7H~H6ko+wXG8$wv(sw23z{Vcb zOTYU_9x) ze{4K)-1qpa8@wCFwA}9LjPFOz0iE2^eh>1h_fWBnDJJ6Fq-+(7TH5ukF3Rti~ zYl6M1Q>Qmjf%#|M4qlP#A(lKp$`;8`(o71D^&Nu0L-ZwG6w3|MVNh+o*hr*{U`aPi zkxt22mthzH#;U9%LZ96%L^_SY-;gLWl!IO3{m&TJnPc~s&;g_!&V#=aZ<{u^Lx>?~ z279;ZKrbIsC>_!%ixN_>C~zFuVLjRHRh?6G%+X zV>CLP!RSPR^2hsDVyjh2fFU>WMUCB!`q`l+*e$|SL481?iORORAxsG72@Y(S%40mt z;jFSVY99v{4hmaG-mCxd4^KTbV|PbA8O((SoX<-p&!}moOX5;}sp|q9g=fy=5 zcl!upQL43|SIaTsbg!^Or4kAJSA4Sn>=S%2vqoJu%#DUqH)qkoo`c6SpFwva<(j;J z!=m!}IFaPXoVinZUh3?3Ub%0Hx@|ruH*{IcY?eLCR=p~96u`pv@h>$AZA`1>(tcLO zdd^Eahnn?FtBfv3|&AxEHYZJGD>i61pqcdm&Tb9H<`-kDhb31cPl-$Jkum_o3rOClToXLBy#etn8eepks8gqfF_D_1Mkz1fz(iE|Ob=YA4kE-Oa-_lzf zpZz7#7C2qmS6RrxcERdvr8R9p>7Wa%La$=^=|6-Yv~KUErbY}1vvJhygGNV?-Say) zQ7J%pO(xIwM2r0;Q5;CR#+CK?piWSpMInHcb&;>-O|Ig|P}zZ(OL?f4n$N_mFKwDc zFyQCvh})dG>tAp5emTj-&28=ApjvKVHxl0##X}VTiD$4xIfoQ+K9x3%D?Phy!JR+0 zNQ$0yP}|afsqyJ*C&*d5_b5Y}9!7KE*!q3mzm(yVSkf)SA&5Kj&?Ecw_uaE)^Pj(* zW|iw!yZY&V21`p!O-}!O@ZQh)ji!yaZ%?=X_#tG6nvhP^F$$R-a{(P`KouJ+l7l(w_0m<)t5bb4)iuUg!ms`r4O=sWUaS3 zQ1+=S{r>0oXI?&s|G;~4wG7_ypNnr_q^71myVv6e8rui;x|m)GezyBC|+@M4qT8^(8-EMZj&;UujCCeIl8+FS!qPb&zRHvqmGEqlbUaur%y0jc9e>f5H&vX@X4aZvj%!g=AY=YtGW)IJ2o~Hl zEzjjZb%y^%)emhwc|IbQj6K9`XYQoGchbnxdKk*2lB^YOrdz;yC)FzV!$-2#X-9DO zkVh}rxDhPpZmqZ~rI3(Yh&1@%-+n_4&z8Of9IY3*MGH*-kH)~Q&x{OW1}R_ z*|GZgQ8`6Txnsx}unh_t#F=)_5W$ky22wAA8dw(v>v>zP*Z|&I)p`*I+Sf?!&-WFv zoa=7-kah8MpCDnoQjeOzM~&+dk@|Tpr~{^-+a zzs;%Pvz^UYY5eg*4Q&`RN9(PAUK=l|uGa0u+Zu_Fb()04Em>>-GP5)YP`$bpLC>Jg zY1Za4uUF=LgQhSoTq$%u#e%VCvayiZ|7I5Mkjcmm-lCLAh-eIz9B`!FRGd1E@Qb9G zrYQB18pqEGUnZ+s?+|Emu=dWowD4ACKDAVuxUHcjQZU{4g|y)(M{|6qO?>3anCOUv zG~g5nkq`(YSf){YE^zP_a*IUVROb%VUwu6byMHa`O}5JINGmqVkZ&%AFnD=xmPc<) zk;}mnUjG|X`&FJc;tZp#%%bp~cKe-st%l{LB7LnY&X;qxXq7Q63l(_ALMt^pPnpyKGINR#)SZP`GT(~RTH zoo~ecniPR%(UD3$VW!b=B1iEIp7a*wa>xWIwT1uQ>hpM)+jUDZsvu1>uV27p{0+C+ zJ*$cC>`jYY&0>S@7N$dA#~-mOm*43Mp5u7ZG29x#q5VFV09kln8!dtZ#)4X+Xc6$3 zbpZcR^nlF#Drc!)&;Ek0|CiHwcclYZv=!Z-rk^8jyQcghlC_7Iwc(8^XFoY@x8wb+ z3Vm%j+sa#2hSMp}6#ZklV-L&0q@?Cnsye37#2-F2zjt_BTbV(H<&4!~*6qKUWY79Y zY;lkQ_GVpXW(32%Lh&Y10(7Ee({H46%rS7w?rpZtD2ah#Y3i?EvMnx}IpJp76zN(y zSLuT}=!4N+Aokb3Y^H4Q*q77K`h@C4v7&B-n!=qR61_5ktZp@<#K#)_Bd(>d{AH^> zCd+q8fp57BWEe9ZF<-7Q(w&JBq_Q9q!hJ*k(~FJ!Jc`)I+RH`s&*c) z?vD48^XRY5d9-gI|4wpij73wc#CE1!U(;heFI?|C&(?RX;&3O8ynZ;N;ra4ZcS5e7 zxdS`SP9OXv$W1pg6QEH?Ol=+z6?N!tzu(*+U`_@~XPhB!LdXX$Vu`Y(%u#cJ3VWsZx z=h;QYa$9UdzU6ZQBhN`}VTCm-oV6Y#C7q|EQ|Fu^sBRa^;@i$U+Q5vi1gth~c=@b7 zc1^o^fxpa(qB?zVIsSy*qYSl-yb7Ob#V5TR?Z4N0$5UN49=u`j@=ac>mGABwOY`vx z?Q@z|WGl0hDgV_sddceXXj@Zl5XaC~)->C?FzL>cGXDC|i$g zt_ljRmd(6=rFvR)`R}iDRu5Ix^ePswbh~YNZbc<8hbV@!vP!T@goQKi@aSpW2r#vN z^p~9q)~}b#wSqg~k&~)d{7EqbyU}w#m9&k5H>%Rw&>mNa{vLLGLzv@Ckd4EVAS}9B zZ0-A&W_t%{x8T>WIi&(WTQSo)Z$45gETr*^(N;)N0~Hn>zvUBZ*E+jauT1vfflZ~G zFux?Dt-;;PrJH=;f64uz53=Q1Daj7L^3l!4*_mUxYsh$IWg=qBJZo9KvS?3YDAT&Q z_o!bk{I>Jf!K(kw5#M?c18u|J(seSSHShp5gtLO94<6ztN{x64S2G2DGLh0shl1rz$aSv==U4`pg zH6Ht=<{JLgEUnc9lQ%s(OZiHUD&!UwvA=-_3>I&1K`0yF@J>M7Lc3GAd+^ zr5T+paC=a_)!d)qC%5=>3Gbr#LFv!zVPMo)QjWEEXS&;AZPSgUc8AV%--Sj`7TW{w zp#_P*G@Q$Un38z%^BYa0XX{Gb>+9eS1=;=n^JkwFk{v;2_a-u#U&>oeeyQr-UY=Ms zn3PvLvQ|&Rv>c}^M(=?)EplFylkd}SY#F%6V4@whx#t&xq)H!zsW$#?YsFTUQu|@X^09iu-J0Qr-+Tv&8@GP@ zlhkwRuNB4%8fOU_npJno|3FS>$n9T;O@BMVS>+hda?SS6nl(d*s%uUOZYJ`zJS@C1YvTQ}NS6-F;h@m3j;!iY!gfVk+))5CvCk z)LzCIT5mk1l(t7>&?UKLlCGb%*>PTiq%!v;Ho^~AD2`O_U0;39GKa^sjbZd!xlz6Q zC(C22a%`k*c`8&YcW=4Y*ms4@}-%mP9 zwHaH{S`>FL1``v3`YTy&J%y1MKbKuxO(tzvp+3VAA>igCM-pW&xVL5zQTbRdqN+4> z)rJ)OtIpfNx%ARcj$?CoT-KM7cj%ir2+k*M^7A8JYh0d=LWAaTYMw0| zN}2$$vwm*Z;_2Zv&!cSf<#=0zd)05${`mJAGagv|+^Rh~2*zxd4BNe%uZVvCzB5rK z(0S>X=!jz**Q@5K%>H>e&981<++9zT$|0fQ#$J)ydC8KYm1Q-tZxy$H_-vCQwy!43 zIPIrTZTd+Suy34aP3Ze#nz~&%kKJI(*c5FE)3TZ$ds$aQORG34Un%FxScE#Q>c_^G~&m6saA zx*Wi-%&qEW?@TVPKY!$+pBu#C4?QT|W*zew}*Y{T%&YwGX@)z9Rb=cwI zAazRsL1nk(H}_Ek6l4W1viD3;GLNE%Mz@UG4{Pu99YH)b>F(EaljK7c!!BRGyxyDV zquF?0RruFqKc$|ZbYt6cz1D(ML5)pQH7ou+*?P`x6tXc5UDkYgCqA-~sEWC12nkT+uZ680o^AGOZb1 zOuN6c<$L5d;?i&EF-13)?orL%!0UXt|0GV*ThHEeczAte*+=``yLTSb5!xDAPpZu} zJPiGBn)a^!a_W$%*yz)D`TM)YC5vEx-X}EMSay6Z&Afe@iUy*JB+owI#diGo9*beu zODcC$)F2Up>1exo<8K>}jh)@y2*s4uit5%9Tk>#l*G()%LwZDXnsmuL(E#L9N!(>h zWLL#nD8-;DhQ2*`R*$e~Y`3p;z2%;dTIr}qmeJ8}zm1QN5eW&2n9qKh&q2Shp|-Ji zF~qbr>nS`r9tOPbAkU>^K9zSrUN4_g5JnDQc?lF4i+#JDYtiz1P}?{Zw>=ZVSmP!~WjswkW#c+}cBr z6g3-h56_cnP7rdyC1VXOQo$J$H^Dh3fhv#FsPYgHlqz;KbDX~4*E()@C)iqx>lJr#6S}qvk8Je3FCxhGK{bs`t8C6*w;B_zqGS#P|)E zNYm|SXt1+Kwb}SY?>QPjnWh3{2vxU%vKC;Yx|G=+j zVDPiXdvATw-nVjRY2G@Q*OJ`gV6i=lb?!$H%|@+31&fT@)%bqx+;X`vVbRKuT7oBY zN(A{yWy%e59g+{a8F%ghQNm|8x44crP`Gr7IRohMoHj-R1(N_D#nD zb=T3o`Wnw1&ci~`RtR_;ZrM_I@e(ZH1}dzo=LE7IKXo)$Ccrfp8@}tRDDTYTPNR_H zd0*dlt+aHgq^Kylyj;}(W}+sE&yG}pselj5+*57i-UI(<^a^9)>z%>Ec2<8}lZJ)D zl(^j_IBk3wYd7m^e+7;1&v^cqI)EXs*qPCXWTI2Vh&0V$Ne&=hSMFYCsyaFR6`!l~ ziU>Qwdg;&milV}^%AKiB-C}sFIX7FhhLih-55`@pSBf;#hhKpW)5;2#95V5J#G(Jh zNFh^$oj9-|c)q@wAaCo;4|7ylwN#w)h0#F86f$!ZaSj$fCC{_^Piry=n0dijj*gAh zDAu!mMAApHT}n_Yb+|nhEL#F*?Pqwu+wiXo!}~q#`@giW3UJ3Oviz%bhKZKgj;*y{YRx&0##ZLr{+()h)}C4>34MMKcQiZvyz=N%VdIch@-cz1m$- zHWZT5bW-$JQ@s36%<=aNKnEsQ-B(P*l5br+{fh-cg17Pl!ovM07H5uY0nGV zpAC~XSZ3>M865Vw7=B0{eE*Tm|0c*}u)>gHO2Or;n>(Sljbn!y_q-JYDVU7BAH)m8fFPJ2pnLGo#ZJ#A{@;acBXqpgbmoC<)l4TyQgn`I-OjR%h6V#k)ffr(Z5@7o1vjrZKPeS2Yv+j z(!t0;e33HC8O0^3biHDBh*kJ%)8AdW2OF}nxX!uv0KrN&>sn@a0gCz&@}CY?8R52T z7h^jNmsRWK8hotnZ6ubg)9j)O-HWATHI8X!hm%HOS}w)Ar8`d-ZSty1*k3R(G1(hz z`gL!l>iX$XQR+mpTBXz^Xl1nkh7p+pel0k)dO0QRWgBTWL5-gjQ^J~>n$}Z^4lT~5 zX0%y!SWZknIoJ;zGb~g=@2oM0Q`$dF+)&XNSMKbVB3ZB0aCnlKU&NwcV8-!5$@=K< zAb9V6YPp@abSDW0uj@85Uv*+Y^-LaC2Mex0~4FE76_8N|a*9h6fM zUv#DqMBpgP)@pjjWd|o)N_N<5uom)dEUl~*0!**cliN)GnTMFfj5c*rLBCkBeAVmV zl^=Qt>#XSoh8Z9jY=-M2(vY79J)d;msa>Zu7Q8WE!4YI*E4zlDGln;Bzh*;3?Eg$o zPEN0n?zU0m4W-dtvosdAw{Ieshp)R-o@?L@@0iuRO8L7Y_sc{+^a~$wQ_&K+s0|29 ztGMW4 z+S^+0Us%WnZjd&pa7WoZ&$iF(chTw|oZjn?jC7uEZM|reJD;h;sTfAwW>{QbYb=8}r!IYCHRJwpjWp?VexIBx-GE$@>f%_f@$8Q{o9jYx zcL5F2h+>dGs!aag9TxejQShm4q5F02eiuQ|8z9W!H}|{H)o1@!CfF+`4x>~IY0c^X zhq`IxguCo4Sn1kn?(G&#Vm`_sSiyA$T&S>TJz^)nyU%vZ}@e5)cBrzLQHW69=TD=*nJ%?zb-NV-v0M!pD-!mH+8`{Q(% zx*2TZ$T`r9M1yDom`O+6Tj%R#4ncCy=v-4A4+%k{gF{1!?5#=qUBDX`5EElpV2@A? zUaTkfk9%?JA~+H74)$*)XDrvizWZ08bI@7>(n2(}N6kg+a^)X^-%<~Zyz?kvz!A*d3 zC0+m{mf>nFMXh&y#&G9{+aVM1L0Or=UYCP9Xs#!|#yC`B(-#~4>pi&LpLH}O<0(d6 zsA@x))3vg4Dr&%N?u>cbo3>fuaHr%6$nC($;bT4i0+N zVzswUR$7g}p5+>Rvp(V~ZE5ExBY|Wa&dC!ync#4;Z=hs=Gj_^5jIH$$a>vii{~(@~NxmI6-AtX?u-#T2!vG*H1l=n9v4a`21lXJ*ZK(Ch= zL*e*e1=Tt#-0$Kt-sd^pm)Xkmo$X_RCg28IIauYR>C*6++H4RPypEEKl*DsR@q4k1 zKHH|=v*Kf27Lse{QhH)95+IhrCe#S;iT4Qv9;9ax>Aiym3#p#2Bzd}i3I;Kjwt|PW z0ZY|eM&3tzWBm|2r-2*hSe~7d!U}E)5tElnb0|}PsLy&*s>RxV``CVPZq2T>_fDH} zAHY-OOp@7dHEVGw;4me1_`rM7#<&NM;(Ef-VIsv`#%L<+#TaxwW(dW z1UbJ!K*vWalWGNiiNfDq%dFl%nFMu0F{$7bgZrQLY;gRRy{W^EUPlGMLKVx?KhXGG zZ2P-pV`WR__gi8az#3&`B_-^jMZBhDe1G-UXcl-++D1=U-M2#4HanDXApZ$cdH}cv zG!n!8m!Hgl-g=dq)Ro1b}cP{(if(yWK3s-9mCUhC$LxM`~}dV;v2ugM0QNsJ7>b@5qACdEoN{ zkMXBO>%U|utQ;LwTc-Uh!2E%xntCEcY!)MU@7r!Mp1yasnJ(y|;FEf71$|1tbDJs5 zxZ14ut#tb``$v6yVv1IVM0FGMGb0MDrwh(pvWgR3eZWw4cv&IG*v8ROOdutV4aj-c&U6Gq>pgX5{Q0lu^+BBWO1Q1jOblm7T+V9w14fV|qWb)CuC%KcH z+1p!PYNa6D-ahv=DfG|ZdOuL0y1fMR_e$&nA(ZQ%w=uH0bjV`s)NEUAWMAI-{`bh( za@@uhO9+B{3eO6Urs$Pt`}hB_+0V4m$O_lwrVdwH?#bez@87qX4Udhr{8g*Va^~%P z#qMr@Z7v%70~mOXR3=5uN|~7)R+r$`B~vNkHH_nN`!c`s5oae(VPPQ}cIO=o<;@XE zZ9fHko+5%sF^{*+Hi^84gV@kdqMH5)mtfX8Ls?DF^D*urU7FP!a&H+C8R z^5t1-NrB$rHK_zLqfO&WI!>MR*xjf3R?#+@WDjXu+l|ANWVA#+{Z+ehr(8B7h(Pnz zo%0fpZ)a#YZ#;+uEe5U^sz$_|W?pj}RwM(^wRF=e?v|7YvVOVQ;o-1z1ZaBGqbdo` zGlc83f5$ww3XlEO<_(^szdT?@AdC}xJdUZ^pXMQAs>ro2 z&aB;UtNn={4+@_ZzuhL`nhV1v8vx+sRE*tLNA}jVjZ`J$?JHaa!Q89o6zeH(cvPQG z7=7G87To4zNoQcfxviendtU0$>4&4OHQ(+)`>rpIy1h1n z0K;msv-Vn3aZS@}wz9_g?mS#!JHMY9m?^wfH2pjC2Tu#>n!t%ZrjZXbN6k4$BOG#ZL2A zPtQOF5{sOg z)nI$94Abr#a>ncF%ihbLVO1**uC7{4JKy95q@?l;xM|!qY$6n8m))Di*8!O`96Q`B z6@+h4lTtCC+XLGS4z!WS9IJv6Q4Wh?xPUe%dw4t83tP758#`O=53fak`0y4YMc{jc zU@v~o_Lh~8a_yZGBjXJHvJ4d!h3<@pj>;-ksYB9g3KvA9xZxIEv&{_NaFMR&(-o7- zm7^h1G`V$fIAed9dN*D&2jT(m-2tG5M5 z87>C0N_L)Y*=lMt=lojsEpt~r>Pfld$l`5!|K`1WN&+`^eTPbP2S)R{@B#&#{+7vY zDyLV4N6q(X=Jjemp3(fylc~mTCqgF9&!2?ug~z=9SZ0Us;TnopYSgFnUc8{LN2w}&>pzc9lVd1Mg zyKj?^Y^)VCZ1Q?zM%OPZ7-`<*y*=^`cChAeM4mt{lbExmvh;9fF0;F#-iOSMY729@ zEgE7+mV@}PyERKLS#}iX#l7BrN_tn}yjgTPHSgVpJoZF2ZuVNH z;VU$%hjb$knmtPdYbZSC6$EtyxI@Y)7LMkd0s2Psi_`>@%-R^88

h~S`_z8m-Rt7TSW?WbVb`u$Vo#)GbUAq`e&+I5|)s#Crw8hb#N z9%%ezr2m?b>%iF8}!Wx-KGJYvWyW z5fk#+Rv%LG>v-RXKm3+O_I~~?Zwb{AhuvC%Nk+J@?Lp&rbhDYib%^ipy#VKbC!fpgNz1Wv*B*C2XXrdG31#7_tU zzdAtPKuyaCJJ_~C81|d<2wzH4S-G9Z_?4x#wL3fNxF8E3jpZ9~ii>a7lObY$n)Od7 z9C)MD?}iyW=Bv4OdgiuIJ8O08J}E5FR%1KYR+^&bR52C8!xj}o{F8xHXt+f5Jqk-L z;5feNgZV0+%UWP293&&U`PJ2f=L4hd<^>Ctd#Y87KW;LlKBh)GnRHl4kzJYNRCp4& z-7}n2?mW|p+c4RzuDu`$y4Gzgj)eBziDQjG* z7J;WNt|QXECTNNy#X?>`>}Ulu)PK4C%Wx-UK>2n8M84v=)xYXe-bb`L`jFy{#m)1L zWH^JYi*5EJol;mqe9Ynaa$bh04rE3<<9G+aq;;cHZIZ}3Q2?_R6kCWvVVSuDT0v$K zx@yLR?8+b0fA%=(-Q{r;N@o66dWvo^jGhl!Q%QT!B2Bk~_6?lkR8cO3S_dp{>St(% ziUf;C2$m;g3N8@PX6EC%68Hv7ZV##LFcdiyua2KUyr1`&;UxG1&bCl`((-A@{b&D5 zYw8+!pF^rD_Eg9T9O)y|&*u=V)IufnJkH*SQc5f>RAot!Al@%zEszA?{0>6Q;bcEO zsW?h7EKWKBYF~CK_Uu4R9{g8yhv>9B#3ts60>{Km214<1q@@aMV`NeNff1VG7X|@5 z{Vz3sQ9kMdvd-i?Ch@(&7JwBZ(zUyU$S##JiuYiC&~CEn!MJ!J4w%EQ*5gQLJnb6* z#lzZvkh)MnLS3i1GcB6N6xU#350p0;sX|I((FfbK4|QlWiStNzL-$HLjckpr z0O{=5=VuOZV7d#FoP!d8&Ug_#bRKNBDT5U}eng?Z10JmgBwBi8OF@ zk%}$~e*d{AzaM{{cz4@Dq4hVnu+|;hfl0Y+hKUoR`$V^|>=Y&Dvog?6bjtRR3^QtJ zEi|5XyiMMErzg2e{GtWxtMjV-62Fz)I+T(sx-6ZAF}Eb79`3%;l)j)!@KdHwy>E}I z>yZYo=F2}9R3hT{XJ(-ev=fg?5Xmo#TpedbCLa!3lY>e+*)m%iF_``Pf4KmnWoU6S z+^~MRW)%F$cO%P~!hYUr=td8xhj`S4=>3Xqdr~CmCAkCiF%c4zD60Q5-?sYkm(SiJ zlYi-kz+#(>x$24Q?W=RT*K5sAB+O2W!W{>6{(g6Myk>0A1*!9jajoIEadnrG>hUp+ z**uKIx!_sE?co#WJD*+~Z*}x6y0K&8+I4x945ZUIF+a)6N59m*mgZ1{lZ?Le{;IP0 zi|Eb6nHKHZT^BO3I7!l*o0jd9J6tk|MEk5r5W3Wv_<2U<4R2P2*`rXzJe~?ykNN&P zQq?pDIb~1ZHj}WUBdi%Uk7dtw+UUl$7;}WHeP;G?bcX|Vhy5uydYb5&{r+OU!g1sh z*Bw+WPw_RkIH-iyq#k^^ws^qhXBDtecp`zJ`Q?EVJqzXsFi|l@GfT4}{`?T94>{43 z5Y-QjYcNWkqfTTr9(u9@c-wicqxbYK`{8$HXz1i4P_A{O; zt%-*G-G_ckYi_HYU@K2M#?ss8!t%NK+PCiX{OZ4^`y8pz%3=cmkh1g4|3~aK>`(fy z)##CU(RuCl2%hvW2SI$qz%F|EiTp^^ln6Vet6YumuSN;X<%gl8oIa7MJMx&8T;zP`wkk`iviuWs;ACjAQ_ z@)VCAlE3}F1Q+A}cqAz!03g?FtD4!^nVL^Rc@jmcHBE3$aC*+!0391n#QC_^=qLJH zS6Y`FN$nBd^OsS+V0NwrwHe|dT|t?OCPpa7&|0d=ORaYz5TvkS1t0k;pEkps3y15) z3gIba((j!eJXYuRa!vCz(2ftP4?fROkoeRFv`4KdFVUoz0w==xPQ-%ezuG#T$yXYBw-|zE-GU2&kKpHFvI^!D(lw2e%6mg3*i#l9UKjy zWSOsfjsw=>H(&8NI}iNjrhlcCuoCCSoEZ!hL#Y1xfz~%64vn5}$cs=B@>bx+CC69; zPG2+|0de>;8H$|ZiQA19iSq(oDo2@SjE`V2QzG==&;#bgZMQrKrt9>-3fJ#aXhq&O z8>Q?0UYR@6B(E_iInZGc%;3wO7AQS6!4G){DOeMLjuA93!<0<@5}!VjBKMnIMsyB* zKncs8ibAVN(N_>Vw|WtjcAfa21$!TN)AWiEo-?$)`MYBaW|cVrOGAWlN45BiG?9M; zNK0Kfe!T8cV+tzRv}ew0K||gBmu)!Lk@4)Crt&-cuI_7JfFl84iN}yr_x62Il}UXM zF5Y3!FZ@?Di10EQ^anR;LVO`*OMOC5%T#Fk=fr(oF^(DFL;#VbYZ&j2+G zW(`nU`Som&G_JH)$L zKv)8Wd5$Y!z!XdGt3JR(Rw)D9jByYe{oiA2KnNoC;4gg{%6m|6H2p3#6~`Ninfm>Y zOVk4wnc!=}!gQ2(ASrXAAu_>a&^x~luz!Dv)8LenGRKdZ|L1I&+~sl{6T#tn{8Cn8 z4;P{R^{M799ztsOmf{x<;-~vlj1E_C{0xv&=V)@_Hu9oY_PQkzLYk{Gpek9*FnWCp zICf{{GO7V|yqtsaKwW;#VnrMOFLRCz`VGIKT5TLR`wtn?_H=9u$)~4w$Rvipx+1&h z4S#3Bpw7Y3`3%ZpzPddRM2Fn}3po^P#BvT%2tXqyXqAx(nQV741SX51wdav|+Df3B z6MhgPkqw_VP#@F#_u6pP(|@ed;r0I#0t#nkrW`We4KP;hFbcB~^dBpekIO($tce7M1M0pX;$`wa)};0HEuo7(IZNE7w~uOuT~BY|+|`dI2hE zg&m*#-;Q^{4L37d6$d2NP@6>)Bl+mxFF@+loah7fQ16F1KulY{WA7!*#QgkUM1mkn zP_x`=HrkPnAfKA=^C9^LXkB4s+r{c0Z7X8CCFVbX1_$-d*eZ3`b*a;o1q>|`HCf;8az%pnS&iM-)rt3WVvyx9edi{+a z7n{|#w<26v5!;`?Z4sYzHR3$~$$E>=_h1<0J!QW{^qvAcB3&d#a_h&uNx;GK;YbZ! z@3OGP6tgO5=O$OwUOq!dmlirW7%wm?$JW<`l?if6oqpQ%EHhv0ry(&rkV^FzuH;z#!8 z-^*dSH^@huM`nv;+!PW!y|d=0f`ZRh+?gU;PFiqM_1iMt?5{7{n{FDsa*C*4cRgvv z{CK_5%nJHv1{eN(7>-bQ_yul@mYC-jiWVPU&hYHL^W1OT@@Dy(2f=a=$w&(J<_fqz zxt>3reo4?jlP~TFdcMUbOY_W_1wMVgmpT&2-zu5$p`5;696{btCk35CPUYO~_)Zpv0*l=37v1A;o$ygbxRov9yLV1`g(LgdCXnly z-gm{FqrM2jA2+!Izw7r_-f8?_j`6jPds9w5A1@rZf?55(2ZD*gwmYF77_-=kr&cG3 zmful~q|D(jPjnihgr9BwKTN%MJeS}9KYo!>5vi1vNFggCBU_>DvNy?|*?UA$NkaB4 zd+)uIglw|OUh%Z|_&zSZ-k;y^dGkkcJ+JFrkMlV9$Nlj*=iE;W$G)+H@!m~GM~^PY zecS7gyXI+RDb~+dKIVAdUbz2KY=Dk~J?xevfOG+8J1G}Vp{LjUz)IZ%T zMh`p{T&n>3Y2NqG$bN=W97BZJoe09}FuxDwf=KN_L?0u}=wjhsRCx1E2KM$+&CIN} z4rEH-vJJaSG)lJ~r>FF#qKDTpPHXOND=ki3g8rAD0@=B zRNNmethn#KBG4?*j)!3u&sY+yze8^iCJL&_D zxR^WMn9*Y=7)g+F<@WCA{B-0kB9uK?42x3+Wx zv92d|``jGt`1qT_gJI7K=GkHx2@M^-JS;OxAE(K^#}^vPoV+g+>UXsb9bfb z9ErjCcK`54K3!%?9^s{}YX6uD29z=x)LhW!V1M^#q*(fm#}OV!+du356_~XgJha%y z90^|Oj5ot-bxz5U>EO)*` z*Z7~(2@?yjE94i!e@VVvWLOhDQoGSAkB+U-%O{EywQIV}XAu>Pbz2%-_~ivdSR(?m zH80Wd%ybWM+V2CW`iJ`g zQ5zOwV`a>U=8KJ|3f!5g!0umc&ch8nQ6&=3T_GXAr26ld;1}>o+@1SE16M?B_Cws; zDviWOI_gjjiD8Ytm|auIi9$dAkFV5**dd6x@N_E^{@!V$JO$u&w8`jAo zO0#*pQSQJ*(H3+HnY)EDwT^p>&!GgyM9PEzkLPz}bwA?G$Y4P45FU=cSjRnL0`Rw) z`hWMm|33~X#Pa4_+b?IMGw7AExX2R)(4UdXgN1!UkxPoCIE5og&PAIHr%(>ZX}`yh`KI4&<%*--$1WM@Xz!OwuxMkFpVT*@L@qdab$XyOU3+of6p^$uNK!C6U4}rr|Dz&)z3jV_3Pf3N|5<$L04j`Wf`H`sEKi397dM2I06AV`Y2bNv(J&ojY zmzIOywA^>W!$SNL*7sQFCqaec`{hF~#8Zp=73v2%PrJF@;Vw)MKC*}WyZI_>)*Btj z9g?2*M>wJbL-!qNITlj2vWGrchpaob4mB3^-G6E)i02cjJ%;}cs;;OXuP-4w_sX() zJ5jIuE+bF_^S$s@&o9!}JiyFKX=B()I;cbEuHYaW->8ESPj^Q*C=_*22zAxft2WwDuU;Q5wja)1b)V2~9@_W;mJ`7S1 zBD;8JA+L&Q01zyd`ix?WisQ%N1o`u@P(Wr59kgW1J<3)WJ9NkYrH)h#&$NrrB5&i` zNUy*=AdIh*Kak;^%-JGeFHGlBVKH9@)TNjwK9MCrke3mVQRUx&Y9te1@)x)#BJu`A z7!mLH3!9L05un0nwNzghd`{X;&;8|!qU8g)3Ar0|hOpH`VubZ=Dp4^O(sJ|t3B+Uq zSNj*}(VHQxR?nv8P*kMaDxE;@A=JZDH9e{2guZA~};53Qn6l_JkCFE?TN?4<-5VJsxHFEs+> ztS*bexbdYrxg444N+o>&O}HZ^^q+0C{H<~E;3~X~m#E8zhdxV*hme=`wEt>3nzIvl z6A2@=cev~D5whOgi$EEk2>WnAV$6i|ub3`%v5^um1A>DsS}MMb2YHR>vzNFi^m!Uz zGeA={g8%%pTLd3gC<23njPfmAG9-KGhZW<)-vpzrEbRYRq49io%>er>;`#A88X;gg zj~QgoqC|*}UZoF$h(Wq{62X^Yd9Y2ue`RHaDN@)J>IQk|(Qf{r+rcFQa8Pf0227H@ zNTh*cf0-Cyh>k||)G6e{`@Zu?Z7JS^&J$z+ry};25rCDPl3#M!I~HNx{|xy_D2Fzx zh-5Fa3Hvp0{=5n=c6WlCh(H?k!|({<>>tnp!%*ov5xqeS3_64GsHS~BY$vwyLm{X1I$h&g7^ZoI)@WXQSeorJZ+ZqEd?Dr)Y8prl{rr-_ z0QbVe9Z$v%B6J;`MhYso8XF#v?Bdn+0)X7fg|Mlk5mprn{&DyJkQ|nkqJ3yX2buB& z>X@|}rE{L3S0M~VtLE8~`Y0Nb4qX}ada^5SGwAbX#A{Gr|3$%b>Ys<4r^{a4s$zg$ zOg6sn;Kd+pP2|7P1lSPE>AM71lKyW}<^1E5j#VK<3C&j_eIkU4;qb0FI3(F&b~6}B z0}bCNAFJNQM9}q{0Y8AoZ}70AWf7!6;iOju3Se@_=2qO8(wE$ezyoW4a?j%es(da;@En4T@>u*ZxJt@WhhV{n(k*;v{@oFJ(C(>n3sCXerUcK;rgi3;m=M3^z&B2Wbnuv{#t5hpiw1qla z|LlfZjp$!(N@o;hEIM+hjqcg}-?)yj&EA26f#>A{*f9ZEd3#;i5dDh^i~~TM;yHXA zL<*Y@!9s$+y%T~KLd)2Jogyc1`TXSpHWH2lHzZ^O0ZH^Ly=inLV)GvH%v@ z!q|ROkMhk_C{v<$W<|0)pb&zM#cV(wH-GSC0mmVJVjT)?f2mIqJ5Or`%sO0|pz#cjT(ftO6=R7PVoE#Lz zkZ0fuBL7f<%7XhQ)VVKUG1GqJV)^$CAxn4?**`0NCq-%HR}jO3o7BMuC`bw*VYv<_ zAw)Yw%fvq!ej=;CBwNmvYIMI+C-gX}q%z_1R${%y4g+>~yQw57og-30&t@(2^@XOw z;%qHqfms(eLdl?<5f{O}ssMqGKKCUq*!g)|Jb-dJRf)biG-qO5-kdu_GXMs>8Hm0# zHs#IWAv$Kzw9}1E_rOe&uw}tSpP7!mBJHz{=)B_NfnlGZ`41Q73z=F%pGW3j5Wng} zzgw+GmVP;)7gqQmvLB=3A%R+*tHj4rTw42?P_H$}3$q2gX!ir)VH8Wz>) zuc8dKiq)^2mS(1hgVJCow+w>4tGC0?u}jGZeSVS*ON=k16?UmU4w(p4ini1L&1JWe z8gJ-=nf45)d zuZWz)ZT-k%=#u6}-+VLmrj7SXeK|&$N#b6nuqnN+@d|9@JpD%xs3ud#i%wmqOBpIr z6}^T`Brd2nk2q^`X&=%|XOBL$rnz_&^veHQn|(pBcv0lJtjrlbx^9Uqy$~sVy@4|n zOPF-m4V4HHRwn`g$y9s556GVaA#^$gVls^8{o^8UN1aQc9~2(Pk9s}o}?>FD&0I9jlEVcs$i59T2?a0=gkKA90jQ(l6F zg_LTloZgP3!;0o??asZTD3jl&<1A6v?5S^N>FJ02NY#JF?5|BPCLjCU7_DM{q_1C) z&R=0$%jp%SMw+@KBUvkt2jCZejJ1H~msTVTi~4uP_)|?WXh* zTBt~pGNbU4=kuTWOuZST;!6x(+2%1rAfnWH6nRJG-D^29R{F*LYS%G>%k1olz77_C zH`Nd!1&!?|=wuH(_7S9gdce>;cR@i*k?C@Ml>Td_sOiP&zL@XWCpjjD^bXHcIJ3f% za&yK&jX>8X)1n>|&R(+~Xuaxw1*I`#33>Gi@czQVVy14O5kOdLwzjr5<~m{6iObR2 zI1d~XSh|ZUYq@GhC_aX59*M#71<(2x_DGWoX1%2=D87n)=}j#;UUu8he_31)8y4Ta zb{&&vs9H# zcg_LLr^KC$D-ujuD!&%BnvTngHW!-FbTf{((t#Y3Io*^?tUabWN34jtecN_&T6VEP z`!J_o8?A34@<8XG{C`y$o39ECF^dr)iM_pwu%iHW7i=y%X*w;3URY|V#_MGCblWm| z9L0sN&6=b&PqC)-{xGN6h{LPxR8FtL{G94sK?>n5mDgs6gErRLTFPaPiB|;IVQWGX zV|!I!RAHeO#GeCLNJX zTJ56U*uGUCH6?I0`!`jY^`OU4mhxC8Xrd`I=3hurBuM+Ut2J!lW84G^JiGqdVYka< zw|g=b?G85bw01)*o7m^SqJ*B67ltBw!T@W{4Z&r~a09lhG#Ae7zANO+=Ficq7}R;% z7E*Aru)&+od9{@#W_atcTl71RB2IFzi+@+bp{97(YTa%}Nj>W?n-IJ(W;p{gAF!?Q z0QAEHQsTJuDFOL$@3{FG%7ciH5>>orDBaV6(*W)jw@vc_-K=#bkZqTcgPTB|)2TJNSj$oL zodVARO_+7uR$N<1qIVVkxU^yaI|aw?t3Jl*y++Y#_fJ=(dT)tT`2Eghf=TC3oPiRI zAx#S_;V109)(qu*=WX`)s~AtQMSLKv@9@{&%U8;mX+OWsHvZl_*MG6ymn+8VcsBIt zU~IT6?l?+)Zzv@$dNEE{v9k%@m?w$zwaw;IMXduqD3uHQ=K`Q){KTbWHFQTcPTUQxM~ zXov}iEk5e_;e6O?AKtJxKur)fFT0KrTZUeG9SQMleg9*?v?FVRiD@_Hc_3DSpuHM?S{Q_svy9nSpE21?B%uWNY(@<>MtB zJ7N5^7PWyFD=UjJu(FiEo-DR6$T&8Kuz%2f_m}zX zg58Mg^ou16zQF2(i}Sx_6Kj~o_xQ!T>Jq#-EvDLsQ^L$F*elagWDxW4B>}Zt+_L6$ z!F7q*6eBe-wwz9u(LmTC^8<3N$pv%gxd=QkQBSQ&!8vhWb$fm?_F^H3*Ry)iYaT{y z{2)#|Wn8jIqyOop{q3b$6T0sFU`18?hY+WO<_kZ**Pm8m{{k=t8R-#u8jmIB)~uW!s}`d=F|v`8t)FtpJA@ri^_S({BtGFiWcRVu=VKBKB%MR#*e z=Y$%6eb|5{HpBe@X54k!cB@&&w%gwn4w!L8?G4n96XBB zR%hmot7*?NB!a3pmd?2i>=WmAow=$i>2D%xPfg#xK2;QHxO}lKu+=`5=Z^Lgy&Ah? zcJ-{}n*KoXUj+%@{R-!K|8~iSaax-bz)*m4fu6>XYXgNK~HuTTr5drE#Csl*~u(N$=z> zCoR)CSVj=XPh=VSUd!%`_nhsR#0gZY2|pb&Y0ftTdAz2+&S3uDgYoo>P{8s>>)n%N z%TEaB9s;xZRkDT~Hm?pEdiO)bQwBA2gh3P`{@RR2nfr`=mK=|bi=4GO*S9FV8Ob1w zIM2Bp<`yCb(#p`=kE;9RUhve{p}qhk&{zsu*U5u%M?6FVHZ{(-WMsd7H?HkjK#n=f}a1Bxvftp zH|`siKHR$=oL~2Ok)Ah@&t{)3cD8AoAAGN#b$UOR+&@wcq}H-#nri&@2h@ftFIU5O z0|4*TxBAYsg`Lwp&?#|OJu}7+g@)?WDFr>hrt{Of{ zlVUaJB_{7}ju_J4Uiq~Y`$5M(o5$)xuiUoEOBX%D*=^>wHwiWw*2Qg@{t{^K-I%d1FP%MhX3V zYtEdQ2rYgA$FG~F?czaFEpiEJfxWQ?OT(eIY=JIo9AAd&S(*1WRHECoF5D=It9VXE zXO0IB+-ufsTBN5Iy3qSRax-$FH=nROs53S@i%VT18cxALt}HNJ`f(r1k18-4jCKz= zA!_IT`L*SxlWd%RF!hCr_lsItVtpgAY)$Hjw#)I>SlWPDv_)89xw~SPm}ZvP;ccUH zW1(JWdfBxvmNVnt%no_N5UBN_%A8J*&innFwlS>?C+j$(?()AHHmuBMYQ<9BJnL6; z1{A8)0`&*h)TDP~S-K0o8oH$9lkK(^Pe$ei2;~>r&Yr5BSX7|+OzECFE4Zl&f&a-_ z>}T!k3IYN>3qMG+%(Zy0d?Xjc;QkaNAu?BQ^-*i}fp@$ebHHC{kBpf7R%8r=PWarM z*<8rv2$<(1EGL#hON0aRi3HnGXYkM{)duoGA?XkG{GBKoINVHKN zp?e0F^Ve-;+U}Jp?LP5IyvE|8wrLH_TN=2_pz}B>h2W4fPsO0ky=<)jenG+rpER+m zWEaeVN<@)emW2iVWM<1iW%Al;V5C2!E+z_$kU7ZE8J?2|$d{14VKkkO1vSG#jXwQ* z`bh1QzhnDV>x{RF(^dF9(w>*p*GH23uO^#HBqhfR@W({YzpnN5y(QEA`jTI3HP(8a z@Zql|tBt|O3ISt_P}R5-)-oi2O$z-V&IPXQ7fufUTqnc|Xu9slC@7!L@xkh?DNm*!m2?iZ*4 zVBMQTXAo+0|9b3O`l<`7E>O(*WMyhxzp>R#foSXL>+hKOXa&SHZ4h}T>>RP24P$XR zaL3wm#hJQBN4ZJhiGMDar3;gnR7ZK7f8He!dusVpe{s+8K7L2dt>Ru2 zz|Gs|>OWrL(ZER__ZcE-JWhCh-2jDhsJo-iwKL|2%{ zVNG|Pg>X{{T3az6txU>yi7#SQFF!uwHQ`vGyI2yc-(p#$M|Z*P_z;C)Dv7GDk|zob z3H-K6Y(_eq&CShqSo5k?#r`k)Yh6?d2!5{bnwKpH!aBERPrif00P;`U&VSwSI=iNM zyyZ9YbPIG3U_N)W6ZWPbXX^0OOzJ~3Z0n6K)$5t+)PWtV^%c&0e=bri^D7i+DYF$( z^9Fv_ACk~l0zH&S|Hw-FT3%V6FPYEP*qG&gq@1+mV`t}^ZCKJ(bK>|gVp(4mXfx=D z1>~~i{+`u!6Za{$s7jwSldrJUF#h z_swd44JnO#d3w0z&Uk6he%_g%`xSF}ynDE{-gy02=C}L1{sefazU6Q7boKB!5SPSW zYuVgC;^k}Sz4Be6>dH23axDgx=bEEe)hmm~Rm)ZD#a#ov@d0+`nxQdI*@8o!6+obx zDylG@0O?sn%- z?Z-;BhhlcshWfik8!1y27}CO-?U&|tGm=J+DbP;&LmftUUPv9*RhEn$J#%Dt4i^z} zH~IWhV}ZhFdyta|d(GXMe~SrwP54HI@>`0dqc9FC%8fi0f?Qa9GU;fhaf#_@WFTfH>|EjWuHd(nsM6w=W*{kYbX$CB;ix2RWTB0>UZ zg3tY|$9gIF40r1Ao0V}PMmw_I^I*imcfZPfsQ7wgr>~`(^4JdLG2H{@?D_GSAsEOX zpWi793XFNe5ThCrBL#q*szon*G6aS^qCzQbe@XS)%g6S~6%0Jhcm|rj&k~dr zIUPh@V1Gl`ID49=xlVX;4^gIN^_tJeEy^@CzM$i4)f*w*hq2xKgol&aaPXd_-wRrp zrQ4$%!P1230#zO4)KwZPN~Y^!UkQHJmn5+6d%Au?cBsL)AZB7NjyVwYNY6R=aZJ_J zkq{v8NgvnG;Of;!K(+OF=2E1Sl@xLmy#`O^(2QN%sF_}oaWU|2sLd3iE**(=-K+|A zZ4bjp#$q5q{xs!O$obrx8mh=hnV}}2G`|v2sU+{C-?ZW8lts0{A@!)w0^)?nvHkf` z@*pqYW#*C1Jo>7ww7!iN?F0S86<T8reDl{+uMGgfB`}$<9TYfUhP=i4v2Y8+ z2c_~Bukp(Ous?W%>bqV>M_Y^$5vgDytDr6qvNN1qTz1EXf?W$Ci_S|eV;yvuBN18q zEeL6$Mge^gUNkbP4*a&yC3_93{mLoSSL*WjQ{%WiP>KW;BwuElGLVetjn1551w`WT-EfGi>65NX=4~f_AI|xY5Kc>%s%?zTjv8>_Sk*MP-L}%dq zFW{v>@+DD{-_lTQt`9XUKhdh=u;Y}j0gkG@q+j{b9&{Rdmo&E zJ)Uw<%*41rJ`Tfi%?%id9d02r$2Gg%*p!J*b{aWjnjrct&9ZE<%|hC5`Q}aA`ZO1o zSbIM`Cl8{;$*9H@@#>x1txi!Y_##%7tyGXLmX+?D#Q#A3Zo2J;RFQ;u*Zh66ZE9m5 zD0+qFLkK?1VeOQ|juy}(WUHOFv zoExXG^itRytp2?>6r5TQ-++{;*gPvI$JE0^8{@hSz|FbQe5D$I#By<{S(s`NS-b)1x?4jE_$bzPtifX#xDzXN=(%ze^P;|+DPfwNiod;fg_>r71nf19RRZ)?dRPlj;T$5X}LDla= z90)qDPQc0Z=bQa2p}f6NbFh1yEw;NeHTFgO&t441^>NMNP)$~At29THG~|`->xC5+ zj4k9vbZFXHn@=6zkaWHA*}qxT@E67WJCc={xFuB%!pX#iKOja9i<7(C$My(7T&=HW zO%|&3n~t;DTLMQ<8;0e9cJ?mJgv!l-_^YR8&z2TH*?XGd43oNnA*K8IOo7Vv*zB5} za;4~K!mB*PE>!ibAy1NI=w9>^>C=eE@{NUIoYvIpboE-DrI~Zm446~djeeV^D>tWy zepD0?P$;r>T~nbj^ir<>WHap(>$1sSzTRCU*Xw4#W*3vge7Rle+LZN!!#2#p$KQQ@ zn}-+=ZOf|7P_v=mAYy5L*qn3lp4{K3Yks-6{v-tHdQ(Pay7$D9x?8w5$-CtH5Txg!%{{YHBZalpeY{$6ncJDOOukYu&oEY}{yG zWPANU(-ySm6_`n(=;RTX;V{ENCfu|$Bx|;8HAbZx2w1LQ7M)%ebvGK{_}{=gOmBNHxQIw!hwMr zu<`-UvOz9?>MJ7ayTc=27$Yz!mhi=-C=uV|SlL;rG^PD`&?AGZdaHe7Ek(V=0O|M*)QedA+8cb}dF{CTer)y>5U|G1B6kpsT_qkca|6pi0xQz!b zbur@L!R9JERiI$ygt=*airAhQIj5t6Ud{K^vI!ooM=u!^P;QkJv zwmjs=`@EFUfg!6qucBKQyS{u0>E*bZoFu|VDmAU;A;YD0RJbr5lqn*&E9)WL>ReTo z8&26nwi8>qwPXOHAR*fzAsLE4&P8A0-w+M5#FmCdUb6BtrZK);QW+ZVDpJoe@tBQW zKG-Bya4&Y4S?@AldbCr`$jC?+f>*N}RRa>EGzI*-E}ILzvD;V()0IAc6PChXRkwaY`THcjEIheX%z=zu#E2J}@y3TVwuJ4sF)v}k3Qt5Sdh)A4R^q~#pE z&}==nSsL9hBigz?L(SvcI!gzKf9g(Et^T-1cbp7rQvO_{9dQRuadSt9`+%$_ zMQVHAf;*>1DxC_dPSzNZ!5Z4TB2aT-%68|#kDZMnFmjQ0vwtXgq96h~)JjT9da9uy zo5>*SV7D!J91-ibMo_hy<&hQzS!Y=Wmu=zkljY#YOOIE3Q*rsTHYLP;NNgu(iY@Ri z<}ZQDjXZ2!LI{Qs!ENs?AGcZ$+>}<0B5Z4F$p9>Cdx^|Q4 z*?ikxk(=eC$E(B}8^LiI2WA*4)}gHZu>`d&69)%nb#?V-J+`1kkl~f|IB4|9RLZbh zvqO895-m#A#-BFoRQ_*`aq7~NIb>zT0y|U(X|dn1^h;!(45jhH#8c6raaL{Jq4pf+ zctUV)p(U=h6mei5FtXCZ!zu5p1)GF(-2YntepG9 zxy9E7)lf>x3|<1@0rgdr`{WS(rVqXBWBEF|11uIhtF}V`vYI^>q&XHi%4D~u1V-em z)Rvv~(oFG+DN60D+t<4*XKj;TR3z(pw+cUrYR)v7+*=1wnO|9bG~zb<*x4H6MoNj< za61|oA8fPDx^&>Oyu7^NO)T&Uvkz)T)k&7_>rs1C!Ll1&k}UJ6MscqhCul?G5BzO< zfr3G;{y(#44V8?YgLuv4iBEhZS^?+vRUa$1`GLjt=P_EpWuBT2rC3seu3rMl#t#WO zr<(XRcVYav0}W!WqYrCwd(pphMtXV=B+-mUZC-_DTc~$pAdUKwW_QlWA+DQkbv3Vo zw7ybETP8z^oqV$Xybk6S2%{_P1NojD2~cFAj2o?St682M+b!h{Um9L!!r4M4q#ZD$ zy)7&?nSy%>f^s0CY8>gjF&F55FiE+{JGT3=daEdBzGCdqVvLFmId7TmlIZHr3srN^ z>eEJ6H}AG!c{cQzaTXPHS0vBuaGz#y8xuT3!a`tDQQsmnBJ6++P;`;|eCe8up-MfR zD^`j=r|GnMZaRCU2gW(4g$2;wUI|gC6Qw@ONVj&qWZPTJYtqgW*RKX8b`i06J@45} z9}Gaw#QPwJwLTy z{l4Mr4L(Pzmi&zrkG&KgZtl{RRkUmr4?9eqPoP=5<`e7nW_$diEAu#^F@iDioFNi0 zzt(F~WFu@jzY6C+IBaYz3*K=##LddgGTr>atm$?{Gtl(8Yd{h5qNe;{0I8(<6qvF^ z>3XW-^lt2wWT<(IOft=G{$G)Om#v=6K1F5_HflN^8?E|V8klT|edIOE#~Lmdl3rde z@3|D~&o5N(X^8jZuPdpR^LWe^_LkAM9~ouu2AmCbmg|fP4WAPabNE!4$7?Js%SooE z>)nXpYxUan^$Pr@AVHJ-Q;u_FUQ@6?PG?!vNitW>xNcqQ67E+wsJTH zmiY|1(!v%&Z4R7K4H?Qg6PCwYmXjby-{c=#0AhN_rG-%4T!FI_MRyziv+V2;n@2xA2kS(DQ_N0tXOD|dK&A9s4JB^XiO z5Iyc}4CEm19N>LxkU`oyGa>s~DdpOFc;k-qrLYvbdr{JpdkbuBHHSR3eacoG2Rzw1 zcXf9bp`B)zC;i5oZB$9WDJh;B*ciO#FD8}Jo%EZiV1Vgpobu?VJBYzvdV!o@bq-=h zN?EX&87U|Q{o@Y*V$$movxuRGP4l+Sw@S0pvsqYDUfK)9Jx=I+tCT_7J%4|2$zFu% zW87BS4LWLFSN98(>%rU}N206byuOb~vMdUDM}Cs~!;eu>g{ZH0=d{x=+R1Q@mxCT^rN7qRpuCeB5vF1mB$H8Qm5_p*9 zW1$v6b7fzoUoOMzCsRvx#&X&I*!~c9`xrtWWbyf7BSNl-0vs?%I&5YA;*YyU7V;$!!aPUR7POPo5wY9fT z{`nJ6hVMDPa(j)BD+M3frjDQX;iH@rB*;BQL_{>v;CF@bRA)&RcNG9fdMLAR5q)CS zQdv6Id_}1&Yn0ZI=8(SXWsh|(kBcOJXa7JyfWc^k#ieM2`^Uy=tUiMM-Qj452F&ph zCJYp9k(U%A?TH9-qfA^xSiur}CN)BVR4wKYgRY(3qIq+jnG+LkID9LzbtbEw6ec|@ zWJ}dF<34Iq1eESZwghAhagqDaZ8|qhzHMk{<*zO+eToW3R2KAY&(}G842VmQ$L%M{ z!0zY?jlbTL%+R;iA64BPl9zUY^G(5YjzPiIRs(i&f3dvQWcr$9Ma8PHurQLmodLxf zuxX{^s;;pMvd}8>9H~4}}v0^o20dFy5%YTa9T6$B{ zzH&}%Ey0P01)(FwN5!k@iloKHnFsvRsiE#4=UsMZ?d|MHk*8b9S{UThX(QF3*;D?1 zvFx7|UAX^%pWnYp&w6nWlc1(}Ezju8`MkZ&VLB;)6^hDia>?|?=5|dYLuLQ4zSh}w zBhDz%C%kbiw4zZmDUx;TAl~~IgSoPQ>Z!Id>d^sFG#ovVg4Bq8%h8ehvw77c3G=hb z-NvhS>IB{;hYZSbp^X*<4=KCcV!5h*TfcR2bW~AjOJ21$iqcoDblyzohSj{aZfWuQ z;<3aN>+K%TDDZUfTW9?ix-M}iOLSmvQ4}0-x8z@Ilv!*Z^3a|Z+7w8CWo1{x)S}B4 z@!eG*pws9Q4E|0t&M*eUmXJb2LqkbuouzXJ_DgMSwX=Qa##*(%N(8YZm{eKe%FI3||W2(quzS*zu;b=v2oU`Vfj%8-IYaX)A;#-pOp>Z-?CZ!Y3NBYF6drw@2C!o+n zZF_B65?w&CqJ&d;X^k(yu)R8y=v3}>v#{=fEe~_Lk#d$t-11q)<9fdL9}?bj zzk7SUx!Snu5zCimu~jv^#r~vuQSNQj51tqq^evnOw52YDGFY@+j33#&j`T=I-jO09 zL@cS}lRnLQlM$gNq5%_$MtP@)v1tE5wWAhRTolgM>${lLrP4|BPP2Eb zoaHTG@@u?urJ-7xgoJT#LafroQ{$ZZm~Hf>HhZ3!((3Au-rn9xHW4x@4fnbpB!1#- zVY~PS>pY3yVn&1J`|JXwG|Dsdt%^d2`_ZnTqAylI78qu=i7xK@`fPhfhA#K@QF7YQ zM?V#th0VS%BAkj*$wKT!lqz=7OfA#_Z$}+kFq0Ryif7-KUTsqpNy z7@3HcJIx!{?$=0?cR$u04`IC?`+aq_dw~@h?%3-VJk06MD=A)9pQN0)*r>_vi!r^X zbqm4Fbju3*%L*PA@>EVuP2HA}l}#8h69Z=iO<|mm37vPUkMffa$(%DZB`wPuO ztFj4Y7Q4%Gcpk%4bwy>^W&A~=s^4x0nycBuyQ`~T$433G)MR8c@QKu3&l`p0bO1XMk?5G12K1N+K73^J zGeA#mRArcFXzNOLo$?8+9nZHNV$>Qxe}oD*3tt>ha+COn?MT>J}`Y7+%VIsuH~jPFmTRpiV!w zuEv}ltoSwvJ$dEI6;L?5OhN*HDC**+l%W`{{UDKfyXe3v{Pv#c3ncySVSM zqqbj+2sYYLdR+PY@Ja0Ku3GyfSStq0=6n6Y-M`-+4EGISVj7f>mogj=1aCY(ShM>{ zzPe|%CvYQR5ZT(e2if~O6}pN> z+XDO|KP#7drz|hB9?xvMU#!_>RD8N!1-g+$`#VY zhTGaB7F^(X)Ghh&4rt(dI5RYOEpd8n2ZpZTLA~I6(CIwBM6y`J>hX5$4Y)7pMCoA< zM)C@{lY{Q<7z#?(mKU944)>TQJRaX~(~|ugg59{V{f}iB6sWp_Nat!R*Vv_y)G95E z7^}uP4&~k5M#{!9K_@v1cSg&zX5D*m5)v7aZ$oj64BZVlAt_q9VnmDQ*!qtKe^_BO z_AuyjdK@zSm=x8w*qmJz$f`KYt7^!x`zX5pF3zutmqbquodi}~@M>dl3OS0~{KSyr z#_<}8AC$-Kf*-H2Xo>tT9r#T(VeoWl-u5fN5+vZ4K(_M(#A^r#Fs=#lyt#bxdvn({ zhl@Noaw+`9tgNjsC@U*Br~uV*uc7q+p^IH8mOui7ET4%HyU&_c{hV>eqFlx6d^@dA zIqUrudLtefKJb(OMpMkq^+$)O^RBEMl;HjmfQBVQ8AQKIE9dmpmMo&?E|rX;or_?2 z$F(VOLf?AS9bnye@oDCOj~|;Ws>7acnQLllHoWBi0PvG!(qCU+KexS)#^=#;)#6ki z>7mcsmYY`JCk#KUQ6?S&N61zEP4O`koL1+`L+gu<)dP6TPoSb|$v;xAfBWJpXzgzacP;$e9*U{1#E>tBmRJbhL~ z;9hI4E1FT>O9bH=_T$$P&Op!NA8W4X<2+(#TJhqS^UbVGJt{^%zKvQs*JZ7`FaRv! z1uNP2(NQfC5y+GHva_?_=RlOyrOumj^UYTcZGe-I6kq30>i|m$R6TpAnfY9olj5WP zp&MZVQTl%AL(r>$=+vOfVxZ=*QnWm2nZegSxwB*JdbG>(dTM*+{A@14&Goy{r*fr) z)aCsa1~!iph-&TU?JF86r|7w>n1y0m4emi?2c$zWFt%{Xo)_#3UV`=#KvL;9lK`lP{#@sS*r+$K*gOV2@jkie_pkbo zOcpD>_%Y++jM>I7Yfi*i1>S^V@p5^~Qw5^DAwyTB+l+ z=-J<4=SnOvt7nHow8S-jP$->+$l;otHI!%R14-^iIGJk#4aqVx@3pef=2?AsE86nv zQqPuil`fyZrk0l2ck4TQAj$eTl=<6$^;@-bh8`>4lp?XSR=|rUSGmFTB)^hbIdOj( zKhQ0!f-q+OVsf=~Zlt27M%(=iQtP8SYq!D^P$l{MD(hoDsh^pV2NuMu6}fGFl&h?> zPidi*hlW@x(|db7zIGXCh1wyJS-26+R0%Z`=XgK^qKL zx^DI=H`oI=;Cz!iA6}A%m)n~MRCflw3iyDC2qbzyDqx`Ak7`BJfKncE|M!0!A#XI} zWGt3!l)h=UYh{-yh0Ba6){nniWVxfdjrmp{P($!~%5v-c>{Fr$+(M2d7=RhjiKWm} zZ~Mkyq?7xr6mq6QVvuYy_*T?z2{J?=)d4s7;V8HX;-f#r6GN6Y{xT^S+v5alNXnJM zFhM6+ffBbmo%3*E&^a$xZK*TRAzE z-H-j&YJEQP+u*z{c>ty0M~JL~N2>t|LrXs_J@$uy3)u49yG{gLKxDwR+UVA&4d<$_ z6c2Oy7-L=dZm?_yN$0RIhduhe>-y{-Z;XtxPn&V(^&Z;!-SpXvDyZeW)SjkNhe06F ziu~cEmtw|`%6Rzet?20}?A}W%$&JQiN*P58(vX?)!%lecvMWP3Zrm6>E#JM`43tSO z$-=q%Qgi63o;3k+wXlb?iZkm@&{x+Q#pO25&O(FTH3qPe%Y9li2-csw*n{NF>wNzL zEJBiZ`bJJpPC~B zQ@a}_Mccq>T=TY1F@Jq`akQ{^Gq~wC1T#HIz*nz$kbp$_@pTZiy+e5eRwDRYjFvRE ztA|jB1p`K-5 zp;^d$XZvjy-WLZrsxZ7ZV;Hkp{NgjC3MND2fx7$k)pCE~A}`LC%URce@!9gkP(Kj> zTtZ`LKx4xLN(zbw^xVkmUQ=w?p$m~G(fP6`*ZlVWDh&QcNSmKEz}wx@eRj_U4t~dp zgq)&tar6BqhPuU~m|4ZwL@4UvZ-DwkcfstO9MpLspY9x`dce!;*V5AR)tU1uA>L|> z_EEkHWXz7&)UNk@IID&%gI9`ynE(X2d3n{(YHL?HlR^v?^?Nn`k_<>UiIs!oD?694 z*|vP9y+e1@04SD6w?Hxz_HCd^PwsU=8uP>N)X}(}6^Y{Cz$L+Dn>Ls_m0wU$+r)fjJ|(W&MrE&h`0{Wl9iAkb{1mhcFow>q zJ3V9Oy%7LeJoB4^5esE79IyQSQ?;OViqu}Sbj$iRcFz~4Mgx6=wt+|4S5N>(H?Sd<{^Ki&JU9q0mbo+(_G-6#fdYAW z9E&}H5kN9KJ9`f@;ih6v)lmJ_h2D&R!%;(9`$|Z`d~}!Ia}vLoYTQs_%aqLEsa>{W zJcnRf;LQMbP&)u)ftVz6DZr&l>z=(f<=4TjU|E58Fv+RVEJGWd6p9C|12+ zm6aOlPh;9=C9{Y}AHP{LZ%qBzZcq^3Y5;sev+zFZBtRSr2F#52p-c>6^FkZ;%IG;? zy1{m=+@OpAijve=ju&^3#qPyTYTbJSNHXySFB97B_fvbDJO z7i_9hYl^Y8Op49POX&b`P)2}i22$&NzGImiwey`UrHoV|>0k>QdhQr0TG2aE4+nd6 zsc?(+r>Ct;%NMLn5}ul;JzbVoUlt!SDf-$y51BI=GOEXYogp4ehX!luW6QcQ$|9j) zp34c`7GS({y(nF6Dbi~&@p`z@sUd6DC^gbVOh)>PTNW}@zs)#t3lP3iC@w=;R>>Dj zNT{L({_M*EwcdsP{7cQrjZiO-dLmR&|9|DVT6}pTQ^SIRuD%MNLXw17#6%_8DNpl|*)kj0q6{<*p zS94y66cO<}M;AZx+yb^&ApJ~$3Fu?JH{h9JOte)SUv42o?fX}e3{*}J`GW-+O5m)M z9hqn3#g1hvQjqolo17w~G&L2`^f zk61*g;>F1Wrgm#T^dWyQK_TraP5j8sy$y8Es@5K?cwSKqy%;@?i}$-Z8~ig0Epr2o zIy{LbM!%h6GzP%>mj|Bo5(@@=?yl4YJfRRz`^PA3+_fgS1Hb!!JzafFQ&$wfudNhj zw0tOKI4C#*MA7LCx;VwBP82EHh3Rx?(k0Uojg^E^RH(Z+L=3t(zXntB=^U#c7&E&G zKDTr-lSLOHT7^}LC}f6e$pGn`%G~d~hw=wJxaXepyT5zR>3#3Mdw7WM^N@GttNK0A zJQ<)v70`#8lT>Z)zP{XB=M`JqNq8`g$(hgMnf<`d%PbZ0YWP_Zm6IZS=;_!n0xZof%Xw7 ziE|G1DD%uOP_~c9zUS*8Y#od|m^w`bS%;f#c}1aW)z zA*&1(0=KWKBxCNVvXQmRnTmykf1W6RM;x_6@>U{id%fx2l>SmnT!>Twi>b|p#(Ega z8-^JD_UUvcUoXK+p%$aYJE=Q&Iq}gp3fKD|Xc3Q${Zt+AVoCTzVd?V^2r=3t@au^b z6S|gHGtc&DI}6Rfuxlhbb6=--G$(vhp}I(dkgEDP*7ZgAwOP!51oT#hx7gy0r%Bm4 zoXE?gPe}ZKHrlp(Y%Ic1D59ckm>mxz@2V4r>{Lq|lYY_LU3aiIOiC zD>jR9b4JSzxV3YX5Qtus)3y2x_;?fz4@;1I8Z^>ufXzMV+m?E&5?E(OwAjkJy1t)~ zFF40KS_S7wRl0y$L3eRj{*1$TEbYmuHJEpWi5sd>Y(NN93}oUSfiXE-l$5 z*3>l+Gn{NmKC7^d-#s?(cTQFjxHSx8HCu5sqE5hOhA{TT6QD6b~vyXA$z zauHaZz+&s83Nkznp=q5!FziRcmp@08kM+;`kZPt{qVT}b^EJ26@A*|P#{J79`ON+f zy=5cJeOCJ1(``jBWyUR6AN#aYZ|Mr85YJZ- z$PY2V==%BmDeP7%JAGn(;~@}Rm=Y$=26sFU6``P{7PN|2aKN1*1f3}usYR_UJD4Q- z7)|ZFrsW#al8)TNPJIfIp&-pcWXo2otw+a4m{w>k#mQlc zK0Q4X!WSqHYQf?wN0jQ!V?r!*z;ovpH~Y!;CJF&PO~I8^r9(A3C`o|-h730NrZglX zHhHU=ibi-2C{8@R{3R^7JoVDKOnm8lq4P(0lOlHzTGW*qW40+-G2)Ptkr~SfhdBx0 zE*+#jnH{%2X3k0QU@#mk>p2fVsO+He>gyJV(j{&(41a9Eb_;92LU6`Q4yzg#i(M}S zerU`;%(H_B1)@g)J?z z(z;twoPdZVo6BInJJ-Ti)D0QfndxuT;z0&rA_#+J!{a>#Sc?$;Y13e|{ra;caW*s} zIp5qAd~^+qgYXQujxW13M+0;e!qaylAq^%<4mNBApHQu7j{7~qF{~kL4Lre8tnsE_ z8z@6`73hm=m^-KGUJJ5*I?5Ikswbk(wcd_&2D9zsoAq8MxZ_+}4TV8^evj(OuouF6A2e1ifq{-c3pU;VGKwRF z&hA`!Qs}gGOoX#SqAQo$S!WKe)quFWgB)P4D2J$9kJQ|Or9$!+zu@+nondU_S_GUg zMOv*j9;Q||C~tM2@w~jgdmecsS+C_Kf0re*OEo($GyB~adfPY0bmeQWn@KEd!IJmR I&a-a&A46cV-T(jq literal 0 HcmV?d00001 diff --git a/ur_calibration/doc/calibration_example_corrected.png b/ur_calibration/doc/calibration_example_corrected.png new file mode 100644 index 0000000000000000000000000000000000000000..a90c695d3d32ef088e68ba49d98be3df9c99e535 GIT binary patch literal 100338 zcmZ6z1z1&E7cRW%?(Pn0knRp?qy*eF0+I@dbZojoT3Q7`T2i_Z5fBg%X_1!h*#F#m zzW?6mu7{%@Hfyap#~gEvcf9YI#OUd$;bBu_Lm&`54RvJ$2n1CN0zvM;L$8p7eZ-2#R?DVu(KtuTGO%RXn3qkVLRggp1c$b^3?{;K1m6W-*z z*Dzy2c&fpEALa2($_TGA0TIyzRr2r`2;}JU?GO<&vm{R4+#|}!?qG~f<>X=%Wwi)v zEFy4C%>5oiyMg36CJPD_by%4yDl0>*DA_h!>FL;+i|_YU^I1D8h9`z%(MfZ(F5D&3Nyd7MhhBq>kM@Ct4+egP?=-4PE zlEibnF3IF1L_`s_hulO&DpZj~Fm@Mo&G0ZVFv&laI)CqL7s5q({`^I_HcNCO4YVo0J{@IX-j!jOu<@p94`kyHiTrI~X zp=_$n)~_|Nzi&@8l?nMf$k#ARD-|YhhKZ(&lPz_ec z^k$qjH!p#fNsSgE%Q=F^9mU?TEgt60xt zYr7pUQA(2HYL!)JIYj>VvOLPm8{%gzFYW4^=4N2{@u67Wzu;s4`5sXoYos+}X6{B~ zua_0D8%-n|7{b)-30RoKREiuPU}qF-D@9ktf+2j>3Ai?7xv}@79Ih58u#^0ZH{zBl zF_+J3%F1e^1xw%#sGtB7#N0Zjpo^G@h)$%JQzZ%*ED^?#116ioqPze;N8AN2uWeUX z#KN3Kh7MD0h$*ZJ(Sn_V?{f1%S^4(YKj*YB`pAvW{v_-FwXRw${0z8}=g|M}s~zkg zS-?+{BAi9iEmD8g{T%q7sqZ}g7)x3<*hY^91tdyt?8X1*Vm$x(t0jjo}{PfxJ?H<7?SY4MZFg}#-0tP|hA^|o@`BD@1`-mUm zTwUPrq@hDbJ@|2M8J7sAKXET(jGrkjTLElU!@Tji0qnHpG@O^>Oiuh;}J`hoeEx@nX4x1pIbCcHPH2o6u5TbjwHf3 z;3}s7Zwvd20;9aWsez5g0+uuEXXxPb2!sQi7NQms(Y*<> zd4HdX2(Q(`EfhSsuj|*VLpX~Ah#ViqoW$tpie+skO@RIH-AIrtrPYUr4&N)@k*u4W zA6oxi0vy4Szwh@`*=z7k|j zKmwkn@!zH>ngo7wFJ*KQ{|tu%@s5jqaw4KU<-4Cdz!bA_JEXQ&&#-})0iS3N6d;-i zs!c!##yA}+2)D0qqRM$~0BqI#cbO4(mE`>M>bVPUNgqKDuqZQ#m|&3L@eY=052Hhe zu?GH&Ae+8ak)bUupMLsWkb*T)v=_RMa3OpJzlPq%o)YtA5|_Xl zjM-msf$Fii-;CDb_f+(ZLiA%w1oJs6E|$1U74I{pjQ#!6`UhHnHhi_MS!7HstBk`3e! z5W?!Khp~FQ>_WC$6J5?kpS4_Wf|Mi4^E7213&J9AA3u)`62ZiZ04_?)Pw6H)S!>EH z+%gYS8%os^0buOVb?oL?bPY{~Zw7?#1=Y6%86}WMTrE4-=oli@6MBqnTn8OrMC#kT z7XoYN40WvQ0t3=7MiHj`>t!*;NRLIGG%U9l=N9R+!)nZGEJ970sbp{=9xgaOCD_&? z`qi%re~fP4Lu`YAU(axc{>E$%j47nSE<1>QeZ9hSMucTz(J_(kiJ-H+Ln@EVYQVQb z+7ui~CL_y{jdiHJ{zj)^%=or#kyfcU&GCCh%>(Xa^XZ{%#4|H~9c$uh>p;-iQP^|y zBCIKIk|LuwYsx&;w>&wWzg$Bz=J9uq4CnW1xEZc-zgtR2@Nj!Prbx8yHT92qBa8jW zc-+NsWtN=vr91q!a||izI&%5WNOS{bY}93f<>d%67##OsmtJRQKyh|2I4I*sOq~v& zNK^hnl9CRtLaP1d8k94Yno6m}Y+!s7m8U+&uRml*yhzF|5C;->9!wrkFr~(*Aw;}o zJr!>w&@off$5A23s>-hSxQVdoDI(JY3?Lv(<(EAbn@wXi_lJ+Xj0>O>?H0F;5qD z1ONWdI>ZS)yzAj74M z@q4<7Gg4;J-bXn9^^*z>&fbT54SVex0kN$O{nf0)(WTz;TCdeAEfl3iU=HoEPmgF! zAN!$FLTKgT!=#bq?0O&8ks$qd4kSsDtgagr*MK%&j85yn2*{wv7>L-FQKsb0f zB!K&6bU{T_YJ|=U9fFc(oBB6hi=Kg?ld_Ke^CBIN5;Jix;9wGt=2UMIGjIJeerOAFrhObrkWW9@J8SStj1NJ<|C-;m_*kU8CHo&otepSs%*O z-*{KQf9i)>tBhS&+~ZA)sS!3;reI(vjBVfd5!ImAma~$t^eVubqdHS84#Y^e(( zGGV9XRRTQmWK%q!?}mbUTF9c=!xf`yr|Ymn0|ueR=uMmSprfc;jbI5HOQ~cNZBJvR znw)X7**?O1qdK5(_A<2Rhpe z;F4CCe6hQwNcqG%j1hAdo62Iw6(>5je=ot&wwBW1{UZ6L@^#0B54KpypK~0!^BT8} z>sC75#Dc-T3WmXhmSZT&VuE)w-|{TE#mp)7P2)D94^G1~ER8!!5QlZJsvd|#Z`3EA zfIttxDp;umda!DbaHU7MDdX2gy3opaHvw_m#;-tr4Pxhpy?J7(L{Q3v zKQCcYzG#F8mTuE_;aIj}_1uFrx<)1X_RQeQ!4GB*p6-&@K|;*At@pxTFmiXs$7DaH zlzlEmTNkMhJAPi9<7gv}N#l%d_~`6` zZ+0YsA^t01KH`W~m9V`Jab?L+SJbynHX=)9?e#{wmmay(>OlwAyGK+T7)8FT&Ww-{ zV&NXP*P5H=gM^7RQ%e-b(Z*h-D6jcOw3^|#gNtj*mlhfMfmZJb2SH(yc6TGMcq7_~ zOVPy<)xg)WLj8&^A9D{L9OH@@hZ1Zi4NB_VkU5vGT318S@3nU~_i_ff2GqQ&AJ{}4 z6i=GIpQ6Wvg%cVXDXIBT;0YBkMY&%qXk0Y&jCjyi_Y8V3xQ>b4Top4V5;9|IlG61XNHtQ)7ryyRfFL5f5QYsl|Y^#wIqXuE>FC!ZDI*J_B!L~dv5W16Dhhn$s zh>=r2$fw$KmZPuObLCpcAkTOgIeYHs)Wv%q6X(lW$Qv+VRiVs8%sKZsi>#QE=bU1j zB}lH`lQAt`lf=hNxPo@MEzdwm>4NDCQ~CCewQ&?WH9ut!5q0W1nNtaG+5Fb zHPE=Xe0jNaZF$@ECT+7BoRl;HMNdC)buHI>@Jskx$;NUk-}eH!fnWV5 zOv6I3WUGdp#RiMQqZ=a9+)2*+0`xFX`li**Dc>qJ(fubgOMQu&rm+`5t4xO-^x-hFVrs}^QYk`g?lT^;uiDfL z^-B>T6A~tiH8Et6kr9TlUX#4U3c;zRYV7j%{L^C}uk$#>);y~t16ZM}QA@ZS-DMIs z=L}Ko0YkP^3ALRQz~-;5J)#9^QW}0hFPt@Qu=tItfa1vIloQLu!Ry~~m?GMbDshn{V?79-J&E#1NeuG6cP^72DJaB}i&2;O~W zQ?G-WN>iaaOdB9ou0HSkb=&U4Y$?ayc$+nqpD{B5oWu4Y87xt}&>?lsOZDX^M zqc9e73i3lzfPwJ2^dR!auSUm}eWy8kEa~fv_K<2@-k|0dg|3TGdjqKB+S{o0k=onT z0cX?*&~AsiyuBndP(GACp4h&m~WbaHs5GHFUm85Jnql9wq%*H&M1CZp?$M4 z$t&zxfyT1{$Es?(an-Lb0q3)j`IlEkFq6HSODm{2GQ?x06=Fe=xYO0(YFhb@ z;&m2pwPlP`Pos8oBOY(Is$LlCE?7M}v z%gU*xXH0p>r5!#V^_lp!g?yfVgsb~HYDe7nP9RFzEQ(yWXS(e{p5IH9ALE>Lnd~Jm zhXv7-?R6qxgZj!8W`_Dm6PlG<-)~uL0F2h821{ z1&<8)qZabgw_QtIfddrU$s@d=`n18-N>u+_zdMGUNGdEP1>JnV{MeQV4fgMt@Wq|+ zgv^AxX6rSGyUd5#aeLTTzpvPlBuov#p-?<>R&J}_Yx|rq$|myF!6>S|#jY34VkUG) z+=I3=<^7&fiYZhj;#}II%bSs#YxTYGlrJ%I$l9#q_wurgSVu#=SH_w8L3c#P^f$;g zuB>SqZw%fu;zn-^|HeR_u+`Mmop*~;X+k-xCVHGP>GXv_8_d<*XVST0+);R0{A&>^ zTONRne(m(qK0M?~JmfpGYp9Sfr_%8anUvXnXb?T_c8vKt!pYSTLiMc@$L~+eX0cz( z8a@PM&Z#+H6QOYU`p@G7SNMqnMh2iNH+8AF@Tw*SYWD`8LK5%1A?>>3=R0MZKd+DB z>D}hR(DH1`Z;@8>P&na;i$aW($777f>9FmAm03}XLA2$r20C$K$UOQ@5NqnpD??0- zDsH4I946O47sS{sF7t~&b7paLfOVQ^4jnv@_WgM!V9I`&Ar#+DE7@~Sxjsi2373<7 zkO^Xl=tukbSp_1`oFXro=e9FKRC%y@BC{O9w$jB){S2nEkK+=-dspj7romxcW}?{+ zjdIG7lC9clb!;$$ggDgCd6wq;wI{BuSPN4pR2AVbFDzN6vS>i-p&F@;5$uBELrZW$ z)zZ#LQ|5@NA@TSIimWy-x^m_c{R(+wTgu>dW@EAZriDyIZ48(M${boEboQv-=AP6^ zp;{T3+Q49`sHgy& zi8H+oZW*7L*i*+t8V5B+b&+xK9Ueb85TG3lt=dtbWPvp)57zM*Rv2N{9%u9>qz{^! zoAv$be@dC3HE%o#EQG1yD( zZTz#Um1d%foT!aWOp-^xHYS`a1+zD*Nh$1`jQ3$lPGJ3VGZt%xq8QH$S&MG#*-*RG zgVJgI!%P@^b=8_kP{TMj`$`CfAEd~koGvWH2U<<#puL64LSCWuHo#$CqnlfMRWhsUjotVd&9Z-LWlZ}{4= zim&KZFiiPph2LR;IafLuShBsl=Gx{_R{N$QQC%9eite|#&Up13v&v#Wl#?TFyIbCnv1q zx_(tVfRWaxl}UNT}NIT)?*Jg7L^HZuBCBSS1V#7@n$PBSC(KR zsc|O%OlxWf{Et5W&86#K){#l?_wPTdgJo)WLaz(pH+g?$5G_R)bo}`v6nC42_cc8Q z2cN1a-uP;(Hzs1NF#*V`Z>wj>e*=LqVa;YlI8=tIHXzqe%dZSanO-luPQ`IU8mrbZ zXb*j9>v%AvIw99M_j{^WIJ4iyfR#^3NNBVduQbLf7jTt{*3C>Pe$BfUKBe5`Q5vB2NC=MNCkH%r71e4^H(u_HiD#a zDm;9AZl4-EPX;#JwWaT`-PTzVg5p#2M zmrXl&f0bBa(}5&+%0-z#M-``6DXFC}KqAn5SLBkMHC~UFWuXDaf{%*Ig(G`S7%19)Q)MRzmn%Y{VUV(%6x`Ei8$5Nf)6BGJn<=BIs zVT^X3oG~M1l{x0yB{Jbw2er9B30FFE|Dhk+3P*5;5JDV!tICrV9{>j+Eo_jFO z`JV+P=9CaZ2%MF+sJ22*wDU ze$;^^(t7!+ns$AP7})q8%sfy%WiJEI1rD<0T`+zB$PpJ{caUeAW zZXn3?de(w-pK)u)Z#3xa*UNA=TLe6ot6~Uh{`x!ib!AM;j(GB`GpsfQ5NtxL`7ppZ zj16?9s=cmsv|pyUit07mB#n=iDxgX&HL(s(WFzPMJyq$gI=dyp+D~za-i!|Z@qsTW zMl8^t+*v26qC{HDPYUz!^RJNdZJKz)%Jd`SW7Ma7~JU+F}!X(95iA_OAjQLGx#Y^j`l{7f=___4*z zBGQp&zsBt9mHyWY@B=X4Pqf8_t%w zfPuOmT4I8v9vfyVjnqZ+!llbuRIh?kAU_!P`?Kw<{J<%n$4hQ${@Rm26tOi@eST7H z6ow8#cTWXjgr-oa>RSVVst~KOfA?n}f3gZCeKVRKuzvvF=?V+5aWcCM4I zPqrRH9C5VoZkOP6G0Mo`Ys>4$ybK0D7tK@kgm?vG(!R;o8C25*fT|tm_-vkS46-9c zf<{G>#_U-YCYh=e`Eycyt3NnnQEK+g&wpt#uZp9#{*2P zLv_gFe1ITtbn5nYksiIJeHth6#ty@$GH`xA55{q<=o=_~qtQ-?ocgh0x=K!Th$|f% zM(8L^jj;QVnGW=ky25g2!VFw&Ibn$xe`rBo466=U=g!K_RVvc!nw_Pz5#%?1N}90( zZN*nf=ysX1<}ioAn#^^ik+KrTjX)Oo%3j_21_tCKpelWR{>jR!4g*k~kbQnKPI>tI$+ji^9-!VH zVd#EO6ODr;b!6(lj=>Vd_>9(Cl9)RYAwUz4U`Y1XtRN|A8N~WDx!U<%> zztz}P?QeM#>%Wu zjk%7EBdVDY8dB}kH7Ft+^a$Yolg3b%1DZ(C**_ubWv{l^qj^t3X$jjkiU*t<$N>pX zP+JoXNEOb!&`K*lSOJH2{3fIR)!PCESECitCgjL=omr_Z(s)=eN$_qN04&x{?~gmR zgQoj+az@#;CSmrEe2+)P4iVWZm33t}jYEw(J`*@QT!=%A$Kv?#@#> z;DYd-Q}MJjQ;Is{cdp)Ap1&w06hQaEIzXgtkCLzYyB~rizn6SOxaqhQ9qP(CnF^gg=iwMuVRM%&D}m+)@6PmiXkYP zf*)#SXZL3B2D-a0GrQ&6T>K`tzh5OjKHkd9i?rZ&_sL-|!yO?2E;;Xt%(x1t%b4=1 z!w8819iQ3@eK>2%j06k24}$U$Q2KuQG^3!iKeiLPKkl73&kNcM?i-Q&UY;l!raG~n z3Jx8zuA1Qj9U{Gl>thynslLJjCv#PQ7_WnfHylZWV}&c#F+GN#wv2X4$B4Y^>tM+k zlOL!X5u2Ggr7N@JgzaxC4SoBTjq|}q68Z#VpXcku{ch_t`xajL!{Cm%xHw8Wy8e?B zVT1RiAi9AXA$6FQi)Lp$^Zn$aM`H=+@_`l`E2HSLXl^NIz08;?~u1-(A zfqaAHR)Ra@4IGwd1P0iBTAK0<`3kdmXdfNt54Z&&x5b{f_Y)|!24Kdhjll+=zLB@<$zP}k9s2*3g^0Rf7>~N%Qu(DoD?&F`ItPl^~(aa{2auH(fpXY3Rkc$~cYT-(LMq^zd9M4tnLN9G=*|>BA6g zf$1Lg8oDcXvH525IZE5$L4~4ZUWpSmFb43VjLghWe;V&&O3J`%Y-*#Yr;W69bXL<% zprKAV0^d!RTk&Cp5Ih>e~Xm7XXlbvx1 z%BQ-$q-au&#qP+brw0jxOS?mXfa(0;yTJ*;5a z#2~)6E;*6+oKywtDyOVG7O_ba5)?3zM(PN~c7WcrHVb5_(`Q&_LU?zUzwHE>LHLt~?23IR&Icn^0zl_(FRGFcha#U@>a>=LD&906Jl*GKAM5uE0KMq9f^C%4-wC+&M)d7GyH%5-*i_L{b~_>Vh&QtPa# z$*fe)U(D$p%;$3liNOfI{-ZKM*T)k#jJ*2{S%`lL-D3gm7zHS^J8+iUW!o0lk75h^ z{F%6CH`Y_2R4UHp`X=?!0`bcK@T9+|p ztx4WuMUV$AumV~VLshhsFm%73R=nSF@J{AiO zZ(8&NWjvesyB*1({qrCK%e$jY01)qX$L?_DZnt!m&e2s>RS!youS%N(E`@@wn}TT& z1wR4}+t}D3FTwB54;TISS7??l(A|DEhaw&re3=;>v$f@PbI1S}ga)1(-JDv&MS>2( z8Bk}Wg72g|F8cXbPiHI#BXB4HPcq>m>bdbXZ@h%QBgXOuIfy9%OFr<1^6L=hn-n65 zdD_L{p^(db_fZ|pH^A|jK5vg>2rCX9qy1oir0g42{ke@Qje1q;ycZnSFV+q z!|;0V-MoaNi%}_HUTkVHf#Al8%|#P28pMVS7{vNHpeJlT;|1w%d-M^O_E!t59{1FbJ57&5{^U4({|%o)S|-;s=uiZ(?*&t;1O>ZSCG* z8KsZA80&F1kAEEUd#m(ue&^?&cnulP#RhwthIk^$3IEnxn|BO1A*{5~0FRI?+`~BF zasZg;jVUsyFbIh)1|vURQnPJ2a@hcH{>uE9PD^B(fTMLmnUBv*n<_|iIL)3Hw z0|N)39D*zgMFS28F?xoe3#KY)dn|}+HURuHHtKnDGEI?!g84N*w9Nb;+_X=wd)y0?U7NC<6cl4T(r=l+J zm3*thwxTrGOf=)gi;LT74v1U#`n{%uuiKM&;?p0ErgNKW5Z0X=%)CH(O*8H- z(@YmMW-;^h=7$UYna{*E3BD?R55eN+b)f;j-^ws7a_Js)Uy`H>V6fd=>ui;e&)TU*<1U!m+iP!58k{m)`M zg3myEDIs-@_tO5gx6Vt>GY#GSs8^gEbHvRuZ$*Hv{CBo~)d4kprnwNC4%F78AtzN#Q ziY=BWmam6~e<*V_Z0~&0Xy4rkx|2ahi~90Egk8`|=h!sUoUe$8U#0|EIE;R+D<0QJ}GwF2C)$GJRL|HO4| z0U%beVl@3WMAhwQ)ImEYWo%Mf*T;3AljT zj*i7MO7PkGvzKEe&qnGF7WRWE5N->A?ZM?(F#Xci_ojnN_duMbivh8}Tu6vm_tIWY zI}9tN>8-~{Xc3Z?*Owtu%#NgKeCumu{gt!!+X>8I~WH!O_@0q0B^*;3kssouwR)d zQ3H*WV9H?0BVFg4efFpUE|%JFtFMf4tWHpQJkt+?J>aYEuwVT7*`4d&5tA$Cz6v(< z#m$CXlATaY@a;^nYc6Y4c#4N!jpa(#TWr)@K1np;svY2gMHcy8;TRRoL5~Mpo_jjx z#0)0kI0`rBRMAK3FeP{XWdB^p^U;hKvUh%b9de=h2E7{^s;sBQ0BELPlH1-ijDsQ^!0L%3O@{5E6jYMcD?EM_Keg zm-$dxwPJQg{k1?Y2`CF~SKAc`zTN5wkRL8CE{tiz2-0!=nS}U8-it*n_D$W#1-l(6{ z?T4OX8LgXnuu)i=q9)4HtsBfdkUmn20QnJ2JI1c`HW`H8&6-QZ!3uvHlfc)XyATHq zCh)(DcIKlH9=kQ|lG97S44H9nLsS$NZN5Y^RgV#*!|nBXcnD*`*c#v#!~u{1A(t#m_GIrTBm+=1oYBftE)EiLPRqQ{sc*G3Ruf@n#dR45V*f%0CE=`&&uvt zu;;wV)!%$G`2k*$;j_c#?jMcgZ_KpO&iDGQ(TF-c4s7Rr2xYx-idx&<7X}E@7z$zG zuND>wjEn$~aG8$;&6}853FSx?b0N9vMNmGbD$gX)d0ZTX9mT##-pBDYF=!h(E$u3t z5wysk%eF>Yn!`m9H2<6ndA1h%SiVf}z<{d2d#IV2VmlN8g!C$=1w=(7ug~{O4BmU? z`R=Dz?Oe+Cg| z${hU^TO^S#ez)^W8LjdGbeqFBO_eoH$U@v&V4<#@xP>KNM&Oll34r3&nsOip%Ax{J zFMM;8lthh3ZeiG{X>E-KDiC9~7IU_ijhkDQ>$h9rj6eagX!j#)t?I4g0T-<}4-!Os z@*u%I00rnu!SM6oBnJ4!pewv^yA>bM=M~dG%JFCiw`K`X3T4HF!uD+{eiTi9qb+QI z#*(d7VybNJ_-rjQfBFKwB->An|WyAXS=*p(JuL|COZLN7(64&ps z{^Fp$$=`16Nuz_Nj~*$A=JsD6Z-5aZ@JdtO6`0+J>S~M)kSKnBdQrXi`nG&##~0+# zj+3|iD?65ONwfv=5@@xOkrAkg*9z{o3JzAH7*zND821z6A-eg>Q7JU^_#G5I zJ4nR%YB&40H3OZMPFRLq)Qf>H$g0~j6eTNHZ5f^)EczRLsQTloG32HY&ali%9OK%p z{)*w%MG>guYg}n^-nmwPot+wc{7e#!?QUn^=VvMB19LelCRFNlV%qsgR;;NJ8qnH0 z6^|$Ul*}qR6r8)5@DxOJmEXiTqx*9qr~Ny}qR-!G+=R+?iVX;3Kuw0xvoQo5D9lR$ z4F>4mfIb1z?q$H;IC8vMWn}QpU@&0O5FQ%IAFzTWpiT15Nimfb;O$^gB%stZZO66y zx!a+F$u1i^4kyXcli_Rkj45Q;V=|4qh$@ACmT0^FV@8I0vxc+f?l8;CfL@S~U2RJ)8(>{7u7)K&<9dd9K$F4Vx05y|R$ zJ1ulWx5_`y?%XekW8$F4G8M&F0md`pYJ1w6*t7&hc0r~QVz;Hlm77bz^x|?E_*@}c zd0a$6ovB|vqhDzZzRpP-o2!~!2EE%C*&1DYg-4ZMG9<>rJ5H&;bH<+g7p^BQs*TQq zlK`NpnxzQ)%_Ln89pW@b?a{_DIHUJ#$VxngjQ#KN5jD`^BLlLx|8zV)Zlf}Dtt~vZ zrWYUO%;1)=N*t+eoh3+pC4ye#W+s^GVyg6HRJG<_nKKzfKutTb9mmSX#QRv(gL32Y z>FugeC83tN!xsc+1}V=-Z_c5Z)rW4rKMB+W%F7k?Nl7!0Df4~N)>pX5Zi&pWk=p^+LU_m}(ZTl2(Z zs;Of>IGd;OJuF6ll;LsgfGy_c+y0;@_~rrOeB(Tqa&a}kACI4om-Ll*M?1Q{EL_m1 z)$*hzQYCX$dC-rnJ^u|S=m_F$GwqqC5mS1C;D;DL|2-J<=jTh5)+#juhFlUO>(y%a zoZL?|2O&hP*3HYxd^G z)2^^~`)bb7F!>y7pO{6%fUr#YQAUJcJAPq1Hd}zJ(L!KTz5;0wLC9IYplpRP(ie0G zs6^7Y$+NtCgaZk@EYiUG*NBKR5wzBa%HCQ9j;1N_i7_C?BJ<#rlObU_y9Oj{wpF6+ zh6~H8qP57pYy6(NIQ9ZP!|V@z&|}=F+OS?1|6++3wua0S5d+X9I}Y z8mW4GVux{-zUi_XV;mm0t%<%C1Cym&kCoE$cF8j?eEbpzt((rt4|+;}Q)8@Lu$-dUfSp^ktTEB^{4!{%0=)ed$ zNoj9(pP=#Z&oF5qXYv!Qto8%?dPhNM2!HMN&k4Qvx4kxxnsup>^dKq9X;2>O-Z-2ATVUK8O4Fr?{_oVZCfcuAf&!!jFz26v|;Ib9w*m}Jkx zYc%0J*BtN?v-3m~uWWm+^3~=^&|aV1*phQIXl)`umOH>%M*DyaqFXyi9sC!jX@lVDKdH9USo#(Q09xSi+Z>L1C$Mj9W$Nljti}$rT zR_LNbDnt58%eNZ^5w*aUMJ9R}ds^Bd3!ZksLb(^Z%1PkjR^X|iFe2GK{&zO9aL4cDAZ7NJ zM6KZRY1-c>&pCQo3D6Dv3hL~B;I+Dl6CAg)z=`z$oLc;}Eb%+kXB-Lt z?ijPPbfIJ4ONxg&5tB);njnaP62XjV|2@z9GilszL)SGBaY(OB?wgw(Mf$JbGf4Z^ z#EWcCn$T;atV=bnthY!DS&40jHjJc$+Q@P&T2@bFgeCCv7LRpo7cR7|=6XT%)~1&b za8m8WR;t}IU8g|==GQN9RmMOsusnsFh{i0AT4V4nR8cI_4bC_>Smii)%v0cLzbhs2 zJvBPlQ%Z9it4|9zPTjR@DzHECEls``ABX^`I%0ntVJKRw7@QpIjyV!#|FSrU6PU$8 zhq)c9ep$GZ^Nk?-hYw%7k=!jLGGuJR7AgKbME)3s4|ecd1E;~aEGy%E0$PA+5tQO) zN-tN{m8mJgRmP8l%Z}9j6#Wy$a_7l}nltKfL5f(*h-WPkU`Y~X1P*&sE!>z8N0qOb zgl8B|-cK}1?V6Eq~1CGxstve|20=njoaIIP!n5W zlE;Fjjjqsi;KTv?w`y)J5GM$A=;buUW5<7)qL3g?SPim(^tbsr5qLNONf(YH(2)T~ zi%dwsBgKx`ycam(s<`OX20A#P)gU`(`d%Kf0om1JW?sjazqn|4To108wt$?Mm$>ic zBDQk=ZvJ}8)k2>XlWBGku`clkCKa?kj?Y|h0&eTF|2uho)o_|iBd#Bu{$0?5) z3a}EW#(=a1u)gxwvuGkG;{WvmoDl1Q)~LXWX)aKa0g1`Eff`1LVRp6}!HxzIv1m^I ziL0#@aH3B(?abwO^?raJ!9|g#|L@4IzoQD(;E|K!{~Hi7I+KR)F~Yijn5x6d? zQ+h+-SyTrG0)>EIet;t51RS&ZW3DP187#MBRWhU?(v6_dS9*~=YuET5@ox;eg*!aI zv)xBtj=4~JcQMd#R$kuYNlS{2wmB*Jj_)yOjN+6IMlLn$^KkaZB*xSJ=0rAAz0WTk zvn?X*Nn6UF&KVS;Ar@QQRmX$L6vkcy$T(h9|BLrguGTU9kG0lrR$oSPfR!zUWlFqC z9$i$G?fke;_wt(hpKfEjq?-ZG#_E6E+Ufp1C$;_kQ^~`JI>9~W)idE(b(Z#^+Zrr3 zcXb<;%qDHxwVB&1owVJ8<~FdaDvh~k@2O?jzln-Wrl*Utl@g%wo-)K6HAc%h z;L__!6cV1R=*3O)BZH<+YVeSUJGmKc@o0{ewHY84e-ckZCeufvR~taEXv+8h{sM)R z(XZ$cH0|5w|7gOl4~UF7|8{aK(Yz5EG`&qQK^6u>&ul^UV`@6Pm^|YB__bVckomNt zxOA;6&6byBmhiQvJ^rLZX1FpNF%}TpQ3FM8hT8~{hr#Lp#k|2;@1^sF;DWtB_0_CV zt6UF$sSEMW5%ZcG;9crZ%_ijWC8oVYk4Fx?V#G9~BrqscDL}q=^#&~rLU5F{@{aQx z^~*5!+JYaBE^0p1BehBz>FRO6a49^ABrF_OKD_AMc)fHyn7x$!eC)OV##aw@&DZ-l zlw&{Z3!YbhxeWT<^lND2_}9_nH+9{ntl5fU8Lstpkm+x<*;7~N)>4XTswJSZb@i{_ z`|cX$yP0~jyEbo{(Xb-Uv(xIfhn$b98X~-mlo|4HA^}FIhr}dY^;!<7HKs2WpWhk;wYsJ55LUFyk5(Vs+)6}T>f}I67C#P{OOmnO!P4}6O3>* z+}&oC7K~AhF6ZZYm-1M6TXr0=BBm!i!Zu6(Se#wSD$~Vh??<}0m4nwKgQux)0#koI zYv~IU&C`jh)LdP2dSh^J`_#{r^136*n$k3*e|eb^s6AQlhL4V(H9xL3eFLo)qkAHC z*`fR5g&5@a_I9?BPUq>)wQR@!TC3Z`IIOpZ7m{hiK$22_Yj6@Tt;m&IqF=fEM(E9R zwDNVbFL)0A!|O+{9vuAnq>}H)rB<};apD-sZIY3d=Sn|x)+-;(SIn!8Tk;Y&?czzV zCvEw31N*}(8PL!L#yOOsh{*(-jd}MjjLJ)tBZ|IVD(%$$u5W zYP_xYTKN)G!_6wclNN5e(Hv$lOdLB1Wedv{wKi z&|l9aw)1t1f(b_&4=pkcMb#uTIr4_BAJM>{=Z&m~O7C|_(M7Uj5J+}?S0uSzl;xc8 zu#@_@{eT^~Rdk+a6#HOe!hONoj;Fpq2RcJtQ($bs+nDsxY!Vb#Z8JAL#ZJzBidQsF zHXM zN8RsteWbSXmQqSAdvng(@kMyFaX-|Wk}l98)Jm)1T5c{0YzU^HuOPWj8D3KbNZs(- zJRcZ1`?j#Kpl`#1aKX2mWLrBsar}Qwy>5t1cN$4tMUXvKdLrJ<k6{MNx96N{2<1t9_x27%hvnl0G3m(-SYj4Hw%2cbtZY5%b!yc zkw_tXN8bXe&P8lZFZ_fktv}fmHneZ64Y(?+fyH{Jx zV7DvUWJtQH$CHqPbLr&zlyS+Fnt??6Brl+?A|&}%PpI&_ndvTfHG-|WBFqb9tt^EvTBD-{C)DIHTncOWupATHjK3##1eYS2jARqOJgX&LpoLY%b&LaM54LT!G zTeIL-U6~zHjv2FG_x&+Uw34;$wy%RnHk+b{ABO&ZRPuI#LdFY&KP-W4Nh&Oczqc4t zxH|}}2c2JKH#1mjWOiXM%hn%_swpnsQ58tNuiIPq6ik7ld5**J0cOeW;i5_2l=)WC z-xoG-UjDl$!fnS=kzzf>wJ}~`nv8$6=e9Ncv@G}CpWotAyy(4qO$~9my~g$Hfyg5X zPVC>lnOt<%^CTwQOtH{k6ZzzumK9qN45L=a0tIo=piH?UCHh>}ZeJUk%q60iB%f7_@{Bsmc|QuY6016u+>3 z(fO3xipcX7`6Xr8qwUs1yGGuXry5W)!VPb;@zu!mo0bB3bmaTECf3Vr%z7?Ot8mpo zb;*w3;F7;k&VOz+?HB8==V=zW%vE6N`qY1O*)yeL8T?CFJ!dM$KJLlAl>CgP=JQCX zyX7^m`sUue$BMmn6*OI!q(FNts2a|Vd^z+b+GH9rAzyp{kn|e&7cWjM%i-NgURZeb z^$Kak92n3$pG2LWo>pBiTpew+tFozxCR_}U2LMDf)R0FZPt#+XTQ#~^y@HFAI2gFh zpt9enhwPn8{??$Z&J%zM9@-O zczEa`o7Mf|T3vP6>8UTA)y1n&!{p!-dRGwKkBsV9Yj77P#vQBP^2x9f8mkUeDU4^> zW_VylgQQULiWQdsSo0y;-^K8uR4L74| zRZ+68FeO6vw2fuAks}mjCFEEn^?%LrDEA_wF`9Qwg04qLN5`f+qd7d(wwv&|3YuGW zWmnYU3@4fiy$uIBK68APP`$b!pGE=A?IZe5K9yKZR%~P%iGGfIA&Pfg-hqBhwIF@a zg3P4iu7H5RkKSG5N&Wmq{v3rJ}xy5*L+M zTy75bxTJYJf?2S}erf^KE1!$UG#-|tE7U!UNBjG)DJv@@uB}%S^={iBT_nF)EH_}} zlMRy6+t)rldxg52e-#!%2T6Is|H`!c*B?0leH31qhT7Y;cT&oB;(-oyIrd@&?fChxnsTx3iGd-vBc` z3go%KKLA>a4jtUq#ubYUXfHAz7ii5oy#-DMe0Q065rki)3I<=Sw#5QN>$tt3O6Pa{ z61-!P;(s5CP;11_iGcfR&0qE8I~=^Qy*x~BnT1@rzeXG}cj2kzaVnL(lk&SBO{Kdo zy=ZKuhQU_XDxr{mBZpYc#QYl+n~Hn6v9p^38Et%*8|3@4nc$>Nh5|i(_{S<9qc(Sh zGBC2Kac7(HFm@-cwyh{FZRzNceex)~JqlL1AZ|2?WOTYe#e`6tQj`+jRSoY9P_@Qt z78Mn}!C-(j@;4oi^_J{yX_5ZiIN3btab74#m)ZDkP>(4?_ee&zI9rI+$+vP{d}Ulj zT`vLB|6H6R!o2DF;x5tm#{R%c5-#s4(ysbGZq;f|F7)E-syoUIpM@oSRuCD$$>dyFmidcH>2*7Ka@4CH3Mmn})m6^?l>04>9n>6M{YYrOcj1BJCHyyj@;d zX>&0G;~12A$J%$Ap`1F!4)foy!+?~G!-Z6@w`x_yDs}bsutd7Q#Ylyh!0@tlg}=wN zRP*BL<^9qyimAGmJ)dUw@y|L?t3GmGKvB(NOGnSJrW4?$V>An6zh18^Tg&{Y!*P-R zdv{o3yj)e~)|$YWm6;jHBnnD9@h`|IW<9!CKe5E4x;r@Hz2o%OwKZh2*|^vslPQoH zU9#jwwmwQ`l)qP1WcvMi@AlI2a#nqP%KZHN<{>2o1=Woktxh$(Ok_xX`1zhH5f+Zq z+Ax`lO6vbTE&Ip&1J(nA-{u`vyXh*m8QZmG!!VZE_Ea+Nj=U32Do!Zs2wzl~`$^sP z`a=2vL91UJvGEJbQ@anZh+MhA67CtElJK(>Gc52+hhnyVO1KH*1l{vyl^NBaZ4Wqk zl#mIH>Kz+QkoC)wK2!FdBHLw>f4l@Dmgz)5U7Rin@ay*)%+ z5AqmkhZBea00(QtZnhR*W?>WWlu3%mL${Yogc8{@ir$UYXh&LCW?M>9wVfk!35%>p z3~@?jrd-pE6OQNAwl=@z&v4mG=;t3IXKi6T;7KA1wJNB}4e~w$1ka z2iXCintq(3PojoE>j139Gk$A?Vn<*-O-`5>)Ay6ORq}MIMn*V9Qq9o zLtSqcc$iRZd7I@vR6#N*{p`=~2{S&y*nygbsJn)gy}O&@ltZ?UI4KnuH>Qq&IZn#R zAT^;R!~-RmixH?p+po4?)Q_(ue3-2wKy|TZLa6VQ3T@GdKFSUt>)mei58FMBn9Gd4 zmC_UR*z&x0aJ~gm1?TNfQb9r0!e{sZF%z}hMB}yFO5QK2eYWsuSDfV&z1WitYBbyr z&pbmum|!*CB+myNK)TP-lyl<0(GZHJF_*RQP%G}y`?6;=6K*-P4Mw`xjGj~V82M#? zufnJI`m5IX7_TN;E*&kJQPRC27m#uhXfTR9M| z62f{eRT6_uvA6(d<;-XDwCZb?c}6l~9?OLJ=6Cp9-y7wb7Ljx-YH;%8JfceS_D(pu zb@Thu6MX^(#Uc933bWm2KAF)>0-hJ!`3iKDeifP@x=OtM>%&L~EzH;+_O+Xp;`41?Qwb}fN z_X}lBS=`pu4fB5yUL$)vSU%nfG^Q%5cO)cwK$ZybXP1>Qi&A+w;jr>h{yt{vOqr)q zD$rbvZK_MrVsipNOrYlF1pcz2|C7A$^I~DnA1;dzF(*tOS5;HBNqctD3a4run@p#ODN8Snwt+dEVhk%!Gvt2O zl_s_9*x4VoibaF*>=vxOPpPZ}GSkyU)HzbjU)bGXP3sioPF0D|8xz(|Pr85iQ!5qK zD|4(k=5fN$-Fp-Sa_!-y(FfEC$;LXA7AeMEdhwlz*D=2(E6zqJ%v|qTgFknk58~5OgUi@`$RFEbLgiM4I>r!Angn3Bs zw<;$W6ux>Q@9_Is0~91O7w-rPcED)Sgo*jq^6QtXc(2hqq1ona81LrS+ee_aoL;Y) z!Z&s3n;XbD6_k*W;NtCdSotLut7H!Qxy<8?7U&Pe)ct7ki<%$9%ng2T6)Fte zKcV1l63&@uQe2IWmsy>EiH@g-q?{Z(E+xDGlwF?rBhEvgvLe&*YfHy;nJ$m|Lnn+g#WCH1;Lk)Af6@?+M;2{u6ur7Zmj_R8m; zp87as$cuXO4unYd$JFpk@myoygZV**SzFMTk7+sV{`=>+)W-;B6ac*%P7haCzbFsa zyYT|lz5ps!s6mL24j&(XxY4MC+<9bt2fjAJ+UZ>(Mlr8B!&E zk^y;#K~P=tfC(x<>OH3*&4Lc-?*Z$boHS1NJ+uO&hx=T(Flgx-4i-|@rkXP>(mjGe z(_}c*x#t7*Jx(cbti~Q0y`2__5$DHCqXY@Be_$H=ktXH_s2-IvrXk>H)Y=)BuJpnW ztU=cFY5L}|iEmRK-({~HUb|QG;^oVzz`(%$ zS=o9w47eZC{T11(%-H%1v}Y7Q$b?J^vok4POS|QMTXDi^r^!vgE$QsT_9jzlBm?t~ zzj6!v*Au&lmHTm^DOI+F#^wG+Y5hd#3P1bplb$iEOYD-Lolc#3K`i3k`1scp^jHcJ zG&30|6@FjlBBg#FAB%$x#uOG9*H@ddh4}=N1y0z3%_n2cJzki`E`eV0c90-zD1qY0 zVmYkX zvOVMM6tlfxT@vW$W{-8LF&YcDsi~F2Z)z|fB-XrlP)^1 zcLxUte0z55o0ohwvT)YR(3soY3L&?d2o{kyTyM`l18koH|*D8AZ2L{@q5FjxI z9kBemBIy^=3iNo0i$_I8g-=Wj4g;_-gE-F{=OW>fz2DIo(0l2y#05ZoC`cIu`(*s{ zOJsY%Hgli}2F#fy#_ZX%H!yY*w@;6nocveHYfVPG`pt58y5y{v-a9}njJf}S$3`r0 zKDRW@)SGOelCLOpSXea-fSC>dt96ILcerB;h%7#P&2v>7_`fN;JBwFALKLl^#&*4u z?GEu%BO)A2p4mA$$HLdf1*WDNv`S01vr{=;@90@iMVq(^T$K7Hx2%6}!KY2%vO*t~;m z0H{peZEZO4UJzyPMZ$K^#-AC--!kqyrn&!rEx_iY-zg%DjnxEpy!1V1oYJ}bE68l~ zhd{3>RjXhDV*J^!kUA0onLvS7C>g7o!)(VT;`U5K9;d?{t4Y5zANU`@Mu|@WMg@NY z94NshekZHIuWs6(_B1nQ^a_ZH0dh>5laqr~{gDy9pG~Kttru@wqm-Y&G7)tprr)1Y zpZv2he(j{5zSWhczm~^aYQI}TkaDc^;GX6PjgilTOkfE@0jt66N150!EX(dRZG3QN>sRw0TdHCXysa3W zt{1&jt1@7?M`tISVM1VmTI!9S6A`>AN;sZqMl~FvDw?(c&Y7Km|B9{4kjd_C8uLL7 zp!LIyAR3h}(|tD8H0^QLnKGNg|Ftv`h+U3k(xATI7Y^qe92BTxUWjkH6HQBhGb zBSMC5^MXGBpuwX8Eg>%Axr!87lU0iAO6+PGl0EBVHP}EvsHm&s%3Qq%CXmzXP5LOu zlS3Eey)sz3JV|CrQV9YjhuX zJpJ-sYqOv&Zb-Q9EPh-%J*>))q@0pB3AP>6)#l?y*^bc$;%?1V)fKBj?h#+<$WnLp z`le@2Z%NvcPrfEQ95l<$$>6A-6A_81*f>!tM<3>{hBWuCFZBkW9#>xT`I&EJR~H!J zOA;~XEN)qj4D)oxC_gaIzNH2GQxX`_B2`%0A$9=J2k9$`NTCFqEm9ys9dpm|&&66p z9|3}15JGvyE^iz8;k z@vq1-alHAQ7hQo0Nju*iRigO=-NH_5l;M*2`1ywa4JzRKNy z`Khh`jAdCN(K910g@Ewf_c;U7w>*h`QY{N9PbOb%t?zim65dbW|5xhzZhe0g?p8?8 zGuIP|cmRk49MfizzG+H%;I#!JYSTsV>!`~6t8taR@_S`y(RN)aKAXZTOv?hL8ZFTs z z8!< zrXTp7_ei6@&$ILL^0{r%I|L&2R@{-O;@HUPo@12WS=_I%a%l*MPq?{_=J{dew!wCyB6_{Ct7pR^`T710kku*p z$qV&=`cH|oF7DgTP9?k`gg{_9KXD!_fjhAE`*$UXX@V^YtOJ6kL(c-}KDd0M|zSM{5<{d-YTEqgB?& z-%E}Op_{@2eoHM)w6mgDvK#4#e%CYs`mi=pp8)^C;LajV!XcMh-$UntS0zLj{J(`d zvh9#QT3YW?%L86&%(aDYQ-ZQxu*@ddGw|IC2Gso!)s1uMGUd4&ocJCVmn^a=-RS9PnPLUwOr*npQOas z{k)*A1*dAZ>fQzv9~2D8yxAH+0Gm!n#Ig``1nmyuf+C@pRN+Z@dUkrUv%8A~^4X2+ zN*Q-G_6^`PpZps`^0oe`pY5o(XK#Luf}Dx)tXO1Ux{HVuXKMF*1mb%#{tHlq{8M~`Xr+YD&BTx)3dcb&pT2#V*b6U1!iZ8m0HpDKcS?Kn1 zqT-J0q0h#%jL*4VeNwAWSN+X*TRz5D`Tow_zcU(QSCgd8ptx6$);SiPbAFgzGq9(} zMe)=C5&1m%V0ktc0JA0*q|m8Ax&urB&%M1<0h|EIb$hEJbvQm585x|brEVBw5?WE& z9P~6q)a@PXEWw26k4xa7O`sZ>=}@A@0fid;yC{b-z+dg{d4tS=RSY+~zzBH-#3Up_ zwr=~IW?+TJ`ueX{XbM1WWHF^J-$zHDVc;edu-pgZ;<8Ydx*@;&wN(za!r3}wQuNJqxKZ3 zev)k1=Kh_UYY{e-6Un!3Mpu!MUIzrz;_J6({J8_m`3}!=rm;n-y_kJ%sRM7KSAXsJ zROd|9t4&5Ot!W+VIg2_}oS%h~C_e!ZXVLzFT?XIwCS#Om* z!%!J9=K#ZovB!LzgZ^k!lVq&suNQX-n|ghx>9JUwZ_?BdemrGd(@Iup3Nv)0AMtkU z3uQ_(PSY3Juk$*>Z@lg0pj|&}crZe(rDKrLA@?B0Ql=^>>bb@iYuS6d!*3 zqK1e4k5!EX69zYhNGUrz3k){>Z6JGjGu$dPG@=JRf+p;r=Rgs)2a^IRi#Yi|`<{4y zHYQ-%^-O~{v~OsrYkA;9ioT!oeYZGlpgd+OGETT4jK(a=mI@!q_k&ps^245v2`NO< z$rUiTC&HQE;*TqSvNMn>?hy?Y2GlZ2>_FvU!7Kwa9npYbQd(MGb906vPw;9T%q?_2 zCoYnt$CElUXUEjjWSc$B*!ELqoFUXZhB)Nge&@(g}`^%1ng zLQa>*>`rPGcw0FDm|Z5102gR^l`r|22_7`&EdN7gXHpd zEFJGOU!crmHD$U{(4bGLoS$^Et5XhvSDp~)>FXoGPBix%-@rzD{``3|4%yUR?aMiQ z;5?vgW95+}McUI-)G;<3l9b?23^#fSgFfYWwB+O_d;kQzXxN_(%N?*v_u9Be=e2eR zK(2f%nAXTB9HDpV^&xMcfa z(E4BngF3}BgpD{h;WLb|n`S6{?B{<<_LSHu@;|u$S$fGIXom&!fzhw;Hp4d=3rZvK zS(NV9uz}Ud?0vrytK7fFemuwiUF$lA$Vlp^de#B0@&>FnAJo$Q&GkYS?cLNhP(RJ6 zWQZcwB6H;Slto>=^>$o7%tYklDohYsa_(3>t|>-mg`49&ChoSmcRpg>h6C?@(c!^C^FGCY{qzBknKU~Im&j(-~A0Ho3_1(F97q6wt zdPv0U9~TnB*gl{x)dNa#s9VD@+-pC5{v1#r*(!bJgzl)G=P*joSIt@slxU&aZ zibiA72X8IQXt+yrx?Q%?zC8nN=NHgwX?@b-kanPj51O8y&es8`64Hx)R$@nHnf`uF z_qC<1yC+UNHw}j_TpQ3YMa*REUojS{PVAg*i4%+B_fCv3{Z`QXHq%Gxa2ccQ>O zEGitPWPB@^$h5aXuKBe>=4Ix3u%i(80LtA%1XI&>S@?0|XX-sNlkqDRJUx^*qCi<-$`V+RMP_X_>HCaB0iHU))1Ngg3{-fz{PokO+WH(_hCdlwQ z(D;|juNy(;ttX_$LdouU{V`=PP?7^OnK=7R!Oi3sSVZ4FBvf<8F7%5CX4cn~#(o3` z=*kKbg$nB%vZF>SB^AYq3kJ0p!;GpL8i-q9!h=^bIXM|WAw7%t8FK{HQ@r;!{N50? z?R-uJ%0CM97H|J!2PdATdX_~5|< znCbzNO|Elex{e8#e>%YrIv;UfVwLP(KDwK-3HCMGUE?n@Gp7=kylBoQl{BrR_IH_S zZ(B*}HrvPgp6-1Y?AbI{6`^$M_7;ME^*-k6lc$Kfa}rp33d`N%CvooDcb7 zFo1-msa4uY%qC~&>>9TxzCvl5Ah5o1{6nnjk1e-K-qL-Lb!$hPDFQh{q;X=D!3m06 zE(&NS&4{i}46=kws)H(O$VDdSTAO^gbt^-iabc zmI}BrON}h(p}c1MN*_-2(ZG>{LA`8!dPkL)kip=!jbaO>{c6pB-_W*4RcGgemKiPlPx{ROEs z5e<|-YKmN}rAk-M`~0IgK%w1-C*zPE&&vn9@R$A`5pDeEVr7(e4jdZ(4+P2kP>Q2f zba#jY0K`=p_!GjKZtCFh9)2t=d;$Uur8^=b!iB*_c?^#Pto z4@X%&RSj$#uln?gWz~S0)tqfm$$321D{pGRJ>h@NDe*NxOgji5Q3~*&yG`!huxLaj zCr83`mTyQ(V>anhwQdsg5tH@W!M*h;u6R>}Q84{Tgqe>V|A`2du;U{WXq##^0Jz75z-7#WzvJ6r9TiNapsp=F-k6 z04tttTFxC-jn;a5^UG*v4)wC{@rCvylDWG#wUjx5Oaw~pffs4n-d3c8?X0cqx*u1n z(*D1BMZ2@zjLwK_z*)kGVmOqCwuB@h*ljbOM(!&&UdO($lK@}wj~I1HL{mREH)ke& zEkUd0O9C?<>ALfwRw%tXZ0oGGZ=`H)V5{%E+%9nx3tIZR^#S4K-9i7rUNOg2&*$B^jH z8oB7-^WNuE!sFIJ#6bWLmNcJ=0v@RxOjRl_&9u;42HxBcv+L&YU0JYYw|gAu3HN zS}Y12`?z9Fi~eS%;=-z;IxULkr8X&^Rc-SFeh=J4*`DNNg{;<@bw|VX011k5q@BV^)pEtZ_;%hWqxvwId3rq#Esyy$nC}N?6tJ z*9tw&`OThk$!9bqn7Pkmp9wkWgCh}Cp{zZx0?$+7ODPROY#X1dr-JKaiRRZsmZoA> zy4=nuonu=Q8XQZfb9Fq>+=Hi|`So^)sx=Meh*;~2lc>PQsrwm8%qs^XNC6o{{a zE%8yi5acNkzgx~l{M0sd1_U*ePKB%J?3qsO^mh3pX4F9U&fe19m5jM8h5nb-DH~77 z{GPABj?V4X7TYRi@-zWe5l7rJVuTia5*&5@!9-Zo7~{S@NtE%oOlA@0P0y<6uEF4+HVT^;jrR+mpMjM zRP`=oa?F+d^pHle*XH(~;}l?TC!_CrF0d$OGe(^kf4cKFi=Z1LDxGEjz6pKDaYBL^ zTnu@;5(%?yG)B1XOZr=Xdna{uq*q#?umRnMv_@)JfYS9OG#{Hs(A+C8)|Gw0iW76XIiogehM~ZGV$QoMw-x?}C{_5{Q zK{MdkmW{R*1k*kh7053CN|gHsuB`YTmYmeNgwXw}(&ErS;TuT67~AmoJ0~*8fi|j` z%?&eoxqhmWLlYB>qL}oQ0`tV_{v7f*v`-EvPQ4OcAWoS&n%rxPXNLv&%0@^T{_!9N zsfMxF^aZ-p>OxO3(PB!y&|Eo~%&lfzK`Muoo zdn(;H?H8LahVI85=Laz<%Ho!MxnWZ63bGV|CS)PW`n46M^flJK11 zUdq!1gaq{e5p#lg52?3&{FLWvnL?!MbB|WF#NUj3a+gM{In%_bE&GsDXWTyYj@2|{ z`=4*g%E`|Ysac>U zlDDzHFVg(ay7>!$Pi^ZU6W`y8^cyFSZ#l#x_C7RrR+V$n$g=;O^zJe?Zp*R_Lo4%zcj2yI8fP!!Izm?JCcOQCTzqt z^Vc^?y+owQkSgyER0=?{Ky_dF!L}V&;vERQCj*KKIa0 z++eai?xc zNC~fEuW}4yytJp~XS=YSTb~S12KxQ83>5ssn=QB813W!yq7Ouz!px>?FUK$Dn^k#{ zywcIX@H=!>9|e~fJvTRJ=JKY8YUT@(U1>H#)Eggg@gAnLxC;cX5$Nqmx|E#&TnrpJ z+9Bmdm6A}3xw$zwxM^JX_}(#m4E3}9t^F@7NRE1aievmO=0oHS+mWkNI`+*YN47(w z@)-l$4KCbDpeKCmoo;}}ZFnJS6XKhXtlKiDqBExqWcF-Vw7|l>g=gKUnQdXI0|nIf zS5o84KvTgOhAWSh%1TRt=7X|;C_0dYIlzY?-5As zuxLR~44L$VEwH&Vj>Z?+D8hh<#?5>E($LvblZ_mR9o4S4{KP;_Pex=Y2<}_DP3RZe z&dzknJAb@F%08-ilTXMu0~K+-S&H^6lkJq?+N6MDZR`!icm zSX0?;AFh@N2Qs7d6FS2F95ELpZgf1~OG!+eR**W>*!Q%we2c7L0NyDtw&i;^s=*u3 z<(jN1re9CDEp%X1JQhJaJQ3&`A@teU_esnT(L@=3?_#H$_BbjZIX< zD{tl#_BtcMT{+n6u9#Ri2=~vQE5XD!2@)I`mVN?jsi&uR$>MsQ$!xF4vd_{lSIH0i zF1CQ~KS)-45Z&|hBUv7%M!OL5fSy>Ne{-^jrZ57C#m4+Jr82!o5^qjmMElAn%j+)J zrO;o2)RgT$(Aw*A@dHC$Yq&6CkueXD>dYZ9u5j~5`_SlfqCcpm+*gxD+KjF8i^++J zmV~MRPj@KuHj-0JLKrJe_p_IGsOT4rtLpMChfA-E<_<4Oj9Z>)FFDBiEe{!J6pLRs zsbuWkMqKc`=afDP<5Of3BN@E7`m^f(5K3q3rVDZVg}fHNue$hogS${Vo|HWVwF&fU z^O)0#X6lW?_GtG#>Zv`&yw?;^{0Y~zyR%N}v`6vqzz!@|nKI8K~kQY=$&mjD8j~mhh|OOwbw4} zoAtG%jFz>nlnlWf#VTc7_;=^DhfZ=!^(!`oj3qyjmgJ?@j$!K^FD~3Bgnkgy`Dw%6zZKGi*EeKI@8(M z$C!+9lXS4&8FBr459VCZB>*Padq)4No2r?1ikN`v=#p;Sbd}u+t_-E%jplRgyY_#r z7e^Xz=A*>te6Asyq5b{hN#59buW_oO3wuXP{^8sd)e6theB9kkL&qwrO;AMoFgkQB z*POHh>D#5~MI0DxUIIJRer3hjmR!X7MIre6_O$5L-R#lWA&VXiH$Bz?Uk@Qy$QR#?LRk-OASq||%&jUU-t!mE`0 zrS(33`iO3RUhdFs{jz={+ea?m=<3&HEQUk#5U~lkaE2Kq=Yie_ip<~nZq+&a4%`^h z`({;x)*x_MogY3aMg48L^1_c9!7e?a~$fYUG}1DDcUK=exuRaDeLX{%rF zRDIKlNvY<%@;0AAWkPJ zzQB0~ug=Yy!RlO%mmr?S^DZY-lYKn3R1x&f)F4Q*dL{M@KmUB0`ZawF!hHDwrC*fX zyJzgZB?rnh`YB}Lxi39L3ixmqF>!ybILM1lGrc2U6udPnrBXRTH(&80AI`ohtN+H|%Vss_Xi=5q;iZWV)sUvXLpsGFQj7Zw!>Zc0AW;DboN8CX91P4pyeT*yS}#frf7YtmJ9VOC?Arn`QdKBV2Q7eA2W#}X3q zPVMRG>P|n-I3$ObvAev@-#7;6Dr&G!yY*q=yg}8-toVzHBUjB_Xhiw%-t7d07bI&m zlHQ4k7!|~0K)!6;<3kUPuiTRlh{`>(rgX0)QqCTwz1`F>QJrjD(u?tE{h_k{FD#hW z$7i6GG_1A8ojkjXFUfeq-qaMB@YZ}=$&a8o1E(CKl7*2II$-0HF5z?g4aLI*==g`D zw23UH+V>=+v%E84i|1R-cuA(O&KCcG5g2sUz^9YYh+wq<&+uv&1Whi{+MV8o^P}>s z!i7eyC}!K3N*jS}+!i`1-&7l+ZiqT|FiHTs&)4{r4*~Bjg_Cki;1pUtu{;z(O|tsf zreu}q^t#T~Z3LMqip{G8>Dwf2G(;P(M?WqZ8p7kDcTQi_D9~!Nb29Legw6fNl7$;V zstL+%2zZYD9TDhUIMj zg3l`Y)ke=PEMP3ZWRN6&xRe9Yf%RP6+(3nsPaQW&7WRx=2wn-nQ2I@L6GAPmI}4Y7 z4v!$CUlUB}$wrXC`_D`$OD{^!U2z@&#Wmt&DlRVO`-r67ArTK?>Yft;>!+*Kwh#S~ z%emX|BY`=*eBcTPK+pk56Qts5QyuEY%Rw4sdC{h5oF)YG&53}A(D%zu<5Hg`=U#O8 z{BVT@DM)m`2&w}5{|!h7FhXppLgVn3RQ!B~{17@g6J(YhOIWv3#KH3eWF4R>QTJJS z3}r1fRfSl7)_ba%H$a`mN@uvrpeD`R&nF?(eXF=+9<~8;yMhd73}iIJd1 zSyFjtGgBvG#s{4yx!Q$59d#nYzrE%&AJAO@#OFOrmN5;RA0(1c1>R_eg31oA2-rtB zE%>>B349^??<8M~Px&V@;3Dn_XmAj!ih_hm9BP72)8Ffof1@HD{{B&H+C|xG@FaM^ zj`uiR{&0hunyCJ@s=E62Mm^>)NZyfXA;=>hYogZ>y*L3lU`f*<2ck|41?fkp$uXYa zCV?LVvP<8RGXIbA&?MC5{t~D8IsB%YXuw||;_m#0%2$7Vz!f%p^FC#fC|?LZ>(&*y zf=(zoUrel@O~R*Q_Eh{o)$u;sE|DZ>+dgGWFQ9nT&9P1>OS#3 zROM*#Ks-6A5^JZ&ujdb9;iv~%k?dz;Oz$Fm-t79LGYgEGFO%YiSF2yo&@jJa!H=R9 z{p5+B7cRnbLf;tKC9ht?kIZJe=-Kub_aZLwg(W6aJ{)|^;VI66S}pE4Z}vl*6T zLvWQyv)Kwd^M4t7KBX+I|MzM9DXGbig=woOy7&z`x}>PMs2fwHNgs*boJdI{Kdw~T zC!ZAEBc#r63@T?yt6^K?n_q{;(uW;#ko-M}S^9L_($kMBCMcu$mxGd%_x)X()50SK&he$mgUb;(Sj$q5IbTHzuQTM*+q2OZ(?#6;i~9B@{& zAycdOLAS{l3#lVLP~3QLIAyfMMKF)oHa3z!h<|xWgIu(LT-CA#<1-$3`%TVvO|}q9cYiv7 zR4JGT(vr4=AdwY~<0!x%#zxF&${e5;dq1z~&1NZ2`^pLjegO8yc&&iYi)ZnSU0l8Y z1&w(4O;%S|%hP@np7JI`LaM_-3M#F1saq*u!Agl)`5%SHWC=6xFLY~Ev40e0XzZoL z9jB#IW@S%5Q7%0blP(Csh8;IeaAnp(@y{;{;rrmz!J3?@W_8<`wy!gSL|ak~@|mh3 zphIGBp%t1& zE>tsteVaLjxgGKJV$?4Sa5f`1Dk14k2sXFt>GK4}sFp8Z@Xv39*z-HvgX047a4@q- z*y<$MTpm;MBe!#@-;m-byNbT`D9173mH65(c{9x`nqRJFlK;vKV7OQcPXizH&$k%# z#j8$rJ-J;i8f;HoPkXv5-Ve3r$dkiFR24Z5pi%{v4sM?L>^T4ZW4an#W&!^Dp{9R#&u>Ho0teDz z&u9>gZ4>eTSk{a!Fv7B-B*Z1Vm5s-olk>A)lkg?^eI1u8@qs^2-6yc~ehu5F^c37( ze$_#YUpe5Ko{^wPYb+4UN1t$24n2IWUD$3M%Rw+uF2$MK3PONfIDf1rFBrC<5Bjm? z$mMcg$@1o8$c}4fC^`m*UU5(hv8WCe@ zb8{qo^ml{>FEo{i@o{NrXdsvY{as-Dp~)%;A~!c@+Mn*3um`%eP74Mi`SR%l@Vv zyQsbIww|^wW9V(f7W0&rp7vdCdt?!ssoJ)eiy>*yqtcmGJo1K6Y8C7dC&9Kqx%~t5 z&TpeA)5*~}^8L5vow1^tER^OW85C;-#$p>Od?uFPcX;>yD7}DncyhXQ&$%>bj0;X= zDx8P(cS1!-6cU$)d@E}M0FY$}{h}j*6U`?dj2mxmerl9R@RBBH!tSY`AN_>g(D-Gn zi?6ZTXRb(VCgig5=@}VyBJ~6;Fvs{v<$;*V=A-)Nc2L!agMcWh2g1mBn0`ZYvHqi% z&6Okf)P9SD)aKoc3 z?lP7NOhnYEc(Nd{j!?U-4VcL$9mNmH2eT}f$~2qAn}`X?PVt{*wT!bR9|4>&;+XLQw4!euC_#PikC4u&t*}A zTyA)3inrmz@{rMvC}im)9*y(zcG#bAMeZu1tC&IVf&G$?T-sygObp?S6k7av1XvfI z(LA_F#2^1kv&GD!VDw?UGG6qn+_g_49<;L!B<8=Xx1-(GE!ZQT0`dE91T z&YSOdJ)OIxXtDkTVte#2Ue7+}Z`bS1`K9p@muV>aZgTsxAjb16Dj6L&V8=;qTg=T|Yibv%UIbQ$L*s=OShyIg)C1G&#@$k^*L68hiT>hEz8Qa=M@ z&jxtlkzZ&~F+|*E8nAz*Br&L{;_^u}?dQksWIChhjgAirF%Od@>TX^DZ=I<$mg+@(=<0ZQAOkxo(=mUt3l@G0y_&miHX`4`P)<->rDEEf47l zaiIs^RF?Se7Vfu89k-*E?k)H-+;f}jq>NG#Rm_$0_z&yb>ya*1PgTlR#mQAJ$g*$3 zg#%_=lY1wo)rKgQI;(QHNhh7cFo@IMeTGSrr z7$N!?Qfa7IU2ce`ksyl*P-Ltwg@jz(Yk6AFP5ITczFH-wZCa_^+=9DX?+7syh)8Jew7;$aw_u`?~x3DTZgcGVxI^*Go6Iz8|2OmdcWg4$ZeZ5h(+rB<_zR_T;1HZ zHfJ7e^WD1T8IjzRU%UMOn0o7|sNZONcxVKK0V#C==~PmrOKND4kdTlrC8eYraeyI2 zkQ_q3bShmc(hLYFNI6J%NW7vpq1vt_Fe~NnXDA((J0SfqhjYELmReJjQXw9fOj^w*BLJlmO`Rmf zt(wUwzuyBEnk$#0(9(L0;|jY{6ks(9$S7FeBQUJDZS#8+R|+G!=O!j-+paFQF~dL~ z2^z%=4gm-%SOM7An7eZwZem|PwO?$;ZnIOO;RDvi0gRQ7dQgG4Ub-h^zB}`6;08^~ zQK^K(RM(z+e7g?1ikqm`>HbWy8|RN$n6;mdT4(75P<2!82Z-eBhrr~xNuw9vtqxe| zD=~b@4>Uoc#a_u4=jA-Udhb*DrlQax2OiBVaSl&7{+>)Xph2R3;0c-o)vrKD94i8% zoDhmyl~{EY2d%W6(;vm(rrsZl;ipGvoHS+F3bsPNFeTSzH9rkGn&A!|V>BCCy*5xAeD@k<4BG%d4?X@NHN!F^8 zSAQfkr3^4}#2J3qbqXq4wDIm3o38nnqd3bICp4xWVpIPCWD@`i;_?KuPz-*o}0Mr|J=>)anAU3FL&H& za3^DHcrha;n-eRCL)w=n7#2j~p3cW!RuBP&ALmIbAdGOJK#Z-&9pT-ksmBQ3!gNML zeaq%l!9{J6Me{Gg$+)nvF%K9~mX^IfuiYKL$Go~9XomqMMf z#y(0!tfyy=T!kdvR8J&^JPsdyKnm9bX9fDn7}L2^T7V1eeB}?KY(L3tkHv~7ZN9n- zMAIKqGn zoIWFd1>w_b&ZJpi>v}g;&9>~xmKb?9Q2qo0BUn{vY!~r(=}|jS1ln!gzL5SSmSNlz zz}OvPOn}qj(gh*JQBf&F7fu@m>>{^l{6z7JA~ zcnNh7#Jp$w@!6U#;1UZwG9;ciYSrixc5Q{!~q|#&WccbGa zp!HmpIuj65zPQ z!058+$I0Y7kAT6r^Ag=!uC6&{PK}p=I}* zeWFjZ1#sv9H1vkZ0nY~-0c8DZmqGmZ@8_Xaw*bfs0IRQqnWsYxe#bjFGN&u#6&CFX zFsF!_4BDKmYHbZKFE4+Oj|1t30ACtJf9*HL$S4m2dhrOr5H30JFbU?U)j%!NzH9KIVv$JMx5l&$!2Cq)nh0?MfyKy9eHu8yqm+jiyp>G8?1 zY*(i|>CyI_qybkV9lmM_m~`6#vJ138tsn$sVe`9~9td@T{!Snr&|lsQ?v1%qu^dwSlQo}LDmNhx!_^SG89WDLJ=SpZZ( z>+04$kT$3e)f>6**FUPRYq-&0js7*GJhJ^9^HuxtH^F>?j)cp#tEd<}Fbvr}mv5xJ z0N6s-IB+OFV1Yrtbwfc?!un)%Iud#-_?9fUzF>I#fwiwV|bs74C0wcpOGXwua? zw^w^sb6Mk94*a7-sga%(gyFiG3vMysZ%}&zw#)Vu)OA=H*uQ^m;zEMj5@b$^frI)J z2noUJlA_LXzP8YD><6WDyamc=wYW$T?u59WG|H$2F4fT^=D_T$KkTa79f{u zOO<)8_-R|#FKnA(V*FS(*c(sV++3lQWrd_^^m8$ZnT@En3h~QKCJQ9>K2I`iAWocc|2( zzsx3|{nV)h`-H_1Z@%sEoSvDY$hBvwVYN>_h-zmQdf5wT>t^Opir@6Czg*MPsuu}fa&2yHGonM ze)q%2NglvF%u+#jgkMPOiz0O)3dD-;_=O=>?L<9?Nb-ctAAkzC2r!A!8$;7Mlc7RP z!zSjO0p{aQ4^_EUj!e0MYyn~jM$P;dV*{T%sLSyZLq25S+P-)=?YNq#_z69nN!ugX zC7=lM>)*e>0QR=>nMpYw050`{iGmtw{+vMy^xd9?GEFj^hyDT?UkoiR-mUy6={;IU zQs!gW3tSv05sQ6eCL&Pxnk?WM+1WF(YzmxEE*J|*v|Fo9ecA;P(_0eDj4}HGe|8Ch z-gU0bzJ|Fm1o{*aYFR1s11P^k_N7DfXXXDRvONGY&3t*=7 z9rr?t7Kmfbohj-IZ4b%SW|Iu-pEI*8?jtY*lpKDW{pnsC zWeOCoY0H_^LIni!Az4{j)n^~bN&3uS*ZY&pK7lFT)NB6=IbzW{% zJ-vEeeutW)qc{k1wG=R!^Bb!+`*vdNxIqu@g$>v}ivd{<74zjxR$O3v>4YVOnG*O`>xHXplqZ*~iGN-A@;i+fwC> zda~RfzUV=&xZEGQy8|^fVTnSO7P8v!8{`@%E2mew%I)N5_?n*i`)dI`D4-3s@DT~h zMLW;NAMLxr;5uJR$-#KV5FL9pZ*sn$dun6d61JFhevv(eEu)35^=~+}bX5Xr8MgEH zwVi3N6NqO^L^VQUJRvbd;m)Km7g?o1znekjIMc7@4gUMt7EIT_&Y#T*SK!?D5;MouxtRCxI|0zpR z9JsZ)iOn&Hlc)nUGygHJ&3}~|hTFcCh{Y7pJNq9H>%h4FMzXJRKU(F+vV4px&9iv8 z9P7z-4rgbOMBp!OrtQ^|U%=?t6k zi&iTXnzE1L(Bn|Dv!Ou?0p!-jcQl1aD@++$WqPV}e?SyqkwySrs{4GMMTkw}c2y+=ok8@z zedMpi(MfbCWByW|`z2-kWSoN`AiEErIGMWjpW_O9WbH~}R6oerA&828GRp(!2^@I| z=Meq>Z!Z8;_rG)M?3zkR2Bb}^40rP1&_^KWQa8#;dvI!!wmc50!+})r-unyjJg){G zIDh$Cs4B0v9q*+hFj$2Ar>=pSI7S*tHf#-%69 z1&E+87~*WQETV7QZoU7dtR{YEm5Pbb((bP7=tC#tNn%)}fCN1{VT{#a6i2h(B=E)9 zi#WC?9?#h#Et2nWJRu_o@(%gx@mP_pyd{&L!T+F$<<4^bh0ijCMAO!+ihG9N8@c)j zaqYi;m_X73G|hogIE5=?%)D@YsC^yVY z=>mgxLsDFhqM3znCZiY7t$TskGDI=O5)@R5JJ0S4Ax4~;a{pt)N9Lo_Y~^Dx1Qufj zDUD~^W8AWX)tpJ>?0tmPN_z?sBHVvJD#w!xhp;6I;Ux%7Quhc(buWAguqWhHTGmRS zh6mfCC(H0Mx#GZ5eYe9k1Fpg$DK<2SE1pjt43}C7{3J;HA+Xyb^BKtx>2=wOY*sD>TSa{zqjcBco<|Mn{EP81(20Z0pJz)FI)b9wk!6lDXZt?I? zQto7(K6gHSo?kd1SEIa7i+$oEqtkw20kS7_W{sDlKffanh^aiiVjDGuC4VoMyKo7; z9V6t@1B2NQc|K;6GmrL}2f%t(4*ekrPl+|yk<(X8h# zboYH1ivOh_*9kxKx*rWD79ab|WcBisa6(R*fzl~Or*$6zgQ03w=K@%8-1i^X5QNLU=GKKuiZ$h9waJQv1+S9-&>|uU`V8xntJe1{;09<<*jS{NCO|Cm=ToP1$ z|4O8wLjtdw>6qx#F9S-nN3R-Tjhn{ zdjo-_>?q-WZgH>6sZA*4o}y3}xU-lTSxOKk=v&!d=yn=Or!MB>a};@n2$c%hQW5g) zy9&fm;#2uY+$dfIc^M@DomeE4D-*5zNL52TnBnh5Z8dIrXpGTv&1K_!f1UZN5H?wk za7u@SEVHv}fe&|Z7X&#)K4t5NDsp8z-5u{)=X7fByV>anTnrKxwr|=p%#5m{fF)2~ z|36lDSb}D^IJ|Rm8F=8xJIjK9In>df>w#v3$1WPC2L@_P@=zw)AmH3tK#HiS$ZhPc zuECiVrzfh)J-t;h0PTMLA)3H~zg<9M)~Kgij2)|lgAGIIBrjjfibNC>-P;E^Loz#J z&bD|dV+#SO@vO9#~zWO~8ynnHG8hqy-xa?=$Y|aI-w-eJ7>fe~v7L>tR zH9*o;=IZszq&%(Bkq2QdUlQ8*9()HaG4|QqLCeE+M+CX~zCZCAs`hcl3<1a1D>QB^=RlyP#HbGk!ma&p7AtS{w+nk9ln25p?WAup{Fic5qsUw+g9=;?H_M-ETaDOuoH z3W#MyVZhP6c;SSNbN8vPZ>I2vLqx3js3H-YM2rC5E!Wwwq_M4GVaJFY&uITtA!6;f z?qMB3Cl;RST!q{Nr@yAiHF!dcDu$Xtcs;jZrO^QxQFw`AU#vC7MUYT=pEm(EVWYe+ zfc*l}2MCPr&!kTZTK=i;S|~Y+4#bzg8b?us&^*`96{i>AU_OZM0a`dQLpQLN*GC2q z!Hju^Y;>@dW*LeKfYac|MIvkWaFort#7ZJq@02(UmFiKjNDTgSzEbMdEzqsFkN>Rw z3+x$Ev^3E&n>v!EI8P<A<;{gs-NdP;-jHY-lG2;cI?#^Oe{gE8LLl19YG3`Z4vm4`@P=A#4oL^ia5Y7S;Z4 zS;`HOp{}yWR2LGT%XWTcHmsEPVq@zVK_swQFLA5}r-`LrUo3$|e+0EXP2wWAr>2rt zfYh^BG^!={@aNCYb+J--y1T^?@PKK1cDd-`L|})CHMn~Wt47G5sse{O;|%H;5c7)% zRBzFGwjLAWT`-b}AqXDa*8q8GI^s$M{3K=PrHAuoAn~Z9S(MI(M&Yy}W|oGeM36u-tMHlb9~J%1vE?ea8Pztrl%L1_019?^+c<}Q}4xM2#I zd*BJE{e`CSA4l)jYr!`t{>6GV6HCxhC&BAc$lJb3$0Ot#o~(!;ORds#f#ulmZ&f`{+1C@NA#iHe0c{3boP_M^gx4IK6zLM(+ZT zI5to?2L<)9gG84Hfr;f^G}HIXi=NG{&q2v>-6u8{Su*!-F@Mm58iDm-uWV8HW4I9;Yg!tX|{`3%D*AVN<*q%AQ{PwF68$}myZIW^ zmr|IAAHIYswRNgyC$fvhAHZ@;^elmj>Q4)6N@Q^_?rdPy|m5WG`9=GjNYNTJVa zL+8j*6(}3;UophjJJ<(6imf})xP7L~Dnty)MQ@0cS_`TS>$XMuA{djW7B`2dD^eM( zgjS{G8bw7+!C}k5#{P?n>qzoI@cR7s)szj;cz}Lvz=wxTY{SL`?8E(z;qhfOZXA)? zBJCiAyMK7i0qc3rfIZLz-Pew0C5g&T2buN=m;F9JtQXvn28k5MW-udtt{GXj(cM7) z{|)-Iq*v?OiglKM#287{M?+&S+cc`&vO86?g(ju%GccxRA)ic?4Xb?B(mQ@g%vKds`=KRs>r;I=xyP?m6qc8xB$M&6vR0%Mq6Nm_1Sf**R>x#@cCX~ zeebtfOrC$S6!;NL5%&NcSBGgHSWhcvVRh_Ud6aDAfa4Zk{#Ed(EQhOoj zUGz%4%&u`w)hi5-k>ZqY8~Bc7u~p6*c|FGa*Vo)(1H|I|er$<`#ub#jG7kM-V43GY z4WIqDY&%-NEV%u~aWp6+n3MaIr!e83DlUId_5AfKLdSu#@PPOF6|n)h$-o`b;XPyB zDQB3A`yp7sLyz;OeqT)f_upO`??pu{y4=pU@z<~2I{EeQaI`8QddaBwaFh9rmjld) z{QD5M*|NUz4J(ah7VVTSj|;?1+xOUQ& za`lvdEn7ZI-bXtzq-Uxn>AfXs_fW&0i0kCNPA;X-g1KkEr5f>ib_LWz1rAK;ulnNW zPdeQBuG1%zd)LjNh?E+)NZ1o|OTB^tzhQOsN5t+NnY+%6^0DX6Vr!caM9gOo z?2pFo15ktk00uQ(h%!nJC3O;QXTxQ**4?-dG*S2WQ6S&>Z-p1~`2~%fUJpLxI@`RT zm~3#)%92m2q9)FBkYTVhzVXwZfa6VH%Og&jp55Psl5bp~Y|JqoyU^hpX%|th{DQpV97j5fx&S}TO(v(t=f=Xhuqt|<-rZu6O;-|wA!R7P>@WZMKR;0ZCMOp3L zZeSql7KpN)j-j6a%;+-x6{8j3!}J=r-!v5C4?!krwP6&P{kBK9^PsqD++>jR4a(e< zh*8!(69VlvKN*?S%bUJghDF!QIjngIze%(&LtonZ>+zIh3S##0@yin z#mB@gBBK0xL^m@`z0>Cea~nK=srlff*cjT50veCLzV(!%PtjH}VhHBKh!hWz8GG>O zpg2ftx}mzYRr(deYX@KqWkanX%gSV9g@vyJeKQ#zl{gocta}x$b6k+9r+}Bt3jEN3kw~u#26hF~DZz{2G zD%W#55EoAPRJORC@%NWoYoC?rjd>m$>dpiOGJl3TB58fsdn-qlkGp(ouMpU*Y~#bA zHVddOjYfGFkK0~uNHgBCA>e32aViQGst|{QhYINc+(lt2zr6wh>fULYoBJ?HNlELx zxVCRt`kWlq$FlPB&Kf?hLJ#N9i{h?N6;8rbpI44YJ$u%*cWO{Jky+((w*ix(Y0t5J ziz{*Cme?~nB-vedF}%pYHw7AFQk8-w2vTw#U%L*Kyr>=DC7taDU!W(H~n zUGZxlBd7b+5+Tq_q8`=FoX@2I5SHSxPVJz*TR?ZAzWyQY^YqYf`$aid-4wF;i7ldq z)Y#4>Xm|i>D^A;XxA)BNGk3i*D?LOVOz{=Xe}BL#+!x(7o9MWQ_UzkF-jl12hRz#v z2~V*lK%aXhfCF{=5oHf$z9lh*T>GT_$a=>owx}8Mw7b2;yx@pRFkny4yARpq$#l^4 zEFhml7X7$x+STRdOF%R9l3)PO%cg9zWlVkq@V0RvOo0cK*ag1$@*$HJ!3=8bPhJg# z)j8I}Y-_&f#f^UsJ2a9_7%zRaFnK2?45xwdH$jR*fKR`ROj1}FJ%6XahMmsy_#FYT zI(k#2Gq%V%?{hZA?H;!alKfLDh};imx_+pPQUM+HH(EC%E2b+foJ4GfD z4<{`E{!hr0S^%*}*AH|#R$Q=@zG#b~yNbS|d^_$fW=?=ue%woMUXPggcPpY3dZ9%s zC$xsCQ}+2qtO9{7VLXxKS_e5j74`TG*B5Cn)q=v)woHqQ@(vT&@ z;8wy?#1Ja1wtYHk3xM6mJsWuRtmS;KpST+eI{H9svWV6;^+RdS2@T)N7KoLx&Kg&D zOg@xoTH9@BgYp&AT=b^j&iS8J*64BNk*CJtNUF4|>Z=Vwh~?qbAUdbi=p~@|K|=n` z(&mN~*5Bmf^7_{xe5A4f1(p2pWB)I`dZSY~AUlCMQ40MKt+0<<1`skLL8;@9t zb%m5+gudr*juw1n{=3{mx3#!)M2D*TTpbgCY~`d7YG-l{Flh;<{%qD7JMIk6&CeYH zjc;o5YL7!@s-lktuGBCBzFIOZY2GX0yN^c%9x+T z$b9Qz1zpShzxBFmZ;Q6QB(g@IxB@;F;7&vUju8l;lhU)*WMPoaSJS`a#Snt@Y-8Gx z+_6KAYkeTd%?`T0<%Z$gXTaV7m+AU0 zV^)*cjG5skv%B`}{AB2&UvrzUR2IInDG>i|@+MW|c6srFkyNvfkOPo~*;6wnc(vnNE}wvvZo<6H$+ItIcf!PD8y< zJ*5*M+yEE+bE`qOnk^g@O(v@6l}sRR&_pp~IVZsAJ?TPr9Ur|B$S;UDDUSksatznm z-lR|^FiIl1%v;H2?Kv3!1O^8Njl$j z6zgj)cAO;YokO07_~DG%_5XCLsWTp4n#u#r0(Gwa2vj!AV5uhvTAf5pHd^i6ra3lA z<4*A6pEYG&^EQA}2t?JfY$5DuKy57^ptzjzuk(n{=ybW3<>|fbc-2xO@i*gkMhc)n z3KcJ|xUn&at=z*GE3@$Y%sa!u@ZSfvD%DT45U@%da=zBnF?q>TPo%=!#{(hlkgbH! z2M;;s+=aOGgqoJ*={Z}DxF#s4Ms#1s&c0jRca|q6ZP@InVfcx_voh`_Q6(Rl4vdR? zG~*=#qTQS8;+`D{e#Qg-HTKZGw}RK3*y;#HdbuGV8K|hm0)Yg4A|fK+lfUmgyHo41 z8DNtDxrFq`HKDa^qJDQPNzQGt;>XF3%I|H^3o*C-^KN{5Ohp{(go*{(#EA1| zcZ~~#r1c+;lX|~HnXBd1>f<_}PYA^O#hfeq`J5}>ovTZxj=?L)kHC3}kgV>?c3CHX zWFkI<=a5~0O`YCrn%>KV-V2eycK2VvPU+I`To2^@m(X?7Dh8r7TUL_jr%k&gX)jvh z!q1o>t$|nyZN7Tsb?yQ52C%urbDtyM8Qi%epn5MHj_lWav&d&qY5*9(2WJ<*uiw$t zF4I-$;h{Gmnp7uom>9-*qYtb@Q%&$HjNlTZuk?tI3W{!O#wlwSJWjSbSy(#`!bs2{ zEiFeJ7u*f!N7gO3S09(TnD@N3IE6_xn|{1s`DZulXrSoi1#Y6)FSk44>qb_Rfu`VnI#wT;hx8GxMx*C`<#FH zFpcJ2#>yXo9iad1@Pk?aIC7VoCn;(a?SK@wu7g}V61E^Ad#ZhtJ#ZdA0M-{G6? z+`P`37_O`Vc46*q{%?i-X^whw_;@bx8 zX5^668kvGwV-N!Z!x+V0n@q0B(OYVbEGpnTY@~?3ux8ce@bfsrgLI5e5kf3CBTd0Z ztmajYVnauf#{u;{Cp4r{W&!yK?_uPu#H4e_{kGC(=+3flaucp@A_Uq=8gbI(2I}jy=`$Cf|wbI zhyk69rkMv}mMxxBo3GH@N7dCy@rpWX%m~c;^KVyvPYg%pY13{pm$C6xm+3t*DaupH zpw=98Z}Cu{HbJ}*yTf#1nLSqd$dWcrI`(Y)BD%3;WN*pa%x~cd{lBKCCew0a8>l%M zxypyr3jfunrzNMIn<6#F;G*%b?ycYrOStOu#oBH9T4L=MeQmdvAlB5{54(YdW!0O2 z_zAWoT6HJE4^`}XUq9$^$3FcRpWXoR@CI$QSU}pW&fuVPP5mI}yFy{=;45P`9BnJv zaXV;;Ba*{b79&KmVB}1EirMb{`JLS0@^!5jHq9KDfaEr}TW@4#$rneO2pf0#(jo(F z*{?ngIvRTu_kYWsRxW*H=>QCXZuaXL4IMzqN+;LBs2c;RdW0%T^OAShFiQCIN3c-_ zv|_6%+4R%^#c9AG?m?L0%aFCvy{AOKYBmZGy|)9~;)bSj^0QS&wmT~)KxQX#Kq8?N zGIDiGg?AmI^2B?{q&8^$w-?9nKCeULz7doLh#t1nZW}gni1m}5Qg7hPh&M@^hPzJ zH=9$avb2cWEM7?Twm2N&ebFVJ)`}xCMd03HM>fFt@qRD4x&r@D<@~U zIaOXge2I3rC3yN^UA*7H^=MEN^NpxUib*_Yaty@8Dn8==FpPm^Gb0Eh7UkWQ6M{OT z5_q)X0FHmN?h@PwGST-Sv5aH~@6g%V+4@jT>u%Tpi%z=H>SUpX{b|2Tvh8Tlp!c(~ zii+ocets_CB4=J44LpuA_HfeV;TdgixX1*OTd;Q2EN8}n-22$uq{2d843?g$tr=tEg@CH$;9RFWE|Zb# zM)L+v#C$n<0L*>%w9E>WIyj2D5rBgG^5ExDAef!eF#E6JBdck{zHH^d`ny|k2}R+Q z`)$O`LXU6NK1(~O=9u&bqk8dRIvouvbwJ3%9p1015o(^IvR5*J3*fqct}C;BtLzLO zP8b0@jlS8ru@rYGYDcd9uI=nQsU~yPBTG8o%*oxoSIT1MuipzHZaFSPK- znVy&US1V(Q3s|T$!&4p##v*0trTAh74Tp=t!1d{&xwegZ? zdV;3XWNJ{B@#cXw_urM%!BKE&Vta{qt7uzqa)-M?#9c%TOAAh{l zDdD#|oYI7JR81>y3&@o`xX()d7(aa0A=oGQXh(3TZ~01+@%1sg%hfrL$<+<(42sG> zOFcP{Ytt;c3l5%%ywpG#SK6f585{1knHqYCyW?9;L)E%oNvjs>lspvJ@G&L^ZNLYx z-AMk|d0&E^Vq;dMK;_eNIAMxHIQZ);G+F0d3WHrj;syFbeJrKrFN{Q;!#C5cF#fMzSHC~${vk*1h z4!C5!n5PPT#O~D0BvByc1zy#`U+!z>@USE$Wl}7b>adiu-sF3Fu=??q>>xGyOx_QM z_XkG)%`Zw<1C0TZP2j5wO421+;ss}F+ohDmZ-K|jW!3|tr%hwSC<|xs_NK>wV{dQItRmO?muQRHO?T?&Ki65v@p99s=?zK15M~!uVj6**96^Xw z_lV-$s{E(7P8f&xOMbOSi}FiHC|7MJyC4cSoHwq`z9)kgo&UlU&}MUA!YP808~V{X zDlw=`U4_D+h9jO6$z0@c1V-VTU;(a6f21A|0q?3D$6>CTo9eDf`DiF64G0WNOxV_w zcztv88$g_A;pG#QTwNt^y%b*Ooe`apX_a=)B)^%`cR3j3A8_h>e?48wxF>VewPq?a zR5jy8<#hUyQi)B08jSPd?E@K*NiU?jGSSLvG9>%F3_&e}wS!QF+{yK~4bnm9^kDE1 zEF|=#%OFmQ*HJ6_yCF}^`-_7;BANO`AG9(1aiO@x(ImT8u30T-@+V#)HAf;hOs1NL zt6G9?X0>L;TIs`7sx~pQQ%Y8lp2MNz3sr?%kSZ4<9TL57z+k#+b8$NkUw`~2MA*$} zXTWaJWI0$ff)TtT8L$aQMG7(QL|fj z?Kmdxpn6p<@1w9?6qRvJSb|94O(iR0H<3bB?uY&t#s?R@k~!oWH5Jlv`RG9R4>qwg zWv`51&qeEDST(`K7)WoI`30(xES2LXw>D?)17O{qzT@y5RrRGNS)r-{mwY>1kK{kg z(=kVbJL*eC>g5jpTDL2fS;?Z@T5Io)C$+Sn&b?z3(bcJnl%tLU`Lvp!+aG#)7;1bS zWh~i@#l$iQuqdPF3fLyA!*jbjx0~uhY-aaI){}dy^Tl`}0vc(18WQyY)R0k;kn1J6 zIV!JaPM^MxH?vbm4sFr7AD`3 zSolq>Pz}0kUpDfn$NXr=Q|PEc>J0AU=L>|ey8VH^ zAtQ_Gg&qsQ6o^S@UeJMYmY{laN+P>`K`dEzYwJNs!L3XKsJ@Sy*Rl-RV-SJ>Xoe#v z0Y#(OUCydJ-=Ls!pU@1iJ-@)4P??vrHD%TN?+3^|bUBT;`$=SLRwf;yC_B*N2RRCC z@=%i!V7y=B+sYP;3jTLJzG;MJWP%6kh6~$t)k19}pwzr5(6DY}v+%D9F`WAPlBC9ML zXt@qKWai@jVF`MJSa>K_!%GK*B1ui`W?STW; zg}sC#I?JCKId@zndE$T9P2~CG$;FX@d6rgfrev9fv~jd{G*oG{axkS{lSooRtd~T) z?qHn&p+FIMm7=EHxAF>sxkvU`3?bZ3PZ4;-M|qO{B$S4gGZB~*hYDA=qha?2 zqji9L|5(PC?gNc8)wKhUe@ad-H#kBq&cWc&+FoI>IS2u=}{>}M_~MP^q8G0 zEPrmZAXtd47G`^V1UF!EN*I)8iXITYL=E{>PD;|^uaN7W4x{D{n7q@Zh984n5ch!9 zg{m~M=4|CIdw)J~mkYYPFLhd4=4HC?oq6DSBMDyyK-|jyT&Wi8iY2Hd=F^`C*33vp z5kDL-Y}-qstko}7eDZrWQOWt!G-|tlq^D>*dUi{H4MZ*aItm?&)-V9t*7;;JBUnHZ z3eqytqa7GrI=OzG|4-kccBglsqAujNQV2jMK=G^ND1wv9r?lZqb9_kXG-#lIS93$E z&Bx^jeD*ssb#NWZ(kN>sAZPz_+QEI7J!hwT_+%ka2ZC(QI(PiiF5Cm_^7grE(S<_Zvl7zL(q^Sd;Bd9!AbW%>&S>i}fXQM20rstqcfjw;WP%geM~4a}az zR>v;6cZMFx(83`OoCqYA_|e{6UiPLr-LUaom8|qEuX$eqWKn|Pr+0-3>OPAP_wQ&f zwT`mBJfL&)3S8~+8$FAg%6eCJG}jV5CZICIf1Q|6ny;BZcf#yz)ihiN(+O?B zaG(gtRmRHZ&Z$K$&P6~K4hk1)MuISfr-?#QF$!FTP=f9PO)%;hUGsd$ zT$TIdL4d$1x$nPTm7V_{0%Y^XWU1xhnr4}K^9?y>7&#!!<3L0vCU6SDzr=s%XlSF) zY+=j@RO3xEeEc5^S4b8AGxr7zLU{+qiag?87xr{Im8QalM(0TL8f(I9U9b=fSyZCX z$a*7s4?4gGp`l`G!aJ|iB;3njArt?eY{&*g01|&%7WEJT z1Z?Bj)Dem$iSVX}LG(Db^UQ-L&t;rVCoVx^XZ34{%Pq-W$X}U=r~mGxTh#@=4t!d- zqb3ud&;IsjSR`w&&)N=eD}}0Z>KEM@H!)RLhGL_>YP%La1Qb`b)#B9Tem@}}V6rD4 zt?dY>mZh;$5(v6TmiUcr@=#aeDT6vt27ByniLE1BgYc)_=N}r*Pm})<2#IIs>rwW9 zNMbb|vNdv-VZ(AH8h7MrBQ7`V&kEA^*^s*`z-h}@lD3J+tMN+^)>M;9&GV-AwU8 zTmGx!RG$}tFGq78G2`c3h2+jD*}uG-dP?OqNCVP})(OV*j|eePf>BPqYy%f6xN#)Z zO~uWAk6h*7$8Nz}(X1i=i+ljoPQ&V%og(r-z{$TSNgQr!1mx)es;L+*U|6TA-2efA@)IYzzU64Vz37yT1KTF927 z@74ld?T-b?4Q4qxxu2pDs)jglTzpc1wj`am87MQuDsjOeg)w|h0rU}M?dhnA$DE5r^N^$X^1%-C^w}qR*Ug#$3|RI2W84hc zwq?f3q}ieV0;#z>>we_Zo`h^f31T*9{u&HH5d*A$-kjgZ7^-d6FPKSDJh){R_58cr zGy0hO&pzrv^~tyAIs=Ah%O`iUIB#}zOXdj8%)DD{p6~#lv--|8%++~*HL8uvbD9BJ><_{fqwn5UJc`6m8?aw0l?e@Oa8ST(o z{yYFjQOChnVVac;bvInAtjarPHuZ2t1|)nD6pyLI2%28u48 zHOv|yR`U-Zm^2_nG(q1)!_@mcW+K+t<9vq^wMuR*XxCIb3~o+u*q+TX3jUr;cBQ*^hwWaLhf)`z~-T#@_aGk%3F1AL@h{W(m5 zCuhPrIEbxa_)gvJp>7W9lGFRV${b<1pKaK?{A~^*(Vz4ljq}= zoWq5=4Q7z`yQPlU2V~Cp=PDIEpaN7ww#i?c$d*u=P;0j8W0H6aeEb71Ts3Wbk(CEF zD%_Mt`bQ05=vXbOKpg&#u1hju&iez;*P+9xF_kxF#GNC=3!MGmE=NAkei>F0vv;?9WbJ?RpYA0+u*ce$p&R(N#llvWfG2KXhN} z+Z&!-Uo^gjFlNgiOel4A8ZA!jW*e~mK3#VXTboe0i%0Kf_#Zp-QH$@E-v`ljHk!^s zdd4i6=eo&&9o9mU-bHhzgCD9Y)(pQsL!?d|rVKWJKCfvW{&%Svw@Mp*wB>en#Dr;8 z;SSUixY0;!Xf>TCvd`v-@Ii?1voW(Ep4UW9M7`fzK}A1x9;Ro8*QiFEh_Q4V{M08F ze|fLm?upf(njn_pw1snuVPhnl1FRN>2R>MZVms+AM>?BrO#s7mL;9Eb)^%y73HN1; zg;i!o`Gx7vhNKn=*Y2mAf3j{_p~d@>S>?#iORLnRa45OYlKgxY0#6N|8}l`4$iZu0 z@1E<>l{YdL0vmzros>NUc9uNjY~v@7{QKkYhh!BBvA_dpA@w<`*O8uKQMRkkbY7 z+?q(5;}-QI2JB<_uC8!>RPaBVswgRtQ=@L2_=2q?NA@nyntT5pX4-s>IN4>DIc~nv z5WVxPcYe=2o_<@}`O_^1 zZ5jCQRH-&-HI2uqPkvQZsa~H8YFz>FR48+mlI;kL&E56~eSFV|uA+7)9{h5MAKm+R zj&9{=3yw9h@Snsa1%KU?veXFELe9#e;cBKvHmDoajP~~%O5W!%3ODT%{zc* z6IVBh=PDw=lruC`%q)&swDIT1CVi=#FsY&~f2h?fY;ac-Y3IO@6OaTRke^>n7#uvO zd$ti{?%y^)U50F5e!7xQ-jw$9oDvD4cTl0&LKf^TjbQ|p@sprEOlmhNBB{17IviGK zmz=n}B{N=(>9ae^AgiK8tVL#&oqlkP%U&6P?e(L!WtP1Q?%tb zPaH-$2{re_zO1Wu%AP3jZ|yn6M{}z5sa^6M+t2iIN)v#sh4k+ zGx1%i5X+wbiUmbDu`Y$5=zoppFz(UZDc!Vslg$%}Aun3mbCkdbM}v z!gPPC+>63x#!;N;qET)a~fPmmq2reyzLYT3^7yC8*aRqA?LQ|q(j8V zap)h6x6YSeF$8?%D%ZqRz5X#Bob-bf%jlTw+F1VNmTvavC)HN7oM0x%wxEo3{^zwT z-&gmwWfezuC+P*0?(R(YQqY?#BaK0hXuJYp4zM^@oc|zO7z~eG$hlwW7szhZgWi7r zMU#z*BVfsbTcEtw(svtw{ya}+IqxK>Z+#R;%>?D;U=8w)8RMen0Eb_*|94DS z)ve@l_fJSmHidY+UA_ca*tU{|uG_+_O}(WjhuWKtzu68{%0I0Du2dSGb>BgHNl9@W zxkLR)3Nv#q60Rd$;IR3?-lW=UaHo8-7*muk=_{+3s9&Q;sV**n|A=1SX>|Hfj4#~- zc!=PuEd;o-(hu~8>@z08u@IBg5@3;jE6e*%H+6_fJe{7bF_tu{y_NmV3v88zCT*kZ zXhijmD?0KL8P|ng&vK>+C5q`#xfdXd)zsAQf4O=!ztvT$)Mgo&R)UxHY;F!S6tu^G zwt&5{K-Gxav%7%DdCq^OPE<0P{0CV0Km7L^xkwr~H6Bfz{0=%YX-S|sJxs=W+|{Fh}GT*T)HbL?M-LULEwdSK1rM zqww#>kI_K91Y+0DdHJ(A1$*Arb)x0%hxL{7YinuP-3#)-*on}32>W^|MDF91luYaY zAE4)`sshmGf?h<5=OdWw#2-VuekXQN zgTAAdo_C{0Dn7z)YZm&kjBan&yN%-_m4u^|w1I_|H)z(@!kg*jce0c^ZqvbIx)^1B z1ErbzL1r{NJ;XA4argS+JC{~@;6jV}19#VjopJUI*)rqu1L?7w2^w;p(DmG$<_qip zp+jaBRl_@M1n0rV>=(kH3L`+QsNXa*Li#oLfN!_ajTq0n4WQ;#)AOn&pQWwtlX0b` z{wbO}v`{D1AQ$9TzW@~~qr=UyT)=UHguSJghzEus!mJ^-;~*YzZ*PLeMTpJjenb8{|0;`^5p)9W9d^Rp4M^d>wDi|GJbbf*I~=AQuyZJ~G!Z;2tr0j7(bTVEywK76Qu_@%ODe>p`sDS>86Q1)mOG+$4rb zWF^?>-X-Xw-e&?vjfB#v(pJCM!L<_F&_~#b4I5QkDe6u3NlPN;0+jupJH|3+PQ6W( zV`y-oH*J;NKU#c@5ifI!2Awndl0&hh#)v}h<-L@qq^HT_7Z&k_+_v!exFSZW26eL} zXN$I}qtA^;+b0fbk>e`lZWC6(^A!IH>ikJ4aULA$O}5D>u06bE0tczH-?uk$PJW`q zt&~dJG8v&;G7!UhVqrGCiyqg9i%uBT);x&$KQBPk%yhfhz~w1nLB56?;S9ZRHV+AR zas;P&;Co-OE<_D3nBtMm>~!B{sL$PwaFN?pYTk>wbM`)kAK`<7lj54}FPz2~nr&}! z5}cfFb!HuGNX)ZI3djxjI{1ZcUzq@~u|0%8FbqsJT}b1C*va~LZE12}|9v9Ca!GNg z`(N9ZqUJ9>u#SQt*fa$xishp47i? zcHg-h@d#F|<3^~XmdPJ=skZ2|3_hS#{Q}TSF)~iT=s|aNFA(INr;9<7d4$q{S^59tC)!&?HffWucmX@Pi#8l79e2^ zo}r&spcHJbPFVcaExe34w_nax5YRr7sOLyfPKc;2MnHq(UTj?49(uf5BT>ss!TK)r&}cF2Ja z6}X8Q1dYGXProc#7oCCUbGP0zM<)3z)E|U9Hh-6FM|3q4p(ViINE;yPCW*D0A>ORf zLSA*d;#Cm-Oqji_Al<_weTJrZbVHDpt(!d$`U+ zpnDlRMvZqk5lkh08P>KKcYSpOy4WZlpwBBeJGQu>0m1`2XB^YJ$(JYockFDz3H+$b zzkz_t=Y?YX-|)G-H@vqu64cytz`u@Occi`W{Pw=LH;;eMdxr4gD=ICB_C;yKW)D8tB=mn zB}RaR4Eom>Z_BFTI$5XeY>$hWFwWgn-(w_Ija?>07&*DrjDd<4<0S@kCnfF z5;z_Q9QR6Qv=|vSXp{jToP?ms^KgOQR&zv(IYpcH;Xeqgc^N(E&S%cy6AO7zOZn=e ze8$E7rt^e8u6H0!nH59G#1f~zyYNSfQv5vfG5X}b2d=GA?oQx$eeMk*_I~&82y2vA z@fARB2{8c3S(<+0;(ED@&Nbb=H7WA*VEp5#B()QqTKqkG?Z-=o#cKoQyqH=)PAl1O zVqqRRRKcYwZA>P9XzLcd?ai0v6to219X4!K!?mbk7H$7n7&L*g^->3TVoD~J-Z zVaBXxGZtM-v1i%jmm$P2Dh3U%F{3gF=0n*vxD?zkxyS8`k8%7XFg6k~Av!r^w9C2< zZ}P>uLP!?R>}gm;mwak=uXWU7UoeDdHMxId(#aMdp~^^6B1Gt#HeWsHCEwXU3%gMj zN&PaOXsspd?bR|E4~A*478S6WtM=N~?)Y>`?ew%K z9zJe(HOu3Q@p|Etz!L@l=U6%2a6ra$>#Q(6kkk^pcmA%* zqC}YfcdQB`@Gndh0&M*xo*WU5IHwLlI zCq|QEd&cz8-~S+kAjRJZy&u!dAP}pOdSt+UZi~*NFmc{f_Kp$ox#Q=5`p(cPM8$Lo zQMPcn`<_lwoQ0Rz8RC$ZI@xxDk-Wq(llexNejHE?_A;%VYXX$O#U)$*2L&J%FuyWS zghqRaJn+O9La|^t-b@4;+V6WctT`(;#xgTMn3Y*mRLVbGHx<}@xPSB*KEj6UPLT=$ z)Sf6py)#fJvc7_Xyi6%Dw#oA_B4wNr)hj_C^qUWwdF#i=CD`QyInb!Gd%%K}W1ov4 z#f$X&Y|?~Wi(kv=J6vq$q$^)cN=rzutc(V{b7^S;$$NQ}e3MW&c?Cd~C@>WO^*DNe zL@>(1a%Ns;y!g1_d}bCmq1>|~)sDckF<1O!m~Ik(jT}3DPbi3zZejL4BJKDn8JvvL zGE*I4^;F4psi)LtEWbPM^gJcV7d8pwivy4Ob=@TA|^?(Kqk{R`%fZv|0p7$$T*G{Y~a|4gnJE*K)e;se* zGf*4&5g}C|U#1}rh7p_^@gpRhum`lz?4#q(sP%lwltyJ1-lbVEdcEPjCocv1-3Z;Ek?^Yxmz(1h0BO;Q+OHuyEQP)S!gG= z?SPQT<0*w~{(~5xRPTO319A|TMT09_pSC9tq)&uRh-aka782yZ@_grUAAnssK$_h8 zP1We)BrzScFbrGEAdh^c_gzGWQ>{V2gI_WT{CVx!bV--@MID5#x9`l}_8&2g{EwIt zs$2Y!pj2>Dkj_j8*ArS%Q;(NF!~a!SMg_)IQ_t-g^(4UZvRL4#p`D+UPx)R+#mZc- zf7&(|c}YL@-eBNm-5ow-n#PnO0dLx)93(W)#z;A}u+|J6Cu@{cJR)PI!u=SLTe~6k zNQYI26Zh?a9vrJpk)~4huFn(@&QJm@BN|ND#lG;V#^ybB2aOK-THD`CEhg z=j-PNYCX53P|U;Me}iDXM<)#e;5IT@;_N@_)C5=(j59Nu>ihajkI%t+iOc z1Ph3AvJ%5=D$I87wG@*TBE_G@;S}7hFi~MpmZ!Oydqx#%YO|u;DhAtJD47g_;+8cXk5F}y zSd$t@sdRXXuO1#A&bDF>#ICO&rjFk*w0T7djf`@zFvNUb<7AXUjW{%Eree4Xz+=er zt2EIWK?!MUY!sg&hH*|BL>s=1cPFl9sm=${q`Oto z+^f{31JjYt6XwwD-xnx~WBO4K=Xn=i!&?EVf~e2@q(<;okK#e{1(U`yiqt6{ilg8Z zMLT-@*}sJiP59YEao(W; zoL(Dgh;6y;FBIGD-MGB~N8}9YL=kMT#)llUwrR(QaL3k}CjQDz5sIXz?NSy~A zq8B$juu(6V-}GsAJShz;uG-7!Pg^^Cqa)WZVF?vuWZ?vnV-K86O3na8`@$lFbBI{p z$UK7sP_rnc(q%3_DMi>eDYazhCaE2fAqlYsmjZof9>a2?CmE0M!U=!*1oOaByU)mR zV+fszAwrsLEV_%vq$9$AP#@9{=SegNOkKB?{@(9>$^R(@_t5#AjvOwY$)w0#nwO3~ zX%%()KfaazoOnN0LiuX$*$!XB0hfG8tcUH7yhq(MK7X@+HxeN*6O@(0IU`C z;Uso{CB;{yGeuvKgS|gXVcwiyQZoPGBSD0}InS%$KeW|VBAqLh?&&SBBCtOb-+mfn z@s5D{!s3fRs*dI0i)rJ|y&E=iB}0YVbz;&yDh{-WSVTjtjjhaIeqlQ^|Nq0~U%n+k zT1m8n-Cxts16qPlfaO)GKCLO;6rPs=VKX!Z)Sgd2v(Ec{+*%_wr;Y>sY`Q*&PJ6VQ zdIGiziIo65>EPL(Ew} z3q-HVV_8I;nNspDpyCK*>JDoaYq8&SS2rw6akZGQxYn0CTa$h_PEX3OvbwbAD%h(d z%vo%u+4J}%)%rUw+L|lVbK6*v5Mc*(I{OuO9XaY5Hi^DslfGEM`0s1W^rYl#=cm%# zVIsoWuOR6JN@$@Dc%J<4JTG3B(DJ;de0SRuAt)NAc5mX(*KJxyN(n>B+pF102L!RSXb{U*&lC-oM|c0U?00UR^fNnbL6_^l$NDzLVg!Jqeb3|3rw<-* zOvl@O3};s^fsi(q7%sIShmogO1;gUCBDdMdWE1S*2XdeA5cyo?Q$EYh_VrPUnH)>J z1>$j!_fm|niMCndz^DDy(R)zT>?(ap$kU})4?QvQ#L~L_yRvQ{?&UcV1N$H9WYievEQ_xC znA#)xqD#CHB1-%f4?{b6G!R4cecG{sXVT!*D(?&7bO?8k9{OxNNL^qq_wy5^$V#4o z&*)Iv#_;G^4^F;lZ>p*RsB|Z|bWISX-@i z*z0u-`KPx-?ly{T-H>s0-e9~vHUHWud4X3J6fugN-&~;q) zw&u7inh=QJ;>18Y@mSktCS=&y2*;>b7(O`Bs06lL*P9?3X*6Ilc>l|u@4xlIXkY%9 zBz`#eDp25u&XxUH$4JloQnzM{$17}fbW~S@LAbyoxH=uk>snRE=rSQd`9`r>Z*x>k z=)7Ccl~*>~s~1tRIgfDcJFP3^DP%<0%NUNC74KP-s)4IVK;SM0%R6cj-&hO6f)oxG zo+*EA3(=j=NgYYq+8PxR{+sC%;!oMxvDWzDL30OW)C2Vkd&6h&Dzw0H9WP;V)>J5~ zvoqgR z?a6Hf*(n-0K$b;w-J@HSK)3ss(UWXX?FPAU4gPqp^JNmeN-AtdILpK8mfq=la{do; z7EexEnC3n%4-UXzR2A0x{deC+BL0`PQ7gN>%Y?AY5cm<$Z*g87l&~m#$T2#dttnsJ zvnN{X#oPasoP0&IK>&(Tb^m-?b=BkjDQN$oZaG5ILPUzZbi(8pzIzMgdy_O%m@VZR zYiLKrIy@2=K*{5(9lvaouzA%yZo>jMr&)AEn60*}-a+kHht0^*2{JD+%)$-^NSV=T zetjXUH~d0PAoHy?MBQxof`VzJd#Pjp`c*Yg?qSCVSn44YhuU)bc8N9kDD9DMijeKe zgws!h2$9f>tN>CTH3rVl`eRM+{9ZlwbPV9jDe)#*{B_$i_s*>nk~}ds&-5W5!C7<9 z`1a~YgkdA*@^5!p<6(hHcr*!sin}0HZx#;fbhGfBGp*I2znih<&Nt=!FDM27Gg^d! zn^1&vCq4p9gSnPOXG{Dp=`9{`>IojIPHAp1+$w_|{4BMQ_4&OY_;-Q3_I&=DsqOkG zu3u1~iS^a8Zb+l`FW=JXijL~hhRZW0t8(^j$s7?etpb`%#`p1}?TDKka6P%@;r-R!XAVNIi)bSTWb(MHJoD^0riZ9pFZ3 zajkxRBrVqyWT(o&SmRw!OZY)!Aqn#h1YEIlmzIH;$@z|adNn6!vqhtDb`CK3;KSZT z1!0BO;}aO#-`oGHA@oByR&we*Y~uCRm&@n{Rv*<4!RMl6jvEu3=U>Xx?>U*ICn`3} z(e+%^=@rx_;VO34Yw0wlw^u3uhax`w4@E4a6wGuJ+x_AMLO~-h)YM2q=pJ2(zwPH@ zXllx;>Jw3Lj2Q*UyhCav@b~GS_vkc>O`4z42oudyH`+{bS@f11y{wZWVZunZX-Mvz zwpgqP&|gEMEd@X6B-v(-tW*c+CnCxCf(`&UW^=QR)yrghPn9<#sxB@G@575V*>0izmz%ZCFGnaiyRz$(;wLEt-sS3nIYf%#%;{EtKN zLf9(!HG{1_t0jgaotO&BBR>xgYsW zlYXdsJ^K^opR3Vt0s(kQ=dzuv^D_~)o^K>)99;!b5SC~c5yn_~P7rbt(~t*qc1eUi z45te4JCPs-KkoPRm>ddmCq`{6n0M6l_z*D36WIo7JxX{iV@dyoLbb_$;OQhGX@_%% zJtkOdfk>uL>;ak}&QHCV?@%>xz%Z=QJ2NTS{J%@|KSLWH4NbJgrK5QAx&7X1K*kSN zemc!fbnR4D}E~3|FD%kA5GZA2LT0+S3YSnF| z-?dqD&5jEm?95E+G-+1aLs!j{$3vSVxY>ib%1zZWn}lLNOP`Bzs>JQ)nVFvrGyj+n z&MVK*68*HC!S$?6D8O%Vbv7#u_a3Js#uXWR3y8?w}ZQEWeu& zE7d${VOi_<&|oC#`KHk?Y)O43LmJ&h!U0bdbJ~};3OL_?LeCjS{%L1t{3jrY_JFt#5DH_tkHCUGGn1~s zzRMIqHjd=KrLNUDi|~(x#Dw}OAvZShGOQcTU`gFR2k1^6iV5ObyU8(~^x??8*MD6z zfI}qofA58{dLoGnuNuQoxJrZvnTN9E`@5|dS(bWkHuryBBK?Id1AR55Gvn9ToM&E- z>BBPng*}_oSN1nGsTIumUiw(zRdtDl3E*S$2VGxK4`P;Z1Wmo~=U5a_8yNJD^xpKX zV`W}n%*8I+$JjcJ*vSMgWR2oojVzt&A8>mpg%L=X zSPR^_k6De!Q9H7J7zxt;-sFMxj5NUakh}hycZyKV6vl*j1Au8IEu6rXbUNIS3LSjH z(SASrw!kh(plkwv++djKOnZW!a1%f_aDO0Eq98kqQ4nS-xO-6%@c&%wOs8VSerB}vv~fzr)&^GRd3=IM0(+zitofrF72NccXJ+OdwfA&Y*&=d zIBOs19}YM(ngD$l_>s@~!O@)pn_9#HvNqWHezXeNn9cMDaLprdnn4*}j5+c$r6+$AP=+>rrf*Pr)6- zM>DmWZ2eTtftsn+7aLzi#mt!D2ZCRCpk)^kC}@Y5#N`ys0OQh_6+e>C6{$X8S-HWl zGbs$2u`(Un<7@-E4(talFJiJ@r-hDphW%V6MdtEhB%4meer@3u2z7g=?H%(0Hkby! zJxA$GK_Knm(;N{#DNwg#Lu^q``L`?YKOIlHvscL6CImp`kT zAmT3VqD8D0pM758-Ftw@7j+sn_SkG;c0Fv5%ZwDD4VUkGl~rm^zBznma6!c5QuLFR zh)1>25;NNf`m)(mMU0h#%q*qnT`%;4z#q8VMs{X`1}|3#MRQZ$<_REc?!iGg{OlhQ zLI{aDKW7slPm)*u5MTq4$Gd%4+EDwe@n!BGQ4e3u_KGLim|ff_G;ogwXPqso{C(Tq z>Hl+vC6Ika-oqn(3XWXgPdyBs-z7m|(J7gJw9R5U^R_q~wNBQ%!zV0vj2TkZqMN?V z=F?BMT@lRs+*GD$aCE+%aK9fSv~R-`g+Fq;;HMbnk{fikiaE?)vJy{4GJwL1(Y9EEk;-McSlE7s{HrE}(^s7%$9b%hNbB^MW+iGy0Pv&)*skgu^hGDIN$LjBwoN);xzcn)D+4% zsJ7A&n6qkXj;o=Wsn@kE0&F$Psc{Y)RFl)Kq-Rkpa7WQNT})RTNwcAO&=8pdbVv*t zT4DD2fJM6WM^A8mQo;`vUZ%jDe@=$X=l`~nY5rA~(Z`b|_1s+yX`H4Jdo1Z5I?Ddr z_iHJ@gbOiaDU9uqP=^<8%>`yy{Nx?Cf4!w#F>H%js9qgd>Nr@d-ZSgjKVI~pu=(H( zc2FNj3Tb{C!7wmi*lrp*RZRekb6puY*j^d*z0N!6+eF$8Zg3$GyuacA77w9cjDWMx zJop1>fW1xm4L}6myz7Aa#d(@8WNhDiI>YC)wY+C@fP%j@7x|9ZhhcnxVLm(XgKF+> z=!Y?5nDdoqFa3X;R`~C7i6aG|SXZ;L$wd6AMv(-amn<$D!X+2gZ9K80fbM{~u*j}s zVb*TAnd$}H30)FVWB90E5YgARi`!b#r!%WVta0tt?QMg$1N_#jbw|`bv##j|nUAzX z9wA9@j?vc9?Zz`fTI0x)l5?*t&rCTmOcDK&^fEz(CsK6Yh_OWZT&PkhUi1?@O`Wn{V zFtKfYUoORMcyG5e>vi;Eh1-fx`|wPVyqJU%_s7qGXNq%(q-2Wd*A`5OAE0udcFcOk zqHqCqp!^A(hjye^pNSe`wm4U~)W1A2`(~J$6?2&N%g$0*J7jdC9wuwR zK5g>42J@fEpH(~UU+x9~=RbIdQ}3YpNk?*W?C^cGD!vwBv{b;Mb@pdZad5SYU_wYnKr!2svE{nI*v9o@(&C>h7( z-|x_*pf}=Hzuvo)0l1EPXlG9M+dnD~9xUWuS=4UXE`WzeCL>l44n>#xZ3DvJxAxiN z9umD)fDQ|$?OaqJeIQUbFhIF&KJX6OW81l2QZc>R3A#P=yy4x&T~D#wp!I6O!T}Sj zPtU#h3vKcQ&|(^J-6239{JaLoDmrxn@Nj!MTS2^eL5p*8DH(@(~QEk7U0bKr42X(zmP*Or2T7 z7mr2Jpq4!W!lS9?D}3PK0Qzjl1o|$@gR4NmF%n{OJP%DnkndQ$X)x_kngPCP={MWZ z!&ez|b7p|qCpoQBBc;dy<7agG8|jM0%gJwxL#;e>%gA;BrmiCTVI?KLZfwraZA6n+ ztN4PNAek+UXB^U0<4`GN+Q$Rd9MqlBqejc><^6daDw%{@S5(6VZc>vd>*U}}} z(4)oSJb9nH6bj3q5D9>vMT1>|)Mn9Vb&7Z+ zctU^JXl-SIi399V0xzSxT^%D5I(f6Jeb%pi6S=NW#Zh6U$F^Vky;|;}k02kF*6Y#0 zUp^KznzHVdu=r2$#lj;8=0Zm3-X;OwN^eR9$|6V5y2H3oLs%OIz4%c2y18wkT;_&c zWByVBcqWf7k-lV84)Vs-P$$O{czp$Xa)bb&sR+%{RMuH3`nW6V86Y`(HM}b=$B_Q0 zk4_9auhZ7ltkKA!$E#l`z#=wtC=!eW$p`Gx!Pqk`?rJO0h*`NCkoOT1wdbzh+G_fb z14*j<<3Lj8Faijl0O3N}3t$xu*^!4=Qp#4pZGqgoR_gu1SZ0B#MtoHZwE>26o2D?` zQiZ5iGD(t7K~__tubsA~J8_mKhTcXL^!0aV65%#wUsMelk|Z#IY5L3`T^U44`|x%d z(}kd1ZPkQehSu3B_WHw~%oRn8M_QVTf0z^Yiu>1A%A0q9{S^Qay zjZ>{yh1&P4SZgs$b>-7T%wA~J-_lNvBkYJkj(OE;el!=DxUWfD^F~@^%ceU?%D%}U z)q~wlMAlIgzBZ>FdO(I{TwSjM)en2{F)95=lSY#M#jS;mkXvjjt)?>jecH8nbm zm08#~ntfIZ*F2R7=SK6pr-@?d;(BQ#IZDsXe@WXUX4gd5C5<}31VT63?PsN02e5&c zuTXm-H?eus2NNeZsFM^z;7|c61{mO3ixJTc{S6|TdHy!UL&)n6lU5v)+FNR@Y7OJ6 za8G`UO*F(L!MdfW{E3gW)ancy?C7pBeh^9W&?rTLQ0qPIP>eV57<2Uhh-f#8ax#$} z1r|p*8B^>OZeajWE6_e`#0_mEP=fMp3Ln|w)ku|ICu%PcvO#K(PQ9pM7pcrlajmNJ zY@RMQ{5X~haEPqy{UX3C%H9(_0p0x3<9bz&-PDh%w zqumdlS#u$SP1$nb!#YBH=w}aN9A@gtGmO@Z%q<`@$38E6mIb`8_uAkfA{qaiN*}Dn z4Z*&Ni@@Am?^IHK#kp&v5c6V7r-*PpY6K5`W^0I&62(_45m5;wGF#vP*zf7+bl3?6>KIl>$K z=G}JyZj&R6dS_F*DnI`{{61A(H}`-rPq;+PEUL#{RC62U4Q*TDUXt>(xE?t;{m^I2 zRUqoW%kF5dGo%Hs272*#(=}d~1IE<0Yb@=WfX_=w^$_9xBYTJZC+wEufY(u8r#QD} zaCds9>vs^`scyTQ`1jm{gDLInXGX^gTK&*Xzo74b61~s8Hrd(C zqxlu5oP~Pm6yW)+*@i&YS(dZoomfP5*&_x`-^%+K9)P6gpApWe(T%t-VL$_JT2w2( z_Aj_xqn;Km#MDzVps{Mak~`=2d1J+8-z1*k#!LY9Np-wxPmqFtKnbu0uaA)Y75AB+ z`n?1x_PdwB*#_8Z$-jUu%C9ZzbkQR%l^W0fg$oz5r;E_vAXI9CLNg(rF z8<77gEPw2CkWL#6v$p9D&ok;bf9DnQl$dq1al=&l2_HkR?SO?yQg5@G5E1xwqA@5; zlj^fg-S-)rhXVopUn?(AM3$yTNjb<|SN5#SD+|E~F{eEAZWql#ALy~w7d_2FtLf8z z-%e}?3gn}=CPj`u%};~4toy1>sk(4A4RCdaVwIfbEobmCjE*m|>)PviIW*+g5nWFYD%x@E;Xt840Jx^R!8Ghn&p}_be@MoF=VRU1l^RQ8B6BQ>FMyDrR z^MlKqGDwxCrd}cxE8)W0yO=RAAki=xrSo6FN2xB|!~jbKQ!=t-h^`!ds$)Fc7h>o> z5x?(hJCb1F8NfA6#J2gn(Jc+QGMsG}1c0TVtT^xjZSN_%{!Hd9B(j%4(g=kh18)?qXV;o zh#A(6aJj!)qsJ_3f2Qq%L^+SL?JDi2F9v%}f95c_5+jpM=fW$Gd*AFdRzHrY*V)7f z&FOGth9<|-yKLjIZus(>vwIn+eYTPW$~)AYrkn8jJ6u$?7~DnPgAnHa$JzOJW!Wx{ zr#)Gs%rjq@%hP25euo*KxIe=t_>!4C%!}(CE|RsHN+yZ$5Tz%zB0^rkxi9qhjN2c* zdQ19mm7xEg#fKC1R=1)3pS}!d@1sL5qjcwjLrAY*ys3ly-$0KwjA*0xFlP11dMXxm+cQ26Fo!jmUP#k1==^!Q@sMB8Iaa5e#&6y?uCQVk4HOS?DFUT{ zkvrYQD`(5JnJnn>RiQlxgidr(wxYvc9{6i)r-U}3vwMr_=MTL|W=D&`dG1wp`lWj} zOuV}Q{->I13}QD2G<0r#+vhmN>L-yPYweGWy!y{TDHHagrrA<@cRsh57&gfON#HHk zdg3#0@lRR2{lD6?%#oCmg?EAPK6xkYHXIJuRI9o2r{W2~Vp^1#l0i=#Hgrv=DcJ-; z*#RfoH&Sue>us(+cVhYgBNs8>vJV4BA>E@T_&DF$cdPU0<-_KaZ_Lp$-$N;ZGb3zIxuc?F$0 z#`q#O|67R!jNE^yIp6wECKDk(j2Q(^JZ`7;#ma$WgBSPhV|1U+%@m1C;b3LyQ3P0? zX*z%7;0#`u;~0!1z17GvW1DKGXC~i0Z4pZ@IBcY|ExFS}erleA>KS9_em(zfxm~ax z_*(pvMv6>RXOT>!LTaJEVbaQ^1!j$5KBxQ3)rLv**AsC{+TEr0_r@@iH;8ORzMozH z-ZA)fd8ZhqLWe03ER5O2bhqGJHq$=WAEetcqwCYj>O=a@JSchpE7nCasgiYM<9Fr?3Pmcp!{Gai9vxS+ ztz`Oh-gQdc(x!oD0NG4U~`Jxbq2aiL}h?IG;i{rP%GAikLj~(3S+67)vgoklQy1*Wd*@XpQP?1>!mgg1TX(pDi6s1 zx3Ms}u~#$iT#C94cZV0t=x}nrD~x=?9&O(3h-&DIH?^CJ2Xa=9Nq@_XfjY_Yj}}lQ zLfZRnTl-cXbK6fA;`gP4o#U^4_}EA?PZ|w-s~yG|cApStvOn4kbqa)LPG%geN+-*- zafRmUq^cP(lneLx#Ri_Jla+PTbz*LIZ=RN#a7Sz)3 z0wju8djxvRtjhuPEBGJX`JZ2qf-R@q>02k4CmiIVi&yqQnLaRe{ zMUSnpG~&zxbB)SLam6iwn5JDy3RIy{o0q)j=2mx}(Nc9Y)1t<<_hWabBqqaFe*%>Z zd0{rndVq%}mPwaMY6Zx@?(3i5wN8*u%B&3WAmkr8`+J5}@qjpfb~DvngHesW)Y`R( zW8()^JkH*EOcV7y&E}x^?Pj4+>S&+MSn8m%NIkhzsf=v1-NjSiS((>2VLoV?*B~ip zCx`mNx?gH@6B``ed1)#MWl>(s8n+?_qXz<*S*0k}!^5LBK*4w$7XnXk*LN1(Y;FzC zlQZooB7a0sJ|tA7@Ay!YEK9kUUm|aKwHjIug&VMBpR?(56gXSNG~OwbLPh;Jp}6T5 zz20n!lpo|b3oeenc{N?#>xvwF9aSB3FB+JE69VMalgLuXd*5b;84+wf)IP7H@atFl z+YMWWlC8Wa2SMRmmn}5u^?rv2wJq$Ki4LJ)_1WT#WHn5>Gjc$|^}g}h0EN743A7gc z$RJ2R;)8CmQ+FH>vHGLk09Ec$Czp0*R7na_aH&Y~V@6Vp6sfAI7kFR_>*|J2r*q$UL3JJ^@Cw)}2btRfzw#%Hi z{4v?CQP@zChBQk0J7`;tTF&ch&X?zrN?i9x{Ksw{6l~u5ee2EJprfZ(eqV0<#{9|0 zA~%9t&Wk3qtPVN~Uo>0HK*(v*8T^g%>4o<8`7K1EfKK968bFJhBlahY;in3I)XJ`j zf9zjSR7!@3Mp#jG$X}*tDYKLD%a#lcvK~tPO!XiPU(673fO35&3i;RGPPc!ZljeR4 zvo&!T%z8gRrxfsxX{_FIhAjO}d0PjJ>=reTr7ed(Sri4XR>6ctxjez6J*r;8$kzsM z{=91j=Fi`r(bP59QS5b^RqPoajy3Y!8Vr`+^rESW$;2pzpN>-NnafZ=tMsE^cD{WJ zO8JdB?IU9H`US%f|Cs~O4axTJ{;KK`YZVX!vpSmV$l4~ARxT*&Kl*ww-FoV0NB_1U z)YyaOm+w7VbN{=Efr9ecq6^uF9kugh_f%=+Lcfc&;B#(B znQYh}ia$PrV=~ru@`{`aV`C7{4p8ab3$cnTrZChzv(luj3&Pn%-5|E)4ULVc>J89S zXhQ(#hx*fAj4w6H9yptw)em80zbS9HSHkGi9?T_hXp^2F32EMKeyC^}{&6*mBIyo0n_*JSM-N(@=Q6B)Bo2Sh z5{37zjPrx)4^Mo+h{KWGDg56ik*7X4^eH_Duhei3Zka!I0vhwg(%b_Y^8~ythy*%< zH`ZV%p?f9I1c`xO5d2^1S$BO2FPTtU3?n-M1oZen;yMUff^Xw9FM|wV5X-&G`_9sS zgh11yq{PEzeWx#*nvd+4CQ&P7t7$#Ao^3zsEz(CV_1BI?#IpjQfoGkPv-3OymTN6m zd{`$I=^@r99SSK$ez;__hNImuTMz5!zWB1T`d0k6K$8wXM^nsX3#3ENolOgou#KB; zDLADK&{d2C_%vZr{M%Q=zutd3qunmM#a+o)ISX0>>m3s#VH7m}m0>?lUP}PIq~ou^ z4$0=e41lTookN@cFt{nUlM3HR84{E}nDy1u=j9ma>RA$c4U|#iQ-OH-Gw8)!ap>{= zTYbX^!0elc^c+Cj&vWM)IpDY^8naz=`j>32XSlfT^=ztg7#qBK6!wBTc=gxzljjx~ zU=J)!TxZ|hG+fBBEG2UJwlL)*`>S&meU9fsIANb|fs+e1_ooXsVZYlx41n@0%Y8^y zR=*6FM^_E|O!9C!BD=kM<_IV$rD#)t2D2NRTeZME2j@xQ(&Iy!gAtx|Ifxxi%kjG) zMHNYw)xNlA8eFnorCvWDJo~e~lRcgCp5kTt!V9X&`7?THfUa7*xsA?7|LGDyFd0Q8 zqj77BbONqc%K4|#cX#lWWi!Ju7c^`-rqN(P|G&2?5v02$$i0|eAOkc z*v!@a{LRZul^YmWOo6u>5R|=LjMQ~yT$} z_;#@1bvWbYlJJum zDvo&0*ZQ8B|Ax*bBY?!IMR<0mAuQ;0pZUuu`qnMO_a8T7Hc!bbF9|N22X4qP8<;N# zGFuDGPj15JuaCbf$H^Axwllb(-lsixS-Luz?;Rc{d->|sUa7?uF<_ml99jcr#1d4Z z_K5@c5m^f@C+HB2kD-}aw@csw!{x@SHu3rdU|gS2I1$h?75Q|R@>J?pF!Jh`{CU<$ zA~If3o*MtRk;VH-h;`tZe2}^17f14ukCMSmfKJ#7GHiF zcFn1H?^)cOwJo*X?6)aQPes7GdsqXH!(=*xnvSz}ndi^qP8a*hPY&q0Z>ye(l_Z6_Y4C@3ZQ8}i+5S_>OAd6KQAr6mr3%OMpo>pmhT=B^}k_ZHBO z_kqK6vVrQSGBR-t&)+Vr4W<3@6o;PfvH&v)o*Q5}DMt@t|1N{Hi{HaQZ`%50R^r>T z-KER2gr{>_ZL?v~pvOn}FM}FFrn+spimywA&X}*s)3%#jOT9!ZqOxVwl*2_uKR?Gj zntdEBN~t&!H_izCgi~=Q9`}h_;Opq*)>A6ZaXUChuduQjl8=N2tp|v<-Y$LHe%DOM zPm>4BgF%nixYHcW`G^Kyj!s1Kh$e-knkkGs;)Y*T%y{XS5%W}iO$A>07fk=%XZiWg z<8xxvoJcMgUiPCrsA9zAl+uD1_Ksnq-=yU z^7i&l{4V3<|Bt7yj*9a8z8*q421H6)8l(lJL25=?Ltw8Xt+K1X>@Lp2D4i zp7K91qa4;^JH7MTam$$>_j)h*sEpA#C13=*K^Au1~RcYP=q%lIiXc6Ck7 zK5$GVnQNx@_9Q?ry4HO!a}uZn;X%+oIYQv?x5_$#$2H-li5!3H8zyF_{KqFl=C@kk z(bXo>LP7||=H&7XP&31KMf$Jz97|puh#0RHeWS#keenYf?+V_*Z6DuZw&2ue1!*_7XYePs6~MrMYwIO8GKaD5pi;{~T@hBZckrle`xw;TT%LOA62o z6z){wV<^f)TE?S|*A*bqlOC-_c?NegWGwydlcJx=YSbkq5{dJ5#2hoRyJl|ql5FV* zG&PetGlKXnApqjHITp16_5X1J!gB-|DVJ+@`+d!dKmn z-kw-z-mh29s9^eoj0m557Q&ZTf}jO6xw(ya!58 zdD5=0dIYE|uGXzr+20;!-O}+lpRs^J_|?_be|tExw$p6#CT(B)`Z72>J43;+Twa$3 zL(cqP_BBKHHBL8I9_i9vl+|_}6}&)61O4|mKhx#G7+0W)22|NXUe?$X^R7q=3kM0m z`MEHh|MabB8k8mTE*viao*xKw0dn+;v-OJEe72n3=y1VT)OsFs|4e_31p#_FDEE1v zFiH1a6B`?z$w5xuJ|MQ%I$8NKfvsW*|QoR<)2Gn@f!568{)GGG*)}8wBB?^q~eL&dZ1jPxH}__ z>{f_9MEy2e8tdjP_Llna@DPYIF_r@{Juusv-AAwZdE@QPJPK5hWY67~U({{_pW!SP4*7bSrPD!k`Ip z`kPJhd8u_}s=+UOG*(uqCg+)L`e&bXI}#S26owbt3Rn}xgEsEJ^6(vx#`kI|41;o6 z^3{|>Kz%h`Ehv1KBXa9lA{YwX{=~#YD+rbUjdD{`Qi6p^V^v#SUHyBpRkjR7iE4c= zMLnC|pC5BZGUco7QZX;ZJ^1k9!~2!Q7YpJfbf~t~RraYJQSL-IG67*=(0*_rM28AU zAa~!J>vHhBeCd6CJZ{GJG#J|RZNAatE|C7}1j0N(*lBmBE(qwFksJFQ--~BcR1EV+ z2b|_eGq&8P36Zj#PiflRUi}aV-Z}EK;J!mGuYHwG8_waAc)1zIm8Oqz5YMB4S6d}v zxk`14WP|*Y*xh{pt>B?L#U?}48ri|k3;rIlpk zZlHXG_Vlc#NR94wn?K?tt7~hE;^>uQkoF8N(9B|qWU2l7;b}78VtWXo{;OAN>=Qss z07y8T9rW?!o8{czH?f2Y)S>%{ZuNJ6sk(WiZHZtl76 zjMT6-549A!iVmVY(#pN>On3|H*o$0ot~c}Tz_A{-F*F%hpDzX=3AmD*P$m3hJ zPRls8|GOjz;|@pt>m=8YTkcvL*FXFFKLfXD(Y&`jl&f-< z>~~HD)GSzc^z`%`ccvbpCHP?P^7V=r!D&G6>68VV8gE}96mu|Bx`W?$pAZZU7a$S@ zsT9wPuV?{@R&WM@1Eubcb>YrOUcWc;RgeKyFj(QWpBWvJdyPS)vR68a|YAK8(Fwk)~IMPZ)xF8 z?Oob1=Dk;8T=C+xH4f4oJ!4~(U_S$yW1Wo}!jS=Wy zacJDfv9z@Od$jRvrpb#c%lBeq!Z`;@rVVTqN|vu^3T9z(5@nlT{r#Xrpta8}0fPE@ zfGj=Up8>(wv|<9B?`|%5-b#B#jrE$TvY9^Ncj6VOabd_V&rXmnC%z{cb-Gcg%4Lf1 z=zEpLx7?_iYx^vL0wZ*sYE=D0hm7*IczJ2I#NZHZe29l82hOxlsb;kM~=pHGfC4ZYT%|34v!PWsm|3gpQV!R8(N> zyH+WsI%V^Ge?Jj8|NjCc&>!t=Z^s0(QP-EJ`x^yWOT}f)?O>Np?3EQ2?{)*^B#zk# zpX25iZwFM101o4%;peC0e_XOO>KqIS_SYiNB7l;&SD17Omtu;iFEGU-36ktO++JZD zk-Fv5ya+#&U2|xR__?DwoFF4gyno^Cwg&?jn=OwKu?pVxx&k*ep1gulpID$5`2t}_ z`dOzGi`!^X#qU>GPVD) z(!Rc`3q<>qz2-|kBhL*sRjzN~l|g2S*>bhQ|E;<@$>R!ajrhMv;`A%)&!fnT*wxOv z&Fn=;)2wHSm=_o?CrN+QMUi%4l@Z7YOjlzS2!X??&>2fH$yYzS`;ArYjQRF0z4;BY z(N1&AOPp6b@80Oz=t?3ZWmAjkCB0sj-cdupnwG`T@rLiwo~kn#d5_ShV8#plR>Plj z`5i5qi8Wqk{BP}j&n?m)JL7;<3Fw-FsVN}$9Lylh58tXs2Nky+T9AbN9e&CW-VY!A z5>Tb=23`vI;%Q~67Of4>}F z06L5GIX|$F^0}aB9*k&+2#+B^8xZ@wvKV2l1OuaqUECZv9M9|O^YAyJhe0-Omi;kHf=zZ#C`UHD8A8E7wPUDdx7(cAC_bxk9#wgHUX$;NWnT>rB1 zqVd2=sOZ!>-C6p_Uf(iHu>Z0+y1oDoro5seFe8J$@$jc)t?#vj?@=xzs7Dqn2W5h` z>K|leSs;L#%s+XG0(}Ic?czdW&SQ#)ZzbLM}}Q=mTEH~&w_$UtA2YylI_y{&F9#JLxAARf>q4&DPQM}bqm{ac;@qgW@5 z!2P5*Mt`mq~$@J!$~y4L%yr=42zlnrLm#53!(-=fW>yWdZ^x z5N2MvPWeC!gjP}@)W5tWj|8%Wdc8!Ya*smX{!YdYC1x36fe!t|-u3}oaBR!t3NyiI zT3z~r<$7h@N6~&BnW3k%bkfKIwKSI16N^(xg8Uf2VCA_RSC3TZu?Q|^#q(`|bP1!C`xM0tpf*kEJRfJ)1q&;L*L?EJZ3d8x!C@Rjr4GS6(Dlj8hZ#d$9ehr zmp4a?Q&Lj{w(5HhW-QqKqjT_@_a5K{n&%Niyl<~h!5fJ?uM!z~?<@8H{J9iDWz>q! z&)gcK=WlOL(TNy6i?0DYi_rVo+4s7zNQFj)n2&l=b`h8fwEN$}$el)-J7J&TH_v_( zK%h7>fkr6K=&)v79pK=fB?~-`2-q-XsD$o6AX&!#0^gBlchX6yOR|_Ur%4hS>K9$z zvJ%?7Op{4AU3>mzUi(y*I6()ihsf{?$LniQ6@9C%4Huhxj|IFfti98T4(N}8>Wc|a zM|!tst6|oDxhJ0E4Ai1dC))_LEBN;&KF7~N(hX{Rps?-IFgt@ruDuJkMufd@?cLaUtSg5@xZhvn!!%k$C5=4fwxzjSHSe*Gf9^&XvndPTcA0M6`I4wZU`qYk%j>=|SVy6Po>bvC zNYSrb?714s>ej)g;lL2Qfodx_1R&Z`@f&sa@wX5GEMcJy3zQQk78VwN(2ptp&rY-{ zSO}hgJ0f^hW|oNdI)`3l*vmI}APD&m){tggaGzEBc-+tXhdiFngO88E+CGD7-0oT3Qsh0rR23qP) zK(q)Qa6!!uFq|p_Vze&z(h`ej)0}F&5Klf-i41_`K$93eqyoMv#5$BQYyoB{*&syg-67EC-bVRik1rg3^rS~2>(MEe909QHK z1LaEGR&@E0z0?`BXHLPEE1bg_xYKDv*mv{x?lrS99wE3=MTj2FaI{x2V=o00T(sF- z*|n1g1zj!W`{AzK5$V7rsL{dt{43>UFwqlL9#C$SFPRaueUUL0+NRquf7}yLuIF;4 zAj|3u4$uZL6Z)0vtZHW;H06 z|N1b3kOuJ&3Auwtw%STx)^x*DApU!o=vM;^@zuB`23;4=)H&BWE@Gl@App#X#tlVG z(bdPpn-)5ce4HX_nTF%46F9ivBg?G5Vq}0Ntk&-oJ+FksIb$o1~@~> zO|LNKYllhGXR-pSzUQmh_g||juw^)EQ>%Ri^^&gx)mH58a(ndnV(mRnPCPtLw*3{^ zn}>lM^XxmZ?d6{%+1EbsH_J85YUpiHhk&`bE!U!;kQ?|~2b z)L+~M=jh41Vu&69gXHChS!Zj`eJ+|t4_~i~Uf5imDtPWj9TC7c?1pdsn|2bXUUn&+ z=AJStY3mgHHhQNBPyLNgChJM9q+P*VW`V#9WJ-1KI0Z6I!DxpEGB^OxmfK0DGMa-- zZ6W=BG!DSskoTsNv39J`6LhnASfZ-nfH0&=lU^}nmM27gEvj& zxe}#{Dm7(OR5wTbJVqI}F$&-7O*Z}a)^RQ&2cetu3m0-Ev2!LhLjYkyTyxy6!+9>` zGz&%!4>DulWp+&I$=uHH(h7Lp%IHDF?|_?Rr3a#+^v^P#YMwsjP>W27UCcASY>us} zdIVmU&7##PPdveekli&x`Jl5Yi+4I$^eNMJh5z=yu zw}pXBKN@Agg`US`)>%Y&rn5G+TrZvw0W+Z<{V)9RHic`~sD&qhXh3s4SaEW5+~<}jU6xPC(;W`nF^w5E<2C2W}mg+^<@$ReFxf_o**P-#}Mp@raXQXzuZxgk@l=|%% z9r#?-gx_pLGag|59!vTvLEaJLHJmUds|ibLd&smyjQL;n_+2JX^N0j;?S%&wwzZ?Qc~K_GsZ=c2ZGNiIk1r+78(4%0w6hHTQ)e*zLCgwh zAZ?LyZ2wapnAWlGuFoVE)3NSMYaT5l@sMPBt{2=Tg*>hl=(_WnO3PibPk8|z# zgN{CDV;$wIdVp9PfX zTTRlgVx7^C3@vUI7PIlITP30!720>*R%gH(E5^5@tHaQ_U6N0PZ-hB~6SeU$0$R6@ zUvv#Qf6y-vNsPNEkJOr^>a|QPz>Em^I=sS$X-yMS_~=b`o+8j=yyyXgag)F`R)&CL zl>tR}21&dsQ^KPNAL1=DeQ9W!!8>R!PRU44e-)R`>Y6o0)wzd@L8*BHEch%aS?)^M z7~^xnm2Hhd3eV&Ayb@TJCQa`4v!b@n9e_IA9BJN)AR=p`jITFeyrKyO^%pU^{-WWo zPNWfmb1~;(AGMNC8mp_|adHM{XI)i|kSE3c`2qX#2MWEs%Zs?UgpS?(3^Ho;W`i>F z1VhXlJKy}?yZS7@S{UQ$hss{3`>;vUQF!?b&W4|?T{9pQArlh_-QU!+oRt4fN$G!i zx_E3H_JhGn2UlS8dl{~Db*>4!;=#Jj?F+x-7iVcL=V@`uQCG*tU>+2hwn+&j8P&1> zJz)-KunxH?_2+l3En_zDp0mN;(8g9&O828I4R7jmdM+TH6=1|NSwYW9Bj1B(y1*Qn z)1L<=COrrn)g;V6k-gAT);nnR_WAV3@WEmF;Z!uwHFZpSEBx{5e$3O;XD8kxmjm@{ zp+NHrgmmNEi}AuyYs=?+F?^sb>gYsoDNa**dF0Z)cT3OT;c&4ro3I(HBLbczH8K_S zS1ScW%jv0%-cSi220bO@$uD=@71BLjke~YA+wfJ+Y1T^Ur!=eLRrqANP2MHLnEh1r zyJ%%~R>=MXG2-0*nR*bhr!@={Elht9&2U9#eQJq`*EuI zZTz+kg@mB)$s0INgSwq522asALN87r@o`;p9nPv~$9wAZ7DY(U z6L(i4M$>m%D*L`f(<)<+o^ogaic1dXYx3am@Gsq_etPUI5^?{1jpjTe!;zUWpqGLtO`d#cbTDKmX|AbX?miNoDCrWii3hZ zr7M5^^n3rc6ZySsDa+YGrJaC9+2yK`JD*44M#k8V^#0BD^pIQk+e^3N5X%UZcI1is zM8#KagNum@a#pav1t-l9SaRYc{_OyqORiVf5$d;)%pFLKt4$3w30uYkUKX`g*iB$U zi?9hGil*gMBGeC_^|C6GC~$>v9%b&^z zMln(d7SjnM!{>T{zSz8` zjB((&*IfQjAvdRbgwAZrDRjEpwK)?9Hk5W7*cQfY`_c ztvGBt45q}tKRjoYio`u$Bgz$JnRC*L#I>^_XR~JxgNX)a{O_Ur1Z?qtP9?%I8Jh%x zpA}(VD@H8qeO9Ynx%hm>zp@2OARb>vZWwQb=7TRr#f( zgMG-d7P|@e2oC4GeTwOLy={5&xTZGK9e%Ah%(Nx711HLwhf^(^yc~&5WlvfMz-TZ$s}MAssAO$&{EC=7YBMnDc`(q%`6g zpPN|{{2vz}g^19e{51$?zcMg^kP7$nSn);eP#tpLGAuxpJ6RBo+fO0u3cX|7u~{Xw zGi-M-wRSx!Gr&vQk!y@|S)Q`y21Uqzu$<(Kh&Mfk{LMsYEffR9X3lRzK&-NL$9s(ylvjws{`5A)6Xz-T><+ z{FWLqF_@55DO8SIPY^3vRTD0WSs7c=JsYDe{L^)8I;wI=3|W<-5k)b2 z@7#gE(f`)zhuLFee%=L#GGnn1u>qV{xeYe z5Yl?TR1e8Xv+^yY(M-}-;+x2SIm-i^WkYXMl)yuxLeUS2>09=}Q#dnRkjQ&N{!Yxx z2p;Dp$TgKN8(TvDiS)Z%jt|l85XfgR;^#lSzQA8k$xabTvwLRW72yl6%Xv|lpLL}e zKj4K$dD5uswZnRY zf$Or|W)<{JfA$#IR_0hM;p}$@zHDGeX_VkGn;_g;e*Pr>!aE%brECXuWCW~zRXqA` zaKYfD+Z>I5JqVb6_V44p)gIx+=-{P3k{^?=U)H5>*RdVx62iPyI36 zGp+dgT>G(rzF5&^ba?n%B-(j#GnxCZ*zjlTI4ta+8t2TV?{V;AE6j&QvFLI?(ywl+ z@l=nDQuq-#`sU~d6auA*pfJpOM9U_v&`B4PleazC!UE({-gpT!SiDAPL8`|yb0jPs z6R02=B1&!99x;eEcZmsMEW1jh7QU%9Q-Q%;q6{@on}llIL|2*B%WSNDQ)gse-{DkV zkmsTF&*{*Ul<_Fw^;ywHKw<0H=Cg_F=;E?l>JMxD%R@CSDhtPuP8j}#XnSi=I9;$j zq+qGNf*#MbtvbW^b2_6g@zwK3%lsv)Kgb?R!@DYM^^<%R3tPMebTBe7A$O+T$Z#0a zt%-#qnS$l0HSA^Lwdq)YN&Tp9y+OTKHr<_8i+T&{0rL+xG8t+ZI6=KG*COIS{l^=> z80ZOg@Q&a!F)#gzm`wi4UoX~gcaVOf80lf3J9D>VilmqWNTyk%kz{QUusd(tv_~drLL|Aj| zv8A0&weX;N_;qYiLUzK`_;}&)<)c_(O{0d!+sEGMF~Ki(UW&xdFJJos< z7OoNFgmvMBIqr0NC#t3erfvOQ#m0YeI>mK$OGtT=o&RinMS+MtBrhuYW&m!vUJWOX zVHdo6AMrr_;DSe}*CQ#;-F5`tLgjIEEZ71l*y@C62$VpTYkwha@b9pftcvqKFT`Y{ z*Ok|>E{3C~rLC8=Ci)=}0Unsl#4zn#i(!UJ&_9$aNcMDt>@dU~-9XFZCN^k(qM;M;|mW=`5i(?6kv|zvk0W+4(i< z9P0hpa09(}iX3wNX0Y)Uni_jrBFUQEgyUv($#eJL)9KmY0X5ReWYy4l@Wgf+hUB;?&YXCp@g+f1SrtuQ0>7Vc zj-;k}dlyG*%*4?eN5>MAmA_DM8spqV4OPu24#E+;tBPSPLn2s7f4 zoB`t@FN=t=g*{gon6*5I#~V#lli%D~MOYv(p6Ma<$}>k}4hF#8mAkvxX%o+btxsh;@rP^Lp00yj65bU{lUTRw;X}bS;xL&9 zOA4}m3UcTawAZ3l0Hd*ML>*5*_;nSF-QrcHPO@r^7+r3(;6l!t47W?lPDWVv{p?V) zUW)9Acu*SrJL<4Ia?G3j$h#0|67g(-h2%9`;4;iSq}*ikq?t8RMwx5*xl^!R+tw~7 z6p(5aD`{ds(XjKI^zz_V#4{-M%Z>92Ba$8s%YbqbV(8c=I*^}jk za9rHYfAKg;7CTQTHkN%SGOVglm-ZiOk<=a3gm@Nn1$>AP!~bU<+Ud6Gi^K8B&6Gx#Vu%wIhx? z%ebo~G^7aFgA+jO!@p~QWNgWRall+t8%BxzAV{z16%ob|ilSLxxzlNBV#g4~H#pTY zdBUm#&mRA`7`ZCqXT%KJU{Ky>3|qijQFc=}6U<*G=Jr`<^$pKza**4(wJ z(Y(kZx-@V?UoF1Hqk&-$2fZv^?Aa;9V0K&?tr2LbC8{w9LXx$&;zH8v9Phcy-oDV? z5-z`pF9~f9`*q)YhTY?Lx6@LO3D3`8tZ)WrmI} zDo!Cr6fD_h1Mrt+mDUKi=TBidx^*gU2T_%!9;N*<{ihjE3GR{&eg9|i;gM$9TbJR1 zkm}{vD>tWF+QA?ATOvZ7lNWTk3!nejqe?Pe%0v)!7DvO(#DpAT^v`_4nkmV8bV|V?DxY6AY&m zjxfQ=Q0P2#Pl;sc5xi9Gvo7lcZBmo+DQiXe%uuEM2NsCfsXuIj!{a<<(Oi2o0oN#{ zc(I;KP+Pnu{}-RL?Xe62*Crwv$H>PKciKkN>7>{7Rqeh6u#iH~zeVswgeqylbsFY> zZ?Gy`CBPilPy$bl<(rGWQ zQE^;gc^6%paiV#rx(Z#Cf7?N`M~4#+=ysXkdcCtK{aue?xj&@1oQ~?l8eg_xjlaO( zh12?v+SIX|S_DZuoez|uxHDe4%B<~y5O0Tf`eq`L`^hI~WS`%E515PHJ6<@d*V1XP zusfS2fqXV_BJ+E}cgDz33mid`(}~h#Ftwk~fJ=K9FTYuWoJ7Xaubz)bCvMi~JEks- ztG)x{RvYytcACg#aW|gPvMnkAy1(`QkE-XpiL3me2f0$2{-W%;0-5)_DlSmu z$zcJc%)BMC^KeYWCAOC%^9?(926Ai% zWH^+;7V`SQ=xBqXcvy_u3mrweWEhUzqrL(kv!Z^*&gC(-38v=ixcEsFA(PdtN~M&W z9*0>!FcQ`03i&)8phJ+xBipLSeD&UbLM<0tu!Eeh^+q)J$T*ZH+`?lHDGF}(e23Dc z6fZm}4AXMzc{fhyu8aWo5s5?2QP0Pd8u$E5>dMA~)OA&1td(#nD%JH>?hIA#chK1< z0Y_&((Vy*kY(40M6+mMP=r+uJR@7B2+36e;ZoW%apcAA+p7e+sl60>}oGc!-$?+_> z9Qh}r+^(OGFT0@utH$8TdXIVg_)iVOb=(*wdAN4Q2IpEGwUQn*xnSEXUZXx`n&{~d z{iH|V2RO%@qJoaZw)F#+ZU*X)F0Z0}6QJ*TGqcteb*Ui=_Or=o^_W&kdo$Lr}z>N)N|Z4IEkzkDL8&-aNk9(*#8i zR~x`ZhNzS7i&i(-xqw3U#_TbH+=A<(o{c}|jI~rfD^Kn3TzQtfz}+Yn=WbXDCl^LO zKmp6s_{=HV+?LAPtB2<1=x7_UmhW_-tbSwT2uz9Q8pUc~$Ph`GzWd0e-@AQD#px&Q z68ONUWs{7hex@tpMnuAUCNN_mEhtW0TvT^6>OzaWwZHpN7qHS0(a9dw!(15Sm zr(#G(t4d8}vbUp+D|QnfAh>(cgT|)VrUkytTg8z8<@yp;J(Jh$THqGb6)>7ak!IR( zmLso^+QBAX(!!239IcENX(c|CH2Drw{Pdq=Ja+=x$OJv6sS>xmo^vR=0E}xu#cud8 zDR27AG^;GX@&W6BTF#%U+}vbe(!*VPutrvBFnE_*q0bAwy<^^mEv}*=$bB*Gq5aaExhTvYTvX&wr)an&^@dAj; zJ10o@jdPfbf?`Vv;%H4o6kpwQ|35&VnVumA2+ zN|5EmGp_z81_G}(5}TS%9XTp9%TM3b=%rJ14NExMI&!=4I`l&n!mG13yGnC`vguvnA zU#I8CLbk@3J0RKfK^BthyWgQW7zrh9d%Lf%_kC1b(lQ@eu;LP14`b*~${YlK(@vbt zDjEuZAv-*Lou{Ima=>2JFPYVNBIl+c#~9|}9k#PEQUERjLDwQIa9uG%hTSl!S!RP3 zE-{qdqRF9jbc(Rpuyd&c`5f2A#Tsm`$(5ql=&2+<0zrVDB zLO{OI&crZ^xlLN$FV|hd*iCfNXX{`e-?d%PFN%nfsB<*fIDO*hYUpnK?#cL;xsK;i z1YaNAf5J@)#-s94EvwNS_oLyPW>LQw^~^QEgG=oKPlt*`qcdDOWyI`S736%L*iW(V zXJ{!*CbA;P&lqxARVIw>#gBZjn@Fsy+lQB={LghY&r@D~mNKPgA$p?AooH_EuMxVA ztt!!z-6E!vvTo<%HLH;v4QK2ttO&f0-(*@7{8=^9f6bjJJ%#cHHw+>>=tM;#+g35f z)nDURkQN3eKB!){zF!`GhEzwEi%5>l2euq+Ec|P70YuyqTDu(!IB9 zJ=ST@lSJ)bujEOtKc+Gq5sEz7^I-6vXG~E6B*V9~e@BGLhVaK7??56x-GN{h_R~HL zXXlAz!3Onzi}i@WhRNfM@*i;fl(I@RX9$mL1SOI-w#;9@YOz7ah2ApD+blN#%!CuH zYqLv)i^bDQoDFbGh6}-hj(nA8-=y9Y(H$C4Hc>Sh4f3)8E*1gWX32(rv^gSs}f08!Z3@I@eLRBQsoq(>D**w(WN6B3A9!^?EW%^6%i?>_~9d#6UWpq zj9M&^Qu0thQY1NQgBb(L&lDP&S5(Xg)TT;2g>WDI_(nNT+KfCiX^jqYrd**t8nm}V z-*bVdSn`-_&Wq3?XlQ5vye+I13#{!5{0|k^iFPV0i9WHtQ{(?>fikzAuKK)3|-_U-AfMrEXp>|k+l{wh#7{dt~O99p-_Sx13RHdAzvG8_a#LN8n=1t$}#D+7xm1k^!Iwq&Hxv zfrV}iv2A>wdSxUI`WfI{fcFW0DrsBaMttnhq4@Qzxp6DWx8-o^Enss1T2+#TJQtdc zQ3oTRiLID*R<%C4NauIk{JPO6esGt4% zZItQyN0_hT8^HHRQ=37T-@uoFyySuyD97dyn z2l$YrYW>A~T+B-<&Y{r;z#m8upjlvwim7Acnf%4iHN|A;hAfnBcXsa#dX_6uItjvE?P`zkJyN z8rhz`L=P2^MrWYmZ?izNUqBq|MKObEPRlsxtbs(Oi(s5wAixSiF~Jc7T+{A@gNmVd z2a)8&BcJ>C6Rn)JBw(249NN8~GBT8!j2LUfhUd5PUV%=w-QC?Exyj&j*&|~Ap#7PQ zgz1vF2KnzVSk4)8u(Z@vz~jq7y!u3vl%IfwaZwB4;|`*yoOG-hjnlJ~{?d<)5qcPfWb0pOmO}^50~21}oFi0}2VQ z?2R~f!0?4l7P`z!SiJ+3I`i*sfCt~d8WM@b03`b0K~vzO-k)sKfCfPSwm7C`bbHh; zvHHA z*UvdLk6y?m0h>pm>qHh7+K-vr&v9!ctT4Cl)Yr?<>u&9>t*v2nI)74QDICXW1nrmL zp)+NCKC!BU_KDZu=bV4}-->Y7-vF5@%*$RQJxlWm~;7uV#kL2ATT zA)iD+z@)6Jdo2EQ4%L73NMruxMJ6m+Nn6BmzO<}N7=4sbf&bPSvs`Slm?US!Z)d!} zRZJQVkrUEs&3iF8IWh60L>7H~zJT+&93te}G#yAe6%y8CJb9UkLTZ}tG8tLL> zMC67(nG$QA4d<5)yJu(m$b-SNt8-^ISdMQCzm*IHLCc7%CuqJSAtg;@jZn_jHg$=J zHpee;=~7PB_aRi%zq$u;e2J$9f%vm-93AOed7itZmmgZc&X{qWcK`SUG>HAmRf#M$^@T&=)d^)uYkjwmq(Y^SM}QxmAoUM zLm)|Zpj#$6GBd3Os3|DDh;I{(>**3rR!mdzYx*SCVi}~7BKPfHAxxfGI;@X#? zF!-{9_gUHaNL!mcgU*CPHKm^FIH}%Tqer~)i;1L+<$*M@b5~2mmyV7ODQH}zX|Ns2 zNQ@0eF70uk2tIT8t;nbQrsgeK6OX#*!j9YL?|*2)gxF&R;6ot4CMQ#otXw6M%!XeP zECcTL(RX;qCQHY+&VK~3riSpyP02flh!(FKthGmP9-g5KwE8}28Kf=_Df z&5;$hCxr{FbwuiU=h|>LTk(s|iPN^FGKl}QoCziba?oX@F5cT2yk}RhII&Os1Zhy3 z^MQ(Aw|I1w z0qZ^?%+|Q%)u#|vQ}NgIM)Pfag!j-N1Ui#9!8^i{ipIX@`DKCk6IdfoPEU`|_RYY0 zw!9p+D5nf%p!_(o*Ls_&U~2NZh0tb1A!)uG!M^u`;ezGn4M0=QscK^-ASd5;eKIW} zCDp%Y_kP}NK6So&j|XP?K=n#c<~?CqTW`A-E5%qeJ;%TlBN0xN5C&uh@1G@pe0air zPcnDWO<(U=Mvv0%tNN!e=OWSNxpv2|SHAsX-F5+sb6t&O9ctKXE(U83oG@${eEY?9 zbFoiLFf;6*dkP>SA^E-IMtCZkenH+4OR0Y*C*be&%7Db=%xw0~_hH zddz!60I9|Q_rgqD;Zxy|Ta|hVCj4`fYM05j;|ByK59b$80zSCL_%u2CCGz$i{gm9J z=+)5F9Njxjv`7ViIR?XT+HdSAaae{|q~HHt2>3EmBy+Za6^$};ZJ2FuikRiN^*P_; z^sYKQ6X*zTp}B23gLY<(kJs${Z9K8I%jf#%2XX#c*$+yuWBG8>hrMUZ-iFf-D`We_ zA@n;R{jSPglYCIJ+q(S!P49po%H9gz5%A&~8X5_#FoqmDMn>aFw{7Q#9gK`P*o$j> z$DST0Cb=r$SwPrW`}&P{Lg2=8=e?h7yt!|J7UxOE`7D{U@!n${${7pt32UGtXALOXuCPZU*e0e3L6v2yp7 zZ59Qi(zim^)YAQ-tz%X$32qCa)O8Rhhb=f{Up=sp$WSi0I+Ih>@y#rsX(xqANJ#Yd zfh{_a$mUIpoAU)l)DED*Ff3^vE|_N``m-t~1b^+0egpQ0v!UQcfdI13XZ|12cR zczaYL#}uk_BE!D@qq{o4kEC{wGwd=Sp$c`2^ih#ef5WUvoj!4{hY$UVWQEDFbOpu~ zcgnQ5oKw#iEBgn3z4Z8hU0n${lp$&5829LbD*ET^cUA-ger_vruszUzGNHJ5A5%=^60b3gZU-@p5J zKkxn4`t4J9i~E>nX3x&{Mf6c zeViRiL-LDZ8KW@;Z{5ta4(>E9V!%sQkH5#;9O>HUC9fneV}u59Ktiu;;8Q3`@~+eA zL9myv{MKR@q0K^Ca#s^(H2?8 z&vc@9uw!nGmBp$Tt7VV^Ob4bsc7)YcybbuQSH4E{+w)_=%SC-fGh|o*fne2d<@uQU zo*uOLVe`kkSQnE*Wv*$QoA!Fw9gspjB_5-aZ1}Tr`2F`sski(J_IqLRy^lQ4ey@)X zk0QSAy;Z1oYagpW$?6`=6xaQ8D0h0|cMc(-ub0B;zOR9~9Cz~M$JFQ5I9IO_9+++;2Ck%&~;xreCX&wZ}&PI31M$zF4Y{Je?hF7Y}o2x zGUr?M_XF{m#{B}Doy+<<+DdPYZDYNU-lpEIb+DP-qb9lP%k|#JG<)LK;-(;pI;pqW zbRe_)x)htpZYuHMc%-GLw{tf?5j1=^_4^{%n-D;I)|ak~o4$dl{>npJq>Z(D+rny% z%g6Li)T@;S^d&VY!}Aq$S7DhS)qXvr$S*LG0Yf*NwiAsJq=GC)*Yv=! zvMffSpRzD~J72DUtWFVupoi1Y2t@hV#J4k_{Bu<%?B5S^mft5m>-xRGEKl)m7ST07 zb7JYPy0o_#F2mqMbmfVlsj+Y_y1^8Bf5WusC^)zaN};zsK-sNR*e7QIFr7w~_~_zP5U0)|iRFvk)Y#20T;IE_|Ew+*n>eX2lJ~KR1qxOtSNE&ao5^@e(CzZ*a6;nL zAezvZlv7gb+}76Suww&)Bt5g{3BdlxUjB0vU6%>5MD?DQ&Bq4a&%C^y`O!vkN~f$@ zZ5)?gaLES`e$^xb>Esrx*4Mn{h(ll?Z7O+!V2Z|L%EbnAbpq`W2)T$~0spgTUiolac|U;c z4ni^cO1btsy@eXwRq%>Bhw-J-wgKskuj0}|s zP&bqD$92HcQM2Nn-VgGgDco+5g@v0v;v>XNm>D|&agI+%zTPfHY_l*s>Egh&GW8a; z!$p1|#&{NM-4a$}{!$#N~~2{@weix8YCXM(F_ za;JGiT=#v$F0K4@?jtOgse>MXC!;zm?{_Y}3Fb7^$-MKMa^Rtqw7q`mQc3&}^Zm%J ztGj^l%&x0TQ#i5rb~?{A`?aa1q3$jz{JiF+f46JvZVaL_rp5hL^k|1D&Kp>%w$&~1P7J>D92sY4{m1N0rt(%n|)hD99|+1W2WArt{uc-^ZnIQo!#6nV**7JHww$Hgeyg4lEqx!gD$1Fd4MO)>X z>yuuSN!XP9QLQi&k9^Iwp1R3yUs)M;+W0Ip71^A|y|+Qg(&d*>wu%KA9Z}>%45iJO zC}J}nPm5s=B`&(4pvn83Rm@ru8NZ8U*vAr%zFW@r*S~5;{o!X@)7Q|@&|iVAoe`m? zGutDNqGYr+uP)pgz)GlM|JyF2emA&O_jXe+4T29DFH_#-+*(?^{dS#N%lknEKdZ>s z&Lz%FRkW1(F^^O`BYZ;RtCgh^Ig{MZrrfXQi%7ab=U=-%_GtBKpM9yncEs(caj(51 zsfm(3xm_#^Bj2TksOR}?_n4Q;#-5+fRLFJ5&#ovbZ&NSR8izZJLS5d7nlJ9kfLkVW zMizHYotQX&Hu5JUB$>#51qP=geDY9~ZYX<*$ObSzn)|iB4J!G!2EzWa<0%f;E?-l; zFfsKl<1LLSZc8>)JU5O&R0gk4^FN1H>$De-Os+8r5JPo2m)6qS{HPN|7n*Ch7rv!e zVKg|!>*iNAI(8nPz!9B7x6{>Q&SqgM-$#eyNY@GG4Sge3=VD z7L*aqbGg)+jEfUh%ACT9JD*s~;&D<}D+lPFYOT4Bp<_F8`HXTq-)Xcc8PT+#^&ie| z4_K0|T3yP+N+1yYhk5g^wPb~H2aw@h5T2Ja8qzySfz~q&Utlb~uTrU-q~E6pcDgS6 z-%Azjq~kz6Gdqq2es*6}FP=1afAur{ECOL5vEI&c^vN3C=jN|%#SHnk_~$ahHd6-h zs$)4LA^wf?s!Q!b_gexmE%cahf&x9qjRwrYKmXXfx}>;I#+~=WTw2yc4abK@Uf#DE zVPnfvbvehL2J!4KNPkNT*Ss(NAYmkOJ6_E=P6{X?VwbarZTKxtr*eUS!4ofEJF!t6 zfv~!9cxIX#^Olx=Iq_ZdiN=IvAdg;uel;e*I@*Nyjg~)oV6!Yl2>wM$ajWe`f~pDw zsvriQ`uD%aUEn(|E|7qxaB;nf6xKE*ceUL=R@u9+FlK+WQmli?K4Q-3b0ABCgEyiY zbd2n3K6t7BQ#bs#NI@#?s}f`BVAp^o5($ncC0V@9jQ44TFk~4yFtWr7>&co;TSmi6r2E-eJJ<0jdcfZnSx03f|&~ zCxX&cw$@ihh^6*$bVn;1j2y(;NFE1_yNZp80Mge~w6D{Xt*+;LOy-*BW4l<}VQ`59eeGRQxG@+IBOrfrK%H?R&7n4Nb2_TU2ba(&L zx2h0c%0?=w#$G-?uR$%1b2B>}vw+DAz-ovu#Jtn06Da$NH)AdY?5;(dYVHc_bxHscwzqU@$N+ISdFf%|W z!i0WF9g{)&>-Ub!&9T7HN#KX%LH&O7scpcQ}EkR?(CHmmkfE`o(!0AqC( z>_6k_RQ~VIf9NE(Ds1S(tC~Wja+y@Da!l$==H_>1dD&2vKp*JO;jIq>XhksaX`g(D zlH|+NAIOGqE7TLkZ3&z9mjQ*ZjES*NjujIT5ee-$k~83%*Mmpa?&dc(oOpBQE8K)h z-HHgh-SfTL{+G|9$a+2vD80@B9r``B4M|WzzR3E9moP_xyM;uQn!0+YqjEFrz4HDY zfCv1gAoFv~GcLFD4e*632X}ViRiEL|T6^_RXx;3d5u1EYR5Rs#q=X8wD250VvwO<> zoz5IYil40-uhKkw7B+TSi#PKu10n7sy|{@yk{QVbbChDXP*bB+6Qn(VqUA51CLu^C zd6@?hjQ?;XzjS;!^knc`X>?wwG`K1w6R%1uD@)6SlOyQ7uIojN8Dq97$b54!5L`XW z$4xW0o{#iwODYXlWlQpZtbJ;?d)`kpN_UA}pX0HQQ?NvmQYEz5!$U3YHy~`RzO$Hw~qKhq??@X)gaT$iLl zR?jItJw2)@%y{2-6#(qj%OSUoEO8p*c^!_z%@df_x(3_Zr8l*14oyrL2G^X6Z~CV> zR_+v~Ej-*S;q*SskOysV^Gga+_V63~ClgN3TaY#dh1CuB-#pXm@O%2*E=T1{xosh~ zsJM?g!3_Z$rQfAlyHz+b!I7=QL$SNCY+)og^qlZMC;9`UID1$7@K9;nur9i)Q|V1u zus{j5#>9RN-Wd1;(5!Q*^1+?Yq)Ogsa|1A8VPPI##o}7ORa`P(n`1FTb$p{VRgNo* z3c#F~mX+m#xz@}T>?X@;k)^!lY=IFo`MQ<^?9l>!csK({Zo-{}P{~hU^f$<+8%p2b z(z{`&lWIhE=QoJ3Zl5_w1R3NkSXx>N(^dDyH1c|){?S&Z|K2MRooe#F;RX3t-QTPl z9`50^mE}}uVr8rpn zkTjFMk!SfL=f0l*nS)?IHQq)yoqTjei_{%Lyeebn%DiQ2bFGNM(;DZ}?U}I?z4B+a zwa7o7;isB?^R5i_GJ)FgV7`E*`UnGh(VD|cX(h>j+Ff?_=&+qqYQwO9(=)GA@Tp*9S}k-)snywfyk7SuSdH(sixe&au;Hb zdlB3vEb@&Bt|NN+WMz5zmE6wb{du~X8NtE96>m<@%gD_D6YQuQ@gonL381w*p=B+F z4{|M;4A!^N814B64{U0;T#Eb$r;JBzQK+CX{y9Pl#k2IVR5bk;uRt~`lq=n$RNCi) zL!0?no@y@GBV6G75dcC-Pl7W4B`8JnS}#U?Z|$DE+kLCs&Y1mR$f9|4wN0lenEvYM z<;Bq$V8IU%em2PjFwV<~#zsWeE(5G@?;at6e(?y&rKJj>JTi>)x<2`6&>=wnA}pAH zqf0pr7)TYcdN<|0)KWFh6uZl5v~4*mVIgu0O*g|^9RT;|vbtsii>hrgUVBLh^OrDd zG0`i)Mfi{W&X>64Ps+fkc0%qW8>;1q(6dNyG-YIDYObbSRq1`@%q)Z%=4EE1qoaS4 zE}j_7B>q_+Ac&(Si89;3Onw`ef(wMNbA$7Kv<1KA7TSsdM$UqxwZ+EeI_;GU+?6qH1|%%3 zt9-MelvG9NLq1q_x;$!hG~bQ`WBLZwfn#|ktubG2;wR(CZ`33zkq0Vv(J?p1)E(ko zn5Jme13K71^-wMouO0nmdoWX@zD694zws9@lJ>i3u&FU zftqVwlIEoSydCk%q{Msp>5U zwEi~F=~tUm{aIfdPhL(F+?+4xFK<#xb7oSu*TpIx4iDWcO;ONL6)0`~?i-m9I@x0q zTf6CDdt2Kqq@tZ5Dg|~Pu94ZH4_I$`qNE*ijx+C0g5VPT7b=;lYblWA=(hkMYnI2u zvTG6A$%e}Nqu|BEOisHf4*GFYYLFy_3`jUAAud#?>d%X?pM4VnSkrT$71*m znqhCCN=oZWCGa+H%gfEjiyJ`A9yV^@h#=VkHuhBGnO)dT!2O|dCLDU#@lBKwi<^-| zou{8oH|B}G1CbRW_*?$R?uwSejC}vj=E5G@ep;0P{~t&vyI8drz^C_pZa654La4Hc zg*?h5u$2h8kGknk8b?dF$V8I9sUcs5WL_?mMgCUbj1)_~`^>!W+Wm^_RYjKougId3 zT)H*iMX^tPc2q9(It0sd-D;7Pwf8pW_hw*B&n!zBb!wbJ#r=Gv&cLOg5|D7c)OEIH zzGpmENAGEWf>g35A8@HI4a{o@gw0WUkCmRDMhh|bi`)qcMHeExxn~8*U=SQC19d@v?U_4^3lS( z@9M{7F}XVJHLv#|s;z36=0Lgj;!hajLmDaMYTH=FhGs0AQ4{mqwhOV{tCb&^mk|hx z7%$Uep2Cu&?tdgw)*5y^@0hwO>ZC})z^31h0>I_%-9QX&9_ZSAq~)#a&~J!p7YlCs z1EA-Tf5}SJkD$VjL_IEq*u4}cvZN)Xps3X}pcj>WE zZTutz>mo1AHUaO$V}B5o^P*|6reKEwrNs6|)UM*E^@E@<20V09O$UUw#PO{%_PHAj zXp5Jm5Qjz~!iE!Xil%{9*UHlC&hOa(rsE`!g$q)z)75&SE1B)|qUhfFAo9y5`?w-K ztO>yKbGz5O7@yPWq;&)fvAbE`7rsl2s}wJ58r?5FfEdguQi=7v>zSqCrzy7f-ffY{ zxK=6-0e4fKH17gPo^3+>*mOW;_x9j;->QI7iRRJES{)rM#`hIp_1Mn@?#)p~QP*OF z!tBVs0KIP=SA9N|c8>`{;#CHeWqtd^(BSsq;9>V;Z$w{7pVgnj9^{ za7G?BDFhT>v%#|7^7vse(u= zGx0(gP$vq4C(!E6D>9hF-@5eHK8c*F1?pUWeR@cIfd|k@Qpo4^-yy*2)8mN_KAW3J zR(LUUqdko`S)^>rfW$8j_JPZg@Lbw=E$*9H10&Q)`6JM>Bd$&pk0^eaUe4H;GKeg5cwkT z5#Qa3xBvY~TEa#|^}xEO|L>>p=FG3Fyk@dzvJQgYAbxe?JueT3*Z%d-dUgOL z%g+-B@A%J2Pk3?LFCrXq8d~5Sfl-C7OACH<@Yl(7HfWq^ zAHoTM^w)rR^e6B5PfPpOTO#}#-BsG!dl67n`Tw29mB8SD?LuN`F%<6{ Nl#cPm!t*u{{|68hlTrWx literal 0 HcmV?d00001 diff --git a/ur_calibration/doc/calibration_uncorrected.png b/ur_calibration/doc/calibration_uncorrected.png new file mode 100644 index 0000000000000000000000000000000000000000..73b2a46dc3e282cd445e2ae0287ff3fc400dcb7f GIT binary patch literal 213664 zcmZU4c|4Tw*Z*x7LWM|{%Dzq{vM(uPHyDh)EZHNJT?wDaHVjereHhEwcOR0FB^pae zh3sU{{=25{^E|)p4`W`;-1l{z>zwy_pZ7WUD}CMj=V`9cKoE2uu5lLuL6lVxL>5R* z3I1}lZ=el+oqMcd_5_0H-xGgGFv9fg5X23^@2VI*vs#_DbiKM1v~ghF;v?1cRvpg7 z>-^=NbgaCm;Wp=B_MOc?+@U|nJxTf5H_p9dl{r@tP}%VK=lP1u{QqvMyL%eGRE^@nRLfp9KGJ)V)tMMx7 z&#?Fm1Gj$ZvioPLo=)t-{_$Dd=4#d8y(_Sc1s|?utqkeWprUfRj*v*JQ;+YBW%3@{ zt!IXU6n+Am33c>Vrp3st_UpybBIoiD|b4+*Ab$v*j2vu+4QuoBFm#tY6Q zi=%hMG>lxb>sZ6a9T-`edhXURoo#*p_mcAUhJW8>D)o&+Hemw+RFH;#I)#lSISRU+ zC~pW;%t~Q&AW?`wzJS(wGYfItp}78m0Rs$$jbV5P9rHAFTfKDJ44Uu}BVV#{ra^XSJ;GV^>a7lu@1dVH8QXn%gtOlSl0KHMs(K=CN?Ko% z*YVaj460Sdu!II=qiCs~!)Rq7BU_U3SE{!6&~Lm+ADi@$@rqKCOlf7qIwh$?n>1^c z@Mk-G+l8(m?XnH{PZ|53bhD(6u2#G?I>NPBTS8Q1- z7#{Ib+Z6u%KKbwyRN)5hZ)8t0ej8f_t&&GOK(3bwsBz(!X6>BWG_>s}i*#*fqUUXz z-q?^<7#cZ}j0<9`p;adE8J*F&xw)|>2GaVFj0GqE!*lc73?;}CC)*z{qPlXNYf$@I zBsO7rIGbXl;f{{*^%1BdANWt;jN=cwP`46-bJ`mjzA+t1Uuc|VX5UyutatlE(x6^3 zvgGC%$@enZ?(>4d?(kSLIdyxM3N5ha?*tzrHPye)*zk2nsnwIRb zHTuNWUhu0{{*YYsiPSd~IDjuWpBt|#$=k!Sg=pK|H8P%1 ze;|>k24<5Nz}7sL_T49e*oiLSo&)@8dd`n?pBLgZm57BEK+hO^w$Deqf%Vx<39wwo z0CVWeOw(7h8Y%-LP^gMPO`@EJ@*gfiO�v%ru2QzdpH47eY4OMFXT2Z-E^u%!@`< zU%+S=Rf$`|J+ZKTLEY|dOOOnmMhbkY*kWrh%NC{xolYj7H*z`8@8adPwK7fh+!pw1 zL1E?)*ndOWB}@iW(k0&dr)+^n4z@+a?OGAH+oEdB654{EYGX_$ z8+V&(gT`sWG8lxaU`c3AkwJFD%KD=4a9VIhob4 zyr8Cm{U9CftA;q_EGK1q*;Y^{aPOvAXWS1JdzJ`FV^e5P4S)Sn@Ttf{x=@9LYH@}C zph1N&+L52==gf_!(6|=3F(0_`Z#2!Tz*Ad{ChuM+X@w)evWBt}um<^fl5xpPm%0I( z&4SAqmJoR3F|311F_K;?wk_j&4folZ*@ZJnMAk zf{tu`ePaO>1jH_jKu5$VJi1mqivHQ~;FrfC1ICP10M0!6*XCNxETIZ1gL)v4i~=?k z!1Caa2ktV2wj>)lHn^wVq-xK|(WGq;UbG6;u0ftN<|I^PLtDPI=*K(bzTLBDIn;Gz zPTmk7F=T6R&B>Gt4I6HFzzFS)tgc=Kn7hYejDqM%38byM&~p(lV+Kfe zUJL~AKr$LHS0Mj$`x=lx2?2E!38SSV<^z8NqRFd=NQNXq&Uzz5IVAbhQ6?^c7gBf* z&bj5KGppIC?TkCR|0Z1F^R#CCSvUER3mX1_^D(p|grXx|vXt5OWD_$z$*>WXf#$`@F(iMC{+D&RQ^7gR-o7E{OxKaOj0@GVv6BdO2~bsW7wL zzTCu#B($2doqrbd{(3h#*u>x4>k#qzCarQv)-cI_2haZc57c^Wo|Nt|XW`gx=ZQ@l zIVB>*LXTUejvhJz#~4FhRUz6V9)LPWy2vkI1VEZfswdr*vU%FGWQ@NdKddQPj=(U6 zSk8p62S2k~OmPw1-P_e(Zvad5$s`TUxC?T6uxbtRHH`KtMm|ZS`Xc#|H9GRrSDHOV zzJ{j^z-$~}c=rG1p5~dLXIdw)4;)`=nz>FMD?GO{05zCt0}8~{ z+Z+rx>{)~pS}rpaz0&wMdYw(^Mrx)QP9%D!8QN%%=24m_o(c@4mxQ20W)PEy%phbA zKf{nN7aX!}!Ppj$E>FTrtoa&_Y+nRC`1wYDFma_3WQG7)lH;tyAN~?OElr2> z{(GG@SG{}0-CsO|PI~{(jFlx0izQinYUBi7(r4e?G9{osq_iEsefrXjoU*CpGQaWc zZz0jaZKD!Gb;V{$O{b&^^jN8oSZj%ah^12HR9a?S$ z-q9dw+1%w(%A+VK!8Q^ta4CZ&xH&n(+R_E430?LGV-YUQ?-(oek$g}3D7#!Lt(BZu?c#Pt~U zM9F*|g;;qq7C?5_0lOdz2k9Z~9{?L+1)10y>MBZV5N&k$zs!%31oqf;p4LX6nMM+% zy3OL^4`A`X4Q}k*1!vAS+f>pE-xV!j& zcqFzGqQmgCJ3b(5uh76&SxEPfQ`rdoX%!#SaREvGC;(zLIx@hi+mDiHAq)M!y%}eq zZLbhya^Nutr?L4{0g%J?z14Fl!WfZXV?v;ThN69&P|>}mWa!n%dB2B3ESD#l&oyBX zq{`x2ACzbIYbqW;uViQ+5@gaHai(n_g0CL{FBRG%p~K{93Y!hRf1nF>+SHYRb$`7N zDvS0*?CXPrs@LEa7mdxJh-r|z_g_E}$Sv)w9ydEqKt;O6O?2C}usqUhnIWb%C>>hb z%fw~sgB%Oe#J9lh^BIj&&}o5DoNI4bGeVJ{Sf?nB$d5 zg$E%zIV>LH22}L-J35<1ke#8)^3fa#mlR%O(~*(FxkmSulna2tMVKfmr6#1P|T1R?facj_fsd-|iB)Zlx#qH_l%+`s&+n$Vd6 z_aM`d*nx#Y>Z)}ru$+pTXMsDc>?B#Vz*3J3=e~IcpIQ(d6D7h(5h{1VVGX**0=dT2 zzJNeIhKFoiK$1)Yb>+4ch6&dJ%Rr@Fe8!wh5@zy|CjC!p{s4|he@DXWC?*- zd>IM(WG=(!)$H>}5z~<*HiQ3{zw)i761*IRRf4ZU?Z}_K#&Me$q1ykVxZ@G3wgry+ z)}mZOE6Wc}CPPwqbTssu4_|tXd2y7Jhqk0t9~SO{kdpY~M(M;$4atqL9aj~SKvU)t zJrGo1_rTL2ykjZjszAUcSWpl|FjJ)s$oC56Ug^KjpfkImd;No=S<-~g7?PR|q_4Gtu6!LP+< z#tiLkj!;M7&BBD8P{Zau(U8pCPQY3M#;7Z4&r}L8oJiEFniv< z_ycL^k(x0JG?h8`tttguzRe29hatU|2KL;DP?kS8>khOJ?-IU zfLDZ4nFxH+h%)Kg>m?_Jb}sQTK;Qr6VWw;`O3&X$XKefl)<*L$73H~bbd!9Cc+-tR z$q0KydHoYWJ7_f)WV5MNQV9B<#WT3mf|uc5s1_LXf#>7rZ~GQhF$OfBr6vBaN45aB<2Q~#Vwx7GfLzr8T^sY+ z{q@!ZmQ31CrYU4$W#K zq`KIS4 z0v9dRg5?*g0xTK|h$BW$9W_9!4W9jSsym~<-XZ4+Zg2*dpcxUkeO2i@plJ+cqCGLh zf@W2@Qv{^{_HVg3;3{!I*K5HuLls9vL6D}9!5c00RIU(@3b5mKqvXZJrQ{2*rH}yH zN<#;N38-c@ZB(IFl^eFmzjdQwI9RbjX55jrVGMY;!Yxbz*_iU+@U-EnVdijh0H)Ht z1V{qlU~s!pZ!MFz%N9B8Fl2o75lMUK;_7OL6$)P(jfFzi7U zZRjJ5!R@`13~9%OpKV66^o?lwVpj}?7PUZPqs(KBS|!$?YtC;7X5j?0SQ=>DJbhOD zp*XZEPRtZ%Ksu#D{tZu)tB?H9!>AeQ6;$_1t)PS(Tf~JkOY}9hgzIc74`*qKA$yI5 zSorpqy)=XKh9)Itu5a`TK&%ec%;ceAoni9O)z^04Y}>kjyc@wbH;OLV!v8&Nz?&g; zpO$};cvt=D(;K=@BfAL+9IntlN5F`coW_Nj&DPKW)4&2ziJz+`N=P%ctuBpJ#IydF zc-9c0AeHswR$po|i74b?%wx}7$9C0a?X3@QaLkW9dzrG1Ui@pLdwUwXc+27&%~39u zwGONWB9lq>aXq(mr0&T}rIhv3y#?VM8bmP5Hx~E=6Q{GWUX}R^J6D_SL>#VChK8vF zDl8+@x=}}pOFe1f7ZWV|v^*uPh47wA2wHsk+NjazeLQ$0(w$(N7S*BO|22(?0>R|= zY@_8(ElyiDS84=tGTJSnhGHa@dA9PLW%>cM+Ts@Z7Z<<9?-UkXp@ry2gX?NZp{Zh1 zi!ZCI@8kz3>jGxqB^vq_UkypLLzGp^`ZnG8i1vz%EkeYG6ll9^6EKsgmLSWC${TBA zu8~eC&3s9`+x-H2!6;R!V|EF4!g>m6d+SQ+a1O|BE#70WXb_e|=0Hb+Uk7-=sSH46 zCjvMtuFERGI^ABz$#1v0YeLRd@MXftIl4}ljk?;HF1YTEnP zdVsSJHaTcQ(8QKefSQy-Ma`wep5soiYJq);=SkRloon%gE7q!97^B%!yCKU=4(;=v zt3bzEfqdXQS@0A_%m?3wCy?>%s*ubxAf701Xt4OL8T%mZ?nn%0lzQJQuyt4kWN^I04}XMAFBj7(-qdCZ1?mxLAWyTZn?@@!jn1aG{TVwaXY zoEym$k)5WZE}xuM=*t>=^9d3Bb0?-Ur$XImBWl` z3?$kX&K2BG8gO8yd`_>UE%fL%!S&0ngO8Wcd07S~3ew-^0+GY^=pmch~K?1y3~S+Q!?lX$WA~R3D;?9-@aXr+OXqyD|sV85&G@N z-;!!-l|-4rf9MqgYX1hL<;ndaIp(_&uM-UN@sW15FRpnU*WbI>Z6tcM<$*D>v`lzA z@X_mPOmdvFx->{Yr9W?nJwz*D(2iV*A=_z8>gen9^l>gc(gj;MG*6GNV-kmw7`Vh0 z7h@bIB@Z^Nal6EOH1TauFP?*~pjdz|zg@otm5`|GV&|7>H56ONfN zjSQp^Jv|^>S#|$u$v_H14JqGxUQ7?^_U*-j``UNMF8cLDI;SUzS5B5*zQgBF{m7NQ<*AzA6^%C(#2so~VN)pm zlzpSuKhnMs(d!p!msU__*_gH5i~qpoe|O1M>@+(^LxPSlhIJlwp-I!3C@T@5_Ac=@ z9#fJp|NiTNT+&yOYR$c#W%-Qe0lWxdWp~eoWG5~-BYvjjAU3#_FQ9nlMO4d&-NlfX zX3)?LbZvR-Mit^5&YrZFSO|sga!)tzSxHok+O0l%3%^2OGEI~I>T+PRI zmUmSe7ZqY&V{ARkUy!5_XcS?)^s76?`()TJH95aK^Hdt2ZZzdvVP^6Whjqv;Gm^d0 z39AX*P8$^}X*?ca%g@<`VdYAf%NjLF%Lis-?y1?1f4*@+;W_*urk?Zd%0Ao=^a1@I zHu>sJZ;X+(?~PAWfkvsgVBO4snly-V&`2XzKIR^l>Bf?l_ViqdPHyj5&RsbV_xwIv z?__L}>@)YiljiMtHZ(w_pHZSCU({v`30I3z|j~lshhhm zy&~hVD67%0F*yib&4$g~Ui+#ma^82r(aZXKtLmIZT&a;V_OKXz|D~FgLSk9RELl)a zlCKYMEO_MQW=QD8(>o$G^YLq$O>)he-c+WqJ{#!SvI#;q_DWRNcx=+C)Ezz^g&cBFcU>=a{Ef^)0qvt@$U z3JYW0O&(6ay|7?zz$2ZQD2FE8Phr_nc?c&Ec*7?ONTuUd;l@khxq2(vuOcy;aRQHS ze<{NC!14-QQ)_SZdD@|3mtBmFlifdhTBau7kWR!nnK_TH(4?JL2NzVx(Lk`?szKtg zwT(IRB`J0kyE{*lk#O(-}bT^-PKUu?g_J z$I6d{siBi_maxvHEdDvU3y7&=ld^M{ww}r^x&RIhdI1ID;ro+gd2E_0Lj2NlLX+@m zg-;UNJ+LIN5wH9B-dGNVeb>y8Vg=d?BM-lU7U{VqI$^6>7&{=Ce}RAuVnZWtuua4Y zkJQ@Vi52Nfa54jcOTddi^B()nM_{y6JMO20kiuml`=vT>l<53$&ntOJeLDsttS=<;ye;(mUPw&C4 ze1R`LhI&p7-o_v+*LXGYsIRy@Ki?V8hQd!LeJaK6EEY{^BYoo$)8!v4UG1CIJlp3R z@viqH=u&HWJ7JTVn1NU!>MJx?&WHCGq}8NpyBF78{_k0UK7_2C&lP(9TJ(748v_lDR^^)bJc+Y}-iFmIb4Puk8c$a2|O;2jdQ)FPyEj=fc+ z6(l5&Oai3NU?`-e(i?HD*XMc zX1bcO7G|-z+A@5duvur3zGT}s6547}N6bR6udCZ;!KlBOnj2PG8M0CWz|0@MA>npk zr7F9|Sv`U7z(n!OGA7!~(j<2F6YQ=R2%=ai&O%276Sp_6XX^Of$wVPs6L~4jWpen}EZVTsfM{6A|Zi zc^|dkfffzuGH~F%9C_biN*8uPJ)xrlBq>7a7}Kq{AfVt0B67SSM(G4yZ`UBff5?LV zBy#n({i#jsFL0ei-hONR1-trHBumqk*~Vw3d!`Sf293n5mI zdbCs51{0Ya?F{l@bYo$q4pT^2RL*FdbdHh#T{Kg~^X1*f4w(Mtw6xFmF}v65pM_pK zi8W^|&(LyhI#iNqZ&rPUeCP>!!GZ-tqQU53I|CC8;V3De53Q#Bz0Oc?;XUWmv~h*1Ev~mC26>d zML2;?m8~G#NcM81BW_HJU5BE-z}-T=aJcCVn{-KUy1s0Z9@}V6=NsJec3_Mrb6$oX zFt>~(Bm4i6(pbHkE;`)2_IE4(j;g^=RimbdwAw<83&w*o76gG<3xFcy(BnKbPMm1j z-gazaAcGFuW8O;F9G{)0E8aON!k6K^s>DWK?^jB!Ax#N1Wg`3_&;cQk(5?bI`;lxf z=XDS7C3%NnVq%x($!K?bb+i@b`L;tN;kqQ^5jjE5>g^l2h}prM0b`%^QCYh4bUMwUOldf&yx1;}w(jyz9< zdgN)Jh_pY(0|BKmZjJR?SGvEGK5rhhXZ?5h1~fNn9Y63w?E}C9TPOA(yr4xj;S%Q5 z&pHkL5sJsK;amp2Vg&BP4+G)3n>vQIvzlmExo^Ti6~P;p(Xlz-V!y)1o?<`YJc{)c zumg}}9$}DjCE+@MnJZ1Ma#Ws!n#4+k9nTt+$Sp`;?aI$9he4vn!wq;+Ytwd_r~iC^ z=iYKwkhcr<;!9<`CHqAuX*JnPs%vS=8+l3CpdI``Z5WVYJ9`TDm56E!253ELnfw}* zp(@HiKROXae<>QX8*@Pw8}YEE$$OdRV~pWwd$~SMucvmI|+<>*Wh@Iv|!RvN?riiEx4TBqK+k0Nu`A@H*QV~~SU1t%q1+$kT zvIWp~SFq)WjmM+=)y>bW;Je98b(gEx>R*VQ)=5X0!5`O5|8|zFbt{>0^#$s2h9MYE z*-s$`Z9WBE>Zp4j(2D+IvP}OnH^j;<&rPO$hAJr&1V@}Dp>5gfYneD3X;)NJXUqgo z$lk>k@3!4H$iugle!g*kKBcV4phQ4>ua$<3qW|9UzJHbtF597|ENkMmaMdS`=Rpgc zM(}^;>zDGBwG5bgG#i|akUKxxP8meSGiLtqb-6)uVWm9v5;|3uxSA2}5=m%sDS+gA zmX8>BMtZuTq7q>jC`upG-n~2a-&X;Sz(gYnAlRezAc8oR;{+*lX$rX&e z=xs5ftC^gLVC;H6tafP@C1ip!M!;*5E|@s5MO@i!^qNfsseN=Aw}Ll!qheO~WHx54 z-Rp417Drr{OZssI?e@M4nQ$%Fw%5wsW5#hJ_Nw$WeJoucn$EEQo@Jj2i_by#jKRTj z{@wvkwWbhWd&D&oDR(}*ai(hGNPEPn#cBgg0w{n+3=l%V9EsmI*8R2iP$I433|;U8 zodzN?ArqJor-gPa`y|RrTC##b1ERYvR0VxkB!UazLqKTCM;vF- zLacN>YL6>TS7phd#moH;hA|ETlb&{FwIY)VOjtz8O7_G1J}!RtEz?;%Bc4*e$9ZW4 zV;t@fkyo#iZ7W1W1}eDT9F+BW!-VVM?mYR|*=nz`MbNP!cv4G}hi^2<{E_&nP*2x~ zV0LOa#T zT=zEa7fP*m_G2}u`||JQik+bhOa@MsWAa@rl{`Pe=1|X6`;Q2$^I|QXxtTRR=%`VgO255 zGxQ;tJTk?OVYkXdN*#i5mb{pk8n%q@t#bkQb!5imBkfJ5jP)aIKYAgeay0rYIH}BH zh2_#eqx{Uc+Me8_Ee|%|H8=U1nb0h5o8}<*QL}Z1A^nUG+NlD^>p0NN_i8k(of{0? zK(!!QfMG9UTgN#FVznVRgJ3c_FxRzcW=#X8jYQt!<|}ny0#-kFSO2mzZuQf-#~O*O zofo1}Q;)c2mYf4a=LpchLvsrk_ab;CVax!;%t0MY#}0n`-WDxMFkqr+G;S^`Sr~Y< z+e?MtFtD4Ki3RFO((&7)_qD0lNnxhwfWuvupHs7BC$1sM`yiB~ODY|By4)zv0V%QK zFXYd!cS50xi9L28=YxdL6u!nS{93gK$U(AcY4T!cU*|{VQ2!>_R$EV&4bZ4{1vvT` zJE|v$!9}&zrYOL45(Zmz6 zkUn`DYPX!*HUzw^2(&D&C6JrF1}z$ypUb7YzkA}dKfk(!5-eZt?26)4x|z*TKI3ex zhHJZxW}Xv$Mg+n zEo}M4S~rhJg7q`DEP(3MNnoo(Pw&5>fXq$HKM-{`+m1I3P}q%h-MTZ*@a!B|QX-pi zRc(R4y?Tw2CWFpZ4O=<#3~B@%7N`t%PX@Oo59O)o(z+_p$t$ZCU~Vl&uGCEiG&YmNMTr#>S& z%@rR|wM}v)B=*B2vX{4X($79CIiK=};L^%IOnR6#E?j&t^17t?V!#DEb%W}q%>MB` zgEofMaDov*}noJ0EVErZ+NEWIxd(;X>62wKbxU?mVBtJL;8jyT25}S{k z0bs;jpY>zEA69Gzsc#LWv=80p4F*gR2;q+nt<^b8iQPV(bol5{K(#3^&ssB6=M&JEk5M=>SwBm$yvc=Bu^f=o@L0T+_us z2dQzNt3j})F7)MmJC z357MQ$^F!1?MYH2|xo5xl(S zuDo=D)f=VWfCsEI8%?hqPkYy0d7Yy{6k15bZO2cm*hsRR~B*W=$A1z3x~8;y%s-dE=KM%0eJ z(CGKqkrrz!T&~fgG4XgBc-SZqWk-pt>6ktk;;Rx%Cz#rf(|nPQb*r1s^4@P3K354r za$|oR6h)>McGqq_Zol1tBMtpm-CPAyt|PX*mLwsY`1b@21J+00$8TKuna|)25~6aa z57Q(>v?A=al5eEex|bTwn?;ma1X|ZcUuH5s@ilM9y;RY}67pQHUT2HA=BVRripWw% zmdt#2$V?#DeM(zddr9+x6-oQLIYafh3x~|3|DLUG&)WRk%`f`TVD;arY6wyjaAHS@ zurv)o&|&(lOrvKmkMv40(h_6$(f6IqEuhKVVrDDQo-|-3$Ge&{pCv0=J=0tI5S1(@ zUSwtF6k>JpZg_UKfR|BuT+zgiQTYN>_R16XA!8~;mim;pa8JCJ};jg3XCu!Y6N_jg7zTT8ef zGes1n^}p*FN|@_~U1f{7A$Tt9s?%=XJ!E;el<7Slwg`k&4~!lAbX5&wP=pl%Q`5>FD8#5SmSv^x3}1`RC`yD`JZ#|>qY5TpUn`tS1r zAWf2Z&HKaqKkDxd)zh&_h#D^K`~x&7z<;*Z(D;c`phqJl=9zwv-CUrXMAGHCLLi!ehZZI<}~~&!{Js;T+GA*U!~7?)Rf>FUz|vOif!= zrE*hO*Vc}LB@R758Gn9q-<~D(IT-#vc})U=slY%|i1KYp|KeOvqW@;sWl%-$_6nCj z+C4na_Te9Faz0GHpr*#VX}Q<)Dm>YJ=C=K$Qy0O+VMXt%jCz6{Yx*^VEdA$cI1@8m zIpUbU4rwTr=+q{gVC2LWQR(!DNj>31clYjMZrt+X=UjAN-Au5#wEGlj%S`=l94ME= zG;dg~QQW_O-{8;A zf-#`ofo|Q5@mR!|SbZKI9*!9EFme2iIi4u%<_ypV50|9u{)`r1HlI06KHU;O!yoZN zuv@Z|^aBF}m04HD9|Db&@*e)mJurq2eP0JX>4Q^=Ximrm!t~YV%?hP(AsPZv^LU)n z>1>_P?1vDvTcN#KthOX?4()PA;zF5&b=a;4ljpN;myCX056~HD zcEqrNQK-MQrF1nXdBqWR6+}mz5{7)ExM?9uwT3_hSdiDj9eAX%*r0~&7uf(+banlo zYD6(tPpu)1np(kB*|K$r@F*Gy|Hz^Z%Iv>@G_CjBUcSork>lmJPGSr>o`qgs9gO;=a z4cTZtDr-IH_gGGK%$Q(wP&b%LgB=9a^~b`WMpznnJLV@lrQvKmEVnj%+E}0pgNqLU z<6Tt*6fa2FN%&1^FbQNM_pAuC-ECPTT2IzI`fA-y2-YW<*6s9-M}B?{L8l;?4_juA z6cje!gPtQWrpc~j$X>|GGT}atLb2DuHF(@oap4E=!|Hsl(;>pIe=$sv#xbKNf>9X= zCJKqy5gip`eRy+b6yl<(!tR&X+LFWDgM*7pg_)pg9vdJ3=X8DJ)QT(kPc}VQ@LiK~ ztIu_CkL&VR;* zd&jep8|S@JTxiGoA!4~`ZbiE7KxewqN2|_b2ATVL$f0p&gbm?Cg`A#wsx=TYFKqp} z{N!u-(x1&)be?k!7KJPDmc=b(hFIw-om2~9dLtB?K|>qN1^^WU72t9+l444n=s<;F zWQFGiuuN-KTJ|%r1nlrqHD}O{LCemtmaP9yk>c6G z;L73d3Qec}%;{d;E^XUy+QXefB~kd{xBb>a>6t*ou`)};d^~n;Azfw@t+~;blN(i1 zwG4g`Xk9V!K5MIQ`soBV=a&6%0c*3<9Wd9k38B2kvCV$c>O_9M<;x+Pm%+qxv42aM z^tWefN{650jBrRPSy}95>p+9d<2inxxsMm5uAI+D6z?sNLbbJ=k1EIHescqW1j0t` zi{qbE(3ChZ;JEet790S$5XNz5@NDXfPrDZuDjGN8URTv0TzS9kgd} zt%CiKyZ)BR%ssXFk({#Gz}1b=-s@9$PEyXctalPKkME*^*QEoddX~UM7 zlrN9s%)x|iO)Zkp6@7VkNiPItz_gV9^xJ2UUz9-8zH8DHj3)VdBgVWE8x2~&#?HnH zpIRqZvo~*jFb3Y`HmfFh=mt@n1){|${-zW)Fi`tnkKK&l@MziPg=cyM zJ=K^w7`PU+TQdCdpW^$RsR+JHSj0IgDf^E;=UWb)iw1+riXAg<&NmJRY=j@aZ4-o} z2p=`nL-riwmS@h6a%BTX34>?H)*9HAy5JR)or6IoF*q>6;pLM*-DmKJ54o1+dY<*( zpqte!*R^FO4l8UHm;p61lAZ$r5F{S~Km>(C4O^e>TCe=Bhs6O# zyab*uQEGl&`4X3nvqU`bFn3{hxkp;Ejm@P5t(59pQiNc~pH>)?;q>POUo~N;6RGsG z4>#iEufrRIPa0d#PBvx?IQB-(J(j@5)6&w=PH6xO*aygIPSVu*$+;y!feTdZdqi-pwq@Zhvk^5*TAe%mfx%B0@?-Ko>EZ&j4Y zFA8!=Z7hf6ZkKp)sd(^aeDI#*6aU#5&k^vCjA?4obzy>s?Uy7IyKdk-+W2rJ0~AJjw5v6$z*G#h&eeq z!Tb998huuhi94!O6Yqq1?=CZgh_zU_Uu%YRe8l4H?Tx@(8eBfa)ZNO7S)&|5^MUr? zUbAo0zueScl`?JLXA(GcL5=TFRqRmJ@Z%2>y-%fLu{L_*2WL#~o3~?)2tJByt)}I5 zTn5vCAG&AD#hYzhyuW z<3OhMXElbH<&O!8SR+#A=$SEd59XcKD!t|L%7|aTPLWEdn@xuenQ~ra88<^HX? zsJPf3u)%7wJZ@^EVx!yDbCa5^5&jG5Pj`sGayYAW`tVL{?qKj<6}XdPE(XJF+5F6) zyzR8n%5R=|y4lYVv{Tl8FD?^=Ei+l7bBZ{W;Xs+ujJV*mm0h@-DC{9vQZFRTyL1ko znc!_OjO$WAv5us7W7Adt{L789$qngNGqG}UI#UuLmXT2Y=g$TwM8>&w(9Fljm(=fI zZ*X{&s1IlJ+?BW=3@1u`Wrdr46eT$DNDzBX`{!}E6E0c*TlpYa!_`0g1^uASOtfWf3_7Y6vu>R_^}9$E zsqf_;{pLVJj(&b-XTKTFvf>mEHQJ7v+DaTVgOCjty2M<)-mm~pV{rLt@WRub0lAGu z5bcAzdy^h@Gv;FDQ=5M0M$D0Kir?p(r05FvB7I!_QTgE%9GD%ds7?`h8k%QjY*I^0 zcEJxl+F3N9FH}sY#iQ~CNkE#zRV(|gHX6%B`i5!6o4Mgc?+!j3$z0xBn_Po!G%RF{ zBF$-|V8gUbqM$J=0Nfh%YyLCmtT zdNZ<_!GOuh-d^3K?WFc}PVe+CgThWcXTa*s{!gEZ^aY6J+!Z#q&ys`kx#fV69sZK8 z4GN9=?^%GhViW5iW3*BESd$`7jZw20JE!S?oa22`&sSJjQ{ioy*>rGL^|bt7pQ(lP zg|@TS3^}od-=r70N&X=h)JMA+REl&4<2gL=J$C3_SM-+Ayt=QXanC5SKf2!8 za02@UnU4_E`*zsHSDa?I3V-0?Zf-D<5##2WXNtE=zzfhcKPRV-Cx5)2vVOV|tvJ2- z1iHvg@uFUy>++{{#h}A?WC=1dCo7;4;~9_H@hG!iI8Lo-X|!eC)GpsuE##*D=^K(j zh^ip83!!3TJ=>ycxT!S?N0gtHrdS8364T)WC#Q3R+dpURB-p^HH}9v5s{e@ImJ3Mt z^5e}Y|}S$ z?`W-VtooAoRjNL;AzYPuQ{e7pUoA{B<4WR;@=Hd!7uC#6;IBm=F)^ytm8}8&4ZRC) z)s&OBhh$3|qh1JyZZD)b-4bzd5Hb?to5v?mm(e4NLuc(8S04X-FVZj-*i8R;zLzpIA{Kh?Mn8N*edBTKr>JzCV8runEz9UL9~wtDylS)%0+<`U<&{p1H9Iygkk&(CMf zDhPDKSh=_sh+jjw5TVn#<_f_X)0ZOt1YFcAXxI3g-vYyQ%b5x z|IwJ(jy2OaK4c?LdPM2tZ=#Aw!lDnZ6^Zc1GB(0sLv81%GYdz1%q*_qb{i#Y5BH;A zUL+G$l8go1IXwMUnfCE<)>^mnhB!vme{h$KotSCJw#@GRLw>I6C1V`s zzib1X#q&qU&-RC>D5qE$Y~XF;*;U`i%m2CA{iOkcy0gG)Ky_&;Y~$JNy#rOK3)x1 z#asVekFb4wwCCnN-B{xuUu9+>NXG1l93&c&351P zmZ1`6lTq*MiPv4Tt%sW?04)3fh=elyj&O@<$Aj>TDu>wLzPCRYJ=nMgj2C3^4{ufV%XpX;_2wIGy~xfO``}l=`|j(!5V`i=%0xsp`}>ov zyuLrrVjm=A+%f6-j{W@m_MHW1x2ATS_vx`82y9kXR%Jo;s)@N6>2He@fR=o-_4G`* z#IGB#TS)S39%Eu^YPvYFp>p@R0V8?fe$&i65t=fALi6lL_~mCH;}(srRHH;)C;8s? z|CFHzu@|sb^UMm_VzuzK#^qT?q`jFuNJN2iH@Iwl_Y#j!H_j9{&i=Ig`Cn|kby$__ z);&zOfV4;{f|P)ObR#Gz-LOdMZt3n6DQOS^VX^4$6lo9_-3UmRbba@7pL5>xzTfW; zudQw`uIIU9&N0UvV?Kx8)P^jm@SE(Y5Nen6%Zhi0qOx+#fST(8)>>1QBDH1_fx@k- z>>IZ1i$U|1@-6V=t}n~(1VKHA>S=Bv4MWMJW7UbZi#i?GIX)@#%S06WR6=gihlh>; z0QiPEH2@mmmy>`Fj0{xKE2FtmRN$1y$KP)~2;n$@m-&){RgBXhv5-wlo*H=qV!aJi zGPnKDAJwC8tYCe0qd{m7A(jjm$=3?@UNE+bbRSkP`nAH3A^3cwSl=Mi`J_Gw>eb-1 zhVv?xs-xCc2c|(qCe4zBQ)f31cJ=Le_nD9HK@hF?l83gAwfEviX9(^!U_sacox?76 z<}B9R5rnxa_Z-%hs&;&Q?0uZR_zOXT05c$ZC*kj2vD@bWBl>l4+^%q}G_sd&bMf<2 zU`n4Evl35oTg*a_zkcow;xrjB;R0{@7ASsXWJD1M#K9Z&CHF9^S02u}xG=r;|$$HNd7DNV=D^lxpq(ab{h{$D} z{sdZGP&mRV3tx+G%WcZ=2Fe?@`yQD!3fHKc*{sJoVeni{o}zz2l>htkfa z!&x;eODx$0DG43wdCPe(tk)rWZF|Z^pArYY)ncm8GGGN_rp^Dfs;T!lW=u9Un&qvv zeV1m|jBiMRAy?$uc4_}c^cKJw%evXQEL}sU*YTRnRHi*i+LSS`+9U1CZR)V1;c^wX zNd0Fw{N8dHN@Gri;}Nqr9$BxT@W)u4+WIG+BCUQdZ7zZ_6KQW5r35n>6E2qgXshwf z zk4sh}L?+mex>plQetet=GH&~O!(YqlN+6yrNX-=ckz1p2Jb!&!M)dUwo4pzl6{vb@cJ@0aF{~twdS&b1W}?MShO7zE z<`pX?qG4aIM8aNkHFM$7m$GcT2!0v2giQLFJW2+kB$NKKnLgXE+n3H3BZM$6`kypb z|2<6LQMba!3}@G0uhZi1C#dxG)ZT+k(qZN3pN&#d-m?!9&?HjwRsytr&iLjM0z{}3 zk?3r@>oJFzYC9SxLSkp|7-#Rv3=m@IC-gp5%0z0?O)xEnZ&e`0$c&GP+R}#yvHSP* zNDGf_7kvwKkkRZu7N)b2rg-L+6}Er%R$jj6>;)dGc>;q+j7-qQ#l`KAB-SIh2bLmC zr-DU@o80gfX4n8pt_=i#PZKpZ_Ix<=%Jw^N8f-LvKi^cD zE@QKTkDr`L)gjbhRN^C{u#XCbn=XPPv%IRQ=-VUXa!yoXcUL2KJgLfK30gfoH*rTv zW!@oTS5;!Do#iY)+DcscQ3p7q`Rjk^fJA%Dcj!xC4A6u!xBwkaJEBLtWVc-qw=6e|6op zcq@|3RsOlZq?Pjxv4+J38XF&rqxi|Lyh;>M& zNIL2SL20!av2&@LeUiFsdH;2{FuY@H>l^Ba^byCEJE4k3+pyxv?ZJ_ece8HS`H7u8 zL;OgUY^{3Z@1_p2np$NYnGq0-8vYHF!9Svs)LiL{Uq^a2^i&Iv!9w|IE)du@$I$=DPW z?mFDQOH3Q)949o+Wjh($omrlUR~f80_q zQ-MlHI!RtuxjYGC&qF!a;+5jrvfzBx5?J;mCKg(SL}lt!Ser5R&gTq@6|}%oX<-0r z86HZLsOKWMu+R*&7dVnKE1FdA)Q6Rzd==lvL0|49$mi zxWQ)5cWQdJ8hggETZK*Bl^RWdp4*Q&2NFXcx_t%k6oAA7Vc?L#3PkGS^bE|E$?NFv z$BB_a?c!W%XD(jR;ovNOvCYOd&-fkxV_&GLKU|HtN;xOZR$0F8>m_m>nK_f@07Ynk zW!iZwZP+_dlN5Dt8Q23Igj=s8Rv?|e9dG)lf(QHb!Gw~3bnjLFGIssv`KJ=WD*yhi zB`mB04#AYH%&T6c)D(tpUzL9&$#{B88JV|o4CJ%C4tha!{+{!Ba2yLB;Z)}nrk6?D z+MT>XsO^@9yba^SV2+R+GaK~m=j*0b9Qo$p53(43j=84&p8D|1ofp&1uAdA6a9Xwu47z>Sk{W% zU;eKJWD(0;`0+D{1@1@c<7c88>&5kJyG4l)98= z{l`&0=U`-HDC8^tduWXt=yf0XWb43W3dfNtO-S=!OyhlUbBLw1~kg5MgP7xzKr zp9+aIGUsJv^p2$+dH!MzB|Y2O^`SLQ#h%F)!T|@D~%c)*b_T1#Dc*K1w0rW80WWVIweum4p- z1<$wA%1pvkX-86vVG(e1GbJktl^EM8F)>xE6lBE;bQei`Qxk9D7ZQl1HY$=ejX}ah zecK>=Gs5Ay7iu(D_3`Zk#^bt_@A&xK?n|5nrn%{)ftPZ3rC|47zAdiqR$u_n^11iV zp9e^m@F(D0X?|eE2$^cwy^iJg_5s)F0KPkGoV zhZr+YabTV?%k--zm>3cSs;y1oR`5~z1_xzuep-fx^$Q{T5geW=Bajux1aP#FgKg1G zNAmzEn}5Af7wmow;-C45j-x};NZ5c*knKYYY7M<-9AO>*b>_P>Sg}jpqB7=TgN^r0 zuxIh`32PtBp=a1}^joy5KY3sbY*y}9W+$|9U$Ne}rnsu5y4v^ovsjUTP1G5eD>ooS z(@Ks>>dRI7m88gkY*J4cgGx>@D94^W3&xiCX`3!C-h#p}wcsP-3f#2KjMe2Z(U^(k2%21l}At&KpWUcRCqL_z@|>FvA=k$hw~;TF-t5$+J9 zAy3;RgKA9Jc1asQ8UJAG-rHHmB)R)cv|VoH5X>%~F~N3u^8-qCov6u60%pWzd8DrM z_W*?Z$o+F^cM;cQoAh5O#_7KiIA4addYMsk;w}%3V!yyP7-1pQjlq#_g0!PvGYk?_1hxu{`lO-lnz_5j2yb3HarfG&c?wP!`>7TQhN0l%_74Sq50dbFB zFog-k#3q1tyG5V;gKpfEO)I<|h*p+Kqdtu2zLmc}(!i1gq3Wd*0LAp#DsMpFl9gG3 zWL0Xyl2!J=GuI6>c!2N+6pS1zwZ4if)~d&wE@>L9HZ|mE9ciaQ%I&UgEG1uG7?RL= zWRYuXGv|-m#)#$^4g1^R2xrg2o36LB&nZ&aTPFSLy&`7_@bBGw&d(pd-FV&_H<5(ytGYt(@^2ZkwelD0{}3 zOxz;^ms0ptt5t3hHYp%s&4LySfE+wf#(pj#M{ z^sZQq-gLO-#8`4@O*Y zo+k9TP#xTxbHNyQb3o1hd4LsjF(A?lc(q5o^xFAgCS>UJ^tRJ-v%3l6IAw>+`Q=lB zB-^e3UzrOj(dxPI4$)A9pcijR?6i%8I{U-H;mavE&!G&~-U#v#q)v?>cs|PM0yK`UGU-*&?GNEKvUkF=?LK* zl?!_`lmBKP$YP!XHlAwJg>uprl--ZBM^K?K^!<&c!>0}^mRqa@&Vkcht6) z<)oy3>XjCGp(=(cs$bM1XY0rXT(@{eM9zq-XP0+MF>@0iJ1G9!L z0Zu5WAjER|cl)ac7zL(5C{L3*dJS<6VBmE7uw9lgI>+{CfaDV{0y?(QlDTv(RtV_J zd=&6{=P3y4Rp!r*JkpDpQ@lkX6O=Zy;@jn0fG6+7nNmnq?i6V4Nb@~t8N4Q$DX?*REsVS2; z+8M)+8N-CbiuzskNsMp}P)UTX_V#-0x4b8QHJ#yNNiyKb*}{pXDi<%8?-|&DnwLJxS*4d~>332_fK>N59Cu5yl}h!>+)D)shM?zK;TbTXEGF zMpr>D-2wmiRfa4ruS3*X#tfmz;_HxzR~&UeGt*t8%i)GN6#m7^486l;gMpmhfM^4~ zBDR6Y34J+;(~@$`d3^LTu24Ce1(z2k;DWHGZ<;{2F{l_m9+Z<(c=oWi^h zmCirSKhO`g46NiVaqtBU4ORslyp9cmtDBO-2?@m00X>+CLPVcoZ|>}h54U2QB#Kki z4&bRw=QTSDi0vFZCqOdYwYodE+L#)5f-3(4GC6Ro+{Dis(2z%pO)<8!7BK8UI(+}? ziBAQxj0qh)@^87{W&)0}i#1=ZnW~~>VVrHuHnivfc@9JPgcp(;yyb|}hGV9sF2MIb z0qAC6*j2nv4o5)$3Bl-G>aVr65h`hx3pFgV!5@%atx5Zo9Al(o0jsbHv#|_Lf|9TJ zAVMnaF^IEJM4Y9$UqjmLux$HJF{SuXTidvfg)CR;K){0wuLMEi{7<6mE={OvO41&i zV@oOLEKi);d~V4@sRmU~Q~|_@WtwCAyIJ1Uw-~dv;I9u)nWiF>C&&Ftew}*NF#eQ} z>3_ngYP$WQDaemI$THL!w!Usxs+(CulTUI%uV|RY%W|MBXQZt`RnKr{&7(UN8+9tg z1e0LK>w1}|9Et+N#>1r#5A{OeY+Y-&Q^B<(98d-xO)ChKAU0(UCjD~0lN7^&p(%0h-4~&2J4Aurb1y=f$35UOZjEp(@8J8Z9+0b zQ)>rTl&pFbH)_Au@JyTyvyQEu5(s;novX$dPERhp8o{CZ#*#J`*4uF>W)gz2Vi?GZ z`i1f=n&O*CD{5WKQgkz#D>=5DQKJUoON=2BYP59aEBuO8+cv3s z!PD<6n&Bm*sBb-&eD_Q2>1&3{#4U) zE}s_AoGkN-SYp8`?kv6!K-J5#IhD^zhKUXJO4Ow&qnj@LPQS1&yhZWLKJtRYJj$e_ zP+B-{30ms0s}4I;&wbCkXq`^B)RDXw@2jR(yFNtc^y4h~-Vg8iy1Y1Om~73ozvd4M@%) zCWRufJLW@b>O3W;*MHkXS83i3_tVw?p&ehpA5LmA`WK%QJXH|7d23;Y zlk?(dikD=Am!$`C>!ge|^`1SY(eJPA)^!v#0y0ak^`~26Cx73~o$WKBH9(tjK0B*K zR@jIf8iDA}FMoM7Bx%5sk*Mf*L3vQH-D+ zD09m1DeUg8deAgLVsmqIU8Rbz9I3(}?B3BP{xwvjjD*%oAeWnnZBdOeURyM$*X=l|G59y}=#m)9 zPT~XTPbl*zIPiv)PSJHr?RD92$2dwg=Nodg&Bz_*>?5@fOcS;va26QCP6jiKT$&!pHKudm= zpDEv>u1oG|zUPMaNf<;VHyQIhILVrr`$L)3L+^p!y%O6pETd1ZN57asf=-e{UsOn- zWpUch^qW>w*D##Hqv8*o0Q(s5`+^D8MSOI#oX0P7=Eq|V!LUgzT`5EdRVW0AIshda zPA&a6@DhTvI+Ok1oYh}Bg0?( zP{!;jwCuqJ4~$}BVtSmb=!AWL4wu8NjI<{jlT?*MH2x&v72tLK#_szU2Z!n@1wDzq zXK1+OH9xI8O_>8K)rT3G*wCt2m7?oU6{;gSi5*9sL-OjT=>3wZjQTASOJ1L9?^%$f z(P51O5+>hLo0ml$2^>FA@FFF({BshLZ^6q`*g6S|A~L5izLZ%n*o<&f_Gx z9zLHBThNo}n2>#HLK+U7L~k*?xX zH@6Jbh1b_3cfvr|??+fiVuNV)XeZ*B8(P9vYlD<6YV`f#v-ugk#tx}EH-); zv%KIQAEQpxwf}b0H#tV?=46_h@?B%tk(T_{A7J#0|FxUT0T#R+luAZ}yFengY>AI5;t2fQ;s zXo20N_ptxJTiX^jD3tdU*CE&ynxN;k%l@iIhT*{3=!FVUIt^zECCbe^!3f#`$4jYP zGYRydePA^J_(7;?J8Yd)lfq$G3bC*>cP)vM?1L7zJ!0vid)6B}GMRTgP--J0Y9_|<@>T}pkqRf76aYXns={lp10 z9P;$z44J%N;2(Ap|@3ce5gJb6PuG?go_*CI%ZP`P?nzF!kxQCqqnT$cr zS9ofZm4a9L@saYA-=RW?CfBHLYQEZ3E1^bQJVa5$JGE6-90}P%HB4PcJO|}%=hYL2 z>~}1hIa}#?8!B^~G~9xFX`^_f1wk^)n7;hxtOs4ImN65A7BTx*)#&o3Fw>Gjv3)}12975waFX389DWO>3$6in#V`xpxPc1-in98C_fR>Qu@@{KoNZb7}bRI`Dr z@x#cO2C|5SJKWybIFMDdw0j$ʐ^ChXfc|%h*ZBw`!B2mQDYMa|3Za%H>zk20TmCs1-%lZ(*6i67$9jRzQ9VGXM7(AJv-s4-nU+7lBhp} z4KqyjI)20Iv1Y2prNL7i_=N<{mKQ1%X2@a}L)pI~-YIg5@sIo*B>_S%l+J{7DJdz0 z!qGP5@bJ)GK>NO_HW`>z0%5laaW5M!_VeMMfJVzgQKpz!vr~PxhX);y@KvfwK|wIDcZ@w z!$CQhjVR|Dns>#{dL}?+6aMOn6{{9|O1}C>#5-dv8#q^-{J+pe(0}QUBY-Li5|L?M zrlGMjG3mOw!r;ye(bv~0SW)BuBozLx@I1ueoR5ud4rF8yT!U&Qc{HsoEIzHRadmY` zA$kAF8v)rz7#9~8C~bj4k;)CU9>R3vZ;>`7&;pF@_Smy9TeHnf^8+T7XIr}nN4mI_ z>J;P0%if_B;NVtqxqfPU9<^6{xee=c)JJF-X6Fb-iRLz z-krBORGC(KH_7>!M&!m*h2E!`rj(ygKa=zabNjCEhwmlstLbO}ls+dM2 zW!k@Q4A08~8k{EJcUa!vmMUSoCeY{kIO8(Gjoqgh5LynKDHUr#(;Oe)V>c)T^vqvA zKTVE7uIMs-;nH(wB6Egp0xzeCL@NVGOxW|ua9(=N( z3#sefMc)Jhzw<60%AWe&#UM^R)cj6u^)b(12g^Z&gM$v|2NFnt^%zXIZ+)P_Jk1N- zLNA-`0h#EkS3N=TBrs3IA2tyxV4e3_Y5tAsnO>(V8+zy4zL!NLIirGtwU31(znS10 zFegq#gyW{Y-~S<-->B<}3d=D1F&4RG~O&a)}RqGczq3NHu$p4suLqPb7lcA z){4c|AwD;Xk}_qg-Y0ga37G8IuT~C?FwzM|Z9!y$7SIGasfhD|=n(8lB8Z(&&r-N@8#d{Xa0MI{#f=`+%R&eJ&*&gWXA zmRm2?iy7qtCUEk3)tFF?uEEL!qkZBXHNq(m%QoOogG)l1T!}?MQLh+WpF)MT) z%7sSfQW+UWV33e1a!Ct8|GtJn+o-qXb~jvQs!k6$tTNqHbce$q(y>&+lD$~0fk58g z0|c}Uj;k0zYKby|p-Dig!vM@IoB{&a{;T|lcqL4um9|2Fn$qSe(J)WNh}9R-`=MF` zud~acP)kGKu{%H;r8P$PkDEYVrbqXez~rp{#yIUyxT6r}#y1#g0aJF1oaxv5!OXYd z3x*B&uA7VYOjnsRli&aW4W=Oywb;`7ik|-M9`yR`y*aiwftHV*4klV_*hE_U8P+9A zTNn^-kBHp~13Puw5OAiS$1I-T1DcjQI|TT82XrG%34pz@K}L|nQ$wf5oG4yrt{oHT z^yxL!`?dgXEX_6SpV|9{ch4pTTo(U{?Za)Kt1%KOFTBiD$ z@4tRM0Yb-8G;5#`$|#}3>U{jg?tu8F&ECQ$I%||g7S$pK!yARG7#(e%j@4>paudi1 z#ltv-B8$g58-iOg;yAw_X^BX@!$i((-D2}!8C#ue^kmjo%vV7O{x^uT&tG0s+AlQs z{rEuyB+Oi%(UQDf=iia_FDGeDiyj>8)m+$pCEKbNI`{RTv|D{YV?j;W%7s8M`{|i2 z3IMfc&nAt$7D@*TU>Y{yBWo7%gV%ztQAa)uW4P#Mt5)s&2kq71h&HufRF{BSm`6Ew=LI1 z4c_(ED{m>Y^#Z>Wx@c*+n=l;?pAy3f>1@5cDpiYGHsZ@dWC{E!@Begr8_TwE8hbFn zz1CX$tM1K zuw2R+>jOEP<$RId1>48ftMP*vyDUD}05`7iVfPc@i}r~JHthQ&$AE7x1Y+^Qp&{p+ z#xOp-)!}Lt{!J!M{t{rTgFneln(bumem^k5j4X6<|btG;`f!|Nv*(6 zVdCRVg#@{LPI=IjY26>Uf`!^5_P~zlum1;p3rPwnAWk!3ScKrheFq_wSnSuH&)_Z& z;ocb)O~|e%*o+P=8w38zdHYC}7mxpPT__=)0LJgkXDjzSCczPXs@NDEx4}e~tLC&S zpt+6ykA@HdTnU9Vhx?WFiY2MZo|5;OA3OfeMJQpu-mwFF&plt@a>j+dC~G;T1TJOw zh*X6_#q9Mzo8$GRQ4?u?mxcQk%{$y&N5VSkJe2sU(L+zgE(WfFA(iku;R|A(q5HyR z-vHgqlr&68Nca_A{H0)d6~l~5%e6XA!G-#di@550{+sy1^E!je$4^Hx*0x=9= z0Wn~40j7}XXsTt!+h1bKjYj@v+GKv$y?%J@4bFF&cL%h$1c8PWaSx~X?2U(qjEKHj z^E&*#_E@;#ZASoET$ z^UXJ^m_o%5117H%MHIMQG}P##7UOKv}zJX zgMUbPron_~bLBOar^Y5JYXAI2Pnv*c>^nlVW%w3>;D+1`I?f}vOx*UTT|H}g19QIn zyz37VfbpPk+{n<--&=H~vlE4wm{{a}4Cts9jsv?0a2#pr=zwpd2DX1YBP|sQwhe>p z7>T<@=jW3ObKvDy^A^DkP4gorE#4Oc2J4EzfqT)^b|tiRA_&~caRMGkPe3aa_5!$Q zq^yU4w@&sPLgoD<5vuOwKYqi7omaO^dlN3CC=z0nW&taL&FzXl0;|PkaI>YUEH`Gs z0|3BW{quq4F8VKV^2;@8{1b#`XRR@256i}}_e);rSflI`qtWO?BPQ*}?OseX^;1$( zuAKSqpCJrGD|a$Lu5JPAGpouFa1Jdh0&Udx+TGhGAloJs(kC&NuBz@|OR^Q}W!)R1 zq^90pJbi8B(&@*#n{4>Y$YxTEG8G7Br!+X5oxC|RT@c`xrf_VmLQm*D*MBLMOI}RX z-p>-YIcNJ{dN@)*`Ug){Ih|UWk|}m|rsJ|L=$qtlg29~#+tBgG$RhXmK+Zv6L%_qw z=j7y!-X|}b^Z~o$$o69sMUL5Sp~UI-8rbTJQ5bbzIliTUP>cCec45u_2}vmO#_K}i zSvz8T6?co5sSwgX-&0QnHFl-25jvm8VN=8ucD#JjcH4G~@#^Wf^NG6F9=^N7eG9)T z&}*j>^UXjwz^Oz$6I1j(BY=zka0^;?R8!^?V{nmVusoQ`4aE7Htw*GSnfT7m&f-%G z1afRv@|3SpZ8aX!;=@YHD=Q^irt!{BW?zDT0^DzC5`-GMmP04olkR)(?r_A`REjhN zT(7Y%Y%oU7Qd2YISgS^tugl6|Ie&p3jbQi;;lk|kh}Z})I0H99^W8154~Si(g1H+s zNWHPttK-?XJc=SGBuGG~VfPfFP21rG!l*nmw@_Q?;LPydXwxH#`%MFXNtXaz@`Z(3 z@xM20+f9}B2wah^OIMEj5NQc@cjV;31|rEFX@m%eI8>Xmb;CDqgJmQDw=q}1^A8jF zUN%=yP>{$OE=s!FEV4@VY-CRlZ&1*Op#tS%|9w8Bgn$6HhKvDS`)3DvwDTC^*3$NC z>f%L-Jv=_XdmFx?V2VMC$7X)qVS3vIw7#@!Tv4pU?{>tm&+md`v7JYREnkU}C(Vtp ze85i&4L zIjzZEKj6YbLEtFLn1dAz7^&QaI9aA&;4GX^c1$-j2^FK%!2H1c>A{SA@xXgWTUPwC z2~|r>Dp_rB3#UkK;6Hqu5Yoizy#c3P@zOu@UG`~Fz-$|Tbl}tM7Uc$QSdRFN$Z7+X zV3rlanOx>~vt3dWOy0HbBmnGXAdY{lWP?mHqz_eASO0uZf&feJUu#&(D`s!TX2u_P z#Rb*qD$rpa@`DDI9kZo};>ZywlONH9eRbVeP-7#))ckKndg78CR)t^7(K_q(pRsH+ z9r*;ykY{HIi5hSp1MW7$+yZVTK=;Od7iQ)$EoIFq9|U3V>X-B1K*u8}>@%^E%f}-o zMt!S*pY!7S_bWbat*6&$Kd+spIq?G9F;Vbiyu(u)`1(+~0NNJ_hHJ0)Drd<)vyM64IHdl!J`-#jF%U+vql~!mT`O|>Ic9Man_IZ0O@$6!UkigP*TwUqps3G; z4y&Jsk^w0(&_-D(`}VSPinS(idTNgG8`taK5bG|aoW*J zmji>QjO|Ob4hz_HD~)@cw4Y+@kT3^67Du7mlX$nc=X-16@(xKq2aTro-SyXhYXRs) z%ZiH{JQb8brQTk*F516&^YLA;P35!(CFRHHn4Z*B=A}mT%4zn`V^}q5UB7-YRcHlh zmAq9-;^E^PxH#U3kjd*d_H|!hskmE`5Iy$FeiZ*2m^1xi!i_$RYyhF%3Q%?A=j8<< zsD_={y0|Ly5iUW&{#pCBA;hokvbNX_kC%_*qXJ9dczKQ0F;N==UxZGp_#G1;Btxr& zueVB4?@r!7@jIN1=;S6hRmP zc|=Wo|NgZ27PK17*ZHipjiLI9!3i4`)eD(-2an+X{dnC>(-#Yg95*Rx&hVMEC-IyI z&1(XhA%VoT*lG?8k1O43sZj;5R|_5wX8EK1X-4WU{(uC{5127dZEYo+na$%Lexj#m z>rV58NOm|&58q!dpXHFOXei1( z>y_{xQN+uyYW>x9b;cC&<&D760(z?MqGVCa(%{2c6&`C;c9X8D85zIc7+ezR*4pHP z1%IYnTW&f)*1rZ^U*pX;r?ZGG31%P#fiCL6a5zv9mP|QO5%e-6$7EK=;}TcJLINa>k@Mli!lpTDH?2R{v&v|KfY*Y z?CB3mcm!L=hkxx6i*{jIm7XUUdYLQLy4s zJr*|2j#Y!wFJIbKFV)#7D(*)fJNYmV5*4X}DWrbEFJHba&CbeN*lx9Wf>l~;{~oyI zzqBpdJG<1l1+1=0%e|Zx_h9;0_ztH#SYuxe(6{+%)|_Z8P$BL4N)Gi7MzLT!DyPwk z)KYC~Uo)<9h-ztldPJ0J?&%r5uz;VI{;X143?iGaQeQf-v%?m<`r$2Ogv`ws;2Qwn zp1KoG8O98Q+g=CSg0oJ01m($_36wWgmW016l?C5WQt7zqQ6OwWQwDDkT zdujbLvhU7cy)IOlibB7=gep4v8mAo-lefPs%Fi`OC2dwHtR*o?id2(}>K3{4fXE8d zU@m2O?HPea0OAOMF*3lX1oY%u$vyAlL}WBICyR9>!^7u9)$(0e!5(P;7$1)^)sBv} z3eOG?|9)EqDhhg|q4tB}2dP-#syH^N_5y11w@ zlj&X0nTOITF{czhc&KZ#zwqoyf@7t2*!nt#N)bPh%n1nvt*SkE_;7WpBM4|VKlTA6 z9BRWGwaO3HaulG*KN-pBk5oBdS-FPSq-}Tr4)fq*#4l^a@Aeohzax;+9)NjsaV=hF zK$-d-49&VYySrTkmYDP5_pMcz?4A83N!PuYDajKp8C6f2$O@P$A(=JQzu8kRvT5&XGy@S|H<9~& z)IyCzDVTA<+pT^H4WEH_fS5(ErbmuCaXFM=8eIckUS1yO%VC zG8xA$uJG42whIF*zdKx6^1j94Neb$K(^QL)tUj{U9D}-E#P{|4 zYWL8QLyRbvT_u{@4-akGFg1t7$A295bR>=RlrcC3u&ADs%8=$bd!_-4nvRaH_E(QT ze|DDruH)JYq1GJa>}7>kz^ zb>Qs(T{JNHhe=OQZ)c$;eFL0Gq7L}c&BcD3JS_Pe!TxoF-Vp4)!}5+;0){Bs_4$#! zrI^P@F;REU<~TK$p0eAmvLi5oalG63`LMyK^}F-3J3gsi{imicob8;_P=)Ha__ED& z)xJ4XLna?3zb20P#}SZXAPhucsV z|7d(pV%ApxYF$*+t3Q}BFJJz`s9?h#uxc(qf6_o@QuX}uO8fZ+3sxzF94CY_D-5WL z!y!Qk;4ggioqp={@!9+twnFwE(oDrJuOWdoZfU!Hyk-wU1yZ1gGWjR8$nzxa-Eyjz zNdrGsn8A3klv=%HxquCL=P}@28X5#A{(omJTDC+-}1U$|h=rfC;SMsCs{ z&<~K8QbW*V*;|qk{^ymkSF{W?an5$eA4hyP@0QOG->I>XuD~g?wjF%0QEW9rr&Aw5 zCOe$yUt9UWQ}fFZrL90_ut%Z^uJ6Et!_ z2kO~Z6%^wctoP%gSS-LIpxS(HoVIu~zYmnL3`=#%wOH#^42M$C8cfZBjlvX#?C$(H z?copK+N9SwZUe!nm0tnF+2;}EPJM`K`-{f06kD%j=V&iyG$&6HfnuN%L+V=)0EugH zZES5BXwGH{72duLj;nCpo`~wq2Wm08dL2FaH4mEk`FX@>4CL#jZN%htBN-L?C>C)OH@#7QS&o z>KAGh?A#9$EN>8CHV#*%!0E?FoPOeJQoP&pa1eK50B9IEYdu3L7v8YCatljN{`F#{ zf$~8S99>gFDPKVI@#6rx`lAiVe2tnTT!C|AOYEjFXUj??5Ndg?ttmw%$kSe=dPj@& zfVkk>&1ESLA+mzsuJs`5y{l8;kpGh5Kok{Jg! zV$OL)1hhtKZD(b8)7LsMX@9i`puT*3AB;-lcU(b30>vO`nB{`+LtYQ>U*m6#WN#qK zgTANP-LBSeko8Bi#_Weu?8?u_LNT=P7LH9jj)g({6aXrq{U_>sLO|P^PTOG3p#YQQ z$-=AaIS!Y;M@CM5aWitm$4DMoA1ejZDbQhANhGtZX7}Ca*ytfQ_=QS)j#OZI6rt!H z2nbc6Wqev~9vVLn0w>QNZyR}uh1@wRjcish_*mHBZwz#1S|gZeO(tqB zyY2ZXP`S=?CngNe(ZOMqaX#+Z#ptltot&I}KX#oDEXI8aPgB#D!NV3nnpN97s&$&+O2_Fw~ z<5azTX`=dr4R(^p`Gz+p0QoMeB@nSA+Z_K+%J1K&m6lq}XFy}27@8?r&Za6XMS3~m zbG|@l3nq2afpZ6PC&_HBCZz3MFTSUj7oZRk_ynLoKWPW_p`E$uZ<+7Ed7Mrw*fgcH zjx-!e5w~fuDADTZQ9*2{jh8&$RoA8XKQD&!F{ixwWESmrwtq_vMjCNko$k^TML6_Q zzdry|<5CbmG=#%DV1Jr7Lr@z1?*2P*s!w8W(JmDrpEUe_feD$+S7HLwfxs57fLX0i zvPZ(6T_c&9nSIL4%+Jk5?sen`6b=|V_C<~55Wtkt`T3#bXSx>F)~gpA*&7H#QuYZ^ z^Z81Yku(`-ek16?D1+kVvu$wU3RxP*zYR#3W37_ehb+eF{`b_!_1V6sHm zs3W?-6~e?%67}L+ZRox1nGr3Sx*^cwv^ORnG}xl4`#c!9Aj= zo_dGe_T{dT=fZQXF1FmE@tqv}{~ud_8C7N5b&tceN=PUvp(u!elz@~V3I-_%o7!}P zbSsU3f}lu9NGO89rn@_(8>CwaMUbxlI`O`r=XuBb8{@h@=-9$Ok8>R>=9+7+a%H%} z=A}Y~n%B&zY2MaIYiZ%Wy))D}_m-3_m{x4P7FC<*GhfaHIYH%mJ(2rQS>0JcIu7fY z4zWSe=p08fyljL8w6u3Lb>dNdJn&RXA>QD2524W?+$`y&6+@;urb+kkx;jaupJ={+ z(-il$l<&|GO0J*yJ|?ODt7aC67X#RfBsh*vPLKueZI{$^_VhfVQI41JO8E858mszn zf%_I8pYKXJly;Dakc)$!BQg|Q_@@F+dT%uGNCR}H7@=RiwOI%m3VdCdZU_HN3QCZB z`@=PilfxEu9t7R#$E9e6X`xP69Xcnd zvqfvNBp_SygRFDD3A3 zN*D&Jmo1aOah3rpo&*7I|J%ah+}apJvDK}gzjs_-;;-TOO=qY(M#pU~X<-wSbSiN+ z3wb>MWZk9u#BQ*w-j_XF%4n0FDi{I`)E)=hBpbtCM|^X0W8QaMbz-}^s-&2C#YlCY z-;mC8y-oH~T=Jchl|wc&d7zIEzWCux)wsjkrkcImUNWE7StYiflCEpjYz2?owJ-uC z*wE16esaJK3S3BV*xv4&oa{o9HK63}frMEtaQDHw#dfFt;E>_6BFbISadC#OuF-GI z`HZA5XSJGSlp`=;z?9&rA&O0^6o;^<&0eSXj(!rOEniIN4aSmRAsPpROlE2sj z0s>9r<7k@gkD@Nt($SQ`P4yO;`^z`FH|xJ~b#H>NI2=$sx(EuBWMB~xV-*s_9*ZY_ z1^8rbtfYT*^xWembeHSF+WKs$kq24UUV6ZiVyn z7m+ENrg3t;+zI2qlzx%w)dP|sBDc?fgtDI|YjVxGaYZVV52uH{Iau@9bhssUxPEm% zgcDv_cxHB=GIsO#8y)Y*P(3If8a{4#lf$eOH~RbDf63u~z;(vY?>Mv{(+PqD+%hW{gTOLEb_TFwk+Rs@N^h)~X<;BeA?0SdYxj%U z!eYVopNbWSlfUt=JZkUz6X}Q9sp`&ocgOyVkAYnnAkl{C(sd6kx=XrCJ6R z-db_zzt}kkf!}RDOmw8WigefsJh$l{M6xxW2yEBCy$|>1uS-03ak=d>;Y59^DEIW~ z(@GFKNAhS8^Aq2U>3&&)-RkJf2LWedH;dpZX9*pBVqEf?$8SSt=O`n-*Gq2twyN3| z>C_O59G#u}1_q=cjf0To=;CtWZ40m%DnUgXH1Gn)Y)13_9hSQMmoCUM-IbKBa~Ego z8VGuj46VXBA^5lUKYFf!&BAv$&3h23?S=z4Rb7FEM$`R-5$Iv=H3G9gQ2DWQwfmZoTVw{(QFk7%Q8pY+z?i(Cu)8vtwo; zR{U7@V5zMG4?wrl6L7z3H)xNF^#ouZR(Rh zGexme?CULFV)aZXc`diP2WaSD1`xcxhYfOV{wXiYYZXr%Z=GyUnXp|XKA!VB6kqC! zUj#K-a`EjvPb?5g@|uBN2{@yxJ8dR){72f@=@BO-!W0_i97#|fXX-rP?7aQD$$(># z;RveD3#MHk^`YTbxwjbCe!DUVZXEtapT@o`1V-M)ug^i?fW-bw|Iht6?Jp4QK(#yK zncyWI6lPH9#Wp91Ub{dTJdY{Cfm{zeNjV(}si2L9Eg=Vc^Sb{=+2hG9cmb0<{C8$*h{xdi)vf2ca52so*A?N!QI4j4V9LEU^9Se<+?9b zFhD+;ANJX^8Uo*%d2Opg!Z{|RsK^~S7sVEbZUK;n3h)%70F?DIlpZYKe^WwMsx(}(;p4tg}{Ynn^ zdb*;3Qr7c%`-akA{5+k|&0(6Z#RhIQYucc=B5Q%S`8Kv^wA1Q{%Z(4Zr1vv9V2C9J z%>|pqc0u_BPNTA}ox4UZT?OZG`UjG;L+*lB@-JkS%_8tC{nn7vWucu>PiSJT{TL*Y z)H(ZldhTAMxN?d!{#ag~g*pJqS>`wQc)Sa&;s8sq%&B?+pk{gm69rv>kN)lq+3uC6 z9;I-z;4&a>JdoH928Fv|o!)zXR$WZX9eIaTS{ zIHJFQ4~3?ACA>pnO92x2x8|`3BjGBf`5ZVIz%l>+{d+yi7sl&^&WFxrni5bk5=-Y(e zDdR42b3| z1pXOIhyWi&oPrL1*CdMmt_-iP7Khxt>1Y4fhA}L3>2x6lhI{VX+?TtV(SVW@*I z^qp*nwa*AcKN3t1kc}#M2IRo)W*dWAycfKUv*7DJe9LI;?*0+9vLh!dTo4>WQBhGn zW&ln^R+b2KudgS#8fvH?njxvhV4e1ruJ977sUX?rpgc|bV^2mR-Sz^%}?z{CxFE2M!9+PI=>riGfj;yNX5Qr4m&sk5Rcp*TpN$GcXRiP}2m;uEl5{2hZYh=^q{pMfq82(= zh;so=3Zsx{>}&>O1X&JEI*86FL@7tJTzdbVFz8jQNkqGkvGD3-{Fj{WYaa}oK4N6? z)zoaL&!+T=V#>?u*61&gmx=YeU)bGD>4*2~o1RV=S`Z%*te6eFQbV;_$ucW6fQ@d0UAi;In=p{KtVDf0(} zvTq3s(~2i7?OEYz55o%+tCZ)V=6J#$`Ko2^qmUgAd_L&Lx~^r4@;Qzykja2fjlw~A z6}({BaDs!7VPFhFUkDI9WCI9yhA)OR)3+bv$1(kR`BpTZi4Trv^g@9ZZa;T^HP?fO z4?%JI?A~D|)hnb&V&Kbuv)y9gwlnw zhqYaLCnrHw|7w4~r_-qBKndL;+4`K*@Ew6$4JC_LOATyP)nGknZ*aS z#Oy3{F4}HzWaN>Jjg9LI08_X9;3M6etv5-sDuqhRqs^Q1)`Smvhz_H3$j5$RHAmg9 zJny^AdGjJAIeFO@90r8HjKU{ipdGcfI#@*<6y#xJ-}+*99-ZF+Broal4&T#EfRFE9(Ml z93*{Wb22b+5grH}>;~*8L-K??^?3+cYR{TVsCvyJm=5xo=8g}3gVgn#ZjWCM947KU zC%aojlmJ%&Cd!df05|%z)a*ugOa3nJm=3uS_Te=ikvsC{D?{t~u3`!xRU0E`4~jVO zB4LIHLJp3nu_~k*z=_cxs|A;;#7V_%kwf#+NHR`xy#eO^nxUDvwzdYSI$RZm?U(RS zB;Ev))<%Q8b@5v<#7u|NXGV*yE&*;EiG~uuk}#VKL`;Y0h}c`+*D6d8mahy={rGVf zu!^FykXg@DQN2`;bBl_C=tg#$aZjZxBuGomZZ~@lYm-E}(1E!WCqE3)io0WW?UMYj;-&*d2P^ z33n<_j()fB5ObkRYuDFpC+<|;0>g#2FR&&{H@ifUof)ja0uwYhHvU!W~6eyTqXeZN92WTB&WGvv^_~Dok-UH7U zY>8v7<`zrVi=1!UVp ziG3xQ;LTn^%oK{h0R1PNRC~aRipynQ0h|2?^;cC@xo;OF8e3QdeNFU?g`VcgK~PJZ z5#P8a1St-#Gc}P4=_;SqIhENXg&^|)yE z5H~QWW==x9YV7D}^wiyxqvO3+l(7at)_N76kP z74J~QC}`P^OCGkxbL&tzkw3r1L$;ZP6Svdk~8IaZebAccV-Q4q@wuVH3SrfLV`K$QP03Y zA@h@r9kuxQ!^E!&S*5F60R+bx1>xDMImX~L6utKQ#g2F9fP{$D>_Fw^$bc>oKs*Q` z@4kBELOB;$UkVDNKkRQJNmS=5#;6n3W@M{<+dUr0oh^3ApvGz0b9{6F>OKD;YMAGR zC187m@J|<>ChlJZB{~qs`UQKhT*aUCZx+tsA;K1|n!$?YG6*M46_hlGkiM0s+1$zl$L&H}M(sJSvSq@^bPIq>iL za9A1AG*jjT2A62u(OtGEsrhJGHlfr%|D*3P6Ljg7cV|?p_TRBZKXjU@$FC(#@wM{R zV?VnD>0Q_(FwXm|;a8x$u0eHIeXE#CjVL{PVM}M?8ss|I5*-^gHY3G#l+AClFmo+| z|H(Hz-v-0WyDaHV=_pdcfP2$l!@m9Ocf!R@w>7M>`R0RW+9~n#cVwwoaVGI944}2N z7_!fDojDHmpBy@B5zR7u5luomHor-boP7R|YkBtaw?uRM*V2n64A9!XS;HR;><+bb z6)578F_>VP6yGH`YJ4@H{daI_dV6~%!RsrptB)c} z5-=EJsNF9NLkA}rhk1TLzAvYwDhfaZaMERK8HJD}-Mqr)ry>xA6-|DD5w{rIP7f~{ z%ej8H&CWRnE`Hcn`2Qmp{a`~)qoOUD?s%Z8oh7ZPm}6oEfCQlntN~dL=IVod9E9$9 zh#?k(;XqG6JFOb0#-0P@JWESyP-yAoUfZalUlSFuDgq*I@6Zqx%1}EPdd#{5I)5JU zbdC;E�NM;pu35G&#X?rFzIZU_H=p2e2NJAI@2QkSpJwKvEHW4GO+Md7(gwosp)K zqamV7eCN%LbrW#!k?oR#my&A|ZM#%0E#FJk*J=qYv8NT6Keu&yQB351-S>DLlJ6~K zB_~C&w#QDxva@H+mR3y@Y&(>O)D$pwX}$Xm8#ol+Fl3$!%}po-LEOSstm}fJSe`*# zQ90D!C|yU~s&nI2j^Azc&Bl7yzh9Cb)PSFRX>3hB#c9hXoO$@MhgMz4vBdjKiB01R z2T3FvhriIqhxo5W>lll88H(sGhH+GU{|H@cb}EL&#lvYrkaP((;4Mx^Wc9M9si3ai z+xSo;$6sE2H&r*!; zp4F!GS*Z&+gMEBFEO?<@+~BI*x46E(Su1%M=^-$Uc!Bf%AJy~Lwo<#D;Z=^wdL$K* z-@mD9(ndmENI5`lP)6a<)kx2mr)A|OX#lGO37rGi)JzdW9L-!_La&XGe=RHf`Mz#& zVG&)mt?A<`<^j48QlEcG&c~{w<^m4+5OkV@w^QTUr9)s0WnHu>1iUqSe#o>EEVNl| z>bdPz&uWNXmsr&Yi_|Q!ia&mGF>VjQ;Dm;mo&nk`r z)J(AHCBz$N8XmSTEe)z7d7mITp5`ShB=0M`^4}z7AvU^!^&@WaY`3@qPF1az-t94t zV#=_w`~TPHpBk__EXH_ZTQBINMw$)lTAq)+;wT5S%33;=wxxI}stf<=6}r5&^V2{2 z_AYUZ%s3tH_AF!I14e!sIem0ABS0Q+y;(D*qaTF^S+m~$ep&IvVQO8shaDf}SN)2o zxWvr_O8X^7k_A(f;Z0uxY|(1!SFTmuW3QT;ja~aSoWMY8EE>AlWc4?8`+x6Ee1vog zOg;Zk%;M^D@VeTTKz8+d0PSgLgQ{v`L$nNj{rq>%Gnyry4+X$KPCWbTV{dQy!@Vs0 zsf5O`1y5R6Ic~ETPgk}e+=Edzd*L4|!C~!r{7dX^qtoos4g%sjMy?~QiMMGOoWNfW z0xJkl)Crz`@oBImSkTsAR@w- zwON-cv(nCGdo87ZwqP1tP&?iyZ1Yp-^_0o_B9XI&d7(EP<08neQlLzyItZ=ccZC8( zWuOrSDHe%-S4{MMR%gsw_ucau1)6n}R)%jgL}ceR|L5LU&40w~PcJV!WGAU84-T5x z-KwdDFaGSjq;XV*<2Vi4?kPA?9-drK(ktY?3zsb%RDI#zJ3c)%4S@nqj@8KYNOk+G zPU8J-=~YgH8q+5UW9R0sgALgW{|{Xm)ltTNF=`2|eWz5pqP9~(6$v84{c*Ju99)0K zh$rd(l{vx_9jB%(KY)5-&FV1n(xDc0*z{TwQ&&=JU99$uBVPl*4naxBievun9JKvT z`HtV!xd*z{Jw5bI25rmf{P>#yNt7B{gk$F>&($UVWl@*HHW>PiOMogs!e+rw>zf zz6@&1^YB>AP%czE<@6zh2R5^6PMpkV9Hj{-BT_^Cn3`ku@j#|FMQmzsQ=goMPa~i9 z<)y7}gguIhiZT*{DxxRnTIIk;j_x^db62klP*Hux09A6F=FXie?~?@;#79VsO@^AE z&#B&xa;QS-LC)CPtSTXEd1w1-8lNociI(Ij+iAoQG}5p>4H)+=1lUSK(V?&_=N~N0 z;)mH6R+9wv^#3${JIlb=k&nI$Y*k=&OeN!Z3&RZO--z;@OwV|wMJZqmGXaMvznsiXzo8> zkNtr%i(u{CB^eGuYK`zmU*u$E`9M@s=ttmZ%lQ8SLrEFr@D!t^g->PRA%)hX;{(vVFW=kzYaLHf?#91o)aqjQBe9pB%@C{)C=k8@*?pD9!_tc8O#sL{y z@j8oXT>}*$K*iaf+jT6`CpA2P2U(Z(pkP|>`fR&&}0N4u1P?~py z@j6Hu^4c==DJteV9E&TDa`vi!d}TN-P$r~6((sy0G1WGMl9|%)mHyppzWP!z@i8g6 zrH^cKY8p`1ci{f+@5|W>LwqY&X+rX=d+A>?INuIY$bs?c3bgu!h~SQkZna#&6?M*!(;Egp@HKBg;aXy{`ESB4vCav!GCZ}W&kf@rr&!6( zLTXSxD+950C>W)LIOXSOQL2^_{_yoGFGzyJ%N#>sqbzGDSb00hl~EkjWFVE?yUwS6 zKAX5f-HtJd|CWN-*u9k~s}99b{ShvmL6(F^hvQ01OYe*_OTCI(qw2=j4CK~!6i)-OOIepoX@c&<)$ZS86c6v33!XYt-7d)XHUF3srg}=F1Sxxp$ zo)T1t>49%g!FVQ6N*jk9@6nd3MxC+bi@LkE2WI@`pP4ZUGbk9TyQXa35#<~-x7jl+ z&rj75Tq-q7kP_Q@DM!3z!cXGyZ-z5BM%@;#x1gp})1cpc=Z-wr55Mbbj%EMH@6}si z+M)S$KKpb=1YY8+@$PTIAk zInWOqRMYdR$(j?=uaI2Fy$R$nJt9;wedf)sur7YRMv4Io%J*NAmVK7UlXM}&cVZlmhIl>VO(!2Nw4Na`ZL;|Gmf z{0p{2aZ}c|iPeUuSK>2|B`#EzL`j!rvnv3+xJXD7V5ekj49cZWlrI(PfZj1({>#`e zGl>oZK;jI1bs}6o_?nxw#+U;3ZThFC3O#);*GCrxZ7n#vI>N2ZuTg~DBV0Y?zk_?w z#!?dYEZ59>Eh#mM_WJPsB255x{aXU`VZf~(mopGGt@a4E8iL3Y*k3C!<$U#4WawKo?8MVn z3Ax@rKstT~c_Tp?nbW2GZd5j7jLIY$R7>NNl06%qN&?VisC1Q0tr-puN6 zCIvGc8B)x723?e#f$EY6HJ4SO4>t`Qj_j3eGg4O;Nge{vG)g>!Kd$uPtAcVb%Mmf& z1`vs@Qyv=BuN%Wvg77Op-yh@(H+xpQ{#okHS%w!b;S$1iqr*BTV+pt_-L-swqQWb1>kk$p(AQ3YiYXNY{ysttI04N>_1wf0()9=+i% zsp^~oXIkuFwZghzQWC>7Fcg4W3|JPl@S%fN*Sm~$4uvv<*OG-I!W8(nXS1|sNcDi*AMHI`cJ{b8uPEo0i$+}A|WoT#c^IBf>HHA&$rab)W1Bt}O zEL8o0RwobfdlFCCsGLB%#3qBS6q7oY~rP!1!)T zQmXbu@kD|Ufv!ch%9TWJ1Na=CK({4CM=iYfC;-L@7RHun4_rqk5) zsG0Y((wj8NYYcTfBpC|+nsuaqxlE7i)m@)oRW)6(KmPMSwcT%x9xfin9j*IR!5~}U zX^X$keZrRx)0Y44s`Xh_Qy@vV7AZ$N1w)O+DB&r`5joEQJe!XaUYvkmWMAg4L^<>vPs2yg8bzij%^a4yrRR~P8qL^H zdo_mlb<+i@404NG(r=93s53tn3ujJve8J|?Omh^b5=TFpIHN+ z#n7QawJO8YV&ob!J|uZkGpMHiP#@YO3zt8(TW==`aw1Ex|w7MLmlPC)hI6kz4%zbcu?zAJ1 zgQe3W6|N5r{k992IfP&xM8k3puqju{uYr#0I3c5h{-IT7DC2wD@Tgx_oC*pQE1`3= zTo1%T!(Q$CpaiA$t$o{noQ*wE4bMz}v>m04T# zg_=zw;F>zf8d7z=Lj>W}bG^mS8R{?<7QG_ADA#Y?OG0)%OdW_XdO1dRS!b-l- z8Py88&jPSky7B1^<{N%0T}GaN#gw|eBz%`51aD>-*R1JW4inTsNBdc(buF_S|6mtf zKipPrLZ)f#Ee}n042RaeMJ{X#D)=UZFn${O0Y<)<-biZ~hFu z=k|N=_o(IEj6#@-lJf1rV79V~ES+)L%Ep9CqT%x<2686EqNTj7Jnu!hO~~|EFI+yW zXGEswO>EE++!p_s%bj6`%OH$#j52`U;cO5iU|v)iL4ZsFp9@vocY@eoF{H} zuIDj9EU&+pKVII$^3M>_iq8;HQA?b1OYn;AAw0LN6xSqFddn)X?;Axft*t-%wJ`~~ z0-Y*zCluP>>5FjvTMs&h|8fDY7)E1rXbPrCA5dGWSn{(AD3_UeiggW!E5`oa(hxh$ zZD@VvXSI@6Y?p0ObUD4a+|8C{4F}|F5v?83vDH=c1dnYunUv2TiO3P91(J#VQ7bz& z*w0{B0(`RwWrnOHYn17Q)76Wmd=;9FTIJ4A%uv>pJ7>mibMnriwb+|w%i@;&wzNJq+YT^A(pd z=JDow!}*>H?dkpJ7tz?zL{zAAdMUV31x3;!mQ7xo+DJseu z3qne4D%#cedNRXl>6118=5=z`X#efl>f)F+)h_DVUG2P(v3fFduB(ESjF z%O8SD9_qE=IiHtcDbJf^`Y5Ifm(zPG^UU5S7oU?k?!;wU^cLNcg>{z=QTA+72Gct` z(6(}UTeyAt;wx^@iLS6^uY4;bhey7L{_s-c_xqTbWGs8i!qSzXrr9VSj`L~H@l~q| z&luRfx)^Y!y}kVq1f%$15xXPbG0>=SVEqn|xS&*&NqO(=WA}=(fRjjj7@_jP%4M12 z7eGWqW{PA|C?v^1N(V>k6Kr;q$0>jneWeRY*(<%#>X+6CIEEJ=k%sDjKTqr8U9>06 zcmJxoGa*N0y_~2K!5Ow3?hA!Dg-?=Ib65{X*1pB%=*LohE2L5H-?jPn@I8B`T{6>~ zNo>?B=F50@$=5dP(eX3-OHs{;-0)dD?#HUgHlHh#R?6{+2IZ@`FrF2L#d5A&w_1RU z5{^k~y3?y2GkA1p!Y>cH6ZJfD_1xOSupULe|G)IvvpDRLX|d*zbGePfc#QN7Y2aXD zLBL#zmH-|Nh~RW0|AYJ$GRp|lrEDo8_p;DjB?~fDnpshJ8UgxADB_4LFxwSbjP4EXxCKvXE^GfZtuEZR#n&&fA*kSPwOa;QCzx1y1 z1QZ6^x=CoRr(7Q(6zS>f`|uFMAl=KE2V3tENd}nT1G2#LDup6CRXGsdhRyMCcW45_ z3OQ6{$OEpVnnQK{H{p_MvuVPWiQA88@LuZQEh-O~iDkQ(^&n(pnQx)qo`ejzcfvW_rICHPx4VV0LU zZv?}#4tkY2drYxlG$Q-~;yqo5VXfo*tS)j}URhI^RNN##Qe#!3t{f z*=*2m(DF^$Cc}u9T9D?HH?182KTV%z)=h_xbqEq(=)V8bOun5m5QXw1Q+)$mA3NB6 z;d>djwapxO+K-jkFo8T}Ee|m;EPTu=vtZ5~h-{zyHII7QyJP>YhQbT)i#=_haC$w3 z=oqGEmpw~mtcD}G_Nq6|K~U#AZv7!^!CMY;-}eyfGI$8`Wyny=m-%~_kn?$VMStiH zRS6}?07qd!>Ow6GRq|3pl5Cv6bXj`X33h)BS~$tlfQbd@^9Tuz@K$Nj1Uw#8-Er*R ze7`hk5t)+0f@NQpW~@;#dhIL@LOx4K_+=&x`<|gI2^B+fFV<&|4Ua@1rC5#aZV`sJ zOa{i=nGfQkmWF!yL>_2Leo`pNRWJv66!G z)sKMDGNZXDHv$i(?dd6p!qxW26tEKQ-Yx z@w(7@do5lMX@?}Hhgq#npM!S9>UNMOan!s~7~*Q2-z+Q`o0xy+ zyNgdLrNI8_KOXQNC1GQg%#GMitQ5ItFJ2`@vhd6G;TrN=3TtlhKdIP=M<+}d>wcsY4jxNTX~6|KKk za(vv(vFoZC;ywEI;GI*mt{xX#Pfkh<=`d_+XzVh*y_%LaEl0HBO`v|4k`0@nP~j1# zZi3x)-n7ev+0Xrz zL4grHz58cwBHV_fH3(m_wkeqU=gNv9C@NG}R~t>fm^#p*Z$Y*iKmvjC5X-4wU#A() z#%GH(a2jmp$tNb+dRmS)nrgV2kL$-jO!7C9=p}B$kEoD%hqjPa!$03u|59D-VE4&Z z&(LWcj!mjNnLISDp06Rid(tY@6e+!`5`ao3@RrbHIdJA^rhVA1`Q=(GMMWJQ8N&v- z>6{?`#oND1%YnhqkBV zYnSmXlwOgg?r=UQ!I?84L<5VWm)ss-s@*nzu6@Jht0YS7Jd9s1!gP!gJSwEG^*zkQ zlxNP1`RUV7i%#tkB;3ARaBlQjz>I$QplbYO@1i2Ym<}w?thqss`G5y@os@K`AxlL( z{j`qP{M<{n*P8CuLgym~T(GvM#XsM|J5{;0pO&{ZSrjEUk)4HD{Hi z@-`R6%G9k0%3c|ev3$cIMl5B;;6Jirzang(Gp~pL2WQ$0Yu^lAD)7yTTJOgG$j-Yi;7ou-bWEb1{82+obWzrX_9mKGB9?lJy+NWTt zvl(yH;?J-WB3di%_gM+Gk zw6r@is~&w8wl=TFt{^Iw_g0NklwT{Svr*3?wu$rZTjm&*nqe6t_+)-AzcCbY&|;N` z_>#FSFN3s5oBPL@;!(lZJbuwzQFZu41eCw6Qnd2Htq zf84>JqZ{?MSX13fIV(~ujDmVrd6{jq7MIk1cO5VE zDGo|qU8ud<1Y`HQ&MWd6-3&=xUXp--m?)9W%UTvAucT`rO(v8(ky&4J_gQFPcSZ zDwxd7EFY(^8BN+3W*=*LVEg12hMKlh;?YU%<&z0e^avzfU21%N0pS|YgK{iAxwd2BibcrMB$*UYj;hV)1PDQ+db=p+&tQ(H z(_GbL%rn7u;7&Gul{hj-rYj<4pgwTaHnp{V2c)$Y^XEQSP~7G;5i%skQbzY^)vO99_}4VMCnGl|g83}Y z@$v7IgkfE;c+gt|F^gS9`v8-ZVBqE!Qdf6>e$xRX6Z!rdD<<)-cjV>#=K zaZs8majE?|a&_nO>lF0Kv%T8N?t-V`;c?^J0$sqT-JZY%kcDw&dV9zDrPuM2*G#0E zXXEnn*hjIlS}>~%7w*HbRQSM(074yQRW$`w6rqF`j)H<8wa@cjg?HxbaOR`Z^=h`* z8v>c;hCTmipjNPDKXgN^HY@iriH5mOP>^cPGi=!fT4x8q17)s%m_2Deo6|{>y=yaa zU44C>hLQGh6e6bvqnnF@Ulyst%ko0rk!uM*S=$b6A> z8QS^)ZQTuD^OVX8MAbS(!vnTk*KKU@VZmq(oC=ZH$>An6SYi0#K1xlkr0~;4gNj*{ zU*r*GYwoDU`uFCeGN+Hf2k|3((_Fs`OXz*j`S|%n!J3eF$V9A#V@5@^{&BJ z*hA;4gI>6Ju7OPZ?Kie^zpQBGAcUU!AXyqg2Y8yzidcKM^qX7c9q-H|R=7SRwz=7U z7pKj2f^i_^gW07 z&Ye!=T&p)CbDpHDoNaiA=4z?-IDpE<1jY~Q>gq(#7dUEPPwaNsUDpR@Ju>dLhbZ9{ z@^l#S6>8pO^g6U-bYGWb^xW0=+z3zXfts@TTH|&|4PRH;+h=dWsB=?5x;i(%EO*3i zc8U*qBV-lw?pzNtkbP>e4%A#uxO-W+j6YnKU8Sn3XYc1%lG*w=EG|Fn6v6lUJFbP) z0=33veD%AnVONz_YC!+icxag8ZYjA@5!PF|2cRUwH0zLf@Ov-NYj-L-mhNsk1uiZf z(_X9L;h5J!-0Ikeh1F5DwBe~{yNoaW@}Obj?gc1Mc_-rW>ps%MvrMp{C4HyjQ5An+<=L${bkuKQ3=Jxn03rvLwWoXZ3qs!_+Nu8J2 z57ftHxvQkoRb(=fV5kU444FAOu*(fl28OXp?Ir_Wb1m2Xzdu9sN&&!A%h53g$>9bb z5VyJ8ZP)*@)OfRd4S{MIwP?CY2PhA~$z3pqwtOu;&`nEiN$^woaSn|Oc znAzAJ01^iu@bAq=i(x%mYOk4N z4tt|jILfc$DZpz`LX=Eq}@C_dP{KdzHkpjg8n`$h`2 z`lfw*G`tn+o#v88(fPLi1FMX{*#<(T1=S1feCdPtf|^P+biEu5J1`WHGPF}WZYKv* zZ&Rf|DdbEyZ&oHi0W0aPOsG9v_I!&SWVRphWvkExXwTWz?bQ4s@mvqFA;U3@Bs}h; zko~GKBQMWeX~Pt3X?eKJeME6|baV)^BLcChEQXr+I>9DI_sVmaGYDtwB}?pIg{+JX`i!7L4~xy7aD6Zr zj00?7qvKXLH0=kf%E?? zZ-H+Msu_c@-oxj2i8{Kn)}QFBs3x^VY!sToRD((;{brr&3(BXQXK}z0NRpA^VIy-} z$ZRg`D5OtVa(aW04=dY$6ww8-waTbrGVeKpib8Mt4MYnI;N7W%$sKU$(8;!kG!%9u zNnuc_mBsho(Ha;n^XSuyo6~8yyc+L0yCSPLren7RV=iyK4(EtTNd7Fw*=&4;{Sa;H zx__2lz~Wo@*Vpu;N->ZP{kotQ_s>S~dq*^ScNhP`)#DP^I+#V;=E}37Kz-2+Gm7Ba z?wW4FzEM0Vbb5js-kN2y;7fH64==f`WPONsBPOi6qrdaRw;lc3w4~L6HYi-;_815O+hURQU+emy0vy3x^o`_B(o z&%rJmAXO_F57HV<1i22%7;pam42#NP(iH?UpLxd+I>8Svv_B^?Y z?aM@ZPEL^^g9m>N-5Cj`lpwqtj9V84{M1Cll6sZEsVqrd}nbnrrd1bKr2NbR)) z>%gVBN}MWVSMW9Mehi8yptxaKIZPTs&|})IJ>3Td>H%%;?fI^d_PfFaIou*7z_yjD zO_T#`46c^#&psCLaBja}OtsIwl}PBYB+cK~yt$o~rG&dUN}PYZ`}QPS5wZwqpCkPW z7)w0E=;}SS7eA$MWfj6h43_zQnR!Ka)3uWz#z#Lw`6VoG|B~CUp*$+Ce96#aO-csJ zQi=e5aCD@Oc){Qv#12*qkOUIsGa-+O>$Fb)a$(jP&Oze}`}`X%l6<=pGZpe1lOB9J zr`W`H#{XgyBgxLzqjh(#S>ZS7Ts#9kk!#p3tEB0^%d6*3v6<~qrc`CzcCl~W+ukr=XY$VRWN$}--u8&GR!*> zM=@IrAv9j`KOq$GH3a0SaXU>o8a*gY%CakXouwY{vj^XSDOTbZyZ4ug1Y24xa+-sd zZpX>PUG>EXCB4oFFGiU*wfp~nTzv;Lmi-^MRLCxSi)4?Gy+_I>>$YX@y;sQyAz2}W z$R4-sy;oMUH%VnDqlEW+*YkhRdEaxM&U2J>U)S}!zVkE8`cRrYCg7MplqO~h8Nn(+8QhzQlKN9@^czFKHGT!ro{s3D02oG)^6^zkKFqx`RgOFmEGDx zI7p?6=nPuRj0@#y-LOc_e*i`SsE329<<03%VekILt~zS>l!J@wM{V$FZAn=fNWG4{ z1Zg{99zPAZaK8|=Bq97wo0d=H!x_@n%fqQW*z=xx%L4;T<8c|4#e940Sx~J{W^ZlF zAtxx)jI4A<{MG2nR!7U(Jpj3s*J8defy5b0D?Sj0EuX7Ha#@vdSqeq``lIEhsSvdMtof}jL_(kR zA*))gdsn4LHBu+UYji+z00-*MdxxuA$*#q4{JC3B7*PH`AVrGOEPbHVs#(|tt3Jqa z-~kcK27{k2&^?w!am6`F%w3;N+VGFFT>R{m40l#w0xtnNyUo z0wztU35dzrgo*3+Y&B<=a2uG^bfYvkJ9wJdx2Isj01x&NxId((Qv5zWz1I1{t^NbF z?!u54;W5Md0ZJm6UDIPV2r_m#MjPPi9O=>z1PH?WAB^l<8S8Z9>k?&Z@KI3xj!NcW zGnSP#C$z*!#)-;o{;5ZBu72*Y)w``%>Slpo+oJ+ zYQ3~wFe80jwkhZ!Om1JkW0!Tb*Gb?^QB^!ej;N@QxtBY}=Rk2}poP>(n)wYog~Ea0 z&9FcESc9rZ17K^!DZM?g|cN$PFlcfEI~v^mR#qHn*GhMSF$hA7ILJ6AU%UQF0k z*K9FA&M)MYo~$Sr%Cr6RRYZF7FjJRJgDFW9FbA*|;=x5^Nh;(TzD3r^T(q2h8f2oJ z;5Dv_&HrX&^H@eU*RU=;U*6pA+D(D3QVjDm$69D{c)cbYrF;H;(6d`*e>?lG#cJ!$ zlB1dsH(rG;CQx<1d)ITEo;@fC)W8xo`|<7lMN= za?oIX*%SfR(kw|u4_;Ig6l{uIOo2tzw1W}3TDeX!&3Gpdtni99i}~#>v7_C|^W~TQ zwW6}$K2Ml{BrZt+|Bv~`oS96j?s5oMaULo>2c)%g$-F?cd`J2|1_IPHotjtZ;(A!Ygb!3Btdw6IH0T0_^g z^I+}=SWcEP@-&es*4p^eUJ}XQe)A0@-1ehGwG^wv;1&LkHfF2e@*Yi+F}g7)k4Ri?;h1Q@>nz@PgzDSTDqA7Dj1`)HrJF>Z=wO3=|m{ z`f78fK>q|n8Kt>ZTmUgNm(HaATc_NTlK{CFS3BX_H9v=j;7>os~M@nDU5 zW~hgSNkAYdhx0Cm&yS965dRrRR)a>kIqmkYU%KUCr?$YOtEMY(m8- znR#!B@p+mWMW0YDtGL|=Dnk&%jTAj?c-?m0U)BGGWm-mXjqCC!SXYWeDTK0dreR*j z>y#=i5Mjp;T?OTj2>FIG=W9r(uH&;gd?W`uJ=ULFu>LBwmj7@V!tqQd3?e^&jPh*| zb(7)c#&1~VVZsVw`Q*-j9ZKgzY^YpW zJ~}l@>yR%ZAQwxKgx_r01)O8yl%Rb>V$>{d&+grz;Jo##nrEG#>`4N+i*_hnPInYV z+c#|q@@kYQNbxN1t@&qX+m0QV&y5}DQry10L+`~FgB_rM$cE!Q^s$8a4la$+_KWgvYMC0CduXzV?m2o{I zqwRV_@^G3Jy3y+v3vtk-4a3oSU{CY++)RDh*btcI8Wd)LFCTHwOrR?Lq~|y{b?2Wo zfAy2rq2_(B8)3-Z7v+p{c>(pX2l6@`PJHBQ4;7iDbsCM^wabal7B<^UuObfpHe=zK z6g}_Y0c|o~35m@2LOO&0kP_q0K_P%hETn?si35 zs@~A*(W9K)->i#()*W{j%f)@cOPu;auJ@;Rf+E42RDo1wF3MiTaZ|>wkNkKf;Wpt9 z*rp<~H?^j4I5M*GDr-V5DW_|~G_l9|6GnN@gYK&2LS%*Jl!uj8p(I07qm4pRCrxG? zcQj{XOoD)*{Qb-SgL&B(=z%bo7_MbU`)ya3DNX5-ygWt$?I z8`-uRNjmw`o(Z1-aA+n&jXZ>Q`_vW{slL_bhH8qUJUN$z*K-`zQ z*UZDi!@#V=E7_O%YwD%vTWI-26K35@PbPI@NUlf}mPBVLW_P?uVt0O6cXB&Fdu3V! zr|IPMSzMUV`>5_qS(-)GFG!+mi7+2YFJEWlDXBRMZIC9%`0DsXCqQ{Y`INWD@ferW zU!^f~o0?tFz)JMgaSm#LqV%C9960ce?7tmvnalo-lx<(gbN&q_wrCpJKA_+%K`!MX zB`3c?w+noNzmqfe^Fudc*Gg7Sgh{s_NbT0md?G#~JLQSnd0z%2kGN2axWz%RPjdjM zNiQJ**XmfnlTRA5f>IOqM_^-1Ao<7Tm_amiWv6qX9x#CXH0HUyYWAl)cU3R}_B5<% zh_LY7;V`zO>76ZD{GKg79Yt5GYgoOs#4;UH(4ALC%!WJaL8KCAhxF*A|0(VvV3KQa zYF`^+v>zBC=2^Z(^Jek>al^v+EM4y|Vw@jFK%1MJ;#0eMGtYZ;i8MT69UI`?@63pL z#h^-!VO9z7(sumY_3}{Z3^(;yDmBP zeyE63B|3y_=~#oU=#!=*li5qnIUHnwi3Xc?0)4S)MO_m8per?`eCYW5`};Rrj$$pR zzwWTudZUfI@o*)7OkDDug zJ=?nb$~Nta^otVr=3Ob->lmCK9Q>V9j75{!fdpFCEF^TY3*{u6i*cLci^B)TWv8^W zlchSvj_x(qo}Qj_NxE}|tFuF>hs>On^>XPx>eVK6{Fe=TNJ!wzqi5d1E-%v|j$3C1 zWa>~oO5x1=nItqPb#-$``yR_phL7Yp+345}I z1(pkk9k)8M(CC(QiLvFsA5PL>B2aSjig_I%P*$jAryGV5p1{<2aWnij!An<6aIW9d zqFmq^RUuND8uOqTSB)P&G}9ND;%a%YKY&28Qq4v6bcL`y`{+r-JQwG5ZyVz#w&V9h zzaMpHdfyI(@H3r`Xkes6elm7qL^YukZkaoKPBc#YXyI%1s^wZy>B;U*CvS?S)%Cfl z=pX2=>}z(_{6~qo>2xiP8oi*{0=nM)qUJ}g5C&F^@Q^Uy#+3~Z4+r5% zLC1vJ1bFw6rvwQDhuKsZ;S^UNHkduq7pO_-LDFzAtK^S#yJ>QmNDR)d3-$|nDZI+n zA{P7JpeiyIv2IbJIaUYmelZRL=~tw}$7Wvg7}uV)oQghs=czVz7psX>+U>RN*W{~I z?L-dZ5;sMXSJxWF3!-)#Q{t+36^^&Px}Ruyt9vyYoGz_@|8Do=BnaLShp8p6^zf*g zPbL>g<5ExsDAvuIw5%+~tgP?+kaOu|iChT!?j#+N^MDd`|z4WWV$XscvU0kcXeN#O;zs^*x~~& z1U4@B2>HL_BXK*M*5C&OdKslaPR!i(?&alpogMh9=Bb&!Ud_|7$w%sfA7WgTn3MW* z5+CjVv5iVux@CDtE33#FCc}t}{@MY*v*P8OulL&3j+=PqOFnE?2MEeeVV&vRxMi0X zo1Y%KGU++jS>$7Udb}9)M`q&$ymGq189ms)TAx#R(OJ9MI7P}{b|;Ct1P$A-hSJb* zD~)AGj@qK%ndxu%SX_@xcEzhL>n~0CMHW|MSbWlJ@_xF$a_?+ z@2F6z?3RRI#tI-{Pr5hGPdYN9`C2sET;4qK@R10Ga&P39V!}KbKy`of@KZXO3AE1& z7WLr7exK9UFD0nl)TXdYDanqTTOlBkx$3LvSVO&qU+$#qEj4i_1_k=dsn%5E(*#uo z5|`t~ecc}6<9K(C;&zS<09<^u+cSPakDB`uuJ){c=b&go#hmG8FRfQ3$9FOTNT>P% z@J$)mNWW4la7~AX9fm;&ef=EGZ({upa{}NWcp8M1+%6|m8(DXQmK@+0_X)2|*Tk#| zP1oQ_i8#Kog?+LnhYo9sy*Fpy_svblgnrYsFUfY98C;@XXx;%)S~UbJaYgwaol@1! zac#%_bx-wFqu8CB6m2Ca8QCXYIc!AI%yOtivUgYR+C9GK+x+7F<4^p6imEcM70phR zVYCx25VcLzeB~9T(;SuU7|S=o-WA23w`#kc_??E=Q_VhjQGC~Gw^YB>3Gpt42RC7$ z%d5D!*gr_QWc$889<5FKGy%Wh&cB(}=UGz1TK250)zAGz3#hFb)=jze6Y2yguUa0U zZcg5RNbP`k0Cf8K(+m;^V6}5+9K5(0x-!8p>mFND12oItgq0ceg9l>t*rk9!+!u?} zEc~S534;$5f?I*S)mR`Mrc3ZgU>X7Tn;;nmYN2VjYgBGnBq>%mQd$6K52fAJZ2YdZ zwblP97Nvu{6HF+Y)Ly}XzSQ}iLyPc{9%+M$TAsFXN5NXbQz5b)f^pzcjA3)Nkvn5NGCwevp~BE=%WyNm^QrikEh|T-KEdZ=%^@(sYGg`k>@k) ziNl@ix2Sw*%aw7?n)j>fv!<7|>08HenaUGA;Az1UhAl}kzdKu-TDc}dua*d{dUKIL zy#O^BDQN3;`G_jkeZKv6L zVHs;rJcF$i9WiuZPX(JXrjfNhHr&p)L#A7*=&z};WdlY!y)@qthi@-Wi5gH-hD(#* z+a_2$Jwn3~kTvdgovm$IKU*sFKN6mgaNBg`ys}pQ0IpYCLt96K>&jo8O5N4}X20v+ ziEsxhahlo9k~bS3*wz~2G45bCGWC7WhccW=+55$W4L>{!XjQBARYJ-Qhi_u#&=>2K zXtHU$E}X}bIzaNQV<^@yy**wvwsV$6l#wJ$gaHYEuI-|ELyaY!br@|8ai2rQ^uCozjw$TUi;J=}CIcv2l80 zXI|(Tn~p?MVG`J3X0J5z&B$3K{kZq{=N5S@&YYzS3p9(GWpHZFo99`fE!Efmo;m-p zNo|U8&B}40`DHG$^+rs_gi*jR7LId^_|DvjMyqEAHqU_#157 z7x#G}-gI~x*|M|jP&MA|1N!Qfb}J_Ja{A)HAZi)gv^cXXq1icxizR(O#Nv{YNa$zF zK?fdqFNH%z<$Ci-7hhkB$G`;Z;JKAD=(@MuekAXm@zW-=C0m1oIc8nRX7*ljTTGnS z*(^FmE!{XWH9auw4Km!3svxG~9a&zE)O}X@YJDbLSqM@0-h2g!1JD9o0_&RTH?2HW zI_(9<@NoEfI56Q>Emdf0Opwb3<1CD<(HEaB@;vuPmd`DGiAjd#dOFmu%}LOaTQ>fU z0*=7vfuR_R(d5gD3It@ny&W(eM2%$&N(`Qz0*(#lU%8upz1L2TyzI99!ZeyYijR8t zhA|OP8Jh={px$mf;%IH$PPwVvJMpt1R{(FpjV~S%0j>qvTA!kZJ&p47bAn~P*!@lE z&KTFehKHFsogWn2Qew+5pMK4kt_gmDBN?3fBgtJuJ2^@sVrQ2;XM`0yB4@V{>==1? zqzJFP*Dw7%{T1KzC1L6IukEkZY71Ilb2|tZczAG$mU!r&9Z?7@$^P;FSSH>VC3$)2 zxb}IY7xSt>>YQg|*2LL8IOw9h!%zQSaz^}j6!7BFaeZTRS{b7gyB=H8=ZKIx=l7Th zS9u-k(XAu;;^U)`Tkw?i6BRXHSk4Imw1)iN4du2kr&uA6>9O|2%5$Tz+W1vC1{uCB)VwDQ`@E()ZwIbJ6 zgS`d*kujTPU*jJl+dDchsvQ+q{8eN~LhfnhP23TkP2qX2fAe>X8o5*Ke)TVeTe5%Nx2@Bw`=j&r5jr&;Op+6to|?8ARaLk{&Z?s%7* zri~x5#idV!@*d-Ig34SOzwgMNaSb?2PaRVQJ1NSy+xSnUugP)#Sskc9IoLk*ovTr) z)<+%p0>5T_@NBn9yVq>YjD-%FA#($mkV95Pb2SN$M~8=yM@x0sXS_HT)r_XD1<;L0 z8ZYtSg^=3(lsI}yFU2~sFS76N2zpJm!Gc|L&8gc>i(b7$4Ro{D6^q*&x$%*2dH>Zz z!}mQ=8`H|h`KrHtCMtEgL#t(2f2Eex!qa)fuYLS*-U)Eo5;e`uFqaQt|M4r}_^nZY zzlG~Z3gtm*K^0v0gM({Lq>5p0tH!jS6g!W+th(D#acrGOb-QIsrjX?X4CXw{7;=?G!aD$3)Ph`lf5h zzoBTyFrdBqy$dPCA+Ly1>pQz40YOozspcO>M*0cRT}|pWU|{__dHKz$+^G{Tay6<% zhrNkedeT^UWhpE8na2{Emq?7|yO-bCaP>@#ZzXMax_va1I3wbXt!Bct+wcd74B-{P z(oB)hE z^b1_`B$lQ&hJj#);!%~qzoNXhwd)&_aE;S;o_PmR^6;CP8%$XbsfoRpW(^F#`+dr< zJj19Ju$uIeDX;5Lk%N%5z{G6u?|L)qM3iRnuu+G1X*;98=?PFsVEZ$l0$VSh=b6$v z#}D>)h)zUr_G#KxbsKE?%|)XI3oYd=#EPNWx21ImQpdy!Uq_qiYgoRd)h6oh4Yi#U zN~N|oJ|~;xZjBs1?0t&eN$A0N4Y_L0S=Io?K*AnZ5VxyO^}<>7l9GQL$wjFS zTau&WhED8CU7CtqDMmf|r^kk-?6Kk># z;duOE`qJ<4-o7I|7|p&i3t}(I(XV%le^S|RQ?HD{oPOJ8GMm%q`}weJxqR+A;9+@G zh(-=ZQArhKf@qcy{*Uu)DPfBbqyj)ZfR@(M(g@IW)AB*?TncC%r~@F9!eyjr+zM1= zvyWgOBigb?1zi!dp*_8;@G+cUmQ< zf2SVl-#Wz)2wtd{Q3TUs8nlwmQ-L?m{6?Sx&LFht9-Q&=m)9Y-5RM(MG;9i9IQ8WN;2ktL z-fD~0&$W^rE(j0Z;#aGSAr7}4Q)C4ZCw9DFEh^a^HEfU@j_e8fPSVp=dK5zcrUD6U z!JgwlfXYC_ER#KY-S``7hDoT%n(6nQ6-Eju%p~qHJ+piK-#O1 zLDQDYmb0#*K@o-(tKHELrYDrhF?>o%)13B>epUUs*lIR#pw>-$^Q)W5`2*Fia{Plx zV%x|Z8zp2w;SUurZCyv*DXrt5I^L~X=A;JG8Qth-qXf}`skIaz&<=RoO#OJcpQ8Iw zKEzSZ_HHO{wDW5$+u=%4N_Ol=S{O`*t!lsZ89Wtdd_)&={e!aAZB|y>vB`@|S5lc7 z7}a`&<8NJXpI==06BH7(%Y~TO`W0JY&p~FB=Jl=JN~V}%D7M+;_0&8;n9K?elLcMU z=sMv{{5EchRUXEYfu)-%((I{vw0mtuABQyI6=}lI;WZ2E{~Dv2hU|3%cAcJLvkL>IxXF)(KoKL?=xzu{#UT;_? zn$K8OG*QG}uRrD^K^K1Znj6@K7h&mxaWY$O&*w%K!-MGW2Nt#`CQ{CGGa%s>!GHJ| z8^PE6hi{;6Sm&VZV9EVkpc#a#q!fL_@OtKbd>Mf=sSEISX#sc&|)MVAt#vNYMzU3swzK$Knqmlra5M3wm zrghz%Gj@i1T#$o}=9E+_7>-TSMoQX`O+NOCf zQQ1!J>eK$Dn>ZWbs3@;Kv#{RwZXMxsDs0Dl`)OJBMqJ!Lj4bM4&|_gfv#`Df|L<7& zl5L?QCZTxiMm#d4gGed2uL!ShmqfjsM4~#5YHr0PxMjc0dY=9;s6rrp5Xq49k6JD zLjv%n*PB!2xh&W?IMJ^r*wS{Si&^msY$?GpsI-(5{R!F=DYWTSrE2#gE#yc-Ld^OH z%fZ=rV*(LOQI%|U8wb07G9wG&`-SZh3X=nHFb>+s4KD^%+Nbt?#|br$55T5RbK4Z+wf+wxiS|_0tWN5s)wN ze*EZm|Cs?D;WeL1$^mh^222oL<-r9G0x-j&uLRL>vahRKsn$MVHZYgj3cm&KN|Iu{ z@@<2tve|uixs-!u*MQuy0`?~GFSr)bsnXl3;{eERfR60@G+Pw2^~anRG+=6xDEk|S zaION9#<)CXanZP@rsn(atq=W=Dxc-Bz#yQg2;ghP^3qd>`GL0bA{kD;s+2RkK{D>} z=sOuNk^GAeBjI^@^7-$q@4tKKc2I*l3e>zuoK>s)8iKDFE|IJ}=-N2A9&?W%tPhL{ z%3jS9_(yVd^2|nY$j@*hUw@2>Idc~C63x64fAvifWkYXt3n!Xq@MF!J5jjO4jLz^x zbTURSjRsy~>uxg8=Sdk{IX(p+cW6%zX6?&ezt52E8>}~MJjrmZuBccZV2RM-wJN`3 zKcA_XH~+j0;A*&?E>mA9si=x)#(Q{h0S8C{2yw!wio$yc6JvV9sJ)$~i&j0nT^fh} z#38GFzh>|`tPB5yQO6H03p5dpm*coj*!q-j8;kZ_=!3^ z{CgJQS=j(T{f^3kl)Mf-p$~&xa-od}h+yU4AU;5d0Uk0SHg|l3rM&p&o-eO(H7}R^^bKQ8=})+uQPYqr9w$yhwqZ3UX0J-vR>kK7>0|-g_;4 zS5lH-+HG^X(!4Epx=6eyGSZc6v1KHsWginF$RwFl?w8s+_l?-bxTm&hU}aOgWxD;R znj_k-`a3q~yU(Vg@mEDZ7TuY%m*m})c2#7;7TsdITbHoRnujq*&+xy??i?OQ`Jly< zzxsO&7-k1JSlL;y4jGiDJmH=)#Xc*EAVcKldeyX(rS8Sw3Ab)hR&yYB=D|${me}VT zo8(En$r|#4*ev>0Tl8TL0`@7yKYxAQ+4%xQ38#fLZG@WOmoMlb9N|Qo%qJ1^{^i~6 zp3((@=~VWZPf?{lVmnrj!l6wy9zXn=yJA(^@>O9&>g($}wXda}r^U8%=(ixeVetqt zsp_S({Toqgh}ool8D7C;rK`&dG`%<#1{*wF1Hg9DCqx0}6?i1&X5fL&`W zSfPg{eHfnA1AfW+Y_+}T$KHM&ySE6c_jIW1?J;J+DKLm|baIL{IscI|-|SCDd=<7_ zVzeG{1cOK+uPt&2`6%E#h;uXqi3VyAhsDI;9fP5bK>?Hw63*q^Ujh)5?TPrrv>Bu8 zlo}HypO(MdsdOg9R2e7#%~m0MGf>r_@>Ph7P{H7bC^-gYwULVV?^(Rjan$%Bbc2|o zlEssZvyUA2jj8@PcwaKv?we6-dOSltFq_>RORt`=J7vNt3i$@?If^sS; zDXG^`pu7gSG(p_@6C?>Iq8Lm_D)r>X`Hzcdgl&5|GvA$ofpXpl)61H6F2O=ih<^Di z|BF-m%kXc{{P=ehTo?nZEw8Spyx+UE_KZVYd(3n0I4wUiXL{58E>6G{#x`ATA6v>c zZl)JQ@zJXo81&uk-%z@B<6CTW2{UWKF5bN{abxD2IB0{s1&P=;4Z~YWwHlWOi?XRk)?HE4ojkN`O>+5JugIioaFia z0c`BQPkv`-M`RpxhY0a;GUAU%{n-1mG6e5~zAjLBbM-vJJKkjf*KoMUa37){&ySIAI|McJ7ja z!Zw-wk&PygQp_uGKVPzb^;+}knWmk(+`kvMW2OC9qcXDUZ=&7LQA9{f`|!t4aP;kp zwWjKU6^q3(&J~TjagA2Vwv=CK30k;B8JWm&A30hR3nK@1kKMm~paA!Jqxd|>^76bQ zwok8v6%v!ishrZs&)@LJy7TD|mBKOnUS^+tT|v{gDTr9U9jP28e0nxAG~{}`vtVS2 ztp@mD@UsT5h_7YG?}~~HbVmDo0FvX>Gr4w;wG8h3MK8Jpgmc}-K3G7q^03~Rux9x&>_U$V>S)6`D-(82tevqXPrNasCOtJj?A zv7t@4?T(T0D6%9Y(C)345Vcn@kSqnDuXm#p1+*`4+7YqT!bl|>)+m`mEjK2|dc%Bm zmb$5XqO_lP2AX4;#K^Nl6Db|SiEhPH#r!>Fg!lxiTU*lS!G9x2cGYw=`n3)sMX*(& zjL9itOUtj9K0WITu|i!}s-B-AL$PLIU0lqzGQE-Dm}j)zM2?}rgIgb;^?j#~>W$dh z&v6)Jxf8sE~cn0bchXEQt-wm!<`;{;zwu-*wOsUm@X$S$SR9ed{n9DBlhgWjZ8h%R`K+VfCKsZ zjFRaw(NAZG2%7i_2P!ezc*``>yq925+JhvFpOAj78B+1^sQi`E8crx$^kFx`FOUuA zVDLFE!P>#;%s^%&j`PzD7@o#V-)JV#`)0RM|X1`f~KL63^bnA3W|qbKbA&thh6@FU4M_ zSpLppfms#$JPo&u`7!i1(PT?b4*#MLAuXS(S8|Cn8!G(7Mf4Ia5QX+C=k~dw?`JW` zPkcXoQ{DIRJx#neSNdl+Uykbt%#i#|mZ+$(unsX%#HPm?G=_5U^!mQ&W_6N zrE+fmue}CvYKRbAL*hCHl)Vk{UhWOaXU{kWi&(jz1!f=~N6GlP<5k2#NLmP_whIGD z8JOe&vkrPZAaD2FJ4-Wz<)aOMlo>e$(U5lfFq!PKL^DRnlUq+sTT>Cg0)k9VJ<-)# z&V0mKu8kWomSXfByLLaZxt787s28E>IK#ZI==U?nkYe4A;hb%zZ_U8?uqrR|NS zF^8#S*2qQ_hwRuLl|4Jroa&iBTEth?rn&g0?-%dSkLc}M(~ZBMDzJ;NoQUQ?Q#zP_ zG>kq}QkSY#>T_{+3}&X}AOY<(2fVlLNAZBAxt-uTr>)JDp$f=L**wi`L$2La8cPHw zbJfwHH50O@2Az8Dy@|cLJ?F{MVD}I9CIhjape}9k+v9(f@_(hECBoZb*Lf-Zv0yqA zv7ehm^8ZFgoj~tQc6*AdEcRXzrZS0X@JDel>s`nbBdP=Elq~KN-6%EArFbF*vfg7o zUzkZ3HjDio(l8pPqH_vLIOnr#gCDpB{(a(WDuu_lMuGmuU?xzaVZv{JDj+MPrj@k`7x&R1n}VUn z0ZrTdx!ac~fwZ#Za&K&PCT~|CiMJNqN1BnIm-PD^=5P+ zbKa95A!CueC%1g?3xv1Rn3|x6xU6N1R8}JU4esP45C&-LX~K03dQWOLDg+qSFjc4@y_jzW7`S#Pw_`e+AI0jEnqGs+#z9F1A1P zomJHzlQR9dt9h+a2$8(G6GLZOUE&%+IgBEb$GsV(MF4c4yMZum9g> z@8HSb@>$H+gP}$X%0Nd4KO2z+!LJS%AHQjtkIUZVRXXWdJNN}$Dv!L!jL6qW$8Gda zs>`i+rWd)EgI~!d7wO|Mu&ZUO@4V_mm$Rsrn&2n4RFENYw+&ecbSUF+vNolFVGqQu zeA^rr?C|gHjTtfP6?E~Ilo*-!4>X@vzfVsY^=lDa{cz#+X}D9rC|O30Bes_PK5G_J z!gSX#frF~!wGKIkm9p%09`K({<+HAHTgQ%+>u~foZdGS_Q^YoA^S6+n$*yT=Ok z?nA#%xN2eXzzg2{EM^f-F%eeLe>dWdyG&1ZLaQYH>X&Jc-+K!ca8HB?kqZc&UfqSP z2c0v=BLZ8Vd+*`V-g+Wi+}1+W2g%}yVes03AkJRxs)l^>l>MVL(utyKPNd>VfY-Gq zE8d(5`}YjA-XYU6>>PtRFCMIHV`sBq)5c*c0T8>Tx6)i8H9g%Na8t5l`)oCz+-&YD zP_0MDE9H0-pqKVmX!~=PesSW=ufOm_rVSlN<&Bbjb1i2anr&9&%+oB~ab<`%_3}yv zd5A_wl#?{D|Ht_sZA)#=FEs_c9R6Diz2wt32Cr+|&n`}ZPSrRor9@%{$pL^(V21* z+F-Pb=?1~L*?U&P?v3&Af}w$%EbIicVOf3Wjx^9;GgKRQ+Yx+&{3h>y3;oT`l#d z9;uBgbGaTY8S%zkzmUBb^Ag_v3Xi&Q z%UJ{_7Zf>Vjc*H^X|Wf~dd=04>miIRZCpSlDui3)ar_)>{FGCsfMN==a9KNjq*;H~ z(ff;2W8mxhX@~PqnxbUsW`!cOS#%tIOa@9M3YyiA;QUC@OYz%XXv_mpiiH@AHy=Yc zRDZheCJb(ezXDnuTR~%MoL@`3n_mT5zVS28LAT=xPk&`9KCTR09_uBU?23)Uk6ZHw z$=ZShuLFtYZ)QzBF~+_c6A%PK8d#k^QHo5VwyI8&xz?wRRpADS!7S@_%he-|jD<%x zbWI1@AA9nxo#R$metE{yir!T4J+O^bH{bSpG*d0z?w`W3#)kH>EsQ-I1R`cinomDt z{GP_v`-w+sUda|~vo{Qt{-|njIRqYPTt$4f>-$q=IRE z8gyhU5Nrn%5{qh4om*bGR}F4x{V2Uyc49`hCD+$FEv$k#miru#_v=6q0Va!@g`bad z4Y}6#eV{4^QR#+Yr`LC@jD1$Fwj5;aqMT~0?Wa!8k6TBagAS;?TlGO<;@5y~OGj<% znIkZtek~ri^n!enI~vU1|5AuifAF&Z)^5uwm*mB-5fCUB1Bf0Xrp`fkMEYsj}3j{hnwTqFm{X!>schl&yEz z&pJHkK~;me za$8~p8~MjUrsz7b7v%kHf#;EF!~fmNE+Ae$*?qoQP6rB{&27VbIwmGr2Bd1!bjkIc z6*X65i;7C-4a|Hh2*&wg;%CzkfxW$9%NM^sYDaBQEh^;hEqOXITy3SNv+0SX20nSE z&F;}YF0Z{(Oe30qG>5{M+c&Pk6^M&_VQ9iO8U_Wg^806Jhb3Ru8{(HwDRHIPr|uKs zVhDqj0xx_y#c*f z-oe1Ms7MiF6Yw9+dt*^<%diyWvR{JtVL&Gqiuy0gSlC*KqFU!o} z#ivtL%OJ6R`J~=05BH=ZPrJDeoydSfc+F~`VEsul!yqfo*FT0zrETa!M*{#;3P{uH z`pjB2fMVOj=c+f1t*)-lKdAQhOv;_h`D}(nLPP|`serRhlZ~I>#(y3i0VRB4L^*4u zHLf31@Z74mMiF&U}gEN`w?im!>(%I=QYUKUB|kjPMo)M zd>?KZIGV!_0w!cAC5{oX16(5`BUtw9>XIqMQiEvOYnU)W&!J~*eEUY^-tW!w@r8wL zs~?~e?+S7oAZ0;8PQDDvPQvSMNzmkZolZZ1-U%K=z+th8=ekL@I%t%GlLN#FxU=y6 zzQ4b{1Jyg!G938W_5137Yhr2{{HndL9!qbk&Nkm~f$rrSEjBOZK9Ap4%<*^NJ37cN z#Uo^Tu@>;I|7MY^3HHB3ymU0BVS4>l$X3SI6HDufC=QkJd9*-L>E%&HTH#B-t%U6N z`PZsQ5mHL=dA9oFK{b9cI?wuMC1YFz2Kl8b<$HgxasVViZ{kK&&gl5~(~z@JD|9rk zTG70#*@r?R+od&~=N8F)BWXj~_wS zQp*sih=F@bq#Wq*gA;dJ0`t55(>RxJnsjtQbzOe~aKC=(i>J@~C|P{YtY7?DIyqU31GF*}%Me{*LS^pmo?uYxbT{MSO{w)2BoeYGY4pAUh@GLJnDBzY zdMGRCH*0!&I?Uc+Xbk5M>=jVsAov10Ls9P?7`@I5Z_S4;@B5(kFQ9_O64g;^Pzw_E z07Gh|Fsg373?~<)1Bs*M0Yg#iymT9~8oZOBg#>p3T#*v)-_kQNQJC`dFxmhcW6+s` zbt}L?K^X2KNEO_Gm9vD&GWW#~?uFx-2gLG_*Wyr8b*NvkjfBy5o$tZz<6V@X(CYCi zSf*M6seb&O+W5o-;3C(1VyF@o^Tf+-{|;ZY{{JlekO2b<$YmFtRLIr{(Z4$?d~!H$ zsZW-R|Az%oh&&VP*&eUW#u0t=&BA&{DTG?jE13~V*{!{{X7&E1LRNL3+d$6UO`I(g zi=@GDcI0dNAVz3iNf?l{&+YPLstr5%@%ZJXHBgJvaej5;9nRr90k`f|>vvOq!}Ka& z8;`1C7$ghTbXtP3xj)})``j7oqP&IbRS-UFBkS6%Rnl5)J^jWNf7RdGGHGyKB=xGx z#xM=!;rU*8S6v5dg-ng8IZCsck zNkA+BZc^(>bn9|%oCG+0ZHYMVeMKOOihz?jO!udq4$ch#L>MGb+6jQy$ea2+Lj?oX zgiW;^-9_76?fl1B*YgB)ZoG%1GATw8strCgsK&e2uuJz#6#sP^tVB6jV zCBy)WFsRmd7DLBuiMzS_Pf&WF9^T&WXTLpLF3xt{fBjf*_z_*H_dLZUC>5nqfjVf_ z)pr2|1Ro*~Jouw(hK7qs5Lr{tOJ+-+SZy&O+Z@=C`cTYC%S}Et*N)Q5 zkF+H(NDJ>>>*n9Cev6^dJHvLnf+HFXLHyif7WJCe4Lz?Y&S+IA6Pcu|IWBDG>LZ!t z8eMBjn)#5gw@b^eV{Yi%dNw~659SJK zfF_(wHX+m!Z^yrhTuM^D4Q5@Too2^X9Y_v%l7q)z#g=9k?OLs1Qo@$B+WIHO7c`%G z>Ri{v!pHDD;2jPh8;lFyde=(V@>@Hp%9@c{cvV6Bt}>CtiB$VJ{o$icx&kuYWvpV; z3c!*@u9$I?afL?STUk15)D{qs$SE#v^KKRGl)Tumj=U${bi9cDXCs4A2z~Gu1%1E| ztkzTK3xa__W7LyL`1S1urRaf-##TuOz%>rWv(6LYLI79pushzDYhif_T2cTPfLRbr z)M{Du1dD-ypdfJmL5Dh1kK^908!NylgW9d0cko-*(k@UovaPDI5XX0$4)7tQ7H^ufB|WmV3q1H zFZXfZpyJJ|TaGX=uCDGbta1jqr3p}-o{8I^+^W^}l^#SIQj9%M7j*vdb6l-44y2;M z&7fd27}{WJd~@=n2JP*|V8$V2%uxqFXde={o^*ryrkW}F?coNUWRg7f$H$8Y2fsJj zXyZDT>2dMDpPXI&;hUky0f+?R)ejU`$3OXOWZVEz&X*1XF$*Nj{&qxJBb}cu(k@Qu zOrT?MDl3|{go%h<{I_TepgTWaH#}w+sIgo!Broe3ZukEMvFz%zaqPWap0TXEQ z*CP`DE&ni|%CUvU5;anrA5OCUtV+nZ>Q&fId^C$FR2Uf+!HS>Y@(CuFPtN%i%~4S` zmeyQr<+x24f4B$h=xY5QUKOp0WWJ1_@;fH89{x^iB;Om z+uDNrei8qWx0qyD%wAA1W22S`QBh^2tsSeJiD7!MD3)Z1z3WA|#Pd9vp(`8V+pe#p zqeD(XkzHF$_86Kau$%9GG`3xAn+7WgU=A3)ks!w27UA~K$Za0w4|A&z&3T)eE~+5n zxblpHD#4C~l#JcM!G}i$&nRNiI9lqBjD!h2slnQDu;eh^g=?b6?6S$l<`v1aZwk{3 zZa-25o@i^bCY>G&vL>nKvMk8uY8wanUX`z$dN1PZ_R^H6ui5_?hQR?oMQt`nsatt3 z_7dynk{D>J_kM=$$z!N@N&w2A9QQ`dJ$T}c79dD(1<$j-zP`qNU84$#22BfUm$cx$ z)V*;~-yuKFPu$(o^V8W)LQ9Y(bSaeRvaqHdd9|#Ux_1YMrzh*;;J-?U-~f;CInvT<$-trR^E4CbCiT z?j2?)4}f`9#`jLo8n3)@*`xMa8T)qbiF6+QKU}?cJk|gIKHeUPWF{-gCM$`9h-8nf zW6NIIJCvQ7y)q(O#*w|Uw-Z7fBV=XoB7E$>jO zi|I#ddf_`~@xa?_j~l=Z!(7?j|HY-;`t-PYB!Mv^snWS6HCN|N7++@AA#$CkNk(%PMSZIc{YkKR1#N@nVA6BvBAk))9-; z_m&5Du&*CuRq|AvsaPrTM}=NUmhI4lxd(NeN1VPS5E7dFv%Y~pG`S|BDuagyp;lhj|ERxoyom3hF`qk0LgkiJ9_Y=M@PPy$T9 zhzaMyIhewB1whQyhjm;D*%?wZDG*> zKmwp)hd~iAq|M(i*B|a29j`x>VTfi&k9qO;HfIib`u6V^524NrFdC-sjB(K!Vmp(2 zbdX=!eGLaYcAfo;M2nT({&uFO#IRCn^-6Yh%JAvt7&5%mex1z)*ag9jTjnH=)-e+0 zl+KZ{T|dkjQPeSyXg@D4nHiRCzETNx3zfdvvr=|fx-`f*5wE=ish#|Il(w{7f|o)< zb%lra-6Q+VP7BE~BEKw!Tgf`_s%KsjT&!K~n6%q2D0BQ>??hKH{4Vg=*!U)9u>UV& zvGt2sU(YhnU%}2^i6yo>wRl+GdDz71zDX}ut_d|$-6Ss`NL!f1AVE#%vsYu2M-S=? z@22bLIi;Hv+dEo~_ggC)obb~WGBtJyBQ9^b60;QqXT&5XR`(~{q)rI?JR3yoW_F|O zRSLMejcL;7wye_4Y0ey!&Z`r|-GB7HM4s3EO;?v55zg?*&#B*Iyw*rl@=L)P-*+CG zm+m`#%(s{nK3;5}Tq7kNasDmy3Z$Zyq0>M&7NJRdP~db11BnjC;$cnAVJ8x)AHSZQ zknnvzUT*;~F08??KIc=IoHaix=c)WeX|&APP9E97sBkyFXDv#)yt#$YSRZ{~XH*L( z^3msp?9Ze&(4E-w%c`q;-fVjPTC{oQdVcP0Lbi^)^*zdt`IoIrHBaa>?0!5w6Crt?UuQ%K>+2LjL=#`yjL&zw$Am5@a!h1 z%}(ThVPRbX%oU4&-v8LQ{1az$+>-1U^&#& zrMCRNzkb>Er+KGZ@r4+uJan@Ueo7ylk?UG73?kg6pX1ee8EWm2Ono3Q?37~msdoNo zZ3WYXv-et`U zh7(@%&YsRA6nkSxq5YcM{Ykg`Q+DOAissV4ixU*o2)xW&+aN?t%zP)RXF?_OT}UUA2aM%*Y? zZj?JBB zjyiV6YSy!H*?F!Afw(Mva?(7N#IZ4Yf1jp>>?fsFQvBL&DB^W6HQ`A9OtOlgKXXJg zJ~M-3o0ga;3}E8>e9nhsEl{I;v^nGfr#n7ApNpAwu;0F*cQ`16>G&oGlYV6-f!xp+ z-V|H@=FZM50S1a6DO?exZ^WZOqy}bf5J`CK8K7DaP}@G_`^9s|1XIXXa@w`=6V-FJ z0z2;JIHj_HX3EN4cmNDUo^)~)kYU^^_!_z@j7jh(kVL-a(Q8-!=B z=@Q_-X(a{`*bpy>vSH4$-$<>W(qV*=vhLSx2p%3@Noi>lcE&$h@jfmFcno^I$%o)@ z0Ssj*#H;X9O8h%OuH^5M6Y2k}Xtx(@YIu2LEYGbPCYbE(6}&T4V}UMC zOFJ=J=lN#qt^+ha)o<^lCtdKl%@T`Z-AI~=33rgLyPv6Dp;r)R#V5%U%RpJdV-39q z2>!&HI3&ylM#JYQZIkyQ#!>$SD^hp3#f3Dc)+K z@e(V?nMc9dnB%=yZ)D1Du1R+5mKHeBdM_^Y-4}a*P3$%V{b{9-4Ho&0TH+qpx|q6c z)Vo0RlB}%k=4=SMcF@bsEfQefqUApP;0%a;&Q<9KwD|qo#r80TUq7NF0L2IRjtks) ztF@myIHW`f*HlP{1$S3)p=qs*5priO=w%20I}OXIc0G>_uZ9yq?i8MgD? zBpf<5t*fgkI%%=^POFs8k1h7*Yf1Rg@qMj!IX zMS~WzVif#9;b!vL)PIU4*?njoNh6WXuWuZ=g<^6rMy7I~*B;mq@vU*o$FP+sM36>~^L|k9ac2qWC9}G;(|}4LJj8msbZ9vyttnd`G9eSN>>q zTFRoq;jGLRmVg=2QO|EkM;0&dGjc-}=wt`&MF*+2#gH%4BBAE_^wA{ildPq6R;Gy( zbixOJuu#dBU!`ogsyh1iD4btskL2Z4RpC_yYz;w80LXTi(L^ZEWoT=~>7ao8@$w#W z$_GSva&i(HTmWdbIchC+k#TKcKs8_%0}DYvEb@=-A_4NQT!~Ys0 z66A^#fkB4V#8M5s#_7~F?57W{N#@+dCz6N=zWTF&1|m@A1vaUgLG zaCdu7-o8J%y@xak332H(s`x2B^6i^lK)`dkh_TVp(Qls^0pnZtnA)geBWU*G=G>Rb zIlcKbhi2_XwLa%kT*-Nlz6?l85g{%w^K>Lw?z!W z`-#0@L-`)V{k}>O2%j>9u)v%_9w5pQZwN6FJt&c#7vS#$$QC#lz7zIL!s;xotgKck z93+&mYyp_bVqKDFQ(UHIAOPed4J36;daZp^P#Yn&9_FW{TofEb5~kB6ywc}tEh9n?Vk~Qf|$-psc>$3oJjP?mc&KE|;%I9dANNLwq4Sf3=*U-=qctc-I2nMJR`5E7k{={XF{pDCp z;LRypr2O9I7t@>AyWBkwL{)>HxD<6gA8sw)_*!Af=hB_+qmHTOOPaZIdvQ^XUwJfA zq0e?4^M)-KP2rIGEKeoDb^TnnlJQKtDvH%5Svp9Qt!LbU#`LJ-!H0sL6WK4HSfGE+ zHwk*OR;sA#zr37N<+xmL9cfMYMm$gLc3S1pyB^h7=iZ3lfPxHOEFIxtJe=1Jot%cf z2#J9_#JVVB@pGtvXfz$%q3{8^crCg>RGC+6AdS~jDx;)gJs2a_$0;x0i zg9nQ*4qOpXqqg81-0Ws8E`d#Ns6>DRDl+XV8s7VR#n65QW7({U^uM=E(D`_z$JL0y znKEK-0%<_~0|f=!`+2`jiVS@Ma^9f~m-ynRGKwdS29gg_Rtqyf({Wy0aT(Fj*8b6- zf-y@P`Q)cts_{XC4MK|`cH8v0u>CmwB-}A@{1_T(Ag^++$L;Ggg~%?WFT8!nLKJVr$!Ta9A)+2!-$6!#H4LAz{U&4zqn?dN9~PQ{ z|2zy$O;doDcVwf!gZ;e%-Qn);a(hKMPNE5FPHFkaz0(%8{M8*<;WSeKsOA6gyR;FU zSiOy1R9jtT3p*??E1{XL=jkb3H(a0mF8^q>D?yp~Vj5aEf`J&-k`+1Um96<${|LGDgca{stN<1*HCBV89zaX!XLu9ZDM$}`oB%9F^l ztE1lxua{dEH>rI!;T@qK<-}vqb3OkmOF`sE|7Ehtm5Q7FJJ^luqL;#2YQJCN)D-EH zL%O}9>ZDLd|4wilcWiLVq!~G>jErT130ZK4a^8ifIoD)~h#|+9YxDPK&eb`=#h=j% z!ZWZ*Abx;(69VqAm@WJZ_?xP^sZb;CuAe_yz};do&3mek z9QAi&?w=CJF{=goX%Ty1gW6j_DhR%0klhZnr}wU;cPsR#T}C%v!3lnVYwqcpLLmI> z)xos)G&?HLRlOf96(br=&8Gw5XXMxI+Y~eqGqUznX*U= zBt(Yoe0^`1yz>s0Wh0+0Dyfi^X|{E~7=*VRL@8JQrv;dG=N{m_7}0Sq|JN~&S7UI# zfW2+bCo?{+N2+V93MKx<1{%a6#!+1eIDZ@%%U7x_xBOZRRao{-eazRNGWMY6WA9X@ zprheq1rOcd*r+{tuq_b9fL&4t)(5;ZgnxZMf3m)D5)NU1dCzkGLix_duSe{mrkxxX zpC*C4!2z=1VT8RB*y4(CR-1y_)eSKUST-GqNXwcc!f&2+j>|Wo#{MWD)rAB&AK=nq z(;pyfak?fb0X7Z48Aglsidi2oAx`1i1%<}?M0E@9y}HlPvjOl7+w%Ftr)l*rA*HN6 z8#@i2f(J5_NcxafTn`iXnz5gWaY>o2aZhfZzav5)NpkTuVJB+u2CXeEy=dzBjz_P= zH?_WBZn>&Y{uJ-q6(h|$E%p`mZEaYG^c%G zr+f{g=)%(nOezpwFlDM&@bI+Q%hErz18P)l2gv#iv5yAJ`R+gnNFrK_G^N{~e@umx z{`qF|^dE)_>z(!54f~TnZZJy5FqC4OYMRq6nw|O$&j`?~e6Qhv3m{uL53cq0SXT8- z#KyB|WLo=&>0_@n$Tbv%!-q{l>$%t1TTtB44RGj^qX4{JTiBqXy3>=RW!q>d4;hm$ z$^f#!#@4~c-Q@b8mX-g?^6w>)?l{N4^Cu@J9uK)5>14m;hMG7gkF>@R zDc>RF;uCd9SxAg$8vV&cocSW~u=$3^!G_&heX-J>l~s@Q5X*wlUaUk{lGnOiuS;fb zn%DY`CZ1#6&p%9i-3d@DsHj!2jr=ocbF2Ukk|_luvnK=%)%Q@(wMW~X45ja0#;C8=cnYM2zz6=c^t%qB9FM!tT?c8t+a62Kmz0^-Vb$7nh3n! zG9-?#fd^$NFer9Ka8Bui=|JOQ&PxGYhxVwPghKJ?T$AtRzi}#9DxUTVfD8(QzkfsA z{ohE&=@X3it*jeo_Xtj!M6gk!xMUpIehn<_QEZUDYib$@0w+7r$po~_v~FQ@lp6Oc zPe}jf1dgG-+C`3YPGdxVM~lo1X30Qd1z{<;WiuqAi#vd%t#)3ch@ci?sj~^6``|zq z+hdGCx7bm}DCfPS#JhwS*fKF~8a`J7V$|7LIxziNb{t$e^d}HbZ~M@D=;y04g0HBl zC!)rU8}+arY>~i3$-ep>wF}mTRRM})V0yWAGKdPmZTC>{1loXBJK1_&Q#(6Yxrv$b zrR$pK$H!VJv9Zaf6ib1hE&Aioa!FZPbORX#kukV8_<_YEeC1f_ix6A3yF_^GJq2awi zg`M>#gY3PPX01GxbLk**rwChet|dD9dV}tY&u*2-$uC1^XJ_bw!7)6?lfV!`%|nUb zx4;}M9ycc&%r+e%VIdHqI?swV3ALw;Rh&rxIaMe!*>E1)yAo&b(rw@!yXr39(N7jo>zKHkt z_g8T@gHu@Tbu8f9L~G5OF}+b%pCaO&(q3U5qkKX1^WMrR{AJD9{L@yu-l-{S*qv*r zws`TWgeB@hAfW`IprGKh9W!?87u(ZsW&Lx1Q*55DpZ?*`W0NBfpm(@WeG*@2N4c{( z)1ty{!PfJflf2g{;`YPowY9a!8}}cS~^s!s$+hZS!!V+*x{-MiBNFD=g6nkmmp(Ok&B#i^*sL60fGzf z_b4-lG+?InxVuPj)pK-dZDH*+V@Jg1MK;~ap{Bpgf#gdPjq@jg$NO^(s8kotj}^qM zf02Rf7ibd&SHd1}3@xwr?MZ6>?Wieff%@hqphldDYUF!>dr(tSfN^Z1iF&@>omO1p z>2zy~LCUmTib1vOL)j%7#>d*jD|?^#)70PflV+9~MRX8L#!BBkMuxD5$y=D`Wd)`R zK)Nzmp#60C-t~qpWvMeWw?4?CoP}=X0_ zB3}KD{v%~avt5+<2jjafOUO7en&;Q)%?oIsMyY2i`E3O5x*J+y#uT*WbQ}M;RYdJ{ zYNPTNaXb3biSvmsBOInz46i^ zphKj*Ds=g2wYGf7@3+L( zAq}z?B86PPdcV`As4_%qCOVFMH}zGaUG`j}+bN{8cTSP_YunnLcm&Td<=$Nd3;!dj zMA|D$2S?blTu~7>*7AprH8`VMT#a1#W~39K0A)yihQq|KEx0BUak~92JGG&QIupt_ zG4dBSSZ$8ag|8@UY22n*SN^DmU5va}zk7o-tuv`ILO18@k2-rK3S)X#Y1WmbJc;zH zJ`z7X8t-N5O zY8Db57=r08`8ItmHIYywXL$V4sn$1A&=Lw2-WxP79|m*PZ4Z6ySoX7?-gt#I<) zzF?M`E1oc8<8)AkdDWk^NACvHK{baF`XaVf*>Xh;+>4-#G{#tnK?^5dDM%YUn>f0W z>%Rqhureur22G=7@i=DdvJKxi>(6l9f3*m+1luAaKGQgy?mGz|;WmnA)r)CW%HUY@yFw)9A;8n5EoaQ=CE6lC1R9)64UVUoU}Ov#v*6Np2J zCpN2LFsg?1T*FOpMPUHvcgyGVuw|$I=*I!?>A&?fle+xcb z_?bDz5u{>cV#2bFIVdCC)0$tkhhzmWcYA0^a>_WG^i3736#5L5S#3bzVXO0ieRo9| zT>79b(&tQgs^<4dZb4RF*u8b(l^w(q+f4bz98DFfBiX<&le(ONeyzB4ldUn zhUjJ0dqr-gcN{0vG*_hw#SkB#JdP@2$uM&j1+U7D#cb3zXV!hnPBZr6-WByc74XY` z_FRy_LF?&{Q<{?*8dO=?`Ole>5ewt$)Nq*QX-?<7d$C&TFB=C?=u*e#6AgAqZ0KV5 zMAj=$PZotcXdDGL4^B_SPu<2a7@p+RTiDOxF`k(6mtRL6b@IsYqq@H?Cx9W5N&Pct z8-Rs0*~nN81M=rsn|Laz=gZCxDK9K1%oIGZKU zuFRGh-`$~}mnyNZ4u#pn!F;SDCHoUptGTTNaNqwBbx$U;69r5C=sVEZRuv@+*Gdv1 z7s`|fYJar|WLZ#+awyr{+csMvB1OOJ$m81zr23>^4|Ybd|CRQQI$L67cZbjr^WBXr zD=KX6)ynwMY&ZDRg|m(c6RIl_&mIvf5fgQEDZY*~=Ao7heIl%6WJg;A4g0RUkoIVn z!y-%Hu*1aft^*tiQrT>ji9v&462E-F72d>#OIQ1h>cnXY{oeLw4qNfTob|LwVqibe z0NM3UOQ7^}*G4bwCicDLSTN?NvPiVG-p#Nlu#m@FnhC#ncF~0$72}SgvjiZ;S?iYQ zj9nglot}9WHKV|ry&Q{?2Y&>a+TV*I`J`W~vy^$9a`d&SPAK~aYPr}xUC8w@qJg!{ zN#P>|gNS5RkwhNxvjU__!552%UoF0vRjCy46(xTt-94h{NGHA^8oD9*%S*OWFdK7i z$?@Ewr$jLsQ2?LlnK?T@<;xp2UiaWk;F5`S$TV(}{47`;tJ&kJDE6eu`R+F2W05*@ zac88%4!FB#8-CUA=0W1Oj0Qt1QRdkGX!U~O?0~SZkZ%bn)w&QbmoX{*#%=nehu5^L zzI0TuyVt)hP#1KaqMO{$7+X^*h0j4g=g#By|E^S?n-Lw_HM=(jQtGR-d9dxX-%u!h z*#)SezD;LFo$L-62e0~oDMqs`|GTFTJ{!$EIPy$wwuw6oI}{b@fhov|u&OU|2niYD zwv>xsV&a~J2=HWOEwT;zD9pK0|4rKfpc;HB7~~wTUGmNQ+BHOstO?>k2xI3I-Q~rX zBlXF99Im4A1G#?2W8cCbdl;t-q)R%O`?u{BZ!hiNkCASbqwM(AfCgQ;v;=?n#n!JD zd~sQu2r|s24ygv#i*Xn2-o5l9XV__xh?FLRgU>_FsAu=Cu2R51wl1hkm{#g$652q` zDCKB^?2N1H0blI{@6a5^S?u@3!TEy{V{3*gp=xuF$g1i0_TI;~G6jjesX?LhP2lic~T>}XW=*Sszv`cHSJ zEep6PK(7kh<|-^_r3^+YqHpiPZN#)>oFPPU`iMj9LX_j*R7tIH_y7y1Wh zGWZbR+-&I+vj%R^X`Ok1yMqk=Azn6S1OnII%vcglm~#q0ejHfY%MMz%3IGnB!^w1E}Ga|9Y=@H})__82VVIfgJEt!4+paN_{i`<@w_rF(AE&@M+&QMgjK^kR3uN?b2TPBTNI;j1@x|z88FEf6TmfV-tKGNBobe>hO=}y#%KFl)#S{+zRLD zTh1pL-St1Qe`h3|ZuP!Sn?vD^P|67a5ihs97=Ja0sA`i%?)~}a;4B7XhfBS7YvF;| zG$#A9(gxuPQ=(R%1J$KT$*R;2)5cwrCkCyyyb#l_m_M@Q=x${#)VxD!g`o?MsxI=O zWw`SElJ8sHd-|rPt(lU-1k}H*Y>p5w$$7}X`MrNki4l*KphMl*_KR(|ikM4~&w0Ev zaaT>xjmjHgw7AahY~%ej@0b0DMaqt@&36*ScZ-87k{5;EWEh>)fbqcl7zlaH**P_j zB#|IAAkWro*Z{lg)WyEKcqFRvo@2%iZ~8N2=71=RrMZ+cxYBDaApQ-_*Tenf{~5a} z_J-d0ut`T4aJybNV#bzV_1yvD9{Z+A7VPbd=0M{n6!jUkX0#-HeBZK`M^EHD=2ekl zC68V)<1|eu&C+^@SkI@`-y~Gg!X`TDBN7(RAhtei(QWB>83e2PaS}!Dy+oCiybZ?N z(HZEGAQpOt)F#tbFI6TWClI(E@hZsn+xxOI3Ch5_{q^GSfl@dY8v`5$JfIVh=>TFJZ2jd4Is?1XxTgMC1 zE`J|bpsFZ7zTSR3abnAA~YM`r494)0zr6hOR7=VO$inPcmbZcM&$Z{tApuR(#V zP8r?qiG0td4?MD`EIp4HHvjYN2@jSxf{-4=u)l|t!qn6Acq1XKIpnoG`R~g>JZiF3Ol#+3=^b_627hCf>Deyhp4fVuF zc;q2bMVliBjq<|Z^>lvc`~HXQcB;$hMNEM7-QSuTwz;F$NpgW|Ls?4UV-xFhRrpyJ zu_=9W(!&CK`!~w7R4Z(zKbI00&0X&Z9$@-0@)2$fDEAWAHC{a?W_Fxq31?jNVx4Z|# zt;5=WYqm{AcDlh6#6(Q7(g5ClXu(Tb^2lwhEt09k^f@z&GXp>e!=J!O5^9nfRdSt& zLIUw}3GnQo^78oJ7dhc!VYrS0R5z)g{0Gxo;E;WVy|j1sH1ekCDcNBc+lz5B4SMCC zv+Iv-@4ygpd-4b8r`GO_yIQ(4i129o*e7W+6>`iH!1Z3&tgy~G!foNC!jWfIj=WEf zw}rSj8S%#LUEpoHl^+8;M&?b)u~ly;77+#)yBuOk)Q9u$-!A&;6e!)+zGJ05`edWs zf!${-VVzdYK*_u!+GPZl$EWF9PD-%hDPD|`$n!mLMC`+uY*8+-H$f_Or%XXtq|DRB zC0@6vz+m9^gE|+V6D~6~^--pH*6j@`tem9tJwF2-!ewb@-I2RR zRywim*Q&s)`g)!&cE(aYoCTVm~{vcN^atEw`mSE~5J2fiEt#ofSieXE;j^W!7Y@4X1tg z3D+HTJIzt(p%6513)>WnQ?BvJ8{W|~W`GIjy`35xo0+QjfU^lpn)tH#EAeeF+qcEl zC_BuLZ24i|Ptly+eyhBac{u699HAi1B>k$@v*OXKKKe!I9wJrbHgsp)3UO}l7TkzI zR5>)Q071dj5s+E4G^1SBn1+urh3J<+Q=w4WEAsxGgAT^m0=u-4uXW&-_0tKh`9Aomb9REc(2oT|ojP>NWEu|GJjSqUqk0#FwL~GXu zE$+T4(CmA!Vn5g#YaA(EKpV7md}Uf4P@K8ajG?Q`2ZrwT37ns{JkJD1otNibm`^+9 zUdy`QukGr8Yh7bQ2p1; zPF{4M;QK63>x4&(ON0bG`?}<1K;E!9H<6sjhS7biLRwN&!|)jIKVB-r|KyYk#5>&o zR4e2`z3%wX>B9N-q5Ywn2c`*LR}Xfd%vLMY(Ab2kO>r$=`Yxe*YJ3nY zrb5|{Bw(wdP8sjgZC_Ekl0(l}LiJ$&3Pl#TlRneWCR6 zH>R_cZL*#-hd+NQ5~&eq%tej|4e1%jS{;h8_ExX^O1uwg;<86qN?}zI;4iy9ydE;$ zmXGY|D!sX7kE?2>#vZzcdrqebI48W!p8Mt6f@=|JOl>-~NMZ*l(=7i27y??^*v#?c z143E9aHzxAh*~;OV+Q-dROSUo&3;rN@5e+&(zAe@$u=Dq8urJQS1y*-y&PC|W^tPf z>xuf$|NA<1vV2a<&z}@?Tfe@DQ>kjfkt%Ualh}P+cW=F1lS`tNZ;Ktjg^+7xPxaH@ypt9)HR{OMhVw)3)UgL!n)g)hxqnI zJjwHp+Z*JcE_AaJn_@<$^%lqV8ZO<3k*5aTG=YrQ-?_*4TXu(MnJdYEBQrfhDyMKe zc-Pi8w8rdXyv~DmyVc{ba!<*r--WCb1sEjR3vz%M-Xz*qJT9K-^QjXWoahXLE2rE zqL2yUPGR5~htd#I?H`PpxDS8hb=BS%`d#Fcn&mu>fZkix@9dnV19N0X?Zv8e}>aC=m1ck0$@xtSr)Q;L3jX8^G7Kw`q*QQ0 z^`~I1qSw~1*KP!y-EEKg7!*fBW1Y1QK2KR#)BeqxjY%Z`JzC=b&^~&)GGU0_OCT3k#4XG?=ccAV zwlAtAq_x?1Qh1Pc)IVPNViZ8uX}8|-9H~?`?n`Bg6P=qoM-DX;19LcvC-2ukF+9^*b!P;5E8a}Sj>JDT7j|N z-`_W@#PHs7N(%ddP$#3XT0=CK-Z`AR9k-^ar;%Na3ZJWDB7VK`tVreRIU3v&DzXlz zH_flU&=|H6&YL|V|D__`RX&J5uA}Qg>}Pl-)$M88CvTKgZ?u3S(+Ff56%~9=f12lR z=M_E&#t@I|uTwI>b^HR6cOPrwVk?4AXQ9H?6zVS-Qs|DTKvE4&lo{%{FO7YLc0l!$ z9;iH6h#BIt7EcmQQkxs3_N#*T1ta_I`JbBVTzCAL{6dDEEzYDMj{;!5`DOTIyq zI%zYUuxHWf(lEqu#fp;Ah(Gk8O*IrKZvhNP)@(O@F?-1GmsAzdHaR;~Prgv-8s-m2 zzIYJrZ`<44eD1jEt!^X1QL$*3^QH%Zo%Jo;-1rso8S<>p1>as>W10x<!zicjs>i|3eqKfE$FTp`oMsSzhbZS~0B_eO*gZy5EBr```r3&*-x_{r52qhqydBIfx0j}raeQjxN5FtB=aI!M1<_+WlI6;4TWo}|&pGkDPmJM1(OqZgfy z?-Pt!_YsfO5npB4sp|ETXj@10TJL;We9LZRdeC^X=TubhaZOF?$z#j&bH^LS=S5QF zO-1QGy_`;Csh|lkzWav96K`xcWbyUfBl7kOqI9Sj)DXQ|g<@K4h`R@S8@`Nb%B9Gx zw&CvXpm<%2FBWZJst-o&^NF(-h;X-Gwurk$FD8}-*905|oLP$W!(Na{XNezvU2%eN zSfGXPCU}nQ9U#%Gg-)F8diYua<~Kj2MYfDngkAFR@F1G)UL9I+P>}AOq4fWp7mCv zH#ecGBx4-?M2QSl?M(1Bid|u$l#IkSX zGE0&4-N4w`ZLj=m-Nqi-RW+Wq3OR;kK?O#uT^V1JtF3WENiKJdBgVa8p^pDiBx#aAO7sk#Xz!-vX%1B0#?b$ zC9!&D6z_ul)OC|2#Czix-YT+N(Z|u>D z?z~&aaywth>k6Y_fMG5ws^fFvG!oya7BDY*9~HEcyO_vI?I~@wb2Fgtp^QNd3A+}{Q z0n5^O4{OQ}X11^ARUQXw#yoBRA$->pe1O!t>|$QVmx44(STy&_W1y_14kCr7T7D!p z5ZECee*M0~g8KjZ&ffW+H&qtc_J_bp)-E<>5hwj~UavnX(w3HT56#I=sX(za)^j49 zFdTOBid&j#MITRH`tPwrs)X`MwismqaR9Edqa0t` z7e}e^KctUU?FBSO%J_e@BuPqVly?YrlFcE3Lz3Vo9w$$@oE8ys5?V(ePpY^Bxr8|W zamIJe<1%qjZnl(+l_k@^hA!2kci}xTzL6IzWooU1nFXVTvA$PEX>Jlb%4W~PqB=wf zFDE*b;uoohHdA2uyYB|Q1b=?_2voDEHyVe1hnnd=`On%^jcL`tQ2pQ<^`A}VZ*{z5=-n||YW#p#=GlSW7bQ2TM%LY9= z6(n!ic075GCTd+Gn1VI5l4bkFm9`Mb1>xJvY4H`^7|E&HtS(H1a#x+5+aSBmDKbWy zo|N9fCj~6d)e7!Mx|7J`OBwe)32^ymCVpM`8pw6~ZrNyO4~<28NBn&{_}EvdE~AQ6 zBar0lViPKgSZ!+2ES#=P-#%BAy%@E0Ol6$5^OiB~??~e9e9eOLL)kh{WdHc#0I6w0 z9I_&%SI&ew$M<5X@QJSz*PG8M>k$3`#k(D|GbKwSH^(lwog$XcTt3j!djLCBj9rD` zX9GzV3?o9gl+&J2|E|@=paRgvcD-SZcCQ!aQix+lZKp1?m5nrga^;HO>0F6s zjPCW)JVVtEA=NRo-M8!&pY8rhI)@Ww$a%D|*ArE#n-=IMyU-xFd+61uK-mFk6@u)> zFSjSk$hN;yf(pD1&=_L74usSH-LCI6#Z81nDLWD=PFS=w0$W0=Bzo_Z$ZoevQ;+$a zvRPqLS)@fc;*4i%*8RR%tnx)Uj_6?&Ok)okQOkuZUsm=Q0{U9;;3l7uW4Si$fb6WywP> z4u=H1#HstQt6M6lXeYX+KDdpNwKHz;We5~HSP(S&zbY}Wrkh;-G0_p8!8v_9J1%RU zuJx9R=-*Sp0c5-)8&xg1ELm4tI1hMa9cesIcOP!PWX^E%4gBOf8nfYfvWFliD)gYn(v6z5#FK1yDx>udP|b0LUtQCgH=fl#(&H{_FG&2(aA91zgsB_k)(2>7Q0+YH)Qj~?Z+zmVCO_jOAGR48>cTvt$iYP)^U;U zzRDQ!0cCP0+WNnr6nzecl4WdW%?vMWHeQXC3!uC>sfSx=rKNk;T^DuK$7(`w$=48< z6eBz~b7`-1*)MvbcNA?qw;e{Gaxr?Dty9i)*+EtMZi{d@N$R}5u`<#F zcDUg=5~AGe5m8geU%8rp)agm*U7b;7xr-6*-{TvYwJ1| zsXKtGO1+`};DzI|GnD|-f*X^%VZCP;0j2A@4%bxC= z-$f70lvzmZi&nA^7KWbkrt;Cp-oM36`rkBy#)C4bs*sVmzxE4`?6*}8n8m~{3qx$nlSDqcg z$YFZwL0881oFs>iRfX%lbpLHd!q?Kuw(Di?kJl}5LeK9|o%BLWFte0}qEd=ALU#I*(P zA0dTxUfG|5=enxPP)lfCP0b{7cSVAGW>LoocGEs15=#0~5ZSf9)6&$uDEexSUtB3> ziVPz^sJ`GCJV*aNTZQ|BzH@z0;ol=OWKnKbKCaC6ALyQXb(aR&wR9HyvY3m)OG3-~ z)=`vSi+sf2f!%VO3HD)D7Z(jMLsIz}F>e!TS^ghiUjY^6`h6`@N?$=hq!md?K^jpI zK|(@skPt~}q+4l0Lb_3rl9Z4JDThuOM7kXZK^Q{%JEQma`>!w7x7NMuu3O6czRz=F zpMCcJmY3-6Nx0jVT%{(qL~#30cQ#67MC?cMkh0n%XGf)uoYCjD%+8LY?oC^6KE9jh z|9N#MPm_`A^NUWB`wDjyiq0+N-1{1m-#cw7!^gl#17cJPc@LL6X!H_Amp7MuoX#V= zBq)fwe5d}O<(98sN5YF0Pil7FgH=qH+LPFv?z<+$;nRc=P%c*V#Um_Ol4%i& zb__i#A>V>7=j7+mGJXj)#m<>y68F&v_AZC>iih}2#eR0Z*B<#VL5Kbepz z51Jbq_=GXstPo8q_3gON{pSSH{GG?+h{9cGPUBt|>A=u?Osj!ePB4GGC22!N_)2K8 zNW>?GiZFkA&jaC(^Ne>&Ja^LcDl>y&n;l4i{4ROuq6ptG326UM?c7=J|ArY^-z^xU zHp!ODW03s%F)%##CXjqww1oa4F@MeyN}ze?9sA7$GRfpEwGj3%ySm2Fs}ewV(B(<) z*n4YJ+mL>SPuoB=jlVB9R5G_FHGPHTcJ>yMF5pkB&6yE(-m5WN-;f@#ebp&UsF?}< z8e(&Qk(?txbcwfhveX;_BYw7WAR_{$#~p6v`i@B(X)5x4=_^`y$c^IabB*ATwAgjm zeDApOi*(=r6<_mi=Z(CYBO(O)jCNpW5$8+(TpQ18g4z(5d1Wfm`uZamoYp*-$gk2Pg?f7Km2&=ni?V9_;NbZm zh|HBAPEV>Q&@vKHosz2;2I}*!Sg-&dSNz@mId^)v;LMbCZ32fzdP;ywftgZM$B0eDBgNfVltU zo&g>lX*XpCytCy!=Ke`>Z8eLN(tq6IA|%ygLb%QM(Jos@So*8x$DTGC4KIoe@bbJ$UInnEt4<$9$GIdXI*$&vd?uoKKvjtUYDr0+r}Q(=l=6)C9M0o zr+NAAefd+8W#)zhzwgMX-2~I;ZT+Vp$(MFY7!%-qc5T^B@M`&djYlS*+O%Kq?w9gd zlQY|{FBil!i0>9$PJnk0OpCF8tTb+`X60d`B7I1^)64Y(>XmoYE)|RSX)hT4Lc>jJ zd)11oM&OTMe3$-BQmn$5AmIPrskMD0T^duAa{u1-h|T?a#4lO?L|4`d3nrxI2RkX5 z&xjR28b%~rRGiBTt?(*2qlM#%-8bs7{nkI-zc@p?cSN~{-Ru#-7(Oz^BQd`PWGIu! zTmEtdIrN28IVYA6zluL8=h1k8{%C7*e7Hvf8yEdjynI&^NIUMA`<6Giuu8tI(a)Zc zF`VyyXH=@u8)x4APfzMqZ_DDIwuW6#yXErFwgcY&2`XB5Ez*>YPWKpy3GI@Ou#@H< z;7ENP}9&&@d51U!dDa(P$TkMh>9mw`nXU+_Md~nw@+ER z7+nU~YY-i@x}3cY?7S14>y{O>HvCxx`lrpJoxHuJ)U253u2zKiAJsfaOrTvGJANE_ zpts&O0RW2Fpowrs)fbKEH?*E*a_jf=W3TB_g$A_~@TdeQvcJ;i7~oCES1q_4>AGVp zy!dUxVGQx$7l_Og_4J%iRZDt0{zj+VGMrb&Y?hcsn#ReMKzbmJ3V|4U>o2y1((ID0 z$4Vnr)bdJQyc6H5~xSwzmjEz(&&#VpOB zu%f)ccjXj$qt-oCf1G?EMv6rLp{xhdF+o2P(=cymv~eWZE1T&0yFsU-)31qEBy}|% zp~UfUaDdl>g}71UC_!dz|2k$%Zba^mWrFg%M0HEUP~wM_H8nL+rkOt0b}>=qpNI(aX|KZW)&S&>_ee|G5y`|Fl3O52u+Lr+)ipo=7+Se` zYok}@O&V9m-3!0Vh#V|#i%ekKwT!%tSd!HrE#*|I_JT2DJa2igUrg3?_x!#c;tjr6BXi{K z>@x8z4u|GYp}UV$?6#G*Vc`+;mpXqXL$pSAb|_HBI)TLWys#Etwm2(md%4{YQNX5n zGU+zf>WdAWa%kdvcHYeMgcs=;*x5%7^0V@8_c~K8=NXl1^CvxD1apIK12KtJ8Nsf4 zJ&Uy3A|b`$g{>ZHz2$P{X(<|lmM<$QJ*fz|z&Q`Z3@z+!n2{!6Qplp5ONz97@+9b8 z`QM=k!Cc3i5p<^`?kKmCMsyZY-!3rYYLI@BV4gUbTE)be={1a5>6kPw*3F(-zu0&V zSPCY1lkJo1d@dWlnN5iP!;K5}hr_EbDCF+-TKcR@JdsZX>Wc0&`pwbNawnZn5)in@ zBXR9d_SSjt~Bv*zyyP zx>cp0@j!qPNKjeHoV>gx%bwGe4=Ll;-+EGFxx9?}#GL6{Y`qg3WCgE=_QvZnFYjkV zXxkAH3Z?7K?P(QEr?OMb5+YSLmtoS?L&kQe;zRQK_v=pI8Adn^TUY&sB^&OA^-9Xa z8fNH?G-7S5K5a*V$C&}ge7!XH8;vwVFJ6n-QMwQ^I9d7vR$Xqrmpq`Z+5LQcyR=Op!*KCwed|&W21yI80U11Lg~;uKK+h`Haaj#B`KRO* zQ8K9q-_D-RTu}=vTCFJYm*q=vr5`^?bf+|_`@;-M?CkC?f(Og^lxmq-)G%<3Fu^lD zRXi$h5s}y+QC+?QM|SVc6f--NaGn2+MA-0uBhf#v5Lv=X$^zzHv{;RRhJ|}7YB@@* z%JzMCr~TNPXET);S;7igtzsC}&He3CLMiafZ1{4!)Bp<83ZQp5n?+b)FSUdD%5yu3_e$lg)CoHw+L51~Z#(R5m?P|yO>K~E}zcvm;g0|4+mh*l|#*6NF^smB-ejXXsk?r{(X6cPbwK#Pj?q$h+a=o~^ z`trlib1LLv3nVIv7hWaYyG&U*$fNQ$`Q}|pkq3pN>WliBv~Z7kPM{k%#a{T&^mctm9wCCJ5@Y!j!=Wt%TtQ*KU{#jcg>|8E*Jdu zkA>Q=W#|Rp-mR;+)?5)fth{#V;2m~GB#dK!{U|Igud7qZ9{S{J2h1imT*T^Dj?75@-+E94$`{ znt#(p1Gdf{l?FAKxhK@A(!De!G(DtuN^a4IAnQUj0zm%ZDSDX0$aCpDv#d|&^`;H- zkhVADKecm=N}-p&vfMSC+=Db{E->3k$urK>33#WmBhiJyAAzQzM=|+8WND;m;rc;p zGNxih=x#t?Aeq4Ltr#8D;s0E-h)@6L-0#=qC1H&AtP|-5FE1~6eWWyR>K&877M>PQ zdWms!KUm~2-?fm465+6jVy}!1XjG)}RCuKn+w^|5y8d$2*7&@2?7QF0$T;QvfwklK zf%QJla+oE6!bX8vvfksAF}5@#p&aAH2DdTStdxKw03m<>&};54J^oR;iL=gujsNwO zSg8JoY{fVg68$W<2BOotg*omsTV%cU8((>M$E?NW+xs)lT+N;zMY2ZWv_?c>MwpH6 zg-rW+0lX%=D4+)&&YyZM7?ueBt~Lsgu~(?m8!8C!{GdHQZrSxu97ujQ9WDugJ%Bk( zGeHisP_MKcglRma#p+p78cey*>FXPGdYp(ETAtd4?0@i!%*`5LlOkgUT-6T!4f)EYY36m3fR5+fhni^g2tALh+7z9I|(iI#n zI!2XW6!9tU_Poo_8n@@SQAOx{8KBWye#-25y3eP-Z(z)f(C(j#9npabxd@md7tCI2!wB!0^iezF1J#l{>Q@gwt)n{{RneiUBNGEckuGof(|! z0*(seR$nXpgX_D*8&#eJNvG9w1Y-9%qOQije;u#JUfSE9p!Sr$%hUq#2vPUT$i+wb zjdT?9K+)MyT<_U{rF-edUgN_XA3DE{pOh#js>k9e7Lpc*mki6YMBCHsCPX6kG->9< zqsX$|2w=@WGpX0mqCd`6i@m2o!_(}5<^^lcauz3VeaUxhpJg9SzGAYk>YiE2fYz3+ zjgQM5J3glMy3tY8>2-&_oZqNH+)1Oi)py7>{H>XN ziKkfrZK&rFG&tex++PQjA){(bYTPngni5GarBo#?ecOZ$<2!12qWa-}5cgm&9L-F% zJNwH={lgGSKa>{5i$qs{7qMVl?-;qI^{=sHfMXqmoWG%TKmMQRbWZo>D(g@MEs29* zCmVmnI;V!<<&~K92-z%rCvyZzPPyV%jQGwAQ$ul$sF{zU4`^%bdxssNJ|FTcwTm@N zRDb*g)X+YBkf-5L<{KOB5{wWe(^P?l0%(7MtV+4O@YIkF=~QMXb#xsUxO1-bFI`qh z>@3O)eOJD$6hi+m(a1>W?*WlshXY~~zi)XA*T5lV^I4v7`MZA6Q}0B zv;ux$cr~C8(R@(f+!J~6x|Wb`fzH>jUuU}$cn>EBju`3q4PG0S;?uUxg%MLSZ^UIy z&K~Wa;Lq%%G+^=7v5ar<)@cy$PQibkz)>1g9Pv&Pk#IFNK7&9#d1GcfdjYbhsjDmAdqCz2c zd~C67j?nU_H?xA7j7+bNZuLdr8=U%|TJ{w#`MTp=wSP6R3u7*P<{O-;al#*Stp!OO zoUR=3YY%qUok7QI|40@mYXySXM+2EM14}&)*o4wUPBi1gskLX`yRvLiZ?w28sz&Fc zkH7l{u(B68B;nobzFA;a(?}38KCg1O&~`(XJIuK0P*{^@+HWW-pDrTL)m8Uw`> zr-TZxN`)JSHTtis?b3kFUopN|Ts;lyx(V*no}q9Srs~~ctq(dFEZDrg!mbQt$ItI? zV?cdr!=`!121crG?(V>pi=Y#LodiY58h}R}7W!|O;vB1nO{JdTbZ&5J&G6TouyG|w z{|nNlFg+PWM4S!#fZtBVWSwh-TfLqAalwa%hV<~F)n5Ue+~wt)1!1doo(Fxgk|5{c z?9t*WIPwU$xbEo)NwnfXWTrHm9s0+|x#i3<4AdcA>z*d({yWSSko*@?jp)T~IAz|2 z4pQlGD^Jec#wG&fN5J;o$uLPnb}vZophC{n8H<;po~0Ch`{iv{>C*n3yT3PGZ2&&{|wI=s!1er&@* zOU2g&!ro5~_|c-DzT)FmB!02(yOV1FLaiWe%ItcfN1^xq=}VX9S8px82!Gjq*X;g> z_npW7r^I+gG;S+c+@`HKX+F%l}q4Af83 zKEGpN+@_LqF6-oQr54PyN*i|=ATU*fc@LaASR>jC_5V%GEa%q?GEt=sn3V9fEhd8UI56dZy;aT&G!pr7)_E2?-fKQuoiW1ySAfp@od?ieG%)tWF;Oet_|8MO4cAL1?Ol zU<5>%Q{as7d--}ZIBP7ld*j11S*NdQYdcRi>|FsBAhiJ2*`L)8*sK$* z@vzn9JW3I^L~g%4(tS1+LMyxQ3AXF@25neLX}^Zs^@cf9J9Vbgwo;4ES>BPL6?L*0 zOjq&?owvJpynAw&@mKP^`; zU782LT5Y~ytZ5_C;ZOKn&Pg(wziYgI4z}Jw**O^}Mz;*#;yipP7(ReE+Hbm(dE;Mz zl!}0h7Szb_@-;Ym>p!QK0=u? zDg+e8aTp?Q{`pv8m7}A$tYQPR7>^&g?=_Eb+_L`gUFiJ-X_Z8E>VY%`8`67LhO8uI zDxU~u-?~N>>IuM_wW4%soBx4>+?@B!0meS&e6X&5XpqSbdLpaF8N2P;0mHf0V3I+C zZ#q1`z{Bji$L^He3dA($<2LZ`^!!;xxVd-5q~|!$4)n(B z!1@MZ960@T)e6s_qlR<>Vd#sacCZ}I665}AQ6VAN(7A$@_T2mv#}+_!5bbHW4gzcN z4NrkfGVb3%^a{oO*H3GE;kP>lH4W}^!d@d(O5m9X!rSc=66&}c2yA)Kdkn?hSoj~- zKZOp%753Z8X2GdjL8SM#mwICHO=;pIC4nBgC(z8Zl>W%bv~5!CyTP;RiICv?X!TtA zg<-=7*>yQDx0*(p9fsxghD~zmRJ*^~iG>j$IC+0`TfY@8C@JdLy7%10;wkfwxAk6jq&x~oX7rP3I+`0vM&!5fQ`RV$B+gIPa?{f0KB8@oLa)leuD&Q5hIMIB7-&&#zXJ&TK%qo_qguH53rN=A~r zzdc3K$TrH_H4$ZMkjP3(p)QboU$Rq0LqJ@0-{;O zw+BlUnvrFG&g|bW!hl^GQ_(s62X0p8S>e7}p^NtgWnWIue^6WR$*uFhb{X{{HIrXR zMn=AH>7Nk1rkNWU-N$4K7=yhp*5qPh%(Dl0QKljiXhD(eCsiN2madgtl({khL#^@U zt~exdomj7s5!AXqve9-Es%mN*wFAB-4r~V8!FChyDQqV!KuHi@x$N$cl2gnm8%g>5 zEy{BH$(k0Zf|IkdkT`)fQ1G{%_^di%5x%K!1C^wWjg7R|mX+Bvcwyt;zWqqa9RLpZ z#y6u=u-^^p9H1^sp*pgBAlqjVCrAbZAS0F^HGTd4AhQquIaEEa-*rOZ7Xg7x$DiM- zw$wNu+uN_Tqq-Pq8!kKC%^FZfAeqEE8C>}p(7t(rMJ5NT#NAKOSTRT`GN0uycS?eP zILZU`XTdSIdPI*Dceu}N7(6sI1Pdets{b7PU2lvah8xuWl=QCyC8LbqVS@baERVAL zN%CozG_9^T4|=r=MZbRg_6{Uf$ln@qhUNZ4&|`frWcJ|VH3sksyDed15nfcx&1WMg zZgq`;STeN|MIe7Ifkoj>_<}fCA;evu_P9h5yAO>}9sfr=Y685BlYL{SPFgeH6{(rI z`k5nOCc&wL@&_Pu_w7IPM<-2LvRm&*e>`8%5XMVJr9v$T>k*XlHcZ53T^L5B1eI9w z#J-{bBxpf`>!#E0XxT65k(eLwuD%0zO-i!z;Ur3%!9B6gvW>17tFN``(wsz*&!>NN zr#m3t?PmD-hW^CzsS0qJpt@qK%FE+Q`2M~egn3=XqR0mb0+zu+h=GP@T>DSnRLziU zq<$3>j|xWNWmX5Hq`tac6U|&u2>xkyk1!Qfa!^D2S{5WV?{Jd`Pphemk1phjsBm}e z?1;hV+o;pYJ{)B^`lqGQJ0+k7UG;bmLFL9QdSPrX~q7p_wO_N;G@@G*%@?OPbJ3vZj0Z z72$YY`Ad@l`AyeeVSc77IXU>R=$h$xA@RPtCx5nF>z(E(wKkoD`HYdHgL zCc`VB?b>3pA6%_0+&GI>sw@9|Nt=x1Z)h(EDSi9b+aapgxga0+VzT(dv=hiQ_MOt1 zRFiY6Le1^mPb%xDblFV4|3e^~n8QW$RaM(TSt^M(^J147UP{M%R3C!rr+28UcQwYobGLI3sMF#Aa`= zs!yZcgzv5E&SVIZ?PYp3y{NO#D^Z{$o*SCQL%oVf493*m3d}O#SK?2)Ykc&j1{YV& zd?>C&_etlqMbSmcb*h}CC%PJx$36L4V|IN~Ji`gSt0vjW@Nq!1#hHpgX5uc3_U2~U z5gGdkX{I!~n;}{?j~y2R*c85GY@;3;XTxjPro_D%%c1XXXN1H?T3qP6=6?&S1V8)i zX)5qvWYqyN>7hAerzm=S4WVR0pM+79$U@d6ga!3+ng>5q0JwqoN`QygakRFRK^ zOgceG5w>*rlR!N>5}!<)jIzy&p@H=be0*{WB7|P4(a*Dms%+D{zEDSiId{0j#oHJw z$qtt}***e7eI>R;G~=*7)NL9-$emhn8O68)G~#Lq2I`@1L|`8RH-1=8P82k4@yEJU zWUB+s&X#``C%{`l<*Do97`Qm+;07Q@!8nHr1$ZYClbC@@PeFj$x7KHs7*;0La#FB**Q2=R8-uO z&02xpA7AQ4ycSMI8yJZY?Xl8OhQQ;?IP#%;o`8S>v;eSu4N_NhMjm)br}@)OXy((u zhx4*1$jWum^WKY|bgt&2L#Z{qg+q?80;EcL z{!R?X-@_4$?v%7Ko;(i+B{nKAmXE?pEDc?_FC4t68H{z}$^l_ZQ#-pz1AZhj9H#3w!i1RyNX^qc(@NZ{k@Jg>%S5i!!4U0ktnx6xSCq;25K0KFTRqr=t!1R-u zSpVJZc$_pcD26tnRXsoi6jl=8=4^sjw}_OK_iHKMtN~|`!^JiGhlf4`b{e+|blw{9 z;}ZuK@-ZP|ig__l2oTwyIc7@RJ_Fi4BfEO|gR^$ZNwWNNhLPaW@f{=Ps#3r3j<-RG zyw}Ehy8P~9{>Fbwkuz-lnNZfFammvuH?rhP#H|aus$x-6?ZWX|;0l530S(5MaK2_B zXfnIG)N@1UwV2}0;}4yEY1j9LlbV81skjo`=WqjAaMc3zQ*l~hpCMO3?c1>P&Bg~h z$wf#A8_9I2u}~t!<>TXi_og=YCM**)SbgF&Lg1mgx0%%3i^IG$`Dn){C)>;UU$xSu!bLV*(n`d)QPL9Y$Gwz(bp;WK*~GdMkP;<{1X zuV#6&nzhkND!_O~Ec#)s!CFf9uWNyPw=i>f_cwQ3KE;_$R}1gsM$Lf`Re#6&fu;+ly4G+>v1dNUv#iH^ibdQ@79%v#Pt7rxx7-=_|8_s=}Nz^ zzE9%hBbh-FMJ>~DMACLtBE=7F9JKGzfaU-OypkUS3jjo%HmBxn~e1IPoS z^Eeq~zx|OckO|57g1S8-sUPtJHk1#ePd4OWi59x;4V-;3Zt$WZcN9B-6;Dw0 z#X$tPn*xP5{E%RyETR4A8vmGUN^)}8fG;%zgUZj+F|p44iMZR1(d9%&hycE?&AwlD zRJqLhD~e+AMrtr-<|#&lFO@@{eilcL4@^#`yO?JL81%Qgp6^@s(?hMUcByjg^To2> z{o8mRgO+QJ-%*H<5iOk3E6T~+G@@yJnQQTJU*NdmnhNe?C<{HdNA&<2)RGQ<^yc0p zH@8GU*q~3tbq6@q6B@*V;%&=1geyc3LnBw2Z? z0&*J$e4Fn6yYA35gU;ih=?Sz3&}YDxvz=H5QRBmblRdeDQEQ#T`?$FrE;-8WE1iTj zA5Anf(OaZAwz$}FI3{2~rdToF?rKt=gh@ZIx|VGE^Q)ic0*XvbN9G1tyY5-(n9_Hl;Uzga=F^@lKetBzmPtO#AXbZm zUTS;~j<)*XAGR07Lha0O|ACl|WMtu}HAp(E*H2lvyYJq(9)i*g9fHIU*A339l+Rv| z@iKU_19Az$|CEBs1gOh;oE+_X?oPSyjh6b2Qme}A#Fy$8O8Xsx>OYHnyBmHW2YxucOF@8e6zt@ojesHhCZNw)oX0uHhGHWfd;$T@fP@Kl zbht7MZbb76Qtnu2z3G5IYGKgo8qS3SCyx$(XelWdVBHyny+NnDEtC?PxNI<|@H86G zabFf9mcLP~y8xiUH3oA1V%^>E6xP)f@JpTvJKf+S_z0Rw2wNJN(k7OcE1zs!({Xnb zX1v|N;s$7P7UZR&nFsZ8+${ph{gqI;LpCt`V3p0yc3ZftrlGM*fasd#@%4=1o6}E> z;gPWTQe(1G`D)dSL5yFfaaKHbWk{R}A-KN_b@j#o8oMo?OBc_Iak-<1@_5Jl?`fZd z)9!&OF4Zj1nNRVBC=*t3W2(Uu>zHu&mGaZNDnE*c;_9^D`(}>9H!LR0o_(U(JQ&hP z;sv42y0u>K`m*HE2o#lKhXI%}tHK-Et-49`h$FBF%mg|P1fOfy)hpRVt{=!`aQ$J4 z`V?iZbaZ%+xjz4%JUqqQg)IJ)i@X@pb2s+%=UDeZ=LN z<}Ng$k_-|3RD!6rSBqOc(}}dT@loeiK%S}f`>xiT7m=E)s~*xGgRpkt2I|bt=r?bB zdQSwNC*o?nAgVxciGW+4BL(lNJw;gD{2%1oQEQom0wOgk*q_Lq$Ce3Y+he5#m_=-h zOh}gW#!w#M*ighux`R)S{T=)K22Qlw|1~}6kZP>F7(%=3yFJLk4_N&60CD<^vu*af zU2OQh??3;;1*kOl&4{gLQHr_Gp9Hcf8%t1rnX^DNyM$Tjk>vN4%`r!J2DFvNC5Wl( zq4HTt&AeJx5?st9HFD``{`|y`uZ_Ion8Lwl{jo#mEu1cAhxabf{30*Twr3dOcAab$ z1f7;y&*|sBFC~pewl`Y$B?U@LsfEQmzpWmVx63EKnvOnOC_Nx`@8vo&$OwHy9uqjy zb@l3184(-P48;=6=aCCH9byQH>)ZD)xYobf{_ZGfb0dNAx^3EWIy1+GhA6L@JdS9S z2fw}y~<4v1BQVhlbLxi|WM2vVig&CHoU3DjAy3#JZFrs+uLZ!t=>$#Mm z2QcFc&Bq2%&~E6YqPf{BO5zea%AAJakvuC(T}_Pi95qcpww#^qV6qHw2*x`23h z{>;^Ez=o}3?(@-d^h$E%^1?j3q^Rgm4+o!~T?$?#?i_?w+|0cojaRJ8%l|#^*6Xb$ z`2be&dtv>LbzbRXxLBoB@upQ>t)Ohb4rtSL_;J^ac2Ds9r;j}E;ePGBY7WWU zLTNDrcbJpT^2fr7QWtGcO-Y#p?>KZJawjh9@ZI`WIH$Rnm*iTz3h`egjxu>n;7D?3 zWPMv*1Rg|6HAZyJo7*#rWknJ(Sl_ti{p5>pMGRbJ1w({gWmGHQNP_FpJ}(^My8-`J z4WFz3Hl~XemGB@U@~uVGk4Ppz+Ocrm+vOF`%UO5U(PuHR;bl@aPiUAq*;qV#V&U7k zvg1E_gk^b7d4UNOW-FOd`B4`xF+IMp+=N~cs}(~%se=LL$??p|!Pcm0J)}8I!OGz~ zxR)LoMJ|pxU(k>}I0zVA?BAt0JAT>eJ&+3T4=uk(NOM_`nt^;V zB}F6bhKSIL%F14;^@fZ;peCGQq1GQiNE{lsMZtDbdiyo5?O}j}%+|HW*QxtDH2Zv- z+MRgwixx~pe5NMNVOe|){%=NAUVe9__Bj8W`#>I*Pt{XigpW6#PsMwoq-C7+!%JMz zC3iF;r)Df82JtTRCNc+vG=zly$?92lxYTHm(lqnTV!YDHAnG&?^F%sW0~OuQQ4Ho_x{#1+2COW{x&_s8PKB4>qOdTQ6Y1u?D5A* zwnG02(Y&slH`0P_ctyBgsfiaf?p8kq#t@8LVgCMpO)F2o={+AGM;MHCU>iP+wZn7~ zpCwL0jC%Tfgd&_}Q00+zmQOS}-JgAUVLMfZ9I9|}_4vTNz``w;z(6yJHK*xIh-vKw zBIp+gTl|zBQ@y0K;D|O&cP(dqsFygjUeoJ}*crtYWzZ~K{(~pW7$QK70{weyRTL`}+!UF?lMpwfF$rj%BlF=5>kXlcg*p83|?|?T*Pvv!;0yehb_R zpIq1DfkL%6gH0c^BHZqk2pJQZ@c{iNV{S=^_2xT|6Wl<2<~U()Z^*hGDT1d$Pt@z=472tuab#^&Su%>l08#7BrzKjhxYGCxqB$;wi)>4PdTZE8E+FJ%Dh zugBAnHIR3E*Yfmx6M6Y&dwMjzXB|oKX|M|yr#Ilvi4yIU?0?p6%iB|%&e0igw3aK+ zh7nvASG|$mV4n;O>BiS*mtuWp!j)mzhR_X9C_B8X<)mAANYBYRsV?=3>qiBvYmT z;enaGy*jF0k`3;$491LO0ExTCWKy9>^XZFi{Q{lLX68)9npS4hatp!-cVHG_o@L@8 z24&^$1o~A8tZ)1a1+zuX{BQB`x9yXU`r`JPFfnn&#`BEys%IfTGUb9FEWg#bQXyd^ zf0BaM!JxirLLQ#u6^rNj{94JIwdIFAQ6mpY#u!}aXWg1BCpYw6^wr`i9BFN>!;`?&wUHMd~ zos<10REZWtIRFV{Mt4gx{s;Y?NB=jpZeJL&t{yKO{qR&VJovQ8U4h5r6nl@ke>6z) zBf9Bc=#P}uJ=r8}`uH=3FOqBY$W-dV$3XnW2#(gSwblD3&(^Cp0#7whwcf{*Jab0s zYD(_CFl}}d6gS*h;--IMzLeG%%m{qb;Y8e}2<5z~=**OCF`PdRsT$1^lAR+Ayxk zvoz2N4foT9uv8~g;*OyGNZt4Td?F{_8A)cC-fYY0(9d$IAC`Dj!jKs^X|0F$tzr%8O*hx)*YrSPe zM0C{bajT-uJ6;=A;SOAOhH^q+ZPOAAc~z_`Q*XDD@xB|D zu=SHtD4QGAAY^BGVjs%$`!)R=qkTbC2bseTEU)gqDdR>{iajikF0sk&^Hu2j&eZoW(MEOU_&gNep6lXv4_##eU z%FDYadogJoX#&s?=xS0R_Zv0(KzPPj4(1X3xKsJxgr7IyV%D{?zM_#m^r#f|sr!72 ze)1(fE=?|t`NhpC{ed|Q8UFUfyS;#BR3o1506nSsczoW9yrPZkP-ArQc@se|UB0$2 z8X>{@AzD0Z-%fX)zf0h!gWQl}{%H}|kh7t$_VkD2_GPwq`M{aJ`E~+%!A-ity#vIrzzWVPp>NF($NejxOxm#-*U()1t11K;7!H~01tr)%w~de zey8s+t4r&#kzk%~z#QM|^t3WfRPv{;*Y7*}X$(Wp_7$=U<1~jm_qFI>zt~w=-27TA zooN1#i{#gmyR+W6Y)X{7?2E&$)LFL+xuiJuxEa_Y6}f}c1Qx0uPL&jk5il8eyBMmS z88ZIpUg7b+axKGN&@f$$aG#HfbAd=7P4z=?S5%Jjah=kQn?)7&_Vy*5ohn4Q;{D~} z>!Acu4+hK0GVI`)wm|L8ZPU|V+uY1ju+kEZk94yGiWav5&_7cbWJywter+l1q2_>r zRZ(5di{1GOoYdwa*;N;PVD7E&c)4St%#&tU`$z9es=VT zl=YXC%eSixMi=!CrXKMghy_zYAidB=GMJm3#joGiGRt~IdcBWkvZo?z91qNJpHf)|4 zNlN&Zbqh5q#`8%9Q=QdD@SqD*g&Gca4FT=OE1aCqk6RMZ4AT5)Y++UrUd-9Z@|R4O z=|CQW-)CK-bH`)OBbTn10Y%O(k3z>mCWIC1Ww1R|H@^C3E)e7qZa>pBnz8n^|_d4e=NxPv1QW1vkReFxed$IXEGDX%2bu^cwNj+HXh97 zHNQuEW{dKJs?gNoRW{VP?jJnD=}`h)+!hq;0+4p%ka3xSq z-bF^Ubk@QdiG)Pa*WGn8#o24cd{O7j$qf zR{76Y7srEo79O0e9Lr%rm*nZOOYxnGFQQ-%OQRA8_PVEB=!ZA-uN8U&h_I7=o^K-e z_wcsWCCOtAGr8=W`0{xfH7$aH`$tn3?Q;V8zpj4|2&`TwHX)sQZ6kLEpG#dGDVG;0 zcxnbKOk}dWvC6V*!rjyQ;pt#TxZtmzuO>Gt>Ou>pf--0&lwz;4!Lw(p%1bkyyBrv7 zmj9)+hCDE^^fGloN>-#9Y4Nz8mnuB_Q9lKDxZK6%75*(iYnH`^T zQt7pHN)ehHAF{2o3gYj(o$&+3pw6#Ra__Obb4Ft^`KeYx)}$Wosc$zzhhoWAN*dZ1 zR}YUv_7j5Z#@<{%GdKp1W# z5*1~$kk|(NxqpC_ARmlzsTmZ&oerq1gvwZSIU)|0Wzqb6XUj6Lf~V`vH>ViM{zN>K z=C)MxaAm*jRSVRw&jhO3pi8pi2_fN;T#%TYr6^CQ*S8VUfT9FfTAB#a%Kjm1i1sG` z85Opp^$iW@_O~ydvyj0D1|?$R>uhA{i9^uy=%pI2p4;PY8a`&+q@|;+eROCKwaq1! zFKqF>nZgl2;tp)ow+|k=o+S5leG3oRqI>UJt^Rh$=7A&`C0P#-lYLHGSzt8_SsT0> z3IqQzPEvCO7oS1T=dPtQn}k-?R-VjmgP+Ykt}2JEyb3~C8t^Bz?H<*9&7er!zo4T) z8Nf)Z$fHzOm@bOq%^5DmwU$b1GOO0O&ahwH8wA9 zaPAD{q0055>QL{enmI989R|(3Z!J_kcN{p|u%qWkF}6iM|4j6Cj9mG6QFQfnB=v3M zXSDMbH(Fs|E`_LM+?M(MqYP2N=^o^I*dIe0WJJE=FR~26)WMi0yo0^uqVGKruGKFl z0_-1V0nFb&0UWJ-YChKve977$ z6V;F82_9D1w|=`pY@>I>;Z%;OJwIh4xk=f{?sG|%ec@*zI=-vd^^WxzA9uXHaCYGy zW_TadSiO7x=Rnue^L*2*-(OPX@b!G|o|sw_AyobRMz?%t8RHwH}T zeI4&)UPn9MDF__VO2x!$fuao+!Nw6#^itB&BG$3<5du4ta!fHhaiYH%I6E0CODkE$ zn*d^vr7+crfi}%g3}zfd3K6O^{}YKhfTQrkPd#a^sKUb8CZdi`P(oy2arLwcHy@|c zlc(VZA83LR>J&Y0Zz(u)$`-f}y_yeK7dNeno%l$5%DLlthh%kSEzsKnTJKe1hR zzHX{l%$s_5e@ zyCNert(|t#Rwv7kViN9Mb$~z0^uEo)n{}#2u`U%L?uGC7(`LAl=IC6XWKcuU+BZ=J z>o1W2g;o9eCx_?jCP-}wk_{hV`(4oDqT!+;0VQ(rFDkVCaZJKj+8Jndtco{$oAa=@ zY!LVu1dLfzQc~VL-~-}L9~gNCtsek&Zl__bD@*O`==w*$B$(yw+M0TMr-6Z(pj9WV z2yFPut^FR-#~DVeQsn|sC-JOb?-F0R8(Xjm6mZcDX2EmETLFluz8ExNFdJZ_)qsso zPnY;CX#d4JMB061ajzNt&*O3_zsLA|P;I)_(!M2~XlFW3@p}FVp;~c^L-n)#o!7Up z9TtkS-tjyluW6z#1{=d0(62J2EooBuAk5_Ivh=j3o86cPR=+1&%58smPk2O1MmApc zDOGdj)lXAFww#aWt)M@sq9j-OxuU-8h28C}(`7#uXw{%)fjpQ%o32kw_MX-ouHJf| zc-`ZZL%z>`Jv!|f7XhETy0%&oa%q{=Af=d=_z+rckRR}=&nSVHudj|}dJ$?et$~najVo6bu=+UVP>(~F$}w8$I0Qm+FUu6y5dD`= zAqk$Tg#=BZ54nWBH%Ox5vPY~3?Y}^9>@L68-RfqTZopPTO~@22_{+Pl;8cUx*2&{s zu_1dgu6WMQq$?W?_wUi}ZC;KO!G5h}Oe~kTIo*8gjkL1U+t#glj#D>h@|vpEOfBQ~ z*JvZBu1XqReCVEcc6C@k5Or|$aLSaArblO)&I#*jJ#n!n_?%INyt)1JpPZCWR_%}z z;-9|gR!(Py+(RfBK0I(uvbMxu!#6(7aO3Rvv3ya|gxCIhiE%xq#0|gr#IU7gW0KU55OUZSjU_IqrULH>gZr{E9Ug8TC8qVog zzU+fRFfdCSV5tTM%t+I|y)=qsqF~9Rck5DN(4ld`@Wnp=8c(P2)Z;*AY|Q~iDWIrA z{{NNA;!^}Nx)`c0+knQE(@is4?8@KhMSVTV(s$_+oY|6l?R|8PlhR;z@)rF&<9QW( zake=Z8P@rY4pH%wv0W?oK>nOZ3)J@#Z+#F}Yr3YKx8O9_F;>QSog$WR!s4mh^X^H{ zQ<6Vvw=>jsP%QIR43#$CgGX8}S_UkdWlfu!^NCglt~QY`Qat$^elyfxj7~{MysoRd zon4nkpO*h2Xv!;+;>E`|UKN+)G#hV!d2|0%Z@W}(&dL3~b^>bZp~qqM z^+N&+Kw4ZsSi}xh(?K$1#Tdze=61`jFRV!3Xf#5)2wy<^e$)fGNl} zoU-R1*xHNeO>b7952>{F)~QBWjk=8+`hR)Ig8wa2f0wi3)>I=|)lYJ`0?%?kRI7Pf zC)VE8E8|O>ibQ(!dF{&HcAv12xk~OmaZ#|#FWG$YIhTLnGpkcza91%1=Q9B6>r7}aSQ>Wx>D)%wb>oz$JlzqGdib(wan2e5HY(uI@Az|CRb z80cOsYv27Mp@Uxdcf$t#4<=bLXmmiP0YF_R{~kOD`A6Cj^3KrKwt~d0m1+__vs$h6 zFYAE#5>wa>b72HP-3#`WWUp)K-tT`fUmB6c7)4At8sZvm{DUU+UCCZj!pYgGvz|qB znhf{@yFvHC;^3?4`19aCr0j@G$E5hS0JnFLQ8v;1EATrluRj`YObTS<@}nX1labC8 z@cfy>tc}}i)|zr{cmY(#pWH3*`<>?&wDXpvUu(tg!T5*YmZvB@ptb6N7QPmbD5pmt zf>En5_Gh%BL=6y~{Q=gg0P-fLL=-tWIRHc(k6RJ{qXob! z(o2b7zNXxOHx4ipdg2F+FS`gM=iayg)rStSV()=&9$;k}^7w~4u?MQmmP^Z1H+%*u4+u%{PKjB7!3>QYOG_5tN^fbdP3fz$hl+9qfC;#c_icju|Y{O*|09|+|>PpmNYqluEk z%9<-AiHj8KfatMB*z7{o%p{YlNeU=EXVO9`PU&N?2xFK)fa zaUzIJ=4C?)Yu}41wUR&5So;?_>4W*B;_lxq$VWMo26LdzEian@CiKyVe&|<{oF+`XlE{^Sh?$#nvs>!yV@$JrgpO?rSQ3iqRy1pG(RChKH(?n!9zeE zm*-YOn!pFHJYB^>l1HZ{8@j}_jq6miHjPJ}(WOU&BlZ;7fxZ5{y81p~m!lLpzV7yC z{C>#r9f%(-FX~q;MjLR$L;b5r~+-+;Z-6XYpTb(?ew37DBfKDw5jALZ7uE2Z~q(zZpq_yvy2v4k-|d zoRl-+R|e-wI^(t$!H8n^%LuvYmbl@|t>ga~LdsVd3V?n@-AMn71K~T|qOXMv-=u+Pxxy_*`4kZ1u5?0>Nbb=g~@@P}BXw&2})w()TfE_6x1GUaL0b zM7+s1XI#Y>JYJ7wqMs{B+#raz4nbvu&zO>n;k^v;W@M z>V9h~mrhr*0JESE55#peu;inW#;=C0>0X?9eIwLT>! zv*10SM2&92Mji62td3)#j$}#(KJ9D;^x(^D-pqp!5e&65T+TGg3lsczaBhT>HF!ay z-yoD`uwUmj6miVzcIOgX$rXy}WiL?rM>v}s(ZZp_tUBQB!B2b5Y44je)P;ttFn<0z zv@VzUm{MLQs*J|n?0Y@e>y|sy5yD@q+30No9->C`cbga6fgwZ8h_DNCw`Z%#yecG$ zCS%xG?F(gqD~aqt8Vs1Pl_6?X*7qX3iO@~J4kx61N3>fNpt0l|L)r9&zh{UEdc$Hw zxwi}l)J1?wQhO#cE5O(dVVsj0&->F`wCF9tKAHV;O@3;T!J)|2H(#W-?yYPFh^j~>v^F)960OaG}Idmu9 z{tB;o^xmEb%ti&MQO#zT*(}L2JGl0!Qere3HwS8-L8 zRm{xnb|JmuCRbkY5--=L(kr(+-6YW%f-7K1paXfWslHFW8>PF?T_M%M#N!pl zGz5KzZEm{TSZ-_WgWsW9Y9}ut$;IruxsT*LdW6lN=^v@~JnnP*zOI#nlJxs4R6&F;&CLFm@c<175bR*mY_=>q}nONh~yBlpm?K1IE{^JhEn(MDA_H_mE@2 z^oAyD#xYH_7y#5kT6w5;(e^FE9V$$B%I{^t#lsKFPHE>;0CKuDXk_oFWBW63t6V9RJgP zntp92lXt8K%J;iFk3BVjgyH{d3_Wem0R0j}21{5PA?T)Q=gb}s+uNOwr)n~MWnfw8 z+H)~u1m{e?guWPL*CZKC9aT(W7YLvmGGqao7m#^!h4PN!TRF4$ILhx11a;Teq#Ax3 zh?Mh&9`f3UsAXp6aryd%&N%{oEZ{z~lzu@Ub^e`H`1A|1Q~g5&ocdF~N3e%ArG;m# zt6#lIJ;nNmKJ)D&Z2%kkkit?Xu62L4wG-hR#Fwyd#MCbebqhb#r*+!{-Mh~E44dGL zE*HmdQAH_lK^3)4HMEQ*kWVa2?IyH6<}m<>C<3->?FtA8WiAy@uF-mu&a10C6xU>6R|)`2JMICkYIk z$>7isu(=ZW1?!9t)xycC1p{?n<8WPUr}JuQoPE# z&C@?J@m@Yjp`oF`fph@YG2lFyOj4O4@np2B=XKtonPab5m7SCc~b@$t33Xh58KkxgLK!9tU&0Xqy2_kjNFA zs^-(c;#-L=c3l(K!8Xs1NN z22#I|I=G?;*L+XnOZcF1(~HMMQWyltS|NW_2lwBP6QU$%+W>`XjgTa+u_eV>DN+^#ze2?`p}7$|3h;Dkaq8qKWc;2 z%_<7#@os`&6KM)w)1;*DZ+->HEx-%iYsg8?!!~x__w^fNo}4j-=t1G1tz z45XY^UQl6ZxP6Q1SXh|)#{nO3cdiXC-u<_;EJ*RUJEw!H-uBZ)DHVeMB6FrtwKR@h zL0^EckN|&f&h7K6D^inlBE#<&kWXEe0&-DdO|_qA-yjNWMym&K>AfG-OylJIGVcS) zUxC~MZZFpj&S}VpTG)Ygc~!$NL=o^2X;NB0t3qYv16K&lQ?p9*@bDhyvRb{_e!E)x{;t3q`g}aU<=K@JGG7OP(-?o4v+c6f=-gf`W#n;#~09gR*Az(4sp*Gi7_YvPdQHqBJdC;OX872ipp zL5I4JFz+uZ3RK1(>u1P&m*f{PKZ5rb5w_S`v6f^Q=}flr7;h7LGp<)m#@mjY^?)gFZej8Zz7S&NnysBIy*;xHnMn(Z6Bl1=Yl9nUG z!)OIc$j$eDl;LF?pJSY-R%xJ*H4#MpybI7x2f+0K*m`;mt88bKsy~gCeb{VblVt>M zJm3!qo!OT4`9>seDc`(A?pe}qV5v_8#20`-E+}OV2h#28Mrrh~=R5Bf|6p~(2fre< zimJv-ukU~T%j2x965Ho{dlq~6|HITZKbLHv^B{U-Fc@LXQpy>L4C1l5bxxbA^fc9Z zPaw^01W~sJd#SBX5|A>u)F@O54lWij2l|aoJy1usGF))UYnR+_XD>5b_jew*ne=yC z={aAwf1FI1&M;KcQm8daF3Y1;2nEIt*hhSh+2mCaEXa<%q?onuLq`$svroVzdnDby znpj9pPlwMPrR}!|jCijzUriQ+VG~@F7@A3VzS7(}np+f`KA*3rc&p(RvkG<*DD=EZ zU5z6zsCLJ|W9R@1BtMIk|6h2f*gAhS_2xg7%!_Tapj3V)tiNi?sWY*(EH%Bax0cd- zLWcwBv)?hy2?GRlDJg%cx9`X9PU&W{Vo(WY^95 zH&yU0h367_&u4FwuNjD|A)9gKX7^iiJ9M)^rR%5W?HTaZlBHRTKU!8!Kl9Efn74%# zS5CoIV`V844L9^c$<+(@+=uboZvw(r$ zzAt3B_N_h;qXQyfXC1(D{nycwCJ%tRbxh`6^Vi-hMbjByJV-%>1Xc~rE8q8kR${D< zPF_0jHQzykz%R8#URgBt^@xAJ7yM)lDcb;ML;QcF)Te0wqwL1KQ^0Tqz=Hw&J745G zrf4Rdk-OoAWD4^JruYGYE-+7@Su?9;?(K>9d?Ybs9VWqMw7P#UnJyWF>~zto7Q29dF6kN1V*fmJj( z7Kgq8ozLyo{f*dfX-(N*b^%J+M0`~hO}`FVu-r(Rp7CD!b+GaZ3jX=?C-A*Iu&J9F zb5WjRna6y_yJICu{%$URM1HomU4GtujbrS*F6aIsJe8p60lIv8%1KX84;ZEzPbVze zd6(4&_H5dr&ep(R{4x8PQSI2hp2^)_9!!CsP7o?zKNK~QHQr2S5q2`~AKn&^O`*ZV z`H4_sA;Al)(#6ZLnt6}#tUR=7J<8ZQIrWT>kB4Ogx~k37tDJI3*M?BdL!bt`1*C@H zRt0T&SwDg*)TpH7t%4H%Br=nNqPFBQcb$p5I?*0@N9ZiH0Ob}Rx`Qr$6l%Lytm-4B@Dn5E1Y1_YDyo+-qZ?6V zP{)owd{IZmx0R_ZUoBr@+XncfZYTajT%Sd^3KmPy>5#|8&g3xqRk_>QAIA7WPy;XU zq5u26z2F3WpCV4((oWqLA$L3OR|g;(V{2+dzZytwP(^9XM5wHUB1hWD3)5#a-A*&H8CGi$!a0kj>YARrR_y?zO!r z=C}+o1!5LKESf`V)_ZfFHv|X5PjHad!+whJXYF8|=piqA`)L<~^<1+#5*r=MWX&;W z?$3JdpC_pT?;*K_ALe^|vQ~%xbi9^38AgF$hCBW{QXiOs4SeyVGqBY>M&n6G6T0iT zRGR#K^S+Dq_iief=9wV45meoUD z{-lfhM@)rbxK)01LjroYm&%Xkp`iVi>Z29kS!?`8ICkS8FVKJQGn`*X5fr$~QS@Ij zeUz3#z=Su;GcP@Q*}BtZRT!I)Vbi5ff)b%oib4^vg4Cl`S9x3FeS78@=JNja;5mX~ zoPLS_?&(YOiZAIG(ywXigY+FP`j9oiis3?7w8&ye5in;r(eMP69O_DZWzWcB1{Z_f zz_+`XyOH%TRyE2|utkd%Mb5lKhSyt~=7 zW)cgoS@yRzx8%-ca)Ic!)t%sv4n7ye3-zx+uY|X!i7}b&42{w+U@CPesg~X43H>s% zKTLaet-H~6gCvlUFY8!d1iIuPzFwFO62VQ|_CR}RZ<#Paw(_L(Ux7dsl*b_`G{=~-Ft2+^eD zj5j5Y`O8tskY*Zw71Pi1!*l{D;PL{nl?!8D3N4aE_Xgo=SE7A%!%P;~$D#T&)Fj{^ zgZJ+ZpTBW^I(2)HX?b2z8#r_G47|>rhiA;7S4;vUQ4y2))zxFydZm?=aA>|Gj{Y%L z$bg4U1iiRGqQdKjSWi5~WW0|4kx6P0A*n)($CjT_E~|noKt&UUE&J=^Wsr!h=mZ6? zfvG0}V`5E}w8T6`b{wwvGbfA}GynEaUp9#khH7>-+s@Tn53uz@JnVUwbwIins>yT9UcW2}i(2`8 zlb{98AJXPpTd0b#HG*Dfg{M@B@1QI#bg9vHX$#E>V7X~c0XvMJwrvb3u^KZ!KJI=2 z1_!-=r#rviUnn+Ecz6_c6mZMMZS9J)ERm&7RUmE|3A^ip8VR&HsRC2Y7@%=;R+8;2 zw)3_QK4G~#_>fgoAsv?oRaG5EC+n`Kr>EfELFsBCyA7rPW=1(5i0c9XXl%wR{Ae6ta{Y-9`E8)Gl>2<6?jeB<%LJyNylcA-S%YCHF-~-1;q}&K zJEjRL)IUwhb>#*jKAX0-N)^7?zF%YX~nhg}vul@ARcjko$cd4+6`uq1Rm~^d^^nAK@HV z5hB7A&!6{Xq<(`%54u^78ZV;oJ7`F9ZO&|5*N{E0OcNZpBO)eStV*5EdLGEf}PfL8Ekk*@NJS#54$-n!zy|WtQ`E*hy8HI@Wqh9c=P#Ip+sbFR3Cnh<#niwv zz5n9dXJ(o;ex*y}awvS)a_fD(J2p4}t6$%fpa56K_FLGxBoee_5n0`PvElmnULRj6 zWoB;-DC{<&hKId_cw()Q(+{oQW!C+Kua9smz6LeE{ACfr?MAcPY6jd_#fgZ+H*4^c zRKJ_VijPJ;*sdBf3&`Y=T#tgVkOHBhbgj*rWZ%C^BdsC6I*x&s?}$*^AqNKs_t-zE ziNT^f!Tw{`zhr!Q%$t!9pSX8Dc}bOUdxKh34+S-ar?Qm7YTjJ~ghMntI_lS?%{nm^ zMciZ*kR8t&!bg?pGCAx<*Blq0uM`$1I0ic9Wm3_?=+QOTq2WKCn{Dj>!lwUZ^BZyZ zrw1ZE?@PEPSgz{17a1s!oV8-Bg8uH>D%t90d!*!M)f*FM_g9Iw&j!Wdpg-SVOFB5 zF4S`&1%d0Vd@#b2YJDG{q4kFZEAC#inW8X5tkDfR2nHP^aQhc|oo%}Pk4 z>ri{)iWWZL6ytnwu)3_XE_^-E$|Xv~YBgti(?MWi=+bNnIZ??^g)pyb_nYi7z;54U!M498fTvD+3N9Cu&`_1PS$t0o3-`?kq8DF$8qdM z?jcf80Jzu2?X1V0MA-MKMH%Pcuqdp0Cir@BnZPY87=9Nq z{*$*)bHj;%(fwqTo#^l&0PD~BIqH2LHANCu*|>^?!Vgp2xpXUj10R>J@$io|Dd~n) z%!k-;dq!rJ_*AqZHe98pzpO~Zdm~z&hKsh-N!wSwd_;6d2f~TA<6oJ?)0_?0@qP5@ zzD;{|HivfKq|Y%cDJ|pM*!xKT5eS%BZx7G!ntjEP2oDxtiO6=^ZIeg)o-*gF^vKBa z6TT@D3LDn@1o6iGO>qocHfg7n^+<0JZ%(Xd&3$XFWLrjles`rFssV^rY^89NsPoO# z91W;n7FS9JVBFTgxqkTz?zsQl+@t`9cC_S(N#Tpreh_4+L!_s5#gs zZeC*k5gcP*>TgD2zsW%bp_@Wh_7#rVzJ8hip-@!Ws&uc24WPcL=nu8h|GvUTp|LDr zlyUp5K;Oox)H#nICi~7IvTI}=e!*0v72PT$w5t#MD+Y@>^*v6k1@WYsf3yH%-|F zHIqZs8epK3Q7-JaB|QEJuWxz$Qd0ehG?R>H<8nRASA9YC!C8Mln%(j^#d+J(MZtE5 z9^JJf>(ZrkA4`mv3OgpY<`HD{wa$Cws&9u&Dz%}(8v)Mx=m~=a$;TOos|JI)*s4G7eEcIX%k1?6t2n6{lBjS&))fWT#h^E=ry$O-?doXr|Cmzqm1es z8W^F~$O2{%YhB*f?9FcJ%uLwPhL#qgQR-dk&i8i*4ysFqUhl>5Irs@V!Fw$g9xN*r zcf7|e$5qalyyd>WfmXKc(r-dJlUOFxvyy>Xd8gCrm`(DpW={SLD*N0o`0n7p{$Gs> z=a=s9)jAIB`|+R`7GA_GN^kkX4gqJ35=Hi zR_1=E#F#VVH$`M|So+`^b0DsG^L0oZxi?TD(diBU28)`rSbf4R`erBgJF#)2cqp!f zrLvDBD?NsNYw>xVAfo;{G_Dcbiw%VhvU#N8wpQ{Z@DQHc(!7VD;kV}4LW zDbU5H?kxqUeBMhr2v2%D}bN87!>e1gu&)Dyh#_O`^3YHG){fL&nYiXrENfM&|D{~o;Va6T*9PN@D6AtM{zDx6J)4s&x9GCyP5~&e zGTy{{xwJXglIIt)FuGXWTV@vk1(>JCZS$$BR%x&hGD@T~4OQFu!|YH|hv|!?iwUi) zfmap)vCe&KAk0_5r0ph6r8CL^n>C)-keeJO?jFbVHSus6-hSS*mG%^>?7K9l()+BH zt2Wt9+a45e|3EnH!ccLq0ZHysvxIzy`6M@WNWUu9O4^+G0DU{ps>PuOjEh%d$P-rY zvhKe&hop&H?;Dj@6WKmJ=>04S3)XvjW0wnC-e7mT?Ei?>%UPJ_I9%g^uE7J}Rqdft zx-Eh4I_PJZcG89=EiAZ+ydpVf|5o8{3Wt87SoK-pypusA)0 zpGf;78780H#xl7N?_5A><#vuZP2Q01hPiy}jlVqgnV!zlxqO; zgN3aQdy!VGFl%Gepl;|pwbe=}x7p>7Xa zaQXFo*c#8hR_(KJ!@b`UGjC)Ofx5KaUy_zyEmTu1q`Oq5+pl`RyAMqA1SLV-KKI&x z1|^NOF&6yReD~usVRZjDf$gP36Hxt?n~?gn^$<|q$u>fx-#q(FUk#t-AbwQxSBEYA zjed0THJCnE;D680t>LB}S@_QY`Z2${T5_os=}hc49~d-o?D{Fc(WjxIflt8EKvjFT z=TrT$kRew_Rf>Z21i3!nN8t_?JT1@bN~E}_7-J4Y-em|lKHP;}$6R4qu$zzr#xXxv zq%j;4PcFrtbsp~fc>I;AD;0&7R?<@3nn1}uVmvjUCwpK!r6l(+uwgZTPA9o!Tzn6>B^sHqs%KqWTR6kVj@Ie&zY9WBsvjAAnYS z^G65u(RIYC-)prG(l~c;jNvj><2@9mIg-;kD;R@HZk60uP=(Y>K<__s?NoP9yr1! zC;lG*QY0O2VTm}&y+-ib;Lc$vM8MA5_e-EQ$W;!j`rq{Rq63)Rl{$bMShrySD`Aq`8bGxj3cfoCP<

O=)`Ch?K#(&z1#~F>r95C5#xqZ@dp%7jRuXrZO<)zw1zwv#Jevb6LJbn_A zl>`XVxc4tDV`Zrl#iWD6-Z-fmM$&~D)s}~NdY4caF`=lNju0E5rrT`<5wkBk^^NgU zp)StDG)jJ_IP3T{1Sel8m zj0J6~dZv(&*uKLli-MlrGa3Jh;@rJttVWQP4UE~Tjxr2{{;2o%mG-qvqj-Wo_s@08 zRU&?v75&0C`10>bVwrGYX#nt=l$10(A(sIqL5bOau!#VXD!tiN>)Y=7Ol#S)qt2u1 z&0|aG>>m(4zq5ICKpnv+43}h~Hf_tL+H;B(1$2>v>Ka04sE#eP{~+;lZ(sccYum5R%hkaEk(sg^S=Sd)w{zL8 z!scY{{9+f4kqY|$|G1U*j|bf7+TDN2l{}d<(toRnWmccAonT^{6JV9WQtq{XgZkps zQBEDeF0b?IR()~TN{SXyPNG$k1q#4Wqc^lwOodExxo<^f2{bF29Dz{T=ZUEuMGxWg zxfNn>fBYU`y26>2{&m_tD{lE4@9sDW22q5o+vO4kq1ACEP`qoZ>!T|*A$KeEge?k7 zV2d?9hD`t^h_uJ6Twd#*8s1$#iN5_Wk=By6!p<^}HC4A$?T-x|o9A3rL751Qm7x;S zYdtKW3V4O#A*#$3g<;KLEPt*v$D0R%+_zK;88<)IQyO`UJzT`N&odp;sKkW?FMU=n zny{5V@O3(=^5rPboBBXHs;D70)O`nXo+ZGMSdv(--E3a7jE;o> zTO#Qx;hP-XyH#=hUNGWG)URHw;@xL?hxX<|;TXkP1&{-kq&LxDkCx;1%FtNI;9=7; zDlz5q(#a~t=~4um1+w~?3C59@yIz|oqNvmNOlU#%IVL)?$+vx4qx=gD5zS(Ly&XD& zy&Kb%OV8gi6paP{IValH5Bc!D(=8a%8cZodz;pjh8F=p&ujjp2Azt#+nN0*q2A7Xh zr6h#mP#G6NCN=IVSYL;&lJ~Ht&NI5#Nvti!h?UA!ZB?Oh;n^DKR{bDI-H6A@$4Zb; z5YFPpjCBR~jGdEOvVxL6u!}Ey_G!wc7G9S5)9Q5ge!N(4d)dW8?P~Q^%{OTBw zz~i2J3F-B#AIc zXtxSk@KLK-@@BLy4^F)c&BK(!fT1d=^~t(phCvcE4Ce?kwjJva5gP<6lO&PY-;@+i z_9E-0?_Y&I#Zafkj%CCEhCxFIhXJ$WmxWBlTkrDY2t}kr!``$6CndZI?}53{GU6%X zDo?`^0eossDM}u*3U0GBzlk`vt4mPHz<7b>aZsJAC=`}e(3ofLj>TFdH)VhrWQ)<4 zd*%|*+&P!bLit+)vBS_ojDHcXLsL3G6GdCSj# z3~mV=V)FW&qu|kAH1zG1h)V;!#mz%<``=PXHB{KMbwZuej%4|Gi5rN+Y|19#INvwO z&U(?nXuJC2nIqWv%PsERz#0nx$BcAqB5jk!gO3W2pv}wd)_$+p!gzGQov^`lQ%-6r zPL`LNB9AMWQ=NhmO0m{$0?VA85AAoOM)>EwZyw_uRA)o93k~47Z z7If9w3arH0sL~m>dZ~@lXYhHkWf`3der`saF1gIJ=UP*h2z{4jESxm2`Iy|=f=C5D z-MNmwxjJrl&ICF^Yp&`9MU#wq40YFWC-P-R}4pR;!7XVzk#`K`~B8y z)Uc|9(6N|xRcE5!$gOjiE!^Z2Qnu3<)T0`2@5^Wk;&fELlG>Rw*grv5mP+ z>^q*_@#T4CJ;Au`=Rf6QX{e-UuLlAo&~jERdto|ROa6f46}e9o8$g}w*E+dZzfevb zC8q`F5#4?bsK-zyn7&P0&krsi;;&E>O~29(5!n#zj~Lg;V?0kU86H=aQ2nD}wAXa$ zULV0315=B41ZZGzO6-z7*?fatV**pAg(~$gN zNbfI^)%uoa0h?9&Ac8b;p;CaH3{3a~4o$$`czmsa+PW4p_a|Xvh8?@BSD!4RzOwIk zxRH}8pd!a99G%qV?$bt+cgv`pz>9luXkVd+a((aKcU-=?Y_+RrT(Y+H$0}VGPg_SI zV_$V++s|u8e?Gic4*{1mJs+Ot!sKU-Nnv%Iec1_`rx#~4i-uKZCejj$wbgpMJxvEU zouSHY@(Z7!6z>|nhtAXA%D_hZnwY8fm9c8rC|^KJOkoO-OBMUVc7HMR8P$U#@xKvU z_%p!9UUj;e-k$jLRJ~mKuuSfdsAEJX7D6Yc*xpXe)Vm;f`McN6J@GV6oVoff>9b_RK?fu(8m+e1YY z099~$MrYbxZP9LeiK(_|?+RcwGA=!*0tF8v^DDSf)1w^Sgn~3a16C%7-1tOJCCQ)f z4Qf538+k;==-xhJk3DZD&w~ z0fnUdu0=4simamQwB&ZD-YZyn*tbeFQHDUdDB}Lpu;6)}AcBK7ZJ)9T3`skbMr85Q z3((d`$&Woo8e#3RveiWA24Ku~!phSXMN{uTonH~k7cBJcLcqUok7YSqtguT-Nda(7 zVZmpzE>S1wy6wyb;>=A))idg=6+xySA4LQ4b`)?D`Bz1BSy zDM>RrHkL-f!EWI^R!kAkt%&;}Q+u^==g<*T;{Jx|(27?hIZ(#zVf-p{4)@)0Q5lD-aKg-Z_}c0l%&f7xLQO}1u14uGAjnRG^&?%#wKxIf z#-bC_Rr@6!0N$#xFX8e&G%@{@-FC*mG+{~ULXyoexEpN_CoKDL#PeQL)%Bo>n|2LF z3t=XMedVgjwQVFu#v1o{+kLJiIJLuFHJSqPUQQ(#xrP$8 zW_y7X6&*Hy)(VU4n=+R*k|3;>+qE&lyY=k^_wQji-vvA`zH9waL`f7l_Uo`l0uC8Q zn8P3;&WO&%=|-;tYEIX*OtaN!&AI+=l&?gnLzNd2AE3@qEFDMq@~w7>yMhwpnV(FXU&F|mZ$}|@q_S?4`5K-TV$oCIq9XthU=wm73Tf?oTbw#O`z{= zo|^j@K0ez1xhdc$i0VR89b0meRAZM~=g62Ai4hu*Ly=yp3QHAum)U1paLMxeT*4`D z9tgWFmTd@@?hP*0VQr$lTfU{VhG!~Hz(IlZZV#Thj55en_Cbmg#88l9;n87)6P+QG zd9Pfqj`N^#3^H?`7YOkmpErh5;Nf^^LqL97ia*JlFbGL#v8_4tAN6ZsztWr1GQ^94 z7HKT4Y9I{n)+<3`sbzIL zYU0Xu^hxU)483jJy<^m8YU9HR))r>Ux_!ZsU*?CU*DOs@HhRg4?(@z*p8N9^%vwB2 z`$OCY!ddUK#?o5UVDogCX#|`L8*{ySw)=Y>kd2_Sk`iw6G3d=yAdCL=yHfeK$;&dmY34Plz}ELqmJj8{2}eKz&;>U zz$p&GLPHFon^9ZHRKZ2)BSh?rksl3_^ps{S9`awd3+Eb3$s~`>_clIg`3C5_6qM?( zj^f8mcdE@C)IfRILqV+YzYE|2I<&SthRH!!{nB2mR1^t*lzVq*@sCF!&YzY_a4k@E zOZ7Lji~^Vx@ln?UQM!$f zNbokIfZm6v3rT_&=e=$%_E9D+9-J#p;)D>#qWtkXL_>m;N#QFKkQKJ#m3i`VZBlv^ zX%Ktt4{UA>y_k`Y`!}Rm=8yPT3AVMURhcpUs>@IHsv7H)~IL|ay9a8U!Mj$ zU3Y5|e6Q46F4t3ULvGMH<|-GUx4V5R7hvBXYK@tu3!}~*(6MyStmp~Qy^doncq`!!0B!?8GR3{~qt#y_3q7NW(A^_V+vB}$hI*1`gC^M38CZ71okRT*_b-OS2`u}! ztzd`KcDv;YEq$C% zq?c4LA*fch!y{lO`H#zzBdpw|G;~A(uxX`)Nw)a}g3XRl^VJ^KhOzQt%>b1!Aou_b zY-l_=lLAmQg4^^xJR-_v@wW*~k$B+nIF{R^akHVMMgRyKuc%DwCh#?Rzid)lbKIvZ z>CDjSQMSk7KebKT?4)qA5F1-F-ozh-1ziL;F=0>WY=|*(z?C^F4G=g2dcS#!H`9D= zaDEGbzNMp&Fz06+wqiQgeVWex3b#*NC%-whOa|TpVWdi!7big8yHNP_?JS$_>|#%L zCy$`Ni!vIj7KgEQ%U*a>yzPvwf>@ z#NLw!HLNM)R>P?6ctYzxw;u^CjhfTYZ0-Ogw& z@VoHpO|()N3v}oDUcG$Z`m?ZVx0kTqk3Y_m1TakxLw`Itfq7?x*Lf-VGxTZl zK+GQp2-JvcpgzyX5|;@BuIyXdH2KOtWJaCOs){>dZ=Kg;W8UO3=kgE5tx#BI=oDg` zS!@K{K5)?X@1`70;VAfPu;KgcWVYr zk8&3~v-V8qAUmt(YON=+g>CU}=w^+N3Tt^{0{{88Xd!MB6C*w<{v;r!i2%BiL%C++ zT-(U?wSMlgm?F{=s;Y!Wv(FE5^o7VW^Ay}hlj*Khd)mgo11)jk6xp>FxwVG~x6Qx5 zuzVkWo4|00P4A7R!0=vG6cn8EUR8!Wqtg3XF}{WctC1C8;H&~e??aaHLsfdrqp8zq zERM^{TS3xmh6S+3KtCuLk9Ob=k%%fqUSan6K&}rnD;Mg|5T+hTNVUikQ!)@6oA!Y+ zKX({4Zg%9wj&N-=)Ox-v#&&Z5GL;~F&I;D^stx%t_=ZlK?yHVk8?ri?YqI>j^#mff z?X^)1Se?G*!VMeR|LrR0b+hzt7q;ep%gVgQz8E^wrbF-27Q(eMezoLl8eW9@<_|3A zCUq%)p?x|?;IC2x`Pct(=N;C7$Yw5jE5muR{d|R1LFANr^zJ8jvO&ZeAevsYL(;C5 zsyozHYI*?4GI}lBv9H!P`~U+8?+t`eVOif};Xue|=;9#d$?Wqy1)!KsNY#&|+P#dC z1@gm$pO^%v>W@6=guHRZ^(Um4x%Jq4D9XX4@K|+`eVfh>Vu{L{dsW5PUy#;XBKN%U z#QgHh8)mDi!&qGODdFNRzUp%l)uEsS_>4xwW!3T%1^nsUz(Db09RP5{mvRqw&m9IJHhW zbk3k^1}+7?htTeABd1;Xa-hTqkd>X#ZpiZJtE-Rqah)&>B)9X&_858kBS{#N>JeQt zGEgxd^tDKJZ|*PAI}$I_eq0GrTzYZcj%v2GJOX@f@KQi41Il{S%9d!g zXx3pHuq_0n-mu$b&23F!2XH7$Zb@pS{eY}P5qG34kIkNxCNP^}F&vMjBKZm`uBs|e zUN3*6(v4dF`zlP&mG5{Rz5?hkZ|{1n?MqR+ftUW?*?$?EhTdn$v+#3yBhwx*fR2HitUj(K;R+m#nezYYrn zsC4ZdsF0VM&TDYOdWYRLk=MlEuAO~Jyv;@K*4RSLxlau&)L%^6G`x<@ zn1(k8nt)nXOoJ;Uqxy&0DD6UOfPt=}pZ32mUOSZd=;UVKw|hCS2>5+i{_4ID0cjH0 zwl?|Km>5(#aS~JrX3&EJLPi!@S%4vsmH3R&ZmVW#ldZ&E^TG?1aKUgcaW3-zu=SQ< zQGV+iDDBWg4=E|#NJt}%fPlo%Fmy=AkOD(UOE*e)4=79Qs;H=v-fYG zbNxTfHDA}e)_U&ej%PWybVa|;K0EUm+;D4LKEBkqp}~+cea&G7UuYSGhv`drtD8QseYq3yzB5nrCDuDmJRC1K7 zaClo|6ROndV&cMGPCA%XGVV_Ub^NgE!@vx(t;DD!2C%^lBV$M^67*!HxwAFQ4F)E( ztZ3-QcKo=YRL=N{b2(oyK-B16^^%=kJvS@Py=45D@9NS;81ypxkj)_XypH1-%3Nd_N zEV7RlreYxjtjl{fyzBYLvMQzi?-a@1WFLOeuqkx)o*qG{ z-qNP7raCe`t;J+hUAR)(l6jpNHn;d}Dv%rG)oezJ2~B&)jEzmE=&*kHC}jc7B#lQ~ zr$*G|uONL_O}lPNxL+os(v|QknlZc3OEgK=-{AcCaiJg`f4H_tw(V>igzvsX!7V`PPD+F6SKj2WyPmj4MFZONf49;&1 zOCO(%2RwbS`W)KFb$379U}s718rv+ZZfXvVv=t225bO;7+Wp#EOa|BolbQ8c_PLTT z%=vXg2+{2&a6`%{qz^ukVml-&x;prFB#9?pWINFD*7FBP^h6y@?P ztB@ZGRl1i}=}vV7f_6gM9Di-Q$cIF>crCZ(@n5@)f34)xWE?6)GNh%uy>Q!=v;sC| zKs&iu6%9$qUh=c{Ix#gokT0)9Xi5vJe≷W>P3k#(yw<{P^VXdoU25@LMr7&gdck zvX?TwJ2a6^1{mw|fY8M0()au4|C3n3c-;?(*H;rR_wgsb0k+<6yaLKhp>({A)s3Yl z1J=TEURTadOtV0kq9|n(zB;eGc*9s6(^P~kVZ-U){QTCSJ)y2QajFzltbFr)l#!Jk z7btc>F?MMR2ZwrslYd91z_;BM_MS&6^5_Q*2&4WVxTBS?U#Cz z=~a#8RIsvW8pqs3pR0AvqCW2KaQ&kA92VC=anz|Ln90Lj>#%I_$@zE2)b*=bLYhuL zjo?-VQkL7j?1$K-P~NV4BNUq*RzT+jnnvTMIk~{edM`U!-a%|!uBo;}93$P=9aYqi z3)RxixPWfFWpn+ZN(QC%GCg?0?vn1udJ|g5?U$CKFotK*b-Js*#wJDHEY9T*bQFEU zCgm{&kSY(A>V~~kLbGC0ATLGCDmB7ZFkY2E@5<_l8Ph#9^snz2ss~L|fBn?;8`IaC zb;la0&J?pDD*}044uU!owNmu|2S^85{R>D-!5059&S~ZYFS*eI#{a;bRp?`ZAh|>5 zjHw+!+luJ3(3wNJ`G%AohHQ0hh`xSuTH|=Y9*qXWbJLX-W>^i9X$s7@gCZu)azySNS9}(sBQHJ4nR5J`AN@{V?oMlP+eYuLruv? z9}XNjBRBi>Uqd<}6-ACrX~{Xc-{#$oKYDACiTNjuH6lro-PKEvj}vqA#XeLY4MA2m z@i`kX0egd|R??KQRJ|;XIBx|NrNYF$VcN}+Q}x(g+vTR3r|#)`yEICgB|rL)EuY{Y zBfMQU9X?%B`Q!+ULRnBs%KW01?AJiGa=sFGM!j4nyk%j0a$BS3-G(1CuJ1y+BbJYN zD6TfIe;x!cElV^mi0zaPc})VCS5r*-xT;=C){3I^vs#s~0c<6XOf99zpzv+-Y+|rU zQOYX?U~<7Lkj!9xOo%_OLghjD?D-7N?Uk{Yr00qA_W>s^UOW40eK`W0wdI4cr@UH& z#`)ro!NCu#EH-ifVzPgYS6+2Mxl8;;qaIHQassGF@_$i}&)XK%4z=Sdz>C~{m)mvZ za+8o-b6DK|vwm(T+x_t|eD)ZKDdkjLNTKn*uUf>36)N}f5&1tVcj~JL=;;NkodDjoVR}V=fwqTy4 z0u&6V@*I;PJ*>BK^NZAuZNdhLx?@kiR*<<gy6-67#_cufa;Zc}qF3*A5 zM=^i5-UXESXbD(QkYeV}E9>y=ftNsmw<3jAtoJ_O6EOY+xHlOQ+2M)5u>gPJ??|Rs zG%yGL_Z1an$LTzS5Cl@*E5AYH{rFCqQO64)%F*1Cu6JHh@mex@tE9@mEJ(Fu;=}}b zr0Z1|&=Wx6D?4VmWXyVxInqAw({}VQtf?~WU?)CVEuPyh+H)ZF;sO5A^vX~3Zz_g<>Hl~Jj?w_Sx|8C#icojhJx^xr?e@0?jYR`TF;USUz+;F%^{NM!WIMPqmRptC zprK2WA;(;TDARqnBHcMZn$E=Iap}{mRpq*##e0 zE#l%v4eQblZxXKCAAU)ntS1Bm$L#^}D*9XSecFcp)b;uIyGsKL8BmdK9N1c+F-*Pd zyl2`ttlFB@(jIUcMH7k}+y3a=xidIKe@w=qAu29a#AV!Jgu<|*F0P?{`39K2G}j1n zD5@GL*1PH{`Shs^n;oo;isqQ(=Td=FT%b6vs&m=x0Q=A;Hstm~mt5XHy1V_1XT{GY zH2BK2`L_I*@Q~;1NB!A51HiuL6LXZ}O~=KM))*VG{skDm<;7p{Eu89B1qUj6T*a<4 z>__pAe)|mGvKuxSqn^zOfbs0=sxL@q z-^DMXDZDVnVyD#gX;7W?3qoAYUxB<7H0{TJUQV84Ii`d#L|9}B%+0H*sfscOe& ziperR{jFqF_AJLVg*i6Kf48D&czajlYmV23dHWW5lh-xU$s+Ns+^gQLm>D!@Zf)f% z_751ks4u`F;nbAV?m@64`dyRMIcMjsdadKr8! z<)6UCkQ2LoL(XFocd007b8T`726d1DcTp9e@2?c!OCnue;iLMr#bge;P$Wc$h?O0# zHf$JEEzONcoS2xSvfWJA{ur49J~uHjuTrQ0kh!&w=pX}TE5?pU)$eou8q=n@=v|Fsvl#ucjCSmWwN zSn^#{Jp4ETkOeOPFO~1t+kxLPXeW(#6a2a=&mcrB zDl4`0sygdUO3=;CvprQQ4ujX<=eoknW-~8dpF8v@L3a48pUSCxMyq5@XR1KcDnhns z9e&Vz+@82nhp01lO2rKUj}bF0dxs~+dLMgS{CV_egBDO1K?V0w1HZ+$laotgM7;#V zQe*YvC+e5ezKfXcPrU`BZ3zG5;10MStDV*zh&jH00}j2P%W!$fe;D5DQM*5N3F^DO zP3dWsylFL^Uh0f3ckY=Zqc&Lz#+TAht9EV&v>-t6d(W^EDDQGyPZEg|e3qW55AM!n-f;dPNjZbZqo2vlT_i=0uA+$0Zir3b0AeL z^0fg-VovB19teL!w$(`eIw?#ksL=C3s_e<(dz;a$sJ%5fnfx$rH9oWdJG;5#%=*Dp5}Ouil>UyO|RPy7w2rztK3G& zIt`GW58!gfBJGqxprb7NWAoExyO|?<%NtJ0a%7Rl+;6{6$DEs>y+4xx=J|B2F1-@C z7lbBFaQv*_oZ_+j=Z)G@o|W{L{Dwp%`GZ->VdfU=&2Nimfe)+DNzO5B=wEj2*Y!W_ zn#>QAliO>-!3}4i)ol5E z{OY1}r-?JIHM9V!sH)<2niTf^A#I>XFhv{qR@O%t4HaB`x^HK*octpAvnnb?C4EDl zZa>%_PXui$pNdZ{V*(A8yYErO6K)=J z*TtB~_#LFLU>4ldv8tGQWR3%%zdqD@6A6z@KX(rqzUt3!vq9n>>PJVHN z5&{zO@i=4Z9pAV_em_>q5wi1Yw)2`IQaqty7)#@*uFlwE3+8dIO_fU^Riuv9V@plm zVOQN^OD#moIfnCN6_P5lH))qiC~dW!H*x%|9E8LQ+d0=UTnj1gFi(*81tnB{f39jL zY~+;JKCGs{YQAx6HRu9iMQFv!%)_`$$5BK;G@mi;Bjzu{f@&7XaH=?kN*{@KoNE|ZW)NT@WmXEV3IFP6-_ z!=w4Ek+D=4A_5F2%_@^mv&ml_Wu48!zu?bukl}NYG`D9=`My!p#&q$hVd1b>DG0YDmFq1)t(d7}_}Tm7q%) zIx7NRUM(caebMqdqi4T=u2go`$bl@jeorR8p)}R4K(Ead&ge@sv>{<=z5fKQT{w=v z$bQsLh!Kb7`p86)(52D;fndQ^CNCa>|7R0ESQadk77wAjc)1rf5tBZ2(IcUW-5XW3 z!Vqi8c|R`B%kbnKEGL77bIAep+jEqx(2L;}bXs+%jchR*>~9E_eT2grBGJfbT%RZR zm4k;#8}yNaCz;@p#MN8`xrDE0{)&H#iXrW!$*0i7B%4yTuXgT57R~E#=%WQ-8N~Z+ zqtzw`mQ8D{4@ck6_K`k=ODmt;a$Tfv^bJ?IWBF;0j>!vBn{Nd5`oC0wk%Kq6Aa7vw zVCJE^gl&A8zZ)0*zy!HlqqV{l*h`L~GRufJ{LO-Mqc|_Z!PW!3F`Sh_-klAJ?(3Eu z7}{7ui_{1Uyn-mCk<$T|e5z(7#1lhSCM^y`BEBfEl5CNsElB4#iK4m0IkraEy?i+< z+0kYl>Hj`}oUpMp$$hoz^h}3@?Ll)sqTOtHYq9d1YPcqOKIg&6kMRHbJVNu|zdw4v zbQmw4PiDMYmpnyhGTF@hfC7OGv?8NwgoBw9x&U!k0DiT8|c z!G6?GH#g%c4utbLX7U%|H+5+G7MCP(Qk^5TV$Skc{;}`RGl=C&C}=^quUnoLuzh+DcM!GoewBMU{~9J zT=)#nMvYv)NY8KlGEY}*44)I`P2=d8%JE5CO5n#zrhQttupyRp?k6&Zs}OKRtTjXb zx*609DI}|KB^-F;L53fS!hk6kQ8(Ugz`w0eG~c7DY=6ngET??xDHLDm5Iabkf8csl z;hl&FDgbrN1aJH5nL-IJ&9@QU?A1yzN*JD&l_Y`WoOq?ul%MTFNAboEJIX3XkWN5Q zbRN{Jt-;$zr^e*W6gspvnpzofwf1P%^1p{>1J1bo@tjt_##qw(sA>ZNsXCMLqvB$c z1BSbKS!j1joalpOArU~%y#BpzE{gHD8qTrk4t-fLUw~^&pa1vI0eepk(@j}vX_5#C z?3>yVS`q{bkf&M9aR4=nW*f;Lq3DlZ{dA!$VYK>JL291CFu?V^I6-^aI3(uy+0~jP zcFxX3bpZ`luLg3Yz&wD|ApRdkDmSVtY=NkOgxd@~M@KfEcUtK5D2{xuUnYk3o9Wb=)(9pH zuDaZcv2;w=UstHv)k>Vg*$MaAv~Muj|sTt^K9rFYv8LR((>1K?y~(Pwbn4 zvjfi}X2CCLm4$>y@zr@#S1V`HHfdWeM9FNH)iDaC_H%{F+MycK>z@13*|SR$i@*CG zL@wugzxD0&;&uhG_GHt`PpiVAX;}PXHEyEPu;Zz(K608gSc3;o{Kz*jF$PH)(Brm| zE#H+m2Xc9(`|SFB^6%m$XipZGq}h*L28b+{kEXpX6Ku&kGQ0+{H?XuUSLm$3q&4M( ze(F81Y(>*Y%^Sfmur@J<1yRIH(z~p~9}UysCba6|NJ_ix-)?kTqzqt$Y!rV)(E=ka z7sE%3fx7+fRR<(6|dTgYNRO#!P?0@taxMA+vBN_6ymZXfo*_r--s|xTlw>DRO?0dQLSTgy6DaHw^ zNwrh1V=E0sq$C^bk7*+rQZc!0Jv@e(ii;MU+jFa-;Enr_s%iRMlD^l{Z3VK`n?Jf)hyKuv?(>I#S2 z#K@=?fs42#_bdgEqTD znl(Vn@))86sNKaj8VpEEGz(Y)~e`{PJziI@kK z*i2tF?lA!Wsd|kreVmee;qM^Uo_#j#(6WRV*_TOU7{A|8Xk3#*wey7-stBQ>$KpNv zal%7U+wpc(k>+Se-Yu+Xnprc_st{GHP-Xci7y}jSvmyV_OJ&o21Hx)Wn{Y<0&9Cl| zknu5WB-cd-hwx0+25(hPap;0Gjo}ub^v3A?6Qg0{i{$#tr5a8JoUGH(M#fp+5d(h5 z4hiHTMm3q7YEuK9A;;9!{g@_^_UX#bL-btqx7B;>yHzQ-8Jg@^{1-om4l>_K=1~G0 zK0;;EOmWn_>H?R&l$d#Y799K(EiExQ-k3aJfsdO2sx|Hnm=cwmK5E&c5M#*N#ofID zCAWp?(Q2y#0|H=tz1!b$lChqsRc7-{#O!7wN1uidEb$ud)Dxm>tEM!-w{tQulOKsB zOk@u5)Im*jEGvIsV?Qu=>dz%_aNXPg{uf^QyTMDtj9NZzP;_1CTwGobet4w6CMwpL zM>fgBfB3GEMlK4;n*0p4@(+P`m#lf;ZChfPeU@RiDSnM9yw{c1TK4Br=|gNvk_GYm zb$sDTGb^E8i@LUkmlev@1=t%1J`EYUncer{a$A&IGcs5Vsy0@AsH3#`!Wf17{nu0s z2bns-x#sTN=@yJBA>x`l)|Y?8r7?djX$HkiXSqn<(XQa~PIvwyem2E!Msjd%-P!d* zSUNR!sF7>d?86S;J0}xGtdR3GhvumDLHWd_B>HIVUc2Re2#qxBLQnik|iU)E9G)H4bzQNS4fcnXK1YG|^7 zcjwgP5+~IBsPf~XR;@$();If&CSRM>$1^!^bjce=m)bg@wz-pWGktE?0=nUq&aM8J zuZw?K)tf?rDMO}E)*)yv>fXO`DX`8Ogp=Y2_NQEj+C%m?trz+AN-tGJiF$FMx;IIU zP+d1?{mc3&;Q6DqM}%Du(T^SncmKL?@tkrloFVE|5|33x?^Prztag36fBCsE#Xy1i zqwH4)%UA}@NM*{;yPo!*!XP=;@|&reIc5eyHql!ke^Xs$2SWKdA{n zzg(qV>b;;_wssj>bXE*|Ub7oh@gFZhyR=|EX1ZjzMBc`afhxi17ls&G@+m@Zlb*nc z93@0Sp?r*>YEj*wiN1-N&x-@P$lNqAF$1$KWKE93rVv$5^+mmugV5XLk~kAi{Tssw z3uUP+=1sibU4t{mtcmS$6#uW499XGlx)ys?Q7<&ZK8lV_MW1$?-E(dIz7(4}6ZG%e z7T{W~Oy8QA*{SIE3Kgy8f@PeJs_Hz{dC_zvZvC^8=tsdSElbr^Vp%=rmM(_j72H4U z1(;q`Dc62Ow_!D}RYle`I<{T%;k_-e+cw1J&kYM8JC(2%qMCL(aiS5Q?cTw$?y2FL6nz9Z9% zN?wjb#N%b%OiCn6_r=^}m_$%;STTLDur61GJ5G+KTK`-m@EbO|1!dPt-=F&ydWv4J zKx9e}fWnu@F;!!GE}>JPmtM5ckO$q6nhi22dG7fFgDc(hGsmemmL3SVihdhW6?ewV zfOx;KM~omsQ6c@HtC1pP=aNU=4*I4=s~lb@DE2CkshAcV#>X7He)6Y+e$y0~*RE)c z6Z&S_PN)&st^53`W_heb_QZ`9tqbg4jj`r;kJc&PPEvUElIPTNnPC{FHjr55>CbJA zrB`PA>HV;u3i#(n$b$oT@ONjU26|<*++apqb6Q1b<&kdlyS8UuUb&LoAhaZA$|Vg% z23f|F4Yh3)yC8~-*1h!- zgcK}-x2P!P7N$B2{G@#!!8D8?SNFW|3vvzHaZzga6`@bh$&|(%IZW-Ozi)K4ROI^& zx~cz8V9@1d@Yrftd%)R<%Uf!7L}IdY9AGQ=jZdIxoMfAbsbzeg-9Eb2Y4|xoU5mV~ zn}AfK4yUjPTrY=U>(A?@{YIc%bCyJp!7(+`NE%Bv4Jh4OLQH&Z`nvM&wS0K|3h@Q> zpeU-j(@teO_Z{uxS%+(|YhG&k#}hUCK6||}?oiu$pud3N&!Q7k zs3z7W>&YDVappfeG*6PpY>p#z?(DX!ljpEUKp8Hf<2F0F{p8QHoZK3RZ!sGgqVZ}^ zSzk@T^3-cT(!P*DrfB~@TK+K@eCtR69RJBS-1krYgqR-}?HU_tIa(=jHzt!DsR)l_ z_V!^UQ=dvGROaw$*pU~cajBb=3r0`VIK-dLf1MYx9kr3Kz}AV!*IC-D2Me1FDJ}{O zM$jyG_+rC=TlMb>`Xk(4q?JINt0qLe7~sHhck7@VJu_xZCf7=$5AP1Y6UTu8URHiA zN{sMJ9XZGVz$B!g%7Tdz$@&llgaX_1CC%*2cp(r|&D}z94Bm4qZ~>BRR8K+GUZEba zYY{2ob<2T{Y0q*z3{S0lsxoFBpt4W#`pVtwmi`=@;vd0lc#6!=MnHx@%^z9&pZ3rr zOVn`{>a7ir8?Hxzjn_Z;e?vl9?ZmXkIwLJaNmfcU-iNAC4;mP4Nf?W(vI7JA1|bAp zT_Y0@SKoer>QZsJWVp7Ik%G(w|AHh#+immWhZUdqKaUG2vXg3NH!Q;Y44(u55M%&o zX!$g%TJ-SMaE-_6en{Y-)spcUwR|*=SutA?gH#VSo5JvpAFhM@<}R$ee@zG91rIJ+ zLk;E63`-;vcI?QFZX|h`-TX-?5#CSU048xcRZa~Sz4vHgiNp*n0w5sAAZkx6lGWT8 zPtwblMO^DN-23)hvYr^nl=97^4GlFcQ~}UuI94~%XI`In-9{TdzRln8JMeVXR(+*1 z-VlDiwj#lcb+){!iEaT&+PR(=ulyskmX^N*HD#5xEk$pC;chcqkLg5_e;{82`_b8u zM9W>J5mv#B!rpeSGduGf8RSgVIf--eiW63UROzv<5GFUc z4;U-ZJD$Wpy4{xk((a$UT1Xp8FN3dyM|YG=cR_iMg?A&_FdgN@NB&X<&ek)IK>lzW2PnZlAhO<%^!?$ang2l7nIj zypxJCL7T5WTh}WLYd)k85~e3+xRu;f!N}1z z-|$+xP>4leZ&}+i5LLA@;PwqekvtuP4JEAAbxjTl$?%=^)!=2lHuo|fC2Y2U#6Ru; z*aUdq)Hv6uhjfPcGZ9sIK2dux~rw8|cx~!)4{;Jn4MkY_gV#?f?Kl@LG zZh&0n3=(Q8u9`;24ohDz1Oh(Na4OQ?ZCYM`ySBrzRv70-TCVdcTMjV%y=A`h9NS0g z&y>XNAD`tmcrJZn)be{QreT>;5IeK#7M}l2QJ9pRvLSW0IiB2`=`1c2FW{yc^MU@O9(XfHtPbezNEQ$qkznNN{1F0f`+uEC&A z+y6O=)vXVlW4^Z4efGaL-J6l{&`B*CI=c8n$FY|!hXNO!4f<)7$7zLZS@n%ywU8~X zm%2ZB+8PSdWIlht%e%kJ4){aZwf^H~3YZu!L7Nm8f#-JvP{g*Bs#|3eERXSfAc(|% zl`zHjv0twFT(t2C4AIp66Xdd1tQU_X%lY0M2<)t;9B1TFTAls-Ub3SbbXhu=S+?$f=G*Kn~-5JSKF(*940}ZLVVdqU;v_?b1{v~Nq7?a zPA|I1exM+xwqwxe@)IgXU*{vl1b!^Ppv6L(tm<1~`l7la5)An`tdij=U8VLF8$QTa zDLaXPE7#W$xv3F8L5TK)NtIN_a=TA$)5Ss|G7pE>;K`J2Cz&M4GjZB^bgF^MQJ}O^ z`*j`7x->FQa;iCU+KAOw0nZYf=VF)wlPdnQy#MN2Xm@hG?*0tT>hj`wiFKsQM(zD_ zpAAgGEZl$A5|Bb$w5;g$c^>g(PV#v&FXF2t9x5FKu3FFz+@Yh67p{8;}D)pHUakr#{*mBBQ)Y%sX$n77~ zfrcv{!+dhXZ`fk_2H&63z=Uitr>oP}Z%Z_~{J2%eyuR7T8nI$1vV#j6c+p8ekj1Q@ zT*@wOyi`5gKkgi=o|0a_sg>G^yS>&V*>!Imo2rn;bXzNtX3i10IRy4k*cjTmWLJ+C|t2Uj%K&`GAwtJ z#-)Y@=vpiXIS+2H(<=ZxxcPsugkritQ9+OKxSv#0KasFdh~GNo=5x$1Ulgnu^Wth( zZ>z3|Q&xRD=SSo1DwIX`+&C9_A*zNptX>$@*Dj77x~DOl1Z!^@@J*KM~-VnubTrWqE!son2uBJx72y6>>dA znadivY26<1Hu~~P40mf(tb@-aIx8-R_<1}S^}MK2YmNOQJ0JN>t6HQm;xTO-*-GYZ zm0ySZnp!1Il6N!fr zwV`0NR9g%!JQ;ArX5qqp`-?7MGP#3pOoB6?boJMj<7fNLm7Lt^aG-g!SzT8Z5&_yj zEFh?UDu?^0P)dum{^rnDnZ2#;jC;p4DDKSVQ{<>3B(*SwQ8f$Wojk~1r*TtE4of)4 za;9l9GX>y5K-nb* zT$9%0EdGwuIq`r$4|f!?)5DuiOP?fIho;F5rf{FnFVjb@*C%e7YO8YIljgRdu;J@< zzZ%kCf^y4d2#qL()!$S}5-hRfFhs3mFk#4o>uR72kmpiV#1s~IVZB~H)7?$VFMtO6 zNO0;yR)hupZ2t&ObNxfyE2Z{KdNb&w5(U^8 z)v@`gI^{g`_f5=xOP1A8`&Z6d#6BgY&VD>jzVPQ_HM#JWJ8Ts-xB4uKt>@}x zSRQO0XvXE|7g5%dII$2~FTewH^E@`TjIYuU*nIqE2|i!ACcCGLsDVP}aPW)+&H?2e zhn;1whv`}EZFi7{&icHcesyR{5*MvS6J3n807!P~__tB@obhp$S5gR%$I7;|VC}8F zpa-ucvejU8?4^%O=X+g?sEM~M89{%ZMV_w~fCVVvZm6{c)fsoA?gj=Zf*!-K2 zI{@qi1H3h6z^DIN@c_4jIiK5gieO-z)T-$3_b@)TshWU$He4B2l?9tuwg(2Or&3iD zbr~4EPu9~&=9jPSs&^J^mhZP|v$b)EK&Q;CE}QaC80iMi8RKmhr9zOHKwUn|5sio6 zo_jTL!D{{AO@^x(U-cvq4Vu52%ORUPlcO(Y2Fdk`)?;IV|Mf}w+CDy+qYL*4hBy5w5*$67Z>m$BU|)LhAye zdUg)mPlfgZraxScW!>ycGy(?LnC`-neU5Z2^`K8T#I^XWj7@T9r*+^8AG3mo*@I=@ z4eC#a0f(Ip8W3J9_s#lZGfvRymBg{Ml%||0{GtN><{&#o|C3*)zHer*Q2rTj?$E5dgrn=$ zsIJuQuP}%De*kfgpVLv*<*s+T;3||C?aavnxVj@Ke**t6VmIo>>sy^iL-ll*1qNfC z1!6F&!wpO zL|JvA{4k?K##nw9Sp9nr<5d1|-=|QX;AUJo5CU)aP_m#CelOppl-D?Rnr1NNp$S$H z-ZZ6E^K?LRfot{wOIj!&v!)URZ^!J@-#KGDbl)ReWXS1Y2Y!vaa%^gg)aLZDmJx%4 z^SJ=T+y3>dZch9Fx*>kElmGEJ4;;GYYQQbE)cSd3*0#i>cuM^sS3iE~5W)3E{)LT} zZm?KjvIh4<<`qNsLZDQ(>i8BkmE!5Aj{mNzn0QW+PukqaIf7qJ>`Te9(1|cr)sdba zRNk)J)7aMEMPN%|TfNMR)-8-`dXTctO>kF@DH%5o!xJkmE7X_E4OPkSyaalc7)E3p zX5j5AV;WyoV=W(+G+S@>q#M1?Bl{WE7HWJ51kiXC3}&=4pA}*l%X@FrCIxOI_q-Q+;uR zwDX1l4g+>!#sn^}MHAzc_Hf`QuBj9Fg=FPUIap{Bp%9?QprC?y_A&V}lar(t0yjlA zDkTK}F`JFY>)Ewapr3VG)<<82WZ@qO$0RoKerj-M91_@qQkjQ0(^vVB@O(L*B2>6y zc11td;++yIWf}j$VG4cOZ^aW>syWtoX#c+P3*}CKR>99qB&Jh(8t$s^{AOIFE(MPo z5OU_QIoy|`4tw+cq2|*kTQR_y`VRnso4V0KdDkDZy?#1w)%g+F-c+X5_G)?aw74+z zr%V(rzJ^0VvW5J#y~Q5`DdU>u(##oc-tHY(H8D6^$A%IO8Zfx7-dD69<_sC+?Euee zUATNV2bTNlr^^GOch{ec8xiRS;c>2kvK&uW<+M2ENc2;Q=gM!j#rEuEo{7p=(y+6* z%@oZpFu!gFb}~50Q)tumfj=xv^58>i@f&))YS?qIB8Xu~t8#Ehz)L({w5vW>H&!~~ z*w)?zj8JADIZGM3Jf;sbxA;TxS4(6$j|C&!hw0^%?E!;^xfZK&m2|x8Q^K9oic~Z_ zL(T??$Akofu0JtS4Yw4AOgv{!ckhsf3Z}VYKwqX8v#m{5v~QYsF3N2=S22Iw+;x1m zyS)3x;}xe5uWqhAwV%T&t?!0bjN)2cYD!LAI#Gjn9ND+d_eiOuguKh~e>#*Yae(k| z%_(_Xxizv{`I6vJKe7>@Zb(Wr;Z!P}tSOdXXj%T+x@=ODXGI_k6<-dwV0t=vBcT@} zNbuY)mLZyvF6g?JCdfZG`(e*z{$`uxDDXs_(`kzm4ZuwTRKG`N@EDkfQ3{dx;u!?f zhD6FL0QgvPHq7OzJ|YJ+uDoKay(q1&p`MLLfKA8L*pMN#TjPrN=cmclgZRc<(>voq z2<&iB4j7_OF4l<`%7r{+Vx}+)L{Ht>y!-M_p#SVv=Wfr>^koqq&Uv687-bMG9S;o; zYt2}7$VfnMUNe*)G~yLKsx4pHcb#s=6zrMZQ|Rv<2#FWJ_9C(rP(yL5TCjL#d?i!= zqO1p=+q$#&s{;q>rOZx=7vS4Y88M$@5W1(aO9MNuHm!Y>UH6nto{L{RMK`!y&{B`V zN-QEWaPxy=%eP~nNsj+*{dm!CZf;<*V|P<ZBwVYF|2%o=@#-z@AmpO!kN#xm z34yA-@t@9ogZ7eA=&6Q2(QZD*U-;9p zlb`I>5yCWi-)d7)Bp|)k1hhOmG705CfQHjM|B-U6w>?%hR4!7yw6CwPjn1%IFD5Ju zU07JSqEbTht@Y!gyhk|(OUIWxK|7PgxxCMQ2SJ(ighNn;$LYHjex%*C&gRqgqVdBS zx&3V>Kv2KM&OoKdb%p-&;;4nqT@;o7SMifb|J%3#gXr?zFOOFCD+C9gt$$N_NnSH* z&1cqKL03xhcn8}M!s}R~3g#WOv<-TcK~`?~=S)i`_+yHkd=Vb$weG<4XnUSjN-2194O~p|8wG>=%Iy4xOFG2#ec*q-w`^ z?w81OU;1=85TzFfGRTC{aDTe2kz^=2^9SNdX0$vsMcK=bBN!g}e6j*ZEI<4dX)^t& zy0ffsS~fADZ`x9B6wAPkQ3KGmgH+y_7k(iAwjg*(l}K75y^OG7Mn9EVjz`F-pg)Z& z^q32#(+_d>2)1{Zv#sQwG~oFq?Du!B){?yYB;NcU1G;7+AA6B%rb?6+HUcL=6rd4Wqv&qOk6RxSqEx(Xy&s{FhD2 zqX-8?aG3uM%ing-vBfV>Y!b0(TB}t0g<;D5l<}3Zyo|BD;&d@zUjCB(HuTz1mwHYL{;6>%RigR!j(gMz}7rr&c*jsU*;Djnp{xa5VfiEh?(vK z=99y3PlC7Bk@@qg)!fZICiSL9H9-~|WHZ~lIK5y7W_VU8N}KhPu>1<;gVwXyiB8N>7`CPmbrKgZl@8{2Yb&s!p;@R{{ zgV<<^7Krhj;sB{!jmREzKK(ilLbkju(S6g2Kv!Q`;9_?y{eJAR)*C)bZksTvF|^(P z@f8%n^zI+9vR`oOz36CoLpjAYRCA;Ww?5nrW3N9rxJ6ybME~`5`p|pNTLf@uZtQdX z4*)r8^EwbOVDmc~;HrKq3#PG8FYkj3VOu<(ZhGN*1CnjEBB)^b^X)`Y7E*}J`p!;~>r1QEII%i;iEseSqL@mxOL3#7%i~`4oqVa}=F^{$t4n`$v#Tru@ zx=4KT2IqZ;^X&i4hsc4_y0m#*(qPnn-!JE>Is|y!uNx}b8UUCI#D0JovpCSmC&l7C zCtL+fE58}AB>!VKo5GDDNvX^J@E40tii==hj4INSI*o1)TxUQxsXFyzdd(^^c##5%kc@b z$I5IAGk>qBg55ypc(x}6Rg&Z+aIj<7j!L_p;63l3`2MbheMNs2=uGlnP)~MUJh!r7 zdb;?d7l&%A<{c^n(Hpj2FqQL5DAuB%cSzhDmb!H2SQzjj*s1gCd^OK<)_PzU#{m;% zEeA|Qa19#3&V*WUVS|ivcQL-S*R~pyUz^n>=SHMN6`<3=aCA&L%pjm3&YsGuV+5f)^@&;)DPmwm)e*Cl{nn~T#;0t>sadgJ^a0*QR#R0; zV#f3S1bdiFM_3GpP2E!#la92F0X6eUlx6Q6)?rL-QYlj?8&)Cihw-i6QKDYc4Xz2k z$)$;T3Fu%(Z?al4!JneY8=8Oz7DeiaM+rd0uMXTJk(b;bTsa9M2~lQ@=6mz%nSvG` z#0wy)bu6&drx(a_n-Y6OWzA{jRM+()?~j;-&HOUgToH2-$~a9SJ+AVloq5zvg%UdG zPT2yn{MViYxz834FXZYSV6csHKWthr+IYiYVhP9keS6bmR@rORid#T5;F{d$WS~g6Dlx zEYDL;N!2&}inTa0g^abbI^%?Y$$F>Wx@B4cB%y}OKsRG2GCVS5f%R_S+%20Oq&VA5 zA$a_U3U+3X&95S&HKekzoJ0Hdt>GY~fUSW+(4TN&q4UwaD-chd5n>Suot%S%NB~U% zVWIpQ!_Yn}mj|8)@K25emvl^?5vW-0gnWkY2>oD26!RXLK9T?>^_L2KbHG)ZTLPXV z(mKlEDm4Y+YQmL_>{X z>m02ZQAfr@g$vkq_4QiZSz`qn0n;B#2UPI0^89jqt)sukKav*d#u?`&@d_IS~!Z)Y7ZF(xLj8u8Gqz+eQb0N%S9KWWOo@gMG_ zB{K_Y@8sx1!8#YK6@baC2;I?2PnC$7NDgbbJBZuFy>Eja0rU)7PTU)AGgf?5<9IY) zfV8S%>wZ^3gS>C5n|$N5=xZ9cGaE_FYsKAD=1cKHx>S#*)cZH8ewc~{T!+=*aQ}Xu zvoeRZlEbRg?U37Ox-s!}i&{(j$oauzef|H^esoi~Z_g$TmBweN8k{Ju@+&Lf)P{6b zljpI`F~6hlZ;0q>;GRUGeuMN^|D6hI?TbH}CYWsR-RtDF8&y}vH`!#PFDL3)l#li7 zTjVM&i`Ly5olN8-YJG1-G4`?UF%$3VBkaskHUT&kha`TSbx4nut9p!4>p+wXcFCC^ ziNw@Ilr|XX^6=tX=r&C3Kle`(f0$N`MOiE9Ymc0xhBDm>-*vD5uv#O^^eWMzcB{(rdo z4tOls_HD8yE351gLiQ#~nIVMiy$RWSWRsDZ9g6I|_YNURl1+%)%+C7G`+45?|NX!3 z{{5<_9{0Mg^E%JtJdWeKt|>?7iXWJo(%8QbNsP8gM>6QS>F|gjYMC0ARC^1%^i~h5 z#?)N<{;ZgtBo-UD)5bsR~dx&%7AU+cu!!Bl=%k{HBx~NwcKsjZ;Qy1;K{G;k&vb5_ z>n1}1jn5G5Fi2rRe0kjx=ZaUR*EkqP>!)(>e_`f=7(&jHelK-Iwxl6`6xkR1rEl&e<<7cdi^3%8QBvB~c`b$g+fw^e7dt#tdHb7_oFey)G7N zUr8S1VxYP*%ULlVeat`lS)=Io_3p{Rd|DBOFI5OcO6l{oZX-N?cY>D@O6YX2A5iMD zT>Hw(=-+ij$-Jqn2e(I03`XqJlIKa)6R)ThN59pQqR=$6vDkVkworqpm zhbX_Wn>V+rpPtCQ6| zqT(Wb`aRhCR|Z7+8QVr!a^Ywn&E@~M7>V?%_oiwTe$Qt4qW-3;ZFYYx<&2=kz8Qs* za{N`djjK?xH0j3V^J%@%_ABp-92xM>b%yThy7?o1ep*^Gukf!*>3vuGp3OqUE8k^) z@M=26I=5xG=6j9a1@3o#kyJUmp_xBD6?DOLi})0u0zaCKC-xqJ-yc;+;ovTjIoTBc zY?J2>zG+FAPOT5kklpjvxw6ku+F5Y!a`gzeH2Jf;7=zSr5^tgw&vas;{#19iP>L1Q zx%-M$#@yO^_Mk0&*4a%4<<*$uBuR)M~K|SE>;X_PEOUxfo2Z4_wKrMsq`Xd z%KG_zF3$a#z9BqJG+K*_cl**|b6nR)OL#~4hC*(+n1^uc-{AQTt(j+)TO#RWX|W~Q zNk7_A8<*zUH9_~x|M0?Vn`)#AnmIb|+Bv`YBg86vF7kRay*7U8g_v*j?=4+T$P)D< zZcQebUAPrYQ}JAcecub~a3~64i9GD9%sF0Fk}EHWB{UbC>}fOqP51G12j8ulF)g(! z@!m`wN3von$MqtN@u529#?SAh2`X;xl4=%>_lilyG2!Ugswcl0Au^wFbvdFj#q-Rf zebS@t;xM?TLi!=2ej*`vq)huh&D$R@YrjhvwyZ@gwrg9W+zq;`TBOkUv?|m7!VUkH z%x`h_2&onPk{Y|gEd6Tg`2{0_pv=<>-@|(n&mv{=P<4oUZ_wPp1V`d=LyELQgxW27 z91sq}?Hp@5RQf_FOK#T8h}2EL06oJ7;~o&pH214#&_Z|w4R&AB*o@$2X5w!evvee} zlqBt2pthh1wa?O1VAM)|?_nR3(DTofG#bT=_=)47=RLIDUClphpJMNxfS8mlEBh~B zDQ>AA60h;GxVc0{jb*px;}ZV2`eu%y@AqRm_Bnc}wc7P%GmU+Iw8(S~2ljY&)=S%zzjC)ap+g?u{xbIor zV!H1{AO8BGap^lX>>3`q%_)Vu5w(54P8AzEo!3SxTU&?I9ohzJZ71RGA~Oev*!HvL z_PqJ*_hMQhRa?(&ecwM=8R^H-WqFwSK*QWX^`hc`zlrvW8fO zldMHbwC3Ae%kneo@?Ja~Gjx6bFtH@|q?m6AUg+DnU` zLWyV-g|Q{t`gC2}_Uo4YU&5e&n<@jXBB_BQbp#iCV#fOhw4r)kmP8I+@}G8gC6)?B zw(f8tk2lpztncJHF^sz<)A`G+V!aICN!^Vu-1hZGNg2s_C=}PobV53f{3MR0smhgl z=jNF3B+hk995q%bgpBXH>^b?DJwGjD3s%AAnXhvv{{2-zrSEkLt?hu~AG;D^j1lGa zw;YO5&nK!bPdHiWv0szcWQ2dH>>}$Ul#_pS7xQ5N+ms7%gdSV9lP3w1r#COpN3Sxl z2xuJFMyMrD7J_PfOL&KH)hC=ep6Nf=cl*q4_*mn>iK~9|nVm-#6XJfLN0ykL(6cSP zkP7)L<}BT^{g=9*-E4I3T@iBQ@Cgqs&N0SohCOtE{YJ)!ucXtc8yR#8*j-lZ_&!A7 z6JV1=xaQZ&SS!(O`8{86SPLO8scLTrI9W>OJwmZE#Xt6{CkM3C>*Sp3QKL+mnK8o= zu7y>gaI7%!@dx&!gtp1Arzh&qT3S`T^yq}PYv+(Am-^+_&)NYAarT%0uV9x&o+z4Q zMp|^3LaML<@vOX1ScfxIf4$mdz{YiQf3C2uk!|SP@zTgf2|LWkwlS{3J)uOz+n&iCey9;yV+&JLoo=VD~6|>RfALMMFz{Qt4M{ z@3g0Qe{YnwQgW`@ROpiNS=Yy)>BP6DQArX<}zti#USeNO!%ou37JQs4LP60DAz zhCh7kVL`nn=0mnV^ZSc;Yj~@^--w%MwSo`X{7Tv!4cAUu=j*uIm+Mq1T!x$ze@eQN z*q^sP|HlS5BJL_R!1m8dppu;lJe&^E&M~WPDtJBFz`rRe~DEj zvymrK_T>);dY1N1=7d&l*-dLrQulXk_#YmRIeBIeE#W^PDV?{c;+o9=F!Pji(o(si z|KxOS{|Zas_KhkIO3K|e9;%Hcp##1JLJ#3q)GJ+cPa=e`>=rGeQlPBG1jnglLDNF? z`FBy1r0z(~xIER~wVcoLIKPK79PKAX*qL5E91Nhn_o8N|3JwfQo z#%;c>H!E|#kvB#YdUUl$QDBbfi5}7$;2@%F*^05X?XRR1f(y$hr zKIolvq0pnlHc?7Ww^99kXAE|>j~sViZ*?%5R~)q@KS|-dx017h{x%v8L`gd>aW>2% zdAh8X{K9lgVC%E`0VI>yg-YHgj?tZKCpZcocOPf|2vy3f{s9V=MYX2pk71B|yJh6;(4{>WG zcAQyUa!yQzEG(Ja-AHFaB&Gokfh#_Am^z*q>zrhowH+49KEiIWb*`LjQ9WR!a^?HE z>NRU*3`upa9QSQ$t(}io7$|o$37x~VbFhn~lqf>&?A@m3+CCdzu3UA1*4y0NeExT` zeRVl@$TJ#&P7|IRPRF|G;=ILv=$i2UQM@<<_3&jGF%d7T({rvz8V!SEzrH3%U-PDR zUKed@`7^8?!-^~H-!`o4&^ic5kI;yTiTNDsComDA2X2kOqO;I?{56NLMv7-36=VDr zS;)H&wtp;JSwB;zZww*^jTr1tab~kvBCgz87r@_$@D$+FN?mfr>**P?al4}HwlW^! z2-rTlL*sKy+DB1W-qt(ko?Yp?*FxH9#$6xe@|iZc0Ou9Tc4u>YBZ{~*kP z;h*RJhtFpkox{r8FK?F~pPcXem)T1^qQHHhNKwt2BP?>On-XYrgS-dAN<({v+m^F?6@$EI zFB8fUT6Ht`Qsytr>_-zUY72-*ox@x*KV`&N-HjnEU45Athw)|JTd}w~WQ1>|{m<>N z`gS_%nDCq4oBcQVeiKT?-N1(pO4qQve;A|-ls_pL&zVHP%BcM;SP-)Dz)Q!&pj9e( zmmYI6r+T~+Hh@=VX~%3_b-OR@JM4_nzQ-Gw8pHA_rSYOipu?2vr}pRe zGV~!Ig;8=;E12aK44Ci~XMrro9&Fr~;6_bu=G`|v=!?m&N59chmUaIjA%M+wM>%Z4 z8M=2N!v%NVlGSv0ITSXb+l&U}W!(f4_i$EK-yqb6`Z&{R{sxzYXBI!=LidmO+UK2; z{C!JmH2NHh9x?_nuM!1bu*G~OBIh#bv63c~VPQj0#L_RF`24PhP5Fyxq~#s6(!T*q zA|ij57FU_t+bxNYucq%yi;g5opfxv*x^EB}7KhDza)-w6)&FKNV;*LzRN+qi9m2ii zx`fZcva3EFyz-xPj__`JKCK^OjzH${7?xeC0{yoFCMAPS*G8MRB%;39?b@Md72MtK z*h8n;X|3j%^X^|38AcLvE`wt1*w?za-%r?#*$MW~>2hvi{oqluRmxiX=WGTOZi={k z>o>1V_d3i!Gd))&MAvI_iGUP{go};NYjW|yuzja5&ioeKwJIA+1OBsnZtm{uhhC=5 zz2aTmOpy$5#jdTbEr*u4*9mq&UHH`aI6Z|c-KSt?@*>TKuR7ya{Nc+Ka- zu;YsmeHnq{=HF^S@ZnoxfR-geG5hsbC`9OH3Pi>jrG%eC=s0H426~u?Y?Yeog=*WI ze4i6_$%Hzs5r*cxXlD%@@SV_!Er&1g%hTX2(@{#TdWtE=w2Pa{zd$dONgn%E03G%h zodok+&?fP9{Zjo_YuHyRY12$sao2H4m^sGued6+S?EvSsZ1Y>5SzJlkBhG@m$=~?` z5>e?so{?KtRNpZATFKe1nmJzOQpf4I`&)u-)MI@^SMMqEETNYqF<1SF?Y7J6y*cf=?U#V8 z46QtqVL9wfc}VMay>*>Fm=i0mRG3|ciwJq=#46G{oSo*xh7L1twj9Sm3|!Rc+`|m& zRR7Tdhkh=jhYt@c!T#WmQU6P4zrW+ze>RHColgIl|J)LkkAH`}zz&~)!1H96e%|lw zUbf%gyX~jL4kz2qJ09mJdvCh%6|>NCS(k=|=6?}fE)aNJT^ye-62J+k-^off;bMqZ zgV<*G9jA-Gu9thXS8qlouQJB0T;9KRUF^az@H;i1^S|=FT;jTX6-CZfRa@KZf0BKP zhO*PX&sf8AKEQQF4c3E?C~cR2ZSCh;2A2C{i3D=>^2QcouTEl5yCu&bAzxs7wz+?6 zy8d(_h~T8a|8GIzi()%FyWJq#^8ojG-<0f&O-m;EF62*4l>2E6Pzq*OX)PsBZwcm& zVGG=TV;aJa^HJ&xuNHmrX5mD$d+dd*<~QABZoH|VKbKZg3|F`6=U1bJ=8U|((_ysY znI2+4%vuBUN>zRRKkvJm?r`#Fi0c%74OH2!dR@zq^v{w!tCn1jz5E^9;Ix7(y$*h>Zt-|t`X9~R6O1`;+rRks zVdvOBepu{oB(b#WZSCbZYfHDhH)|8*3F&rq1Ei07W3SuMRG|v4ZH`}SM#U%G^!yoS zcVt)bX&{S2PLQW1lxVur(&yH2@9k(A;;_WWYAu54DfUOL%}qrkkM<1h1e*s|rN4gu zD1q{@s%cx}qTK(Y?P_P|*ym-Hka5^3DKm3?iyrA^mTPMGR)CjaD| z;R{D1RhZ_G8$+V-(#W3hNL2xmhca7DhRjT0g2Qu1b=qClto)Ask{)Ug!E2-AB<>3? z*J79F))N!1i}#C3U}0f}ttGfgCBM@wCW?6M*r?ZX{%6Q%h27BD&hGW%qVaTydii9b zW^wbLaD)}Vf-qHneSHcXcFSqd@+niy9l02^b#?R9*=k*Le>cS#Qy}BQ!55*c*Y1}& zl)`lr4|9w^+DGDPs{soI9&xnH-l@;YgFK@Kx&Py8XJdmQRq@XU zF5d{-$ub^Z-ma4qVH1?|>`Pkz!JZy;qfGLbb^yBYZrtGE=kGZ`7bl>VV9Fjfr3jss zOkl!kpMNS&V`*fBQh|Bw)f#<>p~E=DE0G-wpPDzd2XUxYswt*ZM@NoZL_(6e&hW0p5 zRriEwQajn4;SF}B*6Xq|&d{*1TQoElR#xGSjUuaSYsV3CMk1L$614jI`Ul6y&sa%V zlN8);_aeWNurS=`Ze(j4WhWRl?OPH1wPk*|=Bz~Z6R%SBi_lz0VMX`?PEPT~&&zqa zxgQuB&bN8G=*y~-Tnh}inEk!AW$xkec5cpqM%<(0>sR7aAHR7g{894K9qzC-V)ov5 zR%uVeO9Cp7D_+=tOCKvDHIsg*sjm2lt;2P z`@8*>?2rbuf}0-7)%p*cQ#zDA(g4|r1+Hm_i|x8#WQ~W5Rm``diIWEQzuXc2=TRd& z&i|^DZgzIoXPI(-0hxR^QHR%E(p*G``}!~;76MjIHn!m4(B||vZ;0~q^F3CQo>Sbu zZ2}2JtM@NyE;p6f7nM{GZPR)dX?awlJw)c zl3jV}-sIIv`|con`DUpjIT0VpUQSjP4X0t-XC!6y>lagGu1cZ$j~_pfL8HhVB-hDG z_45Ax`we=WeSLitw6ts4SEt#YP^ALBrG&5D=zb7i!XG+jl?bl_E9}vuN9aKhA%fyd znzqAmo|one(ZoLJ(dund92ZwVh?dEF9UHs<7g4@n>fk%1T=`bvgIvM*uYFI255%x= zARhhwC0kotU%!6sczN#W<>dv}&uwmQ3Y&a)9vNVu#?O9IBGYdZz*Is+dK5dmKxJ1m za!tO<2_YzCXP=$@Rhg_*M<%|M?oI!ejM}eaBDMc|0ZLBUCfGKJ$R?EGXlygm3EK~+ z`=4+>*o2TZeT%@x41$j!m7}sRdq((5vrBG;CGqf3o=@zz*BvYg`*>ipg^K;F!CI)wF zd|jXaGU4h-S=vMWTXDg9j+sjKod|0p1nEF8wQ$4i@|Sf;q3#R6q=xocw>t*v&i<1+ zt$V3GysnK}cDADR6FpF7+zwct1DPEj9-=2cnUb~%15D+uN4M8TGP{@eDq31TLnUwY zKISB#5r3z}p*H1v(xk^Jl@pigWDlto;tvxG%X9rh%16y&7*mzv+U+M8K@X=h69>#1 ze9r_W|Bl7NY?xJRi|HzIkeR}Bo*Q_EK<+yClZ51=sI2_w_ZXv7W5z6(CP|2+@aJ#e zNZJo|+j~QR+lOYG-5cH4@GG86KIwNdNsSLSPOE!#-N@K2 z`RbVKDt`X&#r%9`6)oh-{$;@RAt?r45oWydjd~Ww#(}-P(#a_)17^I53U_o*aKpNf zT$^3iiHnMOg@r#sc4ud2f3J2|t?*mh7IvpfviYmdcfJ>JrV&61ru1Po4zdA@>N>IF z)b6?1G)Y^U1+L(l)wksjG&CUVdM-x`!3yYKahke&msZm6^PfMw6E+hu1*aE&fB*ia zxOHps&&m*F?2$|{S;6#`@u!mJmX={ojXn>4ID1G4dz$qxItN*qFb&wKGil4jn=6hJ z*V+m6^B-SI(8pWX=*u?C4By07`)r9C@%RcmDZ0Nw9T6fzft!;Qbw+OW(D~6%T>1Df zwMF;Kb8J6FzM5KK61x}Ag3|UvqCM@y^FxH;sA4R$xn+*%2Az4%{Aoi zX@41B2>UdThGJ^0|DdYc^g(yCmqH&(y<_E<^7~a+ZcIJx`6!L`wsDYMQCR8MCDEg5$+^kxFb zal~W1`{Ae?cq~pqb?GQBZyWsmn-$3Gii(bDhxTFMH2CainsgK%+m z9UC9-K157T{rIu494l#$cz}Z$RQDE8!Rh63`zV3`Nw@E-RF0vKMS~N?&-czQg1e1d z47m0@GN7G$xxcCeMRCiOEz;yV7u;i5?~b*;q4@Oa{$4*Vym3YO2(i}mu7@}zqGd>| z=+}CdUqa}mrlsZTl*TI;WH-H?7-){3M3_4|#z9!Z%zm6ioX_oC&}94k!Kt#|F3#4# zA}LwCV)lNidFv#-{rpL2e;;=5a`Urei0sD z$Vl6TYxC@hkA#8umH;HoprD|G!$Teki4lOUp~jmxtAm9t(==O)R9MZLvv^bS+RsFH_pVsD-?w{TzUnS#~*skfqP=l14CDD28?JtgIShsBQ>G+!@{<;kA^Vv#g< zb90;b#r`fL$DE+3q(l@gv!xz%>XQYf{QLLsU-*ZKsL7I2R1bnhWCc-rBby{O`n?5BCSu&h_s%k0E zd8SV@*oTjm{xbn!*Ig1^>L~Th&&wS*OQ-X!{qXXV9&H;6JpCQ_2tAEaWWB0#6{r8# z`)S`-pRIWm&M_Y^uM{`Md(Gm?wze3EKmcDKdZpFJiEB1pf&yB++uqM!DRI1kV~0nt2HO8l zUU@k%YOOI-;5k9#x3ni53WpXo4g_HlcpUtGv*lzfGwI5fggZ1eK3-4iCr_=gu|{(D&Oia zm#DDP4e=Hi7k?fZi61aaBY!yQ3Q?wIXlUu{n^{_VuWPZwcLz>8b!yZb;!njl^id|O zg{#kvq)OGKRMkl)qTjR1HN9pUkc*r^F-=P*>n)?3pi`$NEX_iR=Px(EsuInqpkD{bCR9W}ZzR!x|oTPLJrLjm9WUQXK ze>E>%DZ3h*^h`S5HCoqVR{42>>apf(gm!sw)z&1oa+0BLbt)e9U)1NQ1A!AI=I9l; z)-WWxovAER*nk#&?P-+z$Rm-tJvdJM--pk4t2I&Uo-H?s?U#*uZ}a6PvMm7@+0?>4 zS#R@KvaH{$uyXV9Jrd1a-COSeRHZ1GekXmnjzknaGIznL(E}QM$&2-;+WPt*^f-6Y z3sgVrXlWUlnFT|lnkqz1f5z(7Y5)b1f`Z~fvN>Fk43V}1OZXlJNkyG%`6Lu07;R!a z%v+R{dFAD!ZX}+qb1}W~)k`0>@|onJt7*@gJ&sJ-@?}Fu*M&)X$Rb)AjS`Pl<=Mp5C%!9DV`}-zR>5vyq8s zg4U*rBVoXdm8^7A7orV|O8c7r)dE98{_lI5}PQRz*f*~)6iDsRBlX7CP`PFcB%buPsW%yB z=~6R+t*gIcW2?yLP*0rG5xi zDY6HJ>L$+4<8EVmEgo-#<~-0U9vAnK1Y8^E=fMjysr&>9CZ0*PR1;d<7Z~Uj3eQQR zqy>e9pr@_Ic%=#R)2NrPR`?Df3Nf_jp^~;S-mJ%oiHQm45fU-DdhNJswC#wwwu}vBaPEr%rvpUwL{@D^jdG=G zCYF5W_qBZd^k`_w+s-kw^u2j3OidltyN#UE4qja=)p;0iUSmV5Ure-q>s{HTsv_Fd z%ENdw#crD#1k^?~Y8tMkF2 z98#S;6Nl+TF;w~RNBPzwf7LbM1(%P{UhotXRnpKK*uQvDSzGJ+k(JG=o}j`OR~UWI zbN_;g8!t$a`4Mx%BG85(iz17PSRX5zOJyKO)RFYVNZvMCf(fqk}G#P%XFaf$P%Ey7zh)2Z( z-vn+jMc9-^t{(+3Z8a5`v8|}d#@v~pd{CSm_mjUz)3jbFtz+vjFDc4L^XCJ46YBo4 zm0j(H-LSL8440|z#~y1LF3nG~crF>a{?HP*ng`x7L-pC&Av+y$FKLfu-1Q-w5pxs| zT$68hH}G6x+i5*UtPY4@KgO?-kdTjeY@T(KokJV~R#)+%I9(Zki>OI?MeJ=)qxtq!? z7oVi5s>&UmAjXk}t~^^>AkVHUi}rK=(J0H-IGKyg+K?=(+vZ>q%J?`l0+Ad(rf_aG zTJ63AT29t7_52eGqwR$Dh)(U`^1nqL8{Bq;V zwW0r+boh^_*WPS9KuNEx^+bT{+#;snl7m+|Y&0aJW=A!;A58MQXxH_M({J9u z!}~HlZJS-LJjOpvb8erOyj)Bw^|?r$?Hl6I)S)2NVy~EpNB`Wu{;AQdZjMU0921fN zy?OH{a82Wrla^81(J}1w7I!0G!B()*>>xBG4HIbm`@}a{iK4^K$%U2kxa`LrSOW^eW zx`JMye>uS0=f5I-Y1>~`!UkWl`7FEJ8au3;`a|3a2c1DAlqg`Nq;ia6PyP%4kzIf= z`?+8H9V@Cu2_lAX(0?kiB`v`m>$Ul$1_q+W4=~x+r(a(B0nrL8mjoB%?MrgYl=SSy{~4qqJ-it_;coOaZKz2?+9-^#(k_RRPx5{T9`4#?xTdh~gukKh0a5AE8du9GDT1t|0%q6YF;Nl{Fj|6#p@mesp%dR6G-qz0aOKYxy(CUiWTo z&ja!jeB7_=HTQl*ob~hH8{jF)4=4v`uzcJoj^wX0*rw^R_Qmlm#U$2Mk!?S2EA z%QgzcMbl4On=EtePdjWsCb%x_uU^G=@ZU(B)lp?`CNS5>(xYe+h+n9{4|cpD@+p<%Rb!?f)Qcz}w=-RHP}yohN6QzN<1w@nwEym)Eor zd&puU%{M$m6@Dx0)#`;9r%86&ap}wK^hvHE&CL9!e0ozH9Zn9OC)doztMK?aKcLv_ z*B?KR=isr0UIu1-de4m*cqCY;FUlhb>C<~l`b@VHHTMOTZ>}M@_XBfT4-O8v1q6C2 z9aB=_0CBs9rVBi2IP81eZrdBw}b~gVi*pdq0rT;y#vD?d?zl zS(~$k*{gTF2i?!`6e6#W|E?+1#Cppt$IBT@u3wAc^WZ}KJVN}1&u6lEvvCq%HbU3Jg;R=-{a3< zT2SV@b|nzGADQChlwxDX+KfDHva?NLq^hN&s#6kfXpu}Z;Z553k@Ug2X(yqZX3_DN z^Ba>d|Ijx7{HabCN$VH!wFbd8Nf+ z5#_bhekFnY1&jz}iFxm?B=a<8U^s)N=pl!P_nQ2(ZbaCK*LN{G`0?=c`$-DXl#bMH zq%HihHA^3#ErGc`fU-V8J1Q;Q@Xt-4leSo-t+hU|mcsJ>X+EaT|% zHe9=({w$iFU7%5VFv#Ie7!CSD+#X8-}M4Z1`BF3 zTH79eC4l?2IyYkbg8-WE96u|bIKole`p(kB^`=NATzkUCHT%g&ZSlY(gx%x#_r9)4 z%0WMbRHvWBmykqprW9{A!8ijWN>*YvPFw|)1%J49zCeKA{+_9Q>oJXxf%gq)3)lAF zk6QzOGGNx@I6GqPx}9cCmM;3ibFMqMY*l#5xDQQ3qtS8k8f*fG23Pa>^VIb8WuR1% zR;sz@1SP3ZH*-{k7kHgL+C&WAk1aaO>ldpPC-S)57{k96YCq8n3G$7wYiX!85?p9< z(lD3>dIo=VA!d@7IrMnBBdF3@CXtIukYC1F$V;qJrmnNP@uKIW?F(A*YxEX49Ba?F zzq~9)#kq=~7m{4` zJDLYB4~nv5VuevXPlomI-^ZitF_Dj4rD}BmM_0GDDgjY#ZXP1$z8$B?+~~2#AY?zY zkUoFT4C)?Ih7%GB8(p)#%PM}?MIW{b1AUA{1#A06vHgYWY-f*aHP09ybJS12xNaP8 z_Tf7_S=5X1J2Wh9x&NTQ>{0iR9!?a|YvbH_#bn>ht`9Ho0r53mrmITAK5JAO8oV;% zG#+P9$eujr!Oy$f+Wwcl&1D(0isL3WI>bu@KIS`#>hS#ukL{lMrL~GCtH@lau)yO# zN;X$3Btc53|H!AMbuHPzauDKSf;JUq-@SO+)p#=t&81YvPwd5o{v`JeH2v~CjiGPF z8eR9%DDoqMBMNEluaY!`WG-0O1_t6tLu?x5=x)mvTmOn?8&e^aPgb3!X|ZI@ow~8R zeN~mKm7H$*fSW=*8Q6G$UqHjAvG{L`Yz7{^xAu7;bTw}+i)f&7ZIO+r*%G#CeYITD z?wJ`qL~}G{Of{KADi#^IZpWrpLBb*F1}Y*``F(uQ{lJfz0pG%hR-on){v(jHxFN#b2cTKZQK`Tv zfv^;&l2GRdoUIU6-~8f@y~=s=kDE129q2SO&HY!W4wpBs7A3DNfnJ83Mm^!LM#8Rd z%76RL8#$Fy&AVh#M*$w4sykPX+?Zb!n_X+t=ES!?+OkkZ__fo@$3x@Daqr%n0kfZT z(^7hHDt(U$PuJq^ngWW8M^(*LsHl(emm*T!)EkkFc%fy_M%K8Mf)waw-&>-Tsy}$s z(Su7EX=Kb7In+8j=EBB=1AGZF=R}A>vD12zL&cx5Y4sw3YxV?H8@ZaruHP1DLpX-M z*=kIm(z6fxiS6<|7LSWzw8x>hwYHAP$;ruoD(U|=-&(Q)EimAI6_RK?gwwOM>1}KB z_W~y;CPH#qfjxmr4O&43ZHoydjQ(SWhoJnY3{6S1UieAEs)7NdBdplkWbk(YY6TdJ z0kcnLye~?}KyidLC^qRJkqtjz+1MywsLntZg_IvUI#BHEDWxkpw)3r5ipwT!pbvr$ zJxRgbu)mx-(j+<(5IV3SuqU(Cp1v>Qa1w!}T9XudIUA;CM2J`;P28EF2V8MVRV#c9 zFkh#XIN~vIz74bXO!B$vY;T4wVp}YpeocZ-a`ON?dQvsx`pc3-FKVUnO@t0x(oZro z0i~O<{f{`vs>Qy-%a~NkRcfJg1b%`h%dL6Lb=J?Ah>LIOGV(D4MX0givL0s`pmf=; zh?rWAA^4Y3_PWU*5u|zFK)izvOhS3Q=8x8-jR1T~D0?QAz|J&NA7LNw%vVqD^AmNc z^QOLUZ_nP|wnxUUhd3|;F0*U~>}^88=m8+*^CbJft3p`V<<;m~o*t*rQ_K?g+rVhU zfI-5h2-RTO00NVPgX71}LR$W!lXh(iI(+(-6>}t>N>Tvm!Z8Gc0G}!{x8}x)yF&4a z0Xx5vDNHyhjWV*bAnPF=9a~#@h#+rqnlpXn7PRZK&pA`75#g!%5&70fJQ41PdBLEC z;oIe@6{2_t(eyU^?mIkO7B|9q4Uk=hH5eE$vZyz5OuHUwVN=_NDL?9h@0biUONwg7 z&7$MUO9_^$2cht}Z|}PMUre?fab047*otjxOB*gKkbNn2Y2NVf6BiV8_P$Mrjq(4K+3u9ZnvZw^loiT99}Mzxhn1 zSTo}2!030=%7|!p=n%isYp)yHu0c4^WlfNHhf>M**sMm;nFYGOfT{9Cl-4)AT*fpt zH3hEt53p@}tvkN4Nbl2d)FvZM?Ecp$TziM*{{PqujJQ92{*33pNABNw+j*n% zkXET3pEa?T!|%G#gV@iv4I|aLSpRcVATK;F4ktkzGchsgBC~PPuNU)-rIlQTixx28 z)D$iNUv_p{PEVHIKi1c$AYbKtWak`zvfOYDq`TE10*Qrw$x9w*XXlo^KFXG(pSB=J zjZIF&f#V769QS3%?;8Xq4AZLgkW6+|7fs6B8ML!l)_xVAA3r@TqT8Q$fiI1;rbHjBaFDJk!|x{3!Ued%;E_&zoxI<(2kS z;xt&d-X2&P!?T~0Z$V##5t7R30Db#3%>M+-Z$EwhT@f3!+vi6PSAz5Bt3p5tBk@?v z)#cgw#`E^v^77bna7O7hI0gc}05m&fEGQO*>Ps+I$e%k(ZskR+<5Fy8$T&sfUWQkh>!_GE7)O-qx`+^a#>*kLSNPBwsjlc9$vna?2T>h z?FpMCNUvhlflTt~aJDM72@+HO=MiQJxfTSgKYf%AKhSW@wV8p0{D;JbmY1N8WM^8c z!KtyN#wWi~=(jrF`}@~LwV&4NtaJup!Rw=TbBBXk58nd{WpZ+|4*p3Z6OObhAP#s< zUU6}|>;4Qf439-CjvnEK3MkpeeGIP!bd_9*T|ceFM4SU70eKzZfUA#6JQL(F5Z53= z0JQwx-nIY(fffHCFl%Y~Tg9Z9aFjWa!iy`C&M)vkGPE!i1Q#iwuEvHxA6-(8c z8994DBWQWJ8xma8^5x;Yt#N+uFE+q)E?Y*+#oy8CGvPtn)Zjh>Kt<4}c*m6&6@A=T zN92q6_=(Kc&o4R$YL+fsmkvKTSSFBm^lWKpMOClIn%I(wr@T?&9sPo@D%XVSO{k+J z7Nvl^=FiEQc&3>)ltY`Oti^rBtMju&1!*4x0?w3v1q_eSaKTA*66p_@w+O3m0|`&v z{FF*Lv~mJ3E63$yCf4zz!@)crNHgkoVy( zt}vjv)C$#g+)AK@f@95J-7~q9Ag{+cG}X}7rd+C7EtX+&Fb1x=i;D|@LcD^4eXu-% zQ<3;0!lP7ddM_V%ruiMD8*OjzrEc8KOcm)$yS=cz_j=k;#9=*_8MF?9Ent0pJqI!@ zz#(X}qrxL&;)EwbvTAFS045vsZgH=J@CglDx(AHWYf>4b9^xbLB+&U46%_$-LuCWR zpgu9!eUFfny+XA3Uuy`mk9T($T3%j;o@06#?i}9rYK3+XY2^^6l1V;RQ)Z3qLM9_v zVZamlNW|uAuhaEJJ%oN2kb-tHlr7{aFcHtrw4B;{w`U2$xF9{=V15Bx)(ass02i6c z(ECE z!5III@=4q4f`0AU;7)*g3Fe5m`AHZu@8iWjw>o_XpdxYl>n2jm1Kc@gMFPbc$dv2X zua}gTQWMgdO(|fd$T7Xm$oRF?8wJr(HN^pnk{Q%rofi&9Eyff`1CVKi+=sVvOh9Lv zRZpRrB#*8wpP%j{zs_R@W6M_}H$cMTOnJeg1HC^40t~5_xA#`bgJ>Rdd8mTKNK%d5 z(1%EW^7PjTwO&Bz9jkRM9*xxdJWn3$nlI2^9XXul`Csicf;k7^0X&jTz&mUKiZ@7R zK@b5Zl@tc$$KU$z5h92xGnJ+9RwTc8O-fC=4=S3EghRi;zdW7Yix)hSlI;!#(yHN) z8Q>Hf=jA@Q)u%NQ5J39yPl0-I8uon^Q=eXFP{8znrFhd{ICOfgA3>1YB+goP5#1gU zVOHmEPOZE)w3%v0z%ZbBvwVWhW0-p}%df@$*0aetbs?i@JmDxzD8zWBp-WEm@?krZ z)l%r2(k%H2D3``QS+=&By#fx>d7s`FX~rPHoW~3PJ^;CS!rCIVuw|4l^?| z($(m(KP>cO4(JWZv=voI06>iR!X8%l&z8@Qy*?U6oDnBdzIYZ?gm=bAM1Dz^+Pe zQBj)$shPRCy6at<#TsWT7T}KrZyJ~ywDk3RcO-pzEdE=>;Lot`-O~~stu4Zx4xn7Y zdxI?8&)fcxLbvVdnX1kvU8Pl~~G#Jp!kH5aqx$ zFFL+;5q%*xVW!=;b9@s&461?|aAGQ~(4o|rK8rpqqXfG7SfSXKYl%XZ{`+0@lD_q& zHP)1jG6bY|UVi?^;xq-2df*n_wEoVKZU8sb4|C*BUTgJ} zWYU>Al$9=gl-jh=vL+Q2`D7l{t=AhCaJHU7`64eG3M(hM&Z%8+RW(>&ve+)(JrF+$ z>U?)`=Go1Ej|Y-9$JkOJhuvPU$s4D}&js0jgHUO0`{LYtY6BIt!^~V`gKu-Yh3+$~v>rV_#%*@bX zAu+sJ7))YUFV>K_JTVoMtzps@X@adVo`)090WdRA;DNcP570KGUKl)(YJtD0`vjhM zAQ%A!!xmqGX=<0fC27FG+B!NvEscego&*z7XFs4bihcdnH4~6sIIIuoJE3D!WbXc| zc1GfMsXnO868x7ddOnY^)JM3%(8NHgtIYn$xqhRHTO=SLNwN2{- zBh&u={=H{x{BCo>&jweVR5{3yB_E8w70$tyytkk^BjC9H-KqtiB({|2wOG#Y3z|wP(h)(`KgS#Pd}sR$wV zj~#Ph;FyRtS5s0`Z~5&-89JUFZSmc#7L9gZZ&C(-CLn*nh;4h(4qqUA+iA;7O5zkg zY<}|qQijIv?#As2ge!bQB>f0K%E868;~guglmNOOAWguZAOS#E0Bh(ypi^}=^MaEE zrhzg(YHajP)E@Z%ZkfeyHDV6Y<4-;iBV*v+Js$Ab173)D{0hP^8pI7S<868wLTUwC z`U-43&R3VdmnX4TZzZqxC1o*e0w|xfd{uHbY3X+Ui}~-vhVr_FU@|iR}7Oc}UTWjEsP3 zizbTnZAbnsr)Z$uHzKaZF%8(um&$zV82rulgS6(yRYihXp+;(Pwd}P#`z?nOhqr&f z6Mw|TUD*2@H)6#C+lKfR5%MNF)|lqffn?E#)4bOg(h7oHl|kf! z-Wxc!g9HBgv$G$ZTTZQzsGE%?ej?a z2-$O998E)04~5I9`Caf2enG*|{$+YXY;Kqba3%xP^pP0NlZ`#nK1T~g@)zL3pDoL- zYib&7-f6R)^tT~11r!bQ10)XAVBiQqf8v#pP-af3jKw+<6-)5k~cZO05 zm>ImIfB+!$o62Z^2Maa*?ONoHG$CEn*VbN~b)QFuDtW;6%yJedp<~|~^ z_Wy|Bk$JpQ6rr7<#la;IoUnB57He`PSxq+6D$P@g=vv0cZj5fG|~^=`GL`+}<|M+Mi{518olNBjjmlzv+_{ zR9Q(jj}7)N^@=C7U}#~C%%Swd2^>>F?jdg(>)@TzEG9VSVY?Ts3!x#o7luV5LK8iksrO(p=UfU`pGCv$H<)4$BVI+~9| z9p-;oEjjzn(GtgOq5Nuz>ttN=jE@+n7*mTkwFb-J%tzuHYO&t|Y!m{{3^*|G26m5( zD9i4&hh?ITi_aw8k@w~-={pQ>H`mTLs8`_R@1NAkL5Lz56_{SYUb-Ed+uKl_r_lyU zd)c0;7ODfo0vFAU#+V*L@8rOW(HW#p{t8*rFK3-$}SszB7^N~|g5v2IBUns@J1bYn}$B8BXhpDfC$};P| zf9Vcs6cCV6GqJ8j)^LQUoL=|L6UF-^~A;#hRJ5 z9OixA=iYnHK6~$TZvC(B3r^na!F>8UMQ+2pf2~t03qCMAOhw->=6O>#cE0O$Tt=~v zlWh+{I`is$4VtNY=t4$oxkp@ykVP2$?7~9-P8{44QZ59&zpfeJoHWn@}=Q@d1a+Vq}0Gf)@#V-YZjteBV2~upFf8NF@T*#B_$Qmu5ona z(dTmzY6e*cK}Ac8+`Xo}K>XXKj{dLy>TqpYNgOi8ZHKh;XunVvUga@p7W)1oGA|p5(&!+FAK`}mPU)t0SEgMka zBX^uXDVh|h#}I2F<t$4W^ zfbkK+#`Qj4NFWy@ZF0AznAer_e5mbjo(311PXC3O&(6?m1;ab6?Cf5_P6Ov$x*%)X z0I~-bUIrKtYi!t5NJ8Y0blQs);EaHefO{gm+z5wIV%{Fon5MFvd+tJ#fI~{NQE% zEtC7Itg;s?!|RiFWHr~N&x&r9Uuj9W56(H=_y( zP!9-j$AX~1m0Pv-1ll%>bu55mOcQpl0D~@*{^25ezHNj)KtagxB!ppgK7a2(LPGXS zfUE?3YI9$MxsJtlA>=eTDJhwm&|g-b=Z~iIB5O;B(Aj8WV{2 zXv05(((tRQqh7HNxRifFC#^XU0X|X-wGlNyg;MA(I5Je^X|apH+=ti>?QC475w-?_ zL*wH~Tqof^{oopcx-60{x-Z-v_?w|M5aDNVGgb4Brmh}4>e7Q5qZ5!TaGvly3u~BU z;Rd#hVYPifE0WVPGHTqEgw0b~{^Nh66&J1(5i%+TN>A*xS6@9I-IaEGP~jJ0km$v7}E>;3>eJJ3Bku{MP_d3zFgmA1sm72?8j{ zJS{VC@A{uFlJji=@WUywX?Ox60U$*W`H0ELlC7ijF7uK5)Dt3XwPR=bE-P?%ObZyW zrOJn1=dgMBC}4}{X+<~)*(c-Z85^%2ZO?dg(>zdu#v&#a@HrqkcZeZZXD_du?W&vV z`v<~nBTvqO6^AxbXfbe@cs)t!8dYaF7}EhL7dg{Kznr{C)0$ST_6-UFv2$Vc105XC z^F@@a-?5kBKh_I;P2T1+KO5h2hoTHV8F~}NXRlkp4(h6e`V;N|e-4}r0~J1SxZ7>@ z#e+?H_lpWef79DE`VH*e-doudxa&@64t(mJ8EC@+9-p3ua7I5?eYDpb0{k!Ep|yRF zk60>i-ezX5?Oa{%{Qauo2g@)2fK$G`zh8ZSl_mp?hHpzW%Xskp*e6dMFo|jPwJtcV zSf(ofY3u&oZ#$=hO2QqRynH`Y;fnsIWu?bGvgC=ob%vq>JilFe@zLIwFcflcWj}>$ zK{Lq*+snt;90C%L)RT%6o@%t$jh!z#`0#oJ65Dji8@wqR5e;LY>x|x~4h_h+g)Ia0 z!8GP~WN!zEH}Hjj4f+GEax(G>%`TNCHUGiwM1Yg@iKmY*nYPixE4F65%Zhurem zn8;`Xyx4$i$|@?J$|&33T_AmG8BnbOaTR%ltE!%utkl)jCG`x4uRlrbv)nwazi1zM z+nhz7Z|lC?<)x9Q_2{;aWaWKg+7%xu4WYEWM-_G-1Rs_@b|1T*u8V+kpO}~^AJW-v zL7EPGdYkZSROvxcLRveu4kv|5UeWp1T{9}3kww754I(A~xDVi;9r3^h-Q4Ua0d#*x z+wgkzn0r*fF&R3lIq!`E$zlP?9k%)6m*+D|o#JQUVuFbTw);It4Ijd3!>{bCr<=tl zi)*Gl)uZ`RR)Qso{zfwH zxuYXNM_F%Q_=O{RkBD8m%kIgI4}w>}6aJ&4R+XxWr^e0+6u0$2NyU|H?;b^H;(**} z?E?5S+3sZdIJ8yHtU1~%qv3rkUBg_$>Yz*;O}xHGOGde56IHKMJxB4u>bY)_(jOe! z-G{lL$v}zCq_Qb;@{%k%U|A`k(6t_0CQL5-R_TuGH6pXoD%9QRtH?oRRsrsXO*2-d zX3)sMUGq3U!5(Sn{P^hC15tAm2nN7XkByC?$-RL93Hh;1@l(g3F1YD|>D!uQmJ92*AxEw?6QZLYv1KU% zapt067mREc_P14B#Hp)j-SmgD9m-u0a6jKY!`@SPw$5a$aX{AMD|Hiu{Lxv`huYfJ z$YrX%l)}I?EQu*$U-uHqEcKE#fe>YdksNVHOrYi3tq{%dQn!R{@lyI+P zCdy22kazDn|8lwr6@E=rCJp7aKAY;D=(9!n(#{azruRXkzN62#1JdoMRoJ74A+tixjvGsLSjzw;p-<;K{r9i!G>CinHDJO1O zIw5LV{h0^v)7d*QpmPBL_+8L+ zJ}uE?dnVBGzdOP9+Rk>US>9W5JcSz46yIZ<;I_5QQ*!tXc zJT93!r#ln4Hj|Xw^xVvqyK|?zc2uRL)YbqksBmmE;8{?~nD*)TIHE5PL+6L!yP=i7 zHNGb)=}Sv<8ZoP7Zd0B`168Tx>V>sI;miUVE%EPeVTDz;0=-WP^$i%mHjhl##Xj}* z^4N)2r(Vw{oEBc(#e8IUHIfZ&vn6B0x5-&d{$i@N{H4yA%WB#@(&YXzn5*=PNu>s@ z|MV(yj2I7vo(i9ixQ4L7>4Tz3P3ps!?zamf{?1-Wzi|G;boc4nnXhEc?Cr`UjOwfr z1!vRBH2N2z-p<|1F#}5}gx~gTE9?62S&8-c-}BDzIAgUU+{cm_)x5Jo&p($D<#Wsa z=*FA5f!{3GZE{9r$Tjgk;c6$USz0O7HV|geQEyPcrcO!J{(|avQ%}$Ggn|xFg3)i` zQKvo)1{l;gCN=tT6Rc25Ij zr5EA;m#(S7pHC%?1;x6nEcFW>-DabRL{j^Ar3l5|F=WvhVs*(J`I6Ug(-FO((r>D` zPBq7&W-;R-;Q9;n>=2lcf(2X_(qRCg3)=Jzbq9p=Zt5L&yj}BhF``VeTsoJSuY6Vo z7i3oxhkkX-BM5X8bahHvDJYE)F)J{SAR^&%mz2zWY>4ek&6~e!IC?QWZ>w*zSQRH` zlZgY@2mI%UCED_1oJahfRV-P5XwSYSbni_S5qI7%^7Q`a^6bn&SssXIWCWKu*YFcC zZCm?Xa zgJOGXs(@>tY(;X$8dd)vF981jY}XcZHLZq4(bhd{xc?3H>Uh(B)GbfDjk?O*gv9`&nZwqgB}~s~vX!}DYDB5#qjJkSnZmL5^I5~Y zp1pKBPE=8R;gdnAmET=!W6+*{BVZc@Has^01~yDCEc9${ZYr!!)ZebiaPxgA=sc`X zEH{uM_{r4}`=@B$O&?A*FLY*xJlwl$XMQYg>hF&u-RQQ{D9rqScO*I%o(x4Rq4o6i zy#CO~HuGv9!oj1Fd#Zw0$wygz?QF*SVvgVKzgKWVzDG8Go*Dm zWp|fYHj8EL=exTTQI0cu`uf1#XdMh^VEArFEoW1(`pw03upQ!s$gS?Xr|{-4CvDja z`T1I#CHS)Z--2NWzC{m_Lm9AgTlToMoi6zCx!{E#c_@R!W8eOgh?#4l43<|t3HqBx z%vM)Q492=Ug%mFR9@Xi0Up{hJwKts57D8oMMD?us9L9yP)~tz>NXYsr8hP(-NB z%y=HPVb!O+R@u^cS4&U6aCcv%bD?_0YkHm`FL=!h?X#%k1kT>3jQO~|++;^R;V}M7$Pl@w)n1) zhvE;0a$euP(8_<+Y!0;He|W|EWi4PhOAS|PCoILE*14G=JZ7V_Y`59)4b|3 zCmXPQ6R1OsUgmhC#xeHdlJH>W#`1_E<`nxI<;ar#+bv-m775Ra4tkOe=+V7no!^0X z%&Ib?a?a=-nh0tcI@Y|A2mj8wa>WuF*Snk|iaBkdFS{4;r zs2*^4d_iT!^Y>`R8Loope-c>B`}JxoTo(=v0*75}UJsEV(uF7}6*$OZ8M$>&k;%)_ zy{B?=af(0YsOCGZaC}Wx8RrfDeKlAWVyztBmLew#^?STF;+yt~0z1hMhR>Mtf`hLo zY~x79*;LFMmR#pD-Dm+3530fF)ne89@+OCaXo1T`sw>HoEI}v9?Q3~w^ud3=tI9iD ze8)0rqLrZyIzhXgMOSoi6*)Tk5ZbX3v2>E{ZEdojo{#ZXAq3V>X%i@|$x1mTO~yq~ z?YWbYrRpAhAqyubLRsR)zx!**){i|f=wgo9k%RNojOr-(ahz7jV&BiF$YTT9eK@RA zC-_bN!$r zjkT1U(W$mIjw?Htzjt<#!?_+z=l-2(xp?ezzSm=QN7j%E8N%AFXw8T_6}V!WM@z93 z*jGM13{K-=w6RQ+&sW=_pP_Xd#Wbll>Z>3=byQ|2K0!fEZu{zG+8?;$Z2`1zU&Z$U zsa-SC5)ys~to3l;AgX8kwSzXL#kJw&na+Lv4eHNM#Mre(#3$U}W0lF8^znA*c*VZ? zGg?-3=~aN4J>x<1!P>7BX2dytCM~_z{m7=;kegESd{gDg=rCg%;a4mD+fttiUt<+) zJqSB@GopmiW<#0MJ-}V;0hgOSW=CCYEUCMch*3~C4lGj;lu=-uG<*J>QX@m6Z7uU< zjLGGn_z^# zJ_v1UF+m^nB4c2Jz=h*@6Y(YlkNt%-=3rn=6VsGnxbe4OuD%Kw7U3WE;>DNu95!7Y z1Q}=rGWv4*tS@a_&-GIuI2fhYX0hjW0zr26%S2^OJcHs&@>i;uc-j*^uE6y-19obS zBy0?LadHTfI5{~FIefY6s1z2ywv7FL`~y*R*eMvyj33=+T*uz&H^)AI`G<1y;#V@; z4+$Any_z6i{4>lsS534!bb1C$Yt#EwjV9Jr&(#e(zqKbpH&Q+i7oOH99L23eF}v#P zP~qn$*a)RTHm)gN9o>^4N=h6^`|3&q&@w?a?{&$wp?zo+15V?PV;J90+GQ^~NaZv= z0mP`=9yh8Dxb_(Q`9kHg{h!w15AFB=l3JF7Ef^Vtwnj5xRoSzm8aB|kw!bSu1an=w z%=t!}4TW@n!m8}Q1gk~=z(4?BC=7%|+R-Mbrl`eQC@t{2%&!62mNGcxZtm-g#>&d$ zvcH;?a;PXOH0iO_RhGN-AyAHh2iRll*47b{lrSu0X}|10M)!^(l)&=o17{R1IG1eOt645cw*0JV_uj&sk6mlXzeIl zNx={)!TPNcw$?5X|06vyAt@19m4aqs5Nw;*0vr@|bZJ}D?GK5G89(x$kxc-tEf>IH2ai(r4c`Ba}Nu~g3uf>$|=YcS--VjnZqha(7y1^({uy(l6o+6L~SGT?hbdz)?aB85oz zm1+IwQ&9+UNS&`+!|x9%NJPsUqaRKnO(7-P$`j?N&BQU(-BpZE&h7-^G(Rf54&rT( z7mE^BQG9Sf!L>&Unj5Tg(3)3DX}Ybon;YIxhGbW}+_6Pyax^jOhYufY1g=A4hXPcm z@J*nL*@0p^fbZwEItYTr#l-JNW8xIQ8^6}HIWNySzk9yS+Hx<5fv zaF3Bet@nrJBa&cF1VD(tTGYk+V!6a@oJ9pZ2v2PPwmpg9?9D4h3dfVAxHwHZGqG4t zuXSGUQ>Bj>K>J4dNM)`&{_vs$D{2{xS^KilkkL;8G)Xm9Q1Xqi0TjfnmKCkzuN{%Z7<7G+N=4Ipfro-K53ctsXStyofcF zb{VfG-We1N{QKRSK^<{gfmm~;*ANKxYWw-OAAG$M;rt*sx;EI-q`ov06BB#;nO8K@Cv8L|Ywx}>`~?9l1UaMB6Q*|2 z=aIz!UTBF0ZM(DdgMb{iXGYk~^F^$asUg2m;Ov?`J5Esmj3YJVE@&wPQg7IL^dW?b zm6H>y0V~od_C3CPGELkLPEKaek5f|4wQxF!K|2%?6AL6ph4}6XpNHHgU`&C?o}z84 zPXXqG2NG|mTwfE zZcr~lA8UAF&ef>(a$<<^7WOokX9y$BL=cRpePE|aV)}+%nmL^|dV=Kkxyh{N0&V|` zoF+rw~}ajY?r4`0}YBpbqX;i+(B{;g9f@qC}Ls8Iz-I?;!O@fIW7Q5d=5tLB3})0 zD1&jM=QSJ=+nI>>YYpF)2S-M(#l*(C`uIe_T_q!bue8|6Ab7bP|26`T2qhd4*mp4D z@#I(KP#JW>cyk961FC`?2#QTNTpL7nSUlyRa+(nRP(L^uHp26m6@Vm-HAwZVa=gFXd7FaT~+=ezRAPX`Eu zo9GFDEm8HjmU2G)g37W35DV)Zx$7(~nQ=#u(}8nFY+!1tqHEzHAEA1bU9OrJ zsPsMn9zZWC^+lo9N9ac*hj5Q%88$vnZEaXVwAaWq{$*d%M~^QL^@^#pGZEw*m6`b`Y(X)Je0u}6l}L7Mn^H6 zz*v(Ysql9=A}~_wb!bmkNxdh}&-pS{MT~Csk}0u{?Nr`?*2x8{wLzKa-#W(r#SLp= zXAgtTu3rr-PCR#xS&Q$}IHI9>&s@K|&J?cll#kiJ)+2a8?1>j#dxcKaW}cxO_3`hk z{($?V(k4335x;2hM!#t{Tnua-cwz=^dn3M6QXU!*BtF%r7HXm~xQLDlAw$KdMIrJh zCP@-ZsWG9fn8l9g-P$+=XtXwzxw5#3000Eq74jSUUG8VDz^vs?STGpNd<`9irl+mF z9TlvXx6C%csXI9{(~)^GmC5YQ#0*oJ%0GXGav5i)2Km~MksB&fm>L|tx@++GaR+iy z7MfwOu_qc_j(wfL2g1Y&47UpbgHYuL_MjJ293VLmX^>qfT`uQ;52fm`)@1_tfmg97J3SxrqSoE;!1kQH#t)x{1E)9mczLJw}ev3{zou|8!A zhuX@S6wGc3gC_&G10Ea)fTa*?!FAC7_pd0>5`2)&A$NjY0(Qpb^>u6*#CJ1?_%&c! zu)81`LfH4x(l9`%2RxV4&*$#*r=>kU`4JyWDw%G~V$kpX=LZhphF6gPzznwp_E+%j zwEq6heROmLo2i|*6RZay_9F2QcoBYWZ!c92Np&C_l|bsvo3H#gnz2M@2yaycbIME+ z9el@nkF76r^i+kn8!9%J;`tYqZw_nMeTNLBIN;>L=p&JWu`*m{8%Nm)eNluLTbc?+ zuWD~rI|293uPi}8%np}DB0;BV377{nD{qF6%(xs>*m-_Ek|CxHDQTUE%9;x#6lM$d zAA9h93}H$5gv8*tj7{B~SaO{T<=;J+9C{R2eqkgDIWP5jsCg|b z6ZY-3ikr0N67=hraSBFc6Vs><#arl84S)Q|&=D46aL)zYYt(u3au;i|2Iefs!g4~>0pKMx z$V%{K01_h}g||W301p%776TQBgR}DrIO;l}H!BE+A_XjwgguyEi1phlT&!rSK)BQ0 zl=7h(5CmB*45HbN@6HQ2n|I%j$be!fl?gwwC9zOr0z!Hz14(p61ZH@5f(sK2aA2qp zK$6rj^BWntyPHc&Q*94>QR|oJVMb>Z%togHveb+!2Z%P1-CtXqHOxUI1Bf=#=nAwO z)U0jLW&soT=pytxE@MgmTh_>`2Nu2+#?zeF7YppuZro93hm88cxQyyB-DlR~L)Sak zEtvWDVrNOX;mH-JM zcL&9H6y~X6Cm`Qt-8%nTX=)JK<+5+X@f?Iio3U>p8Vcml}xp8^BkD)@Fl zAkPUCgAfP13K=lL1V`(4HnV_iJcIQep?qiyFQjy04;stBF28bD`t-q*MibaFQkh|E zUI5&hcaTvQnNMN%{VsCX!oNd4jgWizexwybttQR(@XayMcVnw6qSWECA=- z;uFV4g&G&h^}uf-=jb*6UA+O!s$zU^Oh?}zSYA45WE?|5I5!W zI^~r#h?7i|*;k2ko97picH~!QM?#me2`)h_d%pL#8t!X|5$*8?^*Vi8^ziqE#I@Dj3L47jN^3Tq)v_`_(#sLTS#y-6 z?N$%NcN2q1{A_oNArGAhO)mzIo!Ma~0DCN%r&P=$vx5VP4ItuzO%E5PNAzyF9uV!O zQ4By!Tql4Rg9_{;vf_kL1DgXH$>Ev{WJZAggGHE^AAuV86-rkZxOEATM8~mj+34oMe+KGQqcogy*7 zfWhu^_4Evfq~!xGsK^`)fBeZbpWsSNeFYYE7cLPnhdLb6PsUoC`Lpr!xbv^n%Ymfymm)awHFOj2%>OU{WplF#F$q1mixDjaGXQ8j;WmM2)}D z*Y@XGZ5xCfNY2aPE>Gp)NbXxg&c5FJ@s$)RGpNV08FqhsjbEPx&St&QK9)yvXp}dY z7)j&z+&3@I-wLk#UNdKnA!=);RE*6FCU9)gKRh#pr)4K80g zNUGi&Jn{cTE@Bzs?~9fsp=L~sOil0Y)gRMY+!mNESPq(3GWx=)y70!m%7;ztwk-PV;XEhc`yt*U&(g z%No)b0^Z?x9lY^xnSBHs^WtKFG}ONtOVhCg4v&3u#7gvlCUc(jt0xoR27Cc7!& z>Hk3^Q;AN0I!L{@WbwO$5PSe|(EN^fBMqP+hqmDdn^)S=%~qjC;sB^#LYv3l?ovm_ zfoD_lMk4vzk00nzenQY$YP}FXHo_*y{R2_;1g4g+DBfa-L!o|bbG6OiQ-G7nKS zumb?8L2z0^7JoShMTadX%XmI8hke9bOOn4cYv&9J;b4Y7ao&cvccw9>f#ED{=lS{h zR=>`nL~hEPM7fWytd)GtZvBIBsFGb3-g9;?TpWtW{hg;A8eLxqnlHx8Ui(GYUAt|~ zpf;n@!#G$b)bBG#XA#tao7(fj@ZenEy81d|aRK33`dOKAL0UYrlQZk{f|Y@mNi~5f zv8#9hH%IUn306s2Ll!2hrqBYfN_0=E_6jtAzR8$Bfv<>k>{{bx%!eiY^@VcRDY5zk zNT~ecRqit4qhdek`L@b+zLb2=v?~oZ-@qCS} z_6$+JM+;%2@_Vsq-7fzGo{D|7d)L{S4JQ`$GW;FIu_&)aYKD)6pKBUF-J26kCFj>ILMDTq^Vb!1HJrcOk=KlzMGnmuOBltb* z2#C!W8sA<#*77dB$0L5~J5p6nVBh1zdZWAGXJyXJJ#j1BmX+K*6AHkA$R&7+xO~CS zAMzk(f$hwKuGF)>yHN;x*-}P#$v*t$DUHuI3v5p}tfT>kkm%v#Hcq@6#~^(nDzsKA z&|}}Tl`=lmk79m7ykW!h-aCq~8;I9Q>&klNFKvZP8+x65UEJ}Wr)3qk?L!6Y zEGk>OA{cdgI==OP1oTh4+SP=&s0Pdz}$|XRlzBx=Ji4jVxXB zo|ar7N|dY@ch{m>Y}@q;;dA|=EW0Vw?!_-f^Rmh1Kd4%3Ru~RU=<$6{0%ENmWCvL0pPE3ee`???J5FR?t4e8yccNr{nW&n zs4jSqor&|mLE40#((Lrx&7i=H>;NV+#ShOyF&gf4l&R z!in2n79nr=BX-`;xu%VwotA~v8W=P06zN6)jRVZL*vC#Lh9S;>X|%q(Vb^K2MXpn_ z|7>;KXyjxJ#j(JLTFB~;jQZK6Hm5iD)`_-Re+m)z; zcZ?;q#@Why+S~AizmK@HFIb||_@P|O9PMt1|008TJGuuZhoEOPpAFx*_^8f#K7*xm zBzsT}9j99e36%x*IRzr?fwQTf6CINBw%(k}3P|S5KOJW0FW{6_f2Epd&SGS*bl7V! zHQm0s`RTQoRJ2lux;Ix{cw85ie7T-LJS%QG>px${n3@&A6;nIw} zJR&(&q#5}0w(GRFel9KL1&ZJGd`}A!=_8h)KT6rNd$p=~!Ud8Q0(%!^a#?du9W{<3 z_l3Q+wOaZuNLl@SH@37)h~&c6K9dtG=qUGl-?L5sb<1$xf90pxzSR^$%&vits!$+6 z*3CQ`{f5T6IU)&A*=U#c&!=3XG($mK-oC=K4@OK}5t?Tyyz8W+ZBSi995rPz;V>3F z{spUYS(tf&57)fC9Q#@)^788VrSuVAXJO~+Dg|^wTkwmLI=5U1U7nU+O{-_HUF{NG z`KPDvbqf9St;20CzA5<)dS%`lH2hqYU@PVzxYnf4dS6SDof%AXDetDc3z!_;48NV` zjt-ok)C@=r(4%0lOJgOsNjo|$W(o=IE=aw=M4ZSLhnDvKw4ugayFHy$BTTSanc|cr zxQ}C=O3$|?$ShIHfIp3sjgj~^Z!`x*T{VxT>#Ga@bv;J;3z2HdyDsB@02+VkP-Msi zOZQt0c5mmS_w;$V`jZ#S{_@y37OJHmt!8~$jS26wCj2aHFEG}>T3I+JxLkF<>{f1~ ziuVhsjWO)xz|%AdYMQ}$?4r-qME{RKBWq|4Erh89`6&`)qa14Qw_WqU#3huDY^iv4 zm_`BbZI&yxa%WSh-y&;kOQ5?xLszBecFa_g(g%XR7TjezJ(UZ-SQCj%H$vFvURCP- z2PgG4@%1G)@~(CEt&UX`klb3D(0I+!-&#S-+ZXuk(HB{(LLQ0!fY>lG!op^iXZy>l zx{qSZUt<&spc84|#OM)!`RAd;#R15jZp48d18c5+<1{Z^syR7M15pq~Hp7|f3#F+0 ztNhz^u=gKTAm1N7u@6JBZ)8d1g@N zZB$sL=X&(J2fh`8y&5el?el86{dO+#q8Wl6!(k>QtuILBMpA;z8prGTHg%%F^4zz( zqiGorPOb;)vSp7IFdX<|54!sK#Y|0!@)qod*_u>7QB=kGDi36LR*N5>nvrwKY3Q@p z+XRK;{QPca?>&jpJ$DyTE;lkSagdh_9QYDP_=aBF_r$SCz0f=Ne zbJR)q%tYwDw`J4e<(X;J5{zL9dF{prtkpp7L`-Bb6}mqVhWE}J-wt~*{ufIuYlE9F zW;@-Igt8KIs=tcu{Wh!E!D5z}iZc7dTj}_f1BMhGM`m%Rd9eX0B`RtY_=Tm^Nzypo zbD;?&vc&io>n53Cr2qhUmiuVmn!rAczJvtq1s3i5sU#Ji*pV~oUX=*CP}3y;D$a1d z6RGiQQT0K#y;;3)KiUu+xW1Ymor(B-!&1MDmNGC*udzI&C*+R70Or#Yyq_zUWg^mkvM&c&`N*4l*2B7o&c_HbHm99)a|uR$hUH(tfd zx+^4@bLYN(aI(OG5b#YbPIxMeYG>Y8@xy1g^HPO5Gw4|T&X>LR7F2pB3^i`q*G0bh z-Xpud!jeal4Oh4sPHc})ws zRW$%xWrGrir8idSS_+{#mH>t`2*lr2GTKjW8QR+h>g`BU!cZ6DdaB7|=)6gNt*Rav z>1~N}K~((@h9FiD`qr4HB#S*_Ax(7@!(v%lz)uLe10r-LDDC7^;17Z`RjKld^ksY1_yYDdGfz`rwAz}wyG zh0V@PGm)}8-o&UXo)9?b@i(us8Xu%Qd91R2G+IL{ zO|iGKc;>e(Xj>Ei$m&sfEIoJH6Wb(D$Hf7$a~;x}Em@Zvfo{AX#5Hsb2XrGe11G4y zkOdU57A+#EEEdiDhn>+7*Q4D$ovh{LyN7KAKoT++R8qjEhe@X6g_B>d$Z24glCSkbfP+$URM3a z``Bll9C!DBVaqmPw22N=7c8Uc93MYv=^p-)@RFq@`L17nV5_s4?FGwhim0b35hMPR zw`hL?hsCjmDh|7dTnoma_S-hsxC)NY=t|;FcmKwUe7ryX|GxdVgxr5nIM(L8wkmVF z3Lb3XFr3PLNfG*#tC*}7$j4l?VM(m=SLKj;3)i}yNM(EL&~xEUuPx?Jl&=?P_3c^) zm$|&hD~#(kf%NMtkk*8)AKqO8kVjoDLs8WtrK)<0jvMDZjp_?r_Iz{SXb zGj0=a8V8lHd_yh$?82p>_e4$VV?} zj^ESTD7EYEvFMhr&6op1UIX0XsH541eH6e zmR(h@1P058-zX|$O036Y*X*lI$tYtEOc)NVtLYF#T1oT@*R<*--S6e9Q{=p_#fSfr63c@Cn_Lhk;LXS}EHmM*H z8n#tig@_&%A}T;%$03G;+U=Y9$c4o$v9G>qR9gkDfW5VzK}!VBgAVW_MuCz_Gx4Cy4TmNNE zOYBSQ+__)p7kG#(VgDVmt^ci@8cUG+3K%?y<(`mW^#84>+HIu@a-8w~n>1GavMU6; zds6d-4qP0duR(HWIrry>Jp2BOhz`98w0o+|v&^&~JnQC}bn6Bwwr zqFM50)ET)hZc~qknf<-KUqAfv@bLAsMifg@S`R0jWy{w-Va5@r11012x&Z#@syQx2 z$(E93RjozNwuF^YbOMY8qSneE(od|4G8ixV@DlCQj;k|g6X7#OvUDqN$BjR)gsS55 zE_3!D^Q8WM#N_|!rZfNiO}EE9XzXW0TZ+o|v2Jt&ndFqE%WE<1_#~s)@X^;UzoG<& zkn7bD%sdEcYK}Ny1XHk(GY3UOSiwyQs50$`fA*dn^2?`f<`*|hnW;zU{#3=l_fO{W zn7&Et=J}bHRk8L(wQ@r_GoR{IkzwwD+|udEh2is|qARoTxV*p4S#pHGA*6zZ{C{?C z8i*=LN_xscF5H36AeHHHM2WNhTwR5F?jz&-Du+fB(4DHzq!%ThidZ77Tki{gUL8z=DaXXbGP@NjdWa90n-&z%8Op=ZLLSD`Bn#pCV1gmAP zeL0%TA=!!{#NR(SzAsjKQWeMjJsRhX(&BNwOACH?69dX--z!(D=V>eB4Q#MxYin~V zk{@1gaX*Rfy+U7%Poe(PTdyD_{25xOZ>D|y7ld?@!Q_At=jOlp8Unm3l}nvaMb49> zx3wNs(PwXMwty+_%tasyZRyl>!0CyxkLlMuw+bCH$R#H|S&%)p$LN{^0!}^Oh z#eZC_i=G&IfgP@HcBb)0C>;3H>9R2&|9(Og+)&}^-_+nYLz-O?VrbS5Wrs5aype4K zLmLq!G<+3DAB+&=uCbfvilN6go4GJy zi|SL{B-sEb#>&@tR;xRFX3g(X_~Ny2Q2L`ZGpGpu{C{*)D+PuQrG0CZ3prV;P)UzZ z0sujfbNnytF?Sb{6U)3~uE=-Z*mSl7Hqp2YUYLgB*t z_*txb1~*MGReU2dKUba0GL4};lB6})%oLuZ2%%!iCnu>4r)#$&*xtmO#49vy$0YJq zHj{TDoN+asBBZh?<4o-4#Pff&Z7!V8w-j~MHBWye*aKE@$3H8lieMN zg|nrX0by5vr5Qod;l%9oSo&9x&|tKjOz#ho&dvicQsmEzZ)xxL zUsvouee*wY8ynUC6&opKRexNN_wStArrR<4^EHl>=|pv-4ko}0LQ4sZQvGz2M{RX= zrz_8RufXIPzoK}0MpdlshD_A)rgp`vHDz5`o>lDc=`h^#dp&P`io~}D#zsBPX#YBv~o_y1bIC6 zib=s6mKHfK;Xf>OBmK@jJoW zOZoax7IYva>r~1-BuQj4*uPk}wiM(&*N=%f533eD$ATy#08s?WdeE2#{>5_G=C53h zC?QdRS!&FV0l$NeFS6YD0jm?`8?BJQQIA`W92H2jW?RiR+dXWQnHreMh1XX>g7NW$ zWGFT{@>t$k%~`s6{oK=dHi>+JDE&in?w!47>6BN+zhVdzwjaz4pKia5!lAl%Se>49 zbSLi49KTv-Y}Gl_n@yWGRg0vNiQu)5A5F2%r?Ys26d1ST(SG#qml+b(X^E1&p&B)L zz;+EcJuRHfu($`=B9!K)il^u8Pli}FNv>)W4by!aKt5*aVo3DuwP_MYi*d*z!}+Rc z@Z#p&#~^o!-U|9)f5(q5p;3GXbKBiae)~hJTC@)n`1|nd zmu&mRMpYZ;=>Fox*%At#-1f3UxgDHE{d70TTau)#U&6csg3A(goeRbPD^Z5q2iB0% z(9kFxy<=*KVPCe{DLU~{s?Tto0l&ChL7eM5x0B|ZV`GepG)BVBHfQk^c?fN3mEcz& zdieS}ueu|W`6E8?kCX3zmns{)L)D$XKu96YYTF~1tkS0;m+4#?<3(WO%3-WC^i_#? z6gxs+fw6H+roj)l&ts8Xbr+Z4#W1gzzYq1H)1&ln>LKI_sCTgGJ&CI=+|e2Dy=leh zRNzK1?v7As*M_{QcfFHe!-Vl9i)9ga`rc#=o{K*gL(=#{>%~=R1SOAu-BX-8Ih;$c zV(S}V8~o(es#Gg#NWMDI&7_ujm%Q`Mcxm8+5Kd$#eTIaWIZMkUV?hQELN5~|NiyTO ze_CXg$J$(JL}Ez2_<_(W~{bGBEB3AYD6DLwzhqZAOR~(jby~5>~^5XTul*CTn$FpTVS;r!*40(SB z`M3Si`J&_AD&{_IKI5{YaLzI+ZQuKYeIew~6S7@v=dy+GB7xuLfK@{lmlRSqABx=& zs6#_rGE7$I@08(K*r$c=I2l61`8b4%EKt4|Q55g&?v$0ifSMbun}N0>75v>Ko9(mB zes?k$3XyU!!fGmfXq((x^TudQ9S_TDb6)ZDoAjq$ywUpIhAsF=D)Zo*S7O)yKUIPB zN^9UW1c7_Rdls+P-RPuwAwC}Jw{YQ$TI{(*OH)WrB?(Mqu z&wJmLz&D!`@}!c%ChY$HBgT}XXprEMDke7O%ptw!AM_-H{za9)O>X+AS~+tC*}M(d ztjRn0WfZ0;{T}q~h$P1jXF-q+=WF+GNt_;J@`*nV_(4A0xn9n^(dF!u=R3Xwp>1{6Ua`W&qt{jiwFP@+ou^54%x4V2(>^J z9A1An!ftfVo(CB^{g}ry2p}2|?BCz%O|Rf8*D`oWRP{eY$XF8-7!Z8XQsJ>b9R+5~|mq8yr z!-CUmICKUwoHW@ObeN0pg0Q3jnat4?-7k<8P7X^zojo>dpi`}k+_Xnko-D!Q{dp1p zQ|Wfz>C*r#Deeb-n+%br@u3^nGeROAb{O4DUx5b`3f>b_&%`+7^8PR6ng{TG989SW zVg^hs|Bm_I@#(a@{ab84Hfc5E#{R57ttUCkM`HSY_k=qJ`FI=Er_1lF^3S{~-CEG6 zMFoM-RgvYza{WVTpU|ga)p-@h5Rdb3g7QiM+5_EyI5V3SAq0>4r)--uP~Xh_fsSJ$d3S0M1M zQfNaVu|gPJV|_iw(Za(FCu5BPA61#1K?GiYlBGOufXDk!jUU?)vJD|wb8-z+G7VGV z!6m%A4B~rw)D|vHG=@A_J+5%9IcG5Wg9`*4dN3*-g9Bpg5^sR}RcS_d=JOm4fM#M; zxq`oy2RY@Of*k!>qJG<~rtrb`WBpz$_IRZU9g%|QrJj3k zubT}q;z?4}AKQF$W?pJhMqc=0Y+L zWzIZ@l1!OrnKOiJ^OTB0G7n`_88c^=N@XVPkhwBP86$k_r*qErzVG*a``Xv}pL6~v ze#7&ub+7f@>%JF0HNN{sv34V{I&;qXTxRykd=zw+Z2IJ2DwqroFwiXM@l1Z2NE6Ps z#qNCU(pbWirfM02x|~@4gq0v`%Bk$|Kt~&<9;1^va}nYB!yX#ShRnM$?17m|isTc< zo#u(+0x9{w*Y2lygs^r<$GVT*rV-I{i9!ZnCPVg0(}TGoGyLxegkfT^yfhY3{my>u z{3{VcyOF})es&XZ`KT`&o5ebez9=x9Fm()KHtn)t9r~1eN3_i3q2sX>gXaszbfX_# zb{hs?hssiG5xw?RF+L+or{DVL+>M7s-GY;0X#AJTv~-G9mXRrRa?Wb&rtcFZ=~0?| z9FZZC-!BYM>_5KGmMhp5|B3-$Tds<=u8OL#wv*sX@T!X3PG76)gwM1LL%g_yW*Hkk zF)f*?0sh6nYv~2!0%7fevyWTjG#76f91_!pO2sFCTCLt#dIjQVK+)*_sslZC+d%}6 zEDW)Vr~jLMBkFnJU56deWS(QSSCFgS~sCk%rfqbDezt#P1 z(wi(7`%4N#+kqll?iudsOKtQ1>Jb4<@bvCRIp^BV-8>Y|3f;7_bqpc9D@xyW99}3y z)OP979%2E<@HggH1iNCs1)=Cvg@#V@ed7_53bWJ@B3v=*Ye3^;Kgj+1W=fbvkQ8a^ zZ%nJB)Ho>i7D(d-Un`2N(fSQ9or%9u*S8C2Ac&5msCBST=3i7lXgGN+NH(ea2RYVBkyi;$Wtyb zBV%1&TDpHr`~e3sZEfaL_Lclg;8tX*lVWepSkR{BQ7FidPZJmX}Sw|V_bIqF*W_DwmMhR7R_S*^Q5;<*1U zo^9jmHt{%PQF7O!=XU*Ff4#x}&QDpc7w6s#CD*3=dvr^5dc$E<(4f#AP)~SYOMpZ%&^#W-aBm%p?k~+{--70K>=BMBIyC350kP?Y#fR&Q`?x30a-MA9}{d(~4v(D4oKR@dt{Y~r3~{d2OVp)NR; zq%>}a(0Qfa#w*2My|P<|BsoPaw4}CX3+z3lTtEysCAahKFdBRF!mGv7oA-quUKZ#< zp$O*ye}D7ChGcH^WFPM$Na207wVafV_sG=0sK>rfkm$DB)W2K+$C2z6?e1>D$HQ(= zsI|?qz=47G0~w}5baUWhj)?Tn?=n6Q?CyU*s}Og`t*@kuQRSt1i?7lhIS6CmBmTd_ zn01;)DnohHeD9raQhFQL?oh$VqY@fU%W3HIB+R;@Wx9<)J-=5VR>rtlMy?Y+vq+$cVobjmJ$u4f793|6b^y$1QbWVWN6qIVci4tUJ`#gJQfvuR6fB+h5>#E z1dcY`kBE%LW3)4A#gGX5vqvg{${gocxu32nr`y#?sc|d9nNfiR-P(ixRU$vO-j?1R zhmk>`N3Qsfb!U(QvaT2S|7iZC_yh;bd6ku%=A^i^ZlBI|Z1rKdZ3PcxkTR;$Zr0>zU2W+dOyI8HdUg_HMN$exZrP_aYt&Lf0qn;Bc*&N!~FAZ^3tt zrMz(xug?F8)R5ZBl#>4vx%7<_=FDvvQKEPhm)ML^)_xwnaiOgJzl-I|t1lhrz42W; zUAC*z9T0@(?UR$YPV}|xGuJw_*DwNAn=u9xk&4DQ(2lZU+>Ab%W5#3Z!D9LWZQKDf zU_c+_5pq6GPSh}R?9nUW6XaYN7yX}Qm14$yZU;$97CXuy>YMJFH&}S-sxH1z(Z~@U zip^K!b3b;w4~wl!eiMW3;@(_&OnF^cXHwz=zpI$}+mN?R9}mv#m1q?w^BBF&UyFF{ z7yeqnmMe<)7W$3p+6;>ujtC`XDMY>(+Z%RP=6cFOrmFcGzRZk~lUJRa?5{;_W$19^ z01h;%y*IdwKYH)10MGQudFzY#&)8WCmi>xqGzg)z}l*HC#rh4Y^ z-%EL~{3M;BPLO9r703{$wN z_M@|ZPccP~{|-2Lsg@VmAQ&}`<6_Y?b?bP)>myRjp3JS^usD%3=TJLf&eO5&WO7j4 zuGSkFNU6)of7`Ljm6totB^F-b<16BLS zjK^3Y`OcHmnW_msOJ+jDyur7SN;re zG4!*?h-mF-A8QUkhn)(W4Kf+oWn*^Ybw2mpixrr3r%3UE5Gz7S8)LH}!il9D--yaI z)od^|KR3J4-jq*eo3+*X%;&gCYBYT2^WEt+-*J^iz$%5~e?-&Z-(@QLCQUi@Ai(U{ z33W!h%K-|Us`NpZ`f{AeCI)CiO?*ylem*6<{^&bd7oO;+5mQsPL=-rx$NF7Nm zsjX77ca2m!e$voiLiS_DO5wMg?io+qJ?Uq-iqbETfBzkSDyj{5#))m(=pkxI?pWJc zK@PWY*$)=Obv|c1STtoN=XVr)1Sl-Li??}_B=TIVE8e6Lb@_7;b$gr1xatdDK6kW>Li=A1ZmAH53$WX$)}Plw%$9P&^Ri^(&J zv?}E?e%5AT5=NMElL19p(ZOx=WA-%Dr?OslBM&pCxzFji=(p8&Z@bQA>cZRj{rk5G zSwxx#yw@^9SvR#%6+BYMQz?q?xJ&d{tWk?gG{9VuE2!o@k@xzU9w#U~Z04M73t z>B=i;aZDk^;Q7+K^(K?smgLdO^mj&=aex_bo4kHl`SNA-t?d@E{}E;RzC)#|{Int> z)j=)iYQ|0jpZ3eLlfy#}HS!(Rw0yTrBztPz;kXQ$j2kwnt-B1WHWA!fWQ{}T%ZI&; zO1WU71STy@gkA{nvE)-x*`b?-lWT^lM8ali6i=6=(p);D#|(h#$T+qKc)9{{Cd z<_MwaCSXi+=>#Ga3mbtoUKsngXgZYfjKLW~G=Bd~N(%bHrOm^to4kGZSZ?mF<(5$K z7*!=Roa~rm)uBbpcNldN2h+EA^VpvSY}MI)V3 z%a_6&{)P@Mv9=6!xA930uAl!Lbb*%iab;yCIZ>M6?6l;SHg9>~Q~NXzBbFB5hys0r zB(LA)90vnGsvUo`$?d`$7~$+a^9|AN$G7Q7EOuYAx{+=i*chN>-fihFF>k&S z98oWr2_>XQF$IuL+kSsVfmY^N_U(Uqb>KN`-p~Tn8ZC#;^S(iNnM|JxUJx+t)AUt@ zhHWTVfA{X#&4`JXaygVrk73nNO^#Li=XQUCl5k{CPtRAH7;Fl`5aD82*TEB84(h`0 z)$ENIG8JOQHQlSB-QFA97hjqSk?}{x;l9e~MeVG1bI*8=7ra<`%SR_eLh^KFwZrOY zLnmC&>5NwD3@!I(*tq3(a_&}Zxn0&zYzoXyu{?bTdRCY*)#ST24D!aob=x$4o{qMP z=cuQ4qh#3G^v&kd>S&MZ(MKY` zo1?3suE)PIu~3D7zkgZe!$fVQD91tMcenF*9IK>1RY#Vso^q?B#rGPZsH5MVJ!M5& zy|o1p9#rY3rKq7dIB;sb0_Vm&%o`He{JdnNg*+?*-F)l8#Ol|2m?T=PC*8_=?EpHbp8Ba#Xfx4I>cP@&&0WwaMy&Svc1rnza+Gw|?Lb}k~ z#|Ek{Ju88+ArgP_qlHDQ`_x7$wXAw@_;N>tphYy+u&K6wH8V7IeCbJFzKSr0QiRcK zp%xq_>dWo~HG8c7m~9Yh(70;FIU^i@>UDc6b@j$o5*t#7yQW8zC^0c+TNvq5&+A!3 z6$JU!u3E0Lz25nsv_9jWE^Gk}3D(rdH-Ii-i3blTSWG9U&V(od$;3y&9Ig6 znUV^%nYZJRk2AizyE}||%bvS?Nt-jC3yL;odl#8Je3-u=-ks;@rsVex;C5*G(TMi0 zNgB~ed~#^LSFhNm@Vu8!lcq|7Bn-Fm*oVGCIsugN0>+(KovA2l)n8cE6wzHI0fRdq zuh)F^o3_BI%{Kr~f`FsVIuEPii;X&_c3(Y@2nBW(sGwo9^ozvN%G2{t%TKMa71dA? z%OtCkBy2gorF=Z7{A>s&mSOrv11>YrrBxpbNis=a4*OUZnXvwS-^}I}DLuNRf@p5VU@AC6M#UH{fQwsohOQLK zSCvPkJ|xvN`=L5%`1KlcPC~@XM(9zpU(;ZLMY(R=M01+z_ggm%W?Kp`&t~pHdv; zb2d!0(-m(A&wpB zdz?0@S|p|kvmon#qHM_)1pU)ze(XH^u_4b|BC;rLdVdqBeLjiLTbK(++>obIYQ#?_ z89rdQVEtnFIz(Kb*jytnuE$OV5N3KZ*~k73Gl&+7ddN>tVlsb4taJjwR~ zwjS>YkBolIAu$hJU{Rrgsaj1?+h*n8XV{A;-#jHEqlrIL^9)>i6gg~TE+rf*564D6 zhj@eDclE;au6L+gaF>sfUdeYPVO2tNz?>!DbRZjy)efk$7)8gmO4SxuZSeoXs-EVy z|8S07!>SmK4woI&m5Rkp2t=l5F162{6^ia~Jm z>u)VBJ~)891HI@h;drj%69e{kX=CbM`)z;V;E+5_>PuQq&fD+Fy!YWcKV3Cj zoX^+rLG6qSjoKMHv363|%`DKsoU|6{w4IF&1M1Ql!gq5kQ%_G2j+Af8xxyYEA16Y6 zT-prZUM>I`!be@Of-cjyd(Uisg0=QXwD9if48p(rI$Yb~IIg_aRr1(hEI>E{(jrWb z3utW;KF9g~1z(ORMaCF{{FJ2z_={j^kDQ(kh0NgSM&R;n4NSKXYPX=DuKaj)mHYwP zYk=L63{{rmrDvLbE*{O6as#!4l5=yb-YYXD&AWv96-b1WSIwU~^{9(`ukR$5KBLD` z3}an2vP>a3G|}a~K;8_x#{u#ZeA5jclMU{wb3`2i@czY({&!l*7I)-usH31IvDjiZ zbBwdzs>0Ub{S@8$=$kXAq)mnet(f|Ort#@;#=E&XFE2ESGPG?_Nx3pp87XbxCl}OjVi)@VFo4cz{z(#fC=S>)$*7%YtdM&nuU$ zKe$Qq*Gg1{j@FKN4B0Kt$>a^X?-rH49oR5wXl-@}#i$&ZpcCpihF{*>ZS8sU#OD5f z_@aQmw(7XhE7~i=*yhyB1$R;O{h?_s`pvj0spgM5qyr}yM&?osc=GR2H%f?;66i66 zEcg_-8i;Anyd*f|s&_Uy>${GG95gRkh}N2A_QTMkA%lu+U!81Xnoh(^Vs zz&q3~D2UnSNHc4^SzZdIT1T--by1Sh7)_*phq`JRCxmym?5uWUqT{vEjYP%Wea0FZ zO@&8-E0|rLh0O|(Y`Fj4J|Uu=t@C#Ai|XX4o2toe2ZD-_hxBRxdum5JURA6EwQnA) z=Q5pKn5eZR?r~B?PHHG7`uO*n#n>KimNq|5S`CfGd0x~`IwkO&y*ED`@9yo+6B8%! zHYBpw_X&_ObscMJ2?)lm(73ixuQy-3b$4;QWMKjS&KqQE8r&U|`ny~7ICqPl(?6D! zKQ&Nb=K%0_fXU`QL?HP19$<+SGMJb@uY7N@QF>QVTkW%`sC&%Ti&b#EY#V#;R8$!3 z=&RjF8eB~U~kkv(r=V$pN zX784D@1DPpR0AM&b%E?fH;2x)chpy!y2#3#O zGVu~IozS13Un%&pqw$S@GtCUOT7Go|7GE`p+5C7At>g;{=n zk~^0F;ANlvR!wL|ObwPuQ6`P~Ev2~I_rSs3v~Xx5wyZuG^5~$&Pe6M=<(~N9Ds)Rat4Y|6Fp9k-wQom#oJA}eecJPQj8MW9eM7kWf^ zEyKdyA%uFvXO9gqqzL6SYqO_na(wP3B;>u~fQy8W^DnAvD$ZFIrs7@NkvL*~=zUud8sm~!{iitz*C@YfFl9*|851W#Q@p7YMNHMLR7g^nU zKobt?X86KDGEwYh`h4SiM6)k3<)>MS+-u}>eN8}w6m)7ps^~$_+ojv-$9-j<8a$VL zSa9&CfXMv&o^X_Pn%W$`LO!f5r@a4Dm)H!Rty&g7Tyd9G6x&YcjQBm2@`;#|*xbyl zk;y)7W0OqOq?B9Lvsr+Ht)pZ@)XJDYp5tKz;gpP?0WbGM?HL|pQYo9be!uV(SG+Kg znFzi>!@+hF6qryj`5dNKM9>y#5QesR9d0x#HRqYpp4>kT{-enG6Eu~7O%yc8Dz5I= zDL8$1>T(lTDH92XnpK|tC}7Atz%m3A2kZY5TqS>%FJnRO*mT&-KI-H_e4<8uvrG(I z@;FXnnK4gcqhf61cQ@bC#e~^58vLhvBn`1;gZQYYmeHxG`wRX9z4i$~ZwJeCjoryO zMdamU&-|)*$rNjHFGl&v<+_BY1Zc1E4Hx1*ehUmXMfruvYlyfIHg=VP-^H`;lfO-K z%W7qtt1SLhhTGo^TnTYk(lf;E-wTws2Iv)w+N$MSsjoh8ac^7eKU+FpQmJJZ>n-y| zWN+yMTi%JXwBSh%-gp!i#X0kg=wZYu!W1-Gy^)`rg^%+}nI9wH>`w-U?|6hLvA8Fq z3eP5<<7oPw-P*lheP#AT&o+Fgk4}C=o!h;pZEU5*2WPJ8#72tcE`0*Sih&**THL3v?)WUuGCz!1 zwB&gDe5!HAwFYnH4GdlxliScMu|;ct|K06Fp3nb=Wuv8xZL7wQ6z8tO7Y&_1+ZUuL zt$lEs(uMw@5!YzC`CFmy#4&- z-@)eJoy1l!bqc4pZpoE24`1irPIjiF+ABp8&ScpCfo)Mb6uuJTB53tEyV`Vx@b>#Q zCYcx^!P0W-Q!zv*J4VAdTrX0{ON$2lk{8xljk44)c$>@r~|Hf^)Qk+3}4_WD?^gM%}Id;Uf2z5MM=ob@DsRnK=R@8R^9lin<# zw+UhsXRzp){p}vPq7bW>9t^sb8Mb#A8x|3H<*jutOug>qdIQ*+_JiDCXvzpEqm>Kl}P z`B|N+&Y@+0*>}w6b1?gz1Jg;fQb&kCAEBX3Nr;wrtYb7$4HFtKJ%U@FSnK5C@TSYiWUmb-c#2DJ3PnAJWxNm-z75!r(4*jn1|_)?y`lpCZg z(wuGN?Z7@MlW`%*nGSpCe;T=}d;fLTuqn)>54u;X^Ed_bDmp91meH?L{hLz#TQ0A( ztzlr3lH!vNSP{{y(Sn$5*nu5pl7xkXPUE;)|1rF`W6CT<*2-;H$n`!_Jgz=ik|OVj zBIxv{CAo&*EJWTid49JurkO4ChoqiWX5g|^;^o2J`SY?O66u)b*>hDEiBA%NJo@AE z)YFAI7o4hu%i!T7C3wA76#s%V8LPoUMu`#5$Yyt90{=|DQYuCk{i?Cf(ho9Zed|b+ z9!)X0FP2a=x^jTl${nJ>SDnA=^v3(@#ZDW@2FLN0=(&~d{?2%OM)?r;F-S&ElI*5A zE_?|;;Z!WKaKkvIcX#Z#usdZkCV142rJnfnk&0~{CX!G`1=$LT#DTt!Cw!c@d2~lT z2?4Y1GM{~TwefGeEUuRpQq7icg&hgWmcQAQbu5K{=I<|To{YBy%d34*3vd5S9s3z;RhWfR2Fi*&l=%^7S^u3!j! z@4xu~)gb~c*SXy@l=vK)&Zo3f2mMMghuv^@xF-zo_Wzu)>~O2${U|#b@ncf`sUWl{IJKV_!(_9@s=s_j5@W>~Wy-SLV z#i*&t0*$Iyv9)~+^?WMdhYWa z%cq>T-Yj2lytE%t%Fe1w~mMU(U1IkWV-4 zL-x1n@t*E~iqTKLQ2u*|hw7xhu^D#driEn9Xm68xS*BX@yM!iKK=Ub#_J4cA+4@`b zk&ZwSy!eT|GP0<;t!;ws)AFKd%AsX6Q14zN}B-iT{0J72`O%w!>IKarUHu^=`n3n7?QUqjYA#Z zI^^Co8I#)Z-r95Ta;yR>4~lq?l(T=ue>(6kwR2^`z7Yqko-6%J4u7w0;CGP<9@fxG z(OR3LZuxvNYdz(XYzf9h(yn!xf0KiRkmNX6|202 zF=+tis-?fzWByVU=jo`pA|{qtj4m&2ZdL2dQvGvb=n^U(O21t=^uuO%tT%=GuV)NS zxIT6g+^^$8%I`SpN|W@zxN0Lg`0X5;p*%(@7N}AHayH_5byZch1w0w0>rMR*i z)kRqwW|`;5g7f2K=_>9=D8;+4ibPUBTiOZ9myHeQ|{s@Rg4-8%XG zbZ26N5YBJ!Y9lpq5Tg^hQKLhBbo9>;k9F2 zmLysv@y!@=|M^`yM@tt&uS##sj&86)dCTE@p<~+J6`K(h^!EUQwwQqD@UjiOE z>z)7d)_H;Xf&7F6TdPe?JESt`iw9VK-d-rV7i8u3ebnW<6R5}<6+c`)l|i`WNsQbo zXY)VDZM5>C-Ci@Nm7=NZm%Z92KE*`q*4lK^z?i2P_KSCSyueXsh+&wyEE&JKLUm*b2cXAJiGgfsIlszllqN^-ko&WH9tdCAn;s1 z%WD5Z>>rr$+rB)Th%$zFmiRJM64wo{rcyJgM^kNG;3N#5WS0#S9iocbSz*@Od0Bz{d>*KqeL&9q2Nr zGy6Lv$d4gRZ;?LIWj17=!}ZG&CZl(kIVQW$qt9LpGnRqoI`{f?kkL^Ef}#2k{`?kk z8y8?*`#eOoxaMSneaOm;>NIx1igs$9^hpEvJ;{3xpA92X{ch)z=Q`4G^LrPjq_py| zQDJhUlhKhA^pP1Dc6yc~V@}^B+@ZVQ7kM%MwJ=M+RJ6C+qYxAnyT{%ftRPt1&i0>{ z%0{p@1tAReC2M^;-1A4OF73_(-#wKbO}S}Z(@q?-pciBo!u>3f#&ZOs?n9K>-TxIc0DPOb;5wO zJmK?r4s?ZCpmP0;a}4=io}x^zMqu@aA4?ojSl!PdIE6n*K+;|jO zm`2c}ZFCX98jN@_yL?$c${8}zP+p+^g-t;@Bb*PZgIPKkt|@exv-1m9Gc$t6eUij5F6!QX(fKiY{ALK6_j5qtblTd|qV2d|v73yo?1(5x2nQ zt3qmXb%h1fCAYy$p{Rjxfl}rW>bu@p(VD~Xs_7=3A|Z~oT*i4SYm!T4wUKkhr*LoS z8F3HCmALv>B9tltY<5w}jFMTR@};PEzJop}#hM^%N!DVpEY&@AZ*QDgAsPWz5f4;S_$C}DW(J6Brv)`qrRR+kd8n@fx zcRV4?H>gh)1~wlFoKFC;-WpRAwGNzGn$xMw?A zH5bn0yTHedP0=X7in^p#^AK~_;Aabvtu%5KCbv1UAP zFuu)CrKh748xf9D>|8|!y5>Du--uRs`Tbzr=sLlp+Hhg33V&zvgdx4!miLzyPrJsu zZ0*U!Q{NpdxO#2jeCL7!kH_k2`QBpgWqKG=v;UyY>g-S@{kg7N?(LUPzJ93;iQ6kB z_>bS)9qyijoosisso-{kdd&&fFm|_?+la#s%W$-(XERMB6$jg z%n$<>#uE7Ri6aHtD4)*ov5}0CB#LjR?`^Id6{lA(_$*;|Ef>zO??C$vJM)Yen*#Ew zNotUq*W)hXwaW;TaD8cf|X9ukZJ(Zi{9PUtXI=ot4SB zeu-&_O&t}i7_C9Fpj~M*d1lF{z8 zTxcd=S=_r}|Ixd1U^b)N=d(|h`{$QHmw|KSuz~%!-q8vxc_bzfM*b6Ii^>hpj_7vE zyqA%$QK!=3@2dCPyW-|l7krfWr ze62WjDy#i@35Vvhcg%9S3jE2J;yU=-$S)f<9VA7>7e^)dzf8E}Q6wuu?d3bpw}Jwa zU07S(1s&P2wJ_cj3CyR%NVRM7DIPB0vSzOFWW>@#!L-!ig`CWQFt6rFamf{JAPfiO zJlb%n8zb%TnwN;sS3whEaOfBt10_F$T}vui(BG>b`?--oS>>GcH+cV_BR$=yB32Zh zlMgitI6upUc2|q9Ho82uZHZfA|07&`vv$Q|fj+729kpXYQk*>@&ifYLgS$mb$CNip z>%L0$u3hRZ6lZ?Yy1Ms{Fuh%LW9xFj#}ghSm~bg!gXY+~37WHYXrdKvIXtp!(YOO5n#!1 zdLIbFhynfdO5NmJZ~y>3af$7Z2^#Fan)T{pG^j_X$nu6wU7r4k-o2MYfCRC@QMcUGgS6hLYl=VycZd?rZ|KvsQ$X7r}`#njY{F1>Nyi`I%4JCED z%2VO!`>bRmNnvv2YV>HXyQ_EJ%S9`$HuxrEsM@B^5rm;C5AePi5GTBtI3{9$xBUIO z9CBO*3Z;WeM+Z$a7{k^JmgimZ{Dol$dH45z#7be{Ti&)k zYoI88mzm*0I;Pt_d8DvI;IY;#(%EI4ExM#JEE)NdIBX{<4>g<+DWIw7cUAcHqV~JOyOI321D>mJ_fs`0J_!{N zmt!I|ARM$RAMT;DP( zQs#6TG(=MQLllC99LfWYLi}DsS!+*iDarM|D!vbJ7Z|z6U-_quW+Z98wqebTO;w}K z&!Rquf|F2eXy4TjOLWHLb0epV(w&|!&=Lj3^9)_t8rfUm{lXslM-(_MaC88CC6zBP zeVo3!2B!L+aVXm(dX1O*(!I8*nSql~PB?+O_lCR3>YER%+hJQT*IQFcEo87)NoI`ci`tay>DR?534M{`El-*Hw#EDgQ#wJ-|>N} zw@0g#63!UPtU_@|$A%dJPPDynvtdKgio8@#dg~+?OYpg5CgJUd9lp4BYil24KQ0im z^MU5)HYfrjW)O&0@J#FBUh9hxC)OI?nsAXWKZ`g`)Z-HZq?}V{p5(@L5aex(k8l%4 za4147UEvY$m!ZOxP}fTEIsB^7;_Ev-HSasqR$?TZf&YuCa`i=XDV3`Nf5*fL*>_@f zn;&my>yf~B#ou$f-tD}sQJSXj-{OQd(iQ0=U}Uq^6k&6veMH4wRaEu0gsn_NC@WJB z%tbh(Fc$*)17~K>D`X6p20OE`2b2s@8Ux!YnQUq}(7-><=ddW@(XyI&oF@%ubCSV- z!6%b5^}>Yrj0?p|Zcr;4A4n?jdRC>91NCkN_pk`-(yKwg7Y0p+7Ctxj-Cb%(%gA{3 z@gqHCKKPlS1@9FQkhU>Uewjq&`~KjbUvBlSoGrN(j4T&{>gj9K*oB} z*hm2#5HE*Zangu#43+BSUuIe-R78+CTdGK%dS_VLzQ!oRi{O&E6|LOv5rO{MpbU`; zu}Sg%{mY>VYp(Bw-tRdNI)?8eI9tc1qL#~AJs}r z>T#S7{8=3e^6kJ@3Jqlk_XEU`06Yy8=N%!)!AJlc>VjTAA~Fq<)vJ46Spf}7tW7Im za{-=Bh_*9GZ4WH?f`->rAe&ifs=Ne>Be(Aq98|+^fjvx)ayg#~(e}Op+sQ?FL4f3w`#)~}e0$O}56m_oVIe*UYaj*BJ?vYy zG&A$&PJO^n~!zwXoVDZN!So(00A>)Ls8;w@9{ILq)6IO5Fv8(mCzfQXXX4>mVw`n!?8!x{uW~U zsfAC$DyPMVuwTD@a{$LU#DX9fv&FQyDFc?jbc(8%3Bg}L=n)tkMHpLQj^oNKI);ml zK}sC>2Jl3KC-o!BJ?apr9J$~fbZ+Q@G-5*oqErYw4#%fzZgHFt51xki=HgZJmp6!n zn>Xm-P#L)2bRW`&D1dVf<_^=JO0OYCi{4A01R?zKo)duH9K4o#-vv4$i-xFT<8oWb ze83!pH7@)V{H@@L!V&_pL{UUS9?@fle?-W&q*q~i!!`y6kt=&_;KUG&Zh$dCebDAv z%b*2rIdH%T-CwfW+l9FXokv2`k6Qn5BLeclTO&@0F%KAVq!x|C?hGg_wEy_=L-Di3U23w;xp&)`i@Lhg4~;F`5w8jahrn_HzLnZD z!-&PlSS=9Y?UxsTAOwyT z{{9TevJkRtin~_l0WJ?aDwP*fnI8MfumU-+g%7>u}ZWM%jhB>53PhehxW zRkj9>W8gh_!+-%%ZIPSF&$(=fX5|eWi!9Nb=CW?Fbi3=P=fCZ zm=Pd8pJ0#$>s|GwIp`(Y8Z6Y*)&fNegfAk5TXyh~z}Mc6hmh&6S^(n!CfXpPB>nl* zd$T37Gm(Av?Y)!lN39^3L52Y5D==`NwG7=qGG-ZgqJiuyXfwsZgeOo23$AO%nm!V; zK&;{5mN=r?Kz~2!Ty}R&R@lI>>7?rBuw*-BD9~8Ere6`kHAAI>xEcYi6R8h@Fpxqw zG&F>SzZzFuMP+3Yp&9byB1vdqQFE#uj$Z4Szjcxj4*@2tA=`}sAf68N+oL-L@z0$u ztAhw+ivwR7vWE@htL<68@r&@vu1;c0=hQb!j*1-S2*|Y$Rs@cs-r9yr-q2M%d8q+u z1R>=RO>QHudq5gLDvpgreOY;vZxyy@a+QZ{N(AmpNc?EtJYskU| zzZM8ri;Xu&+(0KE4{=dMJR5`_dHb`K;*-wxBcb1fNa_CFVk`a8>Lk@Z z@}s!O37{4u-piFGea8o-uYkfgAv)^SEkvPV+7#XrVw-$nXNmxMX|S~5ymPH-haU&Q zj8{Krs)I)1V#G;S6L{#Gx^qTn=mAZGOVYrKKdl-qvMrF3@~Y16m)$=gC5$X^ay5SI>!nCed+7%l>v9%$mt8vrG_C{Flf7C@&~;)=9G;4ns*nAf!zzj5wGXKBX@f;l)cV#Qt$b~MYzD0RRm~~Mudw% zcR%=oCyUaC+YvKQ`|`6Ae5vtAA5ejTSq1UHfH?)g*gMPKy&QQD zQ}gFCAh`h3scPgk03;{)(^EtG3U46VJs&;`Qpk9(m9o+JkR1Wuz|x8-B7zxq9EHjuTg8-*IKA9#!2j@VsX?O8!YMdMEI+C9L*< zfWyU)A0BiJpIuq}8Z7{pA{I|jZYamuYu7_ak_-GrsLl6r$qzAMf^Y?If(Z4c6}bO5 z^o>8vKNl9HQ~|P!Z=(f}T?p}zQL#RqLVU^&H2lY4PWnq0YX@IXcn59}wpR~Nak^shuNKL5C}uX75k3T`c+XhW|C%`GJRrgkExc1z{0 z31Aa-43IhEV22pJATCR=zCauMygz54czC?CuS+Y0_96#LOI68G4B!OpH>?2}k}{0SPL_9K`@|(BaVKQv?cljW z@RsX?Q5nSi4+8#+rlz|{%79`49y4M!1#V}^bW1rdIlc<`o>A8D%+}c7(ac3Mj*buyt`h*XISx*@{A5@Ol|)1^`R*TEirPyY z2bV6h!fsq!^O~t${KNgf&ldBZq<0M^g;;((lbo|NmesEv+s!A2&ojpz$CjYdB1A zZ7yFmglhym01p|`3t;YN&z`m9sl+nDcK@eN@&?c_zgY&2PB>1_I~~;qEiK5uqVn?D zQ5?#o_En}(m%vB~)D#Hrf$KzyBItEhR98nKH4=jDVc8<+7i_Fx;j@DeBRBzp3EsS~ z45mG)#S$Lxia%1cbbSN(g4KBh?x;!kJ?S}T7Ixryq%|?%{NVpnHzHi9sWQju;=k77 z!a^2SZnk7+ewW@If5!R`+5=EG;wOMSKv!H@yPpM;10eCdUJX6G1^bdf(SRH0b{_Bb z+`61F8O=G)nd`C~AyjZ8klDktcl&R{QN{=Q7s1&+f4RmAq5T8au9AocoG?(xI(g+ zrx9nVb_K?b(1h`1XQ1}_L0y*!zR}TD(GPQ z^>gQ^9pWwwDweSM^q=Ra#1}ET)tCX^e;=d+j6~9iJmD;+&UU3ghsA!30p@v6imL{H zY@UXt3QyWD+C9ijVQL3Q^?DU*<~NYrfQw5Pka5NG0+e0Qp)k;vN)Yz~+03NPA&GVQ zp+1f1c-209$p4RhzAh0;%*q_)enJ_G*LMt3pgTGNL=qeh*#(LM@m!jGh-DR6 z%)zFF1k5{&_cP@N?Brnu1TQNb%qsBMjKJc6q9xVP4aPyIp~L`+2pkjw)P4=tuxns= zHVehXDR8n{w|DFG=5S~#OImt+g`JIs1+tj<%ih_~(>-8fzxOGia@%#6t)WczfveNP z9wtdq_@1dC7EaW_t_TW7rDp-9qMU@FtpFPI;O!Cz*QJrjHa#_E&2fnzVkd^(hLOi6 zmC1kMfU?q=4)XNlxd}K3gpfA1K%$5$4%5c|diDeFD7evL8b2$6x7!VAkaK~d#{zeg zGj?nW&{13so|8T5!a$t{&RPKJk&XnoSp!6X6|Vif-PZ(|(@AH`Z%7~HD8=&a2142? zHBteeDM)q@yrFPJ9MF*d{1Nz*Hm$l2u>m^F{}h6tVJUWe3L5Y5UvfmvH&SEiVLy67 zF^@C>hQ{C!@C0kjyUxa_G}pk07<{4aiHzw%EeaUwk+9X< zG0)a}9(9=|bA^U-HF=h?RB@}#v#*!3(v=vBE1i>&hmqgQl?PZciwA|T$AF(L^e4dU zu}}X9oIsgA{7afqRaxLrG(J7zyLqw3OgDmwb7r%`R}<{u>c)uBBpgUh21yV6CdqMr z2+&)?mCsroZd&~XeR!OzR&Nr~_~6kc17#1qA}Ms%|=L@F0U6k|Yo{`7# z=wK^@p7)*pXYt&El>v>*iXZn&4bO77C(Z@JtA!P)ObVz0O2E@{fGO*Pe~SSifGO2A zqzwYb#|Zd63ir&Up(q$5c(uLXa;_@O(iv19DoYKUK3#<*-#AW;LNFe9paW|gzDVy6 z{vcBFnl}d>M@or@{Kjj8I>Pxw3sZ>aC-jDsMO|x{%}R}|-sl6;J2(hg+{{QAQ;0|7 z1M(Shqc%{-44YdyebG7*!wE-u2;6Ggp16fP9)RQbdmKd-6cR7;M1mU}&#d^E<>S_rrJ=FeCkicI7Jt1~@M|~%7><)pZ)a-|c{NT9?o%Ytf@l{As2vbF* zc)%G+#ejFxbJnCfEc>+PwS^{W&}zx&#;1npVmRS`*G8Ojr;$<=IuM*##7Grcu~0Q4 zJ*1fvt%^dAI>2rb%yaI4@#LIYywEIP!nIW2cW$7nO=KxcR#(wy&B&GvBhB!N|5Sr?eVObhvuktNDReMN`mAio)fNNi4}j(r_D1>; zGyzukk1T`8Cif<`p|Od8d_CTrgaPWxi`qb!%rKw)AhHBoX()?8>UW^tiQc>HD7>OQ z+eZK|vn8pc;mhBXF7YYLHL>hQeu!4pnhM zO5Ee8o^s+WH&{p@@;%fhg2DyxyPD9WrKKm4tbOYukg))4AS=y48>tbWmHcX&z;!79 zKSf=6Jk;C!pSsbNwkb<>L#0TKq=?26Ww{hBickv4R+6PGS#FXV+bu=OptM}cwUfQY zm`auir5KrnY*{X@3E%gbxxd$M{+s#CIp;agzI@JkDqR1VH8dKE5CuM@k@`1ZX+ckE zC~O!$IG|vKA;^?1PPh?`iWb(ta>nP{gvede(N1FH49bs&q-n8?vdIm|f|-%n0a5kq z$>ZGb=j2J5CPOwdpybAom20b;nuzo)(&iB{pU#5=&pWG#cNPiJ>Odb&9V9E7n#?^S zq}iHnDlXsm+;i;Fvu$#o9UpU9V64Ifg@I%LpHm|dj-HB+LMUXapv_MdyC9ADkTdvT zA@!Ai?8wHyU$uk;vl8L2bI(9$1O$BQ-v$c<;vm&P`WnOGgT-7I5Uie1-|IT{vug(% z+L(cM*e-dD1F6Vd!{x&X-y4jyXYi^6k*K$Ga1b(9fbmZ;PlKsNb3W6p>IyfFiOYb4 zPDs%p#>pN#uy_vn1*v4X4`*kl1JEvh2N5FpG$i9nyd>a*MD>+(I(o-77a>2jh2)Wm zMuU(TJ!p0&x%23>w~6}R=2ok`nvm9kNkuG)H=};Ml$lT7^da-SPh-ekz7aW29=cK zIMZEy@`%*hOFCdS(24|98!i4uFi!F&NCi}aR>vBzOQS8&y~DH)s2tLPv$E1)%R`&A z-cU&!B1S*ZwUt<7YisL$#)S94oFqWUVRqcvh>RW_E~N8N3BW<2A2S8#&+Og*plfy* z=b`hQn=Hzk^}kdyw#J`5w=m|7zRR)BH8XnCpTF9`N~0 z33xu;a#G~g-QOmEXda5qG|y->vG;u*Jck^B99NGzE7x$XEGxp z4lKAFH;f;A>#Z8m#5wAb-rc(;w1cKe0Ed%)8?2so1~)t zlMW7b?9IL61w2JBity1`hp_2RQ3{13yqlqgbB8u%7f8VhVI8+6&lOoVmJc#>TNf@^ zuz-bTpr0dl#>B*sr)Yv4PSSB%xw&HKs~Zg$6JA&Z5l@&rE^0?)Flopu&gF8^=Ux(E zz{$Ad?}ZbXl^;GF_MCL~_EtsLV=7YK@Mf11%Z3~=UXZXN+JS%)gigJ7PEPBINnwNE z?Ck8;*p&EC(H$Jwjy%NZ(O3E%sI^QDN%(NpQ%`Y}8Ht(AXtI09XZok_)Z{iCmd zD_JDKn&>|h^c%@Ta^VkObFc)Dt0wLUBFQeio{s(-74P34ghGbhId$Zz`|4rMXcmhF z2DuV6!{f|tQA%6pv8K($F)|`T59mr9aP8rtIe>VEO(_FzjhcKeAsEzN)eiX+_~-0kTj>O{km7Lqs993Su;mg&P>6da!PjI65KgK) zmDtKxUul#?l(%h@NJ&YlzWNv5p{O8`;VO(sU?0R@o+WH4^*J4#D#8l zGPTs#Ls7(Ma?}|q*p0X%##1Q^(ek%48{b4UeGSLxSJ^Z&BH=DEzC$zu< zPXnj?j+6&#L9XpCT+oDjdhf_4!<4MjGxguTog{)mwuq7jA5+6$jo_-VpzZvt8q%LU z!OKDh1Oil0VE<$Tr$>_5U%#H%YNNX16Yuoc3YpMf2j<#WN~FVZb?Iz(Lm$`Q2>a3_wL=TgoFr$6l|H92{v-}U!p{wioLu< zD>~Xknuhyt*-RNt=FCh7y}VuwUDEdmas-wk)gH*$6F@gS>~R4V0*!~6*|czErNPc{ zfKZ34{Qlj=^Gs@EVgREnAk@+uOq_kdg@)-JhW4zpW-=d&7|; zH&@q15{BW~AW^RhmbTKAtXgSzeRcEXc@5c8CGS0Go2FFZ(w=j>SDN1u^z zCaBe}3Y_>7_RV!uTvatYB08Gv1SyNPiCX^o_C{qWUsgb6bCJCy4cwuQP~&;p6)PNR zAba`pWx@~;7cSgHWjcKYLSAIvnXg7P@htwD^SN`|P+JxQ+(QUud{7(tiTZ6TRbMur z!xei3lqXH~IV!8FHkPqd!t#lO8!F0_q?JJ8|7K0`yL%?@uDdP9KI0HbA+Cho5!g$kD@KweA36GkN1}`$)PJ6PN~y;`c3Q0bTZp!tiJ`cBl~sA$y{18n z-lQwcX7K6K(>-mk-3E1g?Hjt%oAYdv5|x-Z7on_qimFz0C+IF^{u5f&*iS_TK=}LE zJS8L7gzZsY(ZIKqZs#sWMuuvBu5pHEfv3^X1;$$H;LawSYbP_hOsob=IovUiKV857 z+dNUd0N(K){Z?(1!HaRu=9lbul97vLm(KfwA^9v1nK$(A^ zR<))|&d&CW&5#%tPAJL^+h1zKQGL@VX*s4bzM6OR6FqeFZf0IwQ}Xr1w2ASvsDLMa z&`4VrXJ!9hH`gGeBaiiK%cO5Fd#6O{i}HgM;RCTIhiw*9D8YZnjpc4INIw^v^wKGy zru9XW?V}imvSY^Pb00EPO&p>8AQh~J(`NGxc+OK+=ZoD6?Dc`>)btR|K(+Md{(k~@ zsVxEReh2M_{%JlYzUUVUMaRM=(u$>!U@kLn2am}a{2a*0=u$VcR`}3&vb@9+_ib8r}g_HtYzjIJvgAiSD^_Bw8WNXw{er&X8OA^)Z3+;|9#%t){99G zr5sZnO5}tj+FVP0iZyFlgsw$NS5&toyoev|fCtd;hPS zHjb$WTa=9&{Wy2;-kl)+z1o?!Q_>nyO}~p#he+ZI_RvcD?BszG`uFi{pX$J*IOBDz z!xPE8`!Fx<&Xv$mf0h|&R_Dps?^@oT%PG9FD2Y>R`}b+4rm@wd`~gn64BT;z8ks{3 zHRlzuF5=Q>hwGa;liFgO=o1;-^o7H>^j_VwxN1q6e}i@>vtkuy3wYFUtz&bRi<(T4 zw$N=fMkgiD4!rjfYS>p|I26dLwFcq7+1Nu&LA&M^ag68RH-AZ$vPwErKK^SF6ByM2 zMx&9AdF-Q=Q`0A*Si(k;V?{m&3wP zWXb8=|B2Bo_uxQkA;+R%{pH7{QM%>ZKhMmg)V<86ZIp&D68y*6gzhYhAI@Q>Z5p@< zIs$Tqz>j6-Pyf#Ie&5Sj=#kW6Zzcbd(UlxW5ORrD)fWe*c&3BPCEx_*xpu3Y?xWY_ z^}GMsmC@W=o$S4jHQxPntcYX7USwC`dR{}g)D#wZ)vvgqoRX=?dLovu{dHBA(++lN z+0ptXA?Xd4t-~#hg~I^~EhzgIIZ*E&CA+*hm5l-I0SYeA+-9Py<(J=BsKIPBIVXA~ zom1Xgv#WgBCTU7=Aeu7+oN22^dBzV8!1G(Sg8qS4VO04S_i=MCHA{tq4nXFDE|Vib>hSI_KA6#*0t;U;c0FM3(d(Jkn1y&fTbFppH0|?l;oa6P z=uV%prL_OaM>Bc4^~>JGX>%IB&9P z!Fi&c^h zFRb_K9~;uuRx)m|ylL#f_Uw~Lsn6=*=s1EkN126%zGh_Wb!;oy0~!~R6~^UwGx8D= z1C{X64r(q)$UeU{o>C|OAM;Z_m?d^0mRSZp$}-cDT%1Gc-e?*7QHjJx>bavibIR9> zwi*)p^O^VA{@XPd2cT-|ECj?^c_^`qYD*U_iX?bkO!zgJyM-ylA9H3Ro!G4Qr}bX3 z$wIBW2-;5k$41GD`0-dm=)fvWCV7c)R`Std&4SOXyr{~e!DYw!%$CfouU)>!@p;cu z0Oq?>0{^NLd6<)|aRs~8EME;VqnWP_$P~?M&~Xsr!;q zRVT>$?$-%CWQdVqNIin3UmGml>&f!hZxN6Zgz+9wF`*$sh)QkXOj)h)9EF9e-{8w`5O6p@3yMfo0b#{&yn* z_KCw!CJvSb>Y4Ju=+-?aiF~)pnK+7A)omw3bOl2W#n)s5$(KQ|z1Rf?x!vq4>=eEm zf~AWR1xpu?=7?hHK#U`w+&_9~-SdIVza6&_#B>WGpt;mTb5bL}3GiE5;U$rqgjp>> zE6i$ho#5L^hWuk4k$p<(dJ{)Wx5X{s1ALeE7`6AmSr-~LSYDJ^32UR%tbChbe>6sg z=}@SvzJh?Vh7Zb=T&*W4uM7fsiSudQZP?Q#^)RRX2U+Se9}A;fK}D7SP>>M(-@376 z;?07IHSh-?0=@vZ!n*M_OLE)W$rKm)j4+=eSb7U7<!7bP>^;;-nw`C-m+{@|=*{P~_gI5uw^la)-+ zLlrFX<#x?%>|*J4fuOgy6ZOJcMO4I7v21}}a`$AN@d-ZtDT6EXJvkW;~ybR3be*u6U(7tBer%8DKIj%6C target_filename:="${HOME}/my_robot_calibration.yaml" + +For the parameter ``robot_ip`` insert the IP address on which the ROS pc can reach the robot. As +``target_filename`` provide an absolute path where the result will be saved to. + +With that, you can launch your specific robot with the correct calibration using + +.. code-block:: bash + + $ ros2 launch ur_robot_driver ur_control.launch.py \ + ur_type:=ur5e \ + robot_ip:=192.168.56.101 \ + kinematics_params_file:="${HOME}/my_robot_calibration.yaml" + +Adapt the robot model matching to your robot. + +Ideally, you would create a package for your custom workcell, as explained in `the custom workcell +tutorial +`_. diff --git a/ur_calibration/src/calibration.cpp b/ur_calibration/src/calibration.cpp index 0c9108b35..9a680d856 100644 --- a/ur_calibration/src/calibration.cpp +++ b/ur_calibration/src/calibration.cpp @@ -73,72 +73,87 @@ void Calibration::correctAxis(const size_t link_index) // the kinematic structure gets destroyed, which has to be corrected: // - With setting d to 0, both the start and end points of the passive segment move along the // rotational axis of the start segment. Instead, the end point of the passive segment has to - // move along the rotational axis of the next segment. This creates a change in a and and theta, if + // move along the rotational axis of the next segment. This creates a change in a and theta, if // the two rotational axes are not parallel. // // - The length of moving along the next segment's rotational axis is calculated by intersecting // the rotational axis with the XY-plane of the first segment. + // + auto& d_theta_segment = chain_[2 * link_index]; + auto& a_alpha_segment = chain_[2 * link_index + 1]; + + auto& d = d_theta_segment(2, 3); + auto& a = a_alpha_segment(0, 3); - if (chain_[2 * link_index](2, 3) == 0.0) { + if (d == 0.0) { // Nothing to do here. return; } - Eigen::Matrix4d fk_current = Eigen::Matrix4d::Identity(); - Eigen::Vector3d current_passive = Eigen::Vector3d::Zero(); + // Start of the next joint's d_theta segment relative to the joint before the current one + Eigen::Matrix4d next_joint_root = Eigen::Matrix4d::Identity(); + next_joint_root *= d_theta_segment * a_alpha_segment; - Eigen::Matrix4d fk_next_passive = Eigen::Matrix4d::Identity(); - fk_next_passive *= chain_[link_index * 2] * chain_[link_index * 2 + 1]; - Eigen::Vector3d eigen_passive = fk_next_passive.topRightCorner(3, 1); + Eigen::Vector3d next_root_position = next_joint_root.topRightCorner(3, 1); - Eigen::Vector3d eigen_next = (fk_next_passive * chain_[(link_index + 1) * 2]).topRightCorner(3, 1); + const auto& next_d_theta_segment = chain_[(link_index + 1) * 2]; + Eigen::Vector3d next_d_theta_end = (next_joint_root * next_d_theta_segment).topRightCorner(3, 1); // Construct a representation of the next segment's rotational axis - Eigen::ParametrizedLine next_line; - next_line = Eigen::ParametrizedLine::Through(eigen_passive, eigen_next); + Eigen::ParametrizedLine next_rotation_axis; + next_rotation_axis = Eigen::ParametrizedLine::Through(next_root_position, next_d_theta_end); - RCLCPP_DEBUG_STREAM(rclcpp::get_logger("ur_calibration"), "next_line:" << std::endl - << "Base:" << std::endl - << next_line.origin() << std::endl - << "Direction:" << std::endl - << next_line.direction()); + RCLCPP_DEBUG_STREAM(rclcpp::get_logger("ur_calibration"), "next rotation axis:" << std::endl + << "Base:" << std::endl + << next_rotation_axis.origin() + << std::endl + << "Direction:" << std::endl + << next_rotation_axis.direction()); // XY-Plane of first segment's start - Eigen::Hyperplane plane(fk_current.topLeftCorner(3, 3) * Eigen::Vector3d(0, 0, 1), current_passive); - - // Intersect the rotation axis with the XY-Plane. We use both notations, the length and - // intersection point, as we will need both. The intersection_param is the length moving along the - // plane (change in the next segment's d param), while the intersection point will be used for - // calculating the new angle theta. - double intersection_param = next_line.intersectionParameter(plane); - Eigen::Vector3d intersection = next_line.intersectionPoint(plane) - current_passive; - double new_theta = std::atan(intersection.y() / intersection.x()); + Eigen::Hyperplane plane(Eigen::Vector3d(0, 0, 1), Eigen::Vector3d::Zero()); + + // Intersect the rotation axis of the next joint with the XY-Plane. + // * The intersection_param is the length moving along the rotation axis until intersecting the plane. + // * The intersection point will be used for calculating the new angle theta. + double intersection_param = next_rotation_axis.intersectionParameter(plane); + Eigen::Vector3d intersection_point = next_rotation_axis.intersectionPoint(plane); + + // A non-zero a parameter will result in an intersection point at (a, 0) even without any + // additional rotations. This effect has to be subtracted from the resulting theta value. + double subtraction_angle = 0.0; + if (std::abs(a) > 0) { + // This is pi + subtraction_angle = atan(1) * 4; + } + double new_theta = std::atan2(intersection_point.y(), intersection_point.x()) - subtraction_angle; // Upper and lower arm segments on URs all have negative length due to dh params - double new_length = -1 * intersection.norm(); - RCLCPP_DEBUG_STREAM(rclcpp::get_logger("ur_calibration"), "Wrist line intersecting at " << std::endl << intersection); + double new_link_length = -1 * intersection_point.norm(); + RCLCPP_DEBUG_STREAM(rclcpp::get_logger("ur_calibration"), "Next joint's rotation axis intersecting at " + << std::endl + << intersection_point); RCLCPP_DEBUG_STREAM(rclcpp::get_logger("ur_calibration"), "Angle is " << new_theta); - RCLCPP_DEBUG_STREAM(rclcpp::get_logger("ur_calibration"), "Length is " << new_length); + RCLCPP_DEBUG_STREAM(rclcpp::get_logger("ur_calibration"), "Length is " << new_link_length); RCLCPP_DEBUG_STREAM(rclcpp::get_logger("ur_calibration"), "Intersection param is " << intersection_param); // as we move the passive segment towards the first segment, we have to move away the next segment // again, to keep the same kinematic structure. - double sign_dir = next_line.direction().z() > 0 ? 1.0 : -1.0; + double sign_dir = next_rotation_axis.direction().z() > 0 ? 1.0 : -1.0; double distance_correction = intersection_param * sign_dir; // Set d parameter of the first segment to 0 and theta to the calculated new angle // Correct arm segment length and angle - chain_[2 * link_index](2, 3) = 0.0; - chain_[2 * link_index].topLeftCorner(3, 3) = - Eigen::AngleAxisd(new_theta, Eigen::Vector3d::UnitZ()).toRotationMatrix(); + d = 0.0; + d_theta_segment.topLeftCorner(3, 3) = Eigen::AngleAxisd(new_theta, Eigen::Vector3d::UnitZ()).toRotationMatrix(); // Correct arm segment length and angle - chain_[2 * link_index + 1](0, 3) = new_length; - chain_[2 * link_index + 1].topLeftCorner(3, 3) = + a = new_link_length; + a_alpha_segment.topLeftCorner(3, 3) = Eigen::AngleAxisd(robot_parameters_.segments_[link_index].theta_ - new_theta, Eigen::Vector3d::UnitZ()) .toRotationMatrix() * Eigen::AngleAxisd(robot_parameters_.segments_[link_index].alpha_, Eigen::Vector3d::UnitX()).toRotationMatrix(); - // Correct next joint + // Correct next joint's d parameter chain_[2 * link_index + 2](2, 3) -= distance_correction; } diff --git a/ur_calibration/test/calibration_test.cpp b/ur_calibration/test/calibration_test.cpp index f6910fe0f..e5f0685b0 100644 --- a/ur_calibration/test/calibration_test.cpp +++ b/ur_calibration/test/calibration_test.cpp @@ -42,12 +42,16 @@ //---------------------------------------------------------------------- #include +#include +#include #include using ur_calibration::Calibration; using ur_calibration::DHRobot; using ur_calibration::DHSegment; +using CalibrationMat = Eigen::Matrix; + namespace { /* @@ -67,12 +71,36 @@ void doubleEqVec(const Eigen::Matrix vec1, const Eigen::Matrix } // namespace -class CalibrationTest : public ::testing::Test +DHRobot model_from_dh(std::array d, std::array a, std::array theta, + std::array alpha) +{ + DHRobot robot; + for (size_t i = 0; i < 6; ++i) { + robot.segments_.emplace_back(DHSegment(d[i], a[i], theta[i], alpha[i])); + } + return robot; +} + +class CalibrationTest : public ::testing::TestWithParam> { public: void SetUp() { - Test::SetUp(); + robot_models_.insert({ "ur10_ideal", model_from_dh({ 0.1273, 0, 0, 0.163941, 0.1157, 0.0922 }, // d + { 0, -0.612, -0.5723, 0, 0, 0 }, // a + { 0, 0, 0, 0, 0, 0 }, // theta + { pi / 2, 0, 0, pi / 2, -pi / 2, 0 } // alpha + ) }); + robot_models_.insert({ "ur10", model_from_dh({ 0.1273, 0, 0, 0.163941, 0.1157, 0.0922 }, // d + { 0, -0.612, -0.5723, 0, 0, 0 }, // a + { 0, 0, 0, 0, 0, 0 }, // theta + { pi_2, 0, 0, pi_2, -pi_2, 0 } // alpha + ) }); + robot_models_.insert({ "ur10e", model_from_dh({ 0.1807, 0, 0, 0.17415, 0.11985, 0.11655 }, // d + { 0, -0.6127, -0.57155, 0, 0, 0 }, // a + { 0, 0, 0, 0, 0, 0 }, // theta + { pi_2, 0, 0, pi_2, -pi_2, 0 } // alpha + ) }); } void TearDown() { @@ -82,24 +110,13 @@ class CalibrationTest : public ::testing::Test protected: const double pi = std::atan(1) * 4; const double pi_2 = 1.570796327; // This is what the simulated robot reports as pi/2 - DHRobot my_robot_; - DHRobot my_robot_calibration_; + std::map robot_models_; }; TEST_F(CalibrationTest, ur10_fw_kinematics_ideal) { - my_robot_.segments_.clear(); - // This is an ideal UR10 - // clang-format off - my_robot_.segments_.emplace_back(DHSegment(0.1273 , 0 , 0 , pi / 2)); - my_robot_.segments_.emplace_back(DHSegment(0 , -0.612 , 0 , 0)); - my_robot_.segments_.emplace_back(DHSegment(0 , -0.5723, 0 , 0.0)); - my_robot_.segments_.emplace_back(DHSegment(0.163941, 0 , 0 , pi / 2)); - my_robot_.segments_.emplace_back(DHSegment(0.1157 , 0 , 0 , -pi / 2)); - my_robot_.segments_.emplace_back(DHSegment(0.0922 , 0 , 0 , 0)); - // clang-format on - - Calibration calibration(my_robot_); + const auto& my_robot = robot_models_["ur10_ideal"]; + Calibration calibration(my_robot); Eigen::Matrix jointvalues; Eigen::Vector3d expected_position; @@ -107,38 +124,28 @@ TEST_F(CalibrationTest, ur10_fw_kinematics_ideal) { jointvalues << 0, 0, 0, 0, 0, 0; Eigen::Matrix4d fk = calibration.calcForwardKinematics(jointvalues); - EXPECT_DOUBLE_EQ(fk(0, 3), my_robot_.segments_[1].a_ + my_robot_.segments_[2].a_); - EXPECT_DOUBLE_EQ(fk(1, 3), -1 * (my_robot_.segments_[3].d_ + my_robot_.segments_[5].d_)); - EXPECT_DOUBLE_EQ(fk(2, 3), my_robot_.segments_[0].d_ - my_robot_.segments_[4].d_); + EXPECT_DOUBLE_EQ(fk(0, 3), my_robot.segments_[1].a_ + my_robot.segments_[2].a_); + EXPECT_DOUBLE_EQ(fk(1, 3), -1 * (my_robot.segments_[3].d_ + my_robot.segments_[5].d_)); + EXPECT_DOUBLE_EQ(fk(2, 3), my_robot.segments_[0].d_ - my_robot.segments_[4].d_); } { jointvalues << M_PI_2, -M_PI_4, M_PI_2, -M_PI_4, 0, 0; Eigen::Matrix4d fk = calibration.calcForwardKinematics(jointvalues); - expected_position << my_robot_.segments_[3].d_ + my_robot_.segments_[5].d_, - my_robot_.segments_[1].a_ / std::sqrt(2) + my_robot_.segments_[2].a_ / std::sqrt(2), - my_robot_.segments_[0].d_ - my_robot_.segments_[1].a_ / std::sqrt(2) + - my_robot_.segments_[2].a_ / std::sqrt(2) - my_robot_.segments_[4].d_; - doubleEqVec(expected_position, fk.topRightCorner(3, 1), 1e-16); + expected_position << my_robot.segments_[3].d_ + my_robot.segments_[5].d_, + my_robot.segments_[1].a_ / std::sqrt(2) + my_robot.segments_[2].a_ / std::sqrt(2), + my_robot.segments_[0].d_ - my_robot.segments_[1].a_ / std::sqrt(2) + my_robot.segments_[2].a_ / std::sqrt(2) - + my_robot.segments_[4].d_; + doubleEqVec(expected_position, fk.topRightCorner(3, 1), 1e-8); } } TEST_F(CalibrationTest, ur10_fw_kinematics_real) { // This test compares a corrected ideal model against positions taken from a simulated robot. - my_robot_.segments_.clear(); - // This is an ideal UR10 - // clang-format off - my_robot_.segments_.emplace_back(DHSegment(0.1273 , 0 , 0 , pi_2)); - my_robot_.segments_.emplace_back(DHSegment(0 , -0.612 , 0 , 0)); - my_robot_.segments_.emplace_back(DHSegment(0 , -0.5723, 0 , 0.0)); - my_robot_.segments_.emplace_back(DHSegment(0.163941, 0 , 0 , pi_2)); - my_robot_.segments_.emplace_back(DHSegment(0.1157 , 0 , 0 , -pi_2)); - my_robot_.segments_.emplace_back(DHSegment(0.0922 , 0 , 0 , 0)); - // clang-format on - - Calibration calibration(my_robot_); + const auto& my_robot = robot_models_["ur10"]; + Calibration calibration(my_robot); Eigen::Matrix jointvalues; Eigen::Vector3d expected_position; @@ -167,46 +174,21 @@ TEST_F(CalibrationTest, ur10_fw_kinematics_real) TearDown(); } -TEST_F(CalibrationTest, calibration) +TEST_P(CalibrationTest, calibration) { // This test compares the forward kinematics of the model constructed from uncorrected // parameters with the one from the corrected parameters. They are tested against random // joint values and should be equal (in a numeric sense). - my_robot_.segments_.clear(); - - // This is an ideal UR10 - // clang-format off - // d, a, theta, alpha - my_robot_.segments_.emplace_back(DHSegment(0.1273 , 0 , 0 , pi / 2)); - my_robot_.segments_.emplace_back(DHSegment(0 , -0.612 , 0 , 0)); - my_robot_.segments_.emplace_back(DHSegment(0 , -0.5723, 0 , 0.0)); - my_robot_.segments_.emplace_back(DHSegment(0.163941, 0 , 0 , pi / 2)); - my_robot_.segments_.emplace_back(DHSegment(0.1157 , 0 , 0 , -pi / 2)); - my_robot_.segments_.emplace_back(DHSegment(0.0922 , 0 , 0 , 0)); - // clang-format on - my_robot_calibration_.segments_.clear(); - // clang-format off - // d, a, theta, alpha - my_robot_calibration_.segments_.emplace_back(DHSegment( 0.00065609212979853 , 4.6311376834935676e-05 , - -7.290070070824746e-05 , 0.000211987863869334 )); - my_robot_calibration_.segments_.emplace_back(DHSegment( 1.4442162376284788 , -0.00012568315331862312 , - -0.01713897289704999 , -0.0072553625957652995)); - my_robot_calibration_.segments_.emplace_back(DHSegment( 0.854147723854608 , 0.00186216581161458 , - -0.03707159413492756 , -0.013483226769541364 )); - my_robot_calibration_.segments_.emplace_back(DHSegment(-2.2989425877563705 , 9.918593870679266e-05 , - 0.054279462160583214 , 0.0013495820227329425 )); - my_robot_calibration_.segments_.emplace_back(DHSegment(-1.573498686836816e-05 , 4.215462720453189e-06 , - 1.488984257025741e-07 , -0.001263136163679901 )); - my_robot_calibration_.segments_.emplace_back(DHSegment( 1.9072435590711256e-05 , 0 , - 1.551499479707493e-05 , 0 )); - // clang-format on + auto [robot_model, robot_calibration] = GetParam(); + auto my_robot = robot_models_.at(robot_model); + Calibration calibration(my_robot); Eigen::Matrix jointvalues; jointvalues << 0, 0, 0, 0, 0, 0; for (size_t i = 0; i < 1000; ++i) { - Calibration calibration(my_robot_ + my_robot_calibration_); + Calibration calibration(my_robot + robot_calibration); jointvalues = 2 * pi * Eigen::Matrix::Random(); Eigen::Matrix4d fk_orig = calibration.calcForwardKinematics(jointvalues); Eigen::Matrix3d rot_mat_orig = fk_orig.topLeftCorner(3, 3); @@ -222,3 +204,45 @@ TEST_F(CalibrationTest, calibration) EXPECT_NEAR(angle_error, 0.0, 1e-12); } } + +// Tests are parametrized by both, the robot model (e.g. "ur10e") and the DH diff as they are stored on the robot +// controller's calibration file. +// The test will then assemble the DH parameters using the ones from the base model and the calibration. +INSTANTIATE_TEST_SUITE_P( + CalibrationTests, CalibrationTest, + ::testing::Values( + std::make_tuple("ur10", + model_from_dh({ 0.00065609212979853, 1.4442162376284788, 0.854147723854608, -2.2989425877563705, + -1.573498686836816e-05, 1.9072435590711256e-05 }, // d + { 4.6311376834935676e-05, -0.00012568315331862312, 0.00186216581161458, + 9.918593870679266e-05, 4.215462720453189e-06, 0 }, // a + { -7.290070070824746e-05, -0.01713897289704999, -0.03707159413492756, + 0.054279462160583214, 1.488984257025741e-07, 1.551499479707493e-05 }, // theta + { 0.000211987863869334, -0.0072553625957652995, -0.013483226769541364, + 0.0013495820227329425, -0.001263136163679901, 0 } // alpha + )), + + std::make_tuple("ur10e", + model_from_dh({ -0.000144894975118076141, 303.469135666158195, -309.88394307789747, + 6.41459904397394975, -4.48232900190081995e-05, -0.00087071402790364627 }, // d + { 0.000108651068627930392, 0.240324175250532346, 0.00180628180213493472, + 2.63076149165684402e-05, 3.96638632500012715e-06, 0 }, // a + { 1.59613525316931737e-07, -0.917209621528830232, 7.12936131346499469, + 0.0710299029424392298, -1.64258976526054923e-06, + 9.17286101034808787e-08 }, // theta + { -0.000444781952841921679, -0.00160215112531214153, 0.00631917793331091861, + -0.00165055247340828437, 0.000763682515545038854, 0 } // alpha + )), + std::make_tuple("ur10e", + model_from_dh({ -0.000160188285741325043, 439.140974079900957, -446.027059806332147, + 6.88618689642360149, -3.86588496858186748e-05, -0.00087908274257374186 }, // d + { 2.12234865571205891e-05, 0.632017132627700651, 0.00229833638891230319, + -4.61409023720933908e-05, -6.39280053471801522e-05, 0 }, // a + { -2.41478068943590252e-07, 1.60233952386694556, -1.68607190752171299, + 0.0837331147700118711, -1.01260355871157781e-07, + 3.91986209186123702e-08 }, // theta + { -0.000650246557584166496, 0.00139416666825590402, 0.00693818880325995126, + -0.000811641562390219562, 0.000411120504570705592, 0 } // alpha + )) + + ));